diff --git a/gtsfm/averaging/rotation/rig_shonan.py b/gtsfm/averaging/rotation/rig_shonan.py deleted file mode 100644 index c2acd3008..000000000 --- a/gtsfm/averaging/rotation/rig_shonan.py +++ /dev/null @@ -1,57 +0,0 @@ -"""Shonan Rotation Averaging for the rig multi-sensory devices. - -Right now, this class is specific to the Hilti 2022 challenge. The hilti dataset has 5 cameras which are fired in sync. -Among the 5 cameras, camera #2 is the one facing up and is used to add intra-rig and inter-rig between factors. All -other priors are ignored. - -TODO(Ayush): generalize. - -Authors: Ayush Baid -""" -from typing import Dict, Tuple - -import gtsam -from gtsam import BetweenFactorPose3, BetweenFactorPose3s - -import gtsfm.utils.logger as logger_utils -from gtsfm.averaging.rotation.shonan import ShonanRotationAveraging -from gtsfm.common.pose_prior import PosePrior - -CAM2_PRIOR_SIGMA = 0.1 - -UPWARD_FACING_CAM_TYPE = 2 -POSE3_DOF = 6 - -logger = logger_utils.get_logger() - - -class RigShonanRotationAveraging(ShonanRotationAveraging): - """Performs Shonan rotation averaging.""" - - def __get_rig_idx(self, camera_idx: int) -> int: - """Get the rig index pertaining to the camera, as there are 5 cameras in sync per timestamp.""" - return camera_idx // 5 - - def __get_camera_type(self, camera_idx: int) -> int: - """Get the type of the camera, i.e. the indexing of the camera according to its physical location in the rig.""" - return camera_idx % 5 - - def _between_factors_from_pose_priors( - self, i2Ti1_priors: Dict[Tuple[int, int], PosePrior], old_to_new_idxs: Dict[int, int] - ) -> BetweenFactorPose3s: - between_factors = BetweenFactorPose3s() - - for (i1, i2), i2Ti1_prior in i2Ti1_priors.items(): - if ( - self.__get_camera_type(i1) == UPWARD_FACING_CAM_TYPE - or self.__get_camera_type(i2) == UPWARD_FACING_CAM_TYPE - ): - i2_ = old_to_new_idxs[i2] - i1_ = old_to_new_idxs[i1] - between_factors.append( - BetweenFactorPose3( - i2_, i1_, i2Ti1_prior.value, gtsam.noiseModel.Isotropic.Sigma(POSE3_DOF, CAM2_PRIOR_SIGMA) - ) - ) - - return between_factors diff --git a/gtsfm/averaging/rotation/rotation_averaging_base.py b/gtsfm/averaging/rotation/rotation_averaging_base.py index 33a9878f0..784df7cf7 100644 --- a/gtsfm/averaging/rotation/rotation_averaging_base.py +++ b/gtsfm/averaging/rotation/rotation_averaging_base.py @@ -24,18 +24,18 @@ class RotationAveragingBase(metaclass=abc.ABCMeta): # ignored-abstractmethod @abc.abstractmethod - def run( + def run_rotation_averaging( self, num_images: int, i2Ri1_dict: Dict[Tuple[int, int], Optional[Rot3]], - i2Ti1_priors: Dict[Tuple[int, int], PosePrior], + relative_pose_priors: Dict[Tuple[int, int], PosePrior], ) -> List[Optional[Rot3]]: """Run the rotation averaging. Args: num_images: number of poses. i2Ri1_dict: relative rotations as dictionary (i1, i2): i2Ri1. - i2Ti1_priors: priors on relative poses. + relative_pose_priors: priors on relative poses as dictionary(i1, i2): PosePrior on i1Ti2. Returns: Global rotations for each camera pose, i.e. wRi, as a list. The number of entries in the list is @@ -71,7 +71,7 @@ def create_computation_graph( self, num_images: int, i2Ri1_graph: Delayed, - i2Ti1_priors: Dict[Tuple[int, int], PosePrior], + relative_pose_priors: Dict[Tuple[int, int], PosePrior], gt_wTi_list: List[Optional[Pose3]], ) -> Tuple[Delayed, Delayed]: """Create the computation graph for performing rotation averaging. @@ -79,14 +79,14 @@ def create_computation_graph( Args: num_images: number of poses. i2Ri1_graph: dictionary of relative rotations as a delayed task. - i2Ti1_priors: priors on relative poses. + relative_pose_priors: priors on relative poses as (i1, i2): PosePrior on i1Ti2. gt_wTi_list: ground truth poses, to be used for evaluation. Returns: global rotations wrapped using dask.delayed. """ - wRis = dask.delayed(self.run)(num_images, i2Ri1_graph, i2Ti1_priors) + wRis = dask.delayed(self.run_rotation_averaging)(num_images, i2Ri1_graph, relative_pose_priors) metrics = dask.delayed(self.evaluate)(wRis, gt_wTi_list) return wRis, metrics diff --git a/gtsfm/averaging/rotation/shonan.py b/gtsfm/averaging/rotation/shonan.py index a056730d5..2a2a3dbc4 100644 --- a/gtsfm/averaging/rotation/shonan.py +++ b/gtsfm/averaging/rotation/shonan.py @@ -10,7 +10,7 @@ Authors: Jing Wu, Ayush Baid, John Lambert """ -from typing import Dict, List, Optional, Tuple +from typing import Dict, List, Optional, Set, Tuple import gtsam import numpy as np @@ -71,12 +71,24 @@ def __between_factors_from_2view_relative_rotations( return between_factors def _between_factors_from_pose_priors( - self, i2Ti1_priors: Dict[Tuple[int, int], PosePrior], old_to_new_idxs: Dict[int, int] + self, relative_pose_priors: Dict[Tuple[int, int], PosePrior], old_to_new_idxs: Dict[int, int] ) -> BetweenFactorPose3s: """Create between factors from the priors on relative poses.""" between_factors = BetweenFactorPose3s() - # TODO(Ayush): use the priors, atleast between disconnected components. + def get_isotropic_noise_model_sigma(covariance: np.ndarray) -> float: + """Get the sigma to be used for the isotropic noise model. + We compute the average of the diagonal entries of the covariance matrix. + """ + avg_cov = np.average(np.diag(covariance), axis=None) + return np.sqrt(avg_cov) + + for (i1, i2), i1Ti2_prior in relative_pose_priors.items(): + i1_ = old_to_new_idxs[i1] + i2_ = old_to_new_idxs[i2] + noise_model_sigma = get_isotropic_noise_model_sigma(i1Ti2_prior.covariance) + noise_model = gtsam.noiseModel.Isotropic.Sigma(POSE3_DOF, noise_model_sigma) + between_factors.append(BetweenFactorPose3(i1_, i2_, i1Ti2_prior.value, noise_model)) return between_factors @@ -100,58 +112,77 @@ def _run_with_consecutive_ordering( not be computed (either underconstrained system or ill-constrained system). """ - obj = ShonanAveraging3(between_factors, self.__get_shonan_params()) + logger.info( + "Running Shonan with %d constraints on %d nodes", + len(between_factors), + num_connected_nodes, + ) + shonan = ShonanAveraging3(between_factors, self.__get_shonan_params()) - initial = obj.initializeRandomly() - result_values, _ = obj.run(initial, self._p_min, self._p_max) + initial = shonan.initializeRandomly() + logger.info("Initial cost: %.5f", shonan.cost(initial)) + result, _ = shonan.run(initial, self._p_min, self._p_max) + logger.info("Final cost: %.5f", shonan.cost(result)) wRi_list_consecutive = [None] * num_connected_nodes for i in range(num_connected_nodes): - if result_values.exists(i): - wRi_list_consecutive[i] = result_values.atRot3(i) + if result.exists(i): + wRi_list_consecutive[i] = result.atRot3(i) + num_computed = sum(wRi is not None for wRi in wRi_list_consecutive) + logger.info("Computed %d global rotations", num_computed) return wRi_list_consecutive - def run( + def _nodes_with_edges( + self, i2Ri1_dict: Dict[Tuple[int, int], Optional[Rot3]], relative_pose_priors: Dict[Tuple[int, int], PosePrior] + ) -> Set[int]: + """Gets the nodes with edges which are to be modelled as between factors.""" + + unique_nodes_with_edges = set() + for (i1, i2) in i2Ri1_dict.keys(): + unique_nodes_with_edges.add(i1) + unique_nodes_with_edges.add(i2) + for (i1, i2) in relative_pose_priors.keys(): + unique_nodes_with_edges.add(i1) + unique_nodes_with_edges.add(i2) + + return unique_nodes_with_edges + + def run_rotation_averaging( self, num_images: int, i2Ri1_dict: Dict[Tuple[int, int], Optional[Rot3]], - i2Ti1_priors: Dict[Tuple[int, int], PosePrior], + relative_pose_priors: Dict[Tuple[int, int], PosePrior], ) -> List[Optional[Rot3]]: """Run the rotation averaging on a connected graph with arbitrary keys, where each key is a image/pose index. - Note: run() functions as a wrapper that re-orders keys to prepare a graph w/ N keys ordered [0,...,N-1]. + Note: functions as a wrapper that re-orders keys to prepare a graph w/ N keys ordered [0,...,N-1]. All input nodes must belong to a single connected component, in order to obtain an absolute pose for each camera in a single, global coordinate frame. Args: num_images: number of images. Since we have one pose per image, it is also the number of poses. i2Ri1_dict: relative rotations for each image pair-edge as dictionary (i1, i2): i2Ri1. - i2Ti1_priors: priors on relative poses. + relative_pose_priors: priors on relative poses. Returns: Global rotations for each camera pose, i.e. wRi, as a list. The number of entries in the list is `num_images`. The list may contain `None` where the global rotation could not be computed (either underconstrained system or ill-constrained system), or where the camera pose had no valid observation - in the input to run(). + in the input to run_rotation_averaging(). """ if len(i2Ri1_dict) == 0: logger.warning("Shonan cannot proceed: No cycle-consistent triplets found after filtering.") wRi_list = [None] * num_images return wRi_list - unique_nodes_with_edges = set() - for (i1, i2) in i2Ri1_dict.keys(): - unique_nodes_with_edges.add(i1) - unique_nodes_with_edges.add(i2) - - nodes_with_edges = sorted(list(unique_nodes_with_edges)) - old_to_new_idxes = {new_idx: i for i, new_idx in enumerate(nodes_with_edges)} + nodes_with_edges = sorted(list(self._nodes_with_edges(i2Ri1_dict, relative_pose_priors))) + old_to_new_idxes = {old_idx: i for i, old_idx in enumerate(nodes_with_edges)} between_factors: BetweenFactorPose3s = self.__between_factors_from_2view_relative_rotations( i2Ri1_dict, old_to_new_idxes ) - between_factors.extend(self._between_factors_from_pose_priors(i2Ti1_priors, old_to_new_idxes)) + between_factors.extend(self._between_factors_from_pose_priors(relative_pose_priors, old_to_new_idxes)) wRi_list_subset = self._run_with_consecutive_ordering( num_connected_nodes=len(nodes_with_edges), between_factors=between_factors diff --git a/gtsfm/averaging/translation/averaging_1dsfm.py b/gtsfm/averaging/translation/averaging_1dsfm.py index 960b1e918..c0fd68c4e 100644 --- a/gtsfm/averaging/translation/averaging_1dsfm.py +++ b/gtsfm/averaging/translation/averaging_1dsfm.py @@ -18,6 +18,8 @@ import numpy as np from gtsam import ( MFAS, + BinaryMeasurementPoint3, + BinaryMeasurementsPoint3, BinaryMeasurementsUnit3, BinaryMeasurementUnit3, Point3, @@ -70,18 +72,21 @@ def __init__( self, robust_measurement_noise: bool = True, projection_sampling_method: ProjectionSamplingMethod = ProjectionSamplingMethod.SAMPLE_WITH_UNIFORM_DENSITY, + MFAS_outlier_rejection: bool = True, ) -> None: """Initializes the 1DSFM averaging instance. Args: robust_measurement_noise: Whether to use a robust noise model for the measurements, defaults to true. projection_sampling_method: ProjectionSamplingMethod to be used for directions to run 1DSfM. + MFAS_outlier_rejection: whether to perform outlier rejection with MFAS algorithm (default True). """ super().__init__(robust_measurement_noise) self._max_1dsfm_projection_directions = MAX_PROJECTION_DIRECTIONS self._outlier_weight_threshold = OUTLIER_WEIGHT_THRESHOLD self._projection_sampling_method = projection_sampling_method + self._MFAS_outlier_rejection = MFAS_outlier_rejection def __sample_projection_directions( self, @@ -91,7 +96,6 @@ def __sample_projection_directions( Args: w_i2Ui1_measurements: Unit translation measurements which are input to 1DSfM. - projection_sampling_method: ProjectionSamplingMethod to be used for sampling directions. Returns: List of sampled Unit3 projection directions. @@ -113,7 +117,7 @@ def __sample_projection_directions( return projections - def compute_inlier_mask( + def __compute_inlier_mask( self, w_i2Ui1_measurements: BinaryMeasurementsUnit3, ) -> Set[Tuple[int, int]]: @@ -125,36 +129,41 @@ def compute_inlier_mask( Returns: Set of indices (i1, i2) which are inliers. """ + # Sample projection directions for 1DSfM. projection_directions = self.__sample_projection_directions(w_i2Ui1_measurements) + logger.debug("Sampled projection directions for 1DSfM.") - # compute outlier weights using MFAS + # Compute outlier weights using MFAS. outlier_weights: List[Dict[Tuple[int, int], float]] = [] # TODO(ayush): parallelize this step. for direction in projection_directions: mfas_instance = MFAS(w_i2Ui1_measurements, direction) outlier_weights.append(mfas_instance.computeOutlierWeights()) + logger.debug("Computed outlier weights using MFAS.") - # compute average outlier weight + # Compute average outlier weight. outlier_weights_sum: DefaultDict[Tuple[int, int], float] = defaultdict(float) - inlier_idxs = set() + inliers = set() for outlier_weight_dict in outlier_weights: # TODO(akshay-krishnan): use keys from outlier weight dict once we can iterate over it (gtsam fix). for idx in range(len(w_i2Ui1_measurements)): w_i2Ui1 = w_i2Ui1_measurements[idx] i2, i1 = w_i2Ui1.key1(), w_i2Ui1.key2() outlier_weights_sum[(i2, i1)] += outlier_weight_dict[(i2, i1)] + logger.debug("Computed average outlier weight.") + # Find inliers. for (i2, i1) in outlier_weights_sum: if outlier_weights_sum[(i2, i1)] / len(projection_directions) < OUTLIER_WEIGHT_THRESHOLD: - inlier_idxs.add((i1, i2)) + inliers.add((i1, i2)) - return inlier_idxs + return inliers def _get_prior_measurements_in_world_frame( self, relative_pose_priors: Dict[Tuple[int, int], PosePrior], wRi_list: List[Optional[Rot3]], - ) -> gtsam.BinaryMeasurementsPoint3: + ) -> BinaryMeasurementsPoint3: """Converts the priors from relative Pose3 priors to relative Point3 priors in world frame. Args: @@ -162,29 +171,32 @@ def _get_prior_measurements_in_world_frame( wRi_list: Absolute rotation estimates from rotation averaging. Returns: - gtsam.BinaryMeasurementsPoint3 containing Point3 priors in world frame. + BinaryMeasurementsPoint3 containing Point3 priors in world frame. """ if len(relative_pose_priors) == 0: - return gtsam.BinaryMeasurementsPoint3() - - def get_prior_in_world_frame(i2, i2Ti1_prior): - return wRi_list[i2].rotate(i2Ti1_prior.value.translation()) - - w_i2ti1_priors = gtsam.BinaryMeasurementsPoint3() - - for (i1, i2), i2Ti1_prior in relative_pose_priors.items(): - # TODO(akshay-krishnan): Use the translation covariance, transform to world frame. - # noise_model = gtsam.noiseModel.Gaussian.Covariance(i2Ti1_prior.covariance) - noise_model = gtsam.noiseModel.Isotropic.Sigma(3, 1e-2) - w_i2ti1_priors.append( - gtsam.BinaryMeasurementPoint3( - i2, + return BinaryMeasurementsPoint3() + + def get_prior_in_world_frame(i1, i1Ti2_prior) -> Tuple[Point3, gtsam.noiseModel.Gaussian]: + """Transforms a direction prior from i1 coordinate frame to world coordinates using wRi1.""" + wRi1 = wRi_list[i1].matrix() + w_i1ti2 = wRi1 @ i1Ti2_prior.value.translation() + w_cov = wRi1 @ i1Ti2_prior.covariance[3:, 3:] @ wRi1.T + noise_model = gtsam.noiseModel.Gaussian.Covariance(w_cov) + return w_i1ti2, noise_model + + w_relative_translation_priors = BinaryMeasurementsPoint3() + + for (i1, i2), i1Ti2_prior in relative_pose_priors.items(): + w_i1ti2, noise_model = get_prior_in_world_frame(i1, i1Ti2_prior) + w_relative_translation_priors.append( + BinaryMeasurementPoint3( i1, - get_prior_in_world_frame(i2, i2Ti1_prior), + i2, + w_i1ti2, noise_model, ) ) - return w_i2ti1_priors + return w_relative_translation_priors def __get_initial_values(self, wTi_initial: List[Optional[PosePrior]]): """Converts translations from a list of absolute poses to gtsam.Values for initialization. @@ -198,8 +210,51 @@ def __get_initial_values(self, wTi_initial: List[Optional[PosePrior]]): initial.insertPoint3(i, wTi.value.translation()) return initial + def augment_measurement_with_priors( + self, + w_i2Ui1_measurements: BinaryMeasurementsUnit3, + w_relative_translation_priors: BinaryMeasurementsPoint3, + noise_model: gtsam.noiseModel, + ) -> BinaryMeasurementsUnit3: + """Augment the measurements with priors. If there is a pair (i1, i2) where the measurement is missing but the + prior is present, we will add the prior as the measurement. + + Args: + w_i2Ui1_measurements: relative unit translation measurements in the world frame. + w_relative_translation_priors: relative translations in the world frame. + noise_model: noise model to be used for newly added measurements. + + Returns: + Augmented measurements, which are a superset of w_i2Ui1_measurements. + """ + # TODO: use deecopy when BinaryMeasurementsUnit3 can be pickled + # augmented_measurements = deepcopy(w_i2Ui1_measurements) + augmented_measurements = w_i2Ui1_measurements + + nodes_with_measurements = set() + for idx in range(len(w_i2Ui1_measurements)): + measurement: BinaryMeasurementUnit3 = w_i2Ui1_measurements[idx] + nodes_with_measurements.add(measurement.key1()) + nodes_with_measurements.add(measurement.key2()) + + for idx in range(len(w_relative_translation_priors)): + prior: BinaryMeasurementPoint3 = w_relative_translation_priors[idx] + i1 = prior.key1() + i2 = prior.key2() + + if i1 in nodes_with_measurements and i2 in nodes_with_measurements: + continue + + i1ti2_from_prior: Point3 = prior.measured() + + i1Ui2 = Unit3(i1ti2_from_prior) + + augmented_measurements.append(BinaryMeasurementUnit3(i1, i2, i1Ui2, noise_model)) + + return augmented_measurements + # TODO(ayushbaid): Change wTi_initial to Pose3. - def run( + def run_translation_averaging( self, num_images: int, i2Ui1_dict: Dict[Tuple[int, int], Optional[Unit3]], @@ -208,7 +263,7 @@ def run( relative_pose_priors: Dict[Tuple[int, int], PosePrior] = {}, scale_factor: float = 1.0, gt_wTi_list: Optional[List[Optional[Pose3]]] = None, - ) -> Tuple[List[Optional[Point3]], Optional[GtsfmMetricsGroup]]: + ) -> Tuple[List[Optional[Pose3]], Optional[GtsfmMetricsGroup]]: """Run the translation averaging. Args: @@ -216,7 +271,7 @@ def run( i2Ui1_dict: relative unit-translation as dictionary (i1, i2): i2Ui1 wRi_list: global rotations for each camera pose in the world coordinates. absolute_pose_priors: priors on the camera poses (not delayed). - relative_pose_priors: priors on the pose between camera pairs (not delayed) + relative_pose_priors: priors on the pose between camera pairs (not delayed) as (i1, i2): i1Ti2. scale_factor: non-negative global scaling factor. gt_wTi_list: ground truth poses for computing metrics. @@ -226,7 +281,7 @@ def run( or ill-constrained system). A GtsfmMetricsGroup of 1DSfM metrics. """ - logger.info("Running translation averaging on {} unit translations".format(len(i2Ui1_dict))) + logger.info(f"Running translation averaging on {len(i2Ui1_dict)} unit translations.") noise_model = gtsam.noiseModel.Isotropic.Sigma(NOISE_MODEL_DIMENSION, NOISE_MODEL_SIGMA) if self._robust_measurement_noise: huber_loss = gtsam.noiseModel.mEstimator.Huber.Create(HUBER_LOSS_K) @@ -235,51 +290,63 @@ def run( w_i2Ui1_measurements = cast_to_measurements_variable_in_global_coordinate_frame( i2Ui1_dict, wRi_list, noise_model ) + logger.debug("Created measurements in global frame.") - inlier_idxs: Set[Tuple[int, int]] = self.compute_inlier_mask(w_i2Ui1_measurements) + # Possibly perform (slow!) outlier rejection with Minimum Feedback Arc Set algorithm. + if self._MFAS_outlier_rejection: + inliers: Set[Tuple[int, int]] = self.__compute_inlier_mask(w_i2Ui1_measurements) + logger.debug("Computed inlier mask with MFAS.") - w_i2Ui1_inlier_measurements = BinaryMeasurementsUnit3() - for idx in range(len(w_i2Ui1_measurements)): - # key1 is i2 and key2 is i1 above. - w_i2Ui1 = w_i2Ui1_measurements[idx] - i1 = w_i2Ui1.key2() - i2 = w_i2Ui1.key1() - if (i1, i2) in inlier_idxs: - w_i2Ui1_inlier_measurements.append(w_i2Ui1) + w_i2Ui1_inlier_measurements = BinaryMeasurementsUnit3() + for idx in range(len(w_i2Ui1_measurements)): + # key1 is i2 and key2 is i1 above. + w_i2Ui1 = w_i2Ui1_measurements[idx] + i1 = w_i2Ui1.key2() + i2 = w_i2Ui1.key1() + if (i1, i2) in inliers: + w_i2Ui1_inlier_measurements.append(w_i2Ui1) + logger.debug("Created inlier measurements.") + w_i2Ui1_measurements = w_i2Ui1_inlier_measurements + else: + inliers = set(i2Ui1_dict.keys()) # Run the optimizer - # TODO(akshay-krishnan): remove once latest gtsam pip wheels updated. - try: - algorithm = TranslationRecovery() - w_i2ti1_priors = self._get_prior_measurements_in_world_frame(relative_pose_priors, wRi_list) - wti_initial = self.__get_initial_values(absolute_pose_priors) - if len(w_i2ti1_priors) > 0: - # scale is ignored here. - wti_values = algorithm.run(w_i2Ui1_inlier_measurements, 0.0, w_i2ti1_priors, wti_initial) - else: - wti_values = algorithm.run(w_i2Ui1_inlier_measurements, scale_factor) - except TypeError as e: - logger.error("TypeError: {}".format(str(e))) - recovery = TranslationRecovery(w_i2Ui1_inlier_measurements) - wti_values = recovery.run(scale_factor) + algorithm = TranslationRecovery() + w_relative_pose_priors = self._get_prior_measurements_in_world_frame(relative_pose_priors, wRi_list) + wti_initial = self.__get_initial_values(absolute_pose_priors) + logger.debug("Computed priors and initial values.") + + if len(w_relative_pose_priors) > 0: + # scale is ignored here. + noise_model_for_augmentation = gtsam.noiseModel.Isotropic.Sigma(NOISE_MODEL_DIMENSION, NOISE_MODEL_SIGMA) + augmented_w_i2Ui1_measurements = self.augment_measurement_with_priors( + w_i2Ui1_measurements, w_relative_pose_priors, noise_model_for_augmentation + ) + logger.debug("Running TranslactionRecovery with priors") + wti_values = algorithm.run(augmented_w_i2Ui1_measurements, 0.0, w_relative_pose_priors, wti_initial) + + else: + logger.debug("Running translation recovery without priors") + wti_values = algorithm.run(w_i2Ui1_measurements, scale_factor) # transforming the result to the list of Point3 - wti_list: List[Optional[Point3]] = [None] * num_images - for i in range(num_images): - if wRi_list[i] is not None and wti_values.exists(i): - wti_list[i] = wti_values.atPoint3(i) + wti_list = [ + wti_values.atPoint3(i) if wRi_list[i] is not None and wti_values.exists(i) else None + for i in range(num_images) + ] + wTi_list = [ + Pose3(wRi, wti) if wRi is not None and wti is not None else None for wRi, wti in zip(wRi_list, wti_list) + ] # Compute the metrics. if gt_wTi_list is not None: - ta_metrics = _compute_metrics(inlier_idxs, i2Ui1_dict, wRi_list, wti_list, gt_wTi_list) + ta_metrics = _compute_metrics(inliers, i2Ui1_dict, wRi_list, wti_list, gt_wTi_list) else: ta_metrics = None - num_translations = 0 - for wti in wti_list: - if wti is not None: - num_translations += 1 + + num_translations = sum([1 for wti in wti_list if wti is not None]) logger.info("Estimated {} translations out of {} images ".format(num_translations, num_images)) - return wti_list, ta_metrics + return wTi_list, ta_metrics def _sample_kde_directions(w_i2Ui1_measurements: BinaryMeasurementsUnit3, num_samples: int) -> List[Unit3]: @@ -370,11 +437,10 @@ def _compute_metrics( - Distribution of translation direction angles for inlier measurements. - Distribution of translation direction angle for outlier measurements. """ + non_none_input_edges = [edge for edge, val in i2Ui1_dict.items() if val is not None] # Get ground truth translation directions for the measurements. - gt_i2Ui1_dict = metrics_utils.get_twoview_translation_directions(gt_wTi_list) - outlier_i1_i2_pairs = ( - set([pair_idx for pair_idx, val in i2Ui1_dict.items() if val is not None]) - inlier_i1_i2_pairs - ) + gt_i2Ui1_dict = metrics_utils.get_twoview_translation_directions(gt_wTi_list, non_none_input_edges) + outlier_i1_i2_pairs = set(non_none_input_edges) - inlier_i1_i2_pairs # Angle between i2Ui1 measurement and GT i2Ui1 measurement for inliers and outliers. inlier_angular_errors = _get_measurement_angle_errors(inlier_i1_i2_pairs, i2Ui1_dict, gt_i2Ui1_dict) @@ -383,10 +449,6 @@ def _compute_metrics( inlier_angular_errors, outlier_angular_errors, MAX_INLIER_MEASUREMENT_ERROR_DEG ) - measured_gt_i2Ui1_dict = {} - for (i1, i2) in set.union(inlier_i1_i2_pairs, outlier_i1_i2_pairs): - measured_gt_i2Ui1_dict[(i1, i2)] = gt_i2Ui1_dict[(i1, i2)] - # Compute estimated poses after the averaging step and align them to ground truth. wTi_list: List[Optional[Pose3]] = [] for (wRi, wti) in zip(wRi_list, wti_list): @@ -409,7 +471,7 @@ def _compute_metrics( GtsfmMetric("num_translations_estimated", len([wti for wti in wti_list if wti is not None])), GtsfmMetric("1dsfm_inlier_angular_errors_deg", inlier_angular_errors), GtsfmMetric("1dsfm_outlier_angular_errors_deg", outlier_angular_errors), - metrics_utils.compute_translation_angle_metric(measured_gt_i2Ui1_dict, wTi_aligned_list), + metrics_utils.compute_translation_angle_metric(gt_i2Ui1_dict, wTi_aligned_list), metrics_utils.compute_translation_distance_metric(wti_aligned_list, gt_wti_list), ] diff --git a/gtsfm/averaging/translation/rig_1dsfm.py b/gtsfm/averaging/translation/rig_1dsfm.py deleted file mode 100644 index d0a45e414..000000000 --- a/gtsfm/averaging/translation/rig_1dsfm.py +++ /dev/null @@ -1,94 +0,0 @@ -"""Translation averaging using 1DSFM for a camera rig. - -This file creates a class that extends the 1DSfM module to work with camera rigs (currently Hilti). - -References: -- https://research.cs.cornell.edu/1dsfm/ -- https://github.com/borglab/gtsam/blob/develop/gtsam/sfm/MFAS.h -- https://github.com/borglab/gtsam/blob/develop/gtsam/sfm/TranslationRecovery.h -- https://github.com/borglab/gtsam/blob/develop/python/gtsam/examples/TranslationAveragingExample.py - -Authors: Akshay Krishnan -""" -from typing import Dict, List, Optional, Tuple - -import gtsam -from gtsam import Rot3 - -import gtsfm.utils.logger as logger_utils -from gtsfm.averaging.translation.averaging_1dsfm import TranslationAveraging1DSFM -from gtsfm.common.pose_prior import PosePrior, PosePriorType - -logger = logger_utils.get_logger() - - -class RigTranslationAveraging1DSFM(TranslationAveraging1DSFM): - """A special case of the 1DSFM implementation that pre-processes the relative prior for the Hilti rig.""" - - def _get_prior_measurements_in_world_frame( - self, - relative_pose_priors: Dict[Tuple[int, int], PosePrior], - wRi_list: List[Optional[Rot3]], - ) -> gtsam.BinaryMeasurementsPoint3: - """Converts the priors from relative Pose3 priors to relative Point3 priors in world frame. - - If the priors are hard constraints (in the same rig), a hard-coded noise model is used. - If the priors are soft constraints, the covariance from the PosePrior is used. - - Soft constraints are only added between the 3rd rig cameras. - Hard constraints are only added between the 3rd camera and other cameras in same rig. - - Args: - relative_pose_priors: Relative pose priors between cameras, could be a hard or soft prior. - wRi_list: Absolute rotation estimates from Shonan averaging. - - Returns: - gtsam.BinaryMeasurementsPoint3 containing Point3 priors in world frame. - """ - if len(relative_pose_priors) == 0: - return gtsam.BinaryMeasurementsPoint3() - - NUM_CAMERAS_IN_RIG = 5 - BODY_FRAME_CAMERA = 2 - - def get_prior_in_world_frame(i2, i2Ti1_prior): - return wRi_list[i2].rotate(i2Ti1_prior.value.translation()) - - HARD_CONSTRAINT_NOISE_MODEL = gtsam.noiseModel.Constrained.All(3) - VALID_HARD_CONSTRAINT_EDGES = [(0, 2), (1, 2), (2, 3), (2, 4)] - - w_i2ti1_priors = gtsam.BinaryMeasurementsPoint3() - priors_added = set() - for (i1, i2), i2Ti1_prior in relative_pose_priors.items(): - if i2Ti1_prior.type == PosePriorType.HARD_CONSTRAINT: - c1 = i1 % NUM_CAMERAS_IN_RIG - c2 = i2 % NUM_CAMERAS_IN_RIG - if (c1, c2) in VALID_HARD_CONSTRAINT_EDGES: - w_i2ti1_priors.append( - gtsam.BinaryMeasurementPoint3( - i2, - i1, - get_prior_in_world_frame(i2, i2Ti1_prior), - HARD_CONSTRAINT_NOISE_MODEL, - ) - ) - priors_added.add((i2, i1)) - else: - r1 = i1 // NUM_CAMERAS_IN_RIG - r2 = i2 // NUM_CAMERAS_IN_RIG - c1 = r1 * NUM_CAMERAS_IN_RIG + BODY_FRAME_CAMERA - c2 = r2 * NUM_CAMERAS_IN_RIG + BODY_FRAME_CAMERA - if (c1, c2) not in priors_added: - # TODO(akshay-krishnan): Use the translation covariance, transform to world frame. - # noise_model = gtsam.noiseModel.Gaussian.Covariance(i2Ti1_prior.covariance) - noise_model = gtsam.noiseModel.Isotropic.Sigma(3, 1e-2) - w_i2ti1_priors.append( - gtsam.BinaryMeasurementPoint3( - i2, - i1, - get_prior_in_world_frame(i2, i2Ti1_prior), - noise_model, - ) - ) - logger.info("Added {} priors in rig translation averaging".format(len(w_i2ti1_priors))) - return w_i2ti1_priors diff --git a/gtsfm/averaging/translation/translation_averaging_base.py b/gtsfm/averaging/translation/translation_averaging_base.py index b1bb14952..e7d8cafcb 100644 --- a/gtsfm/averaging/translation/translation_averaging_base.py +++ b/gtsfm/averaging/translation/translation_averaging_base.py @@ -7,7 +7,7 @@ import dask from dask.delayed import Delayed -from gtsam import Point3, Pose3, Rot3, Unit3 +from gtsam import Pose3, Rot3, Unit3 from gtsfm.common.pose_prior import PosePrior from gtsfm.evaluation.metrics import GtsfmMetricsGroup @@ -29,7 +29,7 @@ def __init__(self, robust_measurement_noise: bool = True) -> None: # ignored-abstractmethod @abc.abstractmethod - def run( + def run_translation_averaging( self, num_images: int, i2Ui1_dict: Dict[Tuple[int, int], Optional[Unit3]], @@ -38,7 +38,7 @@ def run( relative_pose_priors: Dict[Tuple[int, int], PosePrior] = {}, scale_factor: float = 1.0, gt_wTi_list: Optional[List[Optional[Pose3]]] = None, - ) -> Tuple[List[Optional[Point3]], Optional[GtsfmMetricsGroup]]: + ) -> Tuple[List[Optional[Pose3]], Optional[GtsfmMetricsGroup]]: """Run the translation averaging. Args: @@ -46,14 +46,14 @@ def run( i2Ui1_dict: relative unit-trans as dictionary (i1, i2): i2Ui1. wRi_list: global rotations for each camera pose in the world coordinates. absolute_pose_priors: priors on the camera poses (not delayed). - relative_pose_priors: priors on the pose between camera pairs (not delayed) + relative_pose_priors: priors on the pose between camera pairs as (i1, i2): i1Ti2. scale_factor: non-negative global scaling factor. gt_wTi_list: List of ground truth poses (wTi) for computing metrics. Returns: - Global translation wti for each camera pose. The number of entries in the list is `num_images`. The list + Global poses wTi for each camera pose. The number of entries in the list is `num_images`. The list may contain `None` where the global translations could not be computed (either underconstrained system - or ill-constrained system). + or ill-constrained system) or where the global rotations are not available. """ def create_computation_graph( @@ -65,7 +65,7 @@ def create_computation_graph( relative_pose_priors: Dict[Tuple[int, int], PosePrior] = {}, scale_factor: float = 1.0, gt_wTi_list: Optional[List[Optional[Pose3]]] = None, - ) -> Delayed: + ) -> Tuple[Delayed, Delayed]: """Create the computation graph for performing translation averaging. Args: @@ -73,14 +73,14 @@ def create_computation_graph( i2Ui1_graph: dictionary of relative unit translations as a delayed task. wRi_graph: list of global rotations wrapped up in Delayed. absolute_pose_priors: priors on the camera poses (not delayed). - relative_pose_priors: priors on the pose between camera pairs (not delayed) + relative_pose_priors: priors on the pose between camera pairs (not delayed). scale_factor: non-negative global scaling factor. gt_wTi_list: List of ground truth poses (wTi) for computing metrics. Returns: - Global unit translations wrapped as Delayed. + Global poses wrapped as Delayed. A GtsfmMetricsGroup with translation averaging metrics wrapped as Delayed. """ - return dask.delayed(self.run, nout=2)( + return dask.delayed(self.run_translation_averaging, nout=2)( num_images, i2Ui1_graph, wRi_graph, absolute_pose_priors, relative_pose_priors, scale_factor, gt_wTi_list ) diff --git a/gtsfm/bundle/bundle_adjustment.py b/gtsfm/bundle/bundle_adjustment.py index 5b98f340a..29cac5281 100644 --- a/gtsfm/bundle/bundle_adjustment.py +++ b/gtsfm/bundle/bundle_adjustment.py @@ -14,6 +14,7 @@ BetweenFactorPose3, GeneralSFMFactor2Cal3Bundler, GeneralSFMFactor2Cal3Fisheye, + InitializePose3, NonlinearFactorGraph, PinholeCameraCal3Bundler, PinholeCameraCal3Fisheye, @@ -128,7 +129,7 @@ def _between_factors( """Generate BetweenFactors on relative poses for pose variables.""" graph = NonlinearFactorGraph() - for (i1, i2), i2Ti1_prior in relative_pose_priors.items(): + for (i1, i2), i1Ti2_prior in relative_pose_priors.items(): if i1 not in cameras_to_model or i2 not in cameras_to_model: continue @@ -136,8 +137,8 @@ def _between_factors( BetweenFactorPose3( X(i1), X(i2), - i2Ti1_prior.value.inverse(), - gtsam.noiseModel.Diagonal.Sigmas(i2Ti1_prior.covariance), + i1Ti2_prior.value, + gtsam.noiseModel.Gaussian.Covariance(i1Ti2_prior.covariance), ) ) @@ -167,8 +168,30 @@ def __pose_priors( return graph + def __get_calibration( + self, + i: int, + initial_data: GtsfmData, + intrinsics: Optional[List[gtsfm_types.CALIBRATION_TYPE]] = None, + ) -> Optional[gtsfm_types.CALIBRATION_TYPE]: + """Get the calibration for a camera index from the initial data, with the explicitly supplied intrinsics as a + fallback. + """ + + camera = initial_data.get_camera(i) + if camera is not None: + return camera.calibration() + elif intrinsics is not None: + return intrinsics[i] + + return None + def __calibration_priors( - self, initial_data: GtsfmData, cameras_to_model: List[int], is_fisheye_calibration: bool + self, + initial_data: GtsfmData, + cameras_to_model: List[int], + is_fisheye_calibration: bool, + intrinsics: Optional[List[gtsfm_types.CALIBRATION_TYPE]] = None, ) -> NonlinearFactorGraph: """Generate prior factors on calibration parameters of the cameras.""" graph = NonlinearFactorGraph() @@ -178,23 +201,24 @@ def __calibration_priors( calibration_prior_noise_sigma = ( CAM_CAL3FISHEYE_PRIOR_NOISE_SIGMA if is_fisheye_calibration else CAM_CAL3BUNDLER_PRIOR_NOISE_SIGMA ) - if self._shared_calib: + + # add calibration from either the cameras in initial_data or from the intrinsics passed as input argument. + for i in cameras_to_model: + + calibration = self.__get_calibration(i, initial_data, intrinsics) + if calibration is None: + continue + graph.push_back( calibration_prior_factor_class( - K(self.__map_to_calibration_variable(cameras_to_model[0])), - initial_data.get_camera(cameras_to_model[0]).calibration(), + K(self.__map_to_calibration_variable(i)), + calibration, gtsam.noiseModel.Isotropic.Sigma(calibration_prior_factor_dof, calibration_prior_noise_sigma), ) ) - else: - for i in cameras_to_model: - graph.push_back( - calibration_prior_factor_class( - K(self.__map_to_calibration_variable(i)), - initial_data.get_camera(i).calibration(), - gtsam.noiseModel.Isotropic.Sigma(calibration_prior_factor_dof, calibration_prior_noise_sigma), - ) - ) + + if self._shared_calib and graph.size() > 0: + break return graph @@ -204,6 +228,7 @@ def __construct_factor_graph( initial_data: GtsfmData, absolute_pose_priors: List[Optional[PosePrior]], relative_pose_priors: Dict[Tuple[int, int], PosePrior], + intrinsics: Optional[List[gtsfm_types.CALIBRATION_TYPE]] = None, ) -> NonlinearFactorGraph: """Construct the factor graph with reprojection factors, BetweenFactors, and prior factors.""" is_fisheye_calibration = isinstance(initial_data.get_camera(cameras_to_model[0]), PinholeCameraCal3Fisheye) @@ -224,7 +249,7 @@ def __construct_factor_graph( camera_for_origin=cameras_to_model[0], ) ) - graph.push_back(self.__calibration_priors(initial_data, cameras_to_model, is_fisheye_calibration)) + graph.push_back(self.__calibration_priors(initial_data, cameras_to_model, is_fisheye_calibration, intrinsics)) # Also add a prior on the position of the first landmark to fix the scale graph.push_back( @@ -235,17 +260,72 @@ def __construct_factor_graph( return graph - def __initial_values(self, initial_data: GtsfmData) -> Values: - """Initialize all the variables in the factor graph.""" - initial_values = gtsam.Values() + def __initial_pose_values( + self, + initial_data: GtsfmData, + relative_pose_priors: Dict[Tuple[int, int], PosePrior], + cameras_to_model: List[int], + ) -> Values: + """Initialize pose3 variables in the factor graph.""" + + initial_values = Values() + for i in initial_data.get_valid_camera_indices(): + initial_values.insert(X(i), initial_data.get_camera(i).pose()) + + if len(relative_pose_priors) == 0: + return initial_values + + pose_init_graph = NonlinearFactorGraph() + + for i in initial_data.get_valid_camera_indices(): + pose_init_graph.push_back( + PriorFactorPose3( + X(i), + initial_data.get_camera(i).pose(), + gtsam.noiseModel.Isotropic.Sigma(CAM_POSE3_DOF, CAM_POSE3_PRIOR_NOISE_SIGMA), + ) + ) + + for (i1, i2), i1Ti2_prior in relative_pose_priors.items(): + if i1 not in cameras_to_model or i2 not in cameras_to_model: + continue + + # TODO: Investigate why this does not work when we use pose prior's sigmas. + pose_init_graph.push_back( + BetweenFactorPose3( + X(i1), + X(i2), + i1Ti2_prior.value, + gtsam.noiseModel.Isotropic.Sigma(CAM_POSE3_DOF, CAM_POSE3_PRIOR_NOISE_SIGMA), + ) + ) + + return InitializePose3.initialize(pose_init_graph, initial_values, useGradient=False) - # add each camera - for loop_idx, i in enumerate(initial_data.get_valid_camera_indices()): - camera = initial_data.get_camera(i) - initial_values.insert(X(i), camera.pose()) - if not self._shared_calib or loop_idx == 0: - # add only one value if calibrations are shared - initial_values.insert(K(self.__map_to_calibration_variable(i)), camera.calibration()) + def __initial_calibration_values( + self, + initial_data: GtsfmData, + cameras_to_model: List[int], + intrinsics: Optional[List[gtsfm_types.CALIBRATION_TYPE]] = None, + ) -> Values: + """Initialize calibration variables in the factor graph.""" + initial_values = Values() + + is_calibration_added = False + for i in cameras_to_model: + if not is_calibration_added or not self._shared_calib: + calibration = self.__get_calibration(i, initial_data, intrinsics) + if calibration is None: + continue + + initial_values.insert(K(self.__map_to_calibration_variable(i)), calibration) + + is_calibration_added = True + + return initial_values + + def __initial_landmark_values(self, initial_data: GtsfmData) -> Values: + initial_values = Values() # add each SfmTrack for j in range(initial_data.number_tracks()): @@ -265,7 +345,7 @@ def __optimize_factor_graph(self, graph: NonlinearFactorGraph, initial_values: V result_values = lm.optimize() return result_values - def __cameras_to_model( + def _cameras_to_model( self, initial_data: GtsfmData, absolute_pose_priors: List[Optional[PosePrior]], @@ -275,14 +355,21 @@ def __cameras_to_model( proxy for this function.""" cameras: Set[int] = set(initial_data.get_valid_camera_indices()) + # Add all relative pose priors have atleast one node in the GTSFM's data valid cameras. + for i1, i2 in relative_pose_priors.keys(): + if i1 in cameras or i2 in cameras: + cameras.add(i1) + cameras.add(i2) + return sorted(list(cameras)) - def run( + def run_ba( self, initial_data: GtsfmData, absolute_pose_priors: List[Optional[PosePrior]], relative_pose_priors: Dict[Tuple[int, int], PosePrior], verbose: bool = True, + intrinsics: Optional[List[gtsfm_types.CALIBRATION_TYPE]] = None, ) -> Tuple[GtsfmData, GtsfmData, List[bool]]: """Run the bundle adjustment by forming factor graph and optimizing using Levenberg–Marquardt optimization. @@ -291,9 +378,10 @@ def run( absolute_pose_priors: priors to be used on cameras. relative_pose_priors: priors on the pose between two cameras. verbose: Boolean flag to print out additional info for debugging. + intrinsics: intrinsics for all the cameras. Results: - Optimized camera poses, 3D point w/ tracks, and error metrics, aligned to GT (if provided). + Optimized camera poses, 3D point w/ tracks, and error metrics. Optimized camera poses after filtering landmarks (and cameras with no remaining landmarks). Valid mask as a list of booleans, indicating for each input track whether it was below the re-projection threshold. @@ -308,29 +396,39 @@ def run( ) return initial_data, initial_data, [False] * initial_data.number_tracks() - cameras_to_model = self.__cameras_to_model(initial_data, absolute_pose_priors, relative_pose_priors) + cameras_to_model = self._cameras_to_model(initial_data, absolute_pose_priors, relative_pose_priors) graph = self.__construct_factor_graph( cameras_to_model=cameras_to_model, initial_data=initial_data, absolute_pose_priors=absolute_pose_priors, relative_pose_priors=relative_pose_priors, + intrinsics=intrinsics, + ) + initial_values = self.__initial_pose_values( + initial_data=initial_data, relative_pose_priors=relative_pose_priors, cameras_to_model=cameras_to_model ) - initial_values = self.__initial_values(initial_data=initial_data) + initial_values.insert( + self.__initial_calibration_values( + initial_data=initial_data, cameras_to_model=cameras_to_model, intrinsics=intrinsics + ) + ) + initial_values.insert(self.__initial_landmark_values(initial_data=initial_data)) + result_values = self.__optimize_factor_graph(graph, initial_values) final_error = graph.error(result_values) # Error drops from ~2764.22 to ~0.046 if verbose: - logger.info(f"initial error: {graph.error(initial_values):.2f}") - logger.info(f"final error: {final_error:.2f}") + logger.info("Initial error: %.2f", graph.error(initial_values)) + logger.info("Final error: %.2f", final_error) # construct the results - optimized_data = values_to_gtsfm_data(result_values, initial_data, self._shared_calib) + optimized_data = values_to_gtsfm_data(result_values, initial_data, cameras_to_model, self._shared_calib) if verbose: - logger.info("[Result] Number of tracks before filtering: %d", optimized_data.number_tracks()) + logger.info("Number of tracks before filtering: %d", optimized_data.number_tracks()) # filter the largest errors if self._output_reproj_error_thresh: @@ -339,7 +437,7 @@ def run( valid_mask = [True] * optimized_data.number_tracks() filtered_result = optimized_data - logger.info("[Result] Number of tracks after filtering: %d", filtered_result.number_tracks()) + logger.info("Number of tracks after filtering: %d", filtered_result.number_tracks()) return optimized_data, filtered_result, valid_mask @@ -366,6 +464,7 @@ def evaluate( return ba_metrics # align the sparse multi-view estimate after BA to the ground truth pose graph. + # Note: this aligned data is not returned anywhere. aligned_filtered_data = filtered_data.align_via_Sim3_to_poses(wTi_list_ref=poses_gt) ba_pose_error_metrics = metrics_utils.compute_ba_pose_metrics( gt_wTi_list=poses_gt, ba_output=aligned_filtered_data @@ -384,8 +483,8 @@ def evaluate( ba_metrics.add_metrics(metrics_utils.get_stats_for_sfmdata(aligned_filtered_data, suffix="_filtered")) # ba_metrics.save_to_json(os.path.join(METRICS_PATH, "bundle_adjustment_metrics.json")) - logger.info("[Result] Mean track length %.3f", np.mean(aligned_filtered_data.get_track_lengths())) - logger.info("[Result] Median track length %.3f", np.median(aligned_filtered_data.get_track_lengths())) + logger.info("Mean track length %.3f", np.mean(aligned_filtered_data.get_track_lengths())) + logger.info("Median track length %.3f", np.median(aligned_filtered_data.get_track_lengths())) aligned_filtered_data.log_scene_reprojection_error_stats() return ba_metrics @@ -408,20 +507,23 @@ def create_computation_graph( GtsfmData aligned to GT (if provided), wrapped up using dask.delayed Metrics group for BA results, wrapped up using dask.delayed """ - optimized_sfm_data, filtered_sfm_data, _ = dask.delayed(self.run, nout=3)( + optimized_sfm_data, filtered_sfm_data, _ = dask.delayed(self.run_ba, nout=3)( sfm_data_graph, absolute_pose_priors, relative_pose_priors ) metrics_graph = dask.delayed(self.evaluate)(optimized_sfm_data, filtered_sfm_data, cameras_gt) return filtered_sfm_data, metrics_graph -def values_to_gtsfm_data(values: Values, initial_data: GtsfmData, shared_calib: bool) -> GtsfmData: +def values_to_gtsfm_data( + values: Values, initial_data: GtsfmData, cameras_modeled: List[int], shared_calib: bool +) -> GtsfmData: """Cast results from the optimization to GtsfmData object. Args: values: results of factor graph optimization. initial_data: data used to generate the factor graph; used to extract information about poses and 3d points in the graph. + cameras_modeled: the cameras modeled in the factor graph. shared_calib: flag indicating if calibrations were shared between the cameras. Returns: @@ -437,7 +539,7 @@ def values_to_gtsfm_data(values: Values, initial_data: GtsfmData, shared_calib: camera_class = PinholeCameraCal3Fisheye if is_fisheye_calibration else PinholeCameraCal3Bundler # add cameras - for i in initial_data.get_valid_camera_indices(): + for i in cameras_modeled: result.add_camera( i, camera_class(values.atPose3(X(i)), cal3_value_extraction_lambda(i)), diff --git a/gtsfm/bundle/rig_bundle_adjustment.py b/gtsfm/bundle/rig_bundle_adjustment.py deleted file mode 100644 index 91e891902..000000000 --- a/gtsfm/bundle/rig_bundle_adjustment.py +++ /dev/null @@ -1,72 +0,0 @@ -"""Special Bundle adjustment optimizer to handle rigs: devices with multiple sensors. - -Right now, this class is specific to the rig in the Hilti 2022 challenge, and needs generalization. The hilti dataset -has 5 cameras which are fired in sync. Among the 5 cameras, camera #2 is the one facing up and is used to add intra-rig -and inter-rig between factors. -TODO(Ayush): generalize. - -Authors: Ayush Baid. -""" -from typing import Dict, List, Tuple - -import gtsam -from gtsam import BetweenFactorPose3, NonlinearFactorGraph - -import gtsfm.utils.logger as logger_utils -from gtsfm.bundle.bundle_adjustment import BundleAdjustmentOptimizer, X -from gtsfm.common.pose_prior import PosePrior - -UPWARD_FACING_CAM_TYPE = 2 - - -logger = logger_utils.get_logger() - - -class RigBundleAdjustmentOptimizer(BundleAdjustmentOptimizer): - """Bundle adjustment for special rig multi-sensory devices.""" - - # TODO(Ayush): share calibrations between same cams? - # TODO(Ayush): use a diagonal model for calibration prior as distortion should have much lower sigmas? - - def __get_rig_idx(self, camera_idx: int) -> int: - """Get the rig index pertaining to the camera, as there are 5 cameras in sync per timestamp.""" - return camera_idx // 5 - - def __get_camera_type(self, camera_idx: int) -> int: - """Get the type of the camera, i.e. the indexing of the camera according to its physical location in the rig.""" - return camera_idx % 5 - - def _between_factors( - self, relative_pose_priors: Dict[Tuple[int, int], PosePrior], cameras_to_model: List[int] - ) -> NonlinearFactorGraph: - """Add between factors on poses between cameras and IMUs. - - 1. For the same timestamp, add a prior factor between each camera and cam2. - 2. For different timestamps, the between factors are between cam2s only. - """ - graph = NonlinearFactorGraph() - - # translate the relative pose priors between cams to IMUs, and add if not already present - between_factors: Dict[Tuple[int, int], BetweenFactorPose3] = {} - for (i1, i2), i2Ti1_prior in relative_pose_priors.items(): - if i1 not in cameras_to_model or i2 not in cameras_to_model: - continue - - b1: int = self.__get_rig_idx(i1) - b2: int = self.__get_rig_idx(i2) - cam_type_i1: int = self.__get_camera_type(i1) - cam_type_i2: int = self.__get_camera_type(i2) - - if (b1 == b2 and (cam_type_i1 == UPWARD_FACING_CAM_TYPE or cam_type_i2 == UPWARD_FACING_CAM_TYPE)) or ( - cam_type_i1 == UPWARD_FACING_CAM_TYPE and cam_type_i2 == UPWARD_FACING_CAM_TYPE - ): - between_factors[(i1, i2)] = BetweenFactorPose3( - X(i2), X(i1), i2Ti1_prior.value, gtsam.noiseModel.Diagonal.Sigmas(i2Ti1_prior.covariance) - ) - - logger.info("Added %d between factors for BA", len(between_factors)) - - for factor in between_factors.values(): - graph.push_back(factor) - - return graph diff --git a/gtsfm/common/gtsfm_data.py b/gtsfm/common/gtsfm_data.py index 26a123e0a..59e346154 100644 --- a/gtsfm/common/gtsfm_data.py +++ b/gtsfm/common/gtsfm_data.py @@ -329,7 +329,7 @@ def aggregate_metrics(self) -> Dict[str, Any]: convert_to_rounded_float = lambda x: float(np.round(x, 3)) - stats_dict = {} + stats_dict: Dict[str, Any] = {} stats_dict["number_tracks"] = self.number_tracks() stats_dict["3d_track_lengths"] = { "min": convert_to_rounded_float(track_lengths_3d.min()), diff --git a/gtsfm/configs/deep_front_end.yaml b/gtsfm/configs/deep_front_end.yaml index a6e5c493e..2f3611c3f 100644 --- a/gtsfm/configs/deep_front_end.yaml +++ b/gtsfm/configs/deep_front_end.yaml @@ -38,8 +38,7 @@ SceneOptimizer: multiview_optimizer: _target_: gtsfm.multi_view_optimizer.MultiViewOptimizer - # comment out to not run - view_graph_estimator: + view_graph_estimator: # optional _target_: gtsfm.view_graph_estimator.cycle_consistent_rotation_estimator.CycleConsistentRotationViewGraphEstimator edge_error_aggregation_criterion: MEDIAN_EDGE_ERROR @@ -69,6 +68,5 @@ SceneOptimizer: robust_measurement_noise: True shared_calib: False - # comment out to not run - dense_multiview_optimizer: + dense_multiview_optimizer: # optional _target_: gtsfm.densify.mvs_patchmatchnet.MVSPatchmatchNet diff --git a/gtsfm/configs/deep_front_end_astronet.yaml b/gtsfm/configs/deep_front_end_astronet.yaml index e71804142..4c40de457 100644 --- a/gtsfm/configs/deep_front_end_astronet.yaml +++ b/gtsfm/configs/deep_front_end_astronet.yaml @@ -39,7 +39,8 @@ SceneOptimizer: multiview_optimizer: _target_: gtsfm.multi_view_optimizer.MultiViewOptimizer - view_graph_estimator: + + view_graph_estimator: # optional _target_: gtsfm.view_graph_estimator.cycle_consistent_rotation_estimator.CycleConsistentRotationViewGraphEstimator edge_error_aggregation_criterion: MEDIAN_EDGE_ERROR @@ -68,5 +69,5 @@ SceneOptimizer: robust_measurement_noise: True shared_calib: False - dense_multiview_optimizer: + dense_multiview_optimizer: # optional _target_: gtsfm.densify.mvs_patchmatchnet.MVSPatchmatchNet diff --git a/gtsfm/configs/deep_front_end_hilti.yaml b/gtsfm/configs/deep_front_end_hilti.yaml deleted file mode 100644 index a0bc472db..000000000 --- a/gtsfm/configs/deep_front_end_hilti.yaml +++ /dev/null @@ -1,74 +0,0 @@ -SceneOptimizer: - _target_: gtsfm.scene_optimizer.SceneOptimizer - save_gtsfm_data: True - save_two_view_correspondences_viz: False - save_3d_viz: True - pose_angular_error_thresh: 5 # degrees - - feature_extractor: - _target_: gtsfm.feature_extractor.FeatureExtractor - detector_descriptor: - _target_: gtsfm.frontend.cacher.detector_descriptor_cacher.DetectorDescriptorCacher - detector_descriptor_obj: - _target_: gtsfm.frontend.detector_descriptor.superpoint.SuperPointDetectorDescriptor - max_keypoints: 5000 - - two_view_estimator: - _target_: gtsfm.two_view_estimator.TwoViewEstimator - bundle_adjust_2view: True - eval_threshold_px: 4 # in px - bundle_adjust_2view_maxiters: 5 - - matcher: - _target_: gtsfm.frontend.cacher.matcher_cacher.MatcherCacher - matcher_obj: - _target_: gtsfm.frontend.matcher.superglue_matcher.SuperGlueMatcher - use_outdoor_model: True - - verifier: - _target_: gtsfm.frontend.verifier.ransac.Ransac - use_intrinsics_in_verification: True - estimation_threshold_px: 4 # for H/E/F estimators - - inlier_support_processor: - _target_: gtsfm.two_view_estimator.InlierSupportProcessor - min_num_inliers_est_model: 15 - min_inlier_ratio_est_model: 0.1 - - multiview_optimizer: - _target_: gtsfm.multi_view_optimizer.MultiViewOptimizer - - # comment out to not run - # view_graph_estimator: - # _target_: gtsfm.view_graph_estimator.cycle_consistent_rotation_estimator.CycleConsistentRotationViewGraphEstimator - # edge_error_aggregation_criterion: MEDIAN_EDGE_ERROR - - rot_avg_module: - _target_: gtsfm.averaging.rotation.rig_shonan.RigShonanRotationAveraging - - trans_avg_module: - _target_: gtsfm.averaging.translation.rig_1dsfm.RigTranslationAveraging1DSFM - robust_measurement_noise: True - projection_sampling_method: SAMPLE_INPUT_MEASUREMENTS - - data_association_module: - _target_: gtsfm.data_association.data_assoc.DataAssociation - min_track_len: 2 - triangulation_options: - _target_: gtsfm.data_association.point3d_initializer.TriangulationOptions - reproj_error_threshold: 10 - mode: - _target_: gtsfm.data_association.point3d_initializer.TriangulationSamplingMode - value: RANSAC_SAMPLE_UNIFORM - max_num_hypotheses: 100 - save_track_patches_viz: False - - bundle_adjustment_module: - _target_: gtsfm.bundle.rig_bundle_adjustment.RigBundleAdjustmentOptimizer. - output_reproj_error_thresh: 3 # for post-optimization filtering - robust_measurement_noise: True - shared_calib: False - - # comment out to not run - # dense_multiview_optimizer: - # _target_: gtsfm.densify.mvs_patchmatchnet.MVSPatchmatchNet diff --git a/gtsfm/configs/scene_optimizer_unit_test_config.yaml b/gtsfm/configs/scene_optimizer_unit_test_config.yaml index ed7e00dd4..0e441eb45 100644 --- a/gtsfm/configs/scene_optimizer_unit_test_config.yaml +++ b/gtsfm/configs/scene_optimizer_unit_test_config.yaml @@ -31,7 +31,8 @@ SceneOptimizer: multiview_optimizer: _target_: gtsfm.multi_view_optimizer.MultiViewOptimizer - view_graph_estimator: + + view_graph_estimator: # optional _target_: gtsfm.view_graph_estimator.cycle_consistent_rotation_estimator.CycleConsistentRotationViewGraphEstimator edge_error_aggregation_criterion: MEDIAN_EDGE_ERROR @@ -59,5 +60,5 @@ SceneOptimizer: robust_measurement_noise: True shared_calib: True - dense_multiview_optimizer: + dense_multiview_optimizer: # optional _target_: gtsfm.densify.mvs_patchmatchnet.MVSPatchmatchNet diff --git a/gtsfm/configs/sift_front_end.yaml b/gtsfm/configs/sift_front_end.yaml index 6b69b00d4..152e45240 100644 --- a/gtsfm/configs/sift_front_end.yaml +++ b/gtsfm/configs/sift_front_end.yaml @@ -38,8 +38,7 @@ SceneOptimizer: multiview_optimizer: _target_: gtsfm.multi_view_optimizer.MultiViewOptimizer - # comment out to not run - view_graph_estimator: + view_graph_estimator: # optional _target_: gtsfm.view_graph_estimator.cycle_consistent_rotation_estimator.CycleConsistentRotationViewGraphEstimator edge_error_aggregation_criterion: MEDIAN_EDGE_ERROR @@ -69,6 +68,5 @@ SceneOptimizer: robust_measurement_noise: True shared_calib: False - # comment out to not run - dense_multiview_optimizer: + dense_multiview_optimizer: # optional _target_: gtsfm.densify.mvs_patchmatchnet.MVSPatchmatchNet diff --git a/gtsfm/configs/sift_front_end_astronet.yaml b/gtsfm/configs/sift_front_end_astronet.yaml index 305881696..26243fa7b 100644 --- a/gtsfm/configs/sift_front_end_astronet.yaml +++ b/gtsfm/configs/sift_front_end_astronet.yaml @@ -36,7 +36,8 @@ SceneOptimizer: multiview_optimizer: _target_: gtsfm.multi_view_optimizer.MultiViewOptimizer - view_graph_estimator: + + view_graph_estimator: # optional _target_: gtsfm.view_graph_estimator.cycle_consistent_rotation_estimator.CycleConsistentRotationViewGraphEstimator edge_error_aggregation_criterion: MEDIAN_EDGE_ERROR @@ -66,5 +67,5 @@ SceneOptimizer: robust_measurement_noise: True shared_calib: False - dense_multiview_optimizer: + dense_multiview_optimizer: # optional _target_: gtsfm.densify.mvs_patchmatchnet.MVSPatchmatchNet diff --git a/gtsfm/data_association/data_assoc.py b/gtsfm/data_association/data_assoc.py index 4a1418a9a..149665850 100644 --- a/gtsfm/data_association/data_assoc.py +++ b/gtsfm/data_association/data_assoc.py @@ -52,7 +52,7 @@ def __validate_track(self, sfm_track: Optional[SfmTrack]) -> bool: """Validate the track by checking its length.""" return sfm_track is not None and sfm_track.numberMeasurements() >= self.min_track_len - def run( + def run_da( self, num_images: int, cameras: Dict[int, gtsfm_types.CAMERA_TYPE], @@ -85,8 +85,8 @@ def run( # track lengths w/o triangulation check track_lengths_2d = np.array(list(map(lambda x: int(x.number_measurements()), tracks_2d)), dtype=np.uint32) - logger.debug("[Data association] input number of tracks: %s", len(tracks_2d)) - logger.debug("[Data association] input avg. track length: %s", np.mean(track_lengths_2d)) + logger.debug("Input number of tracks: %d", len(tracks_2d)) + logger.debug("Input avg. track length: %d", np.mean(track_lengths_2d)) # Initialize 3D landmark for each track point3d_initializer = Point3dInitializer(cameras, self.triangulation_options) @@ -99,6 +99,7 @@ def run( triangulated_data.add_camera(i, camera) exit_codes_wrt_gt = track_utils.classify_tracks2d_with_gt_cameras(tracks=tracks_2d, cameras_gt=cameras_gt) + logger.debug("Classified %d tracks", len(exit_codes_wrt_gt)) # add valid tracks where triangulation is successful exit_codes_wrt_computed: List[TriangulationExitCode] = [] @@ -116,6 +117,7 @@ def run( per_accepted_track_avg_errors.append(avg_track_reproj_error) else: per_rejected_track_avg_errors.append(avg_track_reproj_error) + logger.debug("Added %d tracks", triangulated_data.number_tracks()) # aggregate the exit codes to get the distribution w.r.t each triangulation exit # get the exit codes distribution w.r.t. the camera params computed by the upstream modules of GTSFM @@ -129,6 +131,7 @@ def run( track_cheirality_failure_ratio = exit_codes_wrt_computed_distribution[ TriangulationExitCode.CHEIRALITY_FAILURE ] / len(tracks_2d) + logger.debug("Computed track_cheirality_failure_ratio: %.2f", track_cheirality_failure_ratio) # pick only the largest connected component # TODO(Ayush): remove this for hilti as disconnected components not an issue? @@ -136,12 +139,13 @@ def run( connected_data = triangulated_data.select_largest_connected_component(extra_camera_edges=cam_edges_from_prior) num_accepted_tracks = connected_data.number_tracks() accepted_tracks_ratio = num_accepted_tracks / len(tracks_2d) + logger.debug("Selected largest connected component with %d tracks.", num_accepted_tracks) mean_3d_track_length, median_3d_track_length = connected_data.get_track_length_statistics() track_lengths_3d = connected_data.get_track_lengths() - logger.debug("[Data association] output number of tracks: %s", num_accepted_tracks) - logger.debug("[Data association] output avg. track length: %.2f", mean_3d_track_length) + logger.debug("Output number of tracks: %s", num_accepted_tracks) + logger.debug("Output avg. track length: %.2f", mean_3d_track_length) data_assoc_metrics = GtsfmMetricsGroup( "data_association_metrics", @@ -211,7 +215,7 @@ def create_computation_graph( data_assoc_metrics_graph: dictionary with different statistics about the data association result """ - ba_input_graph, data_assoc_metrics_graph = dask.delayed(self.run, nout=2)( + ba_input_graph, data_assoc_metrics_graph = dask.delayed(self.run_da, nout=2)( num_images, cameras, corr_idxs_graph, keypoints_graph, cameras_gt, relative_pose_priors, images_graph ) diff --git a/gtsfm/feature_extractor.py b/gtsfm/feature_extractor.py index b0878be9e..d111332ef 100644 --- a/gtsfm/feature_extractor.py +++ b/gtsfm/feature_extractor.py @@ -20,14 +20,14 @@ def __init__(self, detector_descriptor: DetectorDescriptorBase) -> None: """ self.detector_descriptor = detector_descriptor - def create_computation_graph(self, image_graph: Delayed) -> Tuple[Delayed, Delayed]: + def create_computation_graph(self, image: Delayed) -> Tuple[Delayed, Delayed]: """Given an image, create detection and descriptor generation tasks Args: - image_graph: image wrapped up in Delayed + image: image wrapped up in Delayed Returns: Delayed object for detected keypoints. Delayed object for corr. descriptors. """ - return self.detector_descriptor.create_computation_graph(image_graph) + return self.detector_descriptor.create_computation_graph(image) diff --git a/gtsfm/frontend/cacher/two_view_cacher.py b/gtsfm/frontend/cacher/two_view_cacher.py new file mode 100644 index 000000000..d7c7e2223 --- /dev/null +++ b/gtsfm/frontend/cacher/two_view_cacher.py @@ -0,0 +1,183 @@ +"""Cacher for two-view-estimator, which caches the output on disk in the top level folder `cache`. + +Authors: Ayush Baid +""" +from pathlib import Path +from typing import Any, Dict, List, Optional, Tuple + +import numpy as np +from gtsam import Pose3, Rot3, Unit3 + +import gtsfm.common.types as gtsfm_types +import gtsfm.utils.cache as cache_utils +import gtsfm.utils.io as io_utils +import gtsfm.utils.logger as logger_utils +from gtsfm.common.keypoints import Keypoints +from gtsfm.common.pose_prior import PosePrior +from gtsfm.two_view_estimator import TwoViewEstimator + +logger = logger_utils.get_logger() + +CACHE_ROOT_PATH = Path(__file__).resolve().parent.parent.parent.parent / "cache" +NUM_KEYPOINTS_TO_SAMPLE_FOR_HASH = 10 + +ROT_KEY = "rot3" +DIRECTION_KEY = "unit3" +CORR_IDXES_KEY = "idxes" + + +class TwoViewCacher(TwoViewEstimator): + """Cacher for TwoViewEstimator's output on disk, keyed on the input. + + The cached data is the relative rotation, unit translation, and the keypoint indices for verified correspondences. + The key for the cache is the keypoints, descriptors, and image shape of the 2 images. + """ + + def __init__(self, two_view_estimator: TwoViewEstimator) -> None: + self._two_view_estimator = two_view_estimator + # TODO(ayushbaid): make the obj cache key dependent on the code + self._two_view_estimator_key = ( + type(self._two_view_estimator._matcher).__name__ + type(self._two_view_estimator._verifier).__name__ + ) + + def __get_cache_path(self, cache_key: str) -> Path: + """Gets the file path to the cache bz2 file from the cache key.""" + return CACHE_ROOT_PATH / "two_view" / "{}.pbz2".format(cache_key) + + def __generate_cache_key( + self, + keypoints_i1: Keypoints, + keypoints_i2: Keypoints, + descriptors_i1: np.ndarray, + descriptors_i2: np.ndarray, + im_shape_i1: Tuple[int, int], + im_shape_i2: Tuple[int, int], + ) -> str: + """Generates the cache key from the input detections, image shapes, and underlying matcher+verifier. + + This function uses the first few keypoints and descriptors to generate a key, and hence is not guaranteed to + be unique. However, since its unlikely that keypoints/descriptors exactly match in the selected few indices, + and differ in the remaining, its a good choice for a key. + """ + numpy_arrays_to_hash: List[np.ndarray] = [] + + for keypoints_i, descriptors_i in zip([keypoints_i1, keypoints_i2], [descriptors_i1, descriptors_i2]): + # subsample and concatenate keypoints and descriptors + numpy_arrays_to_hash.append(keypoints_i.coordinates[:NUM_KEYPOINTS_TO_SAMPLE_FOR_HASH].flatten()) + if keypoints_i.responses is not None: + numpy_arrays_to_hash.append(keypoints_i.responses[:NUM_KEYPOINTS_TO_SAMPLE_FOR_HASH].flatten()) + if keypoints_i.scales is not None: + numpy_arrays_to_hash.append(keypoints_i.scales[:NUM_KEYPOINTS_TO_SAMPLE_FOR_HASH].flatten()) + numpy_arrays_to_hash.append(descriptors_i[:NUM_KEYPOINTS_TO_SAMPLE_FOR_HASH].flatten()) + + # add the shapes as a numpy array + h1, w1 = im_shape_i1 + h2, w2 = im_shape_i2 + numpy_arrays_to_hash.append(np.array([h1, w1, h2, w2])) + + # hash the concatenation of all the numpy arrays + input_key = cache_utils.generate_hash_for_numpy_array(np.concatenate(numpy_arrays_to_hash)) + + return "{}_{}".format(self._two_view_estimator_key, input_key) + + def __load_result_from_cache( + self, + keypoints_i1: Keypoints, + keypoints_i2: Keypoints, + descriptors_i1: np.ndarray, + descriptors_i2: np.ndarray, + im_shape_i1: Tuple[int, int], + im_shape_i2: Tuple[int, int], + ) -> Optional[Dict[str, Any]]: + """Load cached result, if it exists. The cached result will be a dictionary with 3 items.""" + cache_path = self.__get_cache_path( + cache_key=self.__generate_cache_key( + keypoints_i1=keypoints_i1, + keypoints_i2=keypoints_i2, + descriptors_i1=descriptors_i1, + descriptors_i2=descriptors_i2, + im_shape_i1=im_shape_i1, + im_shape_i2=im_shape_i2, + ) + ) + return io_utils.read_from_bz2_file(cache_path) + + def __save_result_to_cache( + self, + keypoints_i1: Keypoints, + keypoints_i2: Keypoints, + descriptors_i1: np.ndarray, + descriptors_i2: np.ndarray, + im_shape_i1: Tuple[int, int], + im_shape_i2: Tuple[int, int], + data: Dict[str, Any], + ) -> None: + """Save the results to the cache.""" + cache_path = self.__get_cache_path( + cache_key=self.__generate_cache_key( + keypoints_i1=keypoints_i1, + keypoints_i2=keypoints_i2, + descriptors_i1=descriptors_i1, + descriptors_i2=descriptors_i2, + im_shape_i1=im_shape_i1, + im_shape_i2=im_shape_i2, + ) + ) + io_utils.write_to_bz2_file(data, cache_path) + + def run_2view( + self, + keypoints_i1: Keypoints, + keypoints_i2: Keypoints, + descriptors_i1: np.ndarray, + descriptors_i2: np.ndarray, + camera_intrinsics_i1: Optional[gtsfm_types.CALIBRATION_TYPE], + camera_intrinsics_i2: Optional[gtsfm_types.CALIBRATION_TYPE], + im_shape_i1: Tuple[int, int], + im_shape_i2: Tuple[int, int], + i2Ti1_prior: Optional[PosePrior], + gt_wTi1: Optional[Pose3], + gt_wTi2: Optional[Pose3], + gt_scene_mesh: Optional[Any] = None, + ) -> Tuple[Optional[Rot3], Optional[Unit3], np.ndarray]: + # TODO: use prior in cache key + cached_data = self.__load_result_from_cache( + keypoints_i1=keypoints_i1, + keypoints_i2=keypoints_i2, + descriptors_i1=descriptors_i1, + descriptors_i2=descriptors_i2, + im_shape_i1=im_shape_i1, + im_shape_i2=im_shape_i2, + ) + + if cached_data is not None: + return cached_data[ROT_KEY], cached_data[DIRECTION_KEY], cached_data[CORR_IDXES_KEY] + + i2Ri1, i2Ui1, v_corr_idxs = self._two_view_estimator.run_2view( + keypoints_i1, + keypoints_i2, + descriptors_i1, + descriptors_i2, + camera_intrinsics_i1, + camera_intrinsics_i2, + im_shape_i1, + im_shape_i2, + i2Ti1_prior, + gt_wTi1, + gt_wTi2, + gt_scene_mesh, + ) + + results = {ROT_KEY: i2Ri1, DIRECTION_KEY: i2Ui1, CORR_IDXES_KEY: v_corr_idxs} + + self.__save_result_to_cache( + keypoints_i1=keypoints_i1, + keypoints_i2=keypoints_i2, + descriptors_i1=descriptors_i1, + descriptors_i2=descriptors_i2, + im_shape_i1=im_shape_i1, + im_shape_i2=im_shape_i2, + data=results, + ) + + return i2Ri1, i2Ui1, v_corr_idxs diff --git a/gtsfm/frontend/detector_descriptor/colmap_sift.py b/gtsfm/frontend/detector_descriptor/colmap_sift.py new file mode 100644 index 000000000..b55d1de20 --- /dev/null +++ b/gtsfm/frontend/detector_descriptor/colmap_sift.py @@ -0,0 +1,32 @@ +"""Colmap's SIFT detector-descriptor. + +This detector-descriptor uses a third-party implementation. + +Reference: https://github.com/colmap/pycolmap#sift-feature-extraction + +Authors: Ayush Baid +""" +from typing import Tuple + +import numpy as np +import pycolmap + +import gtsfm.utils.images as image_utils +from gtsfm.common.image import Image +from gtsfm.common.keypoints import Keypoints +from gtsfm.frontend.detector_descriptor.detector_descriptor_base import DetectorDescriptorBase + + +class ColmapSIFTDetectorDescriptor(DetectorDescriptorBase): + def detect_and_describe(self, image: Image) -> Tuple[Keypoints, np.ndarray]: + grayscale_vals: np.ndarray[np.uint8] = image_utils.rgb_to_gray_cv(image).value_array + + keypoints_pycolmap, keypoint_scores, descriptors = pycolmap.extract_sift( + grayscale_vals.astype(np.float64) / 255 + ) + return ( + Keypoints( + coordinates=keypoints_pycolmap[:, :2], scales=keypoints_pycolmap[:, 2], responses=keypoint_scores + ), + descriptors, + ) diff --git a/gtsfm/frontend/detector_descriptor/superpoint.py b/gtsfm/frontend/detector_descriptor/superpoint.py index fbc63872a..97c09403c 100644 --- a/gtsfm/frontend/detector_descriptor/superpoint.py +++ b/gtsfm/frontend/detector_descriptor/superpoint.py @@ -31,7 +31,11 @@ class SuperPointDetectorDescriptor(DetectorDescriptorBase): """Superpoint Detector+Descriptor implementation.""" def __init__( - self, max_keypoints: int = 5000, use_cuda: bool = True, weights_path: Union[Path, str] = MODEL_WEIGHTS_PATH + self, + max_keypoints: int = 5000, + use_cuda: bool = True, + weights_path: Union[Path, str] = MODEL_WEIGHTS_PATH, + init_model_in_constructor: bool = False, ) -> None: """Configures the object. @@ -39,22 +43,34 @@ def __init__( max_keypoints: max keypoints to detect in an image. use_cuda (optional): flag controlling the use of GPUs via CUDA. Defaults to True. weights_path (optional): Path to the model weights. Defaults to MODEL_WEIGHT_PATH. + init_model_in_constructor (optional): Initialize the model with weights in the constructor instead of the + `detect_and_describe` function. This setting is recommended when we + are not using dask. Defaults to False. """ super().__init__(max_keypoints=max_keypoints) self._use_cuda = use_cuda and torch.cuda.is_available() self._config = {"weights_path": weights_path} + self.device = torch.device("cuda" if self._use_cuda else "cpu") + if init_model_in_constructor: + self.model = SuperPoint(self._config).to(self.device) + self.model.eval() + else: + self.model = None + def detect_and_describe(self, image: Image) -> Tuple[Keypoints, np.ndarray]: """Jointly generate keypoint detections and their associated descriptors from a single image.""" # TODO(ayushbaid): fix inference issue #110 - device = torch.device("cuda" if self._use_cuda else "cpu") - model = SuperPoint(self._config).to(device) - model.eval() + if self.model is not None: + model = self.model + else: + model = SuperPoint(self._config).to(self.device) + model.eval() # Compute features. image_tensor = torch.from_numpy( np.expand_dims(image_utils.rgb_to_gray_cv(image).value_array.astype(np.float32) / 255.0, (0, 1)) - ).to(device) + ).to(self.device) with torch.no_grad(): model_results = model({"image": image_tensor}) torch.cuda.empty_cache() diff --git a/gtsfm/frontend/inlier_support_processor.py b/gtsfm/frontend/inlier_support_processor.py index 652cd504b..b44cc3546 100644 --- a/gtsfm/frontend/inlier_support_processor.py +++ b/gtsfm/frontend/inlier_support_processor.py @@ -37,7 +37,7 @@ def __init__( self._min_num_inliers_est_model = min_num_inliers_est_model self._min_inlier_ratio_est_model = min_inlier_ratio_est_model - def run( + def run_inlier_support( self, i2Ri1: Optional[Rot3], i2Ui1: Optional[Unit3], @@ -117,4 +117,6 @@ def create_computation_graph( May now be an empty array, if insufficient support. two_view_report_pp_graph: Post-processed two-view report (may now be None, if insufficient support). """ - return dask.delayed(self.run, nout=4)(i2Ri1_graph, i2Ui1_graph, v_corr_idxs_graph, two_view_report_graph) + return dask.delayed(self.run_inlier_support, nout=4)( + i2Ri1_graph, i2Ui1_graph, v_corr_idxs_graph, two_view_report_graph + ) diff --git a/gtsfm/frontend/matcher/superglue_matcher.py b/gtsfm/frontend/matcher/superglue_matcher.py index 0117d337f..2486114f6 100644 --- a/gtsfm/frontend/matcher/superglue_matcher.py +++ b/gtsfm/frontend/matcher/superglue_matcher.py @@ -28,8 +28,16 @@ class SuperGlueMatcher(MatcherBase): """Implements the SuperGlue matcher -- a pretrained graph neural network using attention.""" - def __init__(self, use_cuda: bool = True, use_outdoor_model: bool = True): - """Initialize the configuration and the parameters.""" + def __init__(self, use_cuda: bool = True, use_outdoor_model: bool = True, init_model_in_constructor: bool = False): + """Initialize the class. + + Args: + use_cuda (optional): Use CUDA (GPU) for inference. Defaults to True. + use_outdoor_model (optional): Use the outdoor weights for SuperGlue network. Defaults to True. + init_model_in_constructor (optional): Initialize the model with weights in the constructor instead of the + `match` function. This setting is recommended when we are not using + dask. Defaults to False. + """ super().__init__() self._config = { @@ -39,6 +47,12 @@ def __init__(self, use_cuda: bool = True, use_outdoor_model: bool = True): } self._use_cuda = use_cuda and torch.cuda.is_available() + self.device = torch.device("cuda" if self._use_cuda else "cpu") + if init_model_in_constructor: + self.model = SuperGlue(self._config).to(self.device).eval() + else: + self.model = None + def match( self, keypoints_i1: Keypoints, @@ -73,9 +87,6 @@ def match( if descriptors_i1.shape[1] != SUPERGLUE_DESC_DIM or descriptors_i2.shape[1] != SUPERGLUE_DESC_DIM: raise Exception("Superglue pretrained network only works on 256 dimensional descriptors") - device = torch.device("cuda" if self._use_cuda else "cpu") - model = SuperGlue(self._config).to(device).eval() - # batch size and number of channels B, C = 1, 1 @@ -86,16 +97,21 @@ def match( empty_image_i2 = torch.empty((B, C, H2, W2)) input_data = { - "keypoints0": torch.from_numpy(keypoints_i1.coordinates).unsqueeze(0).float().to(device), - "keypoints1": torch.from_numpy(keypoints_i2.coordinates).unsqueeze(0).float().to(device), - "descriptors0": torch.from_numpy(descriptors_i1).T.unsqueeze(0).float().to(device), - "descriptors1": torch.from_numpy(descriptors_i2).T.unsqueeze(0).float().to(device), - "scores0": torch.from_numpy(keypoints_i1.responses).unsqueeze(0).float().to(device), - "scores1": torch.from_numpy(keypoints_i2.responses).unsqueeze(0).float().to(device), + "keypoints0": torch.from_numpy(keypoints_i1.coordinates).unsqueeze(0).float().to(self.device), + "keypoints1": torch.from_numpy(keypoints_i2.coordinates).unsqueeze(0).float().to(self.device), + "descriptors0": torch.from_numpy(descriptors_i1).T.unsqueeze(0).float().to(self.device), + "descriptors1": torch.from_numpy(descriptors_i2).T.unsqueeze(0).float().to(self.device), + "scores0": torch.from_numpy(keypoints_i1.responses).unsqueeze(0).float().to(self.device), + "scores1": torch.from_numpy(keypoints_i2.responses).unsqueeze(0).float().to(self.device), "image0": empty_image_i1, "image1": empty_image_i2, } + if self.model is not None: + model = self.model + else: + model = SuperGlue(self._config).to(self.device).eval() + with torch.no_grad(): pred = model(input_data) matches = pred["matches0"][0].detach().cpu().numpy() diff --git a/gtsfm/loader/hilti_loader.py b/gtsfm/loader/hilti_loader.py index d6e8114d9..dbdd106e2 100644 --- a/gtsfm/loader/hilti_loader.py +++ b/gtsfm/loader/hilti_loader.py @@ -20,7 +20,7 @@ import numpy as np import gtsam -from gtsam import Cal3Fisheye, Pose3 +from gtsam import Cal3Fisheye, Pose3, Rot3, Point3 import gtsfm.utils.io as io_utils import gtsfm.utils.logger as logger_utils @@ -41,13 +41,15 @@ 4: "calib_3_cam4-camchain-imucam.yaml", } +GT_POSE_RELATIVE_PATH = "lidar/fastlio2_odom.txt" LIDAR_POSE_RELATIVE_PATH = "lidar/fastlio2.g2o" LIDAR_CONSTRAINTS_RELATIVE_PATH = "lidar/constraints.txt" IMAGES_FOLDER = "images" -HARD_RELATIVE_POSE_PRIOR_SIGMA = np.ones((6,)) * 1e-3 # CAM_IMU_POSE_PRIOR_SIGMA in BA should have similar value -SOFT_RELATIVE_POSE_PRIOR_SIGMA = np.ones((6,)) * 3e-2 -SOFT_ABSOLUTE_POSE_PRIOR_SIGMA = np.ones((6,)) * 3e-2 +# TODO: tune the priors, particularly the translation component of the CAM2_BACKBONE prior. +HARD_POSE_PRIOR_COVARIANCE = np.eye(6) * 1e-8 +STATIONARY_POSE_PRIOR_COVARIANCE = np.eye(6) * 1e-7 +CAM2_BACKBONE_POSE_PRIOR_COVARIANCE = np.diag(np.array([np.deg2rad(30.0), np.deg2rad(30.0), np.deg2rad(30.0), 1, 1, 1])) class HiltiLoader(LoaderBase): @@ -56,18 +58,24 @@ def __init__( base_folder: str, max_length: Optional[int] = None, max_resolution: int = 1080, + subsample: int = 1, + add_backbone: bool = True, ) -> None: """Initializes, loads calibration, constraints, and pose priors. Args: - base_folder (str): top-level folder, expects calibration, images and lidar subfolders. - max_length (Optional[int]): limit poses to read. Defaults to None. + base_folder: top-level folder, expects calibration, images and lidar subfolders. + max_length: limit poses to read. Defaults to None. max_resolution: integer representing maximum length of image's short side e.g. for 1080p (1920 x 1080), max_resolution would be 1080 + subsample: subsample along the time axis, default 1 (none). + add_backbone: add a backbone of soft constraints for CAM2-CAM2 pairs. """ super().__init__(max_resolution) self._base_folder: Path = Path(base_folder) self._max_length = max_length + self._subsample = subsample + self._add_backbone = add_backbone # Load calibration. self._intrinsics: Dict[int, Cal3Fisheye] = {} @@ -77,29 +85,119 @@ def __init__( self._intrinsics[cam_idx] = calibration[0] self._cam_T_imu_poses[cam_idx] = calibration[1] + # Jacobian for transforming covariance + self._cam2_J_imu_relative: np.array = self._cam_T_imu_poses[2].AdjointMap() + # Check how many images are on disk. self.num_rig_poses: int = self.__get_num_rig_poses() if self._max_length is not None: self.num_rig_poses = min(self.num_rig_poses, self._max_length) + # Read GT poses from odom file: + self._fastlio_poses = self.__read_fastlio_poses() + # Read the constraints from the lidar/constraints file - self.constraints = self.__load_constraints() - logger.info("Number of constraints: %d", len(self.constraints)) + all_constraints = self._load_constraints() + logger.info("Number of constraints loaded form disk: %d", len(all_constraints)) + filtered_constraints = self._covariance_filtered_constraints(all_constraints) + filtered_constraints = self._filter_outlier_constraints(filtered_constraints) + logger.info("[hilti_loader] Number of outlier-filtered constraints: %d", len(filtered_constraints)) + filtered_constraints = self._update_stationary_constraints(filtered_constraints) + self._constraints = {(c.a, c.b): c for c in filtered_constraints} # convert to dictionary + + logger.info("[hilti_loader] Number of constraints: %d", len(self._constraints)) # Read the poses for the IMU for rig indices from g2o file. self._w_T_imu: Dict[int, Pose3] = self.__read_lidar_pose_priors() - logger.info("Loading %d timestamps", self.num_rig_poses) - logger.info("Lidar camera available for %d timestamps", len(self._w_T_imu)) + logger.info("[hilti_loader] Loading %d timestamps", self.num_rig_poses) + logger.info("[hilti_loader] Lidar camera available for %d timestamps", len(self._w_T_imu)) - def __load_constraints(self) -> List[Constraint]: + def _load_constraints(self) -> List[Constraint]: + """Read all constraints but discard any out of the requested max length.""" + # read constraints constraints_path = self._base_folder / LIDAR_CONSTRAINTS_RELATIVE_PATH constraints = Constraint.read(str(constraints_path)) - # filter them according to max length - constraints = list(filter(lambda c: c.a < self.num_rig_poses and c.b < self.num_rig_poses, constraints)) + return [c for c in constraints if c.a < self.num_rig_poses and c.b < self.num_rig_poses] + + @staticmethod + def _check_covariance(constraint: Constraint, overconfidence_threshold=1e-6) -> bool: + """Return false if covariance is bad.""" + cov = constraint.cov + if np.isnan(cov).any() or np.min(np.diag(cov)) < overconfidence_threshold: + return False + try: + info = np.linalg.inv(cov) + if np.isnan(info).any(): + return False + else: + return True + except np.linalg.LinAlgError: + return False + + @classmethod + def _covariance_filtered_constraints(cls, constraints: List[Constraint]) -> List[Constraint]: + """Filter constraints to remove those with invalid covariances.""" + return list(filter(cls._check_covariance, constraints)) + + @staticmethod + def _update_stationary_constraints(constraints: List[Constraint]) -> List[Constraint]: + """Detect stationary periods and replace constraints there with 'hard' identity constraints.""" + TRANSLATION_THRESHOLD = 0.02 + ROTATION_THRESHOLD = np.deg2rad(0.5) + + def is_stationary(c: Constraint) -> bool: + # Not stationary if either rotation or translation is high enough. + return ( + np.linalg.norm(Rot3.Logmap(c.aTb.rotation())) <= ROTATION_THRESHOLD + and np.linalg.norm(c.aTb.translation()) <= TRANSLATION_THRESHOLD + ) - return constraints + def update(c): + return Constraint(c.a, c.b, Pose3(), STATIONARY_POSE_PRIOR_COVARIANCE, c.counts) if is_stationary(c) else c + + updated_constraints = [update(constraint) for constraint in constraints] + return updated_constraints + + @staticmethod + def _filter_outlier_constraints(constraints: List[Constraint]) -> List[Constraint]: + """Removes 1-step constraints for which the translation magnitude is greater than 2 or 3-step constraints.""" + ERROR_MARGIN = 0.1 # meters + ROT_SIGMA = np.deg2rad(60) + TRANS_SIGMA = 10 # meters + FILTERED_COVARIANCE = np.diag([ROT_SIGMA] * 3 + [TRANS_SIGMA] * 3) + + constraint_magnitudes = {} + for constraint in constraints: + c, d = min(constraint.a, constraint.b), max(constraint.a, constraint.b) + # no need to invert, norm will be the same. + constraint_magnitudes[(c, d)] = np.linalg.norm(constraint.aTb.translation()) + + def is_higher_step_magnitude_lesser(a, b, all_magnitudes, step_size): + c, d = min(a, b), max(a, b) + this_magnitude = all_magnitudes[(c, d)] + step_magnitude = all_magnitudes[(c, d + step_size)] if (c, d + step_size) in all_magnitudes else None + return step_magnitude is not None and this_magnitude - step_magnitude > ERROR_MARGIN + + filtered_constraints = [] + for constraint in constraints: + a, b = constraint.a, constraint.b + # Accept all constraint with step > 1 + if abs(a - b) != 1: + filtered_constraints.append(constraint) + continue + # Do not include if a higher-step magnitude is lesser (for steps of size 2 and 3) + if is_higher_step_magnitude_lesser(a, b, constraint_magnitudes, 1) or is_higher_step_magnitude_lesser( + a, b, constraint_magnitudes, 2 + ): + filtered_constraints.append(Constraint(a, b, constraint.aTb, FILTERED_COVARIANCE, constraint.counts)) + continue + filtered_constraints.append(constraint) + return filtered_constraints + + def get_all_constraints(self) -> List[Constraint]: + return list(self._constraints.values()) def get_camTimu(self) -> Dict[int, Pose3]: return self._cam_T_imu_poses @@ -110,7 +208,7 @@ def __read_lidar_pose_priors(self) -> Dict[int, Pose3]: _, values = gtsam.readG2o(filepath, is3D=True) lidar_keys = values.keys() - logger.info("Number of keys in g2o file: %d", len(lidar_keys)) + logger.info("[hilti_loader] Number of keys in g2o file: %d", len(lidar_keys)) w_T_imu: Dict[int, Pose3] = {} @@ -120,12 +218,28 @@ def __read_lidar_pose_priors(self) -> Dict[int, Pose3]: return w_T_imu + def __read_fastlio_poses(self) -> List[Pose3]: + """Read the poses for the IMU for rig indices.""" + filepath = str(self._base_folder / GT_POSE_RELATIVE_PATH) + + def pose_of_vector(pose_vector): + """Convert from vector to Pose3""" + pose_rotation = Rot3(pose_vector[-1], pose_vector[3], pose_vector[4], pose_vector[5]) # from quaternion + pose_translation = Point3(pose_vector[:3]) + return Pose3(pose_rotation, pose_translation) + + poses = np.loadtxt(filepath)[:, 1:] + logger.info("[hilti_loader] Read %d poses from %s", poses.shape[0], filepath) + return [pose_of_vector(pose) for pose in poses] + def __get_num_rig_poses(self) -> int: """Check how many images we have on disk and deduce number of rig poses.""" - search_path: str = str(self._base_folder / IMAGES_FOLDER / "*.jpg") - image_files = glob.glob(search_path) - total_num_images = len(image_files) - return total_num_images // NUM_CAMS + pattern = "*.png" + search_path: str = str(self._base_folder / IMAGES_FOLDER / pattern) + + image_fnames = [Path(f).stem for f in glob.glob(search_path)] + rig_indices = [int(fname.split("_")[0]) for fname in image_fnames] + return max(rig_indices) + 1 def __load_calibration(self, cam_idx: int) -> Tuple[Cal3Fisheye, Pose3]: """Load calibration from kalibr files in calibration sub-folder.""" @@ -167,7 +281,7 @@ def __len__(self) -> int: """ return self.num_rig_poses * NUM_CAMS - def get_image(self, index: int) -> Image: + def get_image(self, index: int) -> Optional[Image]: return self.get_image_full_res(index) # def get_image_undistorted(self, index: int) -> Image: @@ -201,8 +315,8 @@ def get_image_full_res(self, index: int) -> Image: Returns: Image: the image at the query index. """ - image_path: Path = self._base_folder / IMAGES_FOLDER / f"{index}.jpg" - + filename = f"{self.rig_from_image(index)}_{self.camera_from_image(index)}.png" + image_path: Path = self._base_folder / IMAGES_FOLDER / filename return io_utils.load_image(str(image_path)) def get_camera_intrinsics(self, index: int) -> Optional[Cal3Fisheye]: @@ -257,35 +371,38 @@ def get_relative_pose_prior(self, i1: int, i2: int) -> Optional[PosePrior]: cam_idx_for_i1: int = self.camera_from_image(i1) cam_idx_for_i2: int = self.camera_from_image(i2) - # TODO(Frank): this should come from constraints? - if rig_idx_for_i1 == rig_idx_for_i2: i1_T_imu: Pose3 = self._cam_T_imu_poses[cam_idx_for_i1] i2_T_imu: Pose3 = self._cam_T_imu_poses[cam_idx_for_i2] - i2Ti1 = i2_T_imu.inverse().between(i1_T_imu.inverse()) - # TODO: add covariance - return PosePrior(value=i2Ti1, covariance=HARD_RELATIVE_POSE_PRIOR_SIGMA, type=PosePriorType.HARD_CONSTRAINT) - elif rig_idx_for_i1 in self._w_T_imu and rig_idx_for_i2 in self._w_T_imu: - w_T_i1 = self._w_T_imu[rig_idx_for_i1] * self._cam_T_imu_poses[cam_idx_for_i1].inverse() - w_T_i2 = self._w_T_imu[rig_idx_for_i2] * self._cam_T_imu_poses[cam_idx_for_i2].inverse() - i2Ti1 = w_T_i2.between(w_T_i1) - # TODO: add covariance - return PosePrior(value=i2Ti1, covariance=SOFT_RELATIVE_POSE_PRIOR_SIGMA, type=PosePriorType.SOFT_CONSTRAINT) - - return None - - def get_absolute_pose_prior(self, idx: int) -> Optional[PosePrior]: - rig_idx: int = self.rig_from_image(idx) - cam_idx: int = self.camera_from_image(idx) + i1Ti2 = i1_T_imu * i2_T_imu.inverse() + return PosePrior(value=i1Ti2, covariance=HARD_POSE_PRIOR_COVARIANCE, type=PosePriorType.HARD_CONSTRAINT) + elif cam_idx_for_i1 == 2 and cam_idx_for_i2 == 2 and (rig_idx_for_i1, rig_idx_for_i2) in self._constraints: + constraint = self._constraints[(rig_idx_for_i1, rig_idx_for_i2)] + imui1_T_imui2 = constraint.aTb + i1Ti2 = self._cam_T_imu_poses[2] * imui1_T_imui2 * self._cam_T_imu_poses[2].inverse() + cov_i1Ti2 = self._cam2_J_imu_relative @ constraint.cov @ self._cam2_J_imu_relative.T + + # Rig is stationary, add a hard constraint. + if i1Ti2.equals(Pose3(), 1e-6): + return PosePrior(value=i1Ti2, covariance=cov_i1Ti2, type=PosePriorType.HARD_CONSTRAINT) + + return PosePrior(value=i1Ti2, covariance=cov_i1Ti2, type=PosePriorType.SOFT_CONSTRAINT) + elif cam_idx_for_i1 == 2 and cam_idx_for_i2 == 2: + # CAM2-CAM2 backbone as soft prior + w_T_imui1 = self._fastlio_poses[rig_idx_for_i1] + w_T_imui2 = self._fastlio_poses[rig_idx_for_i2] + imui1_T_imui2 = w_T_imui1.between(w_T_imui2) + i1Ti2 = self._cam_T_imu_poses[2] * imui1_T_imui2 * self._cam_T_imu_poses[2].inverse() - if rig_idx in self._w_T_imu: - w_T_cam = self._w_T_imu[rig_idx] * self._cam_T_imu_poses[cam_idx].inverse() return PosePrior( - value=w_T_cam, covariance=SOFT_ABSOLUTE_POSE_PRIOR_SIGMA, type=PosePriorType.SOFT_CONSTRAINT + value=i1Ti2, covariance=CAM2_BACKBONE_POSE_PRIOR_COVARIANCE, type=PosePriorType.SOFT_CONSTRAINT ) return None + def get_absolute_pose_prior(self, idx: int) -> Optional[PosePrior]: + return None + def camera_from_image(self, index: int) -> int: """Map image index to camera-on-rig index.""" return index % NUM_CAMS @@ -298,15 +415,43 @@ def image_from_rig_and_camera(self, rig_index: int, camera_idx: int) -> int: """Map image index to rig index.""" return rig_index * NUM_CAMS + camera_idx - def get_relative_pose_priors(self, pairs: List[Tuple[int, int]]) -> Dict[Tuple[int, int], PosePrior]: - pairs = set(pairs) + def get_relative_pose_priors(self) -> Dict[Tuple[int, int], PosePrior]: + unique_pairs = set() # For every rig index, add a "star" from camera 2 to 0,1,3,4: - for rig_index in range(self.num_rig_poses): + for rig_index in range(0, self.num_rig_poses, self._subsample): camera_2 = self.image_from_rig_and_camera(rig_index, 2) - for cam_idx in [0, 1, 3, 4]: - pairs.add((camera_2, self.image_from_rig_and_camera(rig_index, cam_idx))) + for cam_idx in [0, 1]: + unique_pairs.add((self.image_from_rig_and_camera(rig_index, cam_idx), camera_2)) + for cam_idx in [3, 4]: + unique_pairs.add((camera_2, self.image_from_rig_and_camera(rig_index, cam_idx))) - priors = {pair: self.get_relative_pose_prior(*pair) for pair in pairs} - priors = {pair: prior for pair, prior in priors.items() if prior is not None} + # Translate all rig level constraints to CAM2-CAM2 constraints + for a, b in self._constraints.keys(): + unique_pairs.add((self.image_from_rig_and_camera(a, 2), self.image_from_rig_and_camera(b, 2))) + + logger.info("Pairs for relative pose before adding backbone: %d", len(unique_pairs)) + if self._add_backbone: + # add the full backbone of CAM2-CAM2 pairs + for a in range(self.num_rig_poses - 1): + b = a + 1 + unique_pairs.add((self.image_from_rig_and_camera(a, 2), self.image_from_rig_and_camera(b, 2))) + + logger.info("Pairs for relative pose after adding backbone: %d", len(unique_pairs)) + + optional_priors = {pair: self.get_relative_pose_prior(*pair) for pair in unique_pairs} + priors = {pair: prior for pair, prior in optional_priors.items() if prior is not None} return priors + + def get_image_fnames(self) -> List[str]: + """Get image name for all the images.""" + image_fnames = [] + for i in range(len(self)): + if self._old_style: + filename = f"{i}.jpg" + else: + filename = f"{self.rig_from_image(i)}_{self.camera_from_image(i)}.png" + + image_fnames.append(filename) + + return image_fnames diff --git a/gtsfm/loader/loader_base.py b/gtsfm/loader/loader_base.py index 47c8a1706..fa341f124 100644 --- a/gtsfm/loader/loader_base.py +++ b/gtsfm/loader/loader_base.py @@ -48,7 +48,7 @@ def __len__(self) -> int: # ignored-abstractmethod @abc.abstractmethod - def get_image_full_res(self, index: int) -> Image: + def get_image_full_res(self, index: int) -> Optional[Image]: """Get the image at the given index, at full resolution. Args: @@ -212,18 +212,13 @@ def get_relative_pose_prior(self, i1: int, i2: int) -> Optional[PosePrior]: """ return None - def get_relative_pose_priors(self, pairs: List[Tuple[int, int]]) -> Dict[Tuple[int, int], PosePrior]: + def get_relative_pose_priors(self) -> Dict[Tuple[int, int], PosePrior]: """Get *all* relative pose priors for i2Ti1 - Args: - pairs: all (i1,i2) pairs of image pairs - Returns: A dictionary of PosePriors (or None) for all pairs. """ - - pairs = {pair: self.get_relative_pose_prior(*pair) for pair in pairs} - return {pair: prior for pair, prior in pairs.items() if prior is not None} + return {} def get_absolute_pose_prior(self, idx: int) -> Optional[PosePrior]: """Get the prior on the pose of camera at idx in the world coordinates. @@ -281,7 +276,7 @@ def get_gt_cameras(self) -> List[Optional[gtsfm_types.CAMERA_TYPE]]: N = len(self) return [self.get_camera(i) for i in range(N)] - def get_image_shapes(self) -> List[Tuple[int,int]]: + def get_image_shapes(self) -> List[Tuple[int, int]]: """Return all the image shapes. Returns: @@ -290,6 +285,11 @@ def get_image_shapes(self) -> List[Tuple[int,int]]: N = len(self) return [self.get_image_shape(i) for i in range(N)] + def get_image_fnames(self) -> List[str]: + """Returns the name of all images.""" + + return [self.get_image(i).file_name for i in range(len(self))] + def get_valid_pairs(self) -> List[Tuple[int, int]]: """Get the valid pairs of images for this loader. diff --git a/gtsfm/multi_view_optimizer.py b/gtsfm/multi_view_optimizer.py index 1aa494290..e136945f2 100644 --- a/gtsfm/multi_view_optimizer.py +++ b/gtsfm/multi_view_optimizer.py @@ -2,11 +2,12 @@ Authors: Ayush Baid, John Lambert """ -from typing import Dict, List, Optional, Tuple +from typing import Dict, List, Optional, Tuple, Mapping, Union import dask +import numpy as np from dask.delayed import Delayed -from gtsam import Point3, Pose3, Rot3 +from gtsam import Pose3, Rot3, Unit3 import gtsfm.common.types as gtsfm_types import gtsfm.utils.graph as graph_utils @@ -15,7 +16,7 @@ from gtsfm.bundle.bundle_adjustment import BundleAdjustmentOptimizer from gtsfm.common.pose_prior import PosePrior from gtsfm.data_association.data_assoc import DataAssociation -from gtsfm.evaluation.metrics import GtsfmMetricsGroup +from gtsfm.pose_slam.pose_slam import PoseSlam from gtsfm.two_view_estimator import TwoViewEstimationReport from gtsfm.view_graph_estimator.view_graph_estimator_base import ViewGraphEstimatorBase @@ -28,118 +29,126 @@ def __init__( data_association_module: DataAssociation, bundle_adjustment_module: BundleAdjustmentOptimizer, view_graph_estimator: Optional[ViewGraphEstimatorBase] = None, + use_pose_slam_initialization: bool = False, ) -> None: self.view_graph_estimator = view_graph_estimator + self.pose_slam_module = PoseSlam() self.rot_avg_module = rot_avg_module self.trans_avg_module = trans_avg_module self.data_association_module = data_association_module self.ba_optimizer = bundle_adjustment_module - self._run_view_graph_estimator: bool = self.view_graph_estimator is not None + self._use_pose_slam_initialization = use_pose_slam_initialization def create_computation_graph( self, - images_graph: List[Delayed], num_images: int, - keypoints_graph: List[Delayed], - i2Ri1_graph: Dict[Tuple[int, int], Delayed], - i2Ui1_graph: Dict[Tuple[int, int], Delayed], - v_corr_idxs_graph: Dict[Tuple[int, int], Delayed], + delayed_keypoints: List[Delayed], + delayed_i2Ri1s: Mapping[Tuple[int, int], Union[Delayed, Optional[Rot3]]], + delayed_i2Ui1s: Mapping[Tuple[int, int], Union[Delayed, Optional[Unit3]]], + delayed_v_corr_idxs: Mapping[Tuple[int, int], Union[Delayed, Optional[np.ndarray]]], all_intrinsics: List[Optional[gtsfm_types.CALIBRATION_TYPE]], absolute_pose_priors: List[Optional[PosePrior]], relative_pose_priors: Dict[Tuple[int, int], PosePrior], two_view_reports_dict: Optional[Dict[Tuple[int, int], TwoViewEstimationReport]], cameras_gt: List[Optional[gtsfm_types.CAMERA_TYPE]], gt_wTi_list: List[Optional[Pose3]], - ) -> Tuple[Delayed, Delayed, Delayed, list]: + images_graph: Optional[List[Delayed]] = None, + ) -> Tuple[Delayed, Delayed, Delayed, List[Delayed]]: """Creates a computation graph for multi-view optimization. Args: num_images: number of images in the scene. - keypoints_graph: keypoints for images, each wrapped up as Delayed. - i2Ri1_graph: relative rotations for image pairs, each value wrapped up as Delayed. - i2Ui1_graph: relative unit-translations for image pairs, each value wrapped up as Delayed. - v_corr_idxs_graph: indices of verified correspondences for image pairs, wrapped up as Delayed. + delayed_keypoints: keypoints for images, each wrapped up as Delayed. + delayed_i2Ri1s: relative rotations for image pairs, each value wrapped up as Delayed. + delayed_i2Ui1s: relative unit-translations for image pairs, each value wrapped up as Delayed. + delayed_v_corr_idxs: indices of verified correspondences for image pairs, wrapped up as Delayed. all_intrinsics: intrinsics for images. - absolute_pose_priors: priors on the camera poses (not delayed). - relative_pose_priors: priors on the pose between camera pairs (not delayed) - two_view_reports_dict: Dict of TwoViewEstimationReports after inlier support processor. + absolute_pose_priors: priors on the camera poses. + relative_pose_priors: priors on the pose between camera pairs. + two_view_reports_dict: cameras_gt: list of GT cameras (if they exist), ordered by camera index. gt_wTi_list: list of GT poses of the camera. + images_graph (optional): list of images. Defaults to None. Returns: - The GtsfmData input to bundle adjustment, aligned to GT (if provided), wrapped up as Delayed. + The GtsfmData input to bundle adjustment, wrapped up as Delayed. The final output GtsfmData, wrapped up as Delayed. - Dict of TwoViewEstimationReports after view graph estimation. List of GtsfmMetricGroups from different modules, wrapped up as Delayed. """ + metrics = [] - if self._run_view_graph_estimator and self.view_graph_estimator is not None: + if self.view_graph_estimator is not None: ( - viewgraph_i2Ri1_graph, - viewgraph_i2Ui1_graph, - viewgraph_v_corr_idxs_graph, - viewgraph_two_view_reports_graph, - viewgraph_estimation_metrics, + viewgraph_i2Ri1s, + viewgraph_i2Ui1s, + viewgraph_v_corr_idxs, + viewgraph_twoview_reports, + viewgraph_metrics, ) = self.view_graph_estimator.create_computation_graph( - i2Ri1_graph, i2Ui1_graph, all_intrinsics, v_corr_idxs_graph, keypoints_graph, two_view_reports_dict + delayed_i2Ri1s, + delayed_i2Ui1s, + all_intrinsics, + delayed_v_corr_idxs, + delayed_keypoints, + two_view_reports_dict, ) + metrics += [viewgraph_metrics] else: - viewgraph_i2Ri1_graph = dask.delayed(i2Ri1_graph) - viewgraph_i2Ui1_graph = dask.delayed(i2Ui1_graph) - viewgraph_v_corr_idxs_graph = dask.delayed(v_corr_idxs_graph) - viewgraph_two_view_reports_graph = dask.delayed(two_view_reports_dict) - viewgraph_estimation_metrics = dask.delayed(GtsfmMetricsGroup("view_graph_estimation_metrics", [])) - - # prune the graph to a single connected component. - pruned_i2Ri1_graph, pruned_i2Ui1_graph = dask.delayed(graph_utils.prune_to_largest_connected_component, nout=2)( - viewgraph_i2Ri1_graph, viewgraph_i2Ui1_graph, relative_pose_priors - ) + viewgraph_i2Ri1s = delayed_i2Ri1s + viewgraph_i2Ui1s = delayed_i2Ui1s + viewgraph_v_corr_idxs = delayed_v_corr_idxs + viewgraph_twoview_reports = two_view_reports_dict - delayed_wRi, rot_avg_metrics = self.rot_avg_module.create_computation_graph( - num_images, pruned_i2Ri1_graph, i2Ti1_priors=relative_pose_priors, gt_wTi_list=gt_wTi_list + pruned_i2Ri1s, pruned_i2Ui1s = dask.delayed(graph_utils.prune_to_largest_connected_component, nout=2)( + viewgraph_i2Ri1s, viewgraph_i2Ui1s, relative_pose_priors ) - wti_graph, ta_metrics = self.trans_avg_module.create_computation_graph( - num_images, - pruned_i2Ui1_graph, - delayed_wRi, - absolute_pose_priors, - relative_pose_priors, - gt_wTi_list=gt_wTi_list, - ) - init_cameras_graph = dask.delayed(init_cameras)(delayed_wRi, wti_graph, all_intrinsics) + if self._use_pose_slam_initialization: + delayed_poses, pose_slam_metrics = self.pose_slam_module.create_computation_graph( + num_images, relative_pose_priors=relative_pose_priors, gt_wTi_list=gt_wTi_list + ) + metrics.append(pose_slam_metrics) + else: + delayed_wRi, rot_avg_metrics = self.rot_avg_module.create_computation_graph( + num_images, pruned_i2Ri1s, relative_pose_priors=relative_pose_priors, gt_wTi_list=gt_wTi_list + ) - ba_input_graph, data_assoc_metrics_graph = self.data_association_module.create_computation_graph( + delayed_poses, ta_metrics = self.trans_avg_module.create_computation_graph( + num_images, + pruned_i2Ui1s, + delayed_wRi, + absolute_pose_priors, + relative_pose_priors, + gt_wTi_list=gt_wTi_list, + ) + metrics += [rot_avg_metrics, ta_metrics] + + initialized_cameras = dask.delayed(init_cameras)(delayed_poses, all_intrinsics) + + ba_input, da_metrics = self.data_association_module.create_computation_graph( num_images, - init_cameras_graph, - viewgraph_v_corr_idxs_graph, - keypoints_graph, + initialized_cameras, + viewgraph_v_corr_idxs, + delayed_keypoints, cameras_gt, relative_pose_priors, images_graph, ) - ba_result_graph, ba_metrics_graph = self.ba_optimizer.create_computation_graph( - ba_input_graph, absolute_pose_priors, relative_pose_priors, cameras_gt + ba_output, ba_metrics = self.ba_optimizer.create_computation_graph( + ba_input, absolute_pose_priors, relative_pose_priors, cameras_gt ) - multiview_optimizer_metrics_graph = [ - viewgraph_estimation_metrics, - rot_avg_metrics, - ta_metrics, - data_assoc_metrics_graph, - ba_metrics_graph, + metrics += [ + da_metrics, + ba_metrics, ] - # align the sparse multi-view estimate before BA to the ground truth pose graph. - ba_input_graph = dask.delayed(ba_input_graph.align_via_Sim3_to_poses)(gt_wTi_list) - - return ba_input_graph, ba_result_graph, viewgraph_two_view_reports_graph, multiview_optimizer_metrics_graph + return ba_input, ba_output, viewgraph_twoview_reports, metrics def init_cameras( - wRi_list: List[Optional[Rot3]], - wti_list: List[Optional[Point3]], + wTi_list: List[Optional[Pose3]], intrinsics_list: List[gtsfm_types.CALIBRATION_TYPE], ) -> Dict[int, gtsfm_types.CAMERA_TYPE]: """Generate camera from valid rotations and unit-translations. @@ -152,11 +161,5 @@ def init_cameras( Returns: Valid cameras. """ - cameras = {} - camera_class = gtsfm_types.get_camera_class_for_calibration(intrinsics_list[0]) - for idx, (wRi, wti) in enumerate(zip(wRi_list, wti_list)): - if wRi is not None and wti is not None: - cameras[idx] = camera_class(Pose3(wRi, wti), intrinsics_list[idx]) - - return cameras + return {idx: camera_class(wTi, intrinsics_list[idx]) for idx, wTi in enumerate(wTi_list) if wTi is not None} diff --git a/gtsfm/pose_slam/pose_slam.py b/gtsfm/pose_slam/pose_slam.py new file mode 100644 index 000000000..156c2de4c --- /dev/null +++ b/gtsfm/pose_slam/pose_slam.py @@ -0,0 +1,90 @@ +"""Pose SLAM initialization module from relative pose priors. + +Authors: Akshay Krishnan, Frank Dellaert +""" + +from typing import Dict, List, Optional, Tuple + +import dask +import gtsam +from dask.delayed import Delayed +from gtsam import Pose3 + +import gtsfm.utils.logger as logger_utils +from gtsfm.common.pose_prior import PosePrior +from gtsfm.evaluation.metrics import GtsfmMetric, GtsfmMetricsGroup + +PRIOR_NOISE_SIGMAS = [0.001, 0.001, 0.001, 0.1, 0.1, 0.1] +POSE_PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(PRIOR_NOISE_SIGMAS) + +logger = logger_utils.get_logger() + + +class PoseSlam: + """Initializes using PoseSLAM given relative pose priors.""" + + def run_pose_slam( + self, + num_images: int, + relative_pose_priors: Dict[Tuple[int, int], PosePrior] = {}, + gt_wTi_list: Optional[List[Optional[Pose3]]] = None, + ) -> Tuple[List[Optional[Pose3]], Optional[GtsfmMetricsGroup]]: + """Run the translation averaging. + + Args: + num_images: number of camera poses. + relative_pose_priors: priors on the pose between camera pairs as (i1, i2): i1Ti2. + gt_wTi_list: List of ground truth poses (wTi) for computing metrics. + + Returns: + List of Optional[Pose3], + GtsfmMetricsGroup of 1DSfM metrics. + """ + logger.info("Running Pose SLAM intilialization") + pose_init_graph = gtsam.NonlinearFactorGraph() + + for (i1, i2), i1Ti2_prior in relative_pose_priors.items(): + pose_init_graph.push_back( + gtsam.BetweenFactorPose3( + i1, + i2, + i1Ti2_prior.value, + gtsam.noiseModel.Gaussian.Covariance(i1Ti2_prior.covariance), + ) + ) + + pose_init_graph.push_back(gtsam.PriorFactorPose3(0, Pose3(), POSE_PRIOR_NOISE)) + + initial_values = gtsam.InitializePose3.initialize(pose_init_graph) + initial_error = pose_init_graph.error(initial_values) + logger.info(f"Initialization complete with error: {initial_error}") + optimizer = gtsam.LevenbergMarquardtOptimizer(pose_init_graph, initial_values) + result = optimizer.optimizeSafely() + + poses = [result.atPose3(i) if result.exists(i) else None for i in range(num_images)] + final_error = pose_init_graph.error(result) + logger.info(f"Optimization complete with error: {final_error}") + + # TODO: add metrics which are on par with the averaging metrics + return poses, GtsfmMetricsGroup( + "pose_slam_metrics", [GtsfmMetric("intial_error", initial_error), GtsfmMetric("final_error", final_error)] + ) + + def create_computation_graph( + self, + num_images: int, + relative_pose_priors: Dict[Tuple[int, int], PosePrior], + gt_wTi_list: Optional[List[Optional[Pose3]]] = None, + ) -> Tuple[Delayed, Delayed]: + """Create the computation graph for performing translation averaging. + + Args: + num_images: number of camera poses. + relative_pose_priors: priors on the pose between camera pairs (not delayed). + gt_wTi_list: List of ground truth poses (wTi) for computing metrics. + + Returns: + List of Optional[Pose3], wrapped as Delayed + GtsfmMetricsGroup of 1DSfM metrics, wrapped as Delayed + """ + return dask.delayed(self.run_pose_slam, nout=2)(num_images, relative_pose_priors, gt_wTi_list) diff --git a/gtsfm/retriever/rig_retriever.py b/gtsfm/retriever/rig_retriever.py index d2c9f484c..04d36bcf4 100644 --- a/gtsfm/retriever/rig_retriever.py +++ b/gtsfm/retriever/rig_retriever.py @@ -4,9 +4,11 @@ """ from typing import List, Tuple + from gtsfm.loader.hilti_loader import HiltiLoader import gtsfm.utils.logger as logger_utils +from gtsfm.common.constraint import Constraint from gtsfm.loader.loader_base import LoaderBase from gtsfm.retriever.retriever_base import RetrieverBase @@ -20,16 +22,23 @@ class RigRetriever(RetrieverBase): """Retriever for camera rigs inspired by the Hilti challenge.""" - def __init__(self, threshold: int = 100): + def __init__(self, subsample: int, threshold: int = 100): """Create RigRetriever Args: threshold (int, optional): amount of "proxy" correspondences that will trigger an image-pair. Default 100. """ + self._subsample = subsample self._threshold = threshold + def __accept_constraint(self, constraint: Constraint) -> bool: + if not self._subsample: + return True + + return constraint.a % self._subsample == 0 and constraint.b % self._subsample == 0 + def run(self, loader: LoaderBase) -> List[Tuple[int, int]]: - """Compute potential image pairs. + """Compute potential image pairs for *visual matching*. Args: loader: image loader. @@ -39,35 +48,37 @@ def run(self, loader: LoaderBase) -> List[Tuple[int, int]]: """ # Get between-rig constraints from HiltiLoader. assert isinstance(loader, HiltiLoader) - constraints = loader.constraints + constraints: List[Constraint] = loader.get_all_constraints() # Get pairs from those constraints. - pairs = set(sum([c.predicted_pairs(self._threshold) for c in constraints], [])) + unique_pairs = set( + sum([c.predicted_pairs(self._threshold) for c in constraints if self.__accept_constraint(c)], []) + ) + + num_cam2_pairs = list(filter(lambda edge: edge[0] % 5 == 2 or edge[1] % 5 == 2, unique_pairs)) - num_cam2_pairs = list(filter(lambda edge: edge[0] % 5 == 2 or edge[1] % 5 == 2, pairs)) + logger.info("Received %d constraints from loader", len(constraints)) + logger.info("Found %d pairs in the constraints file", len(unique_pairs)) + logger.info("Found %d pairs with cam2 in the constraints file", len(num_cam2_pairs)) - logger.info("Found %d pairs from the constraints file", len(pairs)) - logger.info("Found %d pairs with cam2 from the constraints file", len(num_cam2_pairs)) + # Translate all rig level constraints to CAM2-CAM2 constraints + for constraint in constraints: + if not self.__accept_constraint(constraint): + continue + a = constraint.a + b = constraint.b + + unique_pairs.add((loader.image_from_rig_and_camera(a, 2), loader.image_from_rig_and_camera(b, 2))) # Add all intra-rig pairs even if no LIDAR signal. - # Add all inter frames CAM2 pairs - for rig_index in range(loader.num_rig_poses): + for rig_index in range(0, loader.num_rig_poses, self._subsample if self._subsample else 1): for c1, c2 in INTRA_RIG_VALID_PAIRS: - pairs.add( + unique_pairs.add( (loader.image_from_rig_and_camera(rig_index, c1), loader.image_from_rig_and_camera(rig_index, c2)) ) - for next_rig_idx in range(rig_index + 1, min(rig_index + 1 + CAM2_FRAME_LOOKAHEAD, loader.num_rig_poses)): - pairs.add( - (loader.image_from_rig_and_camera(rig_index, 2), loader.image_from_rig_and_camera(next_rig_idx, 2)) - ) - pairs = list(pairs) + pairs = list(unique_pairs) pairs.sort() - # check on pairs - for i1, i2 in pairs: - if i1 > i2: - raise ValueError("Ordering not imposed on i1, i2") - - logger.info("Found %d pairs from the RigRetriever", len(pairs)) + logger.info("RigRetriever finally created %d pairs.", len(pairs)) return pairs diff --git a/gtsfm/runner/frontend_runner.py b/gtsfm/runner/frontend_runner.py index 1a6f646e9..ca1157519 100644 --- a/gtsfm/runner/frontend_runner.py +++ b/gtsfm/runner/frontend_runner.py @@ -41,35 +41,38 @@ def run_frontend( image_shapes = loader.get_image_shapes() # detection and description graph - keypoints_graph_list = [] - descriptors_graph_list = [] + keypoints_list = [] + descriptors_list = [] for delayed_image in image_graph: delayed_dets, delayed_descs = feature_extractor.create_computation_graph(delayed_image) - keypoints_graph_list += [delayed_dets] - descriptors_graph_list += [delayed_descs] + keypoints_list += [delayed_dets] + descriptors_list += [delayed_descs] # estimate two-view geometry and get indices of verified correspondences. - i2Ri1_graph_dict = {} - i2Ui1_graph_dict = {} - v_corr_idxs_graph_dict: Dict[Tuple[int, int], Delayed] = {} - for (i1, i2) in image_pair_indices: - (i2Ri1, i2Ui1, v_corr_idxs, two_view_report) = two_view_estimator.create_computation_graph( - keypoints_i1_graph=keypoints_graph_list[i1], - keypoints_i2_graph=keypoints_graph_list[i2], - descriptors_i1_graph=descriptors_graph_list[i1], - descriptors_i2_graph=descriptors_graph_list[i2], + i2Ri1_dict = {} + i2Ui1_dict = {} + v_corr_idxs_dict: Dict[Tuple[int, int], Delayed] = {} + for i1, i2 in image_pair_indices: + i2Ri1, i2Ui1, v_corr_idxs, _ = two_view_estimator.create_computation_graph( + keypoints_i1=keypoints_list[i1], + keypoints_i2=keypoints_list[i2], + descriptors_i1=descriptors_list[i1], + descriptors_i2=descriptors_list[i2], camera_intrinsics_i1=camera_intrinsics[i1], camera_intrinsics_i2=camera_intrinsics[i2], im_shape_i1=image_shapes[i1], im_shape_i2=image_shapes[i2], + i2Ti1_prior=None, + gt_wTi1=loader.get_camera_pose(i1), + gt_wTi2=loader.get_camera_pose(i2), ) - i2Ri1_graph_dict[(i1, i2)] = i2Ri1 - i2Ui1_graph_dict[(i1, i2)] = i2Ui1 - v_corr_idxs_graph_dict[(i1, i2)] = v_corr_idxs + i2Ri1_dict[(i1, i2)] = i2Ri1 + i2Ui1_dict[(i1, i2)] = i2Ui1 + v_corr_idxs_dict[(i1, i2)] = v_corr_idxs with dask.config.set(scheduler="single-threaded"): keypoints_list, i2Ri1_dict, i2Ui1_dict, v_corr_idxs_dict = dask.compute( - keypoints_graph_list, i2Ri1_graph_dict, i2Ui1_graph_dict, v_corr_idxs_graph_dict + keypoints_list, i2Ri1_dict, i2Ui1_dict, v_corr_idxs_dict ) return keypoints_list, i2Ri1_dict, i2Ui1_dict, v_corr_idxs_dict diff --git a/gtsfm/runner/gtsfm_runner_base.py b/gtsfm/runner/gtsfm_runner_base.py index 9eb648ccb..bbe6ba1f8 100644 --- a/gtsfm/runner/gtsfm_runner_base.py +++ b/gtsfm/runner/gtsfm_runner_base.py @@ -113,7 +113,7 @@ def construct_retriever(self): retriever = SequentialHiltiRetriever(max_frame_lookahead=self.parsed_args.max_frame_lookahead) elif matching_regime == ImageMatchingRegime.RIG_HILTI: - retriever = RigRetriever(threshold=self.parsed_args.proxy_threshold) + retriever = RigRetriever(threshold=self.parsed_args.proxy_threshold, subsample=self.parsed_args.subsample) return retriever @@ -131,20 +131,16 @@ def run(self) -> None: image_pair_indices = pairs_graph.compute() delayed_sfm_result, delayed_io = self.scene_optimizer.create_computation_graph( - num_images=len(self.loader), + self.loader, + self.loader.create_computation_graph_for_images(), image_pair_indices=image_pair_indices, - image_graph=self.loader.create_computation_graph_for_images(), - all_intrinsics=self.loader.get_all_intrinsics(), - image_shapes=self.loader.get_image_shapes(), - relative_pose_priors=self.loader.get_relative_pose_priors(image_pair_indices), absolute_pose_priors=self.loader.get_absolute_pose_priors(), - cameras_gt=self.loader.get_gt_cameras(), - gt_wTi_list=self.loader.get_gt_poses(), + relative_pose_priors=self.loader.get_relative_pose_priors(), matching_regime=ImageMatchingRegime(self.parsed_args.matching_regime), ) with Client(cluster), performance_report(filename="dask-report.html"): - sfm_result, *io = dask.compute(delayed_sfm_result, *delayed_io) + sfm_result, *io = dask.compute(delayed_sfm_result, *delayed_io.values()) assert isinstance(sfm_result, GtsfmData) diff --git a/gtsfm/runner/run_full_hilti_nodask.py b/gtsfm/runner/run_full_hilti_nodask.py new file mode 100644 index 000000000..cda8d9600 --- /dev/null +++ b/gtsfm/runner/run_full_hilti_nodask.py @@ -0,0 +1,242 @@ +"""Run front-end on the hilti dataset without using Dask. + +Authors: Ayush Baid +""" +import time +from argparse import ArgumentParser, Namespace +from typing import Dict, Optional, Tuple + +import hydra +import numpy as np +from hydra.utils import instantiate +from gtsam import Rot3, Unit3 + +import gtsfm.utils.graph as graph_utils +import gtsfm.utils.logger as logger_utils +from gtsfm.common.keypoints import Keypoints +from gtsfm.loader.hilti_loader import HiltiLoader +from gtsfm.retriever.rig_retriever import RigRetriever +from gtsfm.scene_optimizer import SceneOptimizer, save_gtsfm_data, save_metrics_reports, save_visualizations +from gtsfm.multi_view_optimizer import init_cameras + + +logger = logger_utils.get_logger() + + +class HiltiRunner: + def __init__(self) -> None: + argparser: ArgumentParser = self.construct_argparser() + parsed_args: Namespace = argparser.parse_args() + self._save_metrics = parsed_args.save_metrics + if not self._save_metrics: + logger.info("Will not save metrics") + + self.loader = HiltiLoader( + base_folder=parsed_args.dataset_dirpath, max_length=parsed_args.max_length, subsample=parsed_args.subsample + ) + + self.retriever = RigRetriever(subsample=parsed_args.subsample, threshold=parsed_args.proxy_threshold) + + with hydra.initialize_config_module(config_module="gtsfm.configs"): + # config is relative to the gtsfm module + cfg = hydra.compose( + config_name=parsed_args.config_name, + ) + self.scene_optimizer: SceneOptimizer = instantiate(cfg.SceneOptimizer) + + def construct_argparser(self) -> ArgumentParser: + parser = ArgumentParser(description="Run frontend for the hilti dataset") + + parser.add_argument( + "--dataset_dirpath", + type=str, + required=True, + help="path to directory containing the calibration files and the images", + ) + parser.add_argument( + "--config_name", + type=str, + default="deep_front_end_hilti.yaml", + help="Choose the config file", + ) + parser.add_argument( + "--proxy_threshold", + type=int, + default=100, + help="amount of 'proxy' correspondences that will trigger an image-pair. Default 100.", + ) + parser.add_argument("--max_length", type=int, default=None, help="Max number of timestamps to process") + parser.add_argument( + "--subsample", + type=int, + default=6, + help="Subsample the timestamps by given value n (pick every nth rig for visual SfM)", + ) + parser.add_argument("--save_metrics", action="store_true", help="Calculates metrics") + return parser + + def run_frontend( + self, + ) -> Tuple[ + Dict[int, Keypoints], + Dict[Tuple[int, int], Optional[Rot3]], + Dict[Tuple[int, int], Optional[Unit3]], + Dict[Tuple[int, int], np.ndarray], + Dict[int, Tuple[int, int]], + ]: + start_time = time.time() + + pairs_for_frontend = self.retriever.run(self.loader) + + image_indices_for_feature_extraction = set(sum(pairs_for_frontend, ())) + keypoints_dict = {} + descriptors_dict = {} + image_shapes = {} + + counter = 0 + for i in image_indices_for_feature_extraction: + counter += 1 + if counter % 20 == 0: + logger.info("%d/%d images", counter, len(image_indices_for_feature_extraction)) + + image = self.loader.get_image(i) + if image is not None: + keypoints, descriptors = self.scene_optimizer.feature_extractor.detector_descriptor.detect_and_describe( + image + ) + keypoints_dict[i] = keypoints + descriptors_dict[i] = descriptors + image_shapes[i] = (image.height, image.width) + + i2Ri1_dict = {} + i2Ui1_dict = {} + v_corr_idxs_dict = {} + + counter = 0 + for i1, i2 in pairs_for_frontend: + counter += 1 + if counter % 100 == 0: + logger.info("%d/%d pairs", counter, len(pairs_for_frontend)) + if i1 in keypoints_dict and i2 in keypoints_dict: + i2Ri1, i2Ui1, v_corr_idxs = self.scene_optimizer.two_view_estimator.run_2view( + keypoints_i1=keypoints_dict[i1], + keypoints_i2=keypoints_dict[i2], + descriptors_i1=descriptors_dict[i1], + descriptors_i2=descriptors_dict[i2], + camera_intrinsics_i1=self.loader.get_camera_intrinsics(i1), + camera_intrinsics_i2=self.loader.get_camera_intrinsics(i2), + im_shape_i1=image_shapes[i1], + im_shape_i2=image_shapes[i2], + i2Ti1_prior=None, + gt_wTi1=None, + gt_wTi2=None, + gt_scene_mesh=None, + ) + + i2Ri1_dict[(i1, i2)] = i2Ri1 + i2Ui1_dict[(i1, i2)] = i2Ui1 + v_corr_idxs_dict[(i1, i2)] = v_corr_idxs + + end_time = time.time() + duration_sec = end_time - start_time + logger.info("GTSFM took %.2f minutes to compute frontend.", duration_sec / 60) + + return keypoints_dict, i2Ri1_dict, i2Ui1_dict, v_corr_idxs_dict, image_shapes + + def run_full(self): + start_time = time.time() + + metrics = [] + num_images = len(self.loader) + gt_wTi_list = self.loader.get_gt_poses() + relative_pose_priors = self.loader.get_relative_pose_priors() + + # If using Pose-SLAM, try running that immediately. No point in continuing if fails. + if self.scene_optimizer.multiview_optimizer._use_pose_slam_initialization: + wTi_list, pose_slam_metrics = self.scene_optimizer.multiview_optimizer.pose_slam_module.run_pose_slam( + num_images=num_images, relative_pose_priors=relative_pose_priors, gt_wTi_list=gt_wTi_list + ) + if self._save_metrics: + metrics.append(pose_slam_metrics) + + keypoints_dict, i2Ri1_dict, i2Ui1_dict, v_corr_idxs_dict, image_shapes = self.run_frontend() + + keypoints_list = [keypoints_dict.get(i, Keypoints(np.array([[]]))) for i in range(num_images)] + image_shapes_list = [image_shapes.get(i, (100, 100)) for i in range(num_images)] + + pruned_i2Ri1_dict, pruned_i2Ui1_dict = graph_utils.prune_to_largest_connected_component( + i2Ri1_dict, i2Ui1_dict, relative_pose_priors + ) + + absolute_pose_priors = self.loader.get_absolute_pose_priors() + + # If not using Pose-SLAM, we need to run with constraints from front-end. + if not self.scene_optimizer.multiview_optimizer._use_pose_slam_initialization: + + wRi = self.scene_optimizer.multiview_optimizer.rot_avg_module.run_rotation_averaging( + num_images, pruned_i2Ri1_dict, relative_pose_priors + ) + rot_avg_metrics = self.scene_optimizer.multiview_optimizer.rot_avg_module.evaluate( + wRi_computed=wRi, wTi_gt=gt_wTi_list + ) + + if self._save_metrics: + metrics.append(rot_avg_metrics) + + wTi_list, ta_metrics = self.scene_optimizer.multiview_optimizer.trans_avg_module.run_translation_averaging( + num_images=num_images, + i2Ui1_dict=pruned_i2Ui1_dict, + wRi_list=wRi, + absolute_pose_priors=absolute_pose_priors, + scale_factor=1, + gt_wTi_list=gt_wTi_list, + ) + + if self._save_metrics: + metrics.append(ta_metrics) + + gt_cameras = self.loader.get_gt_cameras() + all_intrinsics = self.loader.get_all_intrinsics() + initialized_cameras = init_cameras(wTi_list=wTi_list, intrinsics_list=all_intrinsics) + + ba_input, da_metrics = self.scene_optimizer.multiview_optimizer.data_association_module.run_da( + num_images=num_images, + cameras=initialized_cameras, + corr_idxs_dict=v_corr_idxs_dict, + keypoints_list=keypoints_list, + cameras_gt=gt_cameras, + relative_pose_priors=relative_pose_priors, + images=None, + ) + if self._save_metrics: + metrics.append(da_metrics) + + ba_unfiltered, ba_output, _ = self.scene_optimizer.multiview_optimizer.ba_optimizer.run_ba( + initial_data=ba_input, + absolute_pose_priors=absolute_pose_priors, + relative_pose_priors=relative_pose_priors, + verbose=True, + intrinsics=all_intrinsics, + ) + save_gtsfm_data(None, image_shapes_list, self.loader.get_image_fnames(), None, ba_output, save_for_react=False) + + ba_metrics = self.scene_optimizer.multiview_optimizer.ba_optimizer.evaluate( + ba_unfiltered, ba_output, gt_cameras + ) + if self._save_metrics: + metrics.append(ba_metrics) + + if self._save_metrics: + ba_input_aligned = ba_input.align_via_Sim3_to_poses(wTi_list_ref=gt_wTi_list) + ba_output_aligned = ba_output.align_via_Sim3_to_poses(wTi_list_ref=gt_wTi_list) + save_metrics_reports(metrics) + save_visualizations(ba_input_aligned, ba_output_aligned, gt_wTi_list) + + end_time = time.time() + duration_sec = end_time - start_time + logger.info("GTSFM took %.2f minutes to compute sparse multi-view result.", duration_sec / 60) + + +if __name__ == "__main__": + runner = HiltiRunner() + runner.run_full() diff --git a/gtsfm/runner/run_scene_optimizer_argoverse.py b/gtsfm/runner/run_scene_optimizer_argoverse.py index 45f79b326..04b4a6684 100644 --- a/gtsfm/runner/run_scene_optimizer_argoverse.py +++ b/gtsfm/runner/run_scene_optimizer_argoverse.py @@ -32,19 +32,16 @@ def run_scene_optimizer(args: argparse.Namespace) -> None: ) delayed_sfm_result, delayed_io = scene_optimizer.create_computation_graph( - num_images=len(loader), + loader, + loader.create_computation_graph_for_images(), image_pair_indices=loader.get_valid_pairs(), - image_graph=loader.create_computation_graph_for_images(), - all_intrinsics=loader.get_all_intrinsics(), - image_shapes=loader.get_image_shapes(), - cameras_gt=loader.get_gt_cameras(), ) # create dask client cluster = LocalCluster(n_workers=args.num_workers, threads_per_worker=args.threads_per_worker) with Client(cluster), performance_report(filename="dask-report.html"): - sfm_result, *io = dask.compute(delayed_sfm_result, *delayed_io) + sfm_result, *io = dask.compute(delayed_sfm_result, *delayed_io.values()) assert isinstance(sfm_result, GtsfmData) scene_avg_reproj_error = sfm_result.get_avg_scene_reprojection_error() diff --git a/gtsfm/runner/run_scene_optimizer_astronet.py b/gtsfm/runner/run_scene_optimizer_astronet.py index be6e6aaa6..2ef40f4fd 100644 --- a/gtsfm/runner/run_scene_optimizer_astronet.py +++ b/gtsfm/runner/run_scene_optimizer_astronet.py @@ -12,7 +12,6 @@ from gtsfm.common.gtsfm_data import GtsfmData from gtsfm.loader.loader_base import LoaderBase from gtsfm.loader.astronet_loader import AstronetLoader -from gtsfm.retriever.retriever_base import ImageMatchingRegime from gtsfm.runner.gtsfm_runner_base import GtsfmRunnerBase logger = logger_utils.get_logger() @@ -68,21 +67,16 @@ def run(self) -> None: # Prepare computation graph. delayed_sfm_result, delayed_io = self.scene_optimizer.create_computation_graph( - num_images=len(self.loader), + self.loader, + self.loader.create_computation_graph_for_images(), image_pair_indices=image_pair_indices, - image_graph=self.loader.create_computation_graph_for_images(), - all_intrinsics=self.loader.get_all_intrinsics(), - image_shapes=self.loader.get_image_shapes(), - gt_scene_mesh=gt_scene_trimesh_future, - cameras_gt=self.loader.get_gt_cameras(), - gt_wTi_list=self.loader.get_gt_poses(), - matching_regime=ImageMatchingRegime(self.parsed_args.matching_regime), absolute_pose_priors=self.loader.get_absolute_pose_priors(), - relative_pose_priors=self.loader.get_relative_pose_priors(image_pair_indices), + relative_pose_priors=self.loader.get_relative_pose_priors(), + gt_scene_mesh=gt_scene_trimesh_future, ) # Run SfM pipeline. - sfm_result, *io = dask.compute(delayed_sfm_result, *delayed_io) + sfm_result, *io = dask.compute(delayed_sfm_result, *delayed_io.values()) assert isinstance(sfm_result, GtsfmData) logger.info("GTSFM took %.2f minutes to compute sparse multi-view result.", (time.time() - start_time) / 60) diff --git a/gtsfm/runner/run_scene_optimizer_hilti.py b/gtsfm/runner/run_scene_optimizer_hilti.py index bb25f31bf..85e9a9dc0 100644 --- a/gtsfm/runner/run_scene_optimizer_hilti.py +++ b/gtsfm/runner/run_scene_optimizer_hilti.py @@ -12,7 +12,6 @@ logger = logger_utils.get_logger() - class GtsfmRunnerHiltiLoader(GtsfmRunnerBase): def __init__(self): super(GtsfmRunnerHiltiLoader, self).__init__(tag="GTSFM for the hilti loader") @@ -34,6 +33,12 @@ def construct_argparser(self) -> argparse.ArgumentParser: ) parser.add_argument("--max_length", type=int, default=None, help="Max number of timestamps to process") + parser.add_argument( + "--subsample", + type=int, + default=1, + help="Subsample the timestamps by given value n (pick every nth rig for visual SfM)", + ) return parser @@ -41,6 +46,7 @@ def construct_loader(self) -> LoaderBase: loader = HiltiLoader( base_folder=self.parsed_args.dataset_dirpath, max_length=self.parsed_args.max_length, + subsample=self.parsed_args.subsample, ) return loader diff --git a/gtsfm/scene_optimizer.py b/gtsfm/scene_optimizer.py index eaae81630..caa9ff66c 100644 --- a/gtsfm/scene_optimizer.py +++ b/gtsfm/scene_optimizer.py @@ -15,9 +15,8 @@ from dask.delayed import Delayed from gtsfm.common.pose_prior import PosePrior -import gtsfm.common.types as gtsfm_types import gtsfm.evaluation.metrics_report as metrics_report -import gtsfm.two_view_estimator as two_view_estimator +from gtsfm.loader.loader_base import LoaderBase import gtsfm.utils.ellipsoid as ellipsoid_utils import gtsfm.utils.io as io_utils import gtsfm.utils.logger as logger_utils @@ -26,6 +25,7 @@ from gtsfm.common.gtsfm_data import GtsfmData from gtsfm.common.image import Image from gtsfm.densify.mvs_base import MVSBase +from gtsfm.evaluation.metrics import GtsfmMetricsGroup from gtsfm.feature_extractor import FeatureExtractor from gtsfm.multi_view_optimizer import MultiViewOptimizer from gtsfm.retriever.retriever_base import ImageMatchingRegime @@ -40,10 +40,14 @@ matplotlib.use("Agg") +BASE_PATH_ENV_KEY = "GTSFM_BASE_PATH" +BASE_PATH_STR = os.environ.get(BASE_PATH_ENV_KEY) +BASE_PATH = Path(BASE_PATH_STR) if BASE_PATH_STR is not None else Path(__file__).resolve().parent.parent + # base paths for storage -PLOT_BASE_PATH = Path(__file__).resolve().parent.parent / "plots" -METRICS_PATH = Path(__file__).resolve().parent.parent / "result_metrics" -RESULTS_PATH = Path(__file__).resolve().parent.parent / "results" +PLOT_BASE_PATH = BASE_PATH / "plots" +METRICS_PATH = BASE_PATH / "result_metrics" +RESULTS_PATH = BASE_PATH / "results" # plot paths PLOT_CORRESPONDENCE_PATH = PLOT_BASE_PATH / "correspondences" @@ -52,8 +56,8 @@ MVS_PLY_SAVE_FPATH = RESULTS_PATH / "mvs_output" / "dense_pointcloud.ply" # Paths to Save Output in React Folders. -REACT_METRICS_PATH = Path(__file__).resolve().parent.parent / "rtf_vis_tool" / "src" / "result_metrics" -REACT_RESULTS_PATH = Path(__file__).resolve().parent.parent / "rtf_vis_tool" / "public" / "results" +REACT_METRICS_PATH = BASE_PATH / "rtf_vis_tool" / "src" / "result_metrics" +REACT_RESULTS_PATH = BASE_PATH / "rtf_vis_tool" / "public" / "results" logger = logger_utils.get_logger() @@ -110,12 +114,9 @@ def __init__( def create_computation_graph_for_frontend( self, + loader: LoaderBase, + images: List[Delayed], image_pair_indices: List[Tuple[int, int]], - image_graph: List[Delayed], - all_intrinsics: List[Optional[gtsfm_types.CALIBRATION_TYPE]], - image_shapes: List[Tuple[int, int]], - relative_pose_priors: Dict[Tuple[int, int], PosePrior], - gt_poses_graph: List[Optional[Pose3]], gt_scene_mesh: Optional[Trimesh] = None, ) -> Tuple[Dict[Tuple[int, int], Delayed], Dict[Tuple[int, int], Delayed]]: """The SceneOptimizer plate calls the FeatureExtractor and TwoViewEstimator plates several times.""" @@ -123,20 +124,24 @@ def create_computation_graph_for_frontend( # detection and description graph delayed_keypoints = [] delayed_descriptors = [] - for delayed_image in image_graph: + for delayed_image in images: (delayed_dets, delayed_descs) = self.feature_extractor.create_computation_graph(delayed_image) delayed_keypoints += [delayed_dets] delayed_descriptors += [delayed_descs] # Estimate two-view geometry and get indices of verified correspondences. - i2Ri1_graph_dict = {} - i2Ui1_graph_dict = {} + i2Ri1_dict = {} + i2Ui1_dict = {} + all_intrinsics = loader.get_all_intrinsics() + image_shapes = loader.get_image_shapes() + gt_wTi_list = loader.get_gt_poses() + relative_pose_priors = loader.get_relative_pose_priors() for (i1, i2) in image_pair_indices: # Collect ground truth relative and absolute poses if available. # TODO(johnwlambert): decompose this method -- name it as "calling_the_plate()" # TODO(johnwlambert): decompose this so what happens in the loop is a separate method - i2Ri1, i2Ui1, v_corr_idxs, _ = self.two_view_estimator.create_computation_graph( + i2Ri1, i2Ui1, _, _ = self.two_view_estimator.create_computation_graph( delayed_keypoints[i1], delayed_keypoints[i2], delayed_descriptors[i1], @@ -146,53 +151,54 @@ def create_computation_graph_for_frontend( image_shapes[i1], image_shapes[i2], relative_pose_priors[(i1, i2)], - gt_poses_graph[i1], - gt_poses_graph[i2], + gt_wTi_list[i1], + gt_wTi_list[i2], gt_scene_mesh, ) # Store results. - i2Ri1_graph_dict[(i1, i2)] = i2Ri1 - i2Ui1_graph_dict[(i1, i2)] = i2Ui1 + i2Ri1_dict[(i1, i2)] = i2Ri1 + i2Ui1_dict[(i1, i2)] = i2Ui1 - return i2Ri1_graph_dict, i2Ui1_graph_dict + return i2Ri1_dict, i2Ui1_dict def create_computation_graph( self, - num_images: int, + loader: LoaderBase, + images: List[Delayed], image_pair_indices: List[Tuple[int, int]], - image_graph: List[Delayed], - all_intrinsics: List[Optional[gtsfm_types.CALIBRATION_TYPE]], - image_shapes: List[Tuple[int, int]], absolute_pose_priors: List[Optional[PosePrior]], relative_pose_priors: Dict[Tuple[int, int], PosePrior], - cameras_gt: List[Optional[gtsfm_types.CAMERA_TYPE]], - gt_wTi_list: List[Optional[Pose3]], gt_scene_mesh: Optional[Trimesh] = None, matching_regime: ImageMatchingRegime = ImageMatchingRegime.SEQUENTIAL, - ) -> Tuple[Delayed, List[Delayed]]: + ) -> Tuple[Delayed, Dict[str, Delayed]]: """The SceneOptimizer plate calls the FeatureExtractor and TwoViewEstimator plates several times.""" # auxiliary graph elements for visualizations and saving intermediate data for analysis. - delayed_results = [] + delayed_io: Dict[str, Delayed] = {} # detection and description graph delayed_keypoints = [] delayed_descriptors = [] - for delayed_image in image_graph: + images = loader.create_computation_graph_for_images() + for delayed_image in images: (delayed_dets, delayed_descs) = self.feature_extractor.create_computation_graph(delayed_image) delayed_keypoints += [delayed_dets] delayed_descriptors += [delayed_descs] # Estimate two-view geometry and get indices of verified correspondences. - i2Ri1_graph_dict = {} - i2Ui1_graph_dict = {} - v_corr_idxs_graph_dict: Dict[Tuple[int, int], Delayed] = {} + delayed_i2Ri1s: Dict[Tuple[int, int], Delayed] = {} + delayed_i2Ui1s: Dict[Tuple[int, int], Delayed] = {} + delayed_v_corr_idxs: Dict[Tuple[int, int], Delayed] = {} two_view_reports_dict: Dict[str, Dict[Tuple[int, int], Optional[Delayed]]] = { PRE_BA_REPORT_TAG: {}, POST_BA_REPORT_TAG: {}, POST_ISP_REPORT_TAG: {}, } + all_intrinsics = loader.get_all_intrinsics() + image_shapes = loader.get_image_shapes() + gt_wTi_list = loader.get_gt_poses() + relative_pose_priors = loader.get_relative_pose_priors() for (i1, i2) in image_pair_indices: # Collect ground truth relative and absolute poses if available. # TODO(johnwlambert): decompose this method -- name it as "calling_the_plate()" @@ -214,18 +220,18 @@ def create_computation_graph( ) # Store results. - i2Ri1_graph_dict[(i1, i2)] = i2Ri1 - i2Ui1_graph_dict[(i1, i2)] = i2Ui1 - v_corr_idxs_graph_dict[(i1, i2)] = v_corr_idxs + delayed_i2Ri1s[(i1, i2)] = i2Ri1 + delayed_i2Ui1s[(i1, i2)] = i2Ui1 + delayed_v_corr_idxs[(i1, i2)] = v_corr_idxs for token in (PRE_BA_REPORT_TAG, POST_BA_REPORT_TAG, POST_ISP_REPORT_TAG): two_view_reports_dict[token][(i1, i2)] = two_view_reports[token] # Visualize verified two-view correspondences. if self._save_two_view_correspondences_viz: - delayed_results.append( + delayed_io[f"2view_corr_viz_{i1}_{i2}"].append( dask.delayed(viz_utils.save_twoview_correspondences_viz)( - image_graph[i1], - image_graph[i2], + images[i1], + images[i2], delayed_keypoints[i1], delayed_keypoints[i2], v_corr_idxs, @@ -234,25 +240,24 @@ def create_computation_graph( ) ) - # Note: the MultiviewOptimizer returns BA input and BA output that are aligned to GT via Sim(3). ( ba_input_graph, ba_output_graph, view_graph_two_view_reports, optimizer_metrics_graph, ) = self.multiview_optimizer.create_computation_graph( - image_graph, - num_images, + len(loader), delayed_keypoints, - i2Ri1_graph_dict, - i2Ui1_graph_dict, - v_corr_idxs_graph_dict, + delayed_i2Ri1s, + delayed_i2Ui1s, + delayed_v_corr_idxs, all_intrinsics, absolute_pose_priors, relative_pose_priors, two_view_reports_dict[POST_ISP_REPORT_TAG], - cameras_gt, + loader.get_gt_cameras(), gt_wTi_list, + images, ) if view_graph_two_view_reports is not None: two_view_reports_dict[VIEWGRAPH_REPORT_TAG] = view_graph_two_view_reports @@ -261,16 +266,14 @@ def create_computation_graph( # TODO(akshay-krishnan): this delays saving the frontend reports until MVO has completed, not ideal. metrics_graph_list: List[Delayed] = [] for tag, report_dict in two_view_reports_dict.items(): - delayed_results.append( - dask.delayed(save_full_frontend_metrics)( - report_dict, - image_graph, - filename="two_view_report_{}.json".format(tag), - matching_regime=matching_regime, - ) + delayed_io["full_frontend_metrics"] = dask.delayed(save_full_frontend_metrics)( + report_dict, + images, + filename="two_view_report_{}.json".format(tag), + matching_regime=matching_regime, ) metrics_graph_list.append( - dask.delayed(two_view_estimator.aggregate_frontend_metrics)( + dask.delayed(metrics_utils.aggregate_frontend_metrics)( report_dict, self._pose_angular_error_thresh, metric_group_name="verifier_summary_{}".format(tag), @@ -281,19 +284,25 @@ def create_computation_graph( if optimizer_metrics_graph is not None: metrics_graph_list.extend(optimizer_metrics_graph) + # TODO: fix this? # Modify BA input, BA output, and GT poses to have point clouds and frustums aligned with x,y,z axes. ba_input_graph, ba_output_graph, gt_wTi_list = dask.delayed(align_estimated_gtsfm_data, nout=3)( ba_input_graph, ba_output_graph, gt_wTi_list ) if self._save_3d_viz: - delayed_results.extend(save_visualizations(ba_input_graph, ba_output_graph, gt_wTi_list)) + # TODO: align before viz + delayed_io["save_visualizations"] = dask.delayed(save_visualizations)( + ba_input_graph, ba_output_graph, gt_wTi_list + ) if self._save_gtsfm_data: - delayed_results.extend(save_gtsfm_data(image_graph, ba_input_graph, ba_output_graph)) + delayed_io["save_gtsfm_data"] = dask.delayed(save_gtsfm_data)( + images, loader.get_image_shapes(), loader.get_image_fnames(), ba_input_graph, ba_output_graph + ) if self._run_dense_optimizer: - img_dict_graph = dask.delayed(get_image_dictionary)(image_graph) + img_dict_graph = dask.delayed(get_image_dictionary)(images) ( dense_points_graph, dense_point_colors_graph, @@ -302,10 +311,8 @@ def create_computation_graph( ) = self.dense_multiview_optimizer.create_computation_graph(img_dict_graph, ba_output_graph) # Cast to string as Open3d cannot use PosixPath's for I/O -- only string file paths are accepted. - delayed_results.append( - dask.delayed(io_utils.save_point_cloud_as_ply)( - save_fpath=str(MVS_PLY_SAVE_FPATH), points=dense_points_graph, rgb=dense_point_colors_graph - ) + delayed_io["save_point_cloud_as_ply"] = dask.delayed(io_utils.save_point_cloud_as_ply)( + save_fpath=str(MVS_PLY_SAVE_FPATH), points=dense_points_graph, rgb=dense_point_colors_graph ) # Add metrics for dense reconstruction and voxel downsampling @@ -315,10 +322,10 @@ def create_computation_graph( metrics_graph_list.append(downsampling_metrics_graph) # Save metrics to JSON and generate HTML report. - delayed_results.extend(save_metrics_reports(metrics_graph_list)) + delayed_io["save_metrics_reports"] = dask.delayed(save_metrics_reports)(metrics_graph_list) # return the entry with just the sfm result - return ba_output_graph, delayed_results + return ba_output_graph, delayed_io def get_image_dictionary(image_list: List[Image]) -> Dict[int, Image]: @@ -351,95 +358,77 @@ def align_estimated_gtsfm_data( return ba_input, ba_output, gt_pose_graph -def save_visualizations( - ba_input_graph: Delayed, ba_output_graph: Delayed, gt_pose_graph: List[Optional[Delayed]] -) -> List[Delayed]: +def save_visualizations(ba_input: GtsfmData, ba_output: GtsfmData, gt_poses: List[Optional[Pose3]]) -> None: """Save SfmData before and after bundle adjustment and camera poses for visualization. - Accepts delayed GtsfmData before and after bundle adjustment, along with GT poses, - saves them and returns a delayed object. + Note: no alignment is performed in this function. Args: ba_input_graph: Delayed GtsfmData input to bundle adjustment. ba_output_graph: Delayed GtsfmData output from bundle adjustment. gt_pose_graph: Delayed ground truth poses. - - Returns: - A list of Delayed objects after saving the different visualizations. """ - aligned_ba_input_graph = dask.delayed(lambda x, y: x.align_via_Sim3_to_poses(y))(ba_input_graph, gt_pose_graph) - aligned_ba_output_graph = dask.delayed(lambda x, y: x.align_via_Sim3_to_poses(y))(ba_output_graph, gt_pose_graph) - viz_graph_list = [] - viz_graph_list.append(dask.delayed(viz_utils.save_sfm_data_viz)(aligned_ba_input_graph, PLOT_BA_INPUT_PATH)) - viz_graph_list.append(dask.delayed(viz_utils.save_sfm_data_viz)(aligned_ba_output_graph, PLOT_RESULTS_PATH)) - viz_graph_list.append( - dask.delayed(viz_utils.save_camera_poses_viz)( - aligned_ba_input_graph, aligned_ba_output_graph, gt_pose_graph, PLOT_RESULTS_PATH - ) - ) - return viz_graph_list - - -def save_gtsfm_data(image_graph: List[Delayed], ba_input_graph: Delayed, ba_output_graph: Delayed) -> List[Delayed]: - """Saves the Gtsfm data before and after bundle adjustment. + viz_utils.save_sfm_data_viz(ba_input, str(PLOT_BA_INPUT_PATH)) + viz_utils.save_sfm_data_viz(ba_output, str(PLOT_BA_INPUT_PATH)) + viz_utils.save_camera_poses_viz(ba_input, ba_output, gt_poses, str(PLOT_RESULTS_PATH)) + + +def save_gtsfm_data( + images: Optional[List[Image]], + image_shapes: List[Tuple[int, int]], + image_fnames: List[str], + ba_input: Optional[GtsfmData], + ba_output: Optional[GtsfmData], + save_for_react=True, +) -> None: + """Saves the Gtsfm data before and after bundle adjustment at RESULTS_PATH and a copy at REACT_RESULTS_PATH Args: - image_graph: input image wrapped as Delayed objects. - ba_input_graph: GtsfmData input to bundle adjustment wrapped as Delayed. - ba_output_graph: GtsfmData output to bundle adjustment wrapped as Delayed. - - Returns: - A list of delayed objects after saving the input and outputs to bundle adjustment. + images: list of images (optional). + image_shapes: shapes for the images. + image_fnames: file names of the images. + ba_input: input to bundle adjustment module. + ba_output: output to bundle adjustment module. """ - saving_graph_list = [] - # Save a duplicate in REACT_RESULTS_PATH. - for output_dir in [RESULTS_PATH, REACT_RESULTS_PATH]: - # Save the input to Bundle Adjustment (from data association). - saving_graph_list.append( - dask.delayed(io_utils.export_model_as_colmap_text)( - ba_input_graph, - image_graph, - save_dir=os.path.join(output_dir, "ba_input"), + + paths = [RESULTS_PATH] + if save_for_react: + paths += [REACT_RESULTS_PATH] + for output_dir in paths: + if ba_input is not None: + io_utils.export_model_as_colmap_text( + ba_input, + image_shapes, + image_fnames, + images, + save_dir=str(output_dir / "ba_input"), ) - ) - # Save the output of Bundle Adjustment. - saving_graph_list.append( - dask.delayed(io_utils.export_model_as_colmap_text)( - ba_output_graph, - image_graph, - save_dir=os.path.join(output_dir, "ba_output"), + if ba_output is not None: + io_utils.export_model_as_colmap_text( + ba_output, + image_shapes, + image_fnames, + images, + save_dir=str(output_dir / "ba_output"), ) - ) - return saving_graph_list -def save_metrics_reports(metrics_graph_list: List[Delayed]) -> List[Delayed]: +def save_metrics_reports(metrics_graph_list: List[GtsfmMetricsGroup]) -> None: """Saves metrics to JSON and HTML report. Args: metrics_graph: List of GtsfmMetricsGroup from different modules wrapped as Delayed. - - Returns: - List of delayed objects after saving metrics. """ - save_metrics_graph_list: List[Delayed] = [] if len(metrics_graph_list) == 0: - return save_metrics_graph_list + return None # Save metrics to JSON - save_metrics_graph_list.append(dask.delayed(metrics_utils.save_metrics_as_json)(metrics_graph_list, METRICS_PATH)) - save_metrics_graph_list.append( - dask.delayed(metrics_utils.save_metrics_as_json)(metrics_graph_list, REACT_METRICS_PATH) - ) - save_metrics_graph_list.append( - dask.delayed(metrics_report.generate_metrics_report_html)( - metrics_graph_list, - os.path.join(METRICS_PATH, "gtsfm_metrics_report.html"), - None, - ) + metrics_utils.save_metrics_as_json(metrics_graph_list, str(METRICS_PATH)) + metrics_utils.save_metrics_as_json(metrics_graph_list, str(REACT_METRICS_PATH)) + metrics_report.generate_metrics_report_html( + metrics_graph_list, str(METRICS_PATH / "gtsfm_metrics_report.html"), None ) - return save_metrics_graph_list def save_full_frontend_metrics( diff --git a/gtsfm/two_view_estimator.py b/gtsfm/two_view_estimator.py index 28bbe48ef..e6a6559bb 100644 --- a/gtsfm/two_view_estimator.py +++ b/gtsfm/two_view_estimator.py @@ -34,7 +34,6 @@ from gtsfm.frontend.inlier_support_processor import InlierSupportProcessor from gtsfm.frontend.matcher.matcher_base import MatcherBase from gtsfm.frontend.verifier.verifier_base import VerifierBase -from gtsfm.evaluation.metrics import GtsfmMetric, GtsfmMetricsGroup logger = logger_utils.get_logger() @@ -207,7 +206,7 @@ def bundle_adjust( if i2Ti1_prior is not None: relative_pose_prior_for_ba = {(0, 1): i2Ti1_prior} - _, ba_output, valid_mask = self._ba_optimizer.run( + _, ba_output, valid_mask = self._ba_optimizer.run_ba( ba_input, absolute_pose_priors=[], relative_pose_priors=relative_pose_prior_for_ba, verbose=False ) valid_corr_idxs = verified_corr_idxs[triangulated_indices][valid_mask] @@ -248,7 +247,7 @@ def get_corr_metric_dist_threshold(self) -> float: """Getter for the distance threshold used in the metric for correct correspondences.""" return self._corr_metric_dist_threshold - def run( + def run_2view( self, keypoints_i1: Keypoints, keypoints_i2: Keypoints, @@ -354,7 +353,7 @@ def run( post_isp_i2Ui1, post_isp_v_corr_idxs, post_isp_report, - ) = self.processor.run(post_ba_i2Ri1, post_ba_i2Ui1, post_ba_v_corr_idxs, post_ba_report) + ) = self.processor.run_inlier_support(post_ba_i2Ri1, post_ba_i2Ui1, post_ba_v_corr_idxs, post_ba_report) two_view_reports = { PRE_BA_REPORT_TAG: pre_ba_report, @@ -366,32 +365,34 @@ def run( def create_computation_graph( self, - keypoints_i1_graph: Delayed, - keypoints_i2_graph: Delayed, - descriptors_i1_graph: Delayed, - descriptors_i2_graph: Delayed, + keypoints_i1: Delayed, + keypoints_i2: Delayed, + descriptors_i1: Delayed, + descriptors_i2: Delayed, camera_intrinsics_i1: Optional[gtsfm_types.CALIBRATION_TYPE], camera_intrinsics_i2: Optional[gtsfm_types.CALIBRATION_TYPE], im_shape_i1: Tuple[int, int], im_shape_i2: Tuple[int, int], - i2Ti1_prior: Optional[PosePrior] = None, - gt_wTi1: Optional[Pose3] = None, - gt_wTi2: Optional[Pose3] = None, - gt_scene_mesh_graph: Optional[Delayed] = None, + i2Ti1_prior: Optional[PosePrior], + gt_wTi1: Optional[Pose3], + gt_wTi2: Optional[Pose3], + gt_scene_mesh_graph: Optional[Any] = None, ) -> Tuple[Delayed, Delayed, Delayed, Delayed]: """Create delayed tasks for matching and verification. Args: - keypoints_i1_graph: keypoints for image i1. - keypoints_i2_graph: keypoints for image i2. - descriptors_i1_graph: corr. descriptors for image i1. - descriptors_i2_graph: corr. descriptors for image i2. + keypoints_i1: keypoints for image i1. + keypoints_i2: keypoints for image i2. + descriptors_i1: corr. descriptors for image i1. + descriptors_i2: corr. descriptors for image i2. camera_intrinsics_i1: intrinsics for camera i1. camera_intrinsics_i2: intrinsics for camera i2. im_shape_i1: image shape for image i1. im_shape_i2: image shape for image i2. - i2Ti1_prior: the prior on relative pose i2Ti1. - i2Ti1_expected_graph (optional): ground truth relative pose, used for evaluation if available. + i2Ti1_prior (optional): the prior on relative pose i2Ti1. + gt_wTi1: ground truth camera pose for i1, to be used for metrics. + gt_wTi2: ground truth camera pose for i2, to be used for metrics. + gt_scene_mesh_graph: ground truth scene mesh, to be used for metrics. Returns: Computed relative rotation wrapped as Delayed. @@ -399,11 +400,11 @@ def create_computation_graph( Indices of verified correspondences wrapped as Delayed. Two-view reports at different stages (pre BA, post BA, and post inlier-support-processor), as a dictionary. """ - return dask.delayed(self.run, nout=4)( - keypoints_i1=keypoints_i1_graph, - keypoints_i2=keypoints_i2_graph, - descriptors_i1=descriptors_i1_graph, - descriptors_i2=descriptors_i2_graph, + return dask.delayed(self.run_2view, nout=4)( + keypoints_i1=keypoints_i1, + keypoints_i2=keypoints_i2, + descriptors_i1=descriptors_i1, + descriptors_i2=descriptors_i2, camera_intrinsics_i1=camera_intrinsics_i1, camera_intrinsics_i2=camera_intrinsics_i2, im_shape_i1=im_shape_i1, @@ -484,111 +485,3 @@ def compute_relative_pose_metrics( return (None, None) return (R_error_deg, U_error_deg) - - -def aggregate_frontend_metrics( - two_view_reports_dict: Dict[Tuple[int, int], Optional[TwoViewEstimationReport]], - angular_err_threshold_deg: float, - metric_group_name: str, -) -> None: - """Aggregate the front-end metrics to log summary statistics. - - We define "pose error" as the maximum of the angular errors in rotation and translation, per: - SuperGlue, CVPR 2020: https://arxiv.org/pdf/1911.11763.pdf - Learning to find good correspondences. CVPR 2018: - OA-Net, ICCV 2019: - NG-RANSAC, ICCV 2019: - - Args: - two_view_report_dict: report containing front-end metrics for each image pair. - angular_err_threshold_deg: threshold for classifying angular error metrics as success. - metric_group_name: name we will assign to the GtsfmMetricGroup returned by this fn. - """ - num_image_pairs = len(two_view_reports_dict.keys()) - - # all rotational errors in degrees - rot3_angular_errors_list: List[float] = [] - trans_angular_errors_list: List[float] = [] - - inlier_ratio_gt_model_all_pairs = [] - inlier_ratio_est_model_all_pairs = [] - num_inliers_gt_model_all_pairs = [] - num_inliers_est_model_all_pairs = [] - # populate the distributions - for report in two_view_reports_dict.values(): - if report is None: - continue - if report.R_error_deg is not None: - rot3_angular_errors_list.append(report.R_error_deg) - if report.U_error_deg is not None: - trans_angular_errors_list.append(report.U_error_deg) - - inlier_ratio_gt_model_all_pairs.append(report.inlier_ratio_gt_model) - inlier_ratio_est_model_all_pairs.append(report.inlier_ratio_est_model) - num_inliers_gt_model_all_pairs.append(report.num_inliers_gt_model) - num_inliers_est_model_all_pairs.append(report.num_inliers_est_model) - - rot3_angular_errors = np.array(rot3_angular_errors_list, dtype=float) - trans_angular_errors = np.array(trans_angular_errors_list, dtype=float) - # count number of rot3 errors which are not None. Should be same in rot3/unit3 - num_valid_image_pairs = np.count_nonzero(~np.isnan(rot3_angular_errors)) - - # compute pose errors by picking the max error from rot3 and unit3 errors - pose_errors = np.maximum(rot3_angular_errors, trans_angular_errors) - - # check errors against the threshold - success_count_rot3 = np.sum(rot3_angular_errors < angular_err_threshold_deg) - success_count_unit3 = np.sum(trans_angular_errors < angular_err_threshold_deg) - success_count_pose = np.sum(pose_errors < angular_err_threshold_deg) - - # count image pair entries where inlier ratio w.r.t. GT model == 1. - all_correct = np.count_nonzero( - [report.inlier_ratio_gt_model == 1.0 for report in two_view_reports_dict.values() if report is not None] - ) - - logger.debug( - "[Two view optimizer] [Summary] Rotation success: %d/%d/%d", - success_count_rot3, - num_valid_image_pairs, - num_image_pairs, - ) - - logger.debug( - "[Two view optimizer] [Summary] Translation success: %d/%d/%d", - success_count_unit3, - num_valid_image_pairs, - num_image_pairs, - ) - - logger.debug( - "[Two view optimizer] [Summary] Pose success: %d/%d/%d", - success_count_pose, - num_valid_image_pairs, - num_image_pairs, - ) - - logger.debug( - "[Two view optimizer] [Summary] # Image pairs with 100%% inlier ratio:: %d/%d", all_correct, num_image_pairs - ) - - # TODO(akshay-krishnan): Move angular_err_threshold_deg and num_total_image_pairs to metadata. - frontend_metrics = GtsfmMetricsGroup( - metric_group_name, - [ - GtsfmMetric("angular_err_threshold_deg", angular_err_threshold_deg), - GtsfmMetric("num_total_image_pairs", int(num_image_pairs)), - GtsfmMetric("num_valid_image_pairs", int(num_valid_image_pairs)), - GtsfmMetric("rotation_success_count", int(success_count_rot3)), - GtsfmMetric("translation_success_count", int(success_count_unit3)), - GtsfmMetric("pose_success_count", int(success_count_pose)), - GtsfmMetric("num_all_inlier_correspondences_wrt_gt_model", int(all_correct)), - GtsfmMetric("rot3_angular_errors_deg", rot3_angular_errors), - GtsfmMetric("trans_angular_errors_deg", trans_angular_errors), - GtsfmMetric("pose_errors_deg", pose_errors), - GtsfmMetric("inlier_ratio_wrt_gt_model", inlier_ratio_gt_model_all_pairs), - GtsfmMetric("inlier_ratio_wrt_est_model", inlier_ratio_est_model_all_pairs), - GtsfmMetric("num_inliers_est_model", num_inliers_est_model_all_pairs), - GtsfmMetric("num_inliers_gt_model", num_inliers_gt_model_all_pairs), - ], - ) - return frontend_metrics diff --git a/gtsfm/utils/images.py b/gtsfm/utils/images.py index 5f42b3eaf..e051b9761 100644 --- a/gtsfm/utils/images.py +++ b/gtsfm/utils/images.py @@ -2,7 +2,7 @@ Authors: Ayush Baid """ -from typing import List, Tuple +from typing import List, Optional, Tuple import cv2 as cv import numpy as np @@ -238,7 +238,7 @@ def match_image_widths( return scaled_image_i1, scaled_image_i2, scale_factor_i1, scale_factor_i2 -def get_average_point_color(track: SfmTrack, images: List[Image]) -> Tuple[int, int, int]: +def get_average_point_color(track: SfmTrack, images: Optional[List[Image]]) -> Tuple[int, int, int]: """ Args: track: 3d point/landmark and its corresponding 2d measurements in various cameras @@ -249,6 +249,9 @@ def get_average_point_color(track: SfmTrack, images: List[Image]) -> Tuple[int, g: green color intensity, in range [0,255] b: blue color intensity, in range [0,255] """ + if images is None: + return 0, 0, 0 + rgb_measurements = [] for k in range(track.numberMeasurements()): diff --git a/gtsfm/utils/io.py b/gtsfm/utils/io.py index 742247d3a..36c5343d3 100644 --- a/gtsfm/utils/io.py +++ b/gtsfm/utils/io.py @@ -152,7 +152,13 @@ def read_bundler(file_path: str) -> GtsfmData: return GtsfmData.from_sfm_data(sfm_data) -def export_model_as_colmap_text(gtsfm_data: GtsfmData, images: List[Image], save_dir: str) -> None: +def export_model_as_colmap_text( + gtsfm_data: GtsfmData, + image_shapes: List[Tuple[int, int]], + image_fnames: List[str], + images: Optional[List[Image]], + save_dir: str, +) -> None: """Emulates the COLMAP option to `Export model as text`. Three text files will be save to disk: "points3D.txt", "images.txt", and "cameras.txt". @@ -162,8 +168,8 @@ def export_model_as_colmap_text(gtsfm_data: GtsfmData, images: List[Image], save images: list of all images for this scene, in order of image index. save_dir: folder where text files will be saved. """ - write_cameras(gtsfm_data, images, save_dir) - write_images(gtsfm_data, images, save_dir) + write_cameras(gtsfm_data, image_shapes, save_dir) + write_images(gtsfm_data, image_fnames, save_dir) write_points(gtsfm_data, images, save_dir) @@ -264,7 +270,7 @@ def read_cameras_txt(fpath: str) -> Optional[List[Cal3Bundler]]: return calibrations -def write_cameras(gtsfm_data: GtsfmData, images: List[Image], save_dir: str) -> None: +def write_cameras(gtsfm_data: GtsfmData, image_shapes: List[Tuple[int, int]], save_dir: str) -> None: """Writes the camera data file in the COLMAP format. Reference: https://colmap.github.io/format.html#cameras-txt @@ -280,28 +286,31 @@ def write_cameras(gtsfm_data: GtsfmData, images: List[Image], save_dir: str) -> # Assumes all camera models have five intrinsic parameters camera_model = "RADIAL" - file_path = os.path.join(save_dir, "cameras.txt") - with open(file_path, "w") as f: - f.write("# Camera list with one line of data per camera:\n") - f.write("# CAMERA_ID, MODEL, WIDTH, HEIGHT, PARAMS[]\n") - # note that we save the number of estimated cameras, not the number of input images, - # which would instead be gtsfm_data.number_images(). - f.write(f"# Number of cameras: {len(gtsfm_data.get_valid_camera_indices())}\n") + output_str = "" - for i in gtsfm_data.get_valid_camera_indices(): - camera = gtsfm_data.get_camera(i) - calibration = camera.calibration() + output_str += "# Camera list with one line of data per camera:\n" + output_str += "# CAMERA_ID, MODEL, WIDTH, HEIGHT, PARAMS[]\n" + # note that we save the number of estimated cameras, not the number of input images, + # which would instead be gtsfm_data.number_images(). + output_str += f"# Number of cameras: {len(gtsfm_data.get_valid_camera_indices())}\n" - fx = calibration.fx() - u0 = calibration.px() - v0 = calibration.py() - k1 = calibration.k1() - k2 = calibration.k2() + for i in gtsfm_data.get_valid_camera_indices(): + camera = gtsfm_data.get_camera(i) + calibration = camera.calibration() - image_height = images[i].height - image_width = images[i].width + fx = calibration.fx() + u0 = calibration.px() + v0 = calibration.py() + k1 = calibration.k1() + k2 = calibration.k2() - f.write(f"{i} {camera_model} {image_width} {image_height} {fx} {u0} {v0} {k1} {k2}\n") + image_height, image_width = image_shapes[i] + + output_str += f"{i} {camera_model} {image_width} {image_height} {fx} {u0} {v0} {k1} {k2}\n" + + file_path = os.path.join(save_dir, "cameras.txt") + with open(file_path, "w") as f: + f.write(output_str) def read_images_txt(fpath: str) -> Tuple[Optional[List[Pose3]], Optional[List[str]]]: @@ -343,7 +352,7 @@ def read_images_txt(fpath: str) -> Tuple[Optional[List[Pose3]], Optional[List[st return wTi_list, img_fnames -def write_images(gtsfm_data: GtsfmData, images: List[Image], save_dir: str) -> None: +def write_images(gtsfm_data: GtsfmData, images_fnames: List[str], save_dir: str) -> None: """Writes the image data file in the COLMAP format. Reference: https://colmap.github.io/format.html#images-txt @@ -372,34 +381,37 @@ def write_images(gtsfm_data: GtsfmData, images: List[Image], save_dir: str) -> N else 0 ) + output_str = "" + + output_str += "# Image list with two lines of data per image:\n" + output_str += "# IMAGE_ID, QW, QX, QY, QZ, TX, TY, TZ, CAMERA_ID, NAME\n" + output_str += "# POINTS2D[] as (X, Y, POINT3D_ID)\n" + output_str += f"# Number of images: {num_imgs}, mean observations per image: {mean_obs_per_img:.3f}\n" + + for i in gtsfm_data.get_valid_camera_indices(): + camera = gtsfm_data.get_camera(i) + # COLMAP exports camera extrinsics (cTw), not the poses (wTc), so must invert + iTw = camera.pose().inverse() + iRw_quaternion = iTw.rotation().quaternion() + itw = iTw.translation() + tx, ty, tz = itw + qw, qx, qy, qz = iRw_quaternion + + output_str += f"{i} {qw} {qx} {qy} {qz} {tx} {ty} {tz} {i} {images_fnames[i]}\n" + + # write out points2d + for j in range(gtsfm_data.number_tracks()): + track = gtsfm_data.get_track(j) + for k in range(track.numberMeasurements()): + # write each measurement + image_id, uv_measured = track.measurement(k) + if image_id == i: + output_str += f" {uv_measured[0]:.3f} {uv_measured[1]:.3f} {j}" + output_str += "\n" + file_path = os.path.join(save_dir, "images.txt") with open(file_path, "w") as f: - f.write("# Image list with two lines of data per image:\n") - f.write("# IMAGE_ID, QW, QX, QY, QZ, TX, TY, TZ, CAMERA_ID, NAME\n") - f.write("# POINTS2D[] as (X, Y, POINT3D_ID)\n") - f.write(f"# Number of images: {num_imgs}, mean observations per image: {mean_obs_per_img:.3f}\n") - - for i in gtsfm_data.get_valid_camera_indices(): - img_fname = images[i].file_name - camera = gtsfm_data.get_camera(i) - # COLMAP exports camera extrinsics (cTw), not the poses (wTc), so must invert - iTw = camera.pose().inverse() - iRw_quaternion = iTw.rotation().toQuaternion() - itw = iTw.translation() - tx, ty, tz = itw - qw, qx, qy, qz = iRw_quaternion.w(), iRw_quaternion.x(), iRw_quaternion.y(), iRw_quaternion.z() - - f.write(f"{i} {qw} {qx} {qy} {qz} {tx} {ty} {tz} {i} {img_fname}\n") - - # write out points2d - for j in range(gtsfm_data.number_tracks()): - track = gtsfm_data.get_track(j) - for k in range(track.numberMeasurements()): - # write each measurement - image_id, uv_measured = track.measurement(k) - if image_id == i: - f.write(f" {uv_measured[0]:.3f} {uv_measured[1]:.3f} {j}") - f.write("\n") + f.write(output_str) def read_points_txt(fpath: str) -> Tuple[Optional[np.ndarray], Optional[np.ndarray]]: @@ -460,7 +472,7 @@ def read_scene( return wTi_list, img_fnames, calibrations, point_cloud, rgb -def write_points(gtsfm_data: GtsfmData, images: List[Image], save_dir: str) -> None: +def write_points(gtsfm_data: GtsfmData, images: Optional[List[Image]], save_dir: str) -> None: """Writes the point cloud data file in the COLMAP format. Reference: https://colmap.github.io/format.html#points3d-txt @@ -475,27 +487,31 @@ def write_points(gtsfm_data: GtsfmData, images: List[Image], save_dir: str) -> N num_pts = gtsfm_data.number_tracks() avg_track_length, _ = gtsfm_data.get_track_length_statistics() - file_path = os.path.join(save_dir, "points3D.txt") - with open(file_path, "w") as f: - f.write("# 3D point list with one line of data per point:\n") - f.write("# POINT3D_ID, X, Y, Z, R, G, B, ERROR, TRACK[] as (IMAGE_ID, POINT2D_IDX)\n") - f.write(f"# Number of points: {num_pts}, mean track length: {np.round(avg_track_length, 2)}\n") + output_str = "" - # TODO: assign unique indices to all keypoints (2d points) - point2d_idx = 0 + output_str += "# 3D point list with one line of data per point:\n" + output_str += "# POINT3D_ID, X, Y, Z, R, G, B, ERROR, TRACK[] as (IMAGE_ID, POINT2D_IDX)\n" + output_str += f"# Number of points: {num_pts}, mean track length: {np.round(avg_track_length, 2)}\n" - for j in range(num_pts): - track = gtsfm_data.get_track(j) + # TODO: assign unique indices to all keypoints (2d points) + point2d_idx = 0 + + for j in range(num_pts): + track = gtsfm_data.get_track(j) - r, g, b = image_utils.get_average_point_color(track, images) - _, avg_track_reproj_error = reproj_utils.compute_track_reprojection_errors(gtsfm_data._cameras, track) - x, y, z = track.point3() - f.write(f"{j} {x} {y} {z} {r} {g} {b} {np.round(avg_track_reproj_error, 2)} ") + r, g, b = image_utils.get_average_point_color(track, images) + _, avg_track_reproj_error = reproj_utils.compute_track_reprojection_errors(gtsfm_data._cameras, track) + x, y, z = track.point3() + output_str += f"{j} {x} {y} {z} {r} {g} {b} {np.round(avg_track_reproj_error, 2)} " - for k in range(track.numberMeasurements()): - i, uv_measured = track.measurement(k) - f.write(f"{i} {point2d_idx} ") - f.write("\n") + for k in range(track.numberMeasurements()): + i, uv_measured = track.measurement(k) + output_str += f"{i} {point2d_idx} " + output_str += "\n" + + file_path = os.path.join(save_dir, "points3D.txt") + with open(file_path, "w") as f: + f.write(output_str) def save_track_visualizations( diff --git a/gtsfm/utils/logger.py b/gtsfm/utils/logger.py index a488b1cbb..46d7ec6d2 100644 --- a/gtsfm/utils/logger.py +++ b/gtsfm/utils/logger.py @@ -12,6 +12,7 @@ def get_logger() -> Logger: logger_name = "main-logger" logger = logging.getLogger(logger_name) logger.setLevel(logging.DEBUG) + logger.propagate = False if not logger.handlers: handler = logging.StreamHandler(sys.stdout) fmt = "[%(asctime)s %(levelname)s %(filename)s line %(lineno)d %(process)d] %(message)s" diff --git a/gtsfm/utils/metrics.py b/gtsfm/utils/metrics.py index f36a78d40..4cf7ca9c2 100644 --- a/gtsfm/utils/metrics.py +++ b/gtsfm/utils/metrics.py @@ -18,6 +18,7 @@ from gtsfm.common.gtsfm_data import GtsfmData from gtsfm.common.keypoints import Keypoints from gtsfm.evaluation.metrics import GtsfmMetric, GtsfmMetricsGroup +from gtsfm.common.two_view_estimation_report import TwoViewEstimationReport REPO_ROOT = Path(__file__).resolve().parent.parent.parent @@ -270,7 +271,7 @@ def compute_translation_angle_metric( for (i1, i2) in i2Ui1_dict: i2Ui1 = i2Ui1_dict[(i1, i2)] angles.append(comp_utils.compute_translation_to_direction_angle(i2Ui1, wTi_list[i2], wTi_list[i1])) - return GtsfmMetric("translation_angle_error_deg", np.array(angles, dtype=np.float)) + return GtsfmMetric("translation_angle_error_deg", np.array(angles, dtype=np.float32)) def compute_ba_pose_metrics( @@ -289,7 +290,10 @@ def compute_ba_pose_metrics( A group of metrics that describe errors associated with a bundle adjustment result (w.r.t. GT). """ wTi_aligned_list = ba_output.get_camera_poses() - i2Ui1_dict_gt = get_twoview_translation_directions(gt_wTi_list) + indices_with_valid_poses = [i for i, wTi in enumerate(wTi_aligned_list) if wTi is not None] + possible_img_pair_idxs = list(itertools.combinations(indices_with_valid_poses, 2)) + + i2Ui1_dict_gt = get_twoview_translation_directions(gt_wTi_list, possible_img_pair_idxs) wRi_aligned_list, wti_aligned_list = get_rotations_translations_from_poses(wTi_aligned_list) gt_wRi_list, gt_wti_list = get_rotations_translations_from_poses(gt_wTi_list) @@ -301,21 +305,20 @@ def compute_ba_pose_metrics( return GtsfmMetricsGroup(name="ba_pose_error_metrics", metrics=metrics) -def get_twoview_translation_directions(wTi_list: List[Optional[Pose3]]) -> Dict[Tuple[int, int], Optional[Unit3]]: - """Generate synthetic measurements of the 2-view translation directions between image pairs. +def get_twoview_translation_directions( + wTi_list: List[Optional[Pose3]], edges: List[Tuple[int, int]] +) -> Dict[Tuple[int, int], Optional[Unit3]]: + """Generate synthetic measurements of the 2-view translation directions for the edges. Args: wTi_list: List of poses (e.g. could be ground truth). + edges: edges to get the directions for. Returns: i2Ui1_dict: Dict from (i1, i2) to unit translation direction i2Ui1. """ - number_images = len(wTi_list) # vs. using ba_output.number_images() - - # check against all possible image pairs -- compute unit translation directions i2Ui1_dict = {} - possible_img_pair_idxs = list(itertools.combinations(range(number_images), 2)) - for (i1, i2) in possible_img_pair_idxs: + for (i1, i2) in edges: # compute the exact relative pose if wTi_list[i1] is None or wTi_list[i2] is None: i2Ui1 = None @@ -404,3 +407,111 @@ def compute_percentage_change(x: float, y: float) -> float: percentage change (may be positive or negative). """ return (y - x) / (x + EPSILON) * 100 + + +def aggregate_frontend_metrics( + two_view_reports_dict: Dict[Tuple[int, int], Optional[TwoViewEstimationReport]], + angular_err_threshold_deg: float, + metric_group_name: str, +) -> None: + """Aggregate the front-end metrics to log summary statistics. + + We define "pose error" as the maximum of the angular errors in rotation and translation, per: + SuperGlue, CVPR 2020: https://arxiv.org/pdf/1911.11763.pdf + Learning to find good correspondences. CVPR 2018: + OA-Net, ICCV 2019: + NG-RANSAC, ICCV 2019: + + Args: + two_view_report_dict: report containing front-end metrics for each image pair. + angular_err_threshold_deg: threshold for classifying angular error metrics as success. + metric_group_name: name we will assign to the GtsfmMetricGroup returned by this fn. + """ + num_image_pairs = len(two_view_reports_dict.keys()) + + # all rotational errors in degrees + rot3_angular_errors_list: List[float] = [] + trans_angular_errors_list: List[float] = [] + + inlier_ratio_gt_model_all_pairs = [] + inlier_ratio_est_model_all_pairs = [] + num_inliers_gt_model_all_pairs = [] + num_inliers_est_model_all_pairs = [] + # populate the distributions + for report in two_view_reports_dict.values(): + if report is None: + continue + if report.R_error_deg is not None: + rot3_angular_errors_list.append(report.R_error_deg) + if report.U_error_deg is not None: + trans_angular_errors_list.append(report.U_error_deg) + + inlier_ratio_gt_model_all_pairs.append(report.inlier_ratio_gt_model) + inlier_ratio_est_model_all_pairs.append(report.inlier_ratio_est_model) + num_inliers_gt_model_all_pairs.append(report.num_inliers_gt_model) + num_inliers_est_model_all_pairs.append(report.num_inliers_est_model) + + rot3_angular_errors = np.array(rot3_angular_errors_list, dtype=float) + trans_angular_errors = np.array(trans_angular_errors_list, dtype=float) + # count number of rot3 errors which are not None. Should be same in rot3/unit3 + num_valid_image_pairs = np.count_nonzero(~np.isnan(rot3_angular_errors)) + + # compute pose errors by picking the max error from rot3 and unit3 errors + pose_errors = np.maximum(rot3_angular_errors, trans_angular_errors) + + # check errors against the threshold + success_count_rot3 = np.sum(rot3_angular_errors < angular_err_threshold_deg) + success_count_unit3 = np.sum(trans_angular_errors < angular_err_threshold_deg) + success_count_pose = np.sum(pose_errors < angular_err_threshold_deg) + + # count image pair entries where inlier ratio w.r.t. GT model == 1. + all_correct = np.count_nonzero( + [report.inlier_ratio_gt_model == 1.0 for report in two_view_reports_dict.values() if report is not None] + ) + + logger.debug( + "[Two view optimizer] [Summary] Rotation success: %d/%d/%d", + success_count_rot3, + num_valid_image_pairs, + num_image_pairs, + ) + + logger.debug( + "[Two view optimizer] [Summary] Translation success: %d/%d/%d", + success_count_unit3, + num_valid_image_pairs, + num_image_pairs, + ) + + logger.debug( + "[Two view optimizer] [Summary] Pose success: %d/%d/%d", + success_count_pose, + num_valid_image_pairs, + num_image_pairs, + ) + + logger.debug( + "[Two view optimizer] [Summary] # Image pairs with 100%% inlier ratio:: %d/%d", all_correct, num_image_pairs + ) + + # TODO(akshay-krishnan): Move angular_err_threshold_deg and num_total_image_pairs to metadata. + frontend_metrics = GtsfmMetricsGroup( + metric_group_name, + [ + GtsfmMetric("angular_err_threshold_deg", angular_err_threshold_deg), + GtsfmMetric("num_total_image_pairs", int(num_image_pairs)), + GtsfmMetric("num_valid_image_pairs", int(num_valid_image_pairs)), + GtsfmMetric("rotation_success_count", int(success_count_rot3)), + GtsfmMetric("translation_success_count", int(success_count_unit3)), + GtsfmMetric("pose_success_count", int(success_count_pose)), + GtsfmMetric("num_all_inlier_correspondences_wrt_gt_model", int(all_correct)), + GtsfmMetric("rot3_angular_errors_deg", rot3_angular_errors), + GtsfmMetric("trans_angular_errors_deg", trans_angular_errors), + GtsfmMetric("pose_errors_deg", pose_errors), + GtsfmMetric("inlier_ratio_wrt_gt_model", inlier_ratio_gt_model_all_pairs), + GtsfmMetric("inlier_ratio_wrt_est_model", inlier_ratio_est_model_all_pairs), + GtsfmMetric("num_inliers_est_model", num_inliers_est_model_all_pairs), + GtsfmMetric("num_inliers_gt_model", num_inliers_gt_model_all_pairs), + ], + ) + return frontend_metrics diff --git a/gtsfm/utils/reprojection.py b/gtsfm/utils/reprojection.py index f3cdec27e..1f2adff0f 100644 --- a/gtsfm/utils/reprojection.py +++ b/gtsfm/utils/reprojection.py @@ -21,7 +21,7 @@ def compute_track_reprojection_errors( Returns: reprojection errors for each measurement (measured in pixels). - avg_track_reproj_error: average reprojection error of all meausurements in track. + average_reprojection_error: average reprojection error of all meausurements in track. """ errors = [] for k in range(track.numberMeasurements()): @@ -41,44 +41,34 @@ def compute_track_reprojection_errors( errors.append(np.nan) errors = np.array(errors) - avg_track_reproj_error = np.nan if np.isnan(errors).all() else np.nanmean(errors) - return errors, avg_track_reproj_error + average_reprojection_error = np.nan if np.isnan(errors).all() else np.nanmean(errors) + return errors, average_reprojection_error def compute_point_reprojection_errors( - track_camera_dict: Dict[int, PinholeCameraCal3Bundler], point3d: np.ndarray, measurements: List[SfmMeasurement] + cameras: Dict[int, PinholeCameraCal3Bundler], point3d: np.ndarray, measurements: List[SfmMeasurement] ) -> Tuple[np.ndarray, float]: """Compute reprojection errors for a hypothesized 3d point vs. 2d measurements. Args: - track_camera_dict: Dict of cameras, with camera indices as keys. + cameras: Dict of cameras, with camera indices as keys. point3d: hypothesized 3d point/landmark measurements: corresponding 2d measurements (of 3d point above) in various cameras Returns: reprojection errors for each measurement (measured in pixels). - avg_track_reproj_error: average reprojection error of all meausurements in track. + average_reprojection_error: average reprojection error of all measurements in track. """ - errors = [] - for (i, uv_measured) in measurements: - - if i not in track_camera_dict: - # camera pose was not successfully estimated, PinholeCameraCal3Bundler was uninitialized - errors.append(np.nan) - continue - - # get the camera associated with the measurement - camera = track_camera_dict[i] - # Project to camera - uv_reprojected, success_flag = camera.projectSafe(point3d) - # Projection error in camera - if success_flag: - errors.append(np.linalg.norm(uv_measured - uv_reprojected)) - else: - # failure in projection - errors.append(np.nan) - - errors = np.array(errors) - avg_track_reproj_error = np.nan if np.isnan(errors).all() else np.nanmean(errors) - return errors, avg_track_reproj_error - + nan = np.array([np.nan, np.nan]) + safe_projections = [ + cameras[i].projectSafe(point3d) if i in cameras else (nan, False) for i, uv_measured in measurements + ] + valid_projections = np.array( + [ + uv_projected - uv_measured + for (uv_projected, success), (i, uv_measured) in zip(safe_projections, measurements) + ] + ) + errors = np.linalg.norm(valid_projections, axis=1) + average_reprojection_error = np.nan if np.isnan(errors).all() else np.nanmean(errors) + return errors, average_reprojection_error diff --git a/tests/data/sample_poses.py b/gtsfm/utils/sample_poses.py similarity index 100% rename from tests/data/sample_poses.py rename to gtsfm/utils/sample_poses.py diff --git a/gtsfm/utils/viz.py b/gtsfm/utils/viz.py index 8b4c4e77e..a48bff400 100644 --- a/gtsfm/utils/viz.py +++ b/gtsfm/utils/viz.py @@ -17,7 +17,7 @@ from gtsfm.common.gtsfm_data import GtsfmData from gtsfm.common.image import Image from gtsfm.common.keypoints import Keypoints -from gtsfm.two_view_estimator import TwoViewEstimationReport +from gtsfm.common.two_view_estimation_report import TwoViewEstimationReport COLOR_RED = (255, 0, 0) COLOR_GREEN = (0, 255, 0) diff --git a/gtsfm/view_graph_estimator/cycle_consistent_rotation_estimator.py b/gtsfm/view_graph_estimator/cycle_consistent_rotation_estimator.py index 19f206f83..c9e65bd20 100644 --- a/gtsfm/view_graph_estimator/cycle_consistent_rotation_estimator.py +++ b/gtsfm/view_graph_estimator/cycle_consistent_rotation_estimator.py @@ -15,7 +15,7 @@ import gtsfm.utils.graph as graph_utils import gtsfm.utils.logger as logger_utils from gtsfm.common.keypoints import Keypoints -from gtsfm.two_view_estimator import TwoViewEstimationReport +from gtsfm.common.two_view_estimation_report import TwoViewEstimationReport from gtsfm.view_graph_estimator.view_graph_estimator_base import ViewGraphEstimatorBase logger = logger_utils.get_logger() diff --git a/gtsfm/visualization/view_scene.py b/gtsfm/visualization/view_scene.py index 899adeedb..9654b3cd1 100644 --- a/gtsfm/visualization/view_scene.py +++ b/gtsfm/visualization/view_scene.py @@ -54,10 +54,13 @@ def view_scene(args: argparse.Namespace) -> None: if args.show_mvs_result: point_cloud, rgb = io_utils.read_point_cloud_from_ply(args.ply_fpath) - if len(calibrations) == 1: calibrations = calibrations * len(img_fnames) - mean_pt = compute_point_cloud_center_robust(point_cloud) + + if args.center_trajectory: + mean_pt = compute_point_cloud_center_robust(np.array([T.translation() for T in wTi_list])) + else: + mean_pt = compute_point_cloud_center_robust(point_cloud) # Zero-center the point cloud (about estimated center). zcwTw = Pose3(Rot3(np.eye(3)), -mean_pt) @@ -111,7 +114,12 @@ def view_scene(args: argparse.Namespace) -> None: parser.add_argument( "--show_mvs_result", action="store_true", - help="defaults to false.", + help="Show MVS result, defaults to false.", + ) + parser.add_argument( + "--center_trajectory", + action="store_true", + help="Center point cloud on trajectory, defaults to false.", ) parser.add_argument( "--ply_fpath", diff --git a/notebooks/explore_hilti.ipynb b/notebooks/explore_hilti.ipynb index bda99b990..ffe5d1830 100644 --- a/notebooks/explore_hilti.ipynb +++ b/notebooks/explore_hilti.ipynb @@ -13,7 +13,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 1, "metadata": {}, "outputs": [], "source": [ @@ -49,9 +49,17 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 2, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "/Users/dellaert/git/gtsfm/tests/data/hilti_exp4_medium\n" + ] + } + ], "source": [ "cwd = Path.cwd()\n", "folder_path = Path(cwd.parent / \"tests\" / \"data\" / \"hilti_exp4_medium\")\n", @@ -60,18 +68,40 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 3, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "ls: /Users/dellaert/git/gtsfm/tests/data/hilti_exp4_medium: No such file or directory\n" + ] + } + ], "source": [ "%ls /Users/dellaert/git/gtsfm/tests/data/hilti_exp4_medium" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 4, "metadata": {}, - "outputs": [], + "outputs": [ + { + "ename": "FileNotFoundError", + "evalue": "[Errno 2] No such file or directory: '/Users/dellaert/git/gtsfm/tests/data/hilti_exp4_medium/calibration/calib_3_cam0-1-camchain-imucam.yaml'", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mFileNotFoundError\u001b[0m Traceback (most recent call last)", + "\u001b[1;32m/Users/dellaert/git/gtsfm/notebooks/explore_hilti.ipynb Cell 5'\u001b[0m in \u001b[0;36m\u001b[0;34m()\u001b[0m\n\u001b[1;32m 1\u001b[0m \u001b[39m# Load Images\u001b[39;00m\n\u001b[1;32m 2\u001b[0m indices \u001b[39m=\u001b[39m \u001b[39mrange\u001b[39m(\u001b[39m300\u001b[39m, \u001b[39m300\u001b[39m\u001b[39m+\u001b[39m\u001b[39m20\u001b[39m)\n\u001b[0;32m----> 3\u001b[0m loader \u001b[39m=\u001b[39m HiltiLoader(base_folder\u001b[39m=\u001b[39;49m\u001b[39mstr\u001b[39;49m(folder_path))\n\u001b[1;32m 4\u001b[0m images \u001b[39m=\u001b[39m [loader\u001b[39m.\u001b[39mget_image(i) \u001b[39mfor\u001b[39;00m i \u001b[39min\u001b[39;00m indices]\n", + "File \u001b[0;32m~/git/gtsfm/gtsfm/loader/hilti_loader.py:81\u001b[0m, in \u001b[0;36mHiltiLoader.__init__\u001b[0;34m(self, base_folder, max_length, max_resolution, subsample, old_style)\u001b[0m\n\u001b[1;32m 79\u001b[0m \u001b[39mself\u001b[39m\u001b[39m.\u001b[39m_cam_T_imu_poses: Dict[\u001b[39mint\u001b[39m, Pose3] \u001b[39m=\u001b[39m {}\n\u001b[1;32m 80\u001b[0m \u001b[39mfor\u001b[39;00m cam_idx \u001b[39min\u001b[39;00m \u001b[39mrange\u001b[39m(NUM_CAMS):\n\u001b[0;32m---> 81\u001b[0m calibration \u001b[39m=\u001b[39m \u001b[39mself\u001b[39;49m\u001b[39m.\u001b[39;49m__load_calibration(cam_idx)\n\u001b[1;32m 82\u001b[0m \u001b[39mself\u001b[39m\u001b[39m.\u001b[39m_intrinsics[cam_idx] \u001b[39m=\u001b[39m calibration[\u001b[39m0\u001b[39m]\n\u001b[1;32m 83\u001b[0m \u001b[39mself\u001b[39m\u001b[39m.\u001b[39m_cam_T_imu_poses[cam_idx] \u001b[39m=\u001b[39m calibration[\u001b[39m1\u001b[39m]\n", + "File \u001b[0;32m~/git/gtsfm/gtsfm/loader/hilti_loader.py:217\u001b[0m, in \u001b[0;36mHiltiLoader.__load_calibration\u001b[0;34m(self, cam_idx)\u001b[0m\n\u001b[1;32m 214\u001b[0m \u001b[39m\"\"\"Load calibration from kalibr files in calibration sub-folder.\"\"\"\u001b[39;00m\n\u001b[1;32m 215\u001b[0m kalibr_file_path \u001b[39m=\u001b[39m \u001b[39mself\u001b[39m\u001b[39m.\u001b[39m_base_folder \u001b[39m/\u001b[39m \u001b[39m\"\u001b[39m\u001b[39mcalibration\u001b[39m\u001b[39m\"\u001b[39m \u001b[39m/\u001b[39m CAM_IDX_TO_KALIBR_FILE_MAP[cam_idx]\n\u001b[0;32m--> 217\u001b[0m \u001b[39mwith\u001b[39;00m \u001b[39mopen\u001b[39;49m(kalibr_file_path, \u001b[39m\"\u001b[39;49m\u001b[39mr\u001b[39;49m\u001b[39m\"\u001b[39;49m) \u001b[39mas\u001b[39;00m file:\n\u001b[1;32m 218\u001b[0m calibration_data \u001b[39m=\u001b[39m yaml\u001b[39m.\u001b[39msafe_load(file)\n\u001b[1;32m 219\u001b[0m \u001b[39mif\u001b[39;00m cam_idx \u001b[39m!=\u001b[39m \u001b[39m1\u001b[39m:\n", + "\u001b[0;31mFileNotFoundError\u001b[0m: [Errno 2] No such file or directory: '/Users/dellaert/git/gtsfm/tests/data/hilti_exp4_medium/calibration/calib_3_cam0-1-camchain-imucam.yaml'" + ] + } + ], "source": [ "# Load Images\n", "indices = range(300, 300+20)\n", @@ -192,12 +222,10 @@ "outputs": [], "source": [ "i2Ri1_graph, i2Ui1_graph = scene_optimizer.create_computation_graph_for_frontend(\n", + " self.loader,\n", + " image_graph=loader.create_computation_graph_for_images()\n", " image_pair_indices=subset_pair_indices, \n", - " image_graph=loader.create_computation_graph_for_images(),\n", - " all_intrinsics=loader.create_computation_graph_for_intrinsics(),\n", - " image_shapes = loader.create_computation_graph_for_image_shapes(),\n", - " relative_pose_priors = loader.get_relative_pose_priors(subset_pair_indices),\n", - " gt_poses_graph = loader.create_computation_graph_for_poses())" + " )" ] }, { @@ -465,7 +493,7 @@ ], "metadata": { "interpreter": { - "hash": "4fd427e5d3afc8e77fd80f60207859a2afe2c687da56f6de3914baf61d886f83" + "hash": "4d608302ba82e7596903db5446e6fa05f049271852e8cc6e1cafaafe5fbd9fed" }, "kernelspec": { "display_name": "Python 3.8.13 ('gtsfm-v1')", diff --git a/tests/averaging/rotation/test_shonan.py b/tests/averaging/rotation/test_shonan.py index 47b4ff169..efcc5a486 100644 --- a/tests/averaging/rotation/test_shonan.py +++ b/tests/averaging/rotation/test_shonan.py @@ -11,7 +11,7 @@ from gtsam import Rot3, Pose3 import gtsfm.utils.geometry_comparisons as geometry_comparisons -import tests.data.sample_poses as sample_poses +import gtsfm.utils.sample_poses as sample_poses from gtsfm.averaging.rotation.rotation_averaging_base import RotationAveragingBase from gtsfm.averaging.rotation.shonan import ShonanRotationAveraging @@ -36,8 +36,8 @@ def __execute_test(self, i2Ri1_input: Dict[Tuple[int, int], Rot3], wRi_expected: i2Ri1_input: relative rotations, which are input to the algorithm. wRi_expected: expected global rotations. """ - i2Ri1_priors = {edge: None for edge in i2Ri1_input.keys()} - wRi_computed = self.obj.run(len(wRi_expected), i2Ri1_input, i2Ri1_priors) + i2Ri1_priors = {} + wRi_computed = self.obj.run_rotation_averaging(len(wRi_expected), i2Ri1_input, i2Ri1_priors) self.assertTrue( geometry_comparisons.compare_rotations(wRi_computed, wRi_expected, ROTATION_ANGLE_ERROR_THRESHOLD_DEG) ) @@ -99,13 +99,13 @@ def test_computation_graph(self): i2Ri1_graph = dask.delayed(i2Ri1_dict) # use the GTSAM API directly (without dask) for rotation averaging - i2Ri1_priors = {edge: None for edge in i2Ri1_dict.keys()} - expected_wRi_list = self.obj.run(num_poses, i2Ri1_dict, i2Ri1_priors) + relative_pose_priors = {} + expected_wRi_list = self.obj.run_rotation_averaging(num_poses, i2Ri1_dict, relative_pose_priors) # use dask's computation graph gt_wTi_list = [None] * len(expected_wRi_list) rotations_graph, _ = self.obj.create_computation_graph( - num_poses, i2Ri1_graph, dask.delayed(i2Ri1_priors), gt_wTi_list + num_poses, i2Ri1_graph, relative_pose_priors, gt_wTi_list ) with dask.config.set(scheduler="single-threaded"): @@ -146,8 +146,8 @@ def test_nonconsecutive_indices(self): (1, 3): wTi3.between(wTi1).rotation(), } - i2Ri1_priors = {edge: None for edge in i2Ri1_input.keys()} - wRi_computed = self.obj.run(num_images, i2Ri1_input, i2Ri1_priors) + i2Ri1_priors = {} + wRi_computed = self.obj.run_rotation_averaging(num_images, i2Ri1_input, i2Ri1_priors) wRi_expected = [None, wTi1.rotation(), wTi2.rotation(), wTi3.rotation()] self.assertTrue( geometry_comparisons.compare_rotations(wRi_computed, wRi_expected, angular_error_threshold_degrees=0.1) diff --git a/tests/averaging/translation/test_averaging_1dsfm.py b/tests/averaging/translation/test_averaging_1dsfm.py index ddc3a2169..1c03fb2f2 100644 --- a/tests/averaging/translation/test_averaging_1dsfm.py +++ b/tests/averaging/translation/test_averaging_1dsfm.py @@ -8,13 +8,15 @@ from typing import Dict, List, Tuple import dask +import gtsam import numpy as np from gtsam import Cal3_S2, Point3, Pose3, Rot3, Unit3 from gtsam.examples import SFMdata +from gtsfm.common.pose_prior import PosePrior, PosePriorType import gtsfm.utils.geometry_comparisons as geometry_comparisons -import tests.data.sample_poses as sample_poses +import gtsfm.utils.sample_poses as sample_poses from gtsfm.averaging.translation.averaging_1dsfm import TranslationAveraging1DSFM from gtsfm.averaging.translation.translation_averaging_base import TranslationAveragingBase from gtsfm.loader.olsson_loader import OlssonLoader @@ -32,16 +34,68 @@ class TestTranslationAveraging1DSFM(unittest.TestCase): def setUp(self): super().setUp() - self.obj: TranslationAveragingBase = TranslationAveraging1DSFM() + self.obj: TranslationAveraging1DSFM = TranslationAveraging1DSFM() + + def test_augmentation(self): + """Tests that measurements for betweenTranslations are augmented to input measurements.""" + input_measurements = gtsam.BinaryMeasurementsUnit3() + INPUT_NOISE_MODEL = gtsam.noiseModel.Isotropic.Sigma(2, 1e-2) + input_measurements.append(gtsam.BinaryMeasurementUnit3(0, 1, Unit3(Point3(1, 0, 0)), INPUT_NOISE_MODEL)) + input_measurements.append(gtsam.BinaryMeasurementUnit3(0, 2, Unit3(Point3(0, 1, 0)), INPUT_NOISE_MODEL)) + input_measurements.append(gtsam.BinaryMeasurementUnit3(1, 2, Unit3(Point3(0, 0, 1)), INPUT_NOISE_MODEL)) + + priors = gtsam.BinaryMeasurementsPoint3() + PRIOR_NOISE_MODEL = gtsam.noiseModel.Isotropic.Sigma(3, 1e-2) + priors.append(gtsam.BinaryMeasurementPoint3(0, 2, Point3(1, 1, 0), PRIOR_NOISE_MODEL)) + priors.append(gtsam.BinaryMeasurementPoint3(2, 3, Point3(1, 0, 1), PRIOR_NOISE_MODEL)) + + augmented_measurements = self.obj.augment_measurement_with_priors(input_measurements, priors, INPUT_NOISE_MODEL) + self.assertEqual(len(augmented_measurements), 4) + augmented_measurements_dict = {} + for idx in range(len(augmented_measurements)): + measurement = augmented_measurements[idx] + augmented_measurements_dict[(measurement.key1(), measurement.key2())] = measurement.measured() + self.assertSetEqual(set(augmented_measurements_dict.keys()), set([(0, 1), (0, 2), (1, 2), (2, 3)])) + np.testing.assert_array_equal(augmented_measurements_dict[2, 3].point3(), Unit3(Point3(1, 0, 1)).point3()) + + def test_convert_prior_to_world_frame(self): + """Test the helper method for transforming betweenTranslations to world frame.""" + # Rotate i1 by 90 degrees in Z, and translate by (1, 1, 1) + wRi1 = Rot3.Rz(np.deg2rad(90)) + i1Ti2 = Pose3(Rot3(), Point3(2, 0, 1)) # Identity rotation, X axis. + + prior_covariance = np.zeros((6, 6)) + for i in range(6): + prior_covariance[i, i] = 1.0 if i != 3 else 2.0 + i1Ti2_prior = PosePrior(value=i1Ti2, covariance=prior_covariance, type=PosePriorType.SOFT_CONSTRAINT) + + wRi_list = [Rot3(), wRi1, Rot3()] # identity for 0 and 2, wRi1 for 1 + w_i1ti2_priors = self.obj._get_prior_measurements_in_world_frame({(1, 2): i1Ti2_prior}, wRi_list) + # Check length + self.assertEqual(len(w_i1ti2_priors), 1) + + # Check keys + actual_i1 = w_i1ti2_priors[0].key1() + actual_i2 = w_i1ti2_priors[0].key2() + self.assertEqual(actual_i1, 1) + self.assertEqual(actual_i2, 2) + + # Check value + actual_w_i1ti2 = w_i1ti2_priors[0].measured() + np.testing.assert_array_almost_equal(actual_w_i1ti2, Point3(0, 2, 1)) + + # Check covariance + actual_covariance = w_i1ti2_priors[0].noiseModel().covariance() + expected_covariance = np.eye(3) + expected_covariance[1, 1] = 2.0 + np.testing.assert_array_almost_equal(actual_covariance, expected_covariance) def __execute_test( self, i2Ui1_input: Dict[Tuple[int, int], Unit3], wRi_input: List[Rot3], wti_expected: List[Point3] ) -> None: """Helper function to run the averagaing and assert w/ expected.""" - wti_computed, _ = self.obj.run(len(wRi_input), i2Ui1_input, wRi_input) - - wTi_computed = [Pose3(wRi, wti) for wRi, wti in zip(wRi_input, wti_computed)] + wTi_computed, _ = self.obj.run_translation_averaging(len(wRi_input), i2Ui1_input, wRi_input) wTi_expected = [Pose3(wRi, wti) for wRi, wti in zip(wRi_input, wti_expected)] self.assertTrue( geometry_comparisons.compare_global_poses( @@ -130,16 +184,14 @@ def test_computation_graph(self): i2Ui1_dict[(i1, i2)] = Unit3(expected_wTi_list[i2].between(expected_wTi_list[i1]).translation()) # use the `run` API to get expected results, ignore the metrics - wti_expected, _ = self.obj.run(len(wRi_list), i2Ui1_dict, wRi_list) + wTi_expected, _ = self.obj.run_translation_averaging(len(wRi_list), i2Ui1_dict, wRi_list) # form computation graph and execute i2Ui1_graph = dask.delayed(i2Ui1_dict) wRi_graph = dask.delayed(wRi_list) computation_graph = self.obj.create_computation_graph(len(wRi_list), i2Ui1_graph, wRi_graph) with dask.config.set(scheduler="single-threaded"): - wti_computed, _ = dask.compute(computation_graph)[0] - wTi_computed = [Pose3(wRi, wti) for wRi, wti in zip(wRi_list, wti_computed)] - wTi_expected = [Pose3(wRi, wti) for wRi, wti in zip(wRi_list, wti_expected)] + wTi_computed, _ = dask.compute(computation_graph)[0] self.assertTrue( geometry_comparisons.compare_global_poses( wTi_computed, wTi_expected, RELATIVE_ERROR_THRESHOLD, ABSOLUTE_ERROR_THRESHOLD @@ -163,10 +215,10 @@ def setUp(self): def test_outlier_case_missing_value(self) -> None: """Ensure that a missing `Value` in the 1dsfm result is represented by `None` in the returned entries. - + The scenario below will lead to an outlier configuration -- all edges to the node 4 will be rejected as outliers, so that Value cannot be cast to Point3 -- it is returned as None. - + This test ensures that 1dsfm checks if each Value exists in 1dsfm result, before casting it to a Point3. """ # fmt: off @@ -218,7 +270,7 @@ def test_outlier_case_missing_value(self) -> None: (3, 4): np.array([0.994791, -0.033332, -0.0963361]), } i2Ui1_input = {(i, j): Unit3(t) for (i, j), t in i2Ui1_input.items()} - wti_computed, _ = self.obj.run(len(wRi_input), i2Ui1_input, wRi_input) + wti_computed, _ = self.obj.run_translation_averaging(len(wRi_input), i2Ui1_input, wRi_input) assert len(wti_computed) == 5 assert wti_computed[-1] is None diff --git a/tests/bundle/test_bundle_adjustment.py b/tests/bundle/test_bundle_adjustment.py index 2ea5c5f63..954e45fb9 100644 --- a/tests/bundle/test_bundle_adjustment.py +++ b/tests/bundle/test_bundle_adjustment.py @@ -29,7 +29,7 @@ def setUp(self): # def test_simple_scene(self): # """Test the simple scene using the `run` API.""" - # computed_result = self.ba.run(self.test_data) + # computed_result = self.ba.run_ba(self.test_data) # expected_error = 0.046137573704557046 @@ -42,7 +42,7 @@ def test_create_computation_graph(self): absolute_pose_priors = [None] * EXAMPLE_DATA.number_images() relative_pose_priors = {} - expected_result, _, _ = self.ba.run( + expected_result, _, _ = self.ba.run_ba( self.test_data, absolute_pose_priors=absolute_pose_priors, relative_pose_priors=relative_pose_priors ) diff --git a/tests/data/exp07/constraints.txt b/tests/data/exp07/constraints.txt new file mode 100644 index 000000000..6cc7b3a1d --- /dev/null +++ b/tests/data/exp07/constraints.txt @@ -0,0 +1,10328 @@ +0 1 0.999995420469072 -9.1008916741937e-05 0.00302502202653601 0.00488959819723582 0.000102118700391941 0.999993250483187 -0.00367267747573836 -0.00630484421067648 -0.00302466736270037 0.00367296956791628 0.999988680276881 -0.00174240776079368 3.45860132282125e-05 -2.69480601450187e-06 5.8227452452634e-06 5.36480830234603e-06 -1.09859398893019e-06 -1.72909048937993e-06 -2.69480601450187e-06 9.93904708100545e-05 -5.88532978647765e-06 3.73406168885511e-05 3.33983282465296e-07 -5.31038325813757e-05 5.8227452452634e-06 -5.88532978647765e-06 1.45596732707556e-05 -1.54604956489526e-06 2.70510641319675e-06 3.92018420178657e-06 5.36480830234603e-06 3.73406168885511e-05 -1.54604956489526e-06 5.83422055733379e-05 3.93242825771243e-07 -2.5547410456878e-05 -1.09859398893019e-06 3.33983282465296e-07 2.70510641319675e-06 3.93242825771243e-07 2.37190800225054e-05 8.83854294109877e-08 -1.72909048937993e-06 -5.31038325813757e-05 3.92018420178657e-06 -2.5547410456878e-05 8.83854294109877e-08 5.98943980817282e-05 2645 2645 0 0 11 2646 2647 0 0 14 0 0 0 0 0 0 0 0 75 0 26 30 0 0 2647 +1 2 0.999999225380363 0.00117614872154898 -0.000407324022804137 0.00351805069941526 -0.00117696855048043 0.999997270475087 -0.0020183625558699 -0.00266106891449303 0.000404949016463361 0.00201884039997132 0.99999788014762 -0.0129446240341755 3.28049570193625e-05 -8.14377034237307e-06 4.82873271124046e-06 -3.51730122657364e-06 -4.88460241853084e-06 7.09406601476247e-06 -8.14377034237307e-06 2.4244369853707e-05 -4.90148443879086e-06 -8.17483325985971e-07 1.36867091460749e-06 -1.01105409640857e-05 4.82873271124046e-06 -4.90148443879086e-06 1.53398927847598e-05 -1.14950912168829e-06 4.4770345555849e-06 1.53295063358876e-06 -3.51730122657364e-06 -8.17483325985971e-07 -1.14950912168829e-06 3.71891471522147e-05 6.52471934120907e-06 -2.14446338876758e-06 -4.88460241853084e-06 1.36867091460749e-06 4.4770345555849e-06 6.52471934120907e-06 2.34721304349882e-05 -4.52039986937639e-06 7.09406601476247e-06 -1.01105409640857e-05 1.53295063358876e-06 -2.14446338876758e-06 -4.52039986937639e-06 3.50699949186123e-05 2960 2962 0 0 13 2967 2981 0 0 15 0 0 0 0 0 0 0 0 77 0 10 13 0 0 2854 +2 3 0.999981812056085 0.000609636454518821 -0.00600032502629515 -0.00462332773071896 -0.0006377764799772 0.999988803410411 -0.00468895457186314 -0.00417847227324438 0.00599739928547784 0.00469269615559436 0.999971004481931 0.00456326629700026 6.01705884434123e-05 -3.69564300508888e-06 6.04972216872948e-06 -1.31166829938963e-05 -2.83399714871081e-06 4.69861398886632e-06 -3.69564300508888e-06 4.3375662460213e-05 -8.01663135627435e-06 1.21481848013034e-05 -3.40244275368293e-06 -1.58072649581425e-05 6.04972216872948e-06 -8.01663135627435e-06 1.69639092839299e-05 -3.59648916425472e-06 3.46864858254604e-06 4.30814470293111e-06 -1.31166829938963e-05 1.21481848013034e-05 -3.59648916425472e-06 6.17821916601665e-05 2.34503054712031e-06 -6.71384338135253e-06 -2.83399714871081e-06 -3.40244275368293e-06 3.46864858254604e-06 2.34503054712031e-06 2.73922029836908e-05 -2.46641778978637e-06 4.69861398886632e-06 -1.58072649581425e-05 4.30814470293111e-06 -6.71384338135253e-06 -2.46641778978637e-06 3.82883918587664e-05 2973 2973 0 0 5 2977 2987 0 0 9 0 0 0 0 0 0 0 0 65 0 13 15 0 0 2637 +6 7 0.999994633048962 0.000530727748485909 0.00323298644104893 0.00107468997630771 -0.000520497919433557 0.999994858370543 -0.00316422413774681 -0.00166734974248834 -0.00323464915978294 0.00316252439279467 0.999989767689789 0.00298134253100529 3.46689689086848e-05 -1.20430829791518e-05 5.7707282333679e-06 -2.3893636244502e-06 -3.71061825608284e-06 5.79208930241817e-06 -1.20430829791518e-05 4.8946822338108e-05 -5.22709794553085e-06 1.22541330156438e-05 3.45208603425529e-06 -9.49755410514607e-06 5.7707282333679e-06 -5.22709794553085e-06 1.74570244905188e-05 -3.25207073109378e-06 2.0755718805064e-06 2.40870221958118e-06 -2.3893636244502e-06 1.22541330156438e-05 -3.25207073109378e-06 4.90762206800977e-05 1.19886644638873e-05 -3.18954813231568e-06 -3.71061825608284e-06 3.45208603425529e-06 2.0755718805064e-06 1.19886644638873e-05 2.85390628865175e-05 -3.16309590181362e-06 5.79208930241817e-06 -9.49755410514607e-06 2.40870221958118e-06 -3.18954813231568e-06 -3.16309590181362e-06 3.37194910233536e-05 2945 2959 0 2 8 2945 2959 0 2 8 0 0 0 0 0 0 0 0 54 0 11 14 0 0 2659 +7 8 0.999978276570393 0.000220275438943225 -0.00658770567324261 -0.00478522759706501 -0.000223975327635024 0.999999817611466 -0.00056090292106668 -0.00292997433082698 0.00658758091858349 0.000562366219868085 0.999978143522085 0.00878888357512869 4.0487044306851e-05 -6.99871596203725e-06 9.56426332164438e-06 -5.26473421519424e-06 -3.74569486975599e-06 3.36153293058932e-06 -6.99871596203725e-06 4.78947540906784e-05 -7.11002339279862e-06 8.40815574873181e-06 4.29609945293791e-07 -3.95495186388719e-06 9.56426332164438e-06 -7.11002339279862e-06 1.82892360455548e-05 -4.97399858123327e-06 3.32863333008264e-06 2.77900240077247e-06 -5.26473421519424e-06 8.40815574873181e-06 -4.97399858123327e-06 5.58277871991275e-05 6.81982798625709e-06 -3.9196607590202e-06 -3.74569486975599e-06 4.29609945293791e-07 3.32863333008264e-06 6.81982798625709e-06 2.47790869403404e-05 -8.55937877795904e-08 3.36153293058932e-06 -3.95495186388719e-06 2.77900240077247e-06 -3.9196607590202e-06 -8.55937877795904e-08 4.21828990366672e-05 2803 2804 0 0 8 2805 2816 0 0 11 0 0 0 0 0 0 0 0 66 0 27 41 0 0 2777 +12 13 0.999982014932915 -0.000214338529018555 0.00599365245095682 0.00387543190835776 0.000227816294474271 0.999997447112837 -0.00224808085832616 -0.00255313418357341 -0.00599315529949413 0.00224940587813285 0.999979510921475 -1.9041071252861e-05 4.0402223298559e-05 -1.15763936194138e-05 5.40381370191799e-06 3.00518877336955e-06 8.84751698952682e-07 -7.4353820625344e-07 -1.15763936194138e-05 5.48283932031994e-05 -4.23346339324101e-06 1.38003738281981e-05 6.3237855154115e-06 -8.0225477637731e-06 5.40381370191799e-06 -4.23346339324101e-06 1.61847719392705e-05 -3.34202623472213e-06 7.60561706632716e-08 1.21322762229838e-06 3.00518877336955e-06 1.38003738281981e-05 -3.34202623472213e-06 5.52089026288756e-05 8.69878942004257e-06 -4.59228762932458e-06 8.84751698952682e-07 6.3237855154115e-06 7.60561706632716e-08 8.69878942004257e-06 2.06301056504577e-05 -5.16251712617573e-06 -7.4353820625344e-07 -8.0225477637731e-06 1.21322762229838e-06 -4.59228762932458e-06 -5.16251712617573e-06 4.40288398287086e-05 2800 2800 0 0 12 2801 2804 0 0 14 0 0 0 0 0 0 0 0 66 0 12 23 0 0 2637 +13 14 0.999991827400137 -0.000419474114611685 -0.00402109119550392 0.000660372210041546 0.000409861043713017 0.999997057111982 -0.00239118826113261 -0.00354791676392486 0.00402208240346153 0.0023895206302735 0.999989056462268 0.00301895111351143 2.98546988425199e-05 3.44322057110326e-06 4.19912521985549e-07 5.30303637057897e-06 -6.03586568512856e-07 4.95968328651776e-06 3.44322057110326e-06 5.47193005749988e-05 -1.84752889271344e-06 1.40679575295032e-05 6.5771543498822e-07 -7.06285065665828e-06 4.19912521985549e-07 -1.84752889271344e-06 1.33603327528878e-05 -2.1893429501838e-06 8.08749576269055e-07 9.91689856890821e-07 5.30303637057897e-06 1.40679575295032e-05 -2.1893429501838e-06 4.82206816085285e-05 2.25285890091104e-06 -8.78109255028534e-07 -6.03586568512856e-07 6.5771543498822e-07 8.08749576269055e-07 2.25285890091104e-06 2.10030915092448e-05 1.88815733611261e-06 4.95968328651776e-06 -7.06285065665828e-06 9.91689856890821e-07 -8.78109255028534e-07 1.88815733611261e-06 3.44611688492387e-05 2705 2705 0 0 11 2705 2705 0 0 11 0 0 0 0 0 0 0 0 73 0 17 42 0 0 2844 +9 10 0.999985088178429 0.00115491840883348 0.0053375635124368 0.000876558594977565 -0.00115730547938118 0.999999231685317 0.000444154032105105 0.000176367079914938 -0.00533704644984035 -0.000450324600458916 0.999985656468605 -0.00613047048476899 2.07962733389332e-05 -5.87034056115684e-06 5.33884028177672e-06 4.76375997920645e-06 1.61604258530885e-06 -1.4927348576177e-07 -5.87034056115684e-06 4.36192856875439e-05 -5.29044825954937e-06 6.08622106567308e-06 -4.79343055392715e-07 -9.21863470197603e-06 5.33884028177672e-06 -5.29044825954937e-06 1.40939896114129e-05 2.28623659201727e-06 4.18132459803987e-06 3.09921558908849e-06 4.76375997920645e-06 6.08622106567308e-06 2.28623659201727e-06 4.1844831262651e-05 1.41942240271474e-06 -1.61189367483093e-06 1.61604258530885e-06 -4.79343055392715e-07 4.18132459803987e-06 1.41942240271474e-06 1.67455000707688e-05 7.4254750342678e-07 -1.4927348576177e-07 -9.21863470197603e-06 3.09921558908849e-06 -1.61189367483093e-06 7.4254750342678e-07 2.90642757550034e-05 2870 2884 0 2 10 2872 2886 0 2 14 0 0 0 0 0 0 0 0 69 0 34 38 0 0 3137 +4 5 0.99998877166461 -0.000770968186092534 0.00467569810405669 0.00217858998566164 0.000767517895387746 0.999999431902591 0.000739669369394491 0.00370644125381898 -0.00467626570935674 -0.00073607238217044 0.999988795305459 -0.00262236701291843 3.27729878139152e-05 -1.98556539130991e-06 7.20517590786348e-06 -1.44501534009002e-06 5.42144976845124e-08 2.02136261460137e-06 -1.98556539130991e-06 4.3164358365667e-05 -7.75116726801855e-06 1.1081641227889e-05 1.34130940355733e-06 -9.46255817700411e-06 7.20517590786348e-06 -7.75116726801855e-06 1.82161998462509e-05 -6.16276782645455e-06 3.40620961053992e-06 2.9877344104426e-06 -1.44501534009002e-06 1.1081641227889e-05 -6.16276782645455e-06 6.05133138603053e-05 1.09710700827365e-05 -3.14961946231058e-06 5.42144976845124e-08 1.34130940355733e-06 3.40620961053992e-06 1.09710700827365e-05 2.48903759478381e-05 -4.51551602971356e-07 2.02136261460137e-06 -9.46255817700411e-06 2.9877344104426e-06 -3.14961946231058e-06 -4.51551602971356e-07 2.9394794825788e-05 2697 2707 0 0 13 2697 2707 0 0 17 0 0 0 0 0 0 0 0 77 0 4 7 0 0 2654 +10 11 0.999988083422817 -0.000210611432960204 0.00487736149840855 0.000722503559417975 0.000214706392181017 0.999999624925785 -0.000839076548205744 0.000973576598128171 -0.00487718294992183 0.00084011374997598 0.999987753572693 -0.00559921408456532 3.45343748862575e-05 -1.52039212924352e-06 4.01325456029623e-06 6.30860302310938e-06 6.2200660260095e-07 -2.43714220833649e-06 -1.52039212924352e-06 5.53584610012598e-05 -6.08146786114477e-06 1.19888036510876e-05 5.82587624774842e-08 -1.18001168749937e-06 4.01325456029623e-06 -6.08146786114477e-06 1.74723759412728e-05 -2.50305471767009e-06 6.13336748433493e-07 5.61860673527154e-07 6.30860302310938e-06 1.19888036510876e-05 -2.50305471767009e-06 4.88569226380587e-05 6.78279808573069e-06 3.22097804397912e-08 6.2200660260095e-07 5.82587624774842e-08 6.13336748433493e-07 6.78279808573069e-06 2.49011422578724e-05 1.24640635497654e-06 -2.43714220833649e-06 -1.18001168749937e-06 5.61860673527154e-07 3.22097804397912e-08 1.24640635497654e-06 3.3152791533201e-05 2954 2958 0 0 13 2955 2973 0 0 15 0 0 0 0 0 0 0 0 86 0 9 11 0 0 2646 +8 9 0.9999978586628 1.01222686359744e-05 0.00206943648217314 -0.00070872254612951 -1.20781178590674e-05 0.999999553318374 0.000945101672870654 -0.00150883260308012 -0.00206942599122087 -0.000945124643987018 0.999997412104389 -0.00232255531819257 2.06506627432134e-05 -3.9220288696513e-07 6.653214115473e-06 -1.07406856586849e-06 1.16048151178396e-06 2.38162876096794e-06 -3.9220288696513e-07 4.03694445800218e-05 -2.70975654867379e-06 7.00637259226371e-06 3.79618010027446e-06 -7.47685542921754e-06 6.653214115473e-06 -2.70975654867379e-06 1.51562136648893e-05 -1.94802587691998e-08 2.8051300976238e-06 1.30435501314885e-06 -1.07406856586849e-06 7.00637259226371e-06 -1.94802587691998e-08 4.50240640357701e-05 6.99056211345254e-06 -6.17550623571503e-06 1.16048151178396e-06 3.79618010027446e-06 2.8051300976238e-06 6.99056211345254e-06 2.26973558025404e-05 -2.78499801403322e-06 2.38162876096794e-06 -7.47685542921754e-06 1.30435501314885e-06 -6.17550623571503e-06 -2.78499801403322e-06 3.27183416327173e-05 2922 2930 0 0 15 2926 2945 0 0 16 0 0 0 0 0 0 0 0 56 0 12 14 0 0 3061 +3 4 0.999999135312327 -0.000677861268628924 0.00112688894726561 0.000183759780598284 0.000679376957980004 0.999998864464437 -0.00134518280745859 0.000185960900508602 -0.00112597582031873 0.00134594722668058 0.999998460301072 0.00530840172640279 1.80999560384025e-05 -3.45740713573732e-06 2.78019559065416e-06 5.37808831367901e-07 3.88873768033035e-06 -2.60307616250316e-06 -3.45740713573732e-06 2.61128079498095e-05 -3.48310898816933e-06 -1.8107279947e-06 -1.1279728988987e-06 -6.40257960937133e-06 2.78019559065416e-06 -3.48310898816933e-06 1.34198187807788e-05 -1.94146352346942e-06 3.26642879806636e-06 2.56496760426332e-06 5.37808831367901e-07 -1.8107279947e-06 -1.94146352346942e-06 4.30485639817563e-05 6.49307215411718e-06 4.13192401643221e-06 3.88873768033035e-06 -1.1279728988987e-06 3.26642879806636e-06 6.49307215411718e-06 1.87693102128819e-05 1.02339630837681e-06 -2.60307616250316e-06 -6.40257960937133e-06 2.56496760426332e-06 4.13192401643221e-06 1.02339630837681e-06 2.3851458826369e-05 3086 3099 0 0 13 3087 3100 0 0 15 0 0 0 0 0 0 0 0 74 0 26 32 0 0 3117 +5 6 0.999999625307855 -0.000693139617296451 -0.000518595816229726 -0.00263721927118279 0.000693573897451767 0.999999408602792 0.000837704790250711 0.000393427061694147 0.000518014863155886 -0.000838064160890771 0.999999514654414 0.00391276186137873 2.98251636516978e-05 -3.5868089547396e-06 7.16620169599899e-06 -8.33212049720866e-07 -1.18004865964009e-06 1.77972557516424e-06 -3.5868089547396e-06 1.73212810499636e-05 -4.94123705688881e-06 -2.4939188516147e-06 -2.64355665502584e-06 2.75451684187304e-06 7.16620169599899e-06 -4.94123705688881e-06 1.29893447568418e-05 -1.38907860337795e-06 2.85547084076419e-06 2.60974861922881e-06 -8.33212049720866e-07 -2.4939188516147e-06 -1.38907860337795e-06 3.83750961397007e-05 6.37774270249377e-06 -1.5246496965433e-06 -1.18004865964009e-06 -2.64355665502584e-06 2.85547084076419e-06 6.37774270249377e-06 2.0180745499185e-05 -1.96414995765299e-06 1.77972557516424e-06 2.75451684187304e-06 2.60974861922881e-06 -1.5246496965433e-06 -1.96414995765299e-06 2.55238291944513e-05 2799 2800 0 0 10 2801 2816 0 0 11 0 0 0 0 0 0 0 0 63 0 33 37 0 0 2768 +19 20 0.99998842744364 -0.000145283330343439 -0.00480872868338743 -0.00226842023077848 0.00014247170920945 0.999999818721689 -0.000585028547956113 -0.0025863918331913 0.004808812806565 0.000584336669885623 0.999988266866191 -0.00345251044148052 3.76119732030489e-05 -1.2594751841179e-05 1.98151452950533e-06 4.05665470274184e-06 -2.82053121978605e-06 -7.4626505929646e-07 -1.2594751841179e-05 5.76577758020272e-05 -3.54354601080781e-06 7.7703513590677e-06 3.48430843036194e-06 -8.42659363961425e-06 1.98151452950533e-06 -3.54354601080781e-06 1.53250207167666e-05 -1.41949824724215e-06 3.35123265970876e-06 1.60780708222984e-06 4.05665470274184e-06 7.7703513590677e-06 -1.41949824724215e-06 4.09184931000758e-05 2.35612164390637e-06 -6.23715433424436e-06 -2.82053121978605e-06 3.48430843036194e-06 3.35123265970876e-06 2.35612164390637e-06 2.38358537200136e-05 -1.56806821271183e-06 -7.4626505929646e-07 -8.42659363961425e-06 1.60780708222984e-06 -6.23715433424436e-06 -1.56806821271183e-06 3.72129487394344e-05 2906 2906 0 0 12 2906 2920 0 0 15 0 0 0 0 0 0 0 0 70 0 29 33 0 0 2680 +11 12 0.999996974966992 1.07889908990345e-05 0.00245966267239905 0.000970661516021396 3.49443030561746e-07 0.999989746770229 -0.0045283942288123 -0.00310627684713864 -0.00245968630971663 0.00452838138978226 0.999986721764468 -0.000725224763448655 3.62883928039687e-05 -1.17162303297035e-05 6.89213325054724e-06 3.51994295238957e-07 -2.33881515534419e-06 5.45056320332284e-06 -1.17162303297035e-05 6.55620836562359e-05 -9.61367263934508e-06 2.21392329689667e-05 -1.3521715677801e-06 -1.58108746009229e-05 6.89213325054724e-06 -9.61367263934508e-06 1.76909546925054e-05 -5.34882226074232e-06 4.24683197817906e-06 6.00108371886048e-06 3.51994295238957e-07 2.21392329689667e-05 -5.34882226074232e-06 5.34813760650688e-05 4.46608741888545e-06 -7.86105967360195e-06 -2.33881515534419e-06 -1.3521715677801e-06 4.24683197817906e-06 4.46608741888545e-06 2.8534761091666e-05 -1.07776122028867e-06 5.45056320332284e-06 -1.58108746009229e-05 6.00108371886048e-06 -7.86105967360195e-06 -1.07776122028867e-06 3.74584528052152e-05 2825 2841 0 0 13 2827 2845 0 0 17 0 0 0 0 0 0 0 0 71 0 14 17 0 0 2670 +14 15 0.999978644210088 3.08594667685429e-05 -0.00653530194007138 -0.00417070210935104 -3.83772293049083e-05 0.999999337772952 -0.0011502090439314 -0.00205252182992263 0.0065352621173799 0.00115043528708983 0.999977983181483 0.00377174424046915 4.16996638572531e-05 -2.39824334628195e-06 3.92584985038509e-06 9.03672513727518e-06 -6.26048457760018e-06 7.33759146962819e-06 -2.39824334628195e-06 4.08731631288112e-05 -1.05193075340144e-06 4.86650352958912e-06 3.00959774040529e-07 -5.57986167923902e-06 3.92584985038509e-06 -1.05193075340144e-06 1.40996863907849e-05 -1.71044013973109e-07 1.71430004087772e-06 -1.15200492561516e-06 9.03672513727518e-06 4.86650352958912e-06 -1.71044013973109e-07 4.31295678039835e-05 -1.21918472453965e-06 5.70146845396545e-06 -6.26048457760018e-06 3.00959774040529e-07 1.71430004087772e-06 -1.21918472453965e-06 2.29105111900656e-05 -5.03625860105851e-06 7.33759146962819e-06 -5.57986167923902e-06 -1.15200492561516e-06 5.70146845396545e-06 -5.03625860105851e-06 3.8320576782631e-05 2757 2763 0 1 11 2758 2774 0 1 12 0 0 0 0 0 0 0 0 53 0 31 35 0 0 2644 +16 17 0.999999971797204 -6.59713561980627e-05 0.0002281520804607 0.000878188636093947 6.60800903976139e-05 0.999999884237302 -0.000476611796440675 -0.00214846096757994 -0.000228120611322608 0.000476626859308991 0.999999860393902 -0.00116709904282701 2.14051337166608e-05 -1.29810328378838e-06 2.01576593596e-06 2.50681066399018e-06 3.85509874769935e-06 -1.09358850974479e-06 -1.29810328378838e-06 0.000190783551079423 -6.66999469263389e-06 0.00010147149005165 6.8230025947944e-06 -6.53662208651865e-05 2.01576593596e-06 -6.66999469263389e-06 1.46218746763277e-05 -3.29605302140163e-06 1.1389484700258e-06 2.19821216895116e-06 2.50681066399018e-06 0.00010147149005165 -3.29605302140163e-06 0.000108479523111209 1.09686208345116e-05 -3.91860092903262e-05 3.85509874769935e-06 6.8230025947944e-06 1.1389484700258e-06 1.09686208345116e-05 2.08883922858529e-05 -2.48478752650479e-06 -1.09358850974479e-06 -6.53662208651865e-05 2.19821216895116e-06 -3.91860092903262e-05 -2.48478752650479e-06 5.84181138409576e-05 2469 2469 0 0 10 2470 2494 0 0 12 0 0 0 0 0 0 0 0 73 0 10 12 0 0 3091 +15 16 0.999999366571397 0.0003103764152483 -0.00108190724414335 -0.000396458009300133 -0.000312642117020876 0.999997757378959 -0.00209463408722286 -0.00195016993008632 0.00108125469281615 0.00209497101019294 0.999997220988517 -0.00378821809624997 4.99232036368463e-05 -9.99809905570023e-06 2.34212238418584e-06 -2.94325706634764e-08 -3.72175281030726e-06 -2.07772161102727e-06 -9.99809905570023e-06 6.52369408189788e-05 -8.78902386582688e-06 1.96949465832979e-05 6.22597005249996e-07 -2.05007558076138e-05 2.34212238418584e-06 -8.78902386582688e-06 1.63600931755372e-05 1.50842122856053e-06 1.42676171144167e-06 6.07075974949398e-06 -2.94325706634764e-08 1.96949465832979e-05 1.50842122856053e-06 4.96669159276975e-05 3.14905140446203e-06 -7.80288422255602e-06 -3.72175281030726e-06 6.22597005249996e-07 1.42676171144167e-06 3.14905140446203e-06 2.70297148778153e-05 -7.8998501290381e-06 -2.07772161102727e-06 -2.05007558076138e-05 6.07075974949398e-06 -7.80288422255602e-06 -7.8998501290381e-06 4.70784247248265e-05 2802 2816 0 0 9 2803 2817 0 0 10 0 0 0 0 0 0 0 0 78 0 11 13 0 0 2720 +22 23 0.99999894388659 -5.03569777478671e-05 0.00145247715275726 0.00146111931682793 5.37004175913417e-05 0.999997349088574 -0.00230194093950747 -0.00229895012666133 -0.00145235738358031 0.00230201650702642 0.999996295682155 0.00395028235182885 2.1060175316739e-05 -6.21321773783091e-06 4.28955022423555e-06 1.91475471996063e-06 4.83138464795821e-06 -1.37058667243259e-06 -6.21321773783091e-06 3.87240692325324e-05 -4.70178190760572e-07 6.42177435606677e-06 -5.13959594998608e-06 -1.72151398185879e-06 4.28955022423555e-06 -4.70178190760572e-07 1.45649023174349e-05 -1.45388104788551e-06 4.27030919798337e-06 1.91577441704026e-06 1.91475471996063e-06 6.42177435606677e-06 -1.45388104788551e-06 3.66905680950415e-05 1.29217578238923e-06 -3.92352941529232e-07 4.83138464795821e-06 -5.13959594998608e-06 4.27030919798337e-06 1.29217578238923e-06 2.07523672543889e-05 1.72005224513158e-06 -1.37058667243259e-06 -1.72151398185879e-06 1.91577441704026e-06 -3.92352941529232e-07 1.72005224513158e-06 3.5982459115388e-05 2840 2848 0 0 15 2840 2851 0 0 18 0 0 0 0 0 0 0 0 66 0 11 20 0 0 3120 +20 21 0.999954862892354 0.000587822516043721 0.00948296591911876 0.00647625266592308 -0.000557074814619141 0.999994580683929 -0.00324472963805672 -0.00193403392044866 -0.00948482185306888 0.00323930045886433 0.999949771282014 -0.0006087138239723 2.74642087800591e-05 -8.84394643967024e-06 4.57289877802596e-06 3.69884826186332e-06 2.56516846340035e-06 2.57034938214545e-06 -8.84394643967024e-06 3.37389261379652e-05 -2.58463393369755e-06 5.75427735231528e-07 -2.88554791247878e-06 -3.6396404670581e-06 4.57289877802596e-06 -2.58463393369755e-06 1.28967509318784e-05 1.86063510430128e-06 3.20164867779342e-06 3.40382002386322e-06 3.69884826186332e-06 5.75427735231528e-07 1.86063510430128e-06 3.74167905061397e-05 5.92723857810887e-06 -1.39242834845623e-06 2.56516846340035e-06 -2.88554791247878e-06 3.20164867779342e-06 5.92723857810887e-06 1.88408088172942e-05 -5.38598793251478e-07 2.57034938214545e-06 -3.6396404670581e-06 3.40382002386322e-06 -1.39242834845623e-06 -5.38598793251478e-07 3.3415312432888e-05 2918 2919 0 0 11 2917 2934 0 0 14 0 0 0 0 0 0 0 0 81 0 6 8 0 0 2873 +18 19 0.999999609624052 -0.000274767447164436 -0.000839794375513582 -0.000747559787255107 0.000274924077140575 0.999999944835864 0.00018640016445087 -0.000251775926239609 0.000839743112489714 -0.000186630971378405 0.999999630000124 0.000426494427969427 3.55554424662283e-05 -1.14802278297602e-05 2.40468530730274e-06 9.84993776040735e-07 2.75911479200484e-06 -6.11787214144453e-06 -1.14802278297602e-05 2.08550742445427e-05 -1.78878285360783e-06 2.17979449114481e-06 -2.52538744559414e-06 1.0144875404809e-05 2.40468530730274e-06 -1.78878285360783e-06 1.20347618346476e-05 4.76870463469659e-07 2.447945252621e-06 3.08450090372501e-06 9.84993776040735e-07 2.17979449114481e-06 4.76870463469659e-07 3.40797075627628e-05 2.8279755442027e-06 6.75292436066275e-06 2.75911479200484e-06 -2.52538744559414e-06 2.447945252621e-06 2.8279755442027e-06 2.00667535603921e-05 -4.18705369997671e-06 -6.11787214144453e-06 1.0144875404809e-05 3.08450090372501e-06 6.75292436066275e-06 -4.18705369997671e-06 3.22897253096669e-05 3147 3148 0 0 10 3150 3169 0 0 12 0 0 0 0 0 0 0 0 75 0 34 41 0 0 2608 +17 18 0.999999968901016 -0.000231516712746001 9.2725288125015e-05 -0.00458095478586067 0.000231440896214457 0.999999639616296 0.00081682457721546 -0.00142333259755816 -9.29143632493392e-05 -0.00081680309138926 0.999999662099758 0.00193873147014742 3.26498872558421e-05 -6.12034844770618e-06 5.50611906735635e-06 3.05737677438952e-06 1.83285748936927e-06 5.85820403677619e-06 -6.12034844770618e-06 2.83945355250964e-05 -6.00920641539934e-06 7.68205075882317e-06 -4.47100051325077e-06 1.33050256980078e-06 5.50611906735635e-06 -6.00920641539934e-06 1.39848506715152e-05 -1.47089590783556e-06 4.09546604333598e-06 4.07437248847907e-06 3.05737677438952e-06 7.68205075882317e-06 -1.47089590783556e-06 4.56549382854763e-05 2.25456759930565e-06 -7.92336270222505e-07 1.83285748936927e-06 -4.47100051325077e-06 4.09546604333598e-06 2.25456759930565e-06 2.10550280315881e-05 1.79952306560209e-06 5.85820403677619e-06 1.33050256980078e-06 4.07437248847907e-06 -7.92336270222505e-07 1.79952306560209e-06 3.59116232220224e-05 3036 3036 0 0 8 3038 3055 0 0 9 0 0 0 0 0 0 0 0 70 0 14 16 0 0 2656 +24 25 0.999999848278811 0.000445993481280217 0.000323314350206683 -0.000551971465196934 -0.000444902041588468 0.999994229190784 -0.00336803315048577 -0.00298317671486344 -0.000324814605251104 0.0033678887962693 0.999994275893881 0.00331521044957027 4.9138829939209e-05 -3.42699860620785e-06 8.20424506146585e-06 -3.72585656155464e-06 -7.14247768590026e-06 9.54696050254142e-06 -3.42699860620785e-06 1.8690522110333e-05 -4.97972436925232e-07 6.32100621860592e-07 -1.76101199484607e-06 -3.58885455245374e-06 8.20424506146585e-06 -4.97972436925232e-07 1.32933561762325e-05 -1.2084614822038e-06 4.26509423762271e-06 2.17083249067275e-06 -3.72585656155464e-06 6.32100621860592e-07 -1.2084614822038e-06 3.70849730472886e-05 2.82395947957714e-06 6.71245281482897e-07 -7.14247768590026e-06 -1.76101199484607e-06 4.26509423762271e-06 2.82395947957714e-06 2.50990922726384e-05 -3.86123401458943e-06 9.54696050254142e-06 -3.58885455245374e-06 2.17083249067275e-06 6.71245281482897e-07 -3.86123401458943e-06 3.47798877034783e-05 2985 2983 0 0 10 2987 2998 0 0 13 0 0 0 0 0 0 0 0 89 0 9 12 0 0 2787 +25 26 0.999992173833994 0.000560191670573717 0.00391643409945989 0.000186822257469023 -0.000566395832525375 0.999998586326583 0.00158320579753311 -0.000724078572071761 -0.00391554166420053 -0.00158541165905401 0.999991077461868 -0.000857659008703301 3.76461372542085e-05 -6.61541281054506e-06 9.33723623502879e-06 1.21544549900676e-06 -1.231794950768e-06 9.42315676131254e-06 -6.61541281054506e-06 5.59176300139574e-05 -4.35713156637034e-06 1.45096901964756e-05 2.20438507058863e-07 -3.17023072330892e-05 9.33723623502879e-06 -4.35713156637034e-06 1.65931271260682e-05 9.03126127405404e-07 3.59451030246534e-06 8.67820082327863e-07 1.21544549900676e-06 1.45096901964756e-05 9.03126127405404e-07 4.34945921488483e-05 4.94697142665185e-06 -1.48080145372999e-05 -1.231794950768e-06 2.20438507058863e-07 3.59451030246534e-06 4.94697142665185e-06 2.1784834984946e-05 -4.88164494305062e-06 9.42315676131254e-06 -3.17023072330892e-05 8.67820082327863e-07 -1.48080145372999e-05 -4.88164494305062e-06 5.48569275005899e-05 2875 2892 0 0 12 2876 2894 0 0 14 0 0 0 0 0 0 0 0 68 0 15 22 0 0 2696 +23 24 0.999994259110427 0.000772693514814387 -0.00329919549578293 -0.00118507645765215 -0.000786479558840984 0.999990957170991 -0.00417935714547815 -0.00133728505404642 0.00329593629955979 0.00418192790206834 0.999985824040987 0.00431828501110347 3.29485006041036e-05 -6.05157062480093e-06 4.02048016825499e-06 6.62361769918899e-06 -4.99678472819103e-06 1.41791009959032e-06 -6.05157062480093e-06 3.86847808730868e-05 -4.34361039560017e-06 6.21105851737918e-07 3.24781379835766e-06 3.84403117942686e-06 4.02048016825499e-06 -4.34361039560017e-06 1.30508261173291e-05 1.5455854417332e-06 2.4913738411755e-06 -7.62129484801146e-07 6.62361769918899e-06 6.21105851737918e-07 1.5455854417332e-06 3.45465167996114e-05 1.33514148138316e-06 5.35796181163803e-06 -4.99678472819103e-06 3.24781379835766e-06 2.4913738411755e-06 1.33514148138316e-06 2.70550702507099e-05 1.94774574487099e-06 1.41791009959032e-06 3.84403117942686e-06 -7.62129484801146e-07 5.35796181163803e-06 1.94774574487099e-06 3.84813431030281e-05 3095 3101 0 0 9 3095 3102 0 0 10 0 0 0 0 0 0 0 0 48 0 12 15 0 0 2627 +26 27 0.999999953945244 -0.000300578001802082 -4.19806568593355e-05 -0.00218746867586534 0.000300490071727469 0.999997793584911 -0.00207906975023198 -0.0019245053580438 4.26054868637127e-05 0.00207905703971034 0.999997837850962 0.00485813918504577 3.13808916809266e-05 -3.85133879932209e-06 5.99783966242117e-06 2.95650691198301e-06 -2.56239945652157e-07 6.95942891841679e-06 -3.85133879932209e-06 3.41611029858965e-05 -7.35212202615584e-07 -1.99982441861471e-06 -2.84030657980609e-06 1.68064874911259e-06 5.99783966242117e-06 -7.35212202615584e-07 1.4366098291722e-05 -4.89087999356498e-07 3.51483921191175e-06 4.7520313991887e-06 2.95650691198301e-06 -1.99982441861471e-06 -4.89087999356498e-07 3.32783461400234e-05 4.75297818242309e-06 3.18864182895051e-06 -2.56239945652157e-07 -2.84030657980609e-06 3.51483921191175e-06 4.75297818242309e-06 2.24099564669945e-05 -3.71346085656518e-06 6.95942891841679e-06 1.68064874911259e-06 4.7520313991887e-06 3.18864182895051e-06 -3.71346085656518e-06 3.81993612351313e-05 3063 3074 0 0 10 3063 3076 0 0 10 0 0 0 0 0 0 0 0 68 0 11 14 0 0 3086 +28 29 0.999995295061113 0.000838407450781384 0.00295075051214643 0.00346098770833961 -0.000826183220177587 0.999991082508164 -0.00414153660346908 -0.00144862121609457 -0.00295419649399886 0.00413907925723239 0.9999870702894 -0.0043841818496738 4.43301450735982e-05 -1.29762091111641e-05 4.5381772922482e-06 9.45486793733164e-07 -6.43447627394823e-06 2.00495910311656e-06 -1.29762091111641e-05 5.00165663063676e-05 -2.06750674526354e-06 1.70274753789821e-05 5.34244688645299e-06 3.4688974367477e-06 4.5381772922482e-06 -2.06750674526354e-06 1.48164491786847e-05 7.36070002874717e-07 3.02976442240698e-06 -5.12251211286093e-10 9.45486793733164e-07 1.70274753789821e-05 7.36070002874717e-07 4.91005164579594e-05 2.91212712278363e-06 -2.55602170103726e-06 -6.43447627394823e-06 5.34244688645299e-06 3.02976442240698e-06 2.91212712278363e-06 2.71009530704167e-05 -3.69637966294958e-06 2.00495910311656e-06 3.4688974367477e-06 -5.12251211286093e-10 -2.55602170103726e-06 -3.69637966294958e-06 4.21027144887909e-05 2852 2852 0 1 14 2854 2866 0 1 14 0 0 0 0 0 0 0 0 72 0 27 32 0 0 2613 +27 28 0.999989567679732 -7.74415109391364e-05 0.00456711446260589 0.0021365954725029 9.85399855159394e-05 0.999989324704199 -0.00461960685677961 -0.00494848339275024 -0.00456670795797311 0.00462000870695436 0.999978900126385 -0.00467384419546042 2.79684575839605e-05 3.8453359501742e-06 4.51636380116148e-06 7.46355633161195e-06 -3.02776412862241e-07 -1.75582563344849e-06 3.8453359501742e-06 6.64736456107786e-05 -3.60673151019845e-06 1.88779035811343e-05 -4.40446884826734e-06 -3.56249041314494e-05 4.51636380116148e-06 -3.60673151019845e-06 1.27672574712214e-05 3.98032366011404e-07 3.74978692696442e-06 3.57885849483334e-06 7.46355633161195e-06 1.88779035811343e-05 3.98032366011404e-07 4.0935279892185e-05 8.3179876611009e-07 -1.11364352020086e-05 -3.02776412862241e-07 -4.40446884826734e-06 3.74978692696442e-06 8.3179876611009e-07 2.0118580659343e-05 2.67679485340015e-06 -1.75582563344849e-06 -3.56249041314494e-05 3.57885849483334e-06 -1.11364352020086e-05 2.67679485340015e-06 4.97383929267681e-05 2635 2652 0 0 16 2635 2653 0 0 19 0 0 0 0 0 0 0 0 75 0 19 26 0 0 2776 +33 34 0.999967926622309 7.38667570923028e-05 -0.00800876210045121 -0.00521800904221293 -9.46295128573583e-05 0.999996635877872 -0.0025921570541559 -0.00172652705747384 0.00800854368376194 0.00259283178017983 0.999964569598056 0.00104278638755544 4.17281629912577e-05 -9.35555056105206e-06 8.65102987102928e-07 -7.79903249154246e-06 -2.70347100052714e-06 3.60897723685568e-06 -9.35555056105206e-06 4.66235703401437e-05 -5.46502202244719e-06 1.40475232214734e-05 6.44664866302747e-06 -1.30682614103708e-05 8.65102987102928e-07 -5.46502202244719e-06 1.78230228500503e-05 -2.86594996507618e-06 -1.9684454610276e-08 2.10970202217653e-06 -7.79903249154246e-06 1.40475232214734e-05 -2.86594996507618e-06 5.25205654036047e-05 9.10194286078123e-06 1.04994947399259e-06 -2.70347100052714e-06 6.44664866302747e-06 -1.9684454610276e-08 9.10194286078123e-06 2.59567821551744e-05 -9.78187665438206e-07 3.60897723685568e-06 -1.30682614103708e-05 2.10970202217653e-06 1.04994947399259e-06 -9.78187665438206e-07 3.554582693304e-05 2799 2811 0 0 8 2800 2818 0 0 11 0 0 0 0 0 0 0 0 53 0 14 20 0 0 2689 +21 22 0.999999295333299 0.000441552866872817 0.00110198183760317 0.00208174907979048 -0.00044056778069397 0.999999503327379 -0.000894005047501273 0.000125345987878872 -0.00110237604077068 0.000893518919833128 0.999998993194996 -0.00282630802234436 3.97424894715817e-05 -6.19591303981024e-06 7.47445141426492e-06 -4.78624167125225e-06 -1.65933517248572e-07 -2.50944723488529e-06 -6.19591303981024e-06 2.3181994343868e-05 -2.58929464305244e-06 -9.90196268268799e-07 -6.39032788711391e-07 -1.39615414128932e-06 7.47445141426492e-06 -2.58929464305244e-06 1.45855354657123e-05 -1.88800275064349e-06 4.00764952470557e-06 1.06615927078657e-06 -4.78624167125225e-06 -9.90196268268799e-07 -1.88800275064349e-06 3.42669545143513e-05 4.40422926717283e-06 -9.3400223302897e-07 -1.65933517248572e-07 -6.39032788711391e-07 4.00764952470557e-06 4.40422926717283e-06 2.66988660130083e-05 -5.94202807795787e-06 -2.50944723488529e-06 -1.39615414128932e-06 1.06615927078657e-06 -9.3400223302897e-07 -5.94202807795787e-06 3.16364438457067e-05 2771 2773 0 0 11 2772 2784 0 0 14 0 0 0 0 0 0 0 0 64 0 8 14 0 0 2768 +30 31 0.999979352135815 -4.84336435989535e-05 0.00642595955620854 0.00143856651386788 7.42464736098639e-05 0.999991929936621 -0.00401678342613319 -0.00159759533129566 -0.00642571315085078 0.00401717759297116 0.999971285835093 -0.00240336918241976 3.21214397096732e-05 -7.85562006220104e-06 7.10406491832923e-06 4.34369738509976e-06 -1.1909599251035e-06 -7.43045819728371e-07 -7.85562006220104e-06 4.30591446956059e-05 -9.57519039184821e-06 5.12573183012302e-06 -1.4824098402548e-06 -1.41393693111022e-05 7.10406491832923e-06 -9.57519039184821e-06 1.43430185656899e-05 8.17120643325599e-07 4.39835968492184e-06 1.6575698400872e-06 4.34369738509976e-06 5.12573183012302e-06 8.17120643325599e-07 4.37940054609158e-05 1.9715598368955e-06 -2.84945945134482e-06 -1.1909599251035e-06 -1.4824098402548e-06 4.39835968492184e-06 1.9715598368955e-06 2.38977705022976e-05 -1.6108900359458e-07 -7.43045819728371e-07 -1.41393693111022e-05 1.6575698400872e-06 -2.84945945134482e-06 -1.6108900359458e-07 3.42093751056099e-05 2992 3004 0 0 11 2992 3004 0 0 11 0 0 0 0 0 0 0 0 76 0 16 28 0 0 2625 +29 30 0.999999949611159 0.000317419189810513 4.76846938895825e-06 -0.00164717487539616 -0.000317430248163517 0.999996742774379 0.00253252416950976 0.00179728310053028 -3.96458208691626e-06 -0.00253252555555522 0.999996793144154 -0.00287284395041713 3.63913772621503e-05 -2.18366883039037e-06 6.67475222226505e-06 1.96823543184226e-06 -2.67217383144765e-06 3.91470790538506e-07 -2.18366883039037e-06 3.04674995951568e-05 -2.709753547662e-06 -1.20439433163528e-06 -2.04746039174496e-07 4.09338347445371e-06 6.67475222226505e-06 -2.709753547662e-06 1.63204027588266e-05 -1.97546062619962e-07 4.73294915279064e-06 -1.80419366791157e-07 1.96823543184226e-06 -1.20439433163528e-06 -1.97546062619962e-07 3.91277040681848e-05 -1.17180019142543e-06 2.04308230739039e-06 -2.67217383144765e-06 -2.04746039174496e-07 4.73294915279064e-06 -1.17180019142543e-06 2.21281413980203e-05 -4.06703846925061e-06 3.91470790538506e-07 4.09338347445371e-06 -1.80419366791157e-07 2.04308230739039e-06 -4.06703846925061e-06 3.56672973796906e-05 3015 3016 0 0 8 3015 3031 0 0 12 0 0 0 0 0 0 0 0 65 0 12 14 0 0 2687 +31 32 0.999963397486182 0.000616806743001857 0.00853365322317349 0.00301427237169998 -0.000600022534156953 0.999997881018937 -0.00196924619933692 -0.00030149669867955 -0.0085348497848583 0.00196405373574312 0.999961648680625 -0.00470668715130609 2.99730893444557e-05 -2.22650182816339e-06 4.29898989483773e-06 -3.26784391396904e-06 -2.06934785870389e-06 -2.08675018802146e-06 -2.22650182816339e-06 3.8514838829896e-05 -4.21989065127121e-06 5.71220473112894e-06 -1.07361458619535e-06 -1.10652980178079e-05 4.29898989483773e-06 -4.21989065127121e-06 1.20575303032682e-05 3.69866979785302e-07 4.4105820130964e-06 3.23268121534414e-06 -3.26784391396904e-06 5.71220473112894e-06 3.69866979785302e-07 3.91109284456458e-05 4.11442691914753e-06 2.90339290227055e-06 -2.06934785870389e-06 -1.07361458619535e-06 4.4105820130964e-06 4.11442691914753e-06 1.77436811858101e-05 3.35121815189115e-06 -2.08675018802146e-06 -1.10652980178079e-05 3.23268121534414e-06 2.90339290227055e-06 3.35121815189115e-06 2.82190045352687e-05 2861 2866 0 0 9 2861 2868 0 0 12 0 0 0 0 0 0 0 0 55 0 9 12 0 0 2846 +32 33 0.99999154077647 -0.000365899859307049 0.00409688818431388 -0.00118765463859244 0.000366185451981704 0.99999993057638 -6.89597615178101e-05 0.000810180140420877 -0.00409686266752604 7.04593990232643e-05 0.999991605340643 -0.00222646479333236 3.16132808880971e-05 -1.0378525852513e-05 3.82414257238652e-06 -2.00260356938361e-07 2.3998456700103e-07 1.13119517881353e-06 -1.0378525852513e-05 3.7330135545688e-05 -4.73660500349598e-06 5.50316546044039e-06 8.04216180301746e-07 -8.68782743310273e-06 3.82414257238652e-06 -4.73660500349598e-06 1.4289798025254e-05 2.98746829917856e-07 4.03502355290369e-06 1.73481898314465e-06 -2.00260356938361e-07 5.50316546044039e-06 2.98746829917856e-07 3.56909561460313e-05 4.20275778586062e-06 1.65406328345053e-06 2.3998456700103e-07 8.04216180301746e-07 4.03502355290369e-06 4.20275778586062e-06 1.69721913358356e-05 1.5309061909815e-06 1.13119517881353e-06 -8.68782743310273e-06 1.73481898314465e-06 1.65406328345053e-06 1.5309061909815e-06 2.45636878985043e-05 2735 2738 0 0 9 2738 2750 0 0 12 0 0 0 0 0 0 0 0 67 0 9 12 0 0 3083 +38 39 0.99999544084826 0.00105764951253119 -0.00282836705596431 -0.00165897931533001 -0.00106073033463564 0.999998845574571 -0.00108798009257839 -0.00106234661406546 0.0028272130892109 0.0010909752670458 0.999995408309016 0.000378566391290932 3.20597693841496e-05 -6.02374833985868e-06 9.02338930322454e-06 4.95635888519586e-07 -7.42535016075563e-07 -5.91352246252176e-07 -6.02374833985868e-06 2.75715370920623e-05 6.41230854968268e-07 -1.83436477676019e-06 -3.88177176459809e-07 -6.35761671397003e-06 9.02338930322454e-06 6.41230854968268e-07 1.53043363778892e-05 -8.05194884963842e-07 4.04040459564396e-06 1.21138232371658e-06 4.95635888519586e-07 -1.83436477676019e-06 -8.05194884963842e-07 3.52049912431426e-05 7.48208331457693e-06 -4.66956932333571e-06 -7.42535016075563e-07 -3.88177176459809e-07 4.04040459564396e-06 7.48208331457693e-06 2.03657541250061e-05 -2.77134133690612e-06 -5.91352246252176e-07 -6.35761671397003e-06 1.21138232371658e-06 -4.66956932333571e-06 -2.77134133690612e-06 2.94424448593139e-05 3104 3112 0 0 6 3105 3128 0 0 14 0 0 0 0 0 0 0 0 83 0 14 18 0 0 2686 +35 36 0.999996262972861 -0.000277683565709276 -0.00271973016125733 -0.00270386181419983 0.000300743784193604 0.999963980889058 0.00848212695524925 0.00175927945535002 0.00271727685173719 -0.0084829131992513 0.999960327508129 -0.0169612460781348 3.47537210906371e-05 -6.83179664676037e-06 5.94233291691684e-07 8.28615106554096e-06 -1.73127165576735e-06 1.85522147399558e-05 -6.83179664676037e-06 3.81547167361631e-05 -3.56467292586142e-06 2.8413228564093e-06 2.84784506059368e-06 3.3799568141038e-06 5.94233291691684e-07 -3.56467292586142e-06 1.31933379664716e-05 -1.14940038026676e-06 2.70727577701323e-06 2.26438429617654e-07 8.28615106554096e-06 2.8413228564093e-06 -1.14940038026676e-06 3.60605385427976e-05 3.97989208162905e-06 2.94251949711607e-06 -1.73127165576735e-06 2.84784506059368e-06 2.70727577701323e-06 3.97989208162905e-06 2.35228300196437e-05 -3.35032425236286e-06 1.85522147399558e-05 3.3799568141038e-06 2.26438429617654e-07 2.94251949711607e-06 -3.35032425236286e-06 5.28840440559895e-05 2971 2972 0 0 8 2972 2989 0 0 10 0 0 0 0 0 0 0 0 69 0 9 11 0 0 2826 +42 43 0.999995855814282 -0.000328110933892404 0.00286019186015221 0.00169112529818231 0.00032861414544369 0.999999930611839 -0.00017546811710224 0.00106956507515975 -0.00286013408868099 0.000176407289433704 0.999995894248303 -0.00423399361116202 3.6430078736101e-05 -4.30327240120167e-06 6.60612596481015e-06 -2.03524827982386e-07 1.72401034281977e-06 8.21734933572783e-06 -4.30327240120167e-06 2.66322561263385e-05 -4.83391828985856e-06 3.90050385785344e-06 -2.43622835343736e-06 -9.71865768924401e-06 6.60612596481015e-06 -4.83391828985856e-06 1.63354935868868e-05 -4.29541721294349e-06 3.1076055175198e-06 1.86934950989667e-06 -2.03524827982386e-07 3.90050385785344e-06 -4.29541721294349e-06 5.43195929979758e-05 3.41604224508845e-06 1.23087473280238e-06 1.72401034281977e-06 -2.43622835343736e-06 3.1076055175198e-06 3.41604224508845e-06 2.56813676513213e-05 -5.75217869188268e-06 8.21734933572783e-06 -9.71865768924401e-06 1.86934950989667e-06 1.23087473280238e-06 -5.75217869188268e-06 3.22949576382333e-05 3129 3131 0 1 12 3129 3151 0 1 16 0 0 0 0 0 0 0 0 17 0 8 12 0 0 2628 +34 35 0.999994635081292 0.000663754049146739 0.00320768439770111 -0.00399734315470085 -0.000681108287551133 0.999985122267537 0.00541214699345294 0.00432121457254443 -0.00320404434014933 -0.00541430273815141 0.999980209517031 -0.00436834134709025 4.45565714698215e-05 -8.57077223538639e-06 6.08045484121877e-06 -2.21853957902374e-06 -3.3228741923125e-06 1.04134146970161e-05 -8.57077223538639e-06 4.99377869713954e-05 -1.08265295352323e-07 5.578475043799e-06 -8.80858525421757e-07 -1.20378772912716e-05 6.08045484121877e-06 -1.08265295352323e-07 1.58383514927702e-05 -1.54225693777243e-06 8.54387753069207e-07 2.84855774113793e-06 -2.21853957902374e-06 5.578475043799e-06 -1.54225693777243e-06 4.55657752656031e-05 6.02844008936403e-06 -2.75140383719346e-06 -3.3228741923125e-06 -8.80858525421757e-07 8.54387753069207e-07 6.02844008936403e-06 2.46318623122979e-05 -5.47025338223221e-06 1.04134146970161e-05 -1.20378772912716e-05 2.84855774113793e-06 -2.75140383719346e-06 -5.47025338223221e-06 3.66322096032921e-05 2675 2675 0 2 6 2680 2697 0 2 9 0 0 0 0 0 0 0 0 81 0 12 14 0 0 2609 +43 44 0.999999414759585 -0.000643197986738228 0.000869929213559219 -0.00621420501812845 0.000642924284548618 0.999999743752944 0.000314868880162544 -0.0040170789578854 -0.000870131513672226 -0.000314309397271315 0.999999572040284 -0.000310691407889604 5.796306975462e-05 -2.27767922422653e-05 1.17111682646121e-05 -1.29009156080098e-05 -7.48134321947536e-06 2.09922390968896e-05 -2.27767922422653e-05 7.86895054120374e-05 -7.03855667345536e-06 2.03516579976321e-05 3.40890829381104e-06 -2.46270521263321e-05 1.17111682646121e-05 -7.03855667345536e-06 2.19363787353325e-05 -7.49853066238902e-06 -1.30140153943981e-06 2.75058983269635e-06 -1.29009156080098e-05 2.03516579976321e-05 -7.49853066238902e-06 7.77097943463679e-05 1.05894749597226e-05 -2.660799946221e-05 -7.48134321947536e-06 3.40890829381104e-06 -1.30140153943981e-06 1.05894749597226e-05 3.01736058224807e-05 -3.20461050944447e-06 2.09922390968896e-05 -2.46270521263321e-05 2.75058983269635e-06 -2.660799946221e-05 -3.20461050944447e-06 5.40677167294766e-05 2631 2631 0 0 7 2643 2654 0 0 10 0 0 0 0 0 0 0 0 27 0 29 32 0 0 2343 +41 42 0.999999205276383 0.000528511716649905 0.00114460559490225 0.00293618427136217 -0.000528413642187647 0.99999985669281 -8.59847845994975e-05 0.000135701057364753 -0.00114465087483815 8.53798910540878e-05 0.999999341242108 -0.00453831526836855 4.30287749909075e-05 -7.17623374829234e-06 7.09562484510478e-06 7.74846877291346e-08 -6.00957694949606e-06 3.90962307723361e-07 -7.17623374829234e-06 2.93654242202277e-05 4.17475226973332e-07 -3.01346958012877e-07 4.11788261301092e-06 5.46666695478058e-06 7.09562484510478e-06 4.17475226973332e-07 1.64846205739164e-05 -2.98996088507502e-06 2.22114171192821e-06 9.03684012255314e-07 7.74846877291346e-08 -3.01346958012877e-07 -2.98996088507502e-06 4.11122231005677e-05 9.61169715428019e-06 -3.34756823018237e-06 -6.00957694949606e-06 4.11788261301092e-06 2.22114171192821e-06 9.61169715428019e-06 2.45079804999133e-05 -4.03432806545903e-06 3.90962307723361e-07 5.46666695478058e-06 9.03684012255314e-07 -3.34756823018237e-06 -4.03432806545903e-06 3.62149567472316e-05 2984 2986 0 0 11 2985 3009 0 0 15 0 0 0 0 0 0 0 0 70 0 9 11 0 0 2620 +39 40 0.999958572942318 0.000605420264101999 0.00908217294852049 0.00603678261945638 -0.00058780754631669 0.999997941932686 -0.00194180655078279 -0.0014409702292431 -0.00908332986583202 0.00193638753765471 0.999956870830864 -0.000743293533682754 3.83370351412767e-05 -6.73325636066796e-06 -1.71051045221988e-07 2.62110118606069e-06 9.16669740058186e-07 7.99870040083979e-08 -6.73325636066796e-06 4.003811697285e-05 -2.4764151937201e-06 8.91879468836712e-06 1.47776427085345e-06 -2.71844157025732e-06 -1.71051045221988e-07 -2.4764151937201e-06 1.2383089974515e-05 2.35357417408202e-06 2.35887463282907e-06 5.43913060051137e-07 2.62110118606069e-06 8.91879468836712e-06 2.35357417408202e-06 4.26359571366433e-05 7.37763756314237e-07 4.96667610009136e-06 9.16669740058186e-07 1.47776427085345e-06 2.35887463282907e-06 7.37763756314237e-07 1.94662700162835e-05 -2.06386265161761e-06 7.99870040083979e-08 -2.71844157025732e-06 5.43913060051137e-07 4.96667610009136e-06 -2.06386265161761e-06 3.27374161926625e-05 2953 2960 0 0 11 2955 2969 0 0 14 0 0 0 0 0 0 0 0 87 0 7 10 0 0 2541 +46 47 0.999973903793823 0.000155049292737605 0.0072227204749526 0.00234511251249116 -0.000137613212625486 0.999997075635511 -0.00241449436326935 -0.00215380515348555 -0.00722307371872867 0.00241343741235818 0.99997100084248 0.000309383777099173 4.49205129107183e-05 -1.05868405049096e-05 6.47705108426798e-06 -7.87527643091746e-06 -8.55715614349366e-06 1.07479176238575e-05 -1.05868405049096e-05 4.04110838299687e-05 -5.09394376162108e-06 4.87162285837578e-06 3.07092633146349e-06 -8.90111057646014e-06 6.47705108426798e-06 -5.09394376162108e-06 1.37750226406841e-05 1.95799555188478e-06 4.24910238253022e-06 3.27688490699924e-06 -7.87527643091746e-06 4.87162285837578e-06 1.95799555188478e-06 3.82415410183401e-05 7.51682489213165e-06 -3.66288624309771e-06 -8.55715614349366e-06 3.07092633146349e-06 4.24910238253022e-06 7.51682489213165e-06 2.60894204549048e-05 -3.36143336756263e-06 1.07479176238575e-05 -8.90111057646014e-06 3.27688490699924e-06 -3.66288624309771e-06 -3.36143336756263e-06 3.55602318271476e-05 2910 2912 0 0 12 2910 2931 0 0 12 0 0 0 0 0 0 0 0 62 0 9 12 0 0 2699 +36 37 0.999975357412262 -0.000489753269807052 0.00700319283994989 0.000725960584553482 0.000526207709348371 0.999986318007318 -0.00520450800874812 -0.0011108173650622 -0.00700054809750169 0.00520806489026531 0.999961933468686 -0.00358926354827443 4.15434675069044e-05 -7.67083653629105e-06 5.87171091607089e-06 -1.50078037880452e-06 1.3127390159264e-06 2.68476760049384e-06 -7.67083653629105e-06 3.46386299299928e-05 -4.63633285473368e-06 3.98073110275875e-06 1.2882375986601e-06 -9.22391748979148e-06 5.87171091607089e-06 -4.63633285473368e-06 1.66819115754385e-05 -1.69747655359793e-06 1.59224277901942e-06 3.56268212813719e-06 -1.50078037880452e-06 3.98073110275875e-06 -1.69747655359793e-06 5.83379077779799e-05 8.4830971788946e-07 1.48976073590736e-06 1.3127390159264e-06 1.2882375986601e-06 1.59224277901942e-06 8.4830971788946e-07 2.40673007032013e-05 -6.6637959537631e-06 2.68476760049384e-06 -9.22391748979148e-06 3.56268212813719e-06 1.48976073590736e-06 -6.6637959537631e-06 3.49310547957303e-05 2962 2964 0 0 11 2962 2982 0 0 12 0 0 0 0 0 0 0 0 65 0 7 9 0 0 2659 +37 38 0.999997221692849 0.000676695431092452 -0.00225802787325363 0.000964797170748093 -0.000678746815520548 0.999999357562282 -0.000907842378703709 -0.00313080709904761 0.00225741208982153 0.000909372485667064 0.999997038561784 0.0019264322050659 3.9573298545302e-05 -4.91348001187331e-07 6.17499602536485e-06 -4.40070380842711e-06 -5.0383149069872e-06 8.931209369376e-06 -4.91348001187331e-07 3.32339013321503e-05 -3.50318729574664e-06 -2.27810200606766e-06 -2.74731948061465e-06 -2.29965081048814e-06 6.17499602536485e-06 -3.50318729574664e-06 1.55543710299764e-05 -2.43787207252983e-06 3.50295347464048e-06 3.5913461176922e-06 -4.40070380842711e-06 -2.27810200606766e-06 -2.43787207252983e-06 4.22699788557817e-05 9.51676039090797e-06 -4.84295536501003e-06 -5.0383149069872e-06 -2.74731948061465e-06 3.50295347464048e-06 9.51676039090797e-06 2.66681648914195e-05 1.32384805681114e-07 8.931209369376e-06 -2.29965081048814e-06 3.5913461176922e-06 -4.84295536501003e-06 1.32384805681114e-07 3.69995333544395e-05 3087 3088 0 0 10 3094 3113 0 0 11 0 0 0 0 0 0 0 0 79 0 22 29 0 0 2641 +48 49 0.999977013801509 0.000454150233883664 0.00676502891216527 0.00482205610429556 -0.000443312065501036 0.999998616128679 -0.00160350090104832 -0.00145815183470205 -0.00676574778054502 0.0016004650237181 0.999975831292276 -0.000278529893269678 3.68144570124283e-05 -5.64974273415709e-06 8.17078303511895e-06 2.63501190337178e-06 -5.57239836637766e-06 1.74423707770367e-05 -5.64974273415709e-06 9.56012234771225e-05 -4.63285086303205e-06 2.38372498956312e-05 4.42108419604046e-07 -1.85246672454941e-05 8.17078303511895e-06 -4.63285086303205e-06 1.50647193503015e-05 -3.14650372302038e-07 4.259330087937e-06 3.1127400042128e-06 2.63501190337178e-06 2.38372498956312e-05 -3.14650372302038e-07 4.90269736121432e-05 6.06054132768093e-06 -5.2803537883632e-06 -5.57239836637766e-06 4.42108419604046e-07 4.259330087937e-06 6.06054132768093e-06 2.4160953751435e-05 -8.0528950360859e-06 1.74423707770367e-05 -1.85246672454941e-05 3.1127400042128e-06 -5.2803537883632e-06 -8.0528950360859e-06 4.3553248982402e-05 2876 2894 0 0 11 2877 2897 0 0 14 0 0 0 0 0 0 0 0 64 0 9 12 0 0 2820 +40 41 0.999997869301245 0.00112103652205141 -0.00173339842106715 -0.0004053934778609 -0.0011231237537208 0.999998644941788 -0.00120362270750717 -0.00249940060204169 0.0017320467671975 0.00120556696389113 0.999997773308667 0.00270401776581582 3.67287539033461e-05 -5.1555641020984e-06 9.65215906759993e-06 -7.99586385502458e-06 -1.84033553397048e-06 1.03996392480898e-05 -5.1555641020984e-06 4.09245104084209e-05 -6.19867178555455e-06 1.20544438639711e-05 -2.30490291893762e-08 -1.40713265088602e-05 9.65215906759993e-06 -6.19867178555455e-06 2.07161083125411e-05 -6.59660913434713e-06 1.41960988914208e-06 6.96530004471696e-06 -7.99586385502458e-06 1.20544438639711e-05 -6.59660913434713e-06 6.91324400913381e-05 5.85668659262927e-06 -1.61121861974138e-05 -1.84033553397048e-06 -2.30490291893762e-08 1.41960988914208e-06 5.85668659262927e-06 2.56344138529645e-05 -2.00053672194267e-06 1.03996392480898e-05 -1.40713265088602e-05 6.96530004471696e-06 -1.61121861974138e-05 -2.00053672194267e-06 4.27042278641146e-05 2782 2800 0 0 21 2783 2801 0 0 22 0 0 0 0 0 0 0 0 93 0 16 23 0 0 2826 +44 45 0.999998506234903 -0.000377311999711919 0.00168676128077798 0.00492063178280288 0.000376813593155671 0.999999885260062 0.000295789416185563 0.00227314755089347 -0.00168687269213521 -0.000295153379766651 0.999998533671427 -0.000126458892680428 4.28737989611525e-05 -1.11425162627955e-05 5.14739969775578e-06 1.02302011243896e-05 -4.28572186904626e-06 1.90641927907513e-06 -1.11425162627955e-05 2.70206881317311e-05 -4.53233556078505e-06 4.22879333918365e-06 -1.58009881867072e-06 -1.77765324040166e-07 5.14739969775578e-06 -4.53233556078505e-06 1.64311370094122e-05 -3.44902498064181e-06 2.41448971003639e-06 7.40892461543798e-07 1.02302011243896e-05 4.22879333918365e-06 -3.44902498064181e-06 6.40094048619844e-05 4.23908970890126e-06 1.71186313222974e-07 -4.28572186904626e-06 -1.58009881867072e-06 2.41448971003639e-06 4.23908970890126e-06 2.476549276008e-05 -3.01163430072601e-07 1.90641927907513e-06 -1.77765324040166e-07 7.40892461543798e-07 1.71186313222974e-07 -3.01163430072601e-07 2.87653798794374e-05 2796 2814 0 1 16 2797 2816 0 1 18 0 0 0 0 0 0 0 0 21 0 8 10 0 0 2281 +45 46 0.99998734741609 0.000554696077041796 0.00499973199228017 0.00573183496962521 -0.000558660024127617 0.999999530736838 0.000791470202309618 -0.00320462499253515 -0.00499929062067381 -0.000794253338561909 0.999987188045389 -0.00212859268786385 5.50069084381396e-05 -3.74378872425547e-06 5.1626661031079e-06 9.1703009262375e-06 -9.71111358519839e-06 1.64697230174122e-05 -3.74378872425547e-06 2.91191673157598e-05 -4.36104116838315e-06 3.55838378945457e-06 1.75991338505919e-07 -6.48466021839167e-06 5.1626661031079e-06 -4.36104116838315e-06 1.76201241416181e-05 -2.05198861351749e-06 1.3455611474465e-06 -1.2664245152667e-06 9.1703009262375e-06 3.55838378945457e-06 -2.05198861351749e-06 4.80538584509428e-05 9.14725839604486e-06 -1.32776227040885e-06 -9.71111358519839e-06 1.75991338505919e-07 1.3455611474465e-06 9.14725839604486e-06 3.02760626476331e-05 -4.42321154964438e-06 1.64697230174122e-05 -6.48466021839167e-06 -1.2664245152667e-06 -1.32776227040885e-06 -4.42321154964438e-06 3.33990848254268e-05 2953 2953 0 0 13 2955 2973 0 0 17 0 0 0 0 0 0 0 0 58 0 16 23 0 0 2598 +49 50 0.99998745549744 6.50996600573e-05 0.00500845383231226 0.00387973286884196 -7.960221702131e-06 0.999934929213983 -0.0114077725459962 -0.00727343020719325 -0.00500887057039942 0.0114075895727614 0.999922386045911 0.00237853242925542 5.35394206091627e-05 3.15642553736248e-06 7.77975509093726e-06 -3.92926706843282e-06 -9.6298288038464e-06 1.70689793556882e-05 3.15642553736248e-06 5.07594377399496e-05 -3.37460694411491e-06 7.70339818310553e-06 -5.57089439879519e-06 -4.93829998886736e-06 7.77975509093726e-06 -3.37460694411491e-06 1.6236968080224e-05 -1.94809805547088e-06 4.41656716231788e-06 2.1669132085638e-06 -3.92926706843282e-06 7.70339818310553e-06 -1.94809805547088e-06 4.3854287833158e-05 4.59090329643126e-06 -4.58943425733189e-06 -9.6298288038464e-06 -5.57089439879519e-06 4.41656716231788e-06 4.59090329643126e-06 2.9847126728362e-05 -8.90267307989881e-06 1.70689793556882e-05 -4.93829998886736e-06 2.1669132085638e-06 -4.58943425733189e-06 -8.90267307989881e-06 4.27595304624458e-05 2841 2856 0 0 14 2841 2857 0 0 18 0 0 0 0 0 0 0 0 57 0 28 31 0 0 2502 +47 48 0.999985314291668 -0.00025121786868042 -0.00541369472503588 -0.00378890626327835 0.000224061145590996 0.999987393065856 -0.00501632394847503 -0.0040312583071341 0.00541488666515396 0.00501503728156266 0.99997276383083 0.00582670146905568 4.03422560142198e-05 -7.97289278410964e-06 6.25511979817468e-06 -6.77399321875734e-06 -2.81699270403681e-06 9.05234651536229e-06 -7.97289278410964e-06 4.08480564350308e-05 -2.7348896483331e-06 6.22179964276015e-06 1.39896723830427e-06 -1.18199010548394e-05 6.25511979817468e-06 -2.7348896483331e-06 1.46485313493016e-05 -3.29157358987884e-06 3.56153140317334e-06 2.13704674838947e-06 -6.77399321875734e-06 6.22179964276015e-06 -3.29157358987884e-06 4.52441937407424e-05 4.28227843220338e-06 -1.91072170982813e-06 -2.81699270403681e-06 1.39896723830427e-06 3.56153140317334e-06 4.28227843220338e-06 2.0629238062446e-05 -3.42080126513116e-06 9.05234651536229e-06 -1.18199010548394e-05 2.13704674838947e-06 -1.91072170982813e-06 -3.42080126513116e-06 3.46377049119529e-05 2966 2966 0 2 8 2967 2970 0 2 13 0 0 0 0 0 0 0 0 43 0 34 50 0 0 2639 +54 55 0.999350821471756 0.00925985367282155 -0.0348165296042678 -0.000870648863709981 -0.00936367825159611 0.99995218293189 -0.00282017363815509 -0.015324107275817 0.034788750384679 0.00314435362303481 0.999389741735908 -0.0961756587623537 0.000109781647464405 0.000104673281560367 5.3105839350412e-06 4.8217452726835e-05 -2.20870688107684e-05 9.55463878528141e-05 0.000104673281560367 0.000259468240844598 -8.83782664191138e-06 9.62666707239403e-05 -2.34412503813518e-05 0.000160851819242648 5.3105839350412e-06 -8.83782664191138e-06 1.49526033627622e-05 6.35184251840313e-07 1.78658393881911e-06 -3.28465784484437e-06 4.8217452726835e-05 9.62666707239403e-05 6.35184251840313e-07 8.5028817490939e-05 -1.14291913447511e-05 7.87855437176814e-05 -2.20870688107684e-05 -2.34412503813518e-05 1.78658393881911e-06 -1.14291913447511e-05 2.99602444128826e-05 -1.9495639275292e-05 9.55463878528141e-05 0.000160851819242648 -3.28465784484437e-06 7.87855437176814e-05 -1.9495639275292e-05 0.000176918930609539 3462 3364 0 0 0 3428 3397 0 0 0 0 0 0 0 0 0 0 0 98 0 55 72 0 0 3210 +50 51 0.999999778835135 -0.000275683300396935 -0.000605250691414329 -0.00023509459193396 0.000275949040878644 0.999999865557241 0.000439018936894999 0.000713570980739951 0.000605129579853296 -0.000439185858147222 0.999999720466948 0.00126921802768328 1.5854166424049e-05 -5.27974663347308e-06 6.16459803649038e-06 7.54600074430021e-07 4.1916483775291e-06 3.16860728979044e-06 -5.27974663347308e-06 2.42281426328016e-05 -5.92954811798559e-06 4.59078281195755e-07 -1.79212378397424e-06 -3.56739723321594e-06 6.16459803649038e-06 -5.92954811798559e-06 1.46943530443201e-05 -1.34112690329183e-06 4.18307132183781e-06 3.21685394361276e-06 7.54600074430021e-07 4.59078281195755e-07 -1.34112690329183e-06 4.47274660879946e-05 6.38604738058015e-06 -3.17545885074961e-06 4.1916483775291e-06 -1.79212378397424e-06 4.18307132183781e-06 6.38604738058015e-06 1.82809559184344e-05 4.25753072735574e-07 3.16860728979044e-06 -3.56739723321594e-06 3.21685394361276e-06 -3.17545885074961e-06 4.25753072735574e-07 2.26200944450566e-05 2836 2845 0 1 7 2838 2848 0 1 10 0 0 0 0 0 0 0 0 72 0 13 26 0 0 3107 +58 59 0.998973038138386 0.0288047422568299 0.0349736457361756 0.0164158736182598 -0.0283991366953791 0.999524156989273 -0.0120394613600565 -0.00101402185975114 -0.0353037973526799 0.011033875946408 0.99931571361311 -0.132280737461839 3.41611342502273e-05 8.14499722078726e-06 2.74839120887409e-06 7.05599953064924e-06 -5.95841296311152e-06 1.14806852982246e-05 8.14499722078726e-06 8.63189935186661e-05 -2.21547095250797e-06 9.99896439602558e-06 2.51706482764266e-06 1.02527173594532e-05 2.74839120887409e-06 -2.21547095250797e-06 1.38123848771418e-05 2.90124760016003e-06 2.36437234577839e-06 1.47983765865557e-06 7.05599953064924e-06 9.99896439602558e-06 2.90124760016003e-06 4.2979361292377e-05 1.92695263589515e-06 8.72337879139818e-06 -5.95841296311152e-06 2.51706482764266e-06 2.36437234577839e-06 1.92695263589515e-06 2.05283911661344e-05 3.20188731988081e-07 1.14806852982246e-05 1.02527173594532e-05 1.47983765865557e-06 8.72337879139818e-06 3.20188731988081e-07 0.00013198605721246 3147 3050 0 39 0 3165 3069 0 0 0 0 0 0 0 0 0 0 0 249 0 33 60 0 0 3188 +56 57 0.999431373711791 0.0322020906793689 -0.00999772956425805 0.00428132472591059 -0.0323129575707772 0.999415792935507 -0.0111330860106526 -0.0180168371289825 0.00963338017476147 0.011449811656492 0.999888043632606 -0.130015298087025 6.30189090995075e-05 1.68510515599492e-05 3.60145609968752e-06 1.87134586134664e-05 -7.41540723304298e-06 7.72307809027994e-05 1.68510515599492e-05 0.000171277229373079 -1.37723720342444e-05 4.85015938177778e-05 3.67988798617155e-06 0.000154567200011633 3.60145609968752e-06 -1.37723720342444e-05 1.78125105263758e-05 -3.84918170734167e-06 -1.36920809419961e-06 -1.34968861578598e-05 1.87134586134664e-05 4.85015938177778e-05 -3.84918170734167e-06 8.13818455097719e-05 7.31696000728589e-06 6.76486796024314e-05 -7.41540723304298e-06 3.67988798617155e-06 -1.36920809419961e-06 7.31696000728589e-06 2.99295807644879e-05 -6.61274703051721e-06 7.72307809027994e-05 0.000154567200011633 -1.34968861578598e-05 6.76486796024314e-05 -6.61274703051721e-06 0.000288219552460876 3400 3289 0 29 0 3416 3314 0 0 0 0 0 0 0 0 0 0 0 104 0 84 102 0 0 3207 +60 61 0.999273370340547 0.0153673477777485 0.034879448827666 0.0412004047903527 -0.0151295422225219 0.999860534500042 -0.00707166892794722 0.00614632204359679 -0.0349832571436818 0.00653882034982588 0.99936650711741 -0.0425468510610145 4.14330672698172e-05 -4.21636611816395e-06 -2.37236820826069e-07 7.56599377840335e-06 -1.49774693654469e-06 2.16535175774912e-06 -4.21636611816395e-06 0.000235196077925478 -4.71377851310959e-06 1.59299984163952e-05 -1.45054401170404e-05 -0.000269327517341757 -2.37236820826069e-07 -4.71377851310959e-06 1.09184174962247e-05 5.82172455552411e-07 5.31987673509348e-06 8.71455527713687e-07 7.56599377840335e-06 1.59299984163952e-05 5.82172455552411e-07 3.9898213147449e-05 1.36339069759867e-06 -2.43242779526626e-05 -1.49774693654469e-06 -1.45054401170404e-05 5.31987673509348e-06 1.36339069759867e-06 1.53802379421194e-05 2.6548173973407e-05 2.16535175774912e-06 -0.000269327517341757 8.71455527713687e-07 -2.43242779526626e-05 2.6548173973407e-05 0.00051451153562515 3269 3200 0 35 1 3263 3209 0 0 20 0 0 0 0 0 0 0 0 370 0 1 0 0 0 3368 +51 52 0.999959405612086 0.00357386878424747 -0.00827131125256404 -0.000177577109563855 -0.0035603940740981 0.999992311645536 0.0016432418733252 -0.000436911645534961 0.0082771203906273 -0.00161372603935851 0.999964441950967 0.000267196537580493 5.72928467865922e-05 -2.32588399593962e-05 7.44623864414392e-06 -6.55747761798728e-06 -1.30895537522934e-05 2.63356082111577e-05 -2.32588399593962e-05 7.94786761076455e-05 -8.13813463502821e-06 1.74720546628625e-05 8.81464975437626e-06 -2.35251929492501e-05 7.44623864414392e-06 -8.13813463502821e-06 1.67406814888947e-05 -3.33807467984723e-06 1.59744723872891e-07 3.05677918757989e-06 -6.55747761798728e-06 1.74720546628625e-05 -3.33807467984723e-06 4.99911136839712e-05 7.66837901047593e-06 -8.24504005243424e-06 -1.30895537522934e-05 8.81464975437626e-06 1.59744723872891e-07 7.66837901047593e-06 2.90579907283955e-05 -1.21004401518686e-05 2.63356082111577e-05 -2.35251929492501e-05 3.05677918757989e-06 -8.24504005243424e-06 -1.21004401518686e-05 4.75686074778044e-05 2834 2833 0 0 4 2840 2846 0 0 6 0 0 0 0 0 0 0 0 59 0 34 37 0 0 2651 +55 56 0.999774780880371 0.0167624612587119 -0.0130156601121719 -1.12252000472822 -0.0166094918726461 0.999792736836225 0.0117731962212442 -0.0179390205262146 0.0132103101908282 -0.0115543611715058 0.999845980360266 -0.0873448021011043 6.74213355555851e-05 1.95238160759435e-06 -1.29751152509586e-07 -1.67860892394786e-05 -8.06859223494981e-06 9.09254034311783e-06 1.95238160759435e-06 7.87325773226825e-05 -2.86118736362055e-06 -2.16259011273913e-05 4.34256697366922e-06 3.95666097347875e-05 -1.29751152509586e-07 -2.86118736362055e-06 2.52791946709456e-05 2.69892073049997e-07 -2.23218499225158e-06 4.25160079418242e-06 -1.67860892394786e-05 -2.16259011273913e-05 2.69892073049997e-07 0.000336863940498862 3.38042236116285e-06 -5.2739457443591e-06 -8.06859223494981e-06 4.34256697366922e-06 -2.23218499225158e-06 3.38042236116285e-06 5.51136021396638e-05 8.7974754264431e-07 9.09254034311783e-06 3.95666097347875e-05 4.25160079418242e-06 -5.2739457443591e-06 8.7974754264431e-07 9.34676053820555e-05 1233 1233 0 0 0 1183 1183 0 0 0 0 0 0 0 0 394 266 0 7 0 504 523 0 0 1732 +52 53 0.999547119697782 0.00544560327845888 -0.0295956231358976 0.00925923449622593 -0.00563322514824443 0.99996453997516 -0.00625983759337569 -0.00822293682694823 0.029560485082245 0.00642372144476166 0.999542352041424 -0.0179430379544621 4.60511159544479e-05 -2.80736925305799e-05 4.79506596822581e-06 -8.25843209464917e-06 -7.98413996362468e-06 1.89042724130225e-05 -2.80736925305799e-05 0.000218392131993834 -2.27611551679443e-06 0.00010485387535091 1.10995101905514e-05 -5.03643067985947e-05 4.79506596822581e-06 -2.27611551679443e-06 1.35540505309149e-05 1.62382651784971e-06 -1.9178452284302e-06 -2.42105622698263e-06 -8.25843209464917e-06 0.00010485387535091 1.62382651784971e-06 0.000103150958183267 7.30848532126774e-06 -2.10405667411262e-05 -7.98413996362468e-06 1.10995101905514e-05 -1.9178452284302e-06 7.30848532126774e-06 3.03528036329945e-05 -5.06066087635129e-06 1.89042724130225e-05 -5.03643067985947e-05 -2.42105622698263e-06 -2.10405667411262e-05 -5.06066087635129e-06 5.74768974005217e-05 2404 2402 0 0 3 2414 2422 0 0 3 0 0 0 0 0 0 0 0 57 0 21 24 0 0 2710 +53 54 0.999976387547759 0.00687149036617328 8.34690477261633e-05 0.00124600696664427 -0.00687074336576706 0.9999521926025 -0.00695739858389132 -0.0066786598798494 -0.000131272754631057 0.00695666080824363 0.999975793525955 -0.0660818627250437 5.58011357360358e-05 6.4773653398012e-06 6.73531193849796e-06 4.90412153213245e-06 -9.79186627953741e-06 2.45013989193204e-05 6.4773653398012e-06 0.000226549386613313 -9.97758461790517e-06 0.000106340385614686 2.63560544130525e-06 5.63760828416403e-05 6.73531193849796e-06 -9.97758461790517e-06 1.38719803942641e-05 -3.38187442580231e-06 -7.41751532096051e-07 -2.25931106639207e-06 4.90412153213245e-06 0.000106340385614686 -3.38187442580231e-06 0.000101426324075228 5.97453172526225e-06 3.78504058428187e-05 -9.79186627953741e-06 2.63560544130525e-06 -7.41751532096051e-07 5.97453172526225e-06 2.47510862890967e-05 -3.22314073525365e-06 2.45013989193204e-05 5.63760828416403e-05 -2.25931106639207e-06 3.78504058428187e-05 -3.22314073525365e-06 6.60256990778909e-05 3126 3099 0 0 4 3123 3108 0 0 4 0 0 0 0 0 0 0 0 85 0 17 27 0 0 2935 +64 65 0.999692113752277 -0.023952893731519 0.00647584615248632 0.0620586282884003 0.0238859911870085 0.999662466443588 0.0102182488194584 -0.0002817885910334 -0.0067184169651984 -0.0100604207570443 0.99992682272638 -0.00558533214336588 3.08476756335213e-05 -3.29603337011655e-06 -3.57742355847347e-06 7.07719831001239e-07 1.44330871345315e-06 5.18630271403595e-06 -3.29603337011655e-06 2.26649528562164e-05 -1.28137199471056e-06 -1.07872849300096e-06 -6.0202525498706e-07 4.65613678759891e-06 -3.57742355847347e-06 -1.28137199471056e-06 1.15848746493615e-05 3.17752756613897e-07 1.20809506154577e-07 1.03825037161404e-06 7.07719831001239e-07 -1.07872849300096e-06 3.17752756613897e-07 4.55335211557954e-05 1.3790876977509e-06 -3.04734893041633e-06 1.44330871345315e-06 -6.0202525498706e-07 1.20809506154577e-07 1.3790876977509e-06 1.8871631460172e-05 3.11618474593565e-07 5.18630271403595e-06 4.65613678759891e-06 1.03825037161404e-06 -3.04734893041633e-06 3.11618474593565e-07 0.000203141119385805 3484 3368 0 0 106 3424 3368 0 0 127 0 0 0 0 0 0 0 0 349 0 0 0 0 0 3605 +57 58 0.998509986543461 0.0399845043441772 0.0371355111090215 0.0102595324597734 -0.0394422099731052 0.999105886766244 -0.0152229793888833 -0.00073854942169848 -0.0377109910426028 0.0137355903181246 0.999194282766468 -0.131711106644372 3.58986915683558e-05 6.35943026077695e-06 3.14185797575089e-06 4.54073403537161e-06 -6.69179599756973e-06 3.72797216455267e-05 6.35943026077695e-06 5.25589648157937e-05 -9.05336209799295e-06 1.86287603903669e-05 7.92088098951228e-06 5.72767553195214e-05 3.14185797575089e-06 -9.05336209799295e-06 1.72807600316871e-05 -3.20151524701119e-07 -4.64119128522869e-06 -9.6093386303114e-06 4.54073403537161e-06 1.86287603903669e-05 -3.20151524701119e-07 5.95277677610228e-05 1.07804157415911e-06 2.63142831936302e-05 -6.69179599756973e-06 7.92088098951228e-06 -4.64119128522869e-06 1.07804157415911e-06 3.56640706244754e-05 1.46309354132003e-05 3.72797216455267e-05 5.72767553195214e-05 -9.6093386303114e-06 2.63142831936302e-05 1.46309354132003e-05 0.000203151871576869 3309 3204 0 56 0 3326 3221 0 1 0 0 0 0 0 0 0 0 0 120 0 74 97 0 0 3136 +61 62 0.999916621435452 0.0110358813524215 0.00670518455279003 0.0551743952464379 -0.010996109637017 0.999921899836893 -0.00593968007807424 0.00793672695820878 -0.00677021048139576 0.00586545389159654 0.999959879545516 -0.0418777808322447 3.49518440611092e-05 -2.39113053164682e-06 -3.40815848322571e-07 8.11408814748824e-06 -3.21108414673578e-06 2.0600507482944e-08 -2.39113053164682e-06 2.75266381523466e-05 -3.44778738872351e-07 -6.64834685726293e-06 -3.47461044629091e-06 3.6551352256937e-06 -3.40815848322571e-07 -3.44778738872351e-07 1.10239667550243e-05 7.34950539415279e-07 1.773664789484e-06 -2.04588652731439e-06 8.11408814748824e-06 -6.64834685726293e-06 7.34950539415279e-07 3.78910123717893e-05 4.2399454146097e-06 -1.89353947003399e-05 -3.21108414673578e-06 -3.47461044629091e-06 1.773664789484e-06 4.2399454146097e-06 1.92060497011907e-05 3.52489763173124e-06 2.0600507482944e-08 3.6551352256937e-06 -2.04588652731439e-06 -1.89353947003399e-05 3.52489763173124e-06 0.000165911678243201 3312 3248 0 47 14 3306 3248 0 1 39 0 0 0 0 0 0 0 0 351 0 0 0 0 0 3422 +59 60 0.999462363541131 0.0198586045117366 0.0260886889594518 0.0345106723695305 -0.0196716735337059 0.999779090094076 -0.00740245034064577 0.00608377553969868 -0.0262299280433607 0.00688526234132493 0.999632224389216 -0.101321215795921 4.0739687579068e-05 2.60215137168501e-05 -1.41374084196046e-06 -5.61996247184764e-06 -5.5166241797659e-06 6.694647283333e-05 2.60215137168501e-05 0.000241974825755238 -1.32608942120898e-05 -1.95745962522525e-05 -2.01179032919207e-06 0.000145361188881819 -1.41374084196046e-06 -1.32608942120898e-05 1.32207423325851e-05 5.7511306867655e-07 6.77299371519267e-06 -4.25468834922032e-06 -5.61996247184764e-06 -1.95745962522525e-05 5.7511306867655e-07 4.45652397480271e-05 1.0877858044521e-06 -3.03272512714922e-05 -5.5166241797659e-06 -2.01179032919207e-06 6.77299371519267e-06 1.0877858044521e-06 1.56604189161284e-05 -1.44056338985688e-06 6.694647283333e-05 0.000145361188881819 -4.25468834922032e-06 -3.03272512714922e-05 -1.44056338985688e-06 0.000341068408039321 3302 3223 0 34 1 3306 3248 0 0 4 0 0 0 0 0 0 0 0 353 0 0 5 0 0 3146 +67 68 0.999793544184894 -0.0184130149060529 -0.00859243203515746 0.0820385142069123 0.0184306268136362 0.999828190864243 0.0019750312379305 0.00341344849963463 0.00855458949721152 -0.00213298738950793 0.999961133926379 0.0268962505700318 2.72710491963816e-05 -6.18733255769428e-06 3.02195585311003e-06 -8.51627883027992e-07 -1.78177090103593e-06 9.03370088808367e-06 -6.18733255769428e-06 3.69966564166538e-05 -6.08785678339125e-07 -2.75963684433109e-06 6.05713783860545e-07 -9.72632216704603e-06 3.02195585311003e-06 -6.08785678339125e-07 1.1722681328083e-05 8.89110859644592e-09 2.24698681607712e-06 -2.30938294812421e-06 -8.51627883027992e-07 -2.75963684433109e-06 8.89110859644592e-09 6.5162794988397e-05 3.60624750306092e-06 7.26536540112161e-06 -1.78177090103593e-06 6.05713783860545e-07 2.24698681607712e-06 3.60624750306092e-06 1.49087499498475e-05 8.63430812980028e-07 9.03370088808367e-06 -9.72632216704603e-06 -2.30938294812421e-06 7.26536540112161e-06 8.63430812980028e-07 0.000120594606296986 3336 3249 0 60 122 3330 3249 0 0 138 0 0 0 0 0 0 0 0 421 0 0 0 0 0 3370 +68 69 0.999149479965258 -0.0181910352734137 0.0370054444755825 0.0882106030364569 0.0176579223036854 0.999736275605241 0.0146825412949837 -0.000927365276253305 -0.0372627758637358 -0.0140166142360883 0.999207195760862 0.0266006120081901 3.57330355895554e-05 -9.56085463066091e-08 -3.79154226221542e-07 1.14038492222756e-05 1.36310703788357e-06 4.30751510840303e-06 -9.56085463066091e-08 2.25584980219376e-05 5.87413259613156e-07 1.12185270776413e-06 1.3483109459985e-08 -7.33558168641776e-06 -3.79154226221542e-07 5.87413259613156e-07 1.03671465471452e-05 -1.70500756177244e-06 3.09746261476367e-06 -1.5318358751278e-06 1.14038492222756e-05 1.12185270776413e-06 -1.70500756177244e-06 6.62266941706641e-05 6.95336535663932e-06 2.15246978719693e-05 1.36310703788357e-06 1.3483109459985e-08 3.09746261476367e-06 6.95336535663932e-06 1.31344619589371e-05 2.97098439095747e-06 4.30751510840303e-06 -7.33558168641776e-06 -1.5318358751278e-06 2.15246978719693e-05 2.97098439095747e-06 0.000111000393711621 3494 3396 0 110 121 3492 3396 0 0 138 0 0 0 0 0 0 0 0 355 0 0 0 0 0 3461 +63 64 0.999624893661051 -0.0256466502892766 0.00960839747683021 0.0601107701152328 0.0253773771968692 0.999308647342936 0.027170131987895 -0.0021849982230627 -0.0102985775591115 -0.0269161043721293 0.999584645052978 -0.0180140005171891 3.34473747216358e-05 -1.26765116203645e-05 -1.15377240998005e-06 1.54411414527208e-06 -1.51643178285689e-06 9.7584481940159e-06 -1.26765116203645e-05 5.92872983852497e-05 -2.79099725271589e-06 7.69694675507238e-06 2.86483446431215e-07 -2.48265582366849e-05 -1.15377240998005e-06 -2.79099725271589e-06 1.20282604819726e-05 -8.28848800809243e-07 -3.36320396541675e-07 3.71685495295384e-06 1.54411414527208e-06 7.69694675507238e-06 -8.28848800809243e-07 5.1229203801196e-05 4.28056883568265e-06 2.50656434366728e-06 -1.51643178285689e-06 2.86483446431215e-07 -3.36320396541675e-07 4.28056883568265e-06 1.85912911993942e-05 2.09209282746427e-06 9.7584481940159e-06 -2.48265582366849e-05 3.71685495295384e-06 2.50656434366728e-06 2.09209282746427e-06 0.000172597341534909 3255 3152 0 1 98 3205 3152 0 0 131 0 0 0 0 0 0 0 0 358 0 0 0 0 0 3357 +62 63 0.999462206520699 -0.0104043427985181 -0.0310973855445564 0.0613304819996557 0.0101901789337999 0.99992331435387 -0.00703744732618013 0.00141770833706342 0.0311682208358611 0.0067167747098248 0.999491584230415 -0.0192071714709891 2.95750542812899e-05 -5.19877815522955e-06 -9.13284353586969e-07 -5.93687799590532e-07 -3.61736959631699e-06 -8.41009858867678e-06 -5.19877815522955e-06 2.50401804323251e-05 -3.8215914855104e-06 -1.00567497832282e-06 1.12096589329384e-06 -3.05669311234748e-06 -9.13284353586969e-07 -3.8215914855104e-06 1.04906865877589e-05 -2.38602374443216e-07 1.61809873391408e-06 2.43826069085351e-06 -5.93687799590532e-07 -1.00567497832282e-06 -2.38602374443216e-07 3.74833297531199e-05 5.63471628647465e-06 9.64235983529404e-06 -3.61736959631699e-06 1.12096589329384e-06 1.61809873391408e-06 5.63471628647465e-06 1.67706657157198e-05 7.04340066470265e-06 -8.41009858867678e-06 -3.05669311234748e-06 2.43826069085351e-06 9.64235983529404e-06 7.04340066470265e-06 0.000118746598650835 3491 3420 0 8 72 3471 3420 0 0 86 0 0 0 0 0 0 0 0 358 0 0 0 0 0 3462 +65 66 0.999769197851281 -0.0184955832438466 -0.0109299784206734 0.0706946195022704 0.0185212592855795 0.999825929230485 0.00225259691767478 7.21399179961253e-05 0.0108864127371132 -0.00245451397778106 0.999937728750571 -0.026060117806658 2.80723953761665e-05 -5.70604565774861e-06 -1.60280179674202e-06 1.60232271367768e-06 -2.71694076623452e-06 1.60312993717381e-08 -5.70604565774861e-06 3.21970548767322e-05 -1.80422008924908e-06 -3.31389406894742e-07 5.23802871397349e-07 -2.43224360297873e-05 -1.60280179674202e-06 -1.80422008924908e-06 1.24787354037755e-05 2.07075186661898e-07 1.88539926479389e-06 1.84406219262044e-08 1.60232271367768e-06 -3.31389406894742e-07 2.07075186661898e-07 4.74256987608264e-05 5.39725073792619e-06 -8.34037879087942e-06 -2.71694076623452e-06 5.23802871397349e-07 1.88539926479389e-06 5.39725073792619e-06 1.67042920180381e-05 2.7477349245615e-06 1.60312993717381e-08 -2.43224360297873e-05 1.84406219262044e-08 -8.34037879087942e-06 2.7477349245615e-06 0.00014870392591792 3412 3307 0 27 101 3378 3307 0 0 122 0 0 0 0 0 0 0 0 361 0 0 0 0 0 3562 +69 70 0.999821520354137 0.0140162841439666 0.0126677233762336 0.0911267854970984 -0.014130050185438 0.999860231944144 0.00893634479860958 -0.0077275359127077 -0.0125406984852594 -0.00911374540999605 0.999879828042402 0.00426004382429932 3.35452984168873e-05 -5.30166136440119e-06 -8.7878881125022e-07 4.66753761849219e-07 4.74785018918293e-06 -8.0028006158121e-06 -5.30166136440119e-06 3.54501923128452e-05 -9.48102263964414e-07 3.86453344713033e-06 -5.59723174153155e-07 -1.94311243218384e-05 -8.7878881125022e-07 -9.48102263964414e-07 1.10973706000535e-05 1.46769553574191e-06 2.17843219360408e-06 2.15192806398387e-06 4.66753761849219e-07 3.86453344713033e-06 1.46769553574191e-06 6.73064514931042e-05 1.94067631004096e-06 -4.49061255788542e-06 4.74785018918293e-06 -5.59723174153155e-07 2.17843219360408e-06 1.94067631004096e-06 1.52410485317648e-05 7.2655199863265e-07 -8.0028006158121e-06 -1.94311243218384e-05 2.15192806398387e-06 -4.49061255788542e-06 7.2655199863265e-07 0.000125666258605144 3433 3344 0 148 45 3433 3344 0 25 60 0 0 0 0 0 0 0 0 332 0 0 0 0 0 3548 +70 71 0.999866320432874 0.0161137579603147 -0.00277273663036138 0.0923546299164781 -0.0161642917431968 0.999683327726374 -0.0192862629444836 -0.00672670963924143 0.00246108440850209 0.0193285040890219 0.999810157976611 -0.0160403331082332 2.72238896170816e-05 -4.50404861139552e-06 -3.45042992073447e-06 -9.04158705509638e-07 6.13259100756932e-06 -8.56368759950298e-06 -4.50404861139552e-06 3.62358638573028e-05 1.94440400550408e-06 -1.18059678945599e-05 -8.03912297767696e-07 -1.7617145391468e-05 -3.45042992073447e-06 1.94440400550408e-06 1.26354597368966e-05 -5.31725301933251e-07 2.97178641636597e-06 1.25831243944132e-06 -9.04158705509638e-07 -1.18059678945599e-05 -5.31725301933251e-07 0.00013967961202434 5.33256387276164e-06 -6.84299326605815e-06 6.13259100756932e-06 -8.03912297767696e-07 2.97178641636597e-06 5.33256387276164e-06 1.46639931561546e-05 -3.79725014068367e-06 -8.56368759950298e-06 -1.7617145391468e-05 1.25831243944132e-06 -6.84299326605815e-06 -3.79725014068367e-06 7.8602092818157e-05 3259 3181 0 158 33 3259 3181 0 39 52 0 0 0 0 0 0 0 0 734 0 0 0 0 0 3859 +71 72 0.999934065814969 -0.00245646313732209 -0.0112173888048931 0.0712549943953742 0.00222385768539305 0.999783222513888 -0.0207017496057747 -0.0075684956381152 0.0112658102123319 0.020675438776482 0.999722765446331 -0.0121552125648039 2.86815462682089e-05 -7.32759741770483e-06 -1.50443376608539e-06 3.99382456834118e-06 6.44500367139772e-06 -9.69448621144369e-06 -7.32759741770483e-06 2.58793384187072e-05 2.08691658994103e-06 -2.57425133722049e-06 -1.36514546916696e-06 3.10112361826503e-07 -1.50443376608539e-06 2.08691658994103e-06 9.68266174523173e-06 2.00045942117554e-06 1.334804280054e-06 -3.44638553641158e-07 3.99382456834118e-06 -2.57425133722049e-06 2.00045942117554e-06 0.000147608327796624 6.64252594014195e-06 9.77119958580559e-06 6.44500367139772e-06 -1.36514546916696e-06 1.334804280054e-06 6.64252594014195e-06 1.49876305863099e-05 -2.75223788772114e-06 -9.69448621144369e-06 3.10112361826503e-07 -3.44638553641158e-07 9.77119958580559e-06 -2.75223788772114e-06 0.000115294265594232 3263 3186 0 72 50 3263 3186 0 0 72 0 0 0 0 0 0 0 0 968 0 0 0 0 0 3622 +72 73 0.999943130135784 0.00906886735946265 -0.00561178572883793 0.0760226762689772 -0.00902800001030706 0.999932852400204 0.00726539101533102 -0.00696719780657367 0.00567729777832833 -0.00721431463191271 0.999957860089278 0.0072296727308825 0.00010345945098301 -1.2204698079621e-06 4.19576128627401e-06 -2.83537209923438e-05 -8.01161166129271e-06 -7.67938855694633e-06 -1.2204698079621e-06 5.30687726751038e-05 -2.65722724767879e-06 -1.108232154832e-06 1.3417704725705e-06 5.10694304967137e-05 4.19576128627401e-06 -2.65722724767879e-06 1.36293827023216e-05 -9.80039745303675e-07 5.16615734803576e-07 -3.48244255667542e-06 -2.83537209923438e-05 -1.108232154832e-06 -9.80039745303675e-07 0.000187886679569727 1.1280743811827e-05 -4.71960762298712e-05 -8.01161166129271e-06 1.3417704725705e-06 5.16615734803576e-07 1.1280743811827e-05 2.02373806897139e-05 8.82076032308738e-07 -7.67938855694633e-06 5.10694304967137e-05 -3.48244255667542e-06 -4.71960762298712e-05 8.82076032308738e-07 0.00051530829092955 3221 3149 0 111 30 3221 3149 0 1 54 0 0 0 0 0 0 0 0 1164 0 0 0 0 0 3841 +66 67 0.996836678431402 -0.0249689311475055 -0.0754532239947382 0.0781452931961595 0.0253277294936294 0.999671971860316 0.00380194629174888 0.00127777606849048 0.0753335426788528 -0.00570097835980249 0.997142094284057 -0.0189299566796695 3.01323418524971e-05 -1.07414576297151e-05 -2.24722684870091e-06 -3.0950635270086e-06 -6.80983612797879e-06 9.81561646355377e-06 -1.07414576297151e-05 5.65232877235916e-05 -3.25398868129787e-06 -4.19956203190353e-06 3.18671954007043e-06 -3.40203989814056e-06 -2.24722684870091e-06 -3.25398868129787e-06 1.08313417018121e-05 8.14128370332759e-07 2.04311957683881e-06 2.0687446868277e-07 -3.0950635270086e-06 -4.19956203190353e-06 8.14128370332759e-07 4.69000473571272e-05 8.87590498423254e-06 -1.26303064609116e-05 -6.80983612797879e-06 3.18671954007043e-06 2.04311957683881e-06 8.87590498423254e-06 1.60187700736354e-05 -9.34517035810728e-07 9.81561646355377e-06 -3.40203989814056e-06 2.0687446868277e-07 -1.26303064609116e-05 -9.34517035810728e-07 0.00020710703016839 3298 3194 0 2 127 3275 3194 0 0 145 0 0 0 0 0 0 0 0 485 0 0 0 0 0 3489 +73 74 0.999243580780629 0.0189293210586286 0.0339697964810828 0.0729344049480621 -0.0191117368576535 0.99980458391625 0.00505326571017789 -0.00937962754475228 -0.0338675033474661 -0.00569866513432862 0.999410084716327 -0.000758049518380656 6.42314634876598e-05 1.60937977183801e-05 4.01175924895022e-06 1.4686777071773e-05 2.18676398313859e-06 6.02621072984238e-05 1.60937977183801e-05 4.96978234322954e-05 -8.85320500773306e-07 -1.2681106670815e-06 1.48893869182691e-07 3.95484223440599e-05 4.01175924895022e-06 -8.85320500773306e-07 1.27292960816465e-05 5.30286153534666e-06 5.891900695529e-06 4.13282837028597e-06 1.4686777071773e-05 -1.2681106670815e-06 5.30286153534666e-06 0.0003417611854492 2.50364042339338e-05 5.02001374145792e-05 2.18676398313859e-06 1.48893869182691e-07 5.891900695529e-06 2.50364042339338e-05 1.63151606753932e-05 8.617334168592e-06 6.02621072984238e-05 3.95484223440599e-05 4.13282837028597e-06 5.02001374145792e-05 8.617334168592e-06 0.000399142145370101 3299 3235 0 130 0 3299 3240 0 27 23 0 0 0 0 0 0 0 0 1206 0 0 1 0 0 3723 +79 80 0.999238411456729 0.0159805280099834 0.0355980307595158 0.137886511621125 -0.0167878505840203 0.999605958227186 0.0224965852848322 -0.000900698787155747 -0.0352244963370934 -0.0230770665646926 0.9991129484981 -0.0164357634287438 5.32121411053373e-05 -6.55924671810584e-06 3.75777777517983e-06 -3.56745284820326e-06 2.57560473441057e-07 7.75692700569033e-06 -6.55924671810584e-06 0.000118642256435237 3.99871032915183e-06 1.59644058271978e-05 1.36116302798181e-06 -0.000126595718206117 3.75777777517983e-06 3.99871032915183e-06 1.24436647762646e-05 -4.00956247564111e-06 4.02853549471231e-07 -5.66922526010723e-06 -3.56745284820326e-06 1.59644058271978e-05 -4.00956247564111e-06 0.000242459724578577 9.23647543690865e-06 -4.02192893922695e-06 2.57560473441057e-07 1.36116302798181e-06 4.02853549471231e-07 9.23647543690865e-06 1.44263203425935e-05 -9.63846173594846e-06 7.75692700569033e-06 -0.000126595718206117 -5.66922526010723e-06 -4.02192893922695e-06 -9.63846173594846e-06 0.000417274339474076 3199 3138 0 210 83 3199 3138 0 111 106 0 0 0 0 0 0 0 0 1854 0 0 0 0 0 3856 +74 75 0.999987445325203 0.00319819308728427 0.00385755789987216 0.114407670553462 -0.00322500051659885 0.999970555884109 0.00696324180919258 -0.0052090697911173 -0.00383517452567105 -0.00697559501417603 0.999968315753332 0.00620696028043598 3.76559645130065e-05 3.19612008591557e-06 -2.97069599939617e-07 6.86933832370543e-06 7.57147466168198e-06 -4.35415617016053e-06 3.19612008591557e-06 4.32548621337514e-05 4.83086884861433e-07 2.80686030056174e-06 1.22769288206318e-06 -2.93908247619188e-05 -2.97069599939617e-07 4.83086884861433e-07 1.13421268676939e-05 -2.03129750360673e-06 2.69738033896176e-06 -1.81056754897687e-06 6.86933832370543e-06 2.80686030056174e-06 -2.03129750360673e-06 0.000102880377593224 1.16185573851185e-06 9.82056020381203e-06 7.57147466168198e-06 1.22769288206318e-06 2.69738033896176e-06 1.16185573851185e-06 1.47478248303998e-05 -7.97374096331774e-07 -4.35415617016053e-06 -2.93908247619188e-05 -1.81056754897687e-06 9.82056020381203e-06 -7.97374096331774e-07 0.000136731779708132 3344 3288 0 145 88 3344 3288 0 54 113 0 0 0 0 0 0 0 0 1157 0 0 0 0 0 3739 +75 76 0.999939958449759 -0.00386234227438952 -0.0102548431314425 0.109841065727493 0.00379524354484197 0.999971316630662 -0.00655454364362427 -0.000321829113133824 0.0102798648789936 0.00651523047146481 0.999925935332199 -0.00270447165329133 2.82942053892045e-05 -1.19449816894859e-06 6.19681530957602e-08 1.18710670991037e-05 3.25215816840211e-06 -4.49428576743858e-06 -1.19449816894859e-06 5.44924528461226e-05 -3.21224544107367e-08 7.9178312871579e-06 -1.31068537879486e-06 -4.37069796380554e-05 6.19681530957602e-08 -3.21224544107367e-08 1.15690750876235e-05 9.74530104417944e-07 3.60350929661143e-06 2.31524311781713e-06 1.18710670991037e-05 7.9178312871579e-06 9.74530104417944e-07 0.000185279878349683 8.9983049184629e-06 3.40834081912336e-05 3.25215816840211e-06 -1.31068537879486e-06 3.60350929661143e-06 8.9983049184629e-06 1.32361550143339e-05 2.36886437751009e-06 -4.49428576743858e-06 -4.37069796380554e-05 2.31524311781713e-06 3.40834081912336e-05 2.36886437751009e-06 0.000135151217238577 3319 3268 0 115 99 3319 3268 0 29 124 0 0 0 0 0 0 0 0 1922 0 0 0 0 0 3836 +76 77 0.999791737257536 -0.0146552465100364 -0.0142023188701159 0.146193841292004 0.0148621228888431 0.999783363779734 0.014571987253539 0.00597150129038418 0.0139856860680951 -0.0147800290598647 0.999792954229122 0.018980287641422 3.36098270850951e-05 -6.13238209849517e-06 2.68575471980586e-06 -4.86682308509956e-06 3.17567233123102e-06 1.14091850554901e-05 -6.13238209849517e-06 3.34495448600414e-05 -2.27117146241882e-06 -2.6340750672178e-06 1.78062593799107e-07 -7.65481402885126e-06 2.68575471980586e-06 -2.27117146241882e-06 1.10273329233521e-05 2.27174277030707e-06 6.56860025901144e-07 4.10907827806427e-06 -4.86682308509956e-06 -2.6340750672178e-06 2.27174277030707e-06 0.000117374894375175 -4.20727027370178e-06 3.43268342792274e-06 3.17567233123102e-06 1.78062593799107e-07 6.56860025901144e-07 -4.20727027370178e-06 1.46439356882771e-05 5.19473316817273e-07 1.14091850554901e-05 -7.65481402885126e-06 4.10907827806427e-06 3.43268342792274e-06 5.19473316817273e-07 0.000123288740860099 3471 3410 0 125 164 3471 3410 0 22 196 0 0 0 0 0 0 0 0 1977 0 0 0 0 0 3711 +77 78 0.999937599465826 -0.0111587179360826 0.000529328390634944 0.108563547157986 0.0111561275940348 0.999926876013512 0.00466727361146061 0.00806730605578222 -0.00058137047379367 -0.00466107711602905 0.999988968123394 -0.0231778327620405 4.25267449780086e-05 -7.75417590527562e-06 2.31454639568432e-06 6.87505564476066e-07 -1.78485457131782e-06 4.0486153859585e-06 -7.75417590527562e-06 0.00011520088890288 -3.6626790463121e-06 2.71911797769555e-06 3.18960192396665e-08 -7.51312666822582e-05 2.31454639568432e-06 -3.6626790463121e-06 1.17688320780881e-05 5.87747687696188e-07 2.36611264787048e-06 3.54748573648354e-06 6.87505564476066e-07 2.71911797769555e-06 5.87747687696188e-07 0.000152774350672233 4.15286784277375e-06 2.84847728697399e-05 -1.78485457131782e-06 3.18960192396665e-08 2.36611264787048e-06 4.15286784277375e-06 1.42245831380372e-05 -1.05209403553758e-06 4.0486153859585e-06 -7.51312666822582e-05 3.54748573648354e-06 2.84847728697399e-05 -1.05209403553758e-06 0.000223561930020035 3161 3096 0 77 127 3161 3096 0 0 154 0 0 0 0 0 0 0 0 1977 0 0 0 0 0 3759 +78 79 0.999757095632747 -0.00626623366852105 0.021130169132933 0.121214303410458 0.00647821210539149 0.999929228208975 -0.00997854404814622 0.00797738579072718 -0.0210661458243415 0.010113005933684 0.999726935023306 -0.0127540120635443 4.04238614557617e-05 -6.04069874500896e-06 1.86409158311874e-06 8.83430224676695e-06 5.41787871773205e-06 2.74659438481145e-07 -6.04069874500896e-06 2.96591831818009e-05 8.60553242702663e-07 -6.20827887306536e-07 -7.68870600385309e-07 6.90144784444338e-06 1.86409158311874e-06 8.60553242702663e-07 1.1027291312157e-05 -3.0812034224827e-06 1.97773333481013e-06 1.04253027315786e-06 8.83430224676695e-06 -6.20827887306536e-07 -3.0812034224827e-06 0.000163123022809271 6.70491031635097e-06 1.48267675032134e-05 5.41787871773205e-06 -7.68870600385309e-07 1.97773333481013e-06 6.70491031635097e-06 1.35832238169952e-05 2.87542185589908e-06 2.74659438481145e-07 6.90144784444338e-06 1.04253027315786e-06 1.48267675032134e-05 2.87542185589908e-06 0.000190645257897876 3418 3352 0 121 127 3418 3352 0 16 156 0 0 0 0 0 0 0 0 1903 0 0 0 0 0 3811 +80 81 0.999174432929729 0.0391847197297537 0.0107242864217264 0.130356539380436 -0.0390189632954611 0.999122062198777 -0.0152520598939812 -0.0020569857434608 -0.0113125188575327 0.0148210177573196 0.999826167065923 -0.0114906748563699 6.74467630463155e-05 -1.16571386122042e-05 4.0416694034142e-06 2.32640283510807e-05 1.95333821292048e-06 -4.15442518626919e-06 -1.16571386122042e-05 2.39039414409683e-05 -2.85722854309714e-06 -5.10930953434528e-06 -1.3568817669376e-07 -1.37510161104318e-05 4.0416694034142e-06 -2.85722854309714e-06 1.67208919023011e-05 7.89390737298496e-06 1.95353049939493e-06 7.36615704705713e-08 2.32640283510807e-05 -5.10930953434528e-06 7.89390737298496e-06 0.00029047982193199 9.88824355147118e-06 4.03793702565487e-05 1.95333821292048e-06 -1.3568817669376e-07 1.95353049939493e-06 9.88824355147118e-06 1.46461466013398e-05 3.27425450602289e-06 -4.15442518626919e-06 -1.37510161104318e-05 7.36615704705713e-08 4.03793702565487e-05 3.27425450602289e-06 8.87213389926187e-05 3269 3223 0 264 15 3269 3224 0 164 40 0 0 0 0 0 0 0 0 1982 0 0 0 0 0 3867 +84 85 0.999962422855572 -0.0045559517676289 0.00737537662129776 0.169374322700896 0.00454517549266746 0.999988579538247 0.0014772179325735 0.0124577805545668 -0.00738202252474222 -0.00144364004187358 0.999971710423287 -0.0595884397572901 6.30154209575212e-05 -2.44693769860609e-05 6.37208704180671e-08 -2.82743073794324e-05 -3.22315020190961e-06 -2.56294775308869e-06 -2.44693769860609e-05 3.61539022267765e-05 -3.60757674955861e-06 -6.22153687703166e-06 -2.15714239044453e-06 -1.73942879067491e-05 6.37208704180671e-08 -3.60757674955861e-06 1.42004224102676e-05 1.55573136107759e-06 3.25659855105981e-06 3.12233370345512e-06 -2.82743073794324e-05 -6.22153687703166e-06 1.55573136107759e-06 0.000401047947272565 6.05686348040653e-05 -4.63663658766696e-05 -3.22315020190961e-06 -2.15714239044453e-06 3.25659855105981e-06 6.05686348040653e-05 2.30674642963113e-05 -5.40596639327872e-06 -2.56294775308869e-06 -1.73942879067491e-05 3.12233370345512e-06 -4.63663658766696e-05 -5.40596639327872e-06 0.000169536294455004 3267 3251 0 143 182 3267 3251 0 100 225 0 0 0 0 0 0 0 0 3579 0 0 0 0 0 3641 +83 84 0.999787399143064 0.0203527604313159 0.00330479312115434 0.131911104904209 -0.0204236038001079 0.999525839974992 0.0230428216610638 -0.0027731081388515 -0.00283424109143619 -0.0231054185227802 0.999729016640171 -0.0329854329671221 6.13035070614767e-05 -3.37716623947137e-05 -6.20822837777373e-07 -8.48524925693664e-06 5.3897640600412e-06 -2.30988988892764e-06 -3.37716623947137e-05 0.000166330839599475 -6.89339645554636e-06 2.45107981468804e-05 2.12548020748922e-06 -0.000190469418451581 -6.20822837777373e-07 -6.89339645554636e-06 1.48454464550124e-05 -1.16703917939887e-06 4.15733535207322e-07 4.04059260048379e-06 -8.48524925693664e-06 2.45107981468804e-05 -1.16703917939887e-06 0.00011740752852982 1.1671971333845e-05 -2.99455732196093e-05 5.3897640600412e-06 2.12548020748922e-06 4.15733535207322e-07 1.1671971333845e-05 1.68872180551814e-05 -1.30820827645079e-06 -2.30988988892764e-06 -0.000190469418451581 4.04059260048379e-06 -2.99455732196093e-05 -1.30820827645079e-06 0.000405908977113241 3073 3061 0 191 57 3073 3061 0 120 95 0 0 0 0 0 0 0 0 3509 0 0 0 0 0 3774 +89 90 0.999683326017732 -0.0239991743281144 0.00756883833187362 0.146075746665534 0.0239308233237666 0.999673145456363 0.00899544042435355 0.00746154128064621 -0.00778224756557702 -0.00881146326952589 0.999930894981187 -0.007294090920035 5.65289227364601e-05 -1.85054032538119e-06 6.83772714435952e-06 2.03098366202521e-05 6.76653866004494e-08 5.0593763514484e-06 -1.85054032538119e-06 2.75038113158668e-05 -1.70011570967781e-06 2.10492159598194e-07 1.64891974980583e-06 -1.35424509671083e-05 6.83772714435952e-06 -1.70011570967781e-06 1.77489357523303e-05 -3.56081777621384e-06 4.03877285987789e-06 4.90935633164032e-07 2.03098366202521e-05 2.10492159598194e-07 -3.56081777621384e-06 0.000155798392186824 -1.10664589684968e-07 3.59183812498618e-05 6.76653866004494e-08 1.64891974980583e-06 4.03877285987789e-06 -1.10664589684968e-07 1.12772471347586e-05 -6.28943002070086e-07 5.0593763514484e-06 -1.35424509671083e-05 4.90935633164032e-07 3.59183812498618e-05 -6.28943002070086e-07 9.53290966125572e-05 3312 3252 0 111 193 3312 3252 0 15 222 0 0 0 0 0 0 0 0 3501 0 0 0 0 0 3589 +90 91 0.999917386767494 0.00837039807116972 -0.00975479759892531 0.154419792379976 -0.00832111816018694 0.999952467298653 0.00508154857316945 -0.000994941213047013 0.00979686851141974 -0.00499995794656632 0.999939509064375 0.0178528279548733 7.13904142534118e-05 -9.6819735147482e-06 7.52258011617545e-06 1.7388170754255e-06 1.39205445385e-07 -8.98786978490623e-06 -9.6819735147482e-06 2.55398364457483e-05 -1.86891172035773e-06 -8.39787224360452e-06 -3.44393874348095e-07 4.16229663187688e-06 7.52258011617545e-06 -1.86891172035773e-06 1.52220630920534e-05 2.44623255789303e-07 4.09547767502465e-06 4.23212773918785e-07 1.7388170754255e-06 -8.39787224360452e-06 2.44623255789303e-07 7.65362985881042e-05 -2.26398085526281e-06 -1.31055645101873e-05 1.39205445385e-07 -3.44393874348095e-07 4.09547767502465e-06 -2.26398085526281e-06 1.20876743264503e-05 1.11202078729286e-06 -8.98786978490623e-06 4.16229663187688e-06 4.23212773918785e-07 -1.31055645101873e-05 1.11202078729286e-06 0.000129678909774501 3515 3452 0 220 116 3515 3452 0 121 145 0 0 0 0 0 0 0 0 3338 0 0 0 0 0 3657 +81 82 0.999677899741638 0.0232843094034088 -0.0100964203435515 0.128995806883171 -0.023699663954912 0.998786071879886 -0.0431822712136695 0.00475836054921709 0.00907869465130295 0.0434076439622446 0.999016192936368 -0.0150819159262772 4.543201975477e-05 -1.41294508650166e-05 -1.2659646596069e-07 -6.91172506875151e-06 5.73153017878665e-07 7.00008105415064e-06 -1.41294508650166e-05 3.96588864393222e-05 7.50809734306643e-09 8.98364985058461e-06 -9.08667006540842e-08 -1.38601246674282e-05 -1.2659646596069e-07 7.50809734306643e-09 1.31500337189322e-05 -5.07421970423869e-06 2.86463010469359e-06 3.74012345819959e-07 -6.91172506875151e-06 8.98364985058461e-06 -5.07421970423869e-06 0.000139728105943652 8.72642395788238e-06 -7.20193757496918e-06 5.73153017878665e-07 -9.08667006540842e-08 2.86463010469359e-06 8.72642395788238e-06 1.41935672091286e-05 6.32359418226514e-06 7.00008105415064e-06 -1.38601246674282e-05 3.74012345819959e-07 -7.20193757496918e-06 6.32359418226514e-06 0.000202773551339704 3253 3217 0 205 48 3253 3217 0 113 80 0 0 0 0 0 0 0 0 2343 0 0 0 0 0 3860 +93 94 0.998149967862573 0.0444731371157288 -0.0414581925682943 0.144045446587375 -0.0439653821278113 0.998947422968224 0.0130801880529592 -0.00586896727089271 0.0419962716237967 -0.0112332640061042 0.999054616599848 0.0507048119780386 2.79141855163234e-05 -3.45759410894039e-06 7.08259558668657e-06 -6.94417588451332e-06 3.2029537293627e-06 8.47886480136854e-06 -3.45759410894039e-06 2.41341979118028e-05 1.33661097087534e-06 -2.67414096315166e-06 -4.65246534156662e-07 -3.6150659986215e-06 7.08259558668657e-06 1.33661097087534e-06 1.2202153234761e-05 -1.60007710526889e-06 3.45649099352966e-06 1.4723772335724e-06 -6.94417588451332e-06 -2.67414096315166e-06 -1.60007710526889e-06 6.98113449065866e-05 1.77560656462777e-06 4.0068886941286e-06 3.2029537293627e-06 -4.65246534156662e-07 3.45649099352966e-06 1.77560656462777e-06 1.0873375977438e-05 5.33760558891811e-07 8.47886480136854e-06 -3.6150659986215e-06 1.4723772335724e-06 4.0068886941286e-06 5.33760558891811e-07 9.16367874217573e-05 3536 3505 0 165 7 3536 3509 0 171 36 0 0 0 0 0 0 0 0 3478 0 0 0 0 0 3809 +82 83 0.999427794312035 0.0305888592291016 -0.0144362615535722 0.139121144938831 -0.0307881638276482 0.999430778232373 -0.0137916094041132 0.000814270723811334 0.0140061745206476 0.0142281837525361 0.999800673065587 -0.00743795813604766 7.00063063658562e-05 -2.51926343192513e-05 2.69856385526785e-06 -1.11729713988171e-05 4.30834178457597e-08 1.14751367264146e-05 -2.51926343192513e-05 4.74354351136916e-05 -3.55280393432077e-06 -8.7586681703313e-06 -1.55239534995112e-06 -2.67638497931693e-05 2.69856385526785e-06 -3.55280393432077e-06 1.57591189332826e-05 -1.57690952679371e-06 1.31299008883279e-06 7.20133648985603e-06 -1.11729713988171e-05 -8.7586681703313e-06 -1.57690952679371e-06 0.000188546385989124 1.82098486843239e-05 1.35399881598403e-05 4.30834178457597e-08 -1.55239534995112e-06 1.31299008883279e-06 1.82098486843239e-05 1.79134232421922e-05 5.31825655390384e-06 1.14751367264146e-05 -2.67638497931693e-05 7.20133648985603e-06 1.35399881598403e-05 5.31825655390384e-06 0.000151946451067972 3316 3291 0 244 40 3316 3291 0 157 75 0 0 0 0 0 0 0 0 2811 0 0 0 0 0 3804 +86 87 0.999325729833401 -0.0359235947070705 -0.00758821693561018 0.147240152996833 0.0360282299808595 0.999250809763676 0.0141345615809126 0.0192955907635806 0.00707476765597608 -0.0143984210926214 0.999871308285548 0.185866404077876 7.5978556118522e-05 -4.84857860710914e-05 -4.56078990421485e-06 -9.13128932276387e-06 2.26557456678659e-06 -7.24179506350272e-05 -4.84857860710914e-05 0.000544001816940152 8.35049277330726e-06 -1.68765360412286e-06 -3.98961093504054e-06 0.000748003707680887 -4.56078990421485e-06 8.35049277330726e-06 1.8350882749777e-05 8.17498669674039e-06 2.64574666178221e-07 -9.42832267753135e-07 -9.13128932276387e-06 -1.68765360412286e-06 8.17498669674039e-06 0.000182870803948838 2.60865499626475e-06 8.13718816154865e-05 2.26557456678659e-06 -3.98961093504054e-06 2.64574666178221e-07 2.60865499626475e-06 1.49076280618112e-05 -1.62809940553785e-05 -7.24179506350272e-05 0.000748003707680887 -9.42832267753135e-07 8.13718816154865e-05 -1.62809940553785e-05 0.0037411264466799 3015 2990 0 48 233 3015 2990 0 2 277 0 0 0 0 0 0 0 0 3679 0 0 0 0 0 3191 +85 86 0.999058680902766 -0.0277721708042744 -0.0333235448541185 0.145620112996083 0.0280128657875486 0.999584583568119 0.00677787896906088 0.0133368026048711 0.0331214652935981 -0.00770498681171233 0.999421633603674 -0.0479614972754268 5.8275617125857e-05 -2.31621725303198e-05 -4.72191603594545e-06 1.45343124037835e-05 7.00889655211382e-06 -1.22423910300157e-05 -2.31621725303198e-05 8.80579687934405e-05 9.92802547777948e-07 1.71118898132726e-05 1.20554439160524e-06 7.39533315915235e-05 -4.72191603594545e-06 9.92802547777948e-07 1.36150358790908e-05 -5.01119296846996e-06 2.57644861730178e-06 -2.78141923723749e-06 1.45343124037835e-05 1.71118898132726e-05 -5.01119296846996e-06 0.000113128761991425 1.45264761698826e-05 3.3191402694573e-05 7.00889655211382e-06 1.20554439160524e-06 2.57644861730178e-06 1.45264761698826e-05 1.45505475907831e-05 7.11069421236841e-06 -1.22423910300157e-05 7.39533315915235e-05 -2.78141923723749e-06 3.3191402694573e-05 7.11069421236841e-06 0.000649375936900986 3294 3275 0 63 206 3294 3275 0 1 252 0 0 0 0 0 0 0 0 3673 0 0 0 0 0 3602 +87 88 0.998690580032352 -0.0403095035937127 -0.03150030594571 0.128798506620211 0.039897093977776 0.999111056729921 -0.0136131631940816 0.0215914878823807 0.0320210438114278 0.0123385671797278 0.999411032815417 -0.0444598278164041 6.14420922637362e-05 -5.83774761420936e-06 2.32452666045529e-06 9.64043647867375e-06 3.43702074286333e-06 1.04378744365243e-05 -5.83774761420936e-06 1.83351316960323e-05 -1.51160382196023e-06 -6.69959991312558e-06 7.51493799179136e-07 7.44885435086675e-06 2.32452666045529e-06 -1.51160382196023e-06 1.81508261694149e-05 3.47494622848462e-06 5.82240277348037e-07 -2.00629792998401e-06 9.64043647867375e-06 -6.69959991312558e-06 3.47494622848462e-06 0.000138118275079593 -3.4767040500398e-06 -2.64979124825819e-05 3.43702074286333e-06 7.51493799179136e-07 5.82240277348037e-07 -3.4767040500398e-06 1.36036449539258e-05 3.01169849084411e-06 1.04378744365243e-05 7.44885435086675e-06 -2.00629792998401e-06 -2.64979124825819e-05 3.01169849084411e-06 0.000168829595385953 3542 3505 0 6 224 3529 3505 0 0 267 0 0 0 0 0 0 0 0 3699 0 0 0 0 0 3578 +95 96 0.999509867738634 -0.0192371330512801 -0.0246973076481086 0.135592724871777 0.0197264751108532 0.999610814839758 0.0197252385307974 0.0124771380648911 0.0243082387843888 -0.0202027613796559 0.999500354156935 -0.0556749774742208 6.14943140715403e-05 -1.58556833456601e-06 1.8714091245928e-06 2.65968458997334e-05 3.97232692569568e-06 -2.57610224046595e-05 -1.58556833456601e-06 3.74830726016303e-05 -5.50833489844045e-08 7.40001882336154e-08 -1.02422296175583e-06 -1.61535470160877e-06 1.8714091245928e-06 -5.50833489844045e-08 1.42214096753791e-05 -3.69651554367759e-06 6.61126749587708e-06 2.0140284380039e-06 2.65968458997334e-05 7.40001882336154e-08 -3.69651554367759e-06 8.85466125766374e-05 2.49487950543038e-06 -1.55479776961129e-05 3.97232692569568e-06 -1.02422296175583e-06 6.61126749587708e-06 2.49487950543038e-06 1.23965695840921e-05 -3.41422457725187e-06 -2.57610224046595e-05 -1.61535470160877e-06 2.0140284380039e-06 -1.55479776961129e-05 -3.41422457725187e-06 0.00017291122655127 3072 3045 0 70 174 3072 3045 0 4 216 0 0 0 0 0 0 0 0 3226 0 0 0 0 0 3636 +88 89 0.998578392858871 -0.0523609545758932 -0.00997615914547349 0.156192637428259 0.0523341072997797 0.998625322634003 -0.00293363379946868 0.0209288011285841 0.0101160530114129 0.00240736994155102 0.999945933559127 0.00341235165709508 7.493896756053e-05 -1.82339506406992e-05 6.39384968354131e-06 1.06382151612882e-05 1.08515803435218e-06 3.07149075909709e-05 -1.82339506406992e-05 4.08472304575316e-05 -3.25329856131533e-06 -8.10965839912423e-06 -1.92101745982518e-07 -8.7469942690603e-06 6.39384968354131e-06 -3.25329856131533e-06 1.79419323528265e-05 1.07503985179785e-06 1.6050655701431e-06 3.81184639442824e-06 1.06382151612882e-05 -8.10965839912423e-06 1.07503985179785e-06 0.000175328814178067 -3.97431603369237e-06 2.28879859540022e-05 1.08515803435218e-06 -1.92101745982518e-07 1.6050655701431e-06 -3.97431603369237e-06 1.34554453396586e-05 5.3434289827409e-07 3.07149075909709e-05 -8.7469942690603e-06 3.81184639442824e-06 2.28879859540022e-05 5.3434289827409e-07 0.000170721177391314 3366 3306 0 29 283 3358 3306 0 0 319 0 0 0 0 0 0 0 0 3668 0 0 0 0 0 3512 +94 95 0.999846300700824 0.00836965979523284 0.015405316283322 0.149231746099512 -0.00895752469817575 0.999218643158368 0.0384950115733494 0.00474563476336578 -0.015071089083364 -0.0386270884181399 0.999140035387522 0.0407079532566913 5.2232030117222e-05 -1.78919516890077e-05 5.16079078567381e-06 3.37557220501145e-06 3.72979736335623e-06 -1.05784401182466e-05 -1.78919516890077e-05 5.63200745964699e-05 -5.87170572129493e-07 -7.97062282577888e-06 -1.27151586045836e-08 3.51493214114655e-05 5.16079078567381e-06 -5.87170572129493e-07 1.27596957072873e-05 -2.03150993690073e-06 4.5315126580776e-06 -1.11221192771216e-06 3.37557220501145e-06 -7.97062282577888e-06 -2.03150993690073e-06 6.49859023425424e-05 2.37703694110264e-06 1.55309950778233e-05 3.72979736335623e-06 -1.27151586045836e-08 4.5315126580776e-06 2.37703694110264e-06 1.0969623589682e-05 3.2338228385339e-06 -1.05784401182466e-05 3.51493214114655e-05 -1.11221192771216e-06 1.55309950778233e-05 3.2338228385339e-06 0.000242914956333976 3430 3405 0 170 117 3430 3405 0 112 155 0 0 0 0 0 0 0 0 3315 0 0 0 0 0 3700 +91 92 0.999293586587029 0.0247143448646486 -0.0283112868648422 0.146529967501892 -0.0247884873619412 0.999690139148689 -0.00227081112840596 -0.00714529095040425 0.0282463926960426 0.00297100097361597 0.999596575850916 -0.0449500470126304 6.11613018466535e-05 -2.78185007143437e-06 5.83456385217569e-06 8.11639594144708e-06 2.51676719469175e-06 8.61435499369769e-07 -2.78185007143437e-06 7.28554287457065e-05 1.07061982037171e-06 1.41466133173238e-05 -1.0866095160566e-06 -3.81426888376178e-05 5.83456385217569e-06 1.07061982037171e-06 1.67077574253558e-05 -2.72170841739473e-06 4.10735258609153e-06 -4.95977576855115e-06 8.11639594144708e-06 1.41466133173238e-05 -2.72170841739473e-06 8.29204259352321e-05 -4.22097781105927e-06 5.09135013791491e-05 2.51676719469175e-06 -1.0866095160566e-06 4.10735258609153e-06 -4.22097781105927e-06 1.28391589503725e-05 4.34681860689998e-06 8.61435499369769e-07 -3.81426888376178e-05 -4.95977576855115e-06 5.09135013791491e-05 4.34681860689998e-06 0.000475455856337055 3152 3178 0 263 65 3152 3178 0 159 90 0 0 0 0 0 0 0 0 3477 0 0 0 0 0 3726 +92 93 0.999344185277347 0.0321126828139657 -0.0167324521467873 0.1420992859543 -0.0326939153637041 0.998827412837466 -0.0357058435358272 -0.00338686881947247 0.0155662214601311 0.0362294764922659 0.999222256448759 0.0402625166549696 6.07815752069602e-05 -3.91910849788521e-05 9.43721081425657e-06 8.08202769462203e-06 1.7684516761596e-07 -4.25572888481654e-05 -3.91910849788521e-05 8.93680159815328e-05 -3.39913741970919e-06 -3.55187861745121e-05 6.4830416287823e-07 4.48554854514435e-05 9.43721081425657e-06 -3.39913741970919e-06 1.51153091046356e-05 3.21461116184581e-06 4.32389645382143e-06 -9.02664963165885e-07 8.08202769462203e-06 -3.55187861745121e-05 3.21461116184581e-06 9.75685957435743e-05 -7.92688148424264e-08 -3.79484969577705e-06 1.7684516761596e-07 6.4830416287823e-07 4.32389645382143e-06 -7.92688148424264e-08 1.22724097519911e-05 1.00227531477101e-05 -4.25572888481654e-05 4.48554854514435e-05 -9.02664963165885e-07 -3.79484969577705e-06 1.00227531477101e-05 0.000303719636186902 3365 3418 0 211 34 3365 3418 0 214 62 0 0 0 0 0 0 0 0 3492 0 0 0 0 0 3769 +102 103 0.998535159460961 0.0534585280629836 0.00834991602421485 0.172019967197404 -0.0533645643763703 0.998513427948476 -0.0110976337794616 -0.0120722366292719 -0.00893076643925275 0.0106357878844025 0.999903556062726 -0.0190329279389117 4.54785703755002e-05 -8.78884026214954e-07 5.34110455755243e-06 -1.8708194470996e-05 -1.00314747481941e-06 -6.81418932859174e-06 -8.78884026214954e-07 4.60557086889938e-05 3.09817810205798e-06 1.43764347979207e-05 4.8319706778959e-06 4.993865791466e-05 5.34110455755243e-06 3.09817810205798e-06 2.65021902066339e-05 -8.06763731113436e-06 5.87667224750487e-07 7.19419278739584e-06 -1.8708194470996e-05 1.43764347979207e-05 -8.06763731113436e-06 0.000147498048873813 1.31198496730866e-05 6.79995351854998e-05 -1.00314747481941e-06 4.8319706778959e-06 5.87667224750487e-07 1.31198496730866e-05 1.79836721416294e-05 1.0005203024622e-05 -6.81418932859174e-06 4.993865791466e-05 7.19419278739584e-06 6.79995351854998e-05 1.0005203024622e-05 0.000165948608119028 3348 3307 0 366 17 3348 3307 0 267 43 0 0 0 0 0 0 0 0 2940 0 0 0 0 0 3798 +100 101 0.999434636592055 0.00963629626577151 -0.0322110070377358 0.0897531188958767 -0.00979731472566093 0.999940268617145 -0.00484477265073218 -0.000415139314515423 0.0321623973651396 0.00515761496713482 0.999469348806444 -0.00560884566159655 3.76388028499143e-05 1.74514219406902e-07 -4.64506009591521e-07 4.7565355189115e-05 -2.88615663104401e-06 -6.96635846804457e-06 1.74514219406902e-07 2.59203135586835e-05 -4.78774138657322e-07 1.57412447487286e-05 -1.84429609354569e-06 6.61579571307564e-07 -4.64506009591521e-07 -4.78774138657322e-07 2.54187121351525e-05 2.4090040391304e-05 1.4061463071499e-07 -1.35884201837203e-05 4.7565355189115e-05 1.57412447487286e-05 2.4090040391304e-05 0.000940531997946938 -3.21111132622994e-05 -0.000308626164766946 -2.88615663104401e-06 -1.84429609354569e-06 1.4061463071499e-07 -3.21111132622994e-05 1.71410546847207e-05 1.24771880204421e-05 -6.96635846804457e-06 6.61579571307564e-07 -1.35884201837203e-05 -0.000308626164766946 1.24771880204421e-05 0.000204893496872653 3566 3575 0 95 52 3566 3575 0 84 71 0 0 0 0 0 0 0 0 2953 0 0 0 0 0 3746 +96 97 0.999382548354762 -0.0342756070396157 0.00772688850747195 0.200043388104515 0.034179049369919 0.999340033364075 0.0123000121974903 0.0230146907877762 -0.00814337940352116 -0.0120283198309498 0.999894496881513 0.0721423718602581 7.2073205756925e-05 -5.67671526063708e-06 -8.10315439256019e-06 -1.78897856962785e-05 2.44470937892116e-06 -3.6142376266264e-06 -5.67671526063708e-06 2.47327078382972e-05 3.61980728344523e-06 -4.07756603386788e-06 -7.60539075193466e-08 -6.88846941079849e-06 -8.10315439256019e-06 3.61980728344523e-06 1.50907369128333e-05 -5.39003497402478e-06 3.18867597445488e-06 -4.41124061184929e-06 -1.78897856962785e-05 -4.07756603386788e-06 -5.39003497402478e-06 0.000187895598397787 7.74790965307647e-06 3.49147036159472e-05 2.44470937892116e-06 -7.60539075193466e-08 3.18867597445488e-06 7.74790965307647e-06 1.32275842516806e-05 -4.69117869198696e-07 -3.6142376266264e-06 -6.88846941079849e-06 -4.41124061184929e-06 3.49147036159472e-05 -4.69117869198696e-07 8.14389282934765e-05 3404 3369 0 140 299 3404 3369 0 52 331 0 0 0 0 0 0 0 0 3023 0 0 0 0 0 3516 +98 99 0.998195155962636 -0.0351258529028118 -0.0487093940690941 0.121903825839566 0.0353644619226891 0.999366294647427 0.00404523863220906 0.0159851941702736 0.0485364342082002 -0.00576051911921774 0.998804801236873 -0.0121253035614427 0.000100957213229387 -2.36349783582256e-05 -1.41005455746165e-05 3.98142764429365e-06 8.36536286493437e-06 -3.20091912978767e-05 -2.36349783582256e-05 3.29582450347147e-05 2.96545544032987e-06 -1.76436730606499e-06 -2.91732927354607e-06 2.89795829360421e-05 -1.41005455746165e-05 2.96545544032987e-06 2.30587186278412e-05 -1.8955579995991e-05 3.82310945050757e-07 -3.53403094412534e-06 3.98142764429365e-06 -1.76436730606499e-06 -1.8955579995991e-05 0.000151180772652482 3.13240335937937e-06 2.35343638665407e-05 8.36536286493437e-06 -2.91732927354607e-06 3.82310945050757e-07 3.13240335937937e-06 1.54461434243286e-05 -5.30983541640778e-06 -3.20091912978767e-05 2.89795829360421e-05 -3.53403094412534e-06 2.35343638665407e-05 -5.30983541640778e-06 0.000227769752641254 3625 3612 0 36 198 3610 3612 0 16 227 0 0 0 0 0 0 0 0 2877 0 0 0 0 0 3603 +101 102 0.99865739273242 0.0466561067618594 0.0225082127836027 0.162427091726838 -0.0469909693961305 0.998788830876159 0.0145849275708339 -0.0173306092853136 -0.0218004755933875 -0.015623028479156 0.999640265418036 0.0192110545249258 5.06894185047181e-05 1.69632360469352e-06 -4.45117301196793e-06 1.70247590140622e-05 1.65768958467731e-06 2.38269905669087e-05 1.69632360469352e-06 2.51868930059957e-05 -1.24082764258844e-06 1.52190860487143e-06 -1.47250648687154e-06 8.75174877356002e-06 -4.45117301196793e-06 -1.24082764258844e-06 2.35072087790608e-05 -1.74687836823983e-05 -4.32276724699401e-06 -2.84951320560825e-06 1.70247590140622e-05 1.52190860487143e-06 -1.74687836823983e-05 0.000159480920940031 8.63479522033955e-06 3.57465443118528e-05 1.65768958467731e-06 -1.47250648687154e-06 -4.32276724699401e-06 8.63479522033955e-06 1.64991841774518e-05 2.58343938592277e-06 2.38269905669087e-05 8.75174877356002e-06 -2.84951320560825e-06 3.57465443118528e-05 2.58343938592277e-06 8.94237002839647e-05 3637 3585 0 257 11 3637 3586 0 244 35 0 0 0 0 0 0 0 0 2855 0 0 0 0 0 3785 +97 98 0.99872165809095 -0.0340495109249368 -0.0373588070719047 0.103624754469516 0.0342446740956293 0.999402909271247 0.0045964373432931 0.0191100798753171 0.0371799940310286 -0.00586990169758372 0.99929134505304 -0.0425485293742204 5.78562038441044e-05 -3.05830713965699e-07 -9.89955722385733e-06 4.25546469500172e-05 3.77523166704243e-06 2.4950053817824e-06 -3.05830713965699e-07 4.82628612525121e-05 1.3002461143678e-05 7.19420477701689e-05 5.16997121039561e-07 -1.39850723858855e-05 -9.89955722385733e-06 1.3002461143678e-05 2.4645831494137e-05 -3.19950144700689e-06 9.36424875304265e-07 -1.26459045233485e-05 4.25546469500172e-05 7.19420477701689e-05 -3.19950144700689e-06 0.000746985533180476 4.57176798687063e-06 -4.48100737003517e-05 3.77523166704243e-06 5.16997121039561e-07 9.36424875304265e-07 4.57176798687063e-06 1.48669006209944e-05 -1.15997970762591e-06 2.4950053817824e-06 -1.39850723858855e-05 -1.26459045233485e-05 -4.48100737003517e-05 -1.15997970762591e-06 0.000117980795457364 3312 3281 0 1 181 3246 3271 0 0 217 0 0 0 0 0 0 0 0 3175 0 0 0 0 0 3624 +99 100 0.999138924378483 -0.0229027440362953 -0.0345958683575937 0.152672927974297 0.0221829039085695 0.999532306800795 -0.0210496184208978 0.00950282680927448 0.0350617821279977 0.0202640562842233 0.99917968326869 -0.0671552712103402 6.20445225402677e-05 8.62146631904898e-06 -6.44971022703611e-06 -6.4977610128253e-06 4.42907727815984e-06 9.48581195202461e-06 8.62146631904898e-06 7.74963111272159e-05 8.01944232388066e-06 2.0815937662907e-05 -1.31292312668373e-06 4.33797355207881e-05 -6.44971022703611e-06 8.01944232388066e-06 2.72549686482048e-05 -2.31863251353945e-05 1.62929646357795e-06 -9.71102790288538e-06 -6.4977610128253e-06 2.0815937662907e-05 -2.31863251353945e-05 0.000359036281580087 -1.67952424216461e-05 -3.24689608582754e-05 4.42907727815984e-06 -1.31292312668373e-06 1.62929646357795e-06 -1.67952424216461e-05 1.79125551825535e-05 -3.49539010953002e-07 9.48581195202461e-06 4.33797355207881e-05 -9.71102790288538e-06 -3.24689608582754e-05 -3.49539010953002e-07 0.000226604408639223 3305 3315 0 112 200 3305 3315 0 45 226 0 0 0 0 0 0 0 0 3044 0 0 0 0 0 3586 +103 104 0.999027053707133 0.0417374197265119 0.0142454819440238 0.126157674940421 -0.0421379200273281 0.998688555394111 0.0290786007330758 -0.00885124032838674 -0.0130131340197139 -0.0296505837951988 0.999475613120995 -0.0115909452432683 7.10788390963528e-05 1.20411628350536e-05 -9.3805085227506e-06 1.24446807114673e-05 9.61289141369932e-06 3.1202711548604e-05 1.20411628350536e-05 3.15900404270454e-05 5.27910043951651e-07 1.69764525043602e-06 3.7463907625632e-06 3.01745064889905e-05 -9.3805085227506e-06 5.27910043951651e-07 2.06899701922012e-05 -1.34062268211679e-05 -6.84790764205793e-06 -4.19090653986929e-06 1.24446807114673e-05 1.69764525043602e-06 -1.34062268211679e-05 7.94751723669131e-05 1.06746984716613e-05 2.5617412146951e-05 9.61289141369932e-06 3.7463907625632e-06 -6.84790764205793e-06 1.06746984716613e-05 2.0255917590248e-05 5.56777981255338e-06 3.1202711548604e-05 3.01745064889905e-05 -4.19090653986929e-06 2.5617412146951e-05 5.56777981255338e-06 0.000128568718200932 3636 3599 0 268 0 3636 3609 0 176 28 0 0 0 0 0 0 0 0 3297 0 0 0 0 0 3821 +104 105 0.997937316290735 0.0381008122410853 0.0516666319883016 0.114972194369877 -0.0399861988428523 0.998552865660441 0.0359621799036229 -0.00642147401723406 -0.0502216751666539 -0.0379539535212107 0.99801667358595 -0.0558121864240443 5.19887334140322e-05 -1.95779864231578e-06 4.44157971412802e-06 6.1930156849482e-06 -8.09792630644652e-07 1.28675233695073e-05 -1.95779864231578e-06 2.94191164590087e-05 1.20068427446976e-06 -1.71173937269715e-06 -1.21867042769446e-06 1.64845757906015e-05 4.44157971412802e-06 1.20068427446976e-06 2.11756602247847e-05 -1.44273471906602e-05 -5.97428305000288e-06 -3.28862651865611e-07 6.1930156849482e-06 -1.71173937269715e-06 -1.44273471906602e-05 0.000117725088304689 2.06748157249472e-05 9.26513624486794e-08 -8.09792630644652e-07 -1.21867042769446e-06 -5.97428305000288e-06 2.06748157249472e-05 2.10147616288634e-05 -8.01224417496109e-07 1.28675233695073e-05 1.64845757906015e-05 -3.28862651865611e-07 9.26513624486794e-08 -8.01224417496109e-07 0.000107482951375386 3441 3421 0 230 4 3441 3430 0 155 34 0 0 0 0 0 0 0 0 3106 0 0 0 0 0 3833 +106 107 0.999561596138987 -0.0229822236214662 0.0186663580136387 0.129788158635955 0.0227508542068573 0.999662839711927 0.0125142131971894 0.015128358444483 -0.018947668905138 -0.012084051328065 0.999747448882247 0.0205553016935816 0.000106672762047601 -4.52836354950754e-06 -1.68028507221845e-05 -1.04495463948273e-05 5.38510815793797e-06 -1.92570534500581e-05 -4.52836354950754e-06 8.44456619471827e-05 -5.91960214578182e-07 9.97584656444335e-06 -1.16523703063948e-06 0.000124086495071906 -1.68028507221845e-05 -5.91960214578182e-07 2.31478618915515e-05 -5.99705589549761e-06 9.14533247567996e-07 8.00998476359914e-06 -1.04495463948273e-05 9.97584656444335e-06 -5.99705589549761e-06 0.000118823309953943 9.5728078118235e-06 1.30627572852961e-05 5.38510815793797e-06 -1.16523703063948e-06 9.14533247567996e-07 9.5728078118235e-06 2.13472177908485e-05 -1.50295579513524e-05 -1.92570534500581e-05 0.000124086495071906 8.00998476359914e-06 1.30627572852961e-05 -1.50295579513524e-05 0.00037966193889374 3366 3320 0 57 185 3366 3320 0 4 218 0 0 0 0 0 0 0 0 3141 0 0 0 0 0 3626 +110 111 0.999527682381904 -0.0286406613805931 0.0111411250752507 0.101838255562646 0.0284191979667259 0.999404840860527 0.0195528323133034 0.00888084421173928 -0.011694500382155 -0.0192269753270326 0.999746748972251 -0.0666155007918995 6.64227044414233e-05 2.57012906681611e-06 -7.34443289127937e-07 -6.82773191717079e-06 4.9686110116432e-06 3.71550531915548e-06 2.57012906681611e-06 2.25667718466676e-05 -8.59948175381527e-07 3.00205878464721e-07 1.01671964607838e-06 -2.4099963245067e-06 -7.34443289127937e-07 -8.59948175381527e-07 1.45054618492121e-05 -2.84314029187846e-06 3.06809517926637e-06 -2.63463960079083e-06 -6.82773191717079e-06 3.00205878464721e-07 -2.84314029187846e-06 0.000164610808869677 -6.3575752496857e-06 -1.39036209765348e-06 4.9686110116432e-06 1.01671964607838e-06 3.06809517926637e-06 -6.3575752496857e-06 1.45991652483242e-05 6.51923285214774e-08 3.71550531915548e-06 -2.4099963245067e-06 -2.63463960079083e-06 -1.39036209765348e-06 6.51923285214774e-08 9.01338138979793e-05 3407 3317 0 23 145 3391 3317 0 0 140 0 0 0 0 0 0 0 0 3649 0 0 0 0 0 3154 +113 114 0.999413721935933 0.0337330697932763 -0.00585597203618512 0.144427497610424 -0.0337667714337485 0.999413171018573 -0.00575488849078158 -0.0113754438636843 0.0056584055269678 0.00594925179516657 0.999966293856933 0.0163508089424566 8.42594499051354e-05 -8.64789477549876e-06 1.44808616793949e-06 8.74435404680536e-06 1.17039586291833e-05 -2.70128781517138e-05 -8.64789477549876e-06 3.57821524518007e-05 1.9340039333948e-06 -7.15193219180488e-06 -1.29687706410548e-06 7.61591930700827e-06 1.44808616793949e-06 1.9340039333948e-06 1.64069179776967e-05 -6.62621745172579e-06 -2.16271149181314e-06 1.71960960429968e-06 8.74435404680536e-06 -7.15193219180488e-06 -6.62621745172579e-06 5.46398742683543e-05 7.26293098777777e-06 2.76000476499001e-05 1.17039586291833e-05 -1.29687706410548e-06 -2.16271149181314e-06 7.26293098777777e-06 1.67089876805325e-05 -2.02612620201375e-06 -2.70128781517138e-05 7.61591930700827e-06 1.71960960429968e-06 2.76000476499001e-05 -2.02612620201375e-06 0.000147143883133607 3651 3587 0 290 32 3651 3587 0 196 32 0 0 0 0 0 0 0 0 3493 0 4 4 0 0 3417 +105 106 0.99902729617785 0.00337000912483333 0.0439670846210257 0.189741599180106 -0.00393852747298197 0.999909674378421 0.0128503340728843 0.0136322744011758 -0.0439198075236955 -0.0130110000745026 0.998950331289871 -0.0525442662994552 6.06163651454057e-05 1.7142796447152e-05 -8.10997796913785e-06 -1.17440084725238e-05 2.18741619420776e-06 3.09454729743302e-05 1.7142796447152e-05 3.52867779337339e-05 1.43430385258641e-06 7.87934343750172e-06 6.21897063507378e-07 1.62464955878816e-05 -8.10997796913785e-06 1.43430385258641e-06 2.23309818588557e-05 -5.94205642538889e-06 -1.37709778110673e-06 3.50490608171853e-06 -1.17440084725238e-05 7.87934343750172e-06 -5.94205642538889e-06 0.000160539372480473 1.50804313608383e-05 4.49222493990312e-05 2.18741619420776e-06 6.21897063507378e-07 -1.37709778110673e-06 1.50804313608383e-05 1.84821336566738e-05 7.31692472084177e-07 3.09454729743302e-05 1.62464955878816e-05 3.50490608171853e-06 4.49222493990312e-05 7.31692472084177e-07 9.6600290828049e-05 3221 3210 0 202 189 3221 3210 0 140 236 0 0 0 0 0 0 0 0 3000 0 0 0 0 0 3631 +108 109 0.998764102440499 -0.0449443980637457 0.0212195371983419 0.132477037052509 0.0449814962425089 0.998987007866031 -0.00127401360294403 0.0234509822259775 -0.0211407821995642 0.00222692558539637 0.999774028533662 -0.00463964521659154 9.00031750026012e-05 -1.56496750555544e-05 -3.3873083857829e-06 5.59807555510857e-06 1.11932647957064e-06 -2.3389381611131e-05 -1.56496750555544e-05 7.9408182519883e-05 -6.50201450382832e-06 2.08402198930106e-05 -2.97417632165418e-07 0.000123407938514875 -3.3873083857829e-06 -6.50201450382832e-06 1.98340931512133e-05 -1.36582078731246e-05 -1.48788966916153e-06 -8.83155236999877e-06 5.59807555510857e-06 2.08402198930106e-05 -1.36582078731246e-05 0.000112725355517537 5.30593449504338e-06 0.00011513340706721 1.11932647957064e-06 -2.97417632165418e-07 -1.48788966916153e-06 5.30593449504338e-06 1.62334641958265e-05 6.13586123394768e-06 -2.3389381611131e-05 0.000123407938514875 -8.83155236999877e-06 0.00011513340706721 6.13586123394768e-06 0.000457020722845155 3521 3452 0 10 199 3502 3452 0 0 201 0 0 0 0 0 0 0 0 3391 0 0 0 0 0 3296 +115 116 0.999444902330245 0.00755940126171346 0.0324459960342064 0.131770660130761 -0.00811639169962062 0.999821363007528 0.01706945399088 -0.0107024993529693 -0.0323111651270217 -0.0173233231896436 0.999327719560406 -0.00877359855263507 3.40717906666045e-05 -1.50495602959524e-06 1.0163634527361e-05 -2.38569284329441e-06 -1.18664954196323e-06 1.03976565870119e-05 -1.50495602959524e-06 2.12496919041622e-05 1.05492623210581e-06 -6.53250342348428e-07 -1.03088844436813e-06 9.47210575742567e-06 1.0163634527361e-05 1.05492623210581e-06 1.30083676231523e-05 -1.72948548665028e-06 5.68704840041427e-07 2.8005040069125e-06 -2.38569284329441e-06 -6.53250342348428e-07 -1.72948548665028e-06 4.78023411944905e-05 2.65735699021291e-06 1.91124822794224e-05 -1.18664954196323e-06 -1.03088844436813e-06 5.68704840041427e-07 2.65735699021291e-06 1.28888222390709e-05 -3.17787024794408e-06 1.03976565870119e-05 9.47210575742567e-06 2.8005040069125e-06 1.91124822794224e-05 -3.17787024794408e-06 0.000112440658204144 3725 3676 0 177 79 3725 3676 0 109 86 0 0 0 0 0 0 0 0 3609 0 0 0 0 0 3370 +107 108 0.998759508181733 -0.0446967760138026 -0.0219463671379697 0.164155889466755 0.044481331271236 0.998958050347664 -0.0102090554868348 0.0258386168959325 0.0223798119947677 0.00922018761016699 0.999707023160042 -0.0457434247928975 8.97280138287353e-05 -2.35242727268125e-05 -7.84756583184683e-06 1.58358371349651e-05 2.72733378939726e-06 -5.64959979171245e-05 -2.35242727268125e-05 9.39900845659967e-05 -1.96860173758827e-07 -1.70716388533514e-06 -1.23602026744966e-06 0.000119450856842006 -7.84756583184683e-06 -1.96860173758827e-07 2.39779159080965e-05 -1.69250304914783e-05 1.50372470927736e-07 5.14268903424008e-06 1.58358371349651e-05 -1.70716388533514e-06 -1.69250304914783e-05 0.000187341647135048 1.41739372713922e-05 1.58463871920484e-05 2.72733378939726e-06 -1.23602026744966e-06 1.50372470927736e-07 1.41739372713922e-05 1.91337196740978e-05 -9.57826220251274e-06 -5.64959979171245e-05 0.000119450856842006 5.14268903424008e-06 1.58463871920484e-05 -9.57826220251274e-06 0.000408113678920295 3432 3375 0 36 218 3432 3375 0 0 219 0 0 0 0 0 0 0 0 3225 0 0 0 0 0 3495 +109 110 0.999028265840688 -0.0402334946925586 0.0179941645032979 0.120263340197671 0.040570975298268 0.998999768428287 -0.0188004958332661 0.019234462016234 -0.0172197565225299 0.0195122675528292 0.999661318347495 -0.0560357521272057 6.87740790889826e-05 2.65050326406358e-07 -1.86517414325488e-06 -4.88122583843534e-06 6.57072949100109e-06 1.41888845262392e-05 2.65050326406358e-07 4.02518144787213e-05 4.82047748755286e-06 1.01694967734904e-05 5.34744304309299e-07 2.48398242193183e-05 -1.86517414325488e-06 4.82047748755286e-06 1.88362863699662e-05 -8.73949165946454e-06 2.10575129620651e-06 -1.35209326693767e-06 -4.88122583843534e-06 1.01694967734904e-05 -8.73949165946454e-06 9.74877227304191e-05 -1.02097708385593e-06 3.87621909131823e-05 6.57072949100109e-06 5.34744304309299e-07 2.10575129620651e-06 -1.02097708385593e-06 1.47135543102943e-05 5.66337760211338e-06 1.41888845262392e-05 2.48398242193183e-05 -1.35209326693767e-06 3.87621909131823e-05 5.66337760211338e-06 0.000143423285519359 3459 3380 0 11 178 3439 3380 0 0 178 0 0 0 0 0 0 0 0 3577 0 0 0 0 0 3190 +114 115 0.999618686524606 0.0268793176474104 0.00632327712756675 0.123868927222451 -0.0270257765543028 0.999338241149524 0.0243451674427051 -0.0162564695109759 -0.00566471115409171 -0.024506775777039 0.999683614444367 -0.0450486163428893 4.85766436214978e-05 -2.68945601495711e-07 1.11490389176214e-05 -9.85302457605347e-06 3.31280124270139e-07 -9.84424630920947e-06 -2.68945601495711e-07 3.00767058801809e-05 5.30952308531756e-06 -2.19391639391898e-06 6.99932503044957e-07 -5.28202716721412e-06 1.11490389176214e-05 5.30952308531756e-06 1.49723421742026e-05 -2.35529856251085e-06 3.0223683875617e-06 -6.56815380052811e-06 -9.85302457605347e-06 -2.19391639391898e-06 -2.35529856251085e-06 6.39765201264479e-05 3.11953290964985e-06 3.05022153948294e-05 3.31280124270139e-07 6.99932503044957e-07 3.0223683875617e-06 3.11953290964985e-06 1.23709539704858e-05 2.94773618431668e-06 -9.84424630920947e-06 -5.28202716721412e-06 -6.56815380052811e-06 3.05022153948294e-05 2.94773618431668e-06 7.98015768294227e-05 3506 3455 0 222 37 3506 3455 0 139 46 0 0 0 0 0 0 0 0 3561 0 1 2 0 0 3420 +116 117 0.999766209568181 -0.00793541303805298 0.0201135632245465 0.146000118187888 0.00786287038207105 0.999962304032664 0.00368317567335871 -0.000997301882585504 -0.020142032544584 -0.00352416424157137 0.999790917537948 0.0230317772057218 0.000102829227389425 -3.62524714174218e-05 3.45663151719893e-06 -6.21274446273896e-06 1.09164814922056e-06 -2.26748580708753e-05 -3.62524714174218e-05 9.14939283166143e-05 1.365907890608e-06 -1.21113589849494e-05 -5.87224198278758e-07 1.31516431357796e-05 3.45663151719893e-06 1.365907890608e-06 1.56952526148893e-05 -5.31136099952385e-06 5.72583174158405e-06 -3.67537911439777e-06 -6.21274446273896e-06 -1.21113589849494e-05 -5.31136099952385e-06 5.99901667539842e-05 2.38959904235483e-06 5.35381000406982e-05 1.09164814922056e-06 -5.87224198278758e-07 5.72583174158405e-06 2.38959904235483e-06 1.26806904837511e-05 5.38612890434766e-06 -2.26748580708753e-05 1.31516431357796e-05 -3.67537911439777e-06 5.35381000406982e-05 5.38612890434766e-06 0.000250878369920497 3154 3115 0 140 153 3154 3115 0 72 160 0 0 0 0 0 0 0 0 3646 0 0 0 0 0 3309 +111 112 0.999071618471314 0.0262156985448693 0.0341853523444284 0.156710326828738 -0.0264158889556756 0.999636359582955 0.00541750961412053 -0.00182573155174817 -0.0340308973697373 -0.00631551656970437 0.999400826632972 -0.00169648003008315 8.01527864537694e-05 1.46990389598002e-05 1.12872846946166e-05 2.26734420624104e-05 -6.80521761721106e-06 3.80101198948574e-06 1.46990389598002e-05 4.63332633242742e-05 -3.62879994883451e-06 1.96706628969827e-05 1.74153307527664e-06 3.87265279335797e-05 1.12872846946166e-05 -3.62879994883451e-06 2.11536999281996e-05 -1.67070659243685e-06 9.08079647182882e-07 -1.60512571987238e-05 2.26734420624104e-05 1.96706628969827e-05 -1.67070659243685e-06 0.000159790167190544 -4.10076836246216e-06 7.70774813697198e-05 -6.80521761721106e-06 1.74153307527664e-06 9.08079647182882e-07 -4.10076836246216e-06 1.59591450023167e-05 7.37197968116767e-06 3.80101198948574e-06 3.87265279335797e-05 -1.60512571987238e-05 7.70774813697198e-05 7.37197968116767e-06 0.000226505392562806 3364 3281 0 280 55 3364 3281 0 170 49 0 0 0 0 0 0 0 0 3510 0 0 0 0 0 3250 +112 113 0.998718351560428 0.0429553747609268 0.0267673314988484 0.129596693945131 -0.0423605256456076 0.998851085421979 -0.022407476840602 -0.00466745459974169 -0.0276990996866095 0.0212448801004531 0.99939052174116 -0.044681286916387 7.91107744820081e-05 -4.81702683640721e-06 3.222133341165e-06 -2.62270324761337e-06 -1.01277742959096e-06 -1.450356077619e-06 -4.81702683640721e-06 4.87329919462827e-05 3.54358917909612e-06 7.6013269972173e-06 1.71937041121269e-06 3.57943739118929e-05 3.222133341165e-06 3.54358917909612e-06 1.76565653391382e-05 -1.19879122589823e-06 3.80341604623557e-06 1.46284434057735e-06 -2.62270324761337e-06 7.6013269972173e-06 -1.19879122589823e-06 7.62370551855248e-05 2.3946616628594e-06 6.23571618362598e-05 -1.01277742959096e-06 1.71937041121269e-06 3.80341604623557e-06 2.3946616628594e-06 1.47854792942618e-05 1.21229027722239e-05 -1.450356077619e-06 3.57943739118929e-05 1.46284434057735e-06 6.23571618362598e-05 1.21229027722239e-05 0.000245532786569095 3473 3401 0 281 16 3471 3399 0 184 13 0 0 0 0 0 0 0 0 3473 0 18 19 0 0 3378 +120 121 0.998285617653053 -0.0271202336902913 0.05186828039993 0.124749010186301 0.0278352770193458 0.999526507277334 -0.0131132987165782 0.00470199728301258 -0.0514880854209792 0.0145345854621974 0.998567835895551 -0.0423187431812365 6.19292837145252e-05 -9.68013886708513e-06 7.15713666718796e-06 6.83554877346808e-07 7.37024088828786e-07 -8.96821867217203e-06 -9.68013886708513e-06 3.1902951838839e-05 -2.10885288753012e-06 -2.37389669389421e-06 -1.25994794675469e-06 1.45888578644965e-05 7.15713666718796e-06 -2.10885288753012e-06 1.47281007243e-05 -1.46922180720786e-06 3.45279460921531e-06 3.43905531561293e-06 6.83554877346808e-07 -2.37389669389421e-06 -1.46922180720786e-06 5.95543086117966e-05 2.67923155099805e-06 1.73083839410807e-05 7.37024088828786e-07 -1.25994794675469e-06 3.45279460921531e-06 2.67923155099805e-06 1.21114997584284e-05 8.58580236890734e-07 -8.96821867217203e-06 1.45888578644965e-05 3.43905531561293e-06 1.73083839410807e-05 8.58580236890734e-07 0.000160822200682151 3377 3325 0 74 184 3377 3325 0 5 215 0 0 0 0 0 0 0 0 3682 0 0 0 0 0 3439 +117 118 0.998982917177843 -0.0328851261583626 -0.0308496298907214 0.131974370382106 0.0329646108314677 0.999454373146115 0.00207133576127477 0.00647502751683268 0.0307646813663948 -0.0030861750848955 0.999521890657613 -0.0899961545757425 5.86702652643294e-05 -9.56974294895606e-06 -5.90280077959395e-07 -5.03355324979708e-07 -2.27457568543786e-07 7.23146540651103e-06 -9.56974294895606e-06 3.84390011235596e-05 9.05416533650343e-07 -1.78850747779773e-06 -1.36096322119179e-06 2.44937042270853e-05 -5.90280077959395e-07 9.05416533650343e-07 1.32246001954586e-05 -2.03627584217e-06 5.81923736280949e-06 2.06361786191764e-06 -5.03355324979708e-07 -1.78850747779773e-06 -2.03627584217e-06 4.24922841993415e-05 -2.40622316293018e-06 2.62497558870041e-05 -2.27457568543786e-07 -1.36096322119179e-06 5.81923736280949e-06 -2.40622316293018e-06 1.25003504501029e-05 -2.96129086250734e-06 7.23146540651103e-06 2.44937042270853e-05 2.06361786191764e-06 2.62497558870041e-05 -2.96129086250734e-06 0.00037052464586577 3264 3225 0 39 201 3264 3225 0 0 206 0 0 0 0 0 0 0 0 3726 0 0 0 0 0 3284 +122 123 0.999447670035876 0.0331981003510515 0.00149699463573875 0.141050055500532 -0.0331883665871005 0.999430403096953 -0.00611569200837822 -0.00894069954167949 -0.00169917130924062 0.00606263132168082 0.999980178462713 -0.0337185945483191 4.88126999097467e-05 1.31648132153297e-05 9.65519005702526e-06 -3.00042085107245e-06 1.8394536175431e-06 1.08908714817002e-06 1.31648132153297e-05 4.55421609310503e-05 3.28612236753878e-06 -3.37650723019951e-07 1.25894861012372e-06 2.94185251471622e-06 9.65519005702526e-06 3.28612236753878e-06 1.61150948954615e-05 -4.36439538778108e-06 3.00235573119075e-06 2.00647784564266e-06 -3.00042085107245e-06 -3.37650723019951e-07 -4.36439538778108e-06 4.94332882032216e-05 6.5725553549739e-06 2.60669292306058e-05 1.8394536175431e-06 1.25894861012372e-06 3.00235573119075e-06 6.5725553549739e-06 1.3203221834057e-05 -4.85132094502933e-06 1.08908714817002e-06 2.94185251471622e-06 2.00647784564266e-06 2.60669292306058e-05 -4.85132094502933e-06 0.00016700866396529 3392 3350 0 267 35 3392 3350 0 176 61 0 0 0 0 0 0 0 0 3509 0 0 0 0 0 3599 +123 124 0.998994097072264 0.0405650507139129 -0.0191120557593589 0.135738774808172 -0.0412264517802507 0.998515882756141 -0.0355866766829286 -0.00988608017028652 0.0176401158834582 0.0363388021858495 0.999183825813507 -0.024306522285443 4.07986045804402e-05 1.11476596079085e-06 5.98457638427771e-06 -2.83814864149492e-06 4.45007902894724e-06 -7.05933229330762e-06 1.11476596079085e-06 3.83663829604998e-05 7.91069120147471e-07 -2.74141753091072e-06 -1.51290628771043e-06 -7.73492060760565e-07 5.98457638427771e-06 7.91069120147471e-07 1.29893368230083e-05 -1.88026806401882e-07 3.97611175600472e-06 4.45376825771924e-06 -2.83814864149492e-06 -2.74141753091072e-06 -1.88026806401882e-07 4.22106574244906e-05 4.30137225568457e-06 2.05679674560812e-05 4.45007902894724e-06 -1.51290628771043e-06 3.97611175600472e-06 4.30137225568457e-06 1.21803654272174e-05 4.78452248513458e-06 -7.05933229330762e-06 -7.73492060760565e-07 4.45376825771924e-06 2.05679674560812e-05 4.78452248513458e-06 0.000131674866242079 3481 3446 0 271 11 3481 3453 0 193 30 0 0 0 0 0 0 0 0 3529 0 0 0 0 0 3626 +119 120 0.998466243050314 -0.0443320760893575 -0.0331636626234066 0.120628689607547 0.0436263987864783 0.998812039146771 -0.0217082423146808 0.0138936562202495 0.0340866369405209 0.0202281359763363 0.999214153070806 -0.0945744668080888 6.50676941422425e-05 -1.72321817433931e-05 8.51221643736018e-06 -5.1438897327704e-06 3.27481028798994e-06 -1.83659360762104e-05 -1.72321817433931e-05 5.91465448680587e-05 -6.65269219576691e-06 1.36325457519612e-05 1.92884855520383e-06 3.77254527696103e-05 8.51221643736018e-06 -6.65269219576691e-06 1.78962121156347e-05 -6.43171630392361e-06 3.77230458458502e-06 -4.87742826650071e-06 -5.1438897327704e-06 1.36325457519612e-05 -6.43171630392361e-06 6.43776825430137e-05 3.55316570888191e-06 7.19311104253126e-05 3.27481028798994e-06 1.92884855520383e-06 3.77230458458502e-06 3.55316570888191e-06 1.29592822760368e-05 -3.49474833859791e-06 -1.83659360762104e-05 3.77254527696103e-05 -4.87742826650071e-06 7.19311104253126e-05 -3.49474833859791e-06 0.000320605620094651 3301 3262 0 2 216 3275 3262 0 0 247 0 0 0 0 0 0 0 0 3744 0 0 0 0 0 3365 +118 119 0.996849640257127 -0.0445121031573893 -0.0656465337374487 0.128215894979214 0.0453201081312071 0.99891337165437 0.0108703141202715 0.0111036760584813 0.0650913398096225 -0.0138111767276948 0.997783728509933 -0.124993875152099 5.31703731674119e-05 -1.2154936225154e-06 2.71561327334941e-06 7.59758564350131e-06 8.64060144916924e-07 2.97643962906917e-05 -1.2154936225154e-06 4.47466684661973e-05 -1.05130080096858e-06 1.20918904563881e-05 -3.73641502081006e-07 6.65862333034681e-05 2.71561327334941e-06 -1.05130080096858e-06 1.73908879665283e-05 -2.22949009426185e-06 3.47816925613771e-06 -1.75138954885044e-06 7.59758564350131e-06 1.20918904563881e-05 -2.22949009426185e-06 6.11533451083398e-05 2.09437281275038e-06 0.000106136024557753 8.64060144916924e-07 -3.73641502081006e-07 3.47816925613771e-06 2.09437281275038e-06 1.46234512380893e-05 -9.53224594551044e-06 2.97643962906917e-05 6.65862333034681e-05 -1.75138954885044e-06 0.000106136024557753 -9.53224594551044e-06 0.000556482994929637 3197 3168 0 13 229 3173 3168 0 0 243 0 0 0 0 0 0 0 0 3742 0 0 0 0 0 3297 +127 128 0.999192588614153 -0.0191002918144106 0.0353461413898793 0.151937973321242 0.0184245578033479 0.999643077703223 0.0193456162936223 0.0159839059382014 -0.03570303248045 -0.0186787593975975 0.999187868931097 0.0446903977869316 3.80812186677039e-05 -5.73099859649739e-06 1.16128250938588e-05 -7.08300038388879e-06 2.26123241763964e-07 1.03718103894993e-05 -5.73099859649739e-06 3.33024734029275e-05 1.9662936430885e-07 3.13777871429173e-06 -1.95908686254955e-06 4.97958645574331e-06 1.16128250938588e-05 1.9662936430885e-07 1.42800328568554e-05 -5.60774801567327e-06 1.98257823960003e-06 -1.37470439466596e-06 -7.08300038388879e-06 3.13777871429173e-06 -5.60774801567327e-06 9.21008087596207e-05 7.14355751511148e-06 3.49452155825437e-05 2.26123241763964e-07 -1.95908686254955e-06 1.98257823960003e-06 7.14355751511148e-06 1.3653943230469e-05 4.75973641402845e-06 1.03718103894993e-05 4.97958645574331e-06 -1.37470439466596e-06 3.49452155825437e-05 4.75973641402845e-06 0.000188393054974017 3362 3354 0 97 197 3362 3354 0 37 245 0 0 0 0 0 0 0 0 3678 0 0 0 0 0 3485 +130 131 -0.220642835603051 0.0088586559902011 0.975314443300771 0.295281837625584 0.0867751237978699 0.996171713127319 0.0105828094023422 0.024636324124442 -0.971486910352841 0.0869680526344543 -0.220566862502193 0.0375153936846847 0.000307698765719115 -0.00356472540982201 3.93379876707784e-05 4.25169322115624e-05 3.06244500372073e-06 0.00232029045491589 -0.00356472540982201 0.0554010277351995 -0.000307716639790251 -0.00348024408695579 0.00011831354520127 -0.0391479567922391 3.93379876707784e-05 -0.000307716639790251 5.68752353127491e-05 -8.4571695588159e-05 1.11062983916878e-07 0.0004998618605787 4.25169322115624e-05 -0.00348024408695579 -8.4571695588159e-05 0.00407908401082649 -0.000213957010697857 0.000767972185630455 3.06244500372073e-06 0.00011831354520127 1.11062983916878e-07 -0.000213957010697857 2.70213487675168e-05 -5.78672662807648e-05 0.00232029045491589 -0.0391479567922391 0.0004998618605787 0.000767972185630455 -5.78672662807648e-05 0.0352172948893319 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2561 0 0 0 0 0 2069 +121 122 0.99962831077941 -0.00323018721326705 0.0270703930313361 0.139666035541776 0.00289178627724148 0.999917307212887 0.0125306148394983 -0.00581344959127373 -0.027108630736917 -0.0124476755539475 0.999554989739371 -0.0300675621182679 4.4873206729492e-05 -1.97847953791409e-06 1.04422907488381e-05 -1.64897160115049e-05 -2.644944877699e-06 -1.27720482367771e-05 -1.97847953791409e-06 3.96361516834371e-05 -2.39824687244016e-06 5.78396513474924e-06 1.27608417618516e-06 3.4240035325474e-05 1.04422907488381e-05 -2.39824687244016e-06 1.48481787455778e-05 -2.35743438563162e-06 3.55363587255596e-07 3.02723455079913e-06 -1.64897160115049e-05 5.78396513474924e-06 -2.35743438563162e-06 7.47062100011189e-05 2.59431579160361e-06 5.19267119257964e-05 -2.644944877699e-06 1.27608417618516e-06 3.55363587255596e-07 2.59431579160361e-06 1.45661292107006e-05 -5.29634239082614e-06 -1.27720482367771e-05 3.4240035325474e-05 3.02723455079913e-06 5.19267119257964e-05 -5.29634239082614e-06 0.000243035539654366 3358 3307 0 167 126 3358 3307 0 77 157 0 0 0 0 0 0 0 0 3601 0 0 0 0 0 3512 +124 125 0.999072496532541 0.0429062119287334 -0.00363368272715688 0.125183947545129 -0.042867331459102 0.999028950008944 0.0101758998424294 -0.0176000642448867 0.00406676355478201 -0.0100106953781588 0.999941622002122 -0.0567620928480525 3.04009782005754e-05 -1.70108286298336e-06 1.26252192530815e-05 -9.28768695988035e-06 3.81977873278288e-07 -1.24390423325279e-05 -1.70108286298336e-06 2.06799417462542e-05 -2.88424429714023e-06 -4.71792340999087e-06 1.87592343009941e-06 4.07847501120757e-06 1.26252192530815e-05 -2.88424429714023e-06 1.58655766157436e-05 -3.29951738632405e-06 8.84397820595394e-08 -7.38296688805917e-06 -9.28768695988035e-06 -4.71792340999087e-06 -3.29951738632405e-06 7.74409054234279e-05 7.10202977480404e-06 3.88636737014792e-05 3.81977873278288e-07 1.87592343009941e-06 8.84397820595394e-08 7.10202977480404e-06 1.62621406517728e-05 1.04638855567842e-05 -1.24390423325279e-05 4.07847501120757e-06 -7.38296688805917e-06 3.88636737014792e-05 1.04638855567842e-05 0.000115785643277541 3679 3652 0 266 0 3679 3666 0 192 18 0 0 0 0 0 0 0 0 3535 0 0 0 0 0 3601 +126 127 0.999879158123219 0.00349254562721316 0.015148309339496 0.136307719836216 -0.00360676953881947 0.999965222662338 0.00751961962829102 0.00658031249858884 -0.015121519906976 -0.00757334740403277 0.999856981795297 -0.0343929795172619 3.52401713263583e-05 -6.85342086310706e-06 7.89533625949499e-06 1.30127997684711e-06 3.44654187736176e-06 1.57445754424616e-05 -6.85342086310706e-06 2.68551612042859e-05 -6.94795042012834e-07 -3.62986845670698e-06 -1.85780995691969e-06 -6.08380452945225e-06 7.89533625949499e-06 -6.94795042012834e-07 1.31321788160376e-05 -2.5678718004865e-06 3.88220996270918e-06 1.42932342777544e-06 1.30127997684711e-06 -3.62986845670698e-06 -2.5678718004865e-06 6.55396263815453e-05 1.87377642403962e-06 1.98861263197543e-05 3.44654187736176e-06 -1.85780995691969e-06 3.88220996270918e-06 1.87377642403962e-06 1.24070875105406e-05 6.32429792171085e-06 1.57445754424616e-05 -6.08380452945225e-06 1.42932342777544e-06 1.98861263197543e-05 6.32429792171085e-06 8.45045005352858e-05 3466 3460 0 143 109 3466 3460 0 86 160 0 0 0 0 0 0 0 0 3644 0 0 0 0 0 3508 +134 135 0.998456979805515 0.0427128609660245 -0.0354862083878628 0.135625178471628 -0.0436962801253372 0.998668634818995 -0.0274151952751151 -0.0147845031491689 0.0342679818614669 0.0289235083774719 0.998994062085596 -0.0577192344794799 3.86658802612028e-05 7.46982094556691e-06 6.81267243726856e-06 -2.13051224105691e-05 2.63022266721282e-06 -1.13541995506267e-05 7.46982094556691e-06 5.16335710582129e-05 1.94834046815459e-06 -7.02589316803808e-06 -1.08469254097156e-06 2.18688752450367e-05 6.81267243726856e-06 1.94834046815459e-06 1.2109972005558e-05 2.60193478750589e-07 3.73468708116568e-06 -9.90777056123299e-06 -2.13051224105691e-05 -7.02589316803808e-06 2.60193478750589e-07 0.00020324395944998 -3.82697542226247e-07 5.55137282220376e-07 2.63022266721282e-06 -1.08469254097156e-06 3.73468708116568e-06 -3.82697542226247e-07 1.07956243531207e-05 7.87766523980478e-06 -1.13541995506267e-05 2.18688752450367e-05 -9.90777056123299e-06 5.55137282220376e-07 7.87766523980478e-06 0.000359257795375426 3410 3352 0 304 7 3411 3363 0 203 23 0 0 0 0 0 0 0 0 3479 0 0 2 0 0 3790 +131 132 0.989274649725145 -0.026311339357785 -0.143678045756442 0.136966649885186 0.0278987469226184 0.99956983558104 0.00904454070922271 0.00874782877616722 0.143378266593437 -0.0129559722789365 0.989583152368192 0.0208719962193788 9.19275449202315e-05 1.28210354558973e-05 -1.61673759583134e-05 -6.14906410842504e-06 2.01734172502704e-07 1.05980679817066e-05 1.28210354558973e-05 0.000227174537865392 5.12214606365008e-06 2.13619265773534e-05 5.98618026829827e-07 8.76732507002809e-05 -1.61673759583134e-05 5.12214606365008e-06 2.1244157329065e-05 8.23290198806978e-06 6.24409959141572e-06 -3.89956358871221e-06 -6.14906410842504e-06 2.13619265773534e-05 8.23290198806978e-06 0.000122190576352933 -2.93562240417211e-06 6.71029892301281e-05 2.01734172502704e-07 5.98618026829827e-07 6.24409959141572e-06 -2.93562240417211e-06 1.59952799153148e-05 -5.0630860155189e-06 1.05980679817066e-05 8.76732507002809e-05 -3.89956358871221e-06 6.71029892301281e-05 -5.0630860155189e-06 0.00033911536039099 2580 2509 0 54 176 2570 2509 0 2 203 0 0 0 0 0 0 0 0 3660 0 0 0 0 0 3525 +133 134 0.999116546144646 0.0420056409182919 0.00128582698600404 0.133695643069706 -0.041990328867171 0.999065605569173 -0.0102336723774433 -0.0135963305337803 -0.00171449748359164 0.0101706391021185 0.999946807884616 -0.0132971732906061 5.34084541097748e-05 4.11704985853776e-06 2.54753865591057e-06 9.18549934149552e-06 7.79005546815518e-08 -1.3610233438403e-05 4.11704985853776e-06 5.30242267216493e-05 -2.44027590455785e-06 3.86136403598565e-06 1.00440425127473e-06 -1.11621906521401e-05 2.54753865591057e-06 -2.44027590455785e-06 1.39804049420708e-05 7.45151650676341e-07 3.49833045449252e-06 -1.86414831761634e-06 9.18549934149552e-06 3.86136403598565e-06 7.45151650676341e-07 0.000248949121972335 -4.99858910721493e-06 8.54388386061827e-06 7.79005546815518e-08 1.00440425127473e-06 3.49833045449252e-06 -4.99858910721493e-06 1.23236368154305e-05 3.09702342508327e-06 -1.3610233438403e-05 -1.11621906521401e-05 -1.86414831761634e-06 8.54388386061827e-06 3.09702342508327e-06 0.000193790770054209 3299 3238 0 301 5 3299 3241 0 193 21 0 0 0 0 0 0 0 0 3462 0 0 1 0 0 3776 +125 126 0.999509303937428 0.030704863931905 0.00619376084798962 0.135340361019881 -0.0307895968017502 0.999426666153756 0.0140833131604076 -0.00494070994331064 -0.00575778354095921 -0.0142671059332878 0.999881641804161 -0.0361354721270576 3.00417360381932e-05 -7.56746239657421e-06 6.4138448525346e-06 4.20698170441523e-06 3.07642062939828e-06 1.77624751217578e-05 -7.56746239657421e-06 5.12309656004624e-05 4.44627345411623e-06 1.78103456699867e-06 -9.45046782866193e-08 7.6757446212325e-06 6.4138448525346e-06 4.44627345411623e-06 1.27735745319186e-05 -1.57011194510396e-06 3.479451061363e-06 -2.31270013147651e-06 4.20698170441523e-06 1.78103456699867e-06 -1.57011194510396e-06 4.41507824197421e-05 6.97716425252537e-07 2.64270055315267e-05 3.07642062939828e-06 -9.45046782866193e-08 3.479451061363e-06 6.97716425252537e-07 1.15248604094107e-05 5.22337088441193e-06 1.77624751217578e-05 7.6757446212325e-06 -2.31270013147651e-06 2.64270055315267e-05 5.22337088441193e-06 0.000192580527077965 3362 3358 0 225 28 3362 3358 0 161 75 0 0 0 0 0 0 0 0 3561 0 0 0 0 0 3571 +128 129 0.999222211418493 -0.0304610181046178 -0.0250419365059214 0.120900087051289 0.0308304117427415 0.999419455127344 0.0144996008474684 0.019930175059235 0.0245857259341571 -0.015260376436806 0.999581243817278 -0.0175647148023345 2.65582817363654e-05 -3.24797353900164e-06 7.71304469992296e-06 -3.42837742173196e-06 1.31150971456109e-06 4.67708345798557e-07 -3.24797353900164e-06 1.6910977376153e-05 1.11025388213778e-06 1.0271812595373e-06 -1.91847453707869e-07 1.62015508243646e-06 7.71304469992296e-06 1.11025388213778e-06 1.15627972050403e-05 -3.75338016542678e-07 2.89904518051004e-06 -1.19016041498726e-06 -3.42837742173196e-06 1.0271812595373e-06 -3.75338016542678e-07 9.86953235642214e-05 3.19844388895448e-06 1.59414131777371e-05 1.31150971456109e-06 -1.91847453707869e-07 2.89904518051004e-06 3.19844388895448e-06 1.13264786502524e-05 3.06599784219901e-07 4.67708345798557e-07 1.62015508243646e-06 -1.19016041498726e-06 1.59414131777371e-05 3.06599784219901e-07 9.54733324119918e-05 3616 3598 0 13 187 3603 3598 0 0 238 0 0 0 0 0 0 0 0 3745 0 0 0 0 0 3488 +135 136 0.998752632981438 0.0467036765932651 -0.0176619564407935 0.114905976731765 -0.0467128715624095 0.998908352115128 -0.000108189802772269 -0.0206466457419172 0.0176376229418429 0.000933095553140205 0.999844009628327 -0.011519843538696 3.46611185123963e-05 -2.61439483925594e-06 8.5544618391795e-06 -1.8913618401877e-06 -1.88540088931726e-07 -4.05439169199641e-06 -2.61439483925594e-06 2.84324477877504e-05 -1.75328773688384e-06 -1.03562049947669e-05 -1.64952906247917e-06 8.1448372532885e-06 8.5544618391795e-06 -1.75328773688384e-06 1.1178871679507e-05 1.59022379546423e-06 3.10788819859316e-06 -1.94155592075847e-07 -1.8913618401877e-06 -1.03562049947669e-05 1.59022379546423e-06 0.000183975237534264 6.00884191403998e-06 3.19024168301484e-06 -1.88540088931726e-07 -1.64952906247917e-06 3.10788819859316e-06 6.00884191403998e-06 1.21519997427079e-05 3.5412747614621e-06 -4.05439169199641e-06 8.1448372532885e-06 -1.94155592075847e-07 3.19024168301484e-06 3.5412747614621e-06 0.00017444068918293 3444 3383 0 270 0 3453 3415 0 192 0 0 0 0 0 0 0 0 0 3531 0 0 11 0 0 3813 +129 130 0.99845044757176 -0.051831144118471 -0.0202542894993138 0.159878591155163 0.0518988736201328 0.998648328720615 0.00283239483198846 0.0280709553348246 0.020080106093176 -0.00387918069868928 0.99979084877608 -0.0102322441364673 3.87066860795506e-05 2.20500040885441e-05 8.65742012858841e-06 2.73328315165875e-05 3.25863703221862e-06 1.5134810640955e-07 2.20500040885441e-05 0.00145780165339254 4.39941100637777e-05 0.000345297270934023 3.01950568444831e-05 5.83604407029408e-05 8.65742012858841e-06 4.39941100637777e-05 1.51509281593799e-05 7.93968563447698e-06 3.65733152943364e-06 -2.38450664133518e-06 2.73328315165875e-05 0.000345297270934023 7.93968563447698e-06 0.000205797002457334 9.60751296215515e-06 6.43174133356992e-05 3.25863703221862e-06 3.01950568444831e-05 3.65733152943364e-06 9.60751296215515e-06 1.40335014590187e-05 -3.44345685929486e-05 1.5134810640955e-07 5.83604407029408e-05 -2.38450664133518e-06 6.43174133356992e-05 -3.44345685929486e-05 0.000891083861625865 3276 3237 0 10 296 3261 3237 0 0 333 0 0 0 0 0 0 0 0 3716 0 0 0 0 0 3422 +132 133 0.999285520377836 0.00242699875184493 0.0377168190633209 0.175145282573417 -0.00303612901419284 0.999865757300408 0.0161012204099667 -0.00813590802907443 -0.0376726782138717 -0.016204229544773 0.999158742273246 -0.00957643243897599 6.8489871440413e-05 9.66268899883347e-06 1.50955380057166e-05 5.675011775009e-06 -5.71803663480625e-06 -6.20392666367563e-06 9.66268899883347e-06 4.73042057614943e-05 4.96129717766244e-06 -2.12848428380995e-05 7.97263453034013e-07 2.06497441079411e-06 1.50955380057166e-05 4.96129717766244e-06 1.9811407614598e-05 4.28731508796491e-06 -6.54229041916585e-07 1.86763812617943e-06 5.675011775009e-06 -2.12848428380995e-05 4.28731508796491e-06 0.000174455585824729 -9.09004262000809e-06 4.12474390887961e-06 -5.71803663480625e-06 7.97263453034013e-07 -6.54229041916585e-07 -9.09004262000809e-06 1.61742156227428e-05 -5.75111726053809e-06 -6.20392666367563e-06 2.06497441079411e-06 1.86763812617943e-06 4.12474390887961e-06 -5.75111726053809e-06 0.000148367100551154 3287 3214 0 277 150 3287 3214 0 168 167 0 0 0 0 0 0 0 0 3452 0 0 0 0 0 3582 +137 138 0.999970592242093 0.00281676815527369 0.00713305461625305 0.0369021026881173 -0.00277721675924763 0.999980749574075 -0.0055486528404355 -0.0103101646912143 -0.00714854657053915 0.00552867962817117 0.999959165158007 -0.00289456030267476 3.51271580752877e-05 -8.09724648620574e-06 9.57294156866524e-06 1.88474217892802e-05 2.13370161818923e-06 6.21139077867747e-06 -8.09724648620574e-06 2.6895181202377e-05 4.60185061088177e-07 2.35159720542359e-05 1.39651088148339e-06 3.12895528021026e-06 9.57294156866524e-06 4.60185061088177e-07 1.36687294321698e-05 -5.36553443218837e-06 2.34755073846213e-06 -1.60548398152174e-06 1.88474217892802e-05 2.35159720542359e-05 -5.36553443218837e-06 0.00139260942682893 0.000120885809388343 -5.83090595324478e-05 2.13370161818923e-06 1.39651088148339e-06 2.34755073846213e-06 0.000120885809388343 2.28725072012622e-05 -3.55447498283061e-06 6.21139077867747e-06 3.12895528021026e-06 -1.60548398152174e-06 -5.83090595324478e-05 -3.55447498283061e-06 0.000142954410228355 3525 3500 0 31 0 3525 3519 0 0 11 0 0 0 0 0 0 0 0 3759 0 0 0 0 0 3819 +139 140 0.99822612503207 -0.0219043188034842 -0.0553606730559984 0.183561822677823 0.0229382044077082 0.999572851695741 0.0181094707651884 0.0137996960793021 0.0549403502173768 -0.0193472212630223 0.998302180177621 0.0786085052299215 6.01510031604414e-05 -3.43640490381797e-06 1.10011546936372e-05 -9.69139422740114e-06 -6.85951458662688e-07 -1.13304667693863e-05 -3.43640490381797e-06 2.85732744970828e-05 4.27961967710985e-06 -1.34485321578078e-05 -1.13610478459136e-06 7.68280101469163e-06 1.10011546936372e-05 4.27961967710985e-06 1.45990678626667e-05 -7.92084243203016e-07 -2.94537607037438e-07 -2.82825290845311e-06 -9.69139422740114e-06 -1.34485321578078e-05 -7.92084243203016e-07 0.000189879210868706 2.83451935267342e-06 -1.09031972083089e-05 -6.85951458662688e-07 -1.13610478459136e-06 -2.94537607037438e-07 2.83451935267342e-06 1.17312632757665e-05 -1.29431529755058e-06 -1.13304667693863e-05 7.68280101469163e-06 -2.82825290845311e-06 -1.09031972083089e-05 -1.29431529755058e-06 0.000174205352658038 3303 3282 0 136 241 3303 3282 0 62 284 0 0 0 0 0 0 0 0 3632 0 0 0 0 0 3540 +140 141 0.999119544880717 -0.0346634935760701 -0.023634238943765 0.153764903827827 0.0344709279762185 0.999369492951781 -0.0085071547392533 0.0199549414722398 0.0239142250931864 0.00768497042290933 0.999684475756121 0.0297401657071575 4.80596076410947e-05 3.73641821634707e-06 8.72005439174506e-06 4.26705383094956e-06 2.94504904613465e-06 3.40606911099454e-06 3.73641821634707e-06 2.29237010554589e-05 2.76860507075701e-06 -4.43977397196515e-06 -3.93709498174516e-07 -8.09608374732622e-06 8.72005439174506e-06 2.76860507075701e-06 1.1066900200822e-05 -2.40467319023752e-06 3.52514080578654e-06 -5.48794111127509e-06 4.26705383094956e-06 -4.43977397196515e-06 -2.40467319023752e-06 0.000173826130849529 2.54741972898641e-07 4.14765085282265e-05 2.94504904613465e-06 -3.93709498174516e-07 3.52514080578654e-06 2.54741972898641e-07 9.46983662093748e-06 9.07397328758949e-07 3.40606911099454e-06 -8.09608374732622e-06 -5.48794111127509e-06 4.14765085282265e-05 9.07397328758949e-07 7.1686903250738e-05 3607 3574 0 52 243 3607 3574 0 0 282 0 0 0 0 0 0 0 0 3687 0 0 0 0 0 3557 +136 137 0.999127808804092 0.0398828372198883 -0.0123685475956414 0.115006100882079 -0.0396058091363963 0.998975632772909 0.0218875537376376 -0.0213207488749182 0.0132288154036974 -0.0213785972706002 0.999683927059827 -0.089421863466163 5.44563071787517e-05 -4.05630716362651e-06 7.716519199848e-06 3.21652642203172e-06 -8.33228468253118e-07 2.7418495489495e-05 -4.05630716362651e-06 8.63506495067517e-05 2.73919470774891e-06 2.19507599844686e-05 2.00490722106339e-06 0.000114158142028038 7.716519199848e-06 2.73919470774891e-06 1.53228074577623e-05 -8.77793382365031e-07 3.58580085079355e-06 -7.84322763958015e-06 3.21652642203172e-06 2.19507599844686e-05 -8.77793382365031e-07 0.000156243458546498 9.08289184531183e-07 0.000173248169089197 -8.33228468253118e-07 2.00490722106339e-06 3.58580085079355e-06 9.08289184531183e-07 1.18208527756812e-05 1.02339676691636e-05 2.7418495489495e-05 0.000114158142028038 -7.84322763958015e-06 0.000173248169089197 1.02339676691636e-05 0.00088301744964369 3293 3262 0 244 0 3293 3284 0 171 5 0 0 0 0 0 0 0 0 3550 0 0 0 0 0 3820 +143 144 0.999806329486102 0.00793608322801528 -0.018008945069782 -0.131566600012145 -0.00756922634798649 0.999764298013436 0.0203483471121202 0.0242018737186064 0.0181661865018874 -0.0202080924557564 0.999630743158332 -0.0276507621992813 2.99292678399669e-05 8.48095243323989e-06 6.68867274892108e-06 7.47713086545689e-06 1.4154182000814e-06 -1.33490984779849e-05 8.48095243323989e-06 2.92082750948829e-05 -1.09896191006959e-06 -2.37088499116329e-05 2.43380599049557e-06 1.52622745372708e-05 6.68867274892108e-06 -1.09896191006959e-06 1.35280541611032e-05 -1.24054705968531e-06 5.15494972025556e-06 2.2802700904807e-06 7.47713086545689e-06 -2.37088499116329e-05 -1.24054705968531e-06 0.000379216282499191 -2.74949182878152e-05 -6.69035489350424e-05 1.4154182000814e-06 2.43380599049557e-06 5.15494972025556e-06 -2.74949182878152e-05 1.20066626586955e-05 6.83659767451519e-06 -1.33490984779849e-05 1.52622745372708e-05 2.2802700904807e-06 -6.69035489350424e-05 6.83659767451519e-06 0.000126752052916776 3199 3199 0 0 0 3146 3146 0 0 0 0 0 0 0 0 163 75 0 3694 0 100 117 0 0 3586 +144 145 0.999071345210629 0.0393109146735709 0.017638003474076 0.270729680526818 -0.0389764735184733 0.999060980206675 -0.0189206855198619 -0.014551206493473 -0.0183652304937358 0.0182156475593096 0.999665398267294 0.0367076907669297 6.24621186734934e-05 -1.38238865355304e-05 5.57289955218475e-06 8.61054142236071e-07 1.27327599937485e-07 -6.43619773596689e-05 -1.38238865355304e-05 5.86011460262973e-05 -2.38834924709366e-06 4.74905078528897e-06 5.69507526647577e-07 4.63714030988626e-05 5.57289955218475e-06 -2.38834924709366e-06 1.39955173276138e-05 3.31640446615524e-06 4.72380657904747e-06 2.32410549444004e-06 8.61054142236071e-07 4.74905078528897e-06 3.31640446615524e-06 0.000191001953541562 -4.38205951494148e-06 7.27320305415702e-05 1.27327599937485e-07 5.69507526647577e-07 4.72380657904747e-06 -4.38205951494148e-06 1.0593677763535e-05 3.0265185092456e-06 -6.43619773596689e-05 4.63714030988626e-05 2.32410549444004e-06 7.27320305415702e-05 3.0265185092456e-06 0.000223395210772358 3581 3519 0 579 157 3581 3519 0 462 173 0 0 0 0 0 0 0 0 3183 0 0 0 0 0 3636 +148 149 0.999424394694831 -0.0241051197150163 0.023870954995449 -0.0454790870872212 0.0241301377495761 0.999708536554593 -0.0007605209135641 -0.00827508547137602 -0.0238456650369936 0.00133609258594568 0.999714758876523 -0.00932821685527613 5.573677009286e-05 -1.35119567044933e-05 4.87354871507443e-06 1.15164783976191e-05 -2.03310703942182e-08 -4.58401275197099e-06 -1.35119567044933e-05 2.56972140207288e-05 -5.46562099946639e-06 -2.2763298175987e-06 5.86342317400214e-07 3.67948188673062e-06 4.87354871507443e-06 -5.46562099946639e-06 1.4323161343078e-05 -1.9136569268269e-07 4.56594913501047e-06 5.54784738120207e-06 1.15164783976191e-05 -2.2763298175987e-06 -1.9136569268269e-07 0.000172546155748062 9.39323021585353e-06 2.60913344563084e-05 -2.03310703942182e-08 5.86342317400214e-07 4.56594913501047e-06 9.39323021585353e-06 1.16354697273995e-05 1.84834801077016e-06 -4.58401275197099e-06 3.67948188673062e-06 5.54784738120207e-06 2.60913344563084e-05 1.84834801077016e-06 8.76264490298329e-05 3255 3260 0 0 0 3219 3255 0 0 1 0 0 0 0 0 78 23 0 3672 0 0 1 0 0 3853 +138 139 0.998816761021011 -0.0291150963568705 -0.038953678486473 0.126251084356157 0.0287088654648819 0.999527862763168 -0.0109477213982066 0.0114979739948476 0.0392540309677449 0.00981645171248671 0.999181043819667 0.0244684526384907 3.3427332944205e-05 -3.83080629264808e-06 1.04447768556006e-05 -1.42064602041213e-05 -1.3265790178969e-06 9.46100028508881e-06 -3.83080629264808e-06 2.01576556360225e-05 1.73691184520958e-06 -2.53579539204455e-06 -7.11949689050077e-07 1.04221826817606e-06 1.04447768556006e-05 1.73691184520958e-06 1.26779701362084e-05 -3.06933310425336e-06 2.1634049842216e-06 2.76763328927911e-06 -1.42064602041213e-05 -2.53579539204455e-06 -3.06933310425336e-06 0.000184939116619247 5.73583445442611e-06 2.60109356038154e-05 -1.3265790178969e-06 -7.11949689050077e-07 2.1634049842216e-06 5.73583445442611e-06 1.1389276596301e-05 -1.99114016213565e-06 9.46100028508881e-06 1.04221826817606e-06 2.76763328927911e-06 2.60109356038154e-05 -1.99114016213565e-06 7.7211956923007e-05 3599 3582 0 36 171 3599 3582 0 0 221 0 0 0 0 0 0 0 0 3741 0 0 0 0 0 3594 +150 151 0.999028594313275 -0.0439677966649815 0.00294967809563612 -0.112329212943967 0.0439591193084762 0.999028990430115 0.00294484461518977 0.0138287090558364 -0.00307629225922781 -0.00281231872505639 0.999991313606935 -0.0647100069557986 2.34846484789514e-05 -2.31383064104099e-06 1.03200523760095e-05 2.09334118546759e-05 2.22120847726662e-06 -7.45583779631953e-06 -2.31383064104099e-06 2.16611458849044e-05 -1.53955284485579e-06 -1.02254278439344e-05 1.01047783316633e-06 -3.96851618097311e-06 1.03200523760095e-05 -1.53955284485579e-06 1.23313491553089e-05 8.28217849959867e-06 3.2724122222805e-06 -3.55686717399224e-07 2.09334118546759e-05 -1.02254278439344e-05 8.28217849959867e-06 0.000764546920112144 -1.49011995621773e-05 -0.000117072672564825 2.22120847726662e-06 1.01047783316633e-06 3.2724122222805e-06 -1.49011995621773e-05 1.08048072645481e-05 7.73434228378402e-07 -7.45583779631953e-06 -3.96851618097311e-06 -3.55686717399224e-07 -0.000117072672564825 7.73434228378402e-07 8.85669397498859e-05 3222 3224 0 0 0 3165 3191 0 0 6 0 0 0 0 0 229 156 0 3542 0 0 0 0 0 3795 +141 142 0.998464706224561 -0.0528340576534094 0.0166370903639024 0.178741858555144 0.0535325381804073 0.997561167044264 -0.0447882279315638 0.0228322232609587 -0.0142301714629051 0.045610090519124 0.998857958802438 0.0418525984330081 3.84649509116813e-05 1.45601358927074e-05 3.81826845237925e-06 -1.53018762649826e-05 3.83030237635055e-06 -1.54646795869416e-06 1.45601358927074e-05 5.49168123095628e-05 -2.29361098927788e-06 -6.14012555445523e-06 2.21657613404567e-06 3.87638327013839e-05 3.81826845237925e-06 -2.29361098927788e-06 9.57667154120486e-06 4.42648574075575e-07 3.40934128173355e-06 -5.06334348895213e-07 -1.53018762649826e-05 -6.14012555445523e-06 4.42648574075575e-07 0.000211474251028201 -1.06519785219057e-05 4.43180075673955e-05 3.83030237635055e-06 2.21657613404567e-06 3.40934128173355e-06 -1.06519785219057e-05 9.76671683116863e-06 1.39702354463013e-06 -1.54646795869416e-06 3.87638327013839e-05 -5.06334348895213e-07 4.43180075673955e-05 1.39702354463013e-06 0.000233663195140974 3552 3501 0 59 313 3552 3501 0 4 341 0 0 0 0 0 0 0 0 3669 0 0 0 0 0 3489 +142 143 0.999183652217295 -0.0346472336789474 0.0207749450084585 -0.0195465597950768 0.0345989295438392 0.999397683998741 0.0026801664821952 0.0233522955408746 -0.0208552922810618 -0.00195918767560539 0.999780585112315 0.022047768693145 3.10666627706104e-05 3.76264989341266e-05 2.30291890511836e-06 -9.2582810298005e-06 1.21033887901289e-06 -2.99838289643291e-05 3.76264989341266e-05 0.00165321136537724 -9.61539998428552e-06 -0.00123072903087248 7.81996757645891e-05 -0.0021829346120159 2.30291890511836e-06 -9.61539998428552e-06 1.01573056104595e-05 5.90125711325837e-06 4.49844382713594e-06 8.21992021724202e-06 -9.2582810298005e-06 -0.00123072903087248 5.90125711325837e-06 0.00110896838533314 -6.8710706877245e-05 0.0017949913731904 1.21033887901289e-06 7.81996757645891e-05 4.49844382713594e-06 -6.8710706877245e-05 1.36093071093026e-05 -0.00011575471219668 -2.99838289643291e-05 -0.0021829346120159 8.21992021724202e-06 0.0017949913731904 -0.00011575471219668 0.00311302519767134 3472 3491 0 0 70 3399 3418 0 0 95 0 0 0 0 0 92 8 0 3737 0 0 0 0 0 3721 +153 154 0.999971980669281 0.00670486458788913 -0.00332906401468453 0.177353030897059 -0.00671367470004285 0.999973971971005 -0.00264233846302087 -0.000312882857784263 0.00331126084411991 0.00266461467931582 0.999990967649325 0.0193260700065788 4.07869469692567e-05 1.27710859901323e-05 7.39129514070338e-06 5.49247608066282e-06 1.6032296905491e-06 -1.87911307891497e-05 1.27710859901323e-05 2.75278445789246e-05 2.49009172059634e-06 2.87839202885576e-06 -3.63987278489318e-07 -1.55680500664597e-05 7.39129514070338e-06 2.49009172059634e-06 1.22536975642369e-05 1.08708993497013e-06 3.73359117127699e-06 -3.60999197842209e-06 5.49247608066282e-06 2.87839202885576e-06 1.08708993497013e-06 0.000360633052355994 -1.32511501841375e-05 5.02411941447986e-05 1.6032296905491e-06 -3.63987278489318e-07 3.73359117127699e-06 -1.32511501841375e-05 1.1215777709285e-05 -1.98118156785017e-06 -1.87911307891497e-05 -1.55680500664597e-05 -3.60999197842209e-06 5.02411941447986e-05 -1.98118156785017e-06 9.23596959966223e-05 3414 3348 0 258 146 3414 3348 0 155 170 0 0 0 0 0 0 0 0 3473 0 0 0 0 0 3635 +145 146 0.998669634930298 0.0510877466793226 -0.00700017195602547 0.0713023826424077 -0.0512043293231087 0.998532524884268 -0.0176327367932244 -0.010415970196545 0.00608908258731873 0.0179677179262662 0.999820025897545 0.011029097606584 3.94252894094489e-05 1.45514660674605e-05 5.73409593366173e-07 -6.55878427034434e-06 3.56232075962672e-06 -3.79839830388184e-06 1.45514660674605e-05 3.03620317065988e-05 -2.98730597423126e-06 1.39204403634794e-06 3.15454888331499e-06 1.91561764812968e-05 5.73409593366173e-07 -2.98730597423126e-06 9.70026611352168e-06 7.50158420206716e-07 3.43706214578077e-06 -3.85161798490605e-06 -6.55878427034434e-06 1.39204403634794e-06 7.50158420206716e-07 0.00013722604776344 2.24181036555289e-06 3.58072889754228e-05 3.56232075962672e-06 3.15454888331499e-06 3.43706214578077e-06 2.24181036555289e-06 9.66822949421271e-06 7.02419105542395e-06 -3.79839830388184e-06 1.91561764812968e-05 -3.85161798490605e-06 3.58072889754228e-05 7.02419105542395e-06 0.000142020497854652 3637 3563 0 205 0 3657 3583 0 112 0 0 0 0 0 0 0 0 0 3601 0 46 76 0 0 3798 +156 157 0.998466141693132 0.0415978625632401 -0.0365374016947074 0.158665872771949 -0.0416017489967491 0.999134058312007 0.000654218152803052 -0.00660747785729952 0.0365329765122156 0.000866805139441741 0.999332072074147 -0.0511147718141199 5.07418961974183e-05 5.03731376201512e-06 8.87377339257647e-06 -2.03682594525574e-05 -7.45492140967869e-07 1.54241267267767e-05 5.03731376201512e-06 3.90772960162528e-05 3.73248447784333e-06 -5.70011901044868e-06 1.33652189191314e-07 4.0681020401406e-06 8.87377339257647e-06 3.73248447784333e-06 1.58669188363551e-05 -2.17568190052134e-06 3.84220579854703e-06 -2.08478508485611e-06 -2.03682594525574e-05 -5.70011901044868e-06 -2.17568190052134e-06 0.000306462387236973 1.87273555001359e-05 1.4797619090158e-05 -7.45492140967869e-07 1.33652189191314e-07 3.84220579854703e-06 1.87273555001359e-05 1.38337211836203e-05 4.17223979238197e-06 1.54241267267767e-05 4.0681020401406e-06 -2.08478508485611e-06 1.4797619090158e-05 4.17223979238197e-06 0.000158766353559615 3318 3295 0 313 31 3318 3295 0 217 61 0 0 0 0 0 0 0 0 3470 0 0 0 0 0 3790 +146 147 0.99749737909552 0.0616246165693326 0.034661005903633 0.161162440131084 -0.0626747891475404 0.997580777763717 0.0300742853888441 -0.0199809692139685 -0.0327238369217348 -0.0321713920901945 0.998946521105158 0.0349689820725526 4.30974141559193e-05 4.05626517040166e-07 3.12470360265999e-06 1.54971990241049e-05 4.79822487286244e-06 -2.49234802543164e-06 4.05626517040166e-07 2.18316985797273e-05 1.18258421073442e-06 -6.90748831510297e-06 2.20470191427681e-07 4.05543918723934e-06 3.12470360265999e-06 1.18258421073442e-06 9.81274097944051e-06 -4.71047603869085e-06 3.85037786499398e-06 -1.33859008127919e-06 1.54971990241049e-05 -6.90748831510297e-06 -4.71047603869085e-06 0.000500633609718853 3.53838502870707e-05 2.44222547890274e-05 4.79822487286244e-06 2.20470191427681e-07 3.85037786499398e-06 3.53838502870707e-05 1.14604127366847e-05 -4.22863782774368e-07 -2.49234802543164e-06 4.05543918723934e-06 -1.33859008127919e-06 2.44222547890274e-05 -4.22863782774368e-07 9.16830871955736e-05 3622 3580 0 405 1 3624 3599 0 312 19 0 0 0 0 0 0 0 0 3407 0 0 0 0 0 3811 +147 148 0.998317485985734 0.0318017166488887 0.048485544168421 -0.0945506509564702 -0.033577056107046 0.998778444382601 0.0362519011895432 -0.0245760260362145 -0.0472734436899661 -0.0378189086946717 0.998165793677 0.0225021194215551 6.05071991148446e-05 -7.38349934234371e-06 7.58629069270448e-06 3.68394511159352e-05 7.90835070915403e-06 -8.6372838746858e-06 -7.38349934234371e-06 4.48092737307643e-05 1.9086722494912e-06 -2.86023581349879e-05 -3.2977809436606e-06 2.92880187765712e-05 7.58629069270448e-06 1.9086722494912e-06 1.41509521526714e-05 6.37222147860289e-06 6.20605167363456e-06 -3.73936512221552e-06 3.68394511159352e-05 -2.86023581349879e-05 6.37222147860289e-06 0.00180806514949963 0.000204311557653565 -0.000485175295479528 7.90835070915403e-06 -3.2977809436606e-06 6.20605167363456e-06 0.000204311557653565 3.37959736698211e-05 -6.02502609046399e-05 -8.6372838746858e-06 2.92880187765712e-05 -3.73936512221552e-06 -0.000485175295479528 -6.02502609046399e-05 0.000281255412269113 3228 3181 0 0 0 3220 3207 0 0 0 0 0 0 0 0 0 0 0 3730 0 145 187 0 0 3711 +149 150 0.998496344664591 -0.0546601694412945 0.00416119791637643 -0.127030853801396 0.0546973845267872 0.998458472032005 -0.00942739377782217 0.00210051693319852 -0.00363948037212241 0.00964082486939325 0.99994690292958 -0.0283431429718583 3.48565559202781e-05 2.49634881799743e-06 7.00157463283891e-06 -9.87151315943591e-06 4.55074706223727e-07 2.45671455178378e-05 2.49634881799743e-06 3.91530578320452e-05 3.46845389205892e-06 -1.3990265574123e-05 4.07252339138996e-08 3.41390431345623e-05 7.00157463283891e-06 3.46845389205892e-06 1.49737815750097e-05 4.41524467473676e-06 4.83921409739039e-06 -5.73347898241035e-06 -9.87151315943591e-06 -1.3990265574123e-05 4.41524467473676e-06 0.000612733834130548 1.47326523609812e-05 -5.85713411171897e-05 4.55074706223727e-07 4.07252339138996e-08 4.83921409739039e-06 1.47326523609812e-05 1.07055023297068e-05 -3.23168062780063e-06 2.45671455178378e-05 3.41390431345623e-05 -5.73347898241035e-06 -5.85713411171897e-05 -3.23168062780063e-06 0.000248030980489205 3146 3147 0 0 0 3109 3135 0 0 0 0 0 0 0 0 246 181 0 3488 0 0 1 0 0 3825 +157 158 0.999988198072345 -0.00259184459202037 -0.00410926485346556 -0.101322350575082 0.00260956736321574 0.999987292281551 0.00431340162621327 -0.018065038509828 0.00409803296740666 -0.00432407412320774 0.999982254096929 -0.0539919489937872 2.91449565801516e-05 -8.51012670329846e-06 7.50985087606831e-06 -4.11992208123074e-06 1.21414822281245e-06 5.12840452185312e-06 -8.51012670329846e-06 2.20365871315119e-05 -4.49396862516945e-07 3.95178484211873e-06 -2.92044995573548e-07 -1.0019955185653e-05 7.50985087606831e-06 -4.49396862516945e-07 1.20542805643699e-05 -4.82120347307425e-06 3.35531450384526e-06 9.6760425988114e-07 -4.11992208123074e-06 3.95178484211873e-06 -4.82120347307425e-06 0.00361272446008272 0.000299983833159576 -0.000408113039489033 1.21414822281245e-06 -2.92044995573548e-07 3.35531450384526e-06 0.000299983833159576 3.62612950564495e-05 -3.43386361351365e-05 5.12840452185312e-06 -1.0019955185653e-05 9.6760425988114e-07 -0.000408113039489033 -3.43386361351365e-05 0.000126491930121478 3236 3236 0 0 0 3221 3221 0 0 0 0 0 0 0 0 72 13 0 3623 0 78 115 0 0 3783 +158 159 0.997952741243781 -0.034749147429755 0.0536919267388296 0.174659209322577 0.0344570384793571 0.999385962646915 0.00635689889261416 0.0139823560958181 -0.0538798547070684 -0.00449381989002319 0.998537313694156 0.125276877474457 4.60737395735903e-05 -2.93697110883074e-06 5.1171424421931e-06 -5.80194847541961e-06 1.69354770338154e-06 1.83537201995384e-05 -2.93697110883074e-06 9.23577945881337e-05 5.09839758240088e-07 0.00010785452248373 8.61164502860939e-06 0.000264098029779058 5.1171424421931e-06 5.09839758240088e-07 1.21279727155832e-05 -6.7768502335767e-06 4.16171989452185e-06 -2.94503369704065e-06 -5.80194847541961e-06 0.00010785452248373 -6.7768502335767e-06 0.00105276241596297 5.98730513396955e-05 0.00087218184371957 1.69354770338154e-06 8.61164502860939e-06 4.16171989452185e-06 5.98730513396955e-05 1.39950509519576e-05 5.85852490464503e-05 1.83537201995384e-05 0.000264098029779058 -2.94503369704065e-06 0.00087218184371957 5.85852490464503e-05 0.0015724018581274 3317 3285 0 102 256 3317 3285 0 30 300 0 0 0 0 0 0 0 0 3653 0 0 0 0 0 3533 +151 152 0.999332615182192 -0.0189688147148526 0.0312171155207366 -0.11831299446483 0.0194050957205639 0.999717389499587 -0.0137325668469695 0.0218951702576403 -0.0309478027200183 0.0143291730551461 0.999418284956984 -0.0748820595068393 4.35628919820308e-05 -3.72621175295342e-06 1.13004856233812e-05 5.57701961565323e-05 1.06655416822717e-06 -1.38926646890677e-05 -3.72621175295342e-06 3.39768771371048e-05 3.53987723330943e-06 -9.67069885602169e-06 -1.1844787080819e-06 1.11660911063577e-05 1.13004856233812e-05 3.53987723330943e-06 1.40619887835898e-05 9.89566939935773e-07 3.86717001208527e-06 1.56033398681417e-06 5.57701961565323e-05 -9.67069885602169e-06 9.89566939935773e-07 0.00182553155835038 -5.88304542606893e-05 -0.000129446184910434 1.06655416822717e-06 -1.1844787080819e-06 3.86717001208527e-06 -5.88304542606893e-05 1.31232151191579e-05 2.59152629568377e-06 -1.38926646890677e-05 1.11660911063577e-05 1.56033398681417e-06 -0.000129446184910434 2.59152629568377e-06 0.000205632494175162 3223 3223 0 0 0 3183 3183 0 0 0 0 0 0 0 0 179 98 0 3608 0 18 43 0 0 3706 +152 153 0.99957494349656 -0.0115548567115765 0.0267659787832388 0.144695828080342 0.0114817048601645 0.999929920876122 0.00288509794929896 0.00676905856484651 -0.0267974399402989 -0.00257655255096998 0.999637563614732 -0.0196915462819852 4.46860707751148e-05 1.47594343074904e-05 8.8083501700515e-06 1.48851958093084e-05 7.25235258801781e-07 -7.7075919394329e-06 1.47594343074904e-05 4.81133098501353e-05 1.13494850650876e-06 -8.64960931426975e-06 1.96162183282887e-06 2.25858804244271e-06 8.8083501700515e-06 1.13494850650876e-06 1.35047243916233e-05 -1.27597686447524e-06 4.33557439404159e-06 -3.40311112717408e-07 1.48851958093084e-05 -8.64960931426975e-06 -1.27597686447524e-06 0.000217227967684219 -6.31632374995052e-06 1.01490527859239e-05 7.25235258801781e-07 1.96162183282887e-06 4.33557439404159e-06 -6.31632374995052e-06 1.06730456681865e-05 -3.4232513761785e-06 -7.7075919394329e-06 2.25858804244271e-06 -3.40311112717408e-07 1.01490527859239e-05 -3.4232513761785e-06 0.000158812803183171 3178 3115 0 135 168 3178 3115 0 37 192 0 0 0 0 0 0 0 0 3579 0 0 0 0 0 3611 +154 155 0.998778355496419 0.0405968917392833 -0.0281724860986484 0.142199602591899 -0.0410448360807024 0.999036947865255 -0.0155080053902383 -0.00485646755483635 0.0275157777098503 0.0166453951945967 0.999482772635846 -0.117124676061785 6.41793597537148e-05 2.29193326539597e-06 2.31266424566853e-06 -1.83810496731999e-05 1.87084745771764e-06 -4.15842518291326e-05 2.29193326539597e-06 8.78938441866624e-05 4.42014238946629e-07 8.56709252398221e-06 1.32003685292027e-06 0.000134994553800906 2.31266424566853e-06 4.42014238946629e-07 1.44542098835545e-05 1.84422992935916e-06 3.39487885566979e-06 -2.80038840368049e-06 -1.83810496731999e-05 8.56709252398221e-06 1.84422992935916e-06 0.000190055457398361 -1.31372658293764e-06 0.000244173343516736 1.87084745771764e-06 1.32003685292027e-06 3.39487885566979e-06 -1.31372658293764e-06 1.15388751559066e-05 1.10641717494061e-05 -4.15842518291326e-05 0.000134994553800906 -2.80038840368049e-06 0.000244173343516736 1.10641717494061e-05 0.0011241282824122 3313 3257 0 302 22 3313 3259 0 188 40 0 0 0 0 0 0 0 0 3460 0 0 0 0 0 3775 +160 161 0.999960214068699 -0.00805831304129033 -0.00382542423933721 0.0746861232805467 0.00822541480501785 0.998912791926007 0.0458865631517084 -0.00157403181320845 0.00345149691695235 -0.0459162032132329 0.998939332217684 -0.0204281864200425 2.97736553728404e-05 8.92669996051004e-07 8.15110108203204e-06 4.94612020230196e-06 7.73967575407862e-07 -2.3853747623597e-06 8.92669996051004e-07 2.080906423861e-05 2.32373392363601e-06 -1.33826203860164e-05 -1.47984708026335e-07 -1.54123844582685e-06 8.15110108203204e-06 2.32373392363601e-06 1.08369967487366e-05 -2.78544352845455e-06 4.01605894669509e-06 -2.99288785776084e-06 4.94612020230196e-06 -1.33826203860164e-05 -2.78544352845455e-06 0.000222870648278975 5.9555749946586e-07 -9.12408982644432e-06 7.73967575407862e-07 -1.47984708026335e-07 4.01605894669509e-06 5.9555749946586e-07 1.03504016512355e-05 -2.90635464291622e-06 -2.3853747623597e-06 -1.54123844582685e-06 -2.99288785776084e-06 -9.12408982644432e-06 -2.90635464291622e-06 8.07587593543546e-05 3538 3493 0 33 69 3536 3493 0 0 101 0 0 0 0 0 0 0 0 3730 0 0 0 0 0 3726 +161 162 0.99863674832237 -0.0138466431257974 -0.0503280773949316 -0.0923770007819792 0.0146735284852242 0.999762747501937 0.0160977100598624 0.00718799545520875 0.0500932376865055 -0.0168142553068784 0.998602998371504 -0.150070994975591 4.38015600354099e-05 1.04729335070813e-06 7.72560373677888e-06 3.44724737078983e-05 1.79629751568651e-06 -1.72235203488121e-05 1.04729335070813e-06 4.6231934484598e-05 6.2342730028503e-06 0.000148498563898306 -3.82750450586703e-06 4.20947449579607e-05 7.72560373677888e-06 6.2342730028503e-06 1.39381998126252e-05 2.42065970409033e-05 3.43359243501398e-06 -8.00658099745435e-07 3.44724737078983e-05 0.000148498563898306 2.42065970409033e-05 0.00450631133738362 -7.24384197588804e-05 0.00077075723140735 1.79629751568651e-06 -3.82750450586703e-06 3.43359243501398e-06 -7.24384197588804e-05 1.27509920410028e-05 -3.09469259336023e-05 -1.72235203488121e-05 4.20947449579607e-05 -8.00658099745435e-07 0.00077075723140735 -3.09469259336023e-05 0.000607173770404155 3166 3166 0 0 0 3130 3130 0 0 0 0 0 0 0 0 128 52 0 3665 0 24 51 0 0 3757 +155 156 0.998600855060728 0.0426545367754624 -0.0312557636997326 0.0443366869396138 -0.0429070995126496 0.999051255164614 -0.00745455333470655 -0.00894609847644404 0.0309081394359866 0.00878521749754205 0.999483620110968 -0.0410826009006649 2.79726334484011e-05 -5.46430693061774e-06 1.02521442126342e-05 -2.37115374469087e-06 4.37716018485435e-07 2.28346845109452e-06 -5.46430693061774e-06 2.9502272977498e-05 -1.03363809814609e-06 -7.29896822139704e-05 -3.02244043686356e-06 2.06337930967012e-05 1.02521442126342e-05 -1.03363809814609e-06 1.3884473177232e-05 -1.41301059488095e-06 2.565559018752e-06 5.25645212289656e-06 -2.37115374469087e-06 -7.29896822139704e-05 -1.41301059488095e-06 0.00125249105300955 4.42765661038069e-05 -0.000407764230113017 4.37716018485435e-07 -3.02244043686356e-06 2.565559018752e-06 4.42765661038069e-05 1.34952485630956e-05 -1.3934297729826e-05 2.28346845109452e-06 2.06337930967012e-05 5.25645212289656e-06 -0.000407764230113017 -1.3934297729826e-05 0.000251246558740326 3520 3448 0 131 0 3543 3471 0 47 0 0 0 0 0 0 0 0 0 3659 0 44 73 0 0 3800 +162 163 0.99920616286302 -0.0346663739996088 0.0196287190177967 0.0677657417545443 0.0353257178169644 0.998786909941434 -0.0343045505780068 0.0118522754371386 -0.0184156932336681 0.0349707169409217 0.99921865034604 -0.0416568470644016 3.77493815667299e-05 -5.36808175477659e-06 7.57818797806669e-06 -9.18080647481414e-06 1.85098020826861e-06 1.11419526764397e-05 -5.36808175477659e-06 0.000147820966809381 -3.59143766037802e-06 0.00011022964193838 -1.00939555823163e-05 0.000333931172686333 7.57818797806669e-06 -3.59143766037802e-06 1.42719577901253e-05 -3.26470027587475e-06 3.93301219522767e-06 7.23340970919111e-06 -9.18080647481414e-06 0.00011022964193838 -3.26470027587475e-06 0.000548722348118497 -1.95628336328735e-05 0.000281711800032022 1.85098020826861e-06 -1.00939555823163e-05 3.93301219522767e-06 -1.95628336328735e-05 1.24838352307771e-05 -3.81460026149466e-05 1.11419526764397e-05 0.000333931172686333 7.23340970919111e-06 0.000281711800032022 -3.81460026149466e-05 0.00135357194309052 3396 3348 0 0 141 3326 3342 0 0 169 0 0 0 0 0 0 0 0 3782 0 0 0 0 0 3662 +164 165 0.999132027009792 0.0391153939481924 -0.0143240552771117 0.0574951516176867 -0.0388789810839682 0.999108890586384 0.0164270989866507 -0.00675795171333889 0.0149538434249019 -0.0158559360342583 0.999762457716482 -0.0258564395740865 3.65724739680614e-05 1.51257583620235e-05 8.18683828072124e-06 8.90950381494615e-06 8.93631614410109e-07 -9.03579054571981e-06 1.51257583620235e-05 2.7389365944088e-05 4.07292327207746e-06 4.07071915366346e-07 -1.85052726376333e-06 -1.47775605003048e-05 8.18683828072124e-06 4.07292327207746e-06 1.32460804421126e-05 2.25983119434525e-06 3.84868661264054e-06 -4.63466108468715e-06 8.90950381494615e-06 4.07071915366346e-07 2.25983119434525e-06 0.000608152319325444 -1.33742489938817e-05 3.15162765501956e-05 8.93631614410109e-07 -1.85052726376333e-06 3.84868661264054e-06 -1.33742489938817e-05 1.16939609655881e-05 -1.23791797588666e-06 -9.03579054571981e-06 -1.47775605003048e-05 -4.63466108468715e-06 3.15162765501956e-05 -1.23791797588666e-06 9.29786520386345e-05 3532 3450 0 146 0 3552 3470 0 57 0 0 0 0 0 0 0 0 0 3632 0 28 50 0 0 3768 +159 160 0.999481210520628 -0.0300762386570203 -0.0115208369689495 0.00784682600321715 0.0301320884849634 0.999534851107206 0.00470517434648325 0.00155666650452329 0.0113739641178216 -0.00504988023050291 0.999922562826694 -0.0545846302475936 4.83300558936078e-05 -5.43154642696457e-06 3.75476144362041e-06 -1.77030703123319e-05 -3.01589857206624e-07 2.52595221782498e-06 -5.43154642696457e-06 8.37768130826338e-05 4.84371562704621e-06 0.000300803386078104 6.0353755708179e-06 5.89961134088289e-05 3.75476144362041e-06 4.84371562704621e-06 1.36700291287811e-05 1.91977945190456e-05 4.94364807357802e-06 -3.52188148771353e-06 -1.77030703123319e-05 0.000300803386078104 1.91977945190456e-05 0.0068262189395824 0.00015916077542463 0.000911700672178582 -3.01589857206624e-07 6.0353755708179e-06 4.94364807357802e-06 0.00015916077542463 1.43709222668039e-05 2.25944732957015e-05 2.52595221782498e-06 5.89961134088289e-05 -3.52188148771353e-06 0.000911700672178582 2.25944732957015e-05 0.000386365975672711 3151 3180 0 0 44 3088 3119 0 0 77 0 0 0 0 0 18 0 0 3740 0 0 0 0 0 3744 +167 168 0.999862268265202 -0.0113977824102369 -0.0120637910995328 0.193438777395843 0.0112761503839524 0.999885383802112 -0.0101028556072427 0.00263879300174686 0.0121775585435983 0.00996543100077459 0.999876190962104 -0.0258427691955312 4.55712351687639e-05 -2.23468467678423e-05 6.51225642677265e-06 -2.26676505252039e-06 1.2622082897859e-06 2.6692045691749e-06 -2.23468467678423e-05 0.000109751763965927 2.05809446494153e-06 3.08018415057246e-05 1.86513865655799e-06 -4.87548464064639e-05 6.51225642677265e-06 2.05809446494153e-06 1.41641312300093e-05 7.66213854805579e-06 3.6886457328239e-06 -5.9004816207373e-06 -2.26676505252039e-06 3.08018415057246e-05 7.66213854805579e-06 0.00128911173788804 6.37952612670642e-05 -0.000113936059270593 1.2622082897859e-06 1.86513865655799e-06 3.6886457328239e-06 6.37952612670642e-05 1.41322328335939e-05 -3.94931455419097e-06 2.6692045691749e-06 -4.87548464064639e-05 -5.9004816207373e-06 -0.000113936059270593 -3.94931455419097e-06 0.000279276356418869 3200 3174 0 212 205 3200 3174 0 133 244 0 0 0 0 0 0 0 0 3544 0 0 0 0 0 3580 +168 169 0.998907798868123 -0.000726602219763541 0.0467191760378543 0.167034535695741 0.000711932248007743 0.999999691914129 0.000330641985091902 -0.00208599268353335 -0.0467194018895366 -0.000297019969519839 0.998908008410295 0.0701100623955872 4.55772077464268e-05 -1.67445057225703e-05 7.69449378235026e-06 -3.35165625167685e-06 1.19327431350871e-06 1.21152744894949e-05 -1.67445057225703e-05 6.79426716376157e-05 -7.03823899726224e-06 1.74443652332582e-05 1.51506240098819e-06 5.47554534610093e-05 7.69449378235026e-06 -7.03823899726224e-06 1.25744929126304e-05 2.51458855858523e-06 4.64054937440094e-06 1.91315862914926e-06 -3.35165625167685e-06 1.74443652332582e-05 2.51458855858523e-06 0.000410965697816588 1.48165550185805e-05 8.69558165323246e-05 1.19327431350871e-06 1.51506240098819e-06 4.64054937440094e-06 1.48165550185805e-05 1.1139493556435e-05 7.28504770786117e-06 1.21152744894949e-05 5.47554534610093e-05 1.91315862914926e-06 8.69558165323246e-05 7.28504770786117e-06 0.000448870434533117 3381 3355 0 199 156 3381 3355 0 129 196 0 0 0 0 0 0 0 0 3569 0 0 0 0 0 3612 +165 166 0.997515974526996 0.0704137326870763 -0.0019459734144432 -0.0902505198920922 -0.0704074004766112 0.997513343702586 0.00315072902884777 -0.00860932982005065 0.00216298903900427 -0.00300589160817404 0.999993143023519 -0.0197619189235566 4.51990762384316e-05 1.06029399130743e-05 1.19108299178182e-05 -5.37865401104939e-05 2.24205796140142e-07 -5.42167050096165e-06 1.06029399130743e-05 2.58158571896205e-05 8.84292728890679e-06 2.49512457773091e-05 6.89550022444589e-07 -2.24286922670843e-06 1.19108299178182e-05 8.84292728890679e-06 1.91912945597313e-05 6.22668847278642e-06 2.0065385455957e-06 -4.88386502838375e-06 -5.37865401104939e-05 2.49512457773091e-05 6.22668847278642e-06 0.0014285464569924 4.84980709171223e-05 1.73501705700009e-05 2.24205796140142e-07 6.89550022444589e-07 2.0065385455957e-06 4.84980709171223e-05 1.51411501032809e-05 -3.5060931799904e-06 -5.42167050096165e-06 -2.24286922670843e-06 -4.88386502838375e-06 1.73501705700009e-05 -3.5060931799904e-06 0.000113377646305667 3345 3275 0 18 0 3351 3293 0 0 0 0 0 0 0 0 0 0 0 3797 0 234 266 0 0 3588 +163 164 0.999435575863043 -0.0277234072802314 0.0189721476929079 -0.10232508246344 0.0281954918036934 0.999287620029016 -0.0250851888311237 0.0129933589664058 -0.0182631854082182 0.0256059591798411 0.99950527307925 -0.0256431427287826 5.09213057437468e-05 6.05387673775387e-06 8.07414546130375e-06 -6.93319406640492e-05 3.82714282374443e-06 -1.49527537642754e-05 6.05387673775387e-06 5.86955056621258e-05 9.21144344872717e-07 0.000223647316253271 -1.51713450472321e-05 -9.93869943718283e-06 8.07414546130375e-06 9.21144344872717e-07 1.82815765219978e-05 0.000123924434906662 -4.29703673035189e-06 1.54351292189215e-06 -6.93319406640492e-05 0.000223647316253271 0.000123924434906662 0.0247579320657385 -0.00160450670961326 -1.79670209900371e-05 3.82714282374443e-06 -1.51713450472321e-05 -4.29703673035189e-06 -0.00160450670961326 0.000115858704478171 2.66935997500652e-06 -1.49527537642754e-05 -9.93869943718283e-06 1.54351292189215e-06 -1.79670209900371e-05 2.66935997500652e-06 0.000208090325105174 3044 3044 0 0 0 2983 2992 0 0 1 0 0 0 0 0 185 97 0 3649 0 0 18 0 0 3748 +173 174 0.999554835468742 -0.0263086901882118 0.0140706684857838 0.14295812714714 0.0264722789030688 0.999582599681158 -0.0115691341221724 -0.00144953700157132 -0.0137604266189054 0.0119364666145122 0.999834071945954 -0.0325724624420235 5.46817266218871e-05 1.04070562629679e-05 1.15821764660537e-05 -2.94316599672196e-06 1.30274545275673e-06 -3.10293509089417e-05 1.04070562629679e-05 5.46263110635335e-05 7.69739986645905e-06 1.79024423437919e-05 -1.88425361993555e-06 2.10694489102686e-05 1.15821764660537e-05 7.69739986645905e-06 1.70350174602881e-05 6.50554205373998e-06 2.66845497337699e-06 -9.76493035895972e-06 -2.94316599672196e-06 1.79024423437919e-05 6.50554205373998e-06 0.000172246906761234 -7.06336233798343e-06 7.20368899603625e-06 1.30274545275673e-06 -1.88425361993555e-06 2.66845497337699e-06 -7.06336233798343e-06 1.25144315975161e-05 3.20920322242791e-06 -3.10293509089417e-05 2.10694489102686e-05 -9.76493035895972e-06 7.20368899603625e-06 3.20920322242791e-06 0.000263630538683768 3331 3296 0 100 186 3331 3296 0 25 221 0 0 0 0 0 0 0 0 3656 0 0 0 0 0 3572 +174 175 0.999925998138425 -0.0100952150282985 0.00678858456578843 0.106274690973447 0.0100319554174713 0.999906533804522 0.00928889258888013 -0.00340629014060257 -0.0068817234306759 -0.00922010241582486 0.999933813606713 -0.0351219293522653 3.74660395534857e-05 8.24366495345064e-06 5.7672308495903e-06 -6.09493786410336e-07 2.19991932550819e-06 5.68867204004037e-07 8.24366495345064e-06 4.02121604555792e-05 1.38511098296715e-07 1.37175861235139e-05 2.00026355568858e-07 1.72747332851971e-05 5.7672308495903e-06 1.38511098296715e-07 1.3777470071346e-05 9.93324258361349e-08 4.24419846246493e-06 -1.24100640472855e-06 -6.09493786410336e-07 1.37175861235139e-05 9.93324258361349e-08 0.000209495693536758 -9.78871322421788e-06 7.70582020432943e-05 2.19991932550819e-06 2.00026355568858e-07 4.24419846246493e-06 -9.78871322421788e-06 1.21452723176803e-05 -7.05335096565932e-06 5.68867204004037e-07 1.72747332851971e-05 -1.24100640472855e-06 7.70582020432943e-05 -7.05335096565932e-06 0.000243780667718328 3356 3315 0 85 105 3356 3315 0 11 140 0 0 0 0 0 0 0 0 3683 0 0 0 0 0 3636 +166 167 0.999552302878064 0.0221481856194613 -0.020115955978404 0.169901557833015 -0.0224541035901643 0.999633663233162 -0.015111338888763 -0.00572662616870673 0.0197738980254621 0.0155562593451882 0.999683447773376 0.059060050981344 3.70318814604308e-05 -5.09942409633464e-06 6.83304877415838e-06 -9.64103509050116e-06 -1.22852944816688e-06 2.52827366663502e-05 -5.09942409633464e-06 7.14847008997406e-05 -4.69694524724262e-06 -4.55550919190728e-05 -3.76838625676326e-06 0.000111784105295491 6.83304877415838e-06 -4.69694524724262e-06 1.35448356676538e-05 -8.07391961435154e-07 3.40627043458409e-06 -4.45481568573801e-07 -9.64103509050116e-06 -4.55550919190728e-05 -8.07391961435154e-07 0.000419270055796893 2.56628533199722e-05 -0.000233380787261124 -1.22852944816688e-06 -3.76838625676326e-06 3.40627043458409e-06 2.56628533199722e-05 1.29473382165369e-05 -1.71935443077195e-05 2.52827366663502e-05 0.000111784105295491 -4.45481568573801e-07 -0.000233380787261124 -1.71935443077195e-05 0.000868758133825211 3396 3367 0 265 94 3396 3367 0 186 128 0 0 0 0 0 0 0 0 3503 0 0 0 0 0 3714 +178 179 0.999993825074046 0.00295876750392779 -0.00189618264848122 0.138981135075077 -0.00291456085491411 0.999733353656354 0.0229069186501152 -0.000104312659538567 0.00196345328482819 -0.0229012506618677 0.999735803884867 -0.018113739796396 4.47417748770156e-05 -1.04616299437137e-05 5.44266363775836e-06 -1.91799269697129e-05 1.12273891628269e-06 -9.31646213013223e-06 -1.04616299437137e-05 5.84978199704666e-05 4.5243950239045e-06 5.37019549192673e-05 8.38300284819852e-07 7.69567978395898e-05 5.44266363775836e-06 4.5243950239045e-06 1.33654917580421e-05 1.96623812345823e-06 4.56995822420591e-06 -3.21666627853205e-07 -1.91799269697129e-05 5.37019549192673e-05 1.96623812345823e-06 0.000414211378881761 2.65313699759067e-06 0.000152139908661317 1.12273891628269e-06 8.38300284819852e-07 4.56995822420591e-06 2.65313699759067e-06 1.06051558234647e-05 8.15138772586653e-07 -9.31646213013223e-06 7.69567978395898e-05 -3.21666627853205e-07 0.000152139908661317 8.15138772586653e-07 0.000523580045396485 3382 3362 0 155 105 3382 3362 0 86 149 0 0 0 0 0 0 0 0 3632 0 0 0 0 0 3673 +169 170 0.999647620398984 0.00323005960773772 -0.0263477085451392 0.184464058655693 -0.00270803785930094 0.999799808408701 0.0198244706582147 -0.00945744470393561 0.0264064681773563 -0.0197461343269077 0.999456246474823 -0.143230807386763 4.90933349674122e-05 -1.09078353309039e-05 4.05215614477734e-06 4.53891770633335e-05 2.14466627099267e-06 1.28748526981179e-06 -1.09078353309039e-05 7.18537533164857e-05 -5.847997284206e-07 -7.4239223700262e-05 -2.43756378936403e-06 -3.33698681442761e-05 4.05215614477734e-06 -5.847997284206e-07 1.44377730388053e-05 3.0481053544679e-06 5.20674269662685e-06 -3.7714507774698e-06 4.53891770633335e-05 -7.4239223700262e-05 3.0481053544679e-06 0.00215478296075416 0.000112319263668884 -0.000294989542881189 2.14466627099267e-06 -2.43756378936403e-06 5.20674269662685e-06 0.000112319263668884 1.68127893671175e-05 -1.91922251227087e-05 1.28748526981179e-06 -3.33698681442761e-05 -3.7714507774698e-06 -0.000294989542881189 -1.91922251227087e-05 0.000221574778357419 3259 3238 0 214 150 3259 3238 0 172 196 0 0 0 0 0 0 0 0 3580 0 0 0 0 0 3618 +179 180 0.99957923464659 -0.0191731602290108 0.0217656516137159 0.117194883041334 0.0191627944475273 0.999816142322111 0.000684734323996068 0.00666896293590585 -0.0217747783524607 -0.000267355503626112 0.99976286565802 -0.00498790220478575 4.37165607635925e-05 3.48214108509648e-06 5.20304507393303e-06 1.61823991715672e-05 8.11462885060084e-07 5.30565009075692e-06 3.48214108509648e-06 2.81198423586958e-05 3.93966107109559e-06 1.88968287112235e-05 9.71400795764396e-07 -1.15500609576719e-05 5.20304507393303e-06 3.93966107109559e-06 1.20288664387673e-05 4.63069709781636e-07 5.13046305053441e-06 -4.32644562186603e-06 1.61823991715672e-05 1.88968287112235e-05 4.63069709781636e-07 0.000395537313880893 1.78127847201599e-06 4.50172758268386e-05 8.11462885060084e-07 9.71400795764396e-07 5.13046305053441e-06 1.78127847201599e-06 9.74405923018324e-06 -8.58336385887952e-07 5.30565009075692e-06 -1.15500609576719e-05 -4.32644562186603e-06 4.50172758268386e-05 -8.58336385887952e-07 8.45138768656399e-05 3331 3306 0 60 143 3331 3306 0 3 184 0 0 0 0 0 0 0 0 3722 0 0 0 0 0 3625 +171 172 0.997891235182381 -0.0335171047015457 -0.0555849479500322 0.153564003837017 0.0346083928860125 0.999224342724418 0.0187875503672578 -0.00372344805945191 0.0549121287879969 -0.0206716375592373 0.998277186713485 -0.108003899988894 5.29002623664399e-05 -1.15952771691417e-05 -2.97135086049306e-06 2.45231689342171e-05 2.57958775217621e-06 1.62882084105401e-05 -1.15952771691417e-05 7.43357837812062e-05 2.62759955338576e-06 -3.82276909436691e-05 -1.96481665823553e-06 1.12268283272227e-06 -2.97135086049306e-06 2.62759955338576e-06 1.43797501226141e-05 -5.66281156017849e-06 4.47187493118731e-06 -1.03676195719848e-06 2.45231689342171e-05 -3.82276909436691e-05 -5.66281156017849e-06 0.000268334562488004 5.78263923746919e-06 -1.23449479119976e-05 2.57958775217621e-06 -1.96481665823553e-06 4.47187493118731e-06 5.78263923746919e-06 1.13622993993765e-05 -6.12813588191496e-06 1.62882084105401e-05 1.12268283272227e-06 -1.03676195719848e-06 -1.23449479119976e-05 -6.12813588191496e-06 0.000327714873738033 3201 3179 0 84 207 3201 3179 0 15 248 0 0 0 0 0 0 0 0 3668 0 0 0 0 0 3546 +181 182 0.999348107433826 -0.0308611187121897 -0.018733700122059 -0.00126694492827431 0.0309328402216887 0.999515158116984 0.00355078726481121 0.00921126944498414 0.0186150359723148 -0.00412795908562589 0.999818203669816 -0.0507455669951512 4.82977710280824e-05 -1.03465830621064e-05 1.04316470858685e-05 3.64621608220924e-07 6.62021997647527e-07 4.92078389924983e-06 -1.03465830621064e-05 5.98134524957689e-05 -1.93473265699283e-06 1.32109589335674e-05 -3.11338542996366e-06 7.96611275210887e-06 1.04316470858685e-05 -1.93473265699283e-06 1.47492686504427e-05 -8.67890177646907e-07 4.38045173333004e-06 6.27181380083465e-06 3.64621608220924e-07 1.32109589335674e-05 -8.67890177646907e-07 0.000454341602604053 -1.79711612159665e-05 8.18253901272172e-05 6.62021997647527e-07 -3.11338542996366e-06 4.38045173333004e-06 -1.79711612159665e-05 1.17174868492982e-05 -5.28537757287502e-06 4.92078389924983e-06 7.96611275210887e-06 6.27181380083465e-06 8.18253901272172e-05 -5.28537757287502e-06 0.000221681155954685 3192 3219 0 0 41 3127 3154 0 0 76 0 0 0 0 0 48 0 0 3763 0 0 0 0 0 3716 +172 173 0.989320060299298 -0.029994153821577 -0.142639997987665 0.127481029433631 0.027411801794446 0.999423426608312 -0.0200351558237592 0.000788750923668432 0.143158693105852 0.0159111622148692 0.989571838476215 0.0365099779378281 7.08895278841602e-05 0.000380315559500182 3.91775732355642e-06 -7.76188804963938e-05 3.81711490966345e-06 -0.000549985913918191 0.000380315559500182 0.00730202209617955 0.000209665306903709 -0.00163305879050075 0.000115984173236349 -0.0104893839201443 3.91775732355642e-06 0.000209665306903709 2.616823787465e-05 -5.04167269932688e-05 8.29381653606785e-06 -0.000301951475063187 -7.76188804963938e-05 -0.00163305879050075 -5.04167269932688e-05 0.000846978641067462 -3.8439615026233e-05 0.00243590219527205 3.81711490966345e-06 0.000115984173236349 8.29381653606785e-06 -3.8439615026233e-05 1.5002698565045e-05 -0.000175375019948525 -0.000549985913918191 -0.0104893839201443 -0.000301951475063187 0.00243590219527205 -0.000175375019948525 0.0154486933135871 2366 2328 0 39 132 2357 2328 0 2 171 0 0 0 0 0 0 0 0 3728 0 0 0 0 0 3582 +170 171 0.999978664794179 -0.00630522917805358 0.00170705637360331 0.167800788169795 0.00630897847014248 0.999977678264287 -0.00219994632404211 -0.00444918036635088 -0.00169314710338959 0.00221066916964287 0.999996123089839 0.0435836011953355 3.50464167436637e-05 -7.50008347330685e-06 1.09002679298785e-05 3.55717497457136e-06 -4.92224677189578e-07 6.34010409498091e-07 -7.50008347330685e-06 2.77515966776426e-05 -2.91409378896397e-06 -3.12695633934382e-05 -7.07520546367889e-07 1.67534171548825e-06 1.09002679298785e-05 -2.91409378896397e-06 1.51109189568447e-05 -8.1728525924078e-07 2.82417946265766e-06 -3.8679346373405e-08 3.55717497457136e-06 -3.12695633934382e-05 -8.1728525924078e-07 0.000226561691527784 4.94632342494542e-06 -2.99182387727608e-05 -4.92224677189578e-07 -7.07520546367889e-07 2.82417946265766e-06 4.94632342494542e-06 1.14311357472782e-05 6.44004254508923e-07 6.34010409498091e-07 1.67534171548825e-06 -3.8679346373405e-08 -2.99182387727608e-05 6.44004254508923e-07 0.000124148594992941 3436 3418 0 183 165 3436 3418 0 102 203 0 0 0 0 0 0 0 0 3590 0 0 0 0 0 3604 +176 177 0.95636979589957 0.0414032962187315 0.289210270483671 0.0533746213592874 -0.032549266170646 0.998844459416034 -0.0353594565235769 -0.00307321425487459 -0.290340074331407 0.0244031341453155 0.956612318696095 -0.150519624453477 0.000389116823079961 0.00532963523503876 -0.000286962076940524 -0.000744276031030356 -2.25371789600118e-05 -0.00156751468719323 0.00532963523503876 0.0894670664582185 -0.00482984156424389 -0.0138342220629734 -0.000492711428420095 -0.02870710009975 -0.000286962076940524 -0.00482984156424389 0.000299951018665857 0.00067356669043211 2.49305597409866e-05 0.00123468125978109 -0.000744276031030356 -0.0138342220629734 0.00067356669043211 0.00295607416541008 9.93540070723701e-05 0.00578536360679219 -2.25371789600118e-05 -0.000492711428420095 2.49305597409866e-05 9.93540070723701e-05 1.49572474717113e-05 0.000236284003951708 -0.00156751468719323 -0.02870710009975 0.00123468125978109 0.00578536360679219 0.000236284003951708 0.0154027184858909 1417 1385 0 109 0 1421 1394 0 55 6 0 0 0 0 0 0 0 0 3499 0 0 4 0 0 3337 +177 178 0.999674028802994 0.0240795423283192 -0.00848597537403628 0.153697319295807 -0.0240307958654038 0.999694392184516 0.00580026593413095 -0.00206638757454247 0.00862304974271639 -0.00559445047256914 0.99994717117308 0.0463362603368118 3.65479458800627e-05 -1.17094537307246e-05 9.13902673483698e-06 2.57778255261484e-06 2.49969014653856e-06 1.12916437614836e-06 -1.17094537307246e-05 6.41155250823733e-05 -1.97666428002997e-06 8.01444389016324e-06 5.83522730188e-07 0.000111867544539234 9.13902673483698e-06 -1.97666428002997e-06 1.3507553787054e-05 4.23327664005826e-06 3.42200343873974e-06 2.18182168266776e-06 2.57778255261484e-06 8.01444389016324e-06 4.23327664005826e-06 0.000271638741838471 3.81093742866171e-06 0.000187179252037838 2.49969014653856e-06 5.83522730188e-07 3.42200343873974e-06 3.81093742866171e-06 1.15770504813795e-05 1.34126882873994e-05 1.12916437614836e-06 0.000111867544539234 2.18182168266776e-06 0.000187179252037838 1.34126882873994e-05 0.000720559502130762 3449 3428 0 242 79 3449 3428 0 172 117 0 0 0 0 0 0 0 0 3552 0 0 0 0 0 3701 +182 183 0.999270578278693 -0.0374745829681342 -0.00734622473995153 0.301483528276589 0.0375923979244493 0.999155014741535 0.016615298225816 -0.00192457746376241 0.00671736591643726 -0.0168793408700508 0.999834968805821 -0.0056678356134317 5.42248928317203e-05 4.17367879220717e-06 5.41933010645464e-06 2.74524684847325e-05 -2.8058106258794e-07 -3.70383710228144e-05 4.17367879220717e-06 0.00020804988866447 5.94548689736594e-06 0.00018638894057243 -1.95381683907182e-05 0.000421783856478544 5.41933010645464e-06 5.94548689736594e-06 1.44945586960186e-05 4.11567984252964e-06 3.68249064108652e-06 1.53366991161314e-05 2.74524684847325e-05 0.00018638894057243 4.11567984252964e-06 0.00132449329533314 -0.000106101489996963 0.000474810725093942 -2.8058106258794e-07 -1.95381683907182e-05 3.68249064108652e-06 -0.000106101489996963 2.13634977609001e-05 -6.06823765927448e-05 -3.70383710228144e-05 0.000421783856478544 1.53366991161314e-05 0.000474810725093942 -6.06823765927448e-05 0.00146803325300116 3190 3136 0 360 387 3190 3136 0 256 422 0 0 0 0 0 0 0 0 3380 0 0 0 0 0 3381 +175 176 0.999751372090632 0.0204711952948648 -0.00883878759212264 0.11129481611352 -0.0205097314679506 0.999780442956375 -0.0042914795895034 -0.00508838462124485 0.00874899525726903 0.00447169376792166 0.999951728353341 -0.0675731690249159 6.09542896306118e-05 2.21801593571061e-05 8.54827576066829e-06 -1.13943267103176e-05 1.23365258713345e-06 2.26255317506034e-05 2.21801593571061e-05 3.85570887370245e-05 3.14647435637869e-06 -6.88002152240907e-06 -3.16006022769033e-09 -6.4422475018487e-06 8.54827576066829e-06 3.14647435637869e-06 1.57585925379686e-05 -2.97415849113411e-06 4.16968787238218e-06 1.55056058959529e-06 -1.13943267103176e-05 -6.88002152240907e-06 -2.97415849113411e-06 0.000160885523839834 -3.12298782757745e-06 -4.10324967957442e-05 1.23365258713345e-06 -3.16006022769033e-09 4.16968787238218e-06 -3.12298782757745e-06 1.21440545949033e-05 5.66940149664019e-07 2.26255317506034e-05 -6.4422475018487e-06 1.55056058959529e-06 -4.10324967957442e-05 5.66940149664019e-07 0.000184572278646268 3353 3319 0 173 34 3353 3319 0 96 65 0 0 0 0 0 0 0 0 3613 0 0 0 0 0 3715 +184 185 0.999870286112512 -0.00129433434686324 0.0160541473732308 0.0389895339566269 0.0012646622705038 0.99999747373816 0.00185826441590968 0.00902069516304558 -0.0160565120317099 -0.00183772029874028 0.999869397074178 -0.0784341837444232 5.42243698059345e-05 -4.66566435728739e-06 7.74088156679409e-06 -1.81268642541849e-05 5.4874713909865e-06 -2.10106531369326e-06 -4.66566435728739e-06 3.19544223036499e-05 -3.59310293596502e-06 4.21301825912611e-05 -4.06535238267704e-06 4.39986409531055e-06 7.74088156679409e-06 -3.59310293596502e-06 1.52359844597156e-05 1.81473291772643e-05 2.03072152462669e-06 4.66246492841553e-06 -1.81268642541849e-05 4.21301825912611e-05 1.81473291772643e-05 0.00151116058645735 -0.000175938449382361 0.000188394451171192 5.4874713909865e-06 -4.06535238267704e-06 2.03072152462669e-06 -0.000175938449382361 3.27440533708905e-05 -2.12499614409017e-05 -2.10106531369326e-06 4.39986409531055e-06 4.66246492841553e-06 0.000188394451171192 -2.12499614409017e-05 0.000173158884940958 3378 3311 0 1 43 3339 3311 0 0 63 0 0 0 0 0 0 0 0 3782 0 0 0 0 0 3730 +180 181 0.99910986370204 -0.0239122061256981 0.0347517863065048 0.201557379690798 0.0240042024784148 0.999709365145586 -0.00223237621942614 0.00852002766948701 -0.0346883051858419 0.00306457801531047 0.999393480989806 0.0712290847004857 4.85428550252082e-05 -7.83519733538584e-06 4.07542427470269e-06 -4.43461041986567e-06 3.30313784685404e-06 2.31688749582447e-06 -7.83519733538584e-06 5.46950960334907e-05 4.76478650515771e-06 -5.66168738731619e-07 -1.40043804348107e-06 4.88673012100052e-05 4.07542427470269e-06 4.76478650515771e-06 1.29793951573105e-05 -1.2626392000506e-06 4.28819889095418e-06 1.56917661737998e-06 -4.43461041986567e-06 -5.66168738731619e-07 -1.2626392000506e-06 0.000273781981008116 -4.51429207675821e-06 0.000112545130274178 3.30313784685404e-06 -1.40043804348107e-06 4.28819889095418e-06 -4.51429207675821e-06 1.06237030225684e-05 -3.75485928643776e-06 2.31688749582447e-06 4.88673012100052e-05 1.56917661737998e-06 0.000112545130274178 -3.75485928643776e-06 0.000337934987839425 3386 3355 0 189 262 3386 3355 0 113 300 0 0 0 0 0 0 0 0 3587 0 0 0 0 0 3502 +185 186 0.999134755970042 0.0361141418300657 0.0206278494410631 0.107865828049453 -0.0366428261745223 0.998993930556975 0.0258540132333375 -0.0103173680360616 -0.0196734008912799 -0.02658750590416 0.999452881244117 -0.0134871642389969 5.18129723126822e-05 1.13346644055372e-05 8.90966866222668e-07 3.59252252321379e-05 -3.37423071846482e-07 -4.22543416696688e-06 1.13346644055372e-05 6.09635295151729e-05 -2.07407930846578e-06 -8.14473771693725e-06 1.05380468069627e-06 2.41804801584573e-05 8.90966866222668e-07 -2.07407930846578e-06 1.50329092551543e-05 -6.65313422682653e-06 4.90928601747542e-06 6.25326858795606e-06 3.59252252321379e-05 -8.14473771693725e-06 -6.65313422682653e-06 0.000496738931037841 -2.96155179962309e-05 5.23672440010149e-05 -3.37423071846482e-07 1.05380468069627e-06 4.90928601747542e-06 -2.96155179962309e-05 1.33951050654857e-05 -7.03257055344447e-06 -4.22543416696688e-06 2.41804801584573e-05 6.25326858795606e-06 5.23672440010149e-05 -7.03257055344447e-06 0.000287534471314681 3197 3128 0 226 4 3197 3132 0 128 17 0 0 0 0 0 0 0 0 3563 0 0 3 0 0 3769 +183 184 0.999452472379722 -0.0321648133099173 0.0077575923326558 0.186424395990367 0.0323672789409047 0.999095907544883 -0.027563141711853 0.0048506775120406 -0.00686401544456143 0.027799142285405 0.99958996242468 -0.0684724463487353 5.89039928907095e-05 3.81982143108569e-06 9.48645206357869e-07 -1.07936494393568e-05 5.65713009964576e-06 -2.23147407598935e-06 3.81982143108569e-06 6.40240082016196e-05 -5.35025395023594e-07 -3.52928141287744e-05 3.43681516419949e-06 2.28062516612517e-05 9.48645206357869e-07 -5.35025395023594e-07 1.30001571305658e-05 3.17891723700355e-06 4.54546916992045e-06 2.85480421325052e-06 -1.07936494393568e-05 -3.52928141287744e-05 3.17891723700355e-06 0.000226520336210751 -2.24889859825076e-05 -1.48892250293919e-05 5.65713009964576e-06 3.43681516419949e-06 4.54546916992045e-06 -2.24889859825076e-05 1.40814974429872e-05 3.5049606328218e-06 -2.23147407598935e-06 2.28062516612517e-05 2.85480421325052e-06 -1.48892250293919e-05 3.5049606328218e-06 0.000282384412808752 3229 3161 0 162 252 3229 3161 0 69 277 0 0 0 0 0 0 0 0 3583 0 0 0 0 0 3519 +188 189 0.998927051791361 0.0461729921151769 -0.00357770856156888 0.13712849047336 -0.0461368946109277 0.998889102282141 0.00958896749591802 -0.00568483901266278 0.00401648541387438 -0.00941361466756686 0.999947624480308 0.00725753186143742 3.61009708681942e-05 -6.03619598481726e-06 5.47999150624758e-06 -5.3640709483608e-06 1.58258065914097e-06 -4.42250658665241e-07 -6.03619598481726e-06 2.02283173986617e-05 -1.47760608400187e-06 -5.72802037446473e-06 3.50303251120117e-07 4.95612738121631e-06 5.47999150624758e-06 -1.47760608400187e-06 1.00894253731733e-05 7.24159681076461e-08 3.50775698728285e-06 7.18226269710318e-07 -5.3640709483608e-06 -5.72802037446473e-06 7.24159681076461e-08 0.000182940574883446 8.62064353531732e-06 3.13015868090145e-06 1.58258065914097e-06 3.50303251120117e-07 3.50775698728285e-06 8.62064353531732e-06 1.05690233473147e-05 1.8302433131994e-06 -4.42250658665241e-07 4.95612738121631e-06 7.18226269710318e-07 3.13015868090145e-06 1.8302433131994e-06 0.000110634877962165 3525 3503 0 282 0 3525 3504 0 200 28 0 0 0 0 0 0 0 0 3508 0 0 0 0 0 3811 +189 190 0.999687572148931 0.0249118716063523 0.00203880946721724 0.221564325099279 -0.0249239840862798 0.999670441699272 0.00614841524699228 0.0105923086480628 -0.0018849690294181 -0.00619730956554507 0.999979019902871 -0.0331912158814787 4.46248407060352e-05 -1.59149698915976e-05 1.4073867071723e-06 -2.05360254646479e-05 6.05676909757066e-07 -2.12260201861297e-05 -1.59149698915976e-05 4.50362618650667e-05 1.26666475364869e-06 1.75248915244737e-05 6.48504027858613e-07 9.78894684971288e-06 1.4073867071723e-06 1.26666475364869e-06 1.45565238799294e-05 5.40297144544996e-07 5.70406882127371e-06 2.08415075476823e-06 -2.05360254646479e-05 1.75248915244737e-05 5.40297144544996e-07 0.000770511405686292 6.16054038458521e-05 8.72376198008464e-05 6.05676909757066e-07 6.48504027858613e-07 5.70406882127371e-06 6.16054038458521e-05 1.69250567909166e-05 6.0896221203296e-06 -2.12260201861297e-05 9.78894684971288e-06 2.08415075476823e-06 8.72376198008464e-05 6.0896221203296e-06 0.000201918020241815 3244 3230 0 317 170 3244 3230 0 286 216 0 0 0 0 0 0 0 0 3486 0 0 0 0 0 3636 +192 193 0.998777277828627 -0.0493472789050582 -0.00296569686634949 0.170004111116038 0.0493740386060016 0.998732737001921 0.00975317140135821 0.0214052060632696 0.00248064607909558 -0.00988767441401741 0.999948038794873 0.0223693761477256 5.24017085522019e-05 -2.36650108037994e-05 7.50079185229027e-06 1.32860448836563e-05 6.85640994571679e-07 8.21665583151517e-06 -2.36650108037994e-05 5.38029651900475e-05 -2.46026201544194e-06 -4.64594793449965e-05 -1.48926478820901e-07 -1.33446081573024e-05 7.50079185229027e-06 -2.46026201544194e-06 1.34435452230148e-05 3.35639325253882e-06 4.79600177661218e-06 4.37747260978278e-06 1.32860448836563e-05 -4.64594793449965e-05 3.35639325253882e-06 0.000307695265903674 2.91514937812498e-06 -1.23313302457131e-05 6.85640994571679e-07 -1.48926478820901e-07 4.79600177661218e-06 2.91514937812498e-06 1.13146488827748e-05 -9.55442185840233e-06 8.21665583151517e-06 -1.33446081573024e-05 4.37747260978278e-06 -1.23313302457131e-05 -9.55442185840233e-06 0.000249524068016646 3157 3123 0 49 287 3157 3123 0 0 325 0 0 0 0 0 0 0 0 3698 0 0 0 0 0 3505 +191 192 0.999553467864081 -0.0231769485608229 0.0188598498482431 0.158810496843829 0.022773177130674 0.999512674925335 0.0213493575307721 0.0196690501013011 -0.0193454719318049 -0.0209103256553014 0.999594173150647 0.0367669605841918 3.47383416074336e-05 -5.73833347695115e-06 6.93312563289686e-06 -6.75555471526584e-06 2.2407082906609e-07 -8.60290114216506e-06 -5.73833347695115e-06 2.44409596817337e-05 -2.19051005478218e-08 -7.91562392091392e-06 4.71033240137182e-08 -3.49544776274505e-08 6.93312563289686e-06 -2.19051005478218e-08 1.1755508241907e-05 -5.03265268828349e-06 4.1326671400002e-06 -2.9465215763419e-06 -6.75555471526584e-06 -7.91562392091392e-06 -5.03265268828349e-06 0.000161748157131847 5.39588322011338e-06 3.77758573799324e-05 2.2407082906609e-07 4.71033240137182e-08 4.1326671400002e-06 5.39588322011338e-06 1.08048982112631e-05 -1.1063441895168e-06 -8.60290114216506e-06 -3.49544776274505e-08 -2.9465215763419e-06 3.77758573799324e-05 -1.1063441895168e-06 0.000144479307017087 3172 3153 0 88 219 3172 3153 0 28 269 0 0 0 0 0 0 0 0 3657 0 0 0 0 0 3579 +186 187 0.998127757446855 0.0600144994017845 0.0117999862569958 0.138106036528289 -0.0598766641254403 0.998137133018841 -0.0117067835949342 -0.0100418647464337 -0.0124805812092745 0.0109783218427324 0.999861846227866 -0.00520896995642247 5.18797375774874e-05 7.56145403970858e-06 6.98274719972973e-06 -8.93630456885247e-06 1.88460194926378e-06 -9.60592570959663e-06 7.56145403970858e-06 2.87873400908788e-05 -1.62569395093161e-07 3.0747727735469e-07 9.9548988871762e-07 -2.16212666587396e-06 6.98274719972973e-06 -1.62569395093161e-07 1.39715485143739e-05 -1.67457229374437e-06 2.18607480749441e-06 -4.17493943443518e-06 -8.93630456885247e-06 3.0747727735469e-07 -1.67457229374437e-06 0.000555751733200889 -1.51627444700187e-05 3.89959845727397e-05 1.88460194926378e-06 9.9548988871762e-07 2.18607480749441e-06 -1.51627444700187e-05 1.26287219870344e-05 3.82250447056313e-07 -9.60592570959663e-06 -2.16212666587396e-06 -4.17493943443518e-06 3.89959845727397e-05 3.82250447056313e-07 0.00013078980420284 3439 3362 0 350 0 3448 3386 0 243 0 0 0 0 0 0 0 0 0 3457 0 0 16 0 0 3818 +193 194 0.999073001866631 -0.0358642075858501 -0.0238095685689048 0.135163249695057 0.0354544567591146 0.999219557200173 -0.0174143045972882 0.0195187915211587 0.0244155367975886 0.0165540062501531 0.999564828532875 -0.0381400084312612 4.8701214864983e-05 -2.0205362680122e-05 -3.63215088887268e-07 2.33827525544583e-06 1.04542509488538e-06 2.9334424596593e-06 -2.0205362680122e-05 6.28489764362529e-05 1.75249782188387e-06 -4.126683743114e-05 4.54400526262581e-08 3.29104377294925e-05 -3.63215088887268e-07 1.75249782188387e-06 1.10764616781237e-05 -3.62195047560944e-06 4.80438493922491e-06 1.33081952263825e-06 2.33827525544583e-06 -4.126683743114e-05 -3.62195047560944e-06 0.000231807554672796 -2.01562459784954e-06 -5.22386970516511e-05 1.04542509488538e-06 4.54400526262581e-08 4.80438493922491e-06 -2.01562459784954e-06 1.02762182928711e-05 -1.17107902270359e-05 2.9334424596593e-06 3.29104377294925e-05 1.33081952263825e-06 -5.22386970516511e-05 -1.17107902270359e-05 0.000409013641117983 2992 2947 0 35 214 2991 2947 0 0 248 0 0 0 0 0 0 0 0 3681 0 0 0 0 0 3569 +195 196 0.998547808830235 -0.00692596909225828 0.0534256907533192 0.135977291430121 0.00750963062212013 0.999914213995078 -0.0107317332489001 0.00553715186567303 -0.053346779923961 0.0111173559239288 0.998514158872575 -0.04347752410466 4.37404663416022e-05 3.51023328178644e-06 2.66431027480434e-06 -1.12649967104955e-06 1.77484697409143e-06 3.3775314825177e-06 3.51023328178644e-06 6.38380517784074e-05 -2.80181559766056e-06 -7.17994244463107e-06 4.15514542970757e-07 -1.96554451792513e-05 2.66431027480434e-06 -2.80181559766056e-06 1.15555533477239e-05 -4.43992832707735e-07 4.15843795435226e-06 1.19934428886005e-06 -1.12649967104955e-06 -7.17994244463107e-06 -4.43992832707735e-07 0.000159668733343083 -5.3930121095293e-06 3.84113627515527e-05 1.77484697409143e-06 4.15514542970757e-07 4.15843795435226e-06 -5.3930121095293e-06 1.07541115534632e-05 -7.70112405411553e-07 3.3775314825177e-06 -1.96554451792513e-05 1.19934428886005e-06 3.84113627515527e-05 -7.70112405411553e-07 0.000196506639427879 2833 2855 0 136 141 2833 2855 0 50 167 0 0 0 0 0 0 0 0 3588 0 0 0 0 0 3622 +194 195 0.998897786927381 -0.026251701244554 0.0389109168916345 0.141468268953597 0.0265253039408298 0.999626801453758 -0.0065319266818044 0.00801026046278495 -0.0387249212062155 0.0075568510039933 0.99922133407993 -0.0107800771898223 4.63136103567572e-05 6.04696467207534e-06 6.35391610582645e-06 -1.65797839803662e-05 3.87247594686341e-06 -4.53751905638212e-05 6.04696467207534e-06 8.98791894929134e-05 1.24293299318159e-06 -1.35413136604401e-05 -3.34181682973571e-06 9.2489149646511e-05 6.35391610582645e-06 1.24293299318159e-06 1.25201913292264e-05 -4.43705723725561e-06 5.29851959746269e-06 1.52752568415609e-06 -1.65797839803662e-05 -1.35413136604401e-05 -4.43705723725561e-06 0.000369793209935747 -9.12567713024497e-06 3.0794561114357e-05 3.87247594686341e-06 -3.34181682973571e-06 5.29851959746269e-06 -9.12567713024497e-06 1.12328771374225e-05 -2.31267861580839e-05 -4.53751905638212e-05 9.2489149646511e-05 1.52752568415609e-06 3.0794561114357e-05 -2.31267861580839e-05 0.000683576939035501 3109 3056 0 92 195 3109 3056 0 18 223 0 0 0 0 0 0 0 0 3623 0 0 0 0 0 3570 +187 188 0.99887457840402 0.0468250111517103 -0.00754949990619876 0.195402356400835 -0.0469776774009606 0.998664480816378 -0.0215023854901308 -0.00883388991566484 0.00653256796388353 0.0218328442122671 0.99974029251071 0.051928450658805 4.22824955762767e-05 5.17234671254102e-06 6.33302523379696e-06 2.71734874382282e-06 1.4178299246532e-06 -3.22166996155706e-06 5.17234671254102e-06 3.93568174290487e-05 -1.40414732608874e-06 -1.31690283711912e-05 6.61461432636322e-07 -1.14407092702682e-05 6.33302523379696e-06 -1.40414732608874e-06 1.37186809053129e-05 -6.56488503271712e-07 1.88007250110204e-06 -3.97730460711939e-06 2.71734874382282e-06 -1.31690283711912e-05 -6.56488503271712e-07 0.000335453397620321 8.21158252813953e-06 8.39714246243506e-06 1.4178299246532e-06 6.61461432636322e-07 1.88007250110204e-06 8.21158252813953e-06 1.13628456956148e-05 3.08526490926077e-06 -3.22166996155706e-06 -1.14407092702682e-05 -3.97730460711939e-06 8.39714246243506e-06 3.08526490926077e-06 0.000156455270925541 3492 3458 0 408 57 3492 3458 0 310 86 0 0 0 0 0 0 0 0 3398 0 0 0 0 0 3742 +200 201 0.999616962012561 0.00379738983338927 0.0274136660669849 0.125899180583431 -0.00361154871200932 0.999970184367006 -0.00682547382357866 -0.00432873841302031 -0.0274387676960842 0.00672385361744629 0.999600872258449 -0.0147032058515571 3.21968437832737e-05 3.67163740945433e-06 7.98236391633472e-06 -4.26382962867288e-06 2.02351048496696e-06 2.13363879466786e-06 3.67163740945433e-06 0.000108383670108902 3.57143121958234e-06 4.08422720663607e-05 6.76454215925181e-07 -4.31294597707518e-05 7.98236391633472e-06 3.57143121958234e-06 1.25481908848638e-05 4.27915442549137e-06 4.7920715205352e-06 9.26178795356294e-08 -4.26382962867288e-06 4.08422720663607e-05 4.27915442549137e-06 0.00012383854903846 -2.07255072961576e-06 3.59872209735904e-05 2.02351048496696e-06 6.76454215925181e-07 4.7920715205352e-06 -2.07255072961576e-06 1.03871850135509e-05 -2.30773695413868e-06 2.13363879466786e-06 -4.31294597707518e-05 9.26178795356294e-08 3.59872209735904e-05 -2.30773695413868e-06 0.000324243765661564 3044 3058 0 150 88 3044 3058 0 74 127 0 0 0 0 0 0 0 0 3494 0 0 0 0 0 3706 +190 191 0.999986664149762 0.000236679229473992 0.00515902176509967 0.106640036065861 -0.000371927069523852 0.999655848932846 0.0262306188376672 0.00701051649096207 -0.00515103803959862 -0.0262321878099095 0.999642605699567 -0.00344239185695092 3.96643255754726e-05 -7.90208103457222e-06 4.23452301940262e-06 -2.08224633364289e-06 -1.70264214031309e-07 6.90301595657513e-06 -7.90208103457222e-06 2.26562028805125e-05 7.53832720901156e-07 -1.2509525357658e-05 -1.86377702715184e-09 -1.04344553848679e-05 4.23452301940262e-06 7.53832720901156e-07 1.54784511887398e-05 -9.83947545630262e-07 2.31757435162903e-06 -3.42375825085668e-06 -2.08224633364289e-06 -1.2509525357658e-05 -9.83947545630262e-07 0.000174658763422857 1.01158957947141e-05 8.27793680394199e-07 -1.70264214031309e-07 -1.86377702715184e-09 2.31757435162903e-06 1.01158957947141e-05 1.31176201065984e-05 -1.22507349975613e-06 6.90301595657513e-06 -1.04344553848679e-05 -3.42375825085668e-06 8.27793680394199e-07 -1.22507349975613e-06 9.42700200478849e-05 3326 3315 0 87 84 3326 3315 0 29 126 0 0 0 0 0 0 0 0 3676 0 0 0 0 0 3730 +196 197 0.999877963833769 0.010998107511235 -0.0110950020643265 0.170480988438227 -0.0111082995030866 0.999889099163189 -0.00991942824842658 -0.000764858044307284 0.010984676680987 0.0100414643253498 0.999889246803073 -0.0595538599641825 9.5256777109696e-05 3.08751363320196e-05 6.28866581236917e-06 -7.1962187507296e-05 2.96811442174796e-06 -3.97849444955607e-05 3.08751363320196e-05 0.000187278933067299 2.16326807298935e-06 4.00560894076062e-05 2.83024577786181e-06 -0.000117777573055742 6.28866581236917e-06 2.16326807298935e-06 1.35337347548373e-05 -1.7235004830966e-06 4.28109069071477e-06 -8.38085677672759e-06 -7.1962187507296e-05 4.00560894076062e-05 -1.7235004830966e-06 0.000304483567198106 -6.58864774048409e-06 7.41704671940398e-06 2.96811442174796e-06 2.83024577786181e-06 4.28109069071477e-06 -6.58864774048409e-06 1.15116353320217e-05 -3.14613639855367e-06 -3.97849444955607e-05 -0.000117777573055742 -8.38085677672759e-06 7.41704671940398e-06 -3.14613639855367e-06 0.000783496922380075 2990 3014 0 1 129 2990 3014 0 1 157 0 0 0 0 0 0 0 0 3481 0 0 0 0 0 3645 +203 204 0.998632481491119 -0.0345409104610584 -0.0392440112043888 0.129301586117538 0.035296381515422 0.999201479671641 0.018723473874297 -0.00127205082746609 0.0385659482290637 -0.0200830407688889 0.999054222307612 -0.0215618386619132 4.08057224448644e-05 9.18029226140145e-06 3.68538304246666e-06 -8.04611434745638e-06 1.14761736049007e-06 -1.14169618521103e-05 9.18029226140145e-06 4.82360936694155e-05 1.55895699340063e-06 1.42419063500389e-05 -1.31006197025498e-06 -2.15344104212387e-05 3.68538304246666e-06 1.55895699340063e-06 1.33137317462093e-05 1.59758004640908e-06 3.14607180383296e-06 -1.33430429976673e-06 -8.04611434745638e-06 1.42419063500389e-05 1.59758004640908e-06 6.88127409801384e-05 -2.98824701441664e-06 4.41659622354827e-06 1.14761736049007e-06 -1.31006197025498e-06 3.14607180383296e-06 -2.98824701441664e-06 1.19689348020233e-05 -8.52789917944668e-07 -1.14169618521103e-05 -2.15344104212387e-05 -1.33430429976673e-06 4.41659622354827e-06 -8.52789917944668e-07 0.000125179838790478 3227 3216 0 39 188 3223 3216 0 6 219 0 0 0 0 0 0 0 0 3715 0 0 0 0 0 3582 +197 198 0.999673707708373 0.0248778851886331 0.00579387134266047 0.151319042917383 -0.0248018842907438 0.999609932798398 -0.0128393452485056 -0.00482450807148055 -0.00611102710046895 0.0126914569424854 0.999900786212539 -0.000224567040924525 7.63044259292814e-05 8.91172964639386e-05 -5.95253954345178e-06 2.31859385198566e-05 3.54133778612401e-06 8.82583309695795e-06 8.91172964639386e-05 0.000501314788222771 -5.35385032059558e-06 4.2230210146405e-05 7.48434907018023e-06 0.000152082911575171 -5.95253954345178e-06 -5.35385032059558e-06 1.58274809294627e-05 -2.57535073435918e-06 3.06267776539915e-06 -1.9941951979066e-06 2.31859385198566e-05 4.2230210146405e-05 -2.57535073435918e-06 0.000133120787480925 -1.88892647003222e-06 2.49861939828205e-05 3.54133778612401e-06 7.48434907018023e-06 3.06267776539915e-06 -1.88892647003222e-06 1.16553709680877e-05 7.77621706834898e-06 8.82583309695795e-06 0.000152082911575171 -1.9941951979066e-06 2.49861939828205e-05 7.77621706834898e-06 0.00133106762961737 3059 3004 0 7 74 3059 3004 0 7 104 0 0 0 0 0 0 0 0 3156 0 0 0 0 0 3722 +205 206 0.999002988007263 -0.0084055437644103 0.0438449174544281 0.12418441083124 0.00847811956544237 0.999962980207229 -0.00146959304244826 -0.0044069745993148 -0.0438309415960357 0.00183985029307609 0.999037268328717 0.0104254153185465 4.88854367952834e-05 1.32876792616107e-05 6.37018871936078e-06 3.81396555991974e-06 1.15195290424918e-06 -2.09896031738224e-05 1.32876792616107e-05 3.79940262196684e-05 4.78836378267862e-06 1.101564496812e-06 3.64478510615617e-07 -5.78088338354396e-06 6.37018871936078e-06 4.78836378267862e-06 1.23611166508287e-05 5.08209329582291e-07 4.8070410643026e-06 -4.03896429939041e-06 3.81396555991974e-06 1.101564496812e-06 5.08209329582291e-07 5.2428905703664e-05 -3.8438966644341e-07 9.82093201607333e-06 1.15195290424918e-06 3.64478510615617e-07 4.8070410643026e-06 -3.8438966644341e-07 1.10495954122623e-05 -2.31953343787647e-06 -2.09896031738224e-05 -5.78088338354396e-06 -4.03896429939041e-06 9.82093201607333e-06 -2.31953343787647e-06 0.00011446670263578 3224 3159 0 147 133 3224 3159 0 70 151 0 0 0 0 0 0 0 0 3644 0 0 0 0 0 3665 +198 199 0.999132424247074 0.019513717892479 -0.036791488583322 0.178964712952661 -0.0193132611077172 0.999796681254509 0.00579604156771633 -0.00946288982049999 0.036897110504064 -0.00508044943703793 0.999306155424837 -0.0481192097972447 4.74844202449161e-05 1.11337772031334e-05 -7.98913418213593e-06 -2.15130738387739e-05 2.10435539967484e-06 -2.8298352049879e-05 1.11337772031334e-05 7.06479340257088e-05 -1.78705401870574e-06 0.000116584497981315 1.85855894106709e-06 -1.56710471893535e-05 -7.98913418213593e-06 -1.78705401870574e-06 1.34470970909217e-05 -3.92382069889941e-06 3.93444916491899e-06 -2.99402369845464e-06 -2.15130738387739e-05 0.000116584497981315 -3.92382069889941e-06 0.00423420091499919 -6.80565780528576e-06 0.000447979702878785 2.10435539967484e-06 1.85855894106709e-06 3.93444916491899e-06 -6.80565780528576e-06 1.18020332482405e-05 -8.58300935104739e-07 -2.8298352049879e-05 -1.56710471893535e-05 -2.99402369845464e-06 0.000447979702878785 -8.58300935104739e-07 0.000333522346669678 3151 3106 0 230 106 3151 3106 0 187 137 0 0 0 0 0 0 0 0 2954 0 0 0 0 0 3687 +202 203 0.994798202180643 -0.0366755506310088 0.0950338935542069 0.127873959169787 0.037862239417719 0.999225536501743 -0.0107134508482765 0.00319176098470117 -0.0945673715635332 0.0142559176735636 0.995416385763691 -0.0039185963349049 0.000138999039041273 0.000938009459189883 -1.4523191308725e-05 -9.47308953568105e-05 5.19560143371274e-06 -0.000306779381678265 0.000938009459189883 0.0133818925947905 -0.000183357240460236 -0.00133030527398856 3.72552042492347e-05 -0.0026717935530753 -1.4523191308725e-05 -0.000183357240460236 1.59801964926709e-05 2.1915554621744e-05 2.80525904959555e-06 6.63274044857682e-05 -9.47308953568105e-05 -0.00133030527398856 2.1915554621744e-05 0.000211798682485407 -5.04783559408102e-06 0.000272073197417549 5.19560143371274e-06 3.72552042492347e-05 2.80525904959555e-06 -5.04783559408102e-06 1.17017806251312e-05 -1.79854879270864e-05 -0.000306779381678265 -0.0026717935530753 6.63274044857682e-05 0.000272073197417549 -1.79854879270864e-05 0.00174692279334513 2899 2900 0 30 204 2899 2900 0 9 236 0 0 0 0 0 5 0 0 3700 0 0 0 0 0 3570 +199 200 0.999783617170576 0.0200885940557079 -0.00540066904961275 0.138886358166951 -0.0201838763748658 0.999630461538173 -0.0182085556666111 -0.00719312948037836 0.00503288901155201 0.0183136220842552 0.999819624369492 -0.00124692738501812 0.00567714211336804 0.000145977941531906 2.77499109477771e-05 -0.000144355259334437 0.000205362739467554 -0.00147984621051239 0.000145977941531906 8.20531398200692e-05 -2.9606679410517e-06 -9.4636583063435e-06 4.57092890624988e-06 6.92929478731522e-06 2.77499109477771e-05 -2.9606679410517e-06 1.71734597848503e-05 2.97684076827346e-06 3.11000058109935e-06 1.13929579456915e-05 -0.000144355259334437 -9.4636583063435e-06 2.97684076827346e-06 0.000124732668059541 -7.56629339137761e-06 0.000103001272142678 0.000205362739467554 4.57092890624988e-06 3.11000058109935e-06 -7.56629339137761e-06 2.04935238476672e-05 -6.71584865408631e-05 -0.00147984621051239 6.92929478731522e-06 1.13929579456915e-05 0.000103001272142678 -6.71584865408631e-05 0.000999480173655069 3077 3041 0 217 60 3077 3041 0 137 96 0 0 0 0 0 0 0 0 3175 0 0 0 0 0 3734 +206 207 0.999604735381017 0.00555203434527818 0.0275598969242522 0.131152590451695 -0.00533583071602946 0.999954461835258 -0.00791221627164685 -0.00534904691333748 -0.0276025707936133 0.0077620339079579 0.999588839931297 0.0547952566344807 5.2420972342567e-05 1.11951478088356e-05 2.02718117705058e-06 9.48907769524032e-06 -1.91079930514872e-06 -1.09306167172533e-05 1.11951478088356e-05 6.99744595700111e-05 -3.50693589884506e-06 7.47016150726139e-07 1.85985530272875e-06 -2.58854074759308e-05 2.02718117705058e-06 -3.50693589884506e-06 1.30338497938942e-05 8.91854090838067e-07 3.25479734058102e-06 9.18293382317211e-07 9.48907769524032e-06 7.47016150726139e-07 8.91854090838067e-07 6.61776030532688e-05 -6.41322279500395e-06 -7.73251853002105e-06 -1.91079930514872e-06 1.85985530272875e-06 3.25479734058102e-06 -6.41322279500395e-06 1.29343652910351e-05 -3.65723032904828e-06 -1.09306167172533e-05 -2.58854074759308e-05 9.18293382317211e-07 -7.73251853002105e-06 -3.65723032904828e-06 0.00026454363155354 3125 3055 0 187 100 3125 3055 0 88 120 0 0 0 0 0 0 0 0 3527 0 0 0 0 0 3701 +207 208 0.999574977198042 0.0278663499532113 0.00856338133091938 0.11766927337068 -0.027761116695638 0.999540484544842 -0.0121712840601963 -0.00378801185967426 -0.00889861558585079 0.0119283819585048 0.999889258040363 0.000171441927650922 4.94633465867817e-05 2.6488573219457e-05 -3.47803391739907e-06 -1.33000145474278e-05 4.45088528456104e-07 -4.24121760134993e-05 2.6488573219457e-05 7.432621307293e-05 6.08357555426822e-07 -2.50920928832128e-05 2.05276922117245e-06 -4.68282375726993e-05 -3.47803391739907e-06 6.08357555426822e-07 1.41298334417132e-05 -1.0449892098258e-06 3.43478235877203e-06 -1.37934629501612e-06 -1.33000145474278e-05 -2.50920928832128e-05 -1.0449892098258e-06 9.67508239544948e-05 -5.00548190892224e-06 2.48971228495082e-05 4.45088528456104e-07 2.05276922117245e-06 3.43478235877203e-06 -5.00548190892224e-06 1.33109253741933e-05 -1.42656474222183e-06 -4.24121760134993e-05 -4.68282375726993e-05 -1.37934629501612e-06 2.48971228495082e-05 -1.42656474222183e-06 0.000140383353597388 3117 3055 0 218 33 3117 3055 0 120 51 0 0 0 0 0 0 0 0 3501 0 0 0 0 0 3773 +201 202 0.99926245685049 -0.0226739051271555 -0.0309909076247804 0.140496316087947 0.0222172673175933 0.999640626143247 -0.0150003865575132 0.00151518357135905 0.0313198876444587 0.0143007898460531 0.999407100258807 -0.016296630336147 4.10163659918426e-05 -7.2383325426598e-06 -1.95622471475827e-06 6.51028285789518e-06 1.29412527264457e-06 -9.88485216152659e-06 -7.2383325426598e-06 5.32145673403942e-05 -2.92446455998221e-06 -2.5444164434179e-05 -6.91672010270488e-07 -2.09729385654854e-05 -1.95622471475827e-06 -2.92446455998221e-06 1.34463876309046e-05 -9.77822067447314e-06 2.74764350735209e-06 3.99005094574497e-06 6.51028285789518e-06 -2.5444164434179e-05 -9.77822067447314e-06 0.00021971801228805 6.11367170581679e-06 1.78881811472255e-05 1.29412527264457e-06 -6.91672010270488e-07 2.74764350735209e-06 6.11367170581679e-06 1.15388152329593e-05 -9.52498743673781e-08 -9.88485216152659e-06 -2.09729385654854e-05 3.99005094574497e-06 1.78881811472255e-05 -9.52498743673781e-08 0.000152493765905809 3097 3111 0 67 169 3097 3111 0 57 204 0 0 0 0 0 0 0 0 3639 0 0 0 0 0 3609 +208 209 0.99832468761814 0.0568996241814504 -0.0105000409596177 0.129145750169293 -0.056968298922265 0.998355721590253 -0.00636129592996885 -0.0112992628355626 0.0101208206212441 0.00694880824421622 0.999924638687305 0.0280223634001405 3.588100647764e-05 9.49225481635352e-06 1.05478937242292e-06 -9.41770259175166e-06 -6.71787376916562e-09 5.06821799709275e-06 9.49225481635352e-06 2.73381993364757e-05 -6.23928329043886e-07 -5.60790534678154e-06 -1.06314157746874e-06 -8.73504494610237e-06 1.05478937242292e-06 -6.23928329043886e-07 1.35538732513941e-05 1.78096064111127e-06 2.88545190258629e-06 -2.13620920195332e-06 -9.41770259175166e-06 -5.60790534678154e-06 1.78096064111127e-06 8.59137458206393e-05 8.12789295161152e-07 -1.18565720297425e-05 -6.71787376916562e-09 -1.06314157746874e-06 2.88545190258629e-06 8.12789295161152e-07 1.26189182582896e-05 1.21278194435956e-06 5.06821799709275e-06 -8.73504494610237e-06 -2.13620920195332e-06 -1.18565720297425e-05 1.21278194435956e-06 0.000143856204467996 3400 3327 0 333 0 3419 3355 0 226 0 0 0 0 0 0 0 0 0 3481 0 0 19 0 0 3828 +209 210 0.99847394289911 0.0458080457849243 -0.0308449070815863 0.122041928390776 -0.0453623874761321 0.998858024145876 0.0149967130352812 -0.0113875878933999 0.03149665305982 -0.0135746285681635 0.999411672087767 0.0919402121011066 5.57555214779189e-05 9.30787837364112e-06 5.29057642492337e-06 -1.66242682195465e-05 -8.32734119288968e-07 1.21201511346341e-05 9.30787837364112e-06 5.89960348426738e-05 -2.16059299132557e-06 -1.3041148112463e-06 1.91728577344789e-06 -1.72043967446879e-05 5.29057642492337e-06 -2.16059299132557e-06 1.39750043415573e-05 -1.08585282553433e-06 2.75509627776373e-06 6.33243067547368e-06 -1.66242682195465e-05 -1.3041148112463e-06 -1.08585282553433e-06 9.34629987196271e-05 8.46344536875792e-07 -1.46389793344119e-05 -8.32734119288968e-07 1.91728577344789e-06 2.75509627776373e-06 8.46344536875792e-07 1.35213303772185e-05 -6.14412403598894e-06 1.21201511346341e-05 -1.72043967446879e-05 6.33243067547368e-06 -1.46389793344119e-05 -6.14412403598894e-06 0.000145803480045704 3204 3151 0 270 0 3204 3174 0 182 4 0 0 0 0 0 0 0 0 3515 0 0 0 0 0 3832 +211 212 0.999881218478942 -0.0103006162926115 0.0114650005258885 0.130486569395976 0.0103706543316443 0.999927822406198 -0.0060662596986846 0.0054490048789692 -0.0114016867962502 0.00618443869649656 0.999915873589478 -0.0436846466897752 7.74285685781186e-05 2.42601605413116e-06 1.35108873126289e-06 3.32890403751004e-06 3.2531311046998e-06 3.07790702945028e-06 2.42601605413116e-06 4.65755428539329e-05 -1.65720400571988e-06 1.22168395367921e-06 1.74865294551805e-08 6.90897707996462e-06 1.35108873126289e-06 -1.65720400571988e-06 1.34999224280446e-05 1.79373015628294e-07 3.35205511136007e-06 3.69501128653836e-07 3.32890403751004e-06 1.22168395367921e-06 1.79373015628294e-07 0.000107827392489297 3.29203703140512e-06 8.40600044334515e-06 3.2531311046998e-06 1.74865294551805e-08 3.35205511136007e-06 3.29203703140512e-06 1.23137304336864e-05 5.05942738170999e-06 3.07790702945028e-06 6.90897707996462e-06 3.69501128653836e-07 8.40600044334515e-06 5.05942738170999e-06 0.000213118610626579 3118 3096 0 108 138 3118 3096 0 41 178 0 0 0 0 0 0 0 0 3293 0 0 0 0 0 3651 +212 213 0.999867806196877 -0.0145591879500197 0.00723879667346466 0.148242892090977 0.0145430196036969 0.999891642450704 0.0022812141592086 0.00486717732786088 -0.00727122492089543 -0.00217563863490378 0.999971197527549 0.00350756473167498 3.44237841616726e-05 -3.59947055358162e-06 7.97453511408904e-06 3.60638087354988e-06 1.00431540633993e-06 4.41224802337237e-06 -3.59947055358162e-06 1.78553882823034e-05 -1.76015896221208e-06 -3.25503460321738e-06 1.08792043982356e-08 5.19369426817849e-07 7.97453511408904e-06 -1.76015896221208e-06 1.54785220617965e-05 1.33193293006132e-06 3.99194361247021e-07 4.37714102263511e-06 3.60638087354988e-06 -3.25503460321738e-06 1.33193293006132e-06 7.27395586071541e-05 1.85346641996944e-06 -2.05846537816251e-05 1.00431540633993e-06 1.08792043982356e-08 3.99194361247021e-07 1.85346641996944e-06 1.34086356921964e-05 1.81809186445381e-06 4.41224802337237e-06 5.19369426817849e-07 4.37714102263511e-06 -2.05846537816251e-05 1.81809186445381e-06 9.13943278169365e-05 3565 3536 0 111 166 3565 3536 0 42 209 0 0 0 0 0 0 0 0 3271 0 0 0 0 0 3615 +204 205 0.999690173594001 -0.0235124585956805 -0.00816829911196805 0.122991269369837 0.0235855690652222 0.999681556485255 0.00897254451576854 -0.00161473181129837 0.00795473138866444 -0.00916241856739927 0.999926383457567 0.00761391219262535 4.90899381850847e-05 4.32226053642797e-06 2.67702361119651e-06 1.89607301530348e-05 -1.6402037200926e-06 -1.98977887267931e-05 4.32226053642797e-06 4.50287739202752e-05 -5.70263312499769e-07 -1.96591209694498e-05 1.33397248573976e-06 -2.21397754763473e-05 2.67702361119651e-06 -5.70263312499769e-07 1.61229754112637e-05 4.62174903137758e-06 2.72719179017225e-06 6.66673322756331e-06 1.89607301530348e-05 -1.96591209694498e-05 4.62174903137758e-06 9.3481825663273e-05 -7.71560839542647e-06 3.2547208731243e-05 -1.6402037200926e-06 1.33397248573976e-06 2.72719179017225e-06 -7.71560839542647e-06 1.29986823955704e-05 -6.09942378825881e-06 -1.98977887267931e-05 -2.21397754763473e-05 6.66673322756331e-06 3.2547208731243e-05 -6.09942378825881e-06 0.000179519351673061 3244 3181 0 55 157 3244 3181 0 12 187 0 0 0 0 0 0 0 0 3728 0 0 0 0 0 3623 +213 214 0.995930353205174 -0.0280578450011905 0.0856474687221226 0.173974358392007 0.0267530801935496 0.999508447359231 0.0163443065835311 0.00987871617098145 -0.0860639545034697 -0.0139864574295323 0.996191434787409 0.0503322473833354 6.48278662500118e-05 -0.000305897337272706 1.98296167801386e-07 -4.34464647121175e-05 2.70375353953586e-06 -8.12359331128605e-05 -0.000305897337272706 0.0128726935592046 0.000315867164842806 0.00124410332872889 -2.63705474256445e-05 0.0016346316008747 1.98296167801386e-07 0.000315867164842806 2.21201888905945e-05 3.14173882361633e-05 1.5516674512223e-06 4.70550563814838e-05 -4.34464647121175e-05 0.00124410332872889 3.14173882361633e-05 0.000322133822797762 -1.24383553128778e-05 0.000549885617163871 2.70375353953586e-06 -2.63705474256445e-05 1.5516674512223e-06 -1.24383553128778e-05 1.39493440385859e-05 -8.85176793776525e-05 -8.12359331128605e-05 0.0016346316008747 4.70550563814838e-05 0.000549885617163871 -8.85176793776525e-05 0.00419330083755295 2887 2854 0 127 248 2887 2854 0 53 281 0 0 0 0 0 0 0 0 3339 0 0 0 0 0 3507 +210 211 0.999923449715414 0.0110264416636216 -0.00561358116226578 0.149499312948641 -0.010975742613704 0.999899409073831 0.00898358546910754 -0.00234700939943794 0.00571207346804282 -0.00892128455110511 0.999943889875154 0.027087409268613 3.9129287023221e-05 -1.03624666161346e-05 4.77865571860208e-06 7.09742210302262e-06 3.41268145689569e-06 -7.97736023774275e-06 -1.03624666161346e-05 6.1782555883316e-05 1.29486647765384e-06 -1.01687447572093e-06 1.21015477917812e-06 -2.01036380351378e-05 4.77865571860208e-06 1.29486647765384e-06 1.3627781912613e-05 -3.76164298681159e-07 3.41331375864171e-06 -1.89124386197064e-06 7.09742210302262e-06 -1.01687447572093e-06 -3.76164298681159e-07 0.000105857595549209 2.53633943798427e-07 8.72996468562614e-05 3.41268145689569e-06 1.21015477917812e-06 3.41331375864171e-06 2.53633943798427e-07 1.16857225412634e-05 -1.34845848940141e-06 -7.97736023774275e-06 -2.01036380351378e-05 -1.89124386197064e-06 8.72996468562614e-05 -1.34845848940141e-06 0.000311228602150505 3086 3061 0 198 100 3086 3061 0 127 135 0 0 0 0 0 0 0 0 3454 0 0 0 0 0 3704 +215 216 0.998851123511849 -0.00773894483279997 0.0472920901630673 0.172808901278587 0.00830871478078618 0.999895109250626 -0.0118632101629721 0.0074929397106808 -0.0471953209312994 0.012242517288294 0.998810653954311 0.0752361515218442 5.57373330760157e-05 -2.18479213655334e-05 8.03145874307954e-06 -8.9136814497554e-06 3.29229683767583e-07 5.0664120442813e-06 -2.18479213655334e-05 0.000100471441578627 -2.63538031137341e-06 2.03309657407277e-05 -2.67098390018682e-06 7.85520585328249e-05 8.03145874307954e-06 -2.63538031137341e-06 1.43645777021843e-05 1.35198242265023e-06 3.03047420176722e-06 8.48134067650982e-06 -8.9136814497554e-06 2.03309657407277e-05 1.35198242265023e-06 0.000218323669678393 -7.92796417214032e-06 0.000159073050310546 3.29229683767583e-07 -2.67098390018682e-06 3.03047420176722e-06 -7.92796417214032e-06 1.23104133804939e-05 -1.62473315168365e-05 5.0664120442813e-06 7.85520585328249e-05 8.48134067650982e-06 0.000159073050310546 -1.62473315168365e-05 0.000614036392479195 3267 3223 0 184 193 3267 3223 0 99 222 0 0 0 0 0 0 0 0 3535 0 0 0 0 0 3589 +214 215 0.999463226601723 -0.0252724433464944 -0.0208461573958329 0.151849737941653 0.0256592311682042 0.999499544193586 0.018500405743387 0.0097513675760226 0.0203681743592859 -0.019025371589315 0.999611510892686 -0.0478787095867961 8.3126686651212e-05 1.05720688263854e-05 -1.65330699705551e-06 2.44377545868996e-05 2.80147397276653e-06 2.53352214004308e-06 1.05720688263854e-05 7.73806139246145e-05 -3.80207353433263e-06 2.4815385700226e-05 1.08438753796905e-06 3.93182500938986e-06 -1.65330699705551e-06 -3.80207353433263e-06 1.74162214813494e-05 2.60231852593452e-06 1.33362165574742e-06 7.60662376916217e-06 2.44377545868996e-05 2.4815385700226e-05 2.60231852593452e-06 0.0001501642853063 -6.16764256954131e-08 9.65644398115283e-05 2.80147397276653e-06 1.08438753796905e-06 1.33362165574742e-06 -6.16764256954131e-08 1.39477763607484e-05 -5.57458006909698e-06 2.53352214004308e-06 3.93182500938986e-06 7.60662376916217e-06 9.65644398115283e-05 -5.57458006909698e-06 0.000250376210102914 3164 3117 0 96 206 3164 3117 0 14 241 0 0 0 0 0 0 0 0 3492 0 0 0 0 0 3582 +220 221 0.999884566434106 0.0148652582636194 -0.0031429132402714 0.136497804478532 -0.0147994770857194 0.999690267791162 0.020008597192799 0.00499834399390507 0.00343937274357499 -0.0199597740565947 0.999794868027807 -0.00248278580469281 5.27563206036576e-05 -3.11705696910397e-06 8.57571585066076e-06 -3.91802384035716e-06 1.677828187366e-06 -3.94141565998753e-06 -3.11705696910397e-06 5.79896467836232e-05 1.45312634689072e-06 4.29421060128857e-06 -6.14595200751376e-07 3.01716028831167e-05 8.57571585066076e-06 1.45312634689072e-06 1.37135539172015e-05 -2.11428963217172e-06 2.16503190422721e-06 8.18029206641026e-06 -3.91802384035716e-06 4.29421060128857e-06 -2.11428963217172e-06 0.000140083394166608 4.71558161634671e-06 2.34094871422614e-05 1.677828187366e-06 -6.14595200751376e-07 2.16503190422721e-06 4.71558161634671e-06 1.09625255686688e-05 -4.65215260947796e-06 -3.94141565998753e-06 3.01716028831167e-05 8.18029206641026e-06 2.34094871422614e-05 -4.65215260947796e-06 0.000371261426756902 3003 2969 0 181 83 3003 2969 0 99 122 0 0 0 0 0 0 0 0 3593 0 0 0 0 0 3734 +223 224 0.999866425921393 -0.0159795754991331 0.00343270768442802 0.132755679647668 0.0160140822511648 0.999819003739051 -0.0102717540812116 0.00440657329379012 -0.00326794810732295 0.0103253537043272 0.999941352073235 -0.0179647983206319 6.38880309730308e-05 9.56635777406752e-07 9.42281019476799e-06 -1.67093529218833e-06 1.60314773372477e-06 -1.87868981874559e-05 9.56635777406752e-07 2.01103513328663e-05 -1.82357850366033e-06 -3.12738363998548e-06 -2.88578574348971e-06 3.19785347407913e-07 9.42281019476799e-06 -1.82357850366033e-06 1.79506524820967e-05 -3.6936686669138e-06 1.95984231433017e-06 7.97417018325759e-06 -1.67093529218833e-06 -3.12738363998548e-06 -3.6936686669138e-06 8.56500523930526e-05 6.77047724966657e-06 3.78023405029368e-06 1.60314773372477e-06 -2.88578574348971e-06 1.95984231433017e-06 6.77047724966657e-06 1.16985929886899e-05 -5.03772214947218e-07 -1.87868981874559e-05 3.19785347407913e-07 7.97417018325759e-06 3.78023405029368e-06 -5.03772214947218e-07 0.000117346140145793 3433 3390 0 107 154 3433 3390 0 20 195 0 0 0 0 0 0 0 0 3644 0 0 0 0 0 3640 +216 217 0.999982243218649 -0.000183524505395379 0.00595647262682165 0.143339303809029 0.000150106284204114 0.999984250502301 0.00561036678427403 0.00527348559956245 -0.00595740845515889 -0.00560937305824477 0.999966521548793 -0.0531490667790747 9.21997736385365e-05 7.7218364076928e-05 3.56514627135203e-06 -3.79292558424977e-06 4.14994878826082e-06 -2.90749093419878e-05 7.7218364076928e-05 0.000291900900750084 1.23135484243561e-06 7.38263926130047e-05 4.31165699796991e-06 2.2455699836478e-06 3.56514627135203e-06 1.23135484243561e-06 1.85991361519646e-05 -6.84646068088707e-06 2.37928537374513e-06 -1.62868904376771e-05 -3.79292558424977e-06 7.38263926130047e-05 -6.84646068088707e-06 0.000194632113466253 -1.53301359774441e-06 0.00019601640414066 4.14994878826082e-06 4.31165699796991e-06 2.37928537374513e-06 -1.53301359774441e-06 1.38498249581312e-05 -1.84656965821732e-05 -2.90749093419878e-05 2.2455699836478e-06 -1.62868904376771e-05 0.00019601640414066 -1.84656965821732e-05 0.00108381522328791 3086 3036 0 161 126 3086 3036 0 77 162 0 0 0 0 0 0 0 0 3588 0 0 0 0 0 3657 +224 225 0.999058755964403 -0.0420125813676849 -0.0107956073328017 0.135424113941342 0.0420674894333079 0.999102704936177 0.00491032809428045 0.00448667235875718 0.010579624929028 -0.00535985037464766 0.999929669296957 0.0172141073870971 4.80562791917374e-05 1.41454207977739e-06 4.02403486396566e-06 1.51426571257202e-06 2.57418936554727e-06 -9.05946525650414e-06 1.41454207977739e-06 2.3659319197799e-05 -1.45906666298276e-06 -1.52047215824366e-06 -4.24652586412149e-07 -2.68266377879971e-06 4.02403486396566e-06 -1.45906666298276e-06 1.19897961990109e-05 1.99506932049228e-06 3.27872797986379e-06 -2.04594737471561e-07 1.51426571257202e-06 -1.52047215824366e-06 1.99506932049228e-06 9.75796849443321e-05 1.27735657426744e-06 -6.66001861356041e-06 2.57418936554727e-06 -4.24652586412149e-07 3.27872797986379e-06 1.27735657426744e-06 1.04390403622094e-05 1.54531155016778e-07 -9.05946525650414e-06 -2.68266377879971e-06 -2.04594737471561e-07 -6.66001861356041e-06 1.54531155016778e-07 0.000116992253758861 3107 3029 0 39 219 3107 3029 0 0 252 0 0 0 0 0 0 0 0 3693 0 0 0 0 0 3571 +227 228 0.998551510491825 -0.0331222787125936 0.0424004191887184 0.149523597896881 0.0331359581349607 0.99945078099187 0.000380333038724014 0.00102040983164025 -0.0423897295694595 0.00102519638483435 0.999100625462421 0.0266774805653067 3.84370160145314e-05 7.68145779524607e-06 4.79910449852827e-06 -8.79409979719667e-06 -6.05096736020639e-07 1.89272909211848e-05 7.68145779524607e-06 2.14876970721011e-05 1.8657632776829e-06 3.0332849123639e-06 -2.66804335008496e-06 1.67464092116809e-05 4.79910449852827e-06 1.8657632776829e-06 1.64800256321897e-05 -2.69553907821172e-06 1.40553772280723e-06 3.06526649632721e-07 -8.79409979719667e-06 3.0332849123639e-06 -2.69553907821172e-06 5.12196200081266e-05 4.37243275016386e-06 -7.77773217938297e-06 -6.05096736020639e-07 -2.66804335008496e-06 1.40553772280723e-06 4.37243275016386e-06 1.17705528457096e-05 -8.06739171581178e-07 1.89272909211848e-05 1.67464092116809e-05 3.06526649632721e-07 -7.77773217938297e-06 -8.06739171581178e-07 0.000234133711408383 3330 3224 0 124 225 3330 3224 0 9 234 0 0 0 0 0 0 0 0 3474 0 0 0 0 0 3444 +228 229 0.999755259768515 -0.0203298833103465 -0.00872447189101415 0.139949671041252 0.0203748273150223 0.999779435009147 0.00509389288014116 -0.00622646745123054 0.00861898933010263 -0.00527040580781269 0.999948966620571 0.0140846092410928 5.6850613436624e-05 3.51102865971912e-05 9.60534467438332e-07 -8.99295854954207e-06 2.25635458147072e-06 -1.24348200773019e-05 3.51102865971912e-05 6.91873246183705e-05 -3.07073595467234e-07 1.08432145456173e-06 -7.13446705040937e-07 -1.92613259260474e-05 9.60534467438332e-07 -3.07073595467234e-07 1.45377174536755e-05 -1.1315618966564e-06 5.54722188296138e-06 4.320823440551e-06 -8.99295854954207e-06 1.08432145456173e-06 -1.1315618966564e-06 0.000100726462261387 -1.07714480524294e-05 1.87076648172195e-05 2.25635458147072e-06 -7.13446705040937e-07 5.54722188296138e-06 -1.07714480524294e-05 1.35369857048687e-05 -1.83457542796442e-06 -1.24348200773019e-05 -1.92613259260474e-05 4.320823440551e-06 1.87076648172195e-05 -1.83457542796442e-06 0.000182947830734789 2745 2629 0 157 183 2745 2629 0 23 192 0 0 0 0 0 0 0 0 2799 0 0 0 0 0 3485 +219 220 0.998975228389514 0.0170768869148852 -0.0419150688585281 0.131719074077058 -0.0171979529838909 0.999848904717278 -0.0025294562307315 0.00728628257444662 0.0418655404513402 0.0032477174993418 0.999117975443221 -0.0147958658764242 5.56448340244041e-05 -8.24956526268986e-06 -2.31095744004908e-06 1.41225683565453e-05 1.34603462844783e-06 -8.63956262950172e-06 -8.24956526268986e-06 4.87816981438723e-05 -2.48143531537375e-06 8.92517723779127e-06 7.86948270449463e-07 -2.08057006514043e-05 -2.31095744004908e-06 -2.48143531537375e-06 1.41102616671139e-05 -3.47799708334116e-06 3.90066557680314e-06 -7.906867035368e-07 1.41225683565453e-05 8.92517723779127e-06 -3.47799708334116e-06 0.000108790474423407 6.91100699459498e-06 9.96077285759238e-06 1.34603462844783e-06 7.86948270449463e-07 3.90066557680314e-06 6.91100699459498e-06 1.163174946022e-05 3.73751427387044e-06 -8.63956262950172e-06 -2.08057006514043e-05 -7.906867035368e-07 9.96077285759238e-06 3.73751427387044e-06 0.00013674897305162 3245 3209 0 176 70 3245 3209 0 91 107 0 0 0 0 0 0 0 0 3590 0 0 0 0 0 3747 +221 222 0.999092701167767 -0.00424023339675189 0.0423768202445171 0.126071927891982 0.00371584145426535 0.999915646022046 0.0124456162001097 0.00761539966092235 -0.0424260179086113 -0.0122768587617004 0.999024179759111 0.0374363514241481 7.16647580183365e-05 1.30424015642572e-05 5.7036704739504e-06 2.7616775248893e-05 1.3186544231928e-06 -1.85976199786701e-05 1.30424015642572e-05 3.50768852132668e-05 3.04812122409821e-06 7.80344237820239e-06 -1.63667857908679e-06 -7.15991806127333e-06 5.7036704739504e-06 3.04812122409821e-06 1.36514022753587e-05 -7.81250496376468e-07 3.00581604668125e-06 -1.40518285557146e-07 2.7616775248893e-05 7.80344237820239e-06 -7.81250496376468e-07 0.000115515733127912 5.30725262233482e-06 1.25693781764215e-05 1.3186544231928e-06 -1.63667857908679e-06 3.00581604668125e-06 5.30725262233482e-06 1.08832748293952e-05 1.34253049556992e-06 -1.85976199786701e-05 -7.15991806127333e-06 -1.40518285557146e-07 1.25693781764215e-05 1.34253049556992e-06 0.000181354322332553 2980 2943 0 121 124 2980 2943 0 48 159 0 0 0 0 0 0 0 0 3633 0 0 0 0 0 3698 +218 219 0.999573518487387 0.0272182590485447 0.0105805251812968 0.132005762647941 -0.0269907120934966 0.999413293035993 -0.0210848562631536 0.00762824059744299 -0.011148210593262 0.0207902880527949 0.999721701936719 -0.0223261473625945 5.22976790736484e-05 -3.19922829872741e-06 5.79049856096922e-06 5.13430898490339e-06 2.30512482286149e-06 -1.26597852796434e-05 -3.19922829872741e-06 6.57279785983297e-05 -5.91574739808151e-06 1.00203731178659e-05 6.64217305699533e-07 0.00010262594195985 5.79049856096922e-06 -5.91574739808151e-06 1.57566430463098e-05 2.0369214523148e-06 2.79278649537064e-06 7.05351400542387e-06 5.13430898490339e-06 1.00203731178659e-05 2.0369214523148e-06 7.37695166262303e-05 2.56131481473761e-06 2.28337754070403e-05 2.30512482286149e-06 6.64217305699533e-07 2.79278649537064e-06 2.56131481473761e-06 1.12797828850037e-05 6.04573366364197e-06 -1.26597852796434e-05 0.00010262594195985 7.05351400542387e-06 2.28337754070403e-05 6.04573366364197e-06 0.000593041986379765 3387 3347 0 211 52 3387 3347 0 119 82 0 0 0 0 0 0 0 0 3552 0 0 0 0 0 3769 +229 230 0.998940367690592 -0.0430482564527264 -0.0162784954637974 0.141131176642033 0.0426145101512363 0.998750241555992 -0.0261143354580733 -0.00423518195387467 0.0173823278865275 0.0253929637542944 0.999526413892609 0.0145264835399402 5.1196980320138e-05 2.76541886765212e-05 -3.62402418429129e-06 -4.92119563989969e-06 2.55450876720344e-06 -5.00926077810514e-06 2.76541886765212e-05 8.69844778967122e-05 -7.74610622349593e-06 1.46423896978649e-05 -3.33958692858055e-06 2.7089148437474e-05 -3.62402418429129e-06 -7.74610622349593e-06 1.56635254099096e-05 7.23964141505585e-06 3.47060191500704e-06 4.23120372145959e-06 -4.92119563989969e-06 1.46423896978649e-05 7.23964141505585e-06 8.79347013662577e-05 -1.2387850761989e-05 5.4928733536422e-05 2.55450876720344e-06 -3.33958692858055e-06 3.47060191500704e-06 -1.2387850761989e-05 1.63826219673229e-05 -4.53453605581556e-06 -5.00926077810514e-06 2.7089148437474e-05 4.23120372145959e-06 5.4928733536422e-05 -4.53453605581556e-06 0.000413354485024569 2687 2555 0 97 250 2687 2555 0 0 251 0 0 0 0 0 0 0 0 2169 0 0 0 0 0 3400 +230 231 0.998612849091093 -0.0492901774664152 -0.018516372093313 0.119757224007886 0.0493314530862552 0.998780878749139 0.00177875841421462 -0.0119739711125549 0.0184061230726986 -0.00268973054911253 0.999826975022681 -0.0236807456447554 5.30494553230762e-05 1.8236845684055e-05 7.81214366065527e-07 5.98211779633393e-06 -9.08320472550658e-07 -1.78788800569894e-05 1.8236845684055e-05 4.27220710208486e-05 -5.14218716569701e-07 1.98792779593737e-05 -6.34955468699012e-06 -5.47244103478567e-06 7.81214366065527e-07 -5.14218716569701e-07 1.09201329562781e-05 4.28156434957626e-06 3.16137910132171e-06 -1.44123754759062e-06 5.98211779633393e-06 1.98792779593737e-05 4.28156434957626e-06 0.000105878791132606 -2.08146026547387e-05 4.41522004206817e-05 -9.08320472550658e-07 -6.34955468699012e-06 3.16137910132171e-06 -2.08146026547387e-05 1.86956020576308e-05 -9.69509158033911e-06 -1.78788800569894e-05 -5.47244103478567e-06 -1.44123754759062e-06 4.41522004206817e-05 -9.69509158033911e-06 0.000119801928909476 2577 2433 0 60 202 2572 2433 0 0 197 0 0 0 0 0 0 0 0 1794 0 0 0 0 0 3324 +217 218 0.999775735817182 0.0205384134988992 -0.00516252284832763 0.129170793575008 -0.0205164722128949 0.999780406284076 0.0042677369161066 0.00334350518099777 0.00524904173623934 -0.00416086305900848 0.999977567138111 0.00316233924851751 8.0043340438083e-05 9.21938339110861e-06 -4.72979134738219e-06 1.11750324049862e-05 2.65736709815449e-06 -2.24047671152916e-06 9.21938339110861e-06 4.47808400884198e-05 -1.29019520782796e-06 3.35537910211565e-06 -1.73375063658917e-06 2.51159572393515e-05 -4.72979134738219e-06 -1.29019520782796e-06 1.64001064432912e-05 1.87202141059842e-06 4.10761472148254e-06 5.32273932141987e-06 1.11750324049862e-05 3.35537910211565e-06 1.87202141059842e-06 0.000108023815530186 -6.45712305128009e-07 3.96265103575598e-05 2.65736709815449e-06 -1.73375063658917e-06 4.10761472148254e-06 -6.45712305128009e-07 1.33447603122834e-05 -5.68232110782503e-06 -2.24047671152916e-06 2.51159572393515e-05 5.32273932141987e-06 3.96265103575598e-05 -5.68232110782503e-06 0.000283450747052099 3242 3197 0 186 62 3242 3197 0 102 90 0 0 0 0 0 0 0 0 3577 0 0 0 0 0 3735 +231 232 0.998989253224916 -0.0431224262781292 0.0126857515745442 0.125186467819899 0.0429649241213758 0.998999169410971 0.0124368328538829 -0.0250110627385881 -0.0132093616941986 -0.0118792200113607 0.999842185995147 -0.00503461769288418 3.27297258690313e-05 3.6177557311558e-06 2.80840237758081e-06 -7.71963426988137e-06 1.10183582604252e-06 -1.48890766167692e-05 3.6177557311558e-06 3.41244432912e-05 -7.507200196319e-06 7.04385866691786e-06 -1.79064927746372e-06 9.84960447150795e-07 2.80840237758081e-06 -7.507200196319e-06 1.54476953859516e-05 -2.70587543384554e-06 3.89678955939363e-06 -1.36493537162799e-06 -7.71963426988137e-06 7.04385866691786e-06 -2.70587543384554e-06 6.58770593558878e-05 -6.0399124904652e-06 1.81043193896484e-05 1.10183582604252e-06 -1.79064927746372e-06 3.89678955939363e-06 -6.0399124904652e-06 1.46309120360655e-05 -2.7777518165243e-06 -1.48890766167692e-05 9.84960447150795e-07 -1.36493537162799e-06 1.81043193896484e-05 -2.7777518165243e-06 8.45768667850347e-05 3289 3115 0 74 115 3289 3115 0 0 100 0 0 0 0 0 0 0 0 1600 0 4 0 0 0 3428 +222 223 0.999662613064284 -0.021423744983977 -0.0146861564866231 0.136733901484252 0.0215013538619566 0.999755569663978 0.00514710675597742 0.00741554918454338 0.0145722964419129 -0.00546114243689217 0.999878904717813 0.00427125777368698 7.28345450237251e-05 -6.16427792349077e-07 5.46728714019087e-06 -1.12066277040455e-05 2.11473721638248e-08 -4.02246618783227e-05 -6.16427792349077e-07 0.000148152315292242 8.23132235299098e-06 -1.49955089368777e-05 -7.47645471328861e-06 0.000303296759980709 5.46728714019087e-06 8.23132235299098e-06 1.73240083100389e-05 -3.79701901214787e-06 3.3561275847466e-06 3.08048354938122e-05 -1.12066277040455e-05 -1.49955089368777e-05 -3.79701901214787e-06 9.38074886616711e-05 7.22973213928846e-06 -2.12527639405368e-05 2.11473721638248e-08 -7.47645471328861e-06 3.3561275847466e-06 7.22973213928846e-06 1.2498104693741e-05 -2.48433496315696e-05 -4.02246618783227e-05 0.000303296759980709 3.08048354938122e-05 -2.12527639405368e-05 -2.48433496315696e-05 0.00141142105203834 3148 3105 0 82 166 3148 3105 0 7 207 0 0 0 0 0 0 0 0 3667 0 0 0 0 0 3629 +225 226 0.998275904256402 -0.052731787915169 -0.0257794011631728 0.137748296373308 0.0519288410911169 0.998173150591697 -0.0308829548582799 0.0123275669162196 0.0273608195051921 0.0294910152608325 0.999190505146486 -0.0575230138135783 7.20955762844215e-05 -1.45967208450464e-05 6.49226141935975e-06 -1.33985351541265e-05 1.75722429155725e-06 -9.88344187812579e-06 -1.45967208450464e-05 4.07348401990025e-05 -5.17870784679579e-06 4.36547625437684e-06 -2.44421177409974e-06 1.19134286341769e-05 6.49226141935975e-06 -5.17870784679579e-06 1.71114246333871e-05 1.70425672176604e-06 3.88261629918935e-06 1.51407649435484e-05 -1.33985351541265e-05 4.36547625437684e-06 1.70425672176604e-06 6.59511182628169e-05 2.68413805398357e-06 1.85183923309601e-05 1.75722429155725e-06 -2.44421177409974e-06 3.88261629918935e-06 2.68413805398357e-06 1.12146699224575e-05 -2.74975775475685e-06 -9.88344187812579e-06 1.19134286341769e-05 1.51407649435484e-05 1.85183923309601e-05 -2.74975775475685e-06 0.000281909023203932 3269 3153 0 12 205 3253 3153 0 0 206 0 0 0 0 0 0 0 0 3701 0 0 0 0 0 3545 +226 227 0.998464331879209 -0.0546632201350865 0.008995016924277 0.139677537535059 0.0546086650080393 0.998488566048615 0.00620299735781296 0.00512077287072179 -0.00932049736037185 -0.00570226574655773 0.999940304465377 -0.0133693899470852 5.48761650710624e-05 1.53176497665243e-05 2.38408231329344e-06 1.23520545621371e-07 3.41761653367839e-06 4.07043531663061e-05 1.53176497665243e-05 0.000135367845172492 -9.22267011661336e-06 2.13229144574734e-05 3.46347354028492e-06 0.0003238683438074 2.38408231329344e-06 -9.22267011661336e-06 1.62746333672341e-05 4.64906210279809e-06 3.80361845848727e-06 -1.315621723815e-05 1.23520545621371e-07 2.13229144574734e-05 4.64906210279809e-06 7.30858468046702e-05 -8.83953562342375e-07 0.000116132758080525 3.41761653367839e-06 3.46347354028492e-06 3.80361845848727e-06 -8.83953562342375e-07 1.20746478885477e-05 1.61245471068729e-05 4.07043531663061e-05 0.0003238683438074 -1.315621723815e-05 0.000116132758080525 1.61245471068729e-05 0.00185487717747352 3099 3011 0 28 280 3091 3011 0 0 272 0 0 0 0 0 0 0 0 3680 0 0 0 0 0 3448 +241 242 0.99789922585518 -0.060804352365744 -0.02235991437852 0.0161380299068285 0.0606406425910505 0.998128171616585 -0.00792877616521519 -0.0447858122429047 0.0228001645559144 0.00655620002105292 0.999718544760228 -0.00801272900423744 2.53016373626596e-05 1.05599586779847e-05 2.81596070165605e-06 -4.21548725085435e-06 3.35973820457062e-06 -2.22693695548054e-07 1.05599586779847e-05 5.44576318065225e-05 7.33737249433099e-06 -4.50627879520956e-06 -3.24963798080174e-06 1.69746942312689e-05 2.81596070165605e-06 7.33737249433099e-06 1.88872242822222e-05 -3.7086367924717e-06 4.65834000252172e-06 9.08525343384274e-07 -4.21548725085435e-06 -4.50627879520956e-06 -3.7086367924717e-06 2.85399772394228e-05 -1.96908550356287e-05 1.6355335165866e-05 3.35973820457062e-06 -3.24963798080174e-06 4.65834000252172e-06 -1.96908550356287e-05 7.77767402438415e-05 -8.28939908336578e-06 -2.22693695548054e-07 1.69746942312689e-05 9.08525343384274e-07 1.6355335165866e-05 -8.28939908336578e-06 0.000125573751607332 689 773 0 0 5 689 774 0 0 65 0 0 0 0 0 0 0 0 2637 0 0 0 0 0 2599 +239 240 0.999115543430243 -0.0416396800651522 0.00585388077788992 0.0489901593200276 0.0416434377729464 0.999132399726182 -0.000521447841309158 -0.054108447617552 -0.00582708902804135 0.000764762363244433 0.999982729936866 0.00834495437305203 2.02675232228601e-05 5.44167798080817e-06 7.85650461985881e-07 -5.26521873796652e-06 7.18681432896624e-06 1.61845296136911e-06 5.44167798080817e-06 4.38755974475487e-05 1.85769082462156e-06 1.7978268117552e-06 -1.15720986505042e-05 -2.05133605656818e-07 7.85650461985881e-07 1.85769082462156e-06 1.16552773205358e-05 2.48162219311598e-06 9.75105591204131e-07 6.57276448786468e-06 -5.26521873796652e-06 1.7978268117552e-06 2.48162219311598e-06 2.58174400634225e-05 -2.52737348336132e-05 1.11528225075878e-05 7.18681432896624e-06 -1.15720986505042e-05 9.75105591204131e-07 -2.52737348336132e-05 6.39003853312984e-05 7.87091460358696e-07 1.61845296136911e-06 -2.05133605656818e-07 6.57276448786468e-06 1.11528225075878e-05 7.87091460358696e-07 0.000107331369305394 1095 1135 0 0 67 1095 1135 0 0 90 0 0 0 0 0 0 0 0 2483 0 0 0 0 0 2851 +234 235 0.995233413635666 -0.0964526340028618 -0.0143993672433407 0.104379172609214 0.096385718834991 0.995330092772694 -0.00527253504132501 -0.0371746100714718 0.0148406734267905 0.00385950968517315 0.999882422386367 -0.0128271296820867 2.17632300567603e-05 8.00219657354461e-06 -9.72303330314599e-07 4.12677074943319e-06 -2.63993015671997e-06 -3.40163244387208e-07 8.00219657354461e-06 2.71557237417986e-05 5.48269165998956e-07 3.44662813717468e-06 -4.33472687359727e-06 7.5610042550335e-07 -9.72303330314599e-07 5.48269165998956e-07 1.28206230998779e-05 4.46758756680182e-06 2.91261869077338e-06 -1.6327550576603e-06 4.12677074943319e-06 3.44662813717468e-06 4.46758756680182e-06 3.09245506094062e-05 -5.79788159054288e-06 8.61936054210633e-06 -2.63993015671997e-06 -4.33472687359727e-06 2.91261869077338e-06 -5.79788159054288e-06 1.77455141439977e-05 2.12134441221183e-06 -3.40163244387208e-07 7.5610042550335e-07 -1.6327550576603e-06 8.61936054210633e-06 2.12134441221183e-06 0.000116949983460729 2770 2726 0 0 231 2770 2726 0 0 202 0 0 0 0 0 0 0 0 1709 0 0 0 0 0 3148 +236 237 0.978966343160793 -0.196251320710622 -0.0557702257277135 0.0924263851208705 0.195256617794781 0.980486869939379 -0.0228112052251168 -0.0378968441186232 0.0591587032120087 0.0114418965130782 0.998183014701441 -0.0100809227854095 4.45279683383372e-05 1.5190441924906e-05 2.03025686612749e-07 2.24440311272053e-06 -1.31564461262213e-05 -2.33604228408022e-05 1.5190441924906e-05 4.78238167172715e-05 -2.85778910885378e-06 -9.45335267510418e-07 1.53251154682954e-07 4.49272201015981e-05 2.03025686612749e-07 -2.85778910885378e-06 1.47598228104247e-05 4.31313765742075e-06 2.86893661028122e-06 5.2823106622734e-07 2.24440311272053e-06 -9.45335267510418e-07 4.31313765742075e-06 2.51581630056477e-05 -9.93914439629672e-06 1.2221242950374e-05 -1.31564461262213e-05 1.53251154682954e-07 2.86893661028122e-06 -9.93914439629672e-06 3.85637321744107e-05 2.72160162376659e-05 -2.33604228408022e-05 4.49272201015981e-05 5.2823106622734e-07 1.2221242950374e-05 2.72160162376659e-05 0.000284517267676816 2110 2082 0 0 201 2110 2082 0 0 176 0 0 0 0 0 0 0 0 2031 0 0 0 0 0 2169 +232 233 0.997888905382812 -0.0617412717038036 0.0201431845121532 0.131939106808618 0.0620436129217838 0.997964497958996 -0.0147462167711464 -0.0286144703076743 -0.0191917328426958 0.015964842055181 0.999688352042099 0.02894698156446 3.01840034278812e-05 -4.96547089467891e-06 3.84736711055029e-07 -8.19695013679317e-06 3.24848509962608e-07 -1.14491527091668e-05 -4.96547089467891e-06 2.37303219090907e-05 -5.72174950929109e-06 4.200106306263e-06 -4.00747473580522e-06 1.87368075758674e-06 3.84736711055029e-07 -5.72174950929109e-06 1.3651890221342e-05 2.34073920896088e-06 4.31612135334457e-06 3.49206749507151e-06 -8.19695013679317e-06 4.200106306263e-06 2.34073920896088e-06 4.56090757443318e-05 -3.39597762616597e-06 2.21190661052039e-05 3.24848509962608e-07 -4.00747473580522e-06 4.31612135334457e-06 -3.39597762616597e-06 1.44577898128138e-05 -4.00356509148592e-06 -1.14491527091668e-05 1.87368075758674e-06 3.49206749507151e-06 2.21190661052039e-05 -4.00356509148592e-06 6.93520531330004e-05 3515 3323 0 12 212 3515 3323 0 0 172 0 0 0 0 0 0 0 0 1598 0 0 0 0 0 3024 +237 238 0.987822545263657 -0.155519000265173 -0.00452323173753184 0.0791114109752244 0.15510954769783 0.986659606194904 -0.0494353083968457 -0.0499121272891556 0.0121510197845594 0.0481317157375249 0.998767085289837 -0.00648680699579 1.88017298493569e-05 1.30913830914227e-05 3.28376045160912e-06 -7.363621891063e-06 5.15137465287054e-06 1.12848555677109e-05 1.30913830914227e-05 3.36399186160773e-05 -1.3420009525296e-07 -1.10287883539736e-06 -2.36860623900818e-06 1.77766935445478e-05 3.28376045160912e-06 -1.3420009525296e-07 1.70834835964668e-05 -5.82191184898303e-06 1.17859853584698e-05 4.42081120623021e-06 -7.363621891063e-06 -1.10287883539736e-06 -5.82191184898303e-06 4.31685253932705e-05 -3.78639921630911e-05 1.8075167262784e-05 5.15137465287054e-06 -2.36860623900818e-06 1.17859853584698e-05 -3.78639921630911e-05 8.0761559262045e-05 1.19065707187737e-05 1.12848555677109e-05 1.77766935445478e-05 4.42081120623021e-06 1.8075167262784e-05 1.19065707187737e-05 0.000160685803285634 1628 1620 0 0 376 1628 1620 0 0 339 0 0 0 0 0 0 0 0 2142 0 0 0 0 0 2704 +235 236 0.99027685029525 -0.138073951434489 0.0169512154309156 0.120235516633253 0.137943299336583 0.990402314698716 0.00865454837431872 -0.051800713477739 -0.0179834906916586 -0.00623209232054252 0.999818861138282 0.0751042732999142 3.50224583414122e-05 9.39607389910993e-06 -2.02115048145795e-06 4.64311662189793e-07 -4.26290934141232e-07 -5.90680247011814e-06 9.39607389910993e-06 3.35156831304053e-05 -4.82508880074689e-06 -4.34038716634732e-06 1.1361369589931e-06 -2.93101205331623e-06 -2.02115048145795e-06 -4.82508880074689e-06 1.35125318633259e-05 8.18503448652211e-06 -4.18325307559686e-06 3.24694754531146e-06 4.64311662189793e-07 -4.34038716634732e-06 8.18503448652211e-06 3.98020252411244e-05 -2.26970335662409e-05 1.22865209865945e-05 -4.26290934141232e-07 1.1361369589931e-06 -4.18325307559686e-06 -2.26970335662409e-05 3.34608031899843e-05 -1.44188982873451e-06 -5.90680247011814e-06 -2.93101205331623e-06 3.24694754531146e-06 1.22865209865945e-05 -1.44188982873451e-06 0.000123559531109792 2689 2686 0 0 150 2689 2686 0 0 111 0 0 0 0 0 0 0 0 1821 0 0 0 0 0 3094 +246 247 0.999772600453828 -0.0198874123780501 0.00769663632346591 -0.0107830560773828 0.0198751728350445 0.9998010853751 0.0016634865643767 -0.0706864245122992 -0.00772818779322974 -0.00151013631110954 0.999968996820279 -0.0288837321026359 2.04682354982999e-05 8.82771513279324e-06 -2.02726182554167e-06 1.33651232388321e-06 -1.72828555317837e-06 1.53128163469126e-05 8.82771513279324e-06 3.5395376876058e-05 2.25391054630002e-06 8.47125880029697e-07 2.44399189313394e-06 1.43701087197069e-05 -2.02726182554167e-06 2.25391054630002e-06 1.0933793529253e-05 1.93526361251422e-06 -4.59061668593508e-07 3.48394185586571e-07 1.33651232388321e-06 8.47125880029697e-07 1.93526361251422e-06 1.99590142549043e-05 -7.52978674310726e-06 1.47019039171796e-05 -1.72828555317837e-06 2.44399189313394e-06 -4.59061668593508e-07 -7.52978674310726e-06 6.03452740352916e-05 -1.02919346906939e-06 1.53128163469126e-05 1.43701087197069e-05 3.48394185586571e-07 1.47019039171796e-05 -1.02919346906939e-06 0.000141872914282084 364 364 0 0 0 478 499 0 0 0 0 0 0 0 0 1 0 0 3202 0 0 41 0 0 3162 +233 234 0.997165227886929 -0.0737433432107945 0.0149474956197977 0.129085256785938 0.0740123091051941 0.997089063186779 -0.0183187929250067 -0.0330335897585494 -0.0135530953706563 0.0193731619878388 0.999720458028376 0.0278324949929269 2.71363467163045e-05 2.30634389271473e-06 -5.06319366487475e-06 6.00320848109879e-07 -1.26119939432558e-06 -6.36751193063563e-06 2.30634389271473e-06 3.74888803628783e-05 -7.12638843622993e-06 1.01641880587691e-05 -8.54804203422912e-06 1.01062515800079e-05 -5.06319366487475e-06 -7.12638843622993e-06 2.09378508413995e-05 -8.58902598729968e-06 7.78762778950264e-06 1.83413004409311e-06 6.00320848109879e-07 1.01641880587691e-05 -8.58902598729968e-06 7.82806919502379e-05 -1.93031256516364e-05 2.68636516804242e-05 -1.26119939432558e-06 -8.54804203422912e-06 7.78762778950264e-06 -1.93031256516364e-05 2.06130007871269e-05 -5.95005865793537e-06 -6.36751193063563e-06 1.01062515800079e-05 1.83413004409311e-06 2.68636516804242e-05 -5.95005865793537e-06 0.000125755807162556 3006 2954 0 0 197 3006 2954 0 0 161 0 0 0 0 0 0 0 0 1633 0 0 0 0 0 3221 +243 244 0.999435439265795 -0.0258225818685298 0.0214941155954338 0.00585266915468199 0.0258122580624138 0.999666521042849 0.000757654146527565 -0.0581267673093436 -0.0215065123464069 -0.000202414746173639 0.999768687724798 0.0140991138403773 2.28498531407325e-05 1.91215976494432e-05 3.48008223792793e-06 -6.22277778224138e-07 2.13846028802912e-06 1.31378907175325e-05 1.91215976494432e-05 4.68366854509017e-05 3.50891030366271e-06 -1.59818997545999e-06 3.81005354337773e-06 1.11362227711445e-05 3.48008223792793e-06 3.50891030366271e-06 1.23581276701614e-05 -1.76930501337573e-07 1.13527619888686e-06 -5.40526990336755e-07 -6.22277778224138e-07 -1.59818997545999e-06 -1.76930501337573e-07 2.43182852997125e-05 -1.67733586692824e-05 1.40015825961441e-05 2.13846028802912e-06 3.81005354337773e-06 1.13527619888686e-06 -1.67733586692824e-05 6.10730637190347e-05 -1.17042388153115e-05 1.31378907175325e-05 1.11362227711445e-05 -5.40526990336755e-07 1.40015825961441e-05 -1.17042388153115e-05 0.000103181077810295 500 500 0 0 0 527 608 0 0 0 0 0 0 0 0 0 0 0 2810 0 0 0 0 0 3243 +240 241 0.995775232865591 -0.0851571107597008 -0.0343504308348158 0.0349453442431887 0.0845707203849509 0.996251620556283 -0.0181797082636432 -0.0491765156565793 0.0357698038161778 0.015197862548424 0.999244487655004 -0.0101653548498353 1.92317493240356e-05 1.43813770271849e-05 2.1368374923394e-06 -2.38215199073514e-06 6.4835038377008e-06 1.6548910848454e-05 1.43813770271849e-05 3.40742263797492e-05 1.39670131553724e-06 -3.68355472722088e-07 -7.30829496400812e-06 3.17201151384651e-06 2.1368374923394e-06 1.39670131553724e-06 1.3196872763574e-05 9.86785939554213e-07 8.6356407261547e-06 5.69000614388281e-06 -2.38215199073514e-06 -3.68355472722088e-07 9.86785939554213e-07 2.6114384122989e-05 -1.98158123041146e-05 7.33562834774081e-06 6.4835038377008e-06 -7.30829496400812e-06 8.6356407261547e-06 -1.98158123041146e-05 8.71665381113593e-05 2.02075416094505e-05 1.6548910848454e-05 3.17201151384651e-06 5.69000614388281e-06 7.33562834774081e-06 2.02075416094505e-05 0.000128413113670178 813 882 0 0 129 813 882 0 0 171 0 0 0 0 0 0 0 0 2488 0 0 0 0 0 3111 +245 246 0.998705991182032 -0.0507812578898407 -0.00275808343598146 -0.00561978672016486 0.0507350171782642 0.99860203912727 -0.0148298847864325 -0.0619849454463722 0.00350730794707069 0.0146707633742458 0.999886227274374 0.0049620938844374 4.17639392038607e-05 1.2672554267274e-05 -1.21696403603775e-07 -2.16058751571993e-07 -1.16337821569226e-05 7.56685449883944e-06 1.2672554267274e-05 4.09565945009199e-05 -2.09970395899407e-07 -5.35353002517025e-06 4.18419570748139e-06 5.84319286592572e-06 -1.21696403603775e-07 -2.09970395899407e-07 1.23801861548435e-05 1.21929051530783e-06 3.11949136140184e-07 5.44705648432428e-06 -2.16058751571993e-07 -5.35353002517025e-06 1.21929051530783e-06 2.11544029428593e-05 -5.78769710766638e-06 1.17247843348206e-05 -1.16337821569226e-05 4.18419570748139e-06 3.11949136140184e-07 -5.78769710766638e-06 8.20617125089402e-05 2.51494081922741e-06 7.56685449883944e-06 5.84319286592572e-06 5.44705648432428e-06 1.17247843348206e-05 2.51494081922741e-06 0.000159856911243023 411 411 0 0 0 427 534 0 0 0 0 0 0 0 0 0 0 0 2958 0 0 0 0 0 2384 +238 239 0.996555975580533 -0.0661283848412188 0.0500322321411212 0.0562260762536595 0.0661587280427529 0.997808557659791 0.00105117298838426 -0.0459334525952154 -0.0499921017611426 0.00226251611665314 0.998747050449875 0.0261701113485582 4.35653704982482e-05 4.5301124262645e-06 -3.72708797143258e-06 -2.08156365189972e-05 3.83513004684165e-05 -9.80650227453605e-06 4.5301124262645e-06 4.57443309233236e-05 -2.61831849381537e-06 1.32126030564772e-05 -3.50834800920133e-05 1.653706075554e-05 -3.72708797143258e-06 -2.61831849381537e-06 1.57394413667703e-05 4.31560361916654e-06 -1.52547208873312e-06 9.27987723406368e-06 -2.08156365189972e-05 1.32126030564772e-05 4.31560361916654e-06 4.9714150078111e-05 -7.24108503789055e-05 1.34144426812021e-05 3.83513004684165e-05 -3.50834800920133e-05 -1.52547208873312e-06 -7.24108503789055e-05 0.000174038141909803 -6.87391673619207e-06 -9.80650227453605e-06 1.653706075554e-05 9.27987723406368e-06 1.34144426812021e-05 -6.87391673619207e-06 0.000140038789023519 1298 1318 0 0 179 1298 1318 0 0 174 0 0 0 0 0 0 0 0 2420 0 0 0 0 0 2220 +248 249 0.999541520481874 0.0113639648855249 0.0280643748347184 0.00604343334607204 -0.0115419130075446 0.999914249717742 0.00618687768834517 -0.0691477189197509 -0.0279916608458535 -0.00650795770459736 0.999586971408494 0.00747303560521852 4.06158147597508e-05 1.11682640011151e-05 -3.27137070994016e-06 4.78586455280438e-06 -1.26058291406251e-05 1.01094477674373e-05 1.11682640011151e-05 3.98381280197811e-05 -2.77867137426169e-06 -2.99427302211248e-06 -4.70830524410943e-07 1.70318643853421e-05 -3.27137070994016e-06 -2.77867137426169e-06 1.20838217641984e-05 3.64124897222278e-07 3.51772878160061e-06 -4.33141042943442e-06 4.78586455280438e-06 -2.99427302211248e-06 3.64124897222278e-07 2.02516361845745e-05 -9.36236580673887e-06 1.86732069148263e-05 -1.26058291406251e-05 -4.70830524410943e-07 3.51772878160061e-06 -9.36236580673887e-06 7.58157374468409e-05 -1.0141314503776e-05 1.01094477674373e-05 1.70318643853421e-05 -4.33141042943442e-06 1.86732069148263e-05 -1.0141314503776e-05 0.000161916245929514 537 535 0 19 0 653 653 0 0 0 0 0 0 0 0 0 0 0 3098 0 0 86 0 0 3159 +250 251 0.999444543890062 0.0321881193773259 -0.00863299828205273 0.0241181646955805 -0.0320436536242173 0.999352229555492 0.0163806454353249 -0.0737909896134435 0.00915466825166802 -0.0160949138990445 0.999828558201747 0.00159219847743177 3.13297901469568e-05 1.26819320215406e-05 -1.23202027552632e-08 1.73992812623509e-06 -7.13903507327448e-06 2.60285273331371e-05 1.26819320215406e-05 2.63868843275341e-05 1.20799292759706e-06 -1.79827082847477e-06 -4.91868249811346e-06 1.18036566780597e-05 -1.23202027552632e-08 1.20799292759706e-06 1.08892794859417e-05 1.04973288214428e-06 -2.45884584180815e-06 1.65922939952108e-06 1.73992812623509e-06 -1.79827082847477e-06 1.04973288214428e-06 2.05519668890115e-05 -1.10664425441751e-05 2.00482928377971e-05 -7.13903507327448e-06 -4.91868249811346e-06 -2.45884584180815e-06 -1.10664425441751e-05 5.40756647313799e-05 -1.24132317111153e-05 2.60285273331371e-05 1.18036566780597e-05 1.65922939952108e-06 2.00482928377971e-05 -1.24132317111153e-05 0.000172504058116144 571 571 0 0 0 686 686 0 0 0 0 0 0 0 0 0 0 0 2977 0 21 115 0 0 3212 +242 243 0.998782556991765 -0.0458451738199584 0.0182105432760655 0.00499342305124187 0.045472777490631 0.99875801974475 0.0203628215833037 -0.0541335356082558 -0.0191214632358306 -0.0195099470261631 0.999626796164827 -0.033076769645822 2.96051278575757e-05 2.19891259345299e-05 -3.61893518982013e-06 6.33203067883345e-06 -8.93929605217302e-06 5.45585155068819e-05 2.19891259345299e-05 5.24093672554183e-05 -2.98531238804075e-06 -1.54867096200432e-06 -1.36074616047366e-05 2.54739297516638e-05 -3.61893518982013e-06 -2.98531238804075e-06 1.21565441506324e-05 1.30374462756374e-06 1.05295530276636e-06 -4.96921515172431e-06 6.33203067883345e-06 -1.54867096200432e-06 1.30374462756374e-06 2.73097544976372e-05 -1.69552522043725e-05 4.90424535680555e-05 -8.93929605217302e-06 -1.36074616047366e-05 1.05295530276636e-06 -1.69552522043725e-05 6.22658834001917e-05 -3.9819844839388e-05 5.45585155068819e-05 2.54739297516638e-05 -4.96921515172431e-06 4.90424535680555e-05 -3.9819844839388e-05 0.000362043632359633 568 604 0 0 0 568 667 0 0 5 0 0 0 0 0 0 0 0 2531 0 0 0 0 0 3141 +249 250 0.999448600141721 0.0183394107215045 0.0276796258851655 0.0133505162662029 -0.0180395003056605 0.999776254177926 -0.011046176292132 -0.0587379146817161 -0.0278760130484407 0.010540758812474 0.999555811498378 -0.0118000226732122 3.77454865332664e-05 2.05801276181336e-05 1.40237020267268e-07 -4.23682144232421e-06 -9.96697463510035e-06 7.59661177029474e-06 2.05801276181336e-05 3.5985540087839e-05 2.18644738611996e-06 -8.86973515610106e-06 -1.8579091282382e-06 8.30833228773493e-06 1.40237020267268e-07 2.18644738611996e-06 1.44876213131243e-05 8.02312787833002e-07 4.34417926549782e-06 4.85048914895162e-06 -4.23682144232421e-06 -8.86973515610106e-06 8.02312787833002e-07 2.26331507867618e-05 -1.0015198421877e-05 1.17472381385262e-05 -9.96697463510035e-06 -1.8579091282382e-06 4.34417926549782e-06 -1.0015198421877e-05 9.52797531909334e-05 2.50077168918368e-05 7.59661177029474e-06 8.30833228773493e-06 4.85048914895162e-06 1.17472381385262e-05 2.50077168918368e-05 0.000176664125272432 577 577 0 10 0 693 693 0 0 0 0 0 0 0 0 0 0 0 3174 0 0 78 0 0 2438 +244 245 0.998820847990835 -0.047479232366385 0.0101309482659939 0.00186917754101919 0.0475800667644434 0.998817812920118 -0.00995559341090969 -0.0719278578905105 -0.00964628765694505 0.0104258854478199 0.99989911993514 0.0168296441039541 2.75669729627508e-05 1.58002630958634e-05 -2.92747520486779e-07 -8.68977297824844e-07 -1.29981364334654e-06 2.58152750031579e-05 1.58002630958634e-05 4.36510350177833e-05 1.65650991189636e-06 -2.36700820202209e-06 -4.44156290245961e-06 2.73222126406697e-05 -2.92747520486779e-07 1.65650991189636e-06 1.21329837412461e-05 2.82584652434415e-06 7.49052021744776e-07 5.61521153424389e-06 -8.68977297824844e-07 -2.36700820202209e-06 2.82584652434415e-06 2.19171108089091e-05 -1.11638949272827e-05 1.8179159349103e-05 -1.29981364334654e-06 -4.44156290245961e-06 7.49052021744776e-07 -1.11638949272827e-05 5.82575597181422e-05 -1.30238314709736e-05 2.58152750031579e-05 2.73222126406697e-05 5.61521153424389e-06 1.8179159349103e-05 -1.30238314709736e-05 0.000162238401088802 464 464 0 0 0 476 580 0 0 0 0 0 0 0 0 0 0 0 2851 0 0 0 0 0 3072 +247 248 0.999736005645156 0.0183419338629298 -0.0138380807497244 -0.00285685129548878 -0.0182917047409287 0.999825669084369 0.00374766296037343 -0.0700773389193321 0.0139044077305964 -0.00349355151125295 0.999897225990501 -0.00015769150947369 2.56528174627264e-05 1.03401006899103e-05 -5.52339165080167e-06 2.83558394469883e-06 -2.65881848740893e-06 2.32795671292081e-05 1.03401006899103e-05 5.03370967508991e-05 -4.29280653409344e-06 -7.48230973148438e-07 -4.51021630422886e-06 1.8119542946167e-05 -5.52339165080167e-06 -4.29280653409344e-06 1.15157425053025e-05 2.41135938954405e-06 1.69351919070022e-06 -6.88534661035428e-06 2.83558394469883e-06 -7.48230973148438e-07 2.41135938954405e-06 2.81061628962743e-05 -7.95448027342532e-06 4.60380544622682e-05 -2.65881848740893e-06 -4.51021630422886e-06 1.69351919070022e-06 -7.95448027342532e-06 5.80015807957826e-05 -3.06890165396436e-05 2.32795671292081e-05 1.8119542946167e-05 -6.88534661035428e-06 4.60380544622682e-05 -3.06890165396436e-05 0.000290466727260418 419 413 0 22 0 542 542 0 0 0 0 0 0 0 0 0 0 0 3064 0 17 121 0 0 3071 +252 253 0.999511294515497 0.00152437057264149 -0.0312225628402425 0.0254338970130796 -0.00180590023385403 0.99995795256456 -0.00899065221434125 -0.0711583300251978 0.0312075449258828 0.00904264326682956 0.999472020490042 0.00674866553813997 3.01099461816808e-05 1.4666524970071e-05 1.83615673834009e-06 -8.84245695137037e-08 -4.9797445324811e-06 -9.11145839723314e-06 1.4666524970071e-05 2.75248222728034e-05 1.8683405412575e-06 -5.7055501235632e-06 2.57996016197493e-06 -1.24071191389949e-05 1.83615673834009e-06 1.8683405412575e-06 1.11297028175864e-05 -6.9825815358168e-07 -1.06522872970697e-06 -2.87317319260853e-06 -8.84245695137037e-08 -5.7055501235632e-06 -6.9825815358168e-07 2.39987726387683e-05 -8.35015980019075e-06 2.16912426655101e-05 -4.9797445324811e-06 2.57996016197493e-06 -1.06522872970697e-06 -8.35015980019075e-06 5.12012410175042e-05 1.16187923663936e-05 -9.11145839723314e-06 -1.24071191389949e-05 -2.87317319260853e-06 2.16912426655101e-05 1.16187923663936e-05 0.000210855290280587 667 667 0 0 0 756 762 0 0 0 0 0 0 0 0 0 0 0 3003 0 0 54 0 0 2834 +251 252 0.999524953158834 0.0226810230447051 -0.0208671801275454 0.0219064600252447 -0.022853393106596 0.99970634223601 -0.0080592627834764 -0.0629333413439217 0.0206782599931731 0.00853232012662993 0.999749773231738 0.00405734025134234 2.35058862641999e-05 8.27890633871885e-06 3.64182975169137e-07 -2.38002206229534e-06 4.94973528151286e-08 2.99706278586444e-06 8.27890633871885e-06 3.70374339714348e-05 2.16639429628653e-06 -4.73243771837351e-06 2.74847768097712e-06 9.33869949001946e-06 3.64182975169137e-07 2.16639429628653e-06 1.32410380680689e-05 -2.55014534239338e-06 3.67456740316231e-06 3.78927789266743e-06 -2.38002206229534e-06 -4.73243771837351e-06 -2.55014534239338e-06 2.48479454047725e-05 -1.25080948424989e-05 1.33026259903545e-05 4.94973528151286e-08 2.74847768097712e-06 3.67456740316231e-06 -1.25080948424989e-05 6.85779446821304e-05 1.4849172894028e-05 2.99706278586444e-06 9.33869949001946e-06 3.78927789266743e-06 1.33026259903545e-05 1.4849172894028e-05 0.000140820284485243 634 634 0 0 0 738 738 0 0 0 0 0 0 0 0 0 0 0 2919 0 7 82 0 0 2923 +253 254 0.999574609903096 0.0226169357039193 -0.0184139473345002 0.0201435006824803 -0.0221960947859404 0.999494831648981 0.0227467554439723 -0.0867001255697288 0.0189191070964386 -0.0223283614790499 0.999571664094343 0.00231593212232346 2.26549677350461e-05 9.88559676272127e-06 -3.94474368121574e-06 -1.68911944360042e-06 -2.49838635165289e-06 -2.72798514660192e-06 9.88559676272127e-06 2.87083722849597e-05 -3.89391071838868e-06 -5.19104027888275e-07 -1.25248482282247e-06 3.82020461583495e-07 -3.94474368121574e-06 -3.89391071838868e-06 1.16598978627237e-05 1.22501777959036e-06 1.33484627591141e-06 8.57821565894186e-07 -1.68911944360042e-06 -5.19104027888275e-07 1.22501777959036e-06 2.72888814092625e-05 -1.26190403997689e-05 2.77258106947567e-05 -2.49838635165289e-06 -1.25248482282247e-06 1.33484627591141e-06 -1.26190403997689e-05 6.09404818752135e-05 5.03647130983578e-06 -2.72798514660192e-06 3.82020461583495e-07 8.57821565894186e-07 2.77258106947567e-05 5.03647130983578e-06 0.000161131974021154 667 667 0 0 0 762 762 0 0 0 0 0 0 0 0 0 0 0 2806 0 45 127 0 0 3103 +254 255 0.999400761818916 0.0193607967012867 0.0286928009588074 0.0200275191114749 -0.019727022664129 0.999726808876914 0.0125360356409237 -0.0803906051577981 -0.028442254702805 -0.0130945471045399 0.999509665277704 -0.0150625494878208 2.11409978821706e-05 5.39956867003111e-06 -2.21360109882731e-06 2.14633589483249e-06 -1.90823948306236e-06 -7.73068555997091e-07 5.39956867003111e-06 2.71253634029612e-05 -4.67590989263145e-06 -8.24626918820829e-07 -9.87283766975029e-08 8.23072491681556e-06 -2.21360109882731e-06 -4.67590989263145e-06 1.11321217884169e-05 1.41325051269694e-06 2.21737437026764e-06 -2.00212820865262e-06 2.14633589483249e-06 -8.24626918820829e-07 1.41325051269694e-06 2.4035452258621e-05 -1.07612866045105e-05 1.34210982097164e-05 -1.90823948306236e-06 -9.87283766975029e-08 2.21737437026764e-06 -1.07612866045105e-05 5.39178381172253e-05 4.37678111033227e-07 -7.73068555997091e-07 8.23072491681556e-06 -2.00212820865262e-06 1.34210982097164e-05 4.37678111033227e-07 0.000105527665250357 750 750 0 0 0 842 842 0 0 0 0 0 0 0 0 0 0 0 2821 0 39 111 0 0 3269 +256 257 0.999983395143308 -0.00573707524494125 -0.000543512001231212 0.0306784965773896 0.00574170933670626 0.99994348766722 0.00894730382902629 -0.100392162885209 0.000492149930793654 -0.00895027594826052 0.999959824367407 0.0231779707141391 4.06142678593476e-05 2.19067502230828e-05 -2.27679147251979e-06 -1.08915276498271e-06 -4.12245793832603e-06 -2.19992260444738e-05 2.19067502230828e-05 4.51134291551372e-05 -1.38542912026284e-06 -7.6997226661814e-07 7.90089479608238e-06 -1.38104158004526e-06 -2.27679147251979e-06 -1.38542912026284e-06 1.16489271631446e-05 1.15446151609104e-06 3.60567352677894e-06 7.62864498027866e-06 -1.08915276498271e-06 -7.6997226661814e-07 1.15446151609104e-06 2.61011996027182e-05 -1.19510599215165e-05 3.22248732729611e-05 -4.12245793832603e-06 7.90089479608238e-06 3.60567352677894e-06 -1.19510599215165e-05 6.31187814876175e-05 2.73041479489093e-05 -2.19992260444738e-05 -1.38104158004526e-06 7.62864498027866e-06 3.22248732729611e-05 2.73041479489093e-05 0.000308348108060986 752 752 0 0 0 834 837 0 0 0 0 0 0 0 0 0 0 0 2718 0 2 63 0 0 2879 +259 260 0.999845955920723 0.00247229973206448 -0.0173767707877447 0.0210396301203168 -0.00248228021592889 0.99999676633635 -0.000552812602362035 -0.08651102473956 0.0173753478786639 0.000595861459196841 0.999848859695913 -0.0282749739003579 3.02173689781659e-05 1.78109441991685e-05 -1.41903569477299e-06 5.67423338335859e-06 -2.16565576492455e-07 5.06048278033451e-05 1.78109441991685e-05 2.71915112866024e-05 3.77856180504108e-07 -4.6122573692526e-07 -1.77069880808271e-06 1.30784645785453e-05 -1.41903569477299e-06 3.77856180504108e-07 8.942209661415e-06 -1.2288700307247e-06 -6.21839582256038e-07 -2.06439740365481e-07 5.67423338335859e-06 -4.6122573692526e-07 -1.2288700307247e-06 2.58511120679723e-05 -6.89559640082716e-06 3.7440783661917e-05 -2.16565576492455e-07 -1.77069880808271e-06 -6.21839582256038e-07 -6.89559640082716e-06 4.6176716597927e-05 1.12406907222151e-05 5.06048278033451e-05 1.30784645785453e-05 -2.06439740365481e-07 3.7440783661917e-05 1.12406907222151e-05 0.000353651958428513 713 713 0 0 0 807 807 0 0 0 0 0 0 0 0 0 0 0 2799 0 9 88 0 0 3284 +266 267 0.999258909314304 -0.00560531263273982 0.0380816573467637 0.0326640063929449 0.00498307572841938 0.999852849872092 0.0164148578714926 -0.0901367025201451 -0.0381680640362059 -0.0162129291907944 0.999139799935316 0.0107071584370013 2.32164294218835e-05 1.05741404646548e-05 5.37120089655739e-07 9.67487912990538e-07 -3.87073080597963e-06 1.06363356867183e-05 1.05741404646548e-05 2.40927971306762e-05 -1.39837688910828e-06 2.31010709603927e-06 -6.740011587995e-08 1.61219218927195e-06 5.37120089655739e-07 -1.39837688910828e-06 1.02002804497997e-05 -1.38470329706521e-06 1.83044443854473e-06 -1.15376590324689e-06 9.67487912990538e-07 2.31010709603927e-06 -1.38470329706521e-06 2.75926854656467e-05 -1.412323202347e-05 1.47856247371655e-05 -3.87073080597963e-06 -6.740011587995e-08 1.83044443854473e-06 -1.412323202347e-05 5.0112105194993e-05 -1.0724577222934e-05 1.06363356867183e-05 1.61219218927195e-06 -1.15376590324689e-06 1.47856247371655e-05 -1.0724577222934e-05 0.000122517853413181 867 867 0 0 0 920 929 0 0 0 0 0 0 0 0 0 0 0 2666 0 0 40 0 0 3404 +255 256 0.999468999340793 0.00250391099262443 0.0324876866898089 0.0242742470051747 -0.00273881755404429 0.999970414259636 0.00718814884492816 -0.0934000301031314 -0.032468727032636 -0.00727330977974936 0.999446287065857 -0.0196138347910467 2.01150835050276e-05 7.76122070706833e-06 -2.43096728215987e-06 -8.77572317748342e-07 -3.91847619011776e-06 1.36710937880034e-05 7.76122070706833e-06 4.18293492284228e-05 -2.35449964310832e-06 1.42953566396849e-06 7.32214177468694e-06 2.83410110313576e-05 -2.43096728215987e-06 -2.35449964310832e-06 1.11359545469122e-05 3.68330006734084e-06 2.16421561970178e-06 1.80259733676658e-06 -8.77572317748342e-07 1.42953566396849e-06 3.68330006734084e-06 2.46815061232798e-05 -8.42897184334032e-06 2.81496021563655e-05 -3.91847619011776e-06 7.32214177468694e-06 2.16421561970178e-06 -8.42897184334032e-06 5.25460540459026e-05 1.20023879178389e-05 1.36710937880034e-05 2.83410110313576e-05 1.80259733676658e-06 2.81496021563655e-05 1.20023879178389e-05 0.000228090475955529 761 761 0 0 0 853 853 0 0 0 0 0 0 0 0 0 0 0 2673 0 0 66 0 0 3393 +257 258 0.999880475721448 -0.0153962577861088 0.00141050247599283 0.0167507751416275 0.0154159089331152 0.999765919328566 -0.0151807872283765 -0.0985124201497841 -0.00117644499106204 0.015200716933455 0.999883770336279 -0.00835127854021096 2.67961671505974e-05 2.81883906074032e-06 -2.20923040658324e-06 -3.51133275580279e-06 -2.48493024561866e-07 -2.22178439146884e-06 2.81883906074032e-06 7.09764733933045e-05 -2.0972578542518e-06 6.45614821199931e-06 -5.85079904574083e-06 2.80379837478771e-06 -2.20923040658324e-06 -2.0972578542518e-06 1.01930305601095e-05 2.87818275621985e-06 -1.60385524374465e-06 3.07307897949035e-07 -3.51133275580279e-06 6.45614821199931e-06 2.87818275621985e-06 2.80831635342722e-05 -1.53547046246734e-05 2.77253300930592e-05 -2.48493024561866e-07 -5.85079904574083e-06 -1.60385524374465e-06 -1.53547046246734e-05 4.8376591139059e-05 -6.71057310370585e-06 -2.22178439146884e-06 2.80379837478771e-06 3.07307897949035e-07 2.77253300930592e-05 -6.71057310370585e-06 0.000210503285359876 764 764 0 0 0 841 846 0 0 0 0 0 0 0 0 0 0 0 2871 0 0 48 0 0 3084 +268 269 0.999681871674852 -0.0241075786012098 -0.00741485661698891 0.0298670564123675 0.0241043850646034 0.999709311978744 -0.0005197726852825 -0.103433094892676 0.00742523166785623 0.00034087677177395 0.999972374487268 0.0404453278470938 3.72357037062208e-05 2.30600009529016e-05 2.83459073654326e-07 6.26447512130064e-07 -3.59755246489846e-06 -9.91530170956518e-06 2.30600009529016e-05 3.70619900191309e-05 -3.60228010163831e-07 -8.99378900596818e-07 -5.06635122555311e-07 -1.63508543238842e-05 2.83459073654326e-07 -3.60228010163831e-07 8.98267585944959e-06 3.89211680298521e-06 1.49018879967901e-07 3.87450769443319e-06 6.26447512130064e-07 -8.99378900596818e-07 3.89211680298521e-06 1.91225561917092e-05 1.09797092901578e-06 1.46173591853334e-05 -3.59755246489846e-06 -5.06635122555311e-07 1.49018879967901e-07 1.09797092901578e-06 3.86666022275175e-05 1.53483816523875e-05 -9.91530170956518e-06 -1.63508543238842e-05 3.87450769443319e-06 1.46173591853334e-05 1.53483816523875e-05 0.000201715749497624 712 712 0 0 0 771 792 0 0 0 0 0 0 0 0 0 0 0 2633 0 0 31 0 0 3131 +258 259 0.999530162209776 -0.0248588411666318 0.0179302216592883 0.0168672500279323 0.0251618257991245 0.999540951602222 -0.0168750879280217 -0.0890694477244131 -0.0175024956892881 0.0173183164879304 0.999696823321286 0.000338442006360023 7.98772761286354e-05 3.06654705938161e-05 -8.06133832831001e-06 2.8025319648356e-05 -2.13804684644651e-05 0.000237314897884149 3.06654705938161e-05 4.49382967455495e-05 -4.46172220363941e-06 4.95249846460434e-06 -5.91494722276513e-06 5.48645474156462e-05 -8.06133832831001e-06 -4.46172220363941e-06 1.23978905254124e-05 -4.71409562431794e-06 3.90182055079179e-06 -3.47837742727905e-05 2.8025319648356e-05 4.95249846460434e-06 -4.71409562431794e-06 4.27847301459702e-05 -2.52320334482378e-05 0.000162785956737755 -2.13804684644651e-05 -5.91494722276513e-06 3.90182055079179e-06 -2.52320334482378e-05 7.90174675806671e-05 -6.44044083366088e-05 0.000237314897884149 5.48645474156462e-05 -3.47837742727905e-05 0.000162785956737755 -6.44044083366088e-05 0.00157758413810137 757 757 0 0 0 805 845 0 0 0 0 0 0 0 0 0 0 0 2671 0 0 16 0 0 3001 +261 262 0.999891113196224 0.00412222553980905 0.014169298070649 0.0277861955155554 -0.00416508055184661 0.999986836998723 0.00299631995721744 -0.0793544698350326 -0.0141567600535073 -0.00305500996534158 0.99989512102965 -0.0198769836557138 9.67225519037138e-05 4.75137378025671e-05 -1.1957594788144e-06 6.58423223757081e-06 -1.76915437183503e-05 -7.40237167243707e-06 4.75137378025671e-05 4.48853020741394e-05 1.72997033699975e-06 2.7763927842855e-06 -2.21196504683564e-06 -5.17634780316022e-06 -1.1957594788144e-06 1.72997033699975e-06 1.05559668349602e-05 2.10056526035731e-06 1.52886065351055e-06 2.16471520561208e-06 6.58423223757081e-06 2.7763927842855e-06 2.10056526035731e-06 1.98152438733041e-05 -1.27522368849417e-05 6.15123398802924e-06 -1.76915437183503e-05 -2.21196504683564e-06 1.52886065351055e-06 -1.27522368849417e-05 6.43267582554787e-05 2.11761214492673e-05 -7.40237167243707e-06 -5.17634780316022e-06 2.16471520561208e-06 6.15123398802924e-06 2.11761214492673e-05 0.00017495706666026 829 829 0 0 0 932 932 0 0 0 0 0 0 0 0 0 0 0 2664 0 0 63 0 0 2817 +263 264 0.998645067505329 0.0196468914471151 -0.0481874340854868 0.0313233332284779 -0.0200165925212191 0.999773711007979 -0.00720158324078089 -0.0968028634536499 0.0480350410754205 0.00815637381436717 0.998812348940021 -0.00703198324470327 2.87596549451493e-05 2.13882114164797e-05 -1.38857724973925e-06 3.16373965181229e-06 -3.00695793919711e-06 5.52061745311551e-06 2.13882114164797e-05 3.08791159321054e-05 -5.38326868462951e-07 -7.06733722224142e-07 -6.04665806447843e-07 -5.63630575803521e-06 -1.38857724973925e-06 -5.38326868462951e-07 9.62437324482199e-06 2.88487687466845e-06 -7.11620272034409e-07 3.29301184087938e-06 3.16373965181229e-06 -7.06733722224142e-07 2.88487687466845e-06 2.27048461373217e-05 -9.69948952590294e-06 2.28253168091965e-05 -3.00695793919711e-06 -6.04665806447843e-07 -7.11620272034409e-07 -9.69948952590294e-06 4.54391200980723e-05 2.3786512528545e-05 5.52061745311551e-06 -5.63630575803521e-06 3.29301184087938e-06 2.28253168091965e-05 2.3786512528545e-05 0.000236454099594116 661 661 0 0 0 757 757 0 0 0 0 0 0 0 0 0 0 0 2554 0 98 90 0 0 3210 +260 261 0.999674799195415 -0.00274488784545535 0.025352740371045 0.0279124187654447 0.00277661878476082 0.999995405296135 -0.00121645992259878 -0.0814519951228038 -0.0253492848366548 0.00128645922401261 0.999677827492905 -0.00298708396751769 2.08498787536239e-05 1.12012789055151e-05 -1.72866973400012e-06 1.11391045025351e-06 -3.26110547119193e-06 1.17120339667842e-05 1.12012789055151e-05 2.79220108063904e-05 -2.10601224669345e-06 -5.74407914517762e-06 6.41828169326191e-07 1.06428697341981e-05 -1.72866973400012e-06 -2.10601224669345e-06 1.11870543136868e-05 2.176146097105e-06 1.77599488030175e-06 1.56280362447743e-06 1.11391045025351e-06 -5.74407914517762e-06 2.176146097105e-06 2.2300629524575e-05 -8.46418675479201e-06 1.38225404632357e-05 -3.26110547119193e-06 6.41828169326191e-07 1.77599488030175e-06 -8.46418675479201e-06 5.13499017806603e-05 8.95938963471789e-07 1.17120339667842e-05 1.06428697341981e-05 1.56280362447743e-06 1.38225404632357e-05 8.95938963471789e-07 0.000149639145664498 709 709 0 0 0 796 807 0 0 0 0 0 0 0 0 0 0 0 2932 0 0 46 0 0 3450 +265 266 0.999641835764688 0.0241212314364153 0.0115916514351863 0.0211401165613506 -0.0242421817240757 0.999651918469805 0.0104095400904822 -0.100515439742878 -0.011336525669748 -0.0106868186860896 0.999878630180738 -0.0382841930821662 2.53961201325771e-05 1.50510336387993e-05 -1.94121941899703e-06 -2.00345187817646e-06 8.80877687808548e-07 -8.25653842199231e-06 1.50510336387993e-05 3.97866593511937e-05 -1.77232809120363e-06 -3.51075745176366e-06 -2.15048423092454e-06 -9.04397446753455e-06 -1.94121941899703e-06 -1.77232809120363e-06 9.02816570072342e-06 1.79529633306533e-06 -1.37838007542796e-06 2.87063991824093e-07 -2.00345187817646e-06 -3.51075745176366e-06 1.79529633306533e-06 2.21722306404228e-05 -2.96202559293605e-06 9.97192946419036e-06 8.80877687808548e-07 -2.15048423092454e-06 -1.37838007542796e-06 -2.96202559293605e-06 3.66496948484077e-05 1.53600814644795e-06 -8.25653842199231e-06 -9.04397446753455e-06 2.87063991824093e-07 9.97192946419036e-06 1.53600814644795e-06 8.48298454505878e-05 928 928 0 0 0 900 900 0 0 0 0 0 0 0 0 0 0 0 2632 0 117 165 0 0 3457 +262 263 0.999352309982177 0.0304311593296612 -0.0192069017579472 0.0398765786111496 -0.0303091781906667 0.999518712125421 0.00661043330998185 -0.0968830533681036 0.019398820858317 -0.00602400639044124 0.999793677263622 0.0447611753830062 2.42780253273903e-05 1.29703739075113e-05 4.17077095289504e-07 2.32620343635359e-06 -3.8485267761753e-06 -1.29529229084732e-06 1.29703739075113e-05 2.73274268319848e-05 -7.64635286860134e-07 2.44845898546624e-06 1.87415274695812e-06 4.28517868224281e-06 4.17077095289504e-07 -7.64635286860134e-07 1.04624692228624e-05 2.70074301393748e-06 3.43670711720304e-06 4.05958121678432e-07 2.32620343635359e-06 2.44845898546624e-06 2.70074301393748e-06 2.3910497722888e-05 -1.38029504433072e-05 1.3644497102733e-05 -3.8485267761753e-06 1.87415274695812e-06 3.43670711720304e-06 -1.38029504433072e-05 5.46624795830776e-05 8.64099479316166e-06 -1.29529229084732e-06 4.28517868224281e-06 4.05958121678432e-07 1.3644497102733e-05 8.64099479316166e-06 0.000169417038316186 604 604 0 0 0 709 709 0 0 0 0 0 0 0 0 0 0 0 2621 0 55 135 0 0 3326 +264 265 0.999691658152845 0.00583989797214721 -0.02413470967901 0.0321021175126539 -0.00583522156612974 0.999982940052342 0.000264184684414787 -0.0975543590912838 0.0241358407537289 -0.000123271846809966 0.999708680564074 0.00752362522526053 2.96867588754319e-05 1.65946814856997e-05 -3.30862661535617e-07 1.41473979150255e-06 2.8467965590387e-06 2.75279814951177e-06 1.65946814856997e-05 3.0973061637688e-05 1.48132518729124e-07 2.41463941419801e-06 1.12024350114996e-06 3.97928564371615e-06 -3.30862661535617e-07 1.48132518729124e-07 1.00031791987453e-05 1.93695067539416e-06 -8.63880532150848e-07 -1.78473508743138e-06 1.41473979150255e-06 2.41463941419801e-06 1.93695067539416e-06 2.30842663071577e-05 -7.79885411238729e-06 2.09278392395795e-05 2.8467965590387e-06 1.12024350114996e-06 -8.63880532150848e-07 -7.79885411238729e-06 4.47312982526095e-05 -5.41112839946604e-07 2.75279814951177e-06 3.97928564371615e-06 -1.78473508743138e-06 2.09278392395795e-05 -5.41112839946604e-07 0.000170163665060042 884 883 0 0 25 831 831 0 0 0 0 0 0 0 0 0 0 0 2603 0 142 123 0 0 3042 +271 272 0.99967086506031 0.0154163430339124 -0.0205060458653842 0.019440681151869 -0.0155250764704007 0.999866195641674 -0.00515391245887789 -0.103263283358183 0.0204238475846425 0.0054705740563772 0.999776444646168 -0.0108301076083509 2.31975333681994e-05 1.25815589054089e-05 1.77420662865117e-06 2.47321693136961e-06 -2.9205439359737e-06 -2.46361889764594e-06 1.25815589054089e-05 2.87452854934864e-05 -1.0596914314559e-07 4.96448439836015e-06 2.80318155875389e-06 1.10580873186122e-05 1.77420662865117e-06 -1.0596914314559e-07 1.0035997052761e-05 -5.88588322900547e-07 1.97253617206583e-06 -3.25673721258479e-06 2.47321693136961e-06 4.96448439836015e-06 -5.88588322900547e-07 2.07450814597407e-05 -2.29862927869796e-06 1.18317188958388e-05 -2.9205439359737e-06 2.80318155875389e-06 1.97253617206583e-06 -2.29862927869796e-06 4.33958547646778e-05 -9.69372031917841e-07 -2.46361889764594e-06 1.10580873186122e-05 -3.25673721258479e-06 1.18317188958388e-05 -9.69372031917841e-07 0.000110765382637522 1265 1265 0 0 0 1358 1358 0 0 0 0 0 0 0 0 0 0 0 2984 0 88 121 0 0 3380 +267 268 0.99975753898143 -0.0216131557721828 0.00421126434231717 0.0347698716077835 0.0215556910129331 0.999679925111136 0.0132438481850808 -0.0979297647715647 -0.00449615777619811 -0.0131498603552233 0.999903428205889 0.0235310304486491 3.71768152505313e-05 2.39621551159867e-05 1.60553210236867e-07 -2.65495240440306e-07 3.37066657510022e-06 -5.21918403410211e-06 2.39621551159867e-05 5.58968916562195e-05 7.96291912613016e-07 2.5676293952179e-06 2.696671577429e-06 3.13233231582555e-06 1.60553210236867e-07 7.96291912613016e-07 9.64272942232248e-06 2.54775925512987e-06 -4.24939802401774e-07 9.6716154935309e-08 -2.65495240440306e-07 2.5676293952179e-06 2.54775925512987e-06 1.98352646425355e-05 -3.18931427733491e-06 1.06837599738596e-05 3.37066657510022e-06 2.696671577429e-06 -4.24939802401774e-07 -3.18931427733491e-06 3.77844501523355e-05 -8.10771989367839e-06 -5.21918403410211e-06 3.13233231582555e-06 9.6716154935309e-08 1.06837599738596e-05 -8.10771989367839e-06 0.000130836613900641 793 793 0 0 0 819 858 0 0 0 0 0 0 0 0 0 0 0 2674 0 0 11 0 0 3304 +274 275 0.999252754983235 0.0375060506649987 -0.00933958360584868 0.0415948630858121 -0.0374574007633884 0.999284007522925 0.00533061318919311 -0.1113711974531 0.00953282678259727 -0.00497679338896373 0.999942176698781 0.016761219449143 4.83899043873185e-05 1.41667709413585e-06 -2.89396444185879e-06 3.06363522526566e-06 -6.53797360035708e-06 -3.4992127662316e-06 1.41667709413585e-06 4.39118903451299e-05 -2.07655981116139e-06 5.98180512168801e-06 -9.69399064129934e-07 6.42361853878655e-07 -2.89396444185879e-06 -2.07655981116139e-06 1.12519752288181e-05 -7.77353839130507e-07 8.52071888684667e-07 -1.66208934129241e-06 3.06363522526566e-06 5.98180512168801e-06 -7.77353839130507e-07 2.57006647460389e-05 -2.9350952203926e-06 1.66631838037793e-05 -6.53797360035708e-06 -9.69399064129934e-07 8.52071888684667e-07 -2.9350952203926e-06 4.01041846498342e-05 2.89836318414209e-06 -3.4992127662316e-06 6.42361853878655e-07 -1.66208934129241e-06 1.66631838037793e-05 2.89836318414209e-06 0.000134731578728879 1952 1952 0 0 0 1995 1995 0 0 0 0 0 0 0 0 0 0 0 2960 0 118 170 0 0 3107 +269 270 0.999191440438493 -0.0381277824303123 0.0127568633055486 0.0170835561332383 0.0382682541534581 0.999207453581983 -0.0109546990034058 -0.113366254652602 -0.0123290745190392 0.0114340243639609 0.999858618509811 0.00647979925291518 3.07785045359601e-05 1.81252065628715e-05 3.69714808709739e-07 3.63139247414859e-06 -1.28915317430606e-06 9.9393977865801e-06 1.81252065628715e-05 2.99795028674061e-05 1.06577886865128e-06 4.33030105876537e-06 -6.12794791384394e-07 1.20556274389569e-05 3.69714808709739e-07 1.06577886865128e-06 8.28338869337339e-06 2.15032376064161e-06 -2.46108902931186e-06 2.43282990063622e-07 3.63139247414859e-06 4.33030105876537e-06 2.15032376064161e-06 1.95233150942983e-05 -4.33906633261215e-06 1.88135419907584e-05 -1.28915317430606e-06 -6.12794791384394e-07 -2.46108902931186e-06 -4.33906633261215e-06 3.51312818706409e-05 -1.38818131220087e-06 9.9393977865801e-06 1.20556274389569e-05 2.43282990063622e-07 1.88135419907584e-05 -1.38818131220087e-06 0.000183707310380818 878 878 0 0 0 941 965 0 0 0 0 0 0 0 0 0 0 0 2997 0 0 31 0 0 3235 +276 277 0.99986006972561 0.0141913727853064 -0.00885696938949375 0.029362365469171 -0.0142745414045525 0.999853940320335 -0.00939869637715695 -0.102150075376938 0.00872229533939777 0.00952381039126318 0.999916605822527 -0.0104266857630552 5.23330035451784e-05 2.51696320074933e-05 -1.65116588195333e-06 1.33198798399368e-05 -2.88208856081679e-06 4.27424932637567e-05 2.51696320074933e-05 5.16731283024311e-05 -5.04472515970739e-06 1.67834393751441e-05 -1.05343990056808e-05 5.5532513873585e-05 -1.65116588195333e-06 -5.04472515970739e-06 1.13314405763732e-05 -2.98010307255732e-06 -2.49638868179207e-07 -6.4907167326863e-06 1.33198798399368e-05 1.67834393751441e-05 -2.98010307255732e-06 3.44345200440439e-05 -1.26168614276038e-05 5.05725532630477e-05 -2.88208856081679e-06 -1.05343990056808e-05 -2.49638868179207e-07 -1.26168614276038e-05 4.37144606794696e-05 -1.39495489185864e-05 4.27424932637567e-05 5.5532513873585e-05 -6.4907167326863e-06 5.05725532630477e-05 -1.39495489185864e-05 0.000262570412963222 1929 1941 0 91 0 1978 1992 0 97 0 0 0 0 0 0 0 4 0 2937 0 89 124 0 0 3172 +270 271 0.999778500861653 -0.0184790432484815 -0.0100734391071647 0.016725553333744 0.0184482136087819 0.999824871257677 -0.00314487348139594 -0.10753789527202 0.0101297892115167 0.00295833993820558 0.99994431624733 -0.0180405728859811 1.90853054974841e-05 1.08139069567363e-05 3.54327973711698e-06 -2.35984892721233e-06 -1.07102321536876e-06 5.88683778722347e-06 1.08139069567363e-05 2.02395850804825e-05 3.54699816812365e-06 -3.13350907163011e-06 3.14106510726962e-06 7.68316643360657e-06 3.54327973711698e-06 3.54699816812365e-06 1.19932138095184e-05 -5.46678657821602e-06 4.14263138237052e-07 1.58394183014178e-06 -2.35984892721233e-06 -3.13350907163011e-06 -5.46678657821602e-06 2.23663436447632e-05 -1.99415151146327e-06 1.19898429398059e-05 -1.07102321536876e-06 3.14106510726962e-06 4.14263138237052e-07 -1.99415151146327e-06 3.7403054282271e-05 8.38264022572375e-06 5.88683778722347e-06 7.68316643360657e-06 1.58394183014178e-06 1.19898429398059e-05 8.38264022572375e-06 9.18503007601374e-05 1162 1162 0 0 0 1249 1249 0 0 0 0 0 0 0 0 0 0 0 3245 0 3 65 0 0 3336 +275 276 0.99914669371537 0.017374338830134 -0.0374702120071378 0.0347565484541035 -0.0164094866729754 0.999529707102006 0.0259054698414869 -0.117364929855092 0.0379026804431243 -0.0252684975967002 0.998961906102746 0.00995258161975904 2.03290399183232e-05 2.98656842972341e-06 -1.17095653181375e-06 3.06473392950474e-06 -2.77698642584425e-06 -1.0313413953263e-06 2.98656842972341e-06 2.55565540262582e-05 -1.45759723079043e-06 -2.01146707248889e-07 -1.48784625337256e-06 3.79814651017144e-06 -1.17095653181375e-06 -1.45759723079043e-06 1.2472086773227e-05 1.10392979031144e-07 1.90990525124285e-06 1.56970069775003e-06 3.06473392950474e-06 -2.01146707248889e-07 1.10392979031144e-07 2.36425714433143e-05 -5.17691424522232e-06 7.71851792576411e-06 -2.77698642584425e-06 -1.48784625337256e-06 1.90990525124285e-06 -5.17691424522232e-06 4.45428808956704e-05 2.24699174889268e-06 -1.0313413953263e-06 3.79814651017144e-06 1.56970069775003e-06 7.71851792576411e-06 2.24699174889268e-06 7.17985527215865e-05 2012 2012 0 3 0 2075 2075 0 3 0 0 0 0 0 0 0 0 0 2936 0 89 133 0 0 3240 +272 273 0.998802874812837 0.0196527142741537 0.0447949560471947 0.0246843368717279 -0.0202076750471477 0.999724147698933 0.0119698946040002 -0.109480813344244 -0.0445473583369487 -0.012860767057235 0.998924488405354 0.0206369225942193 2.2272217393726e-05 1.29009931940202e-05 1.8967896105481e-06 1.43701336989241e-07 1.63227082101099e-06 -5.7795557881753e-06 1.29009931940202e-05 3.54257878000259e-05 -8.14876954691751e-07 -1.25736017389004e-06 2.81861432255843e-06 2.09338144732344e-06 1.8967896105481e-06 -8.14876954691751e-07 1.24915469245591e-05 -2.48289552851251e-06 3.38738044231509e-07 -1.14780711875974e-06 1.43701336989241e-07 -1.25736017389004e-06 -2.48289552851251e-06 1.87182242906714e-05 -2.25299862728328e-06 5.03964804759004e-06 1.63227082101099e-06 2.81861432255843e-06 3.38738044231509e-07 -2.25299862728328e-06 4.20720294765936e-05 2.07392732432802e-06 -5.7795557881753e-06 2.09338144732344e-06 -1.14780711875974e-06 5.03964804759004e-06 2.07392732432802e-06 7.60084320096371e-05 1672 1672 0 0 0 1690 1690 0 0 0 0 0 0 0 0 0 0 0 3167 0 182 164 0 0 3606 +273 274 0.999801789795441 0.0157509420824004 0.0121773948506818 0.0387145630297519 -0.015689941208648 0.999863955830551 -0.00508876957141698 -0.109604243615345 -0.0122558911019034 0.00489669831607759 0.999912903946589 0.0226485794374145 2.3928061590849e-05 1.02586620695648e-05 -8.53454701225283e-07 3.33232244269097e-06 -2.57359909021382e-06 1.42544234229978e-05 1.02586620695648e-05 4.3265685431703e-05 -4.01336607954012e-06 3.47493596241756e-06 -3.47163522320965e-06 3.53156951119067e-06 -8.53454701225283e-07 -4.01336607954012e-06 1.17822735959933e-05 3.67376864171747e-06 6.79388955650048e-06 -2.55962665423589e-06 3.33232244269097e-06 3.47493596241756e-06 3.67376864171747e-06 1.9837681393963e-05 -2.94895909876233e-06 1.31622089564535e-05 -2.57359909021382e-06 -3.47163522320965e-06 6.79388955650048e-06 -2.94895909876233e-06 5.86148277202788e-05 -1.6651547260525e-06 1.42544234229978e-05 3.53156951119067e-06 -2.55962665423589e-06 1.31622089564535e-05 -1.6651547260525e-06 0.000136422936940978 1718 1718 0 0 0 1686 1686 0 0 0 0 0 0 0 0 0 0 0 2835 0 108 146 0 0 3454 +282 283 0.997827979421807 0.053492504629267 -0.0384431454420821 0.0232754417557157 -0.053916435249227 0.99849461387411 -0.0100759155617867 -0.114871575213749 0.0378462877044651 0.012126747827847 0.999209988187723 -0.0052281605622641 2.81210701325489e-05 -3.31766626313474e-06 1.58118407721759e-06 -4.16073932199488e-07 8.33808478540136e-07 -1.03935795320894e-05 -3.31766626313474e-06 3.65041700938071e-05 1.38270024733557e-06 -1.88912649291292e-06 -3.18156699781797e-06 1.33950323377259e-05 1.58118407721759e-06 1.38270024733557e-06 1.35451877651232e-05 -4.79154744032724e-06 3.15311852339426e-06 4.89633898967938e-07 -4.16073932199488e-07 -1.88912649291292e-06 -4.79154744032724e-06 2.51050876295711e-05 -8.25846638033205e-06 1.25057147321501e-05 8.33808478540136e-07 -3.18156699781797e-06 3.15311852339426e-06 -8.25846638033205e-06 4.50756557015033e-05 5.81028292733419e-06 -1.03935795320894e-05 1.33950323377259e-05 4.89633898967938e-07 1.25057147321501e-05 5.81028292733419e-06 0.000103141534629694 2835 2766 0 188 0 2880 2812 0 55 0 0 0 0 0 0 0 0 0 3118 0 223 245 0 0 3156 +280 281 0.999270211836664 -0.0204883502154733 -0.032237730090015 0.0200641493073077 0.0207820815736453 0.999745275062028 0.0088028448025184 -0.114608167464813 0.032049162569011 -0.00946638772705769 0.999441463359424 -0.00380184061618175 7.40077343240024e-05 1.69253269950576e-05 -9.57682030115237e-06 3.02360320804871e-05 -1.76173800901108e-06 0.000132520735537267 1.69253269950576e-05 7.39340399898441e-05 -3.29121084079241e-06 3.27049773379621e-05 -2.36512555530172e-06 0.000135222168264187 -9.57682030115237e-06 -3.29121084079241e-06 1.20071909214174e-05 -3.85584309500153e-06 8.46195547015988e-07 -2.31472658708945e-05 3.02360320804871e-05 3.27049773379621e-05 -3.85584309500153e-06 5.3252663583617e-05 -5.22669266486328e-06 0.000149778909900327 -1.76173800901108e-06 -2.36512555530172e-06 8.46195547015988e-07 -5.22669266486328e-06 3.00697798274278e-05 -1.15004952714564e-05 0.000132520735537267 0.000135222168264187 -2.31472658708945e-05 0.000149778909900327 -1.15004952714564e-05 0.000663089752860922 2426 2392 0 64 0 2425 2426 0 0 0 0 0 0 0 0 0 0 0 2477 0 13 56 0 0 3451 +279 280 0.998064778888995 -0.0512008967976165 -0.0352868999542561 0.0389123939580625 0.0503420364568293 0.998423751999193 -0.0248131176846871 -0.103144984087876 0.0365017329265493 0.0229886844115682 0.999069138689803 0.0216584866753201 6.6406576027606e-05 -4.10040694768118e-05 -4.38172969324964e-06 3.50800770586002e-06 2.16787850574509e-06 1.49257950123965e-06 -4.10040694768118e-05 9.92256686718431e-05 3.5766643367639e-06 4.3557559506375e-06 2.5710428947756e-06 1.22354900001419e-06 -4.38172969324964e-06 3.5766643367639e-06 1.12379472098809e-05 -4.10262647371461e-06 -9.22020046650018e-08 2.17615324709175e-07 3.50800770586002e-06 4.3557559506375e-06 -4.10262647371461e-06 3.26798772309894e-05 -4.44566922982637e-06 3.27388843750332e-05 2.16787850574509e-06 2.5710428947756e-06 -9.22020046650018e-08 -4.44566922982637e-06 3.33644782101498e-05 3.91206020794428e-06 1.49257950123965e-06 1.22354900001419e-06 2.17615324709175e-07 3.27388843750332e-05 3.91206020794428e-06 0.000196441211417848 1968 2006 0 0 2 1968 2011 0 0 35 0 0 0 0 0 0 0 0 2681 0 0 0 0 0 3184 +283 284 0.995641008784642 0.0920887038577241 -0.0147868944712917 0.0316119727908435 -0.0915118490302397 0.995158871486363 0.0358385545056656 -0.130070957839096 0.0180156352473998 -0.0343291585069213 0.999248190272487 0.0112454029815142 3.0022596551135e-05 -1.71271714788999e-06 1.41437696695864e-06 3.38120370448572e-06 -1.54455469610457e-06 1.57945036860459e-06 -1.71271714788999e-06 3.72004398856328e-05 2.24946643251404e-07 3.66734732373372e-07 -3.10962379333025e-06 1.70945590109194e-05 1.41437696695864e-06 2.24946643251404e-07 1.22402749121719e-05 -4.31983586143916e-06 1.18338109030172e-06 -2.91053374978277e-07 3.38120370448572e-06 3.66734732373372e-07 -4.31983586143916e-06 2.51915799999301e-05 -5.79386786135597e-06 1.17478817867655e-05 -1.54455469610457e-06 -3.10962379333025e-06 1.18338109030172e-06 -5.79386786135597e-06 3.81120751989558e-05 -3.26105597148087e-06 1.57945036860459e-06 1.70945590109194e-05 -2.91053374978277e-07 1.17478817867655e-05 -3.26105597148087e-06 9.33162846499198e-05 2998 3017 0 278 0 3023 3042 0 171 0 0 0 0 0 0 0 0 0 2841 0 339 336 0 0 3103 +277 278 0.999840316608885 0.0171655004276335 0.00496858918744672 0.029610292671375 -0.0172040030316479 0.999821473208595 0.00781306538318562 -0.10874051588132 -0.00483358698398507 -0.00789729738985408 0.99995713364664 -0.0179838160656487 3.57236534172414e-05 -5.89483289832087e-06 -3.52204038547136e-06 3.98262109445893e-06 -5.36735575232711e-06 9.82593721384435e-06 -5.89483289832087e-06 6.8605827533294e-05 1.63693353720035e-06 5.97084837880659e-06 8.47983169299295e-06 -2.11034684542728e-05 -3.52204038547136e-06 1.63693353720035e-06 1.02164457118124e-05 2.68059545624341e-08 3.85922791360953e-08 -3.85086642212969e-06 3.98262109445893e-06 5.97084837880659e-06 2.68059545624341e-08 2.74758754527092e-05 -7.89475534297106e-06 8.77025321475288e-06 -5.36735575232711e-06 8.47983169299295e-06 3.85922791360953e-08 -7.89475534297106e-06 3.59030136653225e-05 2.47623933994964e-06 9.82593721384435e-06 -2.11034684542728e-05 -3.85086642212969e-06 8.77025321475288e-06 2.47623933994964e-06 0.000134813965065961 1752 1768 0 92 0 1794 1812 0 113 0 0 0 0 0 0 0 2 0 2934 0 93 122 0 0 3424 +288 289 0.993700469925457 0.107412204199178 0.0319686480633628 0.0921307648968278 -0.108336414839229 0.993698971589043 0.0287328223928948 -0.0969517574991224 -0.0286809569175713 -0.0320151878325461 0.999075788145394 -0.0138547873517032 0.00016771327778574 9.29312188438196e-05 -2.05520539500872e-05 5.56973936211343e-05 -5.83912086578689e-06 0.000367115255616709 9.29312188438196e-05 9.634886074951e-05 -1.14846390842619e-05 3.85496395402262e-05 5.95947881989127e-06 0.000265429895753275 -2.05520539500872e-05 -1.14846390842619e-05 1.84666083998279e-05 -1.55986678667672e-05 7.08614038184817e-07 -5.35558096501891e-05 5.56973936211343e-05 3.85496395402262e-05 -1.55986678667672e-05 8.67613054642875e-05 -8.24498120461374e-06 0.000210151558749894 -5.83912086578689e-06 5.95947881989127e-06 7.08614038184817e-07 -8.24498120461374e-06 2.65834001019278e-05 -7.53870808653786e-06 0.000367115255616709 0.000265429895753275 -5.35558096501891e-05 0.000210151558749894 -7.53870808653786e-06 0.00126972859641086 3508 3368 0 595 0 3472 3332 0 440 0 0 0 0 0 0 0 0 0 2919 0 291 264 0 0 3487 +278 279 0.999808499061887 -0.0181570185376183 -0.00729985489180449 0.0377762477873085 0.0182221315152406 0.999793864577435 0.00895445567073214 -0.110499751760866 0.00713576391552394 -0.00908575979995154 0.999933262694166 0.0136198590769039 2.86862834159457e-05 -1.04151937142339e-05 -3.65442877181001e-06 3.16785967442628e-06 -4.24993361242393e-06 1.36248378733075e-05 -1.04151937142339e-05 5.16233933846687e-05 4.14725987647708e-06 1.05369291315982e-06 5.49857286261122e-06 -1.52769668581839e-05 -3.65442877181001e-06 4.14725987647708e-06 9.7438619200922e-06 -2.71009045736252e-06 -5.17353857602263e-07 -2.3524802271194e-06 3.16785967442628e-06 1.05369291315982e-06 -2.71009045736252e-06 2.30551211351638e-05 -8.2349804604277e-06 1.00743762972998e-05 -4.24993361242393e-06 5.49857286261122e-06 -5.17353857602263e-07 -8.2349804604277e-06 3.41299885793356e-05 -2.95342494774526e-06 1.36248378733075e-05 -1.52769668581839e-05 -2.3524802271194e-06 1.00743762972998e-05 -2.95342494774526e-06 9.21208925681571e-05 1811 1824 0 32 0 1848 1867 0 54 0 0 0 0 0 0 3 20 0 2838 0 7 41 0 0 3482 +281 282 0.999284193125011 0.0159278453107971 0.0343133372648358 0.00905982570086489 -0.01616491533008 0.999847273660422 0.0066426550559168 -0.118472931981288 -0.0342022935322531 -0.00719257238933814 0.999389048378837 -0.00562285396143801 2.690032765609e-05 -1.85617609583423e-06 -1.4621868039329e-08 1.76589822247807e-06 -3.77672266445834e-06 1.24829513419245e-05 -1.85617609583423e-06 3.56280474817832e-05 -2.73610159155549e-06 5.81957133905299e-06 -1.07217498812932e-06 2.16908729680346e-05 -1.4621868039329e-08 -2.73610159155549e-06 1.28379757078714e-05 -2.19079194064128e-06 1.09206615159707e-06 -3.68770949185198e-06 1.76589822247807e-06 5.81957133905299e-06 -2.19079194064128e-06 2.61917494805221e-05 -6.84825367280005e-06 1.4013779664581e-05 -3.77672266445834e-06 -1.07217498812932e-06 1.09206615159707e-06 -6.84825367280005e-06 3.97358787479807e-05 -7.03215704164741e-06 1.24829513419245e-05 2.16908729680346e-05 -3.68770949185198e-06 1.4013779664581e-05 -7.03215704164741e-06 0.000115313680893224 2689 2629 0 74 0 2732 2678 0 19 0 0 0 0 0 0 0 0 0 2854 0 117 156 0 0 3620 +290 291 0.997310236095068 0.0693378003109949 0.0237605224696886 0.113951051670021 -0.0699586706987734 0.997201058552983 0.0263786507401464 -0.0828617797126231 -0.0218649805410517 -0.0279699529646125 0.999369603478661 -0.0174960687688264 2.69255419368754e-05 8.33745772701534e-06 3.83876252874575e-06 -6.50008666336729e-06 -1.40584392268939e-06 4.71056181299326e-06 8.33745772701534e-06 3.0813725063845e-05 1.85862617751399e-06 4.29306207587662e-06 -2.12433658782013e-06 1.26420421007351e-05 3.83876252874575e-06 1.85862617751399e-06 1.40693046848249e-05 -5.1644735243409e-06 -2.53222388351793e-06 3.64797786769198e-06 -6.50008666336729e-06 4.29306207587662e-06 -5.1644735243409e-06 5.15128611112743e-05 -6.26598610860521e-06 3.21011000548945e-06 -1.40584392268939e-06 -2.12433658782013e-06 -2.53222388351793e-06 -6.26598610860521e-06 1.53316258408794e-05 -5.41577801619278e-06 4.71056181299326e-06 1.26420421007351e-05 3.64797786769198e-06 3.21011000548945e-06 -5.41577801619278e-06 0.000103973280285107 3579 3467 0 494 0 3570 3458 0 364 0 0 0 0 0 0 0 0 0 3195 0 166 152 0 0 3525 +292 293 0.997689944587963 0.0679319512456709 0.000156422578333399 0.114885123655043 -0.067926165153318 0.997569160212961 0.0155501343907623 -0.0632843524711505 0.000900308631190501 -0.0155248379045446 0.999879077115031 -0.0486264348977467 6.36962719320027e-05 4.50571459689619e-05 -9.84958652211293e-07 -5.4614420331822e-06 5.59859182211029e-06 2.41890817653188e-05 4.50571459689619e-05 7.51187671321346e-05 -3.1267353342754e-06 -4.63851709197966e-07 5.46980933095705e-07 4.30518169062325e-05 -9.84958652211293e-07 -3.1267353342754e-06 1.43367033822608e-05 3.93752753794414e-06 3.90857697098938e-06 -5.94252221537811e-06 -5.4614420331822e-06 -4.63851709197966e-07 3.93752753794414e-06 4.74732775511045e-05 -3.87812894230591e-06 3.0835907700552e-05 5.59859182211029e-06 5.46980933095705e-07 3.90857697098938e-06 -3.87812894230591e-06 1.70736900883591e-05 -2.43294576076282e-06 2.41890817653188e-05 4.30518169062325e-05 -5.94252221537811e-06 3.0835907700552e-05 -2.43294576076282e-06 0.000183766931868684 3224 3136 0 427 0 3223 3135 0 316 0 0 0 0 0 0 0 0 0 3373 0 147 157 0 0 2565 +285 286 0.990818629327077 0.134434653335052 -0.0143446073873705 0.0667655730078989 -0.13400779890468 0.990600349397471 0.0274382507884643 -0.133115152447832 0.0178984248227661 -0.0252640407752255 0.99952057239087 -0.00620699949829244 8.9334094931403e-05 -2.85431577305748e-05 -5.37744373217128e-06 9.59544271253855e-06 1.65267613002208e-06 5.32670502674638e-05 -2.85431577305748e-05 7.0249067625242e-05 1.12687509476859e-05 -1.04350011262305e-05 1.8800784810477e-06 -1.27422234809723e-05 -5.37744373217128e-06 1.12687509476859e-05 1.3519436990057e-05 -5.69495143290806e-06 1.06050527453201e-06 -3.30651973846115e-06 9.59544271253855e-06 -1.04350011262305e-05 -5.69495143290806e-06 3.51767642968512e-05 -1.17902473814525e-05 8.25046948697402e-06 1.65267613002208e-06 1.8800784810477e-06 1.06050527453201e-06 -1.17902473814525e-05 3.39780313734158e-05 2.94124914325771e-06 5.32670502674638e-05 -1.27422234809723e-05 -3.30651973846115e-06 8.25046948697402e-06 2.94124914325771e-06 8.87608385760909e-05 3251 3180 0 221 0 3255 3184 0 223 0 0 0 0 0 0 0 0 0 2725 0 355 331 0 0 3070 +284 285 0.992465839006839 0.11795041522156 0.0331550592445967 0.0427019272928281 -0.119475154451474 0.991649659468346 0.0485452401900559 -0.136055200892913 -0.0271522719721097 -0.0521406983591083 0.998270555361309 0.00813609005682497 2.5425592283031e-05 -1.70902880043428e-06 1.62807624638867e-06 9.28661535566448e-07 1.47554451812635e-06 3.84094047165482e-06 -1.70902880043428e-06 2.93243009011242e-05 -1.10336843638037e-06 1.72422682141452e-06 -1.88520281861511e-06 1.42590520403913e-06 1.62807624638867e-06 -1.10336843638037e-06 1.24127888206997e-05 -6.12136834581675e-06 7.84904947659821e-07 2.80946027702909e-06 9.28661535566448e-07 1.72422682141452e-06 -6.12136834581675e-06 3.4994026374274e-05 -1.66583034670561e-05 -1.24312107309299e-06 1.47554451812635e-06 -1.88520281861511e-06 7.84904947659821e-07 -1.66583034670561e-05 3.73788252264959e-05 1.0805875476312e-05 3.84094047165482e-06 1.42590520403913e-06 2.80946027702909e-06 -1.24312107309299e-06 1.0805875476312e-05 6.07493824483892e-05 3006 3032 0 222 0 2995 3021 0 245 0 0 0 0 0 0 0 0 0 2942 0 375 380 0 0 2903 +286 287 0.994088165014893 0.103783920217506 -0.031900126670736 0.0776977773902634 -0.102786202728011 0.994205437434995 0.0314729201607808 -0.11896951411667 0.0349816624258892 -0.0280079645632634 0.998995414010967 -0.0268918644434592 3.88985077949678e-05 8.88124642257031e-06 -1.17702026090422e-06 1.41458716465009e-06 -1.73085295205942e-07 2.03094496163208e-05 8.88124642257031e-06 4.49263357345334e-05 3.67436409289135e-06 -1.43762680252162e-06 1.47305477256558e-06 -3.92292719799471e-06 -1.17702026090422e-06 3.67436409289135e-06 1.20255474170545e-05 -3.06684403853336e-06 1.10254594401258e-06 -3.98045668712537e-06 1.41458716465009e-06 -1.43762680252162e-06 -3.06684403853336e-06 3.7195381349702e-05 -1.16536899177848e-05 7.73876917065606e-06 -1.73085295205942e-07 1.47305477256558e-06 1.10254594401258e-06 -1.16536899177848e-05 2.75471911727685e-05 1.33602724516867e-06 2.03094496163208e-05 -3.92292719799471e-06 -3.98045668712537e-06 7.73876917065606e-06 1.33602724516867e-06 9.23397312215129e-05 3632 3477 0 392 0 3598 3443 0 288 0 0 0 0 0 0 0 0 0 2927 0 195 181 0 0 3437 +287 288 0.993991639268439 0.107280542357862 0.0217141957218 0.0842192565927284 -0.107567230074758 0.994119321432512 0.0124926285707149 -0.112980024114396 -0.020246285547867 -0.0147533042388719 0.999686164721484 -0.0210634009790706 5.24393419475159e-05 1.49487172440702e-05 -4.89915135117011e-06 1.03921245085149e-05 1.00187439989993e-06 6.54810954730672e-05 1.49487172440702e-05 3.34398670266928e-05 1.08616062399013e-06 1.98241351667199e-06 9.5469390047357e-07 2.38356492600672e-05 -4.89915135117011e-06 1.08616062399013e-06 1.36120258078883e-05 -1.11309680770294e-05 4.39384841692419e-06 -1.18779366712397e-05 1.03921245085149e-05 1.98241351667199e-06 -1.11309680770294e-05 7.19323878956686e-05 -2.35698625543133e-05 5.15307178148083e-05 1.00187439989993e-06 9.5469390047357e-07 4.39384841692419e-06 -2.35698625543133e-05 2.92656069382189e-05 2.5021218397063e-06 6.54810954730672e-05 2.38356492600672e-05 -1.18779366712397e-05 5.15307178148083e-05 2.5021218397063e-06 0.000316678787883101 3604 3452 0 590 0 3589 3437 0 433 0 0 0 0 0 0 0 0 0 2993 0 207 174 0 0 3645 +291 292 0.997678047130657 0.0680603634392498 0.00251021952729123 0.120503126077315 -0.0680650905290063 0.997679170480115 0.00184830770938538 -0.0713002619058167 -0.00237859724126256 -0.0020148743453689 0.999995141266464 0.00366715675665669 5.50509899852512e-05 2.07778576816942e-05 2.05626855860399e-06 -1.91933515244263e-05 4.68853994686191e-06 3.05222429812766e-05 2.07778576816942e-05 6.35729385585611e-05 5.31988218862529e-06 1.13880564559924e-05 2.18206626508946e-06 9.54005616913631e-05 2.05626855860399e-06 5.31988218862529e-06 1.2433556991632e-05 1.47552234764242e-06 2.38553504820282e-06 1.44637919129574e-06 -1.91933515244263e-05 1.13880564559924e-05 1.47552234764242e-06 6.07614996948378e-05 -8.2797398074446e-06 4.30725089053291e-05 4.68853994686191e-06 2.18206626508946e-06 2.38553504820282e-06 -8.2797398074446e-06 1.73833124169324e-05 -3.80092100353217e-06 3.05222429812766e-05 9.54005616913631e-05 1.44637919129574e-06 4.30725089053291e-05 -3.80092100353217e-06 0.000324204116426136 3418 3318 0 463 0 3404 3304 0 352 0 0 0 0 0 0 0 0 0 3241 0 201 199 0 0 2655 +289 290 0.995829772732892 0.0892703063096495 0.0188115961613431 0.101670036326061 -0.0898952584285222 0.995317902944746 0.0355121752324906 -0.0922449339050413 -0.0155533356816251 -0.0370551546893987 0.999192178342144 -0.0187544524466066 3.89712554464363e-05 1.93217401967684e-05 -1.92254495744168e-06 6.6166808928268e-07 -3.69652115498101e-06 3.58621755473885e-05 1.93217401967684e-05 4.03043837142556e-05 -9.03887306533019e-07 5.83046152587525e-06 -3.9953341842939e-06 1.97845662199345e-05 -1.92254495744168e-06 -9.03887306533019e-07 1.469054814182e-05 -6.85069412767458e-06 -1.92743674938421e-06 -5.11096494176838e-07 6.6166808928268e-07 5.83046152587525e-06 -6.85069412767458e-06 5.43324577353302e-05 -7.08441968313142e-06 2.45263290073495e-05 -3.69652115498101e-06 -3.9953341842939e-06 -1.92743674938421e-06 -7.08441968313142e-06 2.37324708562313e-05 -1.43113620361086e-05 3.58621755473885e-05 1.97845662199345e-05 -5.11096494176838e-07 2.45263290073495e-05 -1.43113620361086e-05 0.000183227238664739 3407 3281 0 549 1 3365 3239 0 400 1 0 0 0 0 0 0 0 0 3074 0 183 177 0 0 3614 +297 298 0.999018907151531 0.0441875368023112 -0.0029469891594291 0.128710316126704 -0.0442353690996589 0.998843331378159 -0.0188475855747914 -0.00984105926559296 0.00211075208831868 0.0189594554965731 0.999818025329057 -0.0314484921755358 3.23334824386913e-05 1.27612015217692e-05 4.50640320708552e-06 5.39040136359904e-06 -3.52891829265989e-06 1.15249948848958e-05 1.27612015217692e-05 8.109356891356e-05 1.38874460416956e-07 1.22337454869192e-05 1.71831974327953e-06 -8.03779044222855e-07 4.50640320708552e-06 1.38874460416956e-07 1.31953157938456e-05 1.89025022116879e-06 2.05506596125978e-06 8.68462717454838e-07 5.39040136359904e-06 1.22337454869192e-05 1.89025022116879e-06 6.98263693834153e-05 2.29748263056272e-06 9.27967677306259e-06 -3.52891829265989e-06 1.71831974327953e-06 2.05506596125978e-06 2.29748263056272e-06 1.65698607747622e-05 -4.31191208926302e-06 1.15249948848958e-05 -8.03779044222855e-07 8.68462717454838e-07 9.27967677306259e-06 -4.31191208926302e-06 0.000103488442385219 3163 3164 0 308 0 3163 3173 0 252 24 0 0 0 0 0 0 0 0 2696 0 0 0 0 0 3373 +299 300 0.999209890743872 0.0364856550404648 0.0157604319701843 0.106501599826244 -0.036745740397548 0.999187748926757 0.0165406456136254 -0.00543286868323922 -0.0151441342523965 -0.0171067054381533 0.999738973846072 -0.0300721432434099 2.68769818189105e-05 -4.89976774589437e-06 1.28886882196711e-06 -4.22372655754588e-06 2.74065877028279e-06 4.16255753629901e-06 -4.89976774589437e-06 4.03907603235918e-05 3.62637915615657e-06 2.12782816526327e-06 -3.39655465532853e-06 -3.84167227535457e-06 1.28886882196711e-06 3.62637915615657e-06 1.05623598740349e-05 -1.15645488787057e-08 2.91713049187068e-06 7.60811560166826e-07 -4.22372655754588e-06 2.12782816526327e-06 -1.15645488787057e-08 9.0388550138819e-05 3.53039678742806e-06 8.02443568217305e-06 2.74065877028279e-06 -3.39655465532853e-06 2.91713049187068e-06 3.53039678742806e-06 1.61148614522168e-05 -2.86444731238614e-06 4.16255753629901e-06 -3.84167227535457e-06 7.60811560166826e-07 8.02443568217305e-06 -2.86444731238614e-06 0.000107770788705152 3394 3417 0 197 0 3394 3424 0 148 29 0 0 0 0 0 0 0 0 2515 0 0 0 0 0 3515 +300 301 0.999838132022892 0.00676205016510962 0.0166728650969068 0.123704244412431 -0.00668183955640199 0.99996585703565 -0.00486187032949163 0.00582926750575597 -0.0167051720469324 0.00474967793885337 0.999849177519469 -0.0209186279764424 3.00448000409715e-05 -2.55527146024725e-06 5.22235530241224e-07 6.54727494612859e-06 2.72313920506672e-06 4.90488808762121e-06 -2.55527146024725e-06 3.05629720671778e-05 2.92108817835486e-06 -4.8951313827983e-06 -1.15047333822897e-06 1.03628558222052e-05 5.22235530241224e-07 2.92108817835486e-06 1.14285610720479e-05 4.29194529826526e-06 1.78476841894182e-06 1.79046046975696e-06 6.54727494612859e-06 -4.8951313827983e-06 4.29194529826526e-06 5.73813653305701e-05 1.87800025479181e-06 2.42594125536388e-06 2.72313920506672e-06 -1.15047333822897e-06 1.78476841894182e-06 1.87800025479181e-06 1.51613917891597e-05 -5.34298480799961e-06 4.90488808762121e-06 1.03628558222052e-05 1.79046046975696e-06 2.42594125536388e-06 -5.34298480799961e-06 8.6838705914715e-05 3390 3423 0 128 75 3390 3423 0 87 146 0 0 0 0 0 0 0 0 2508 0 0 0 0 0 3527 +302 303 0.999826642120201 -0.00142469309514911 0.0185649119639079 0.113901739557473 0.00172966074231504 0.99986366348669 -0.0164214101919084 0.00607893336271959 -0.0185389854188278 0.0164506744104627 0.999692793477617 -0.00436110640833706 3.88234470651704e-05 -2.34119867085847e-06 1.00641216265398e-06 4.61468653484381e-06 3.49890727756153e-08 -6.30138198193305e-06 -2.34119867085847e-06 5.2406063796441e-05 4.83514595385265e-06 1.78146949556166e-06 -3.37887648785306e-06 -7.96561524686613e-07 1.00641216265398e-06 4.83514595385265e-06 1.18649842629004e-05 7.77884762085216e-07 1.44770533964245e-06 1.23597554239591e-06 4.61468653484381e-06 1.78146949556166e-06 7.77884762085216e-07 5.2079568582841e-05 -3.39539416371423e-07 9.92265433788006e-06 3.49890727756153e-08 -3.37887648785306e-06 1.44770533964245e-06 -3.39539416371423e-07 1.35440680230074e-05 -2.31543830455675e-06 -6.30138198193305e-06 -7.96561524686613e-07 1.23597554239591e-06 9.92265433788006e-06 -2.31543830455675e-06 0.000113355814683404 3204 3237 0 92 87 3204 3237 0 59 155 0 0 0 0 0 0 0 0 2656 0 0 0 0 0 3525 +293 294 0.998572414633948 0.0513256329781366 0.0147922997373655 0.103957879430889 -0.0515321690597383 0.998574085714124 0.0139366743593982 -0.0478488662847053 -0.0140558985527427 -0.0146790578578796 0.999793457158167 -0.05053819451122 5.19945406910767e-05 2.37961266787107e-05 4.86753114635288e-06 -8.63189288055677e-07 -5.73868392634943e-07 2.19435317449345e-05 2.37961266787107e-05 3.8350552572072e-05 7.12248499406237e-06 9.90521185086578e-07 -2.98400451648222e-08 2.63345581617736e-05 4.86753114635288e-06 7.12248499406237e-06 1.43612407916023e-05 -4.1979102321463e-08 1.88395818613062e-06 5.84892300066484e-06 -8.63189288055677e-07 9.90521185086578e-07 -4.1979102321463e-08 6.0161245105466e-05 -2.97028972975339e-06 3.08319024413328e-05 -5.73868392634943e-07 -2.98400451648222e-08 1.88395818613062e-06 -2.97028972975339e-06 1.62204392244357e-05 -1.02561301795933e-05 2.19435317449345e-05 2.63345581617736e-05 5.84892300066484e-06 3.08319024413328e-05 -1.02561301795933e-05 0.000182689325413529 3482 3404 0 324 0 3491 3413 0 228 0 0 0 0 0 0 0 0 0 3477 0 71 92 0 0 2486 +294 295 0.998785357576313 0.0441841996450167 0.0218074756192735 0.102824962194501 -0.0442018238236601 0.999022568373033 0.000326576193066746 -0.0396261898969159 -0.0217717307951851 -0.00129010971512997 0.999762135387766 -0.0335053962027742 7.58085084782244e-05 -1.1384099155075e-05 -8.49912734924581e-06 -1.73857393566876e-05 3.76572058652522e-06 -2.49999376050487e-05 -1.1384099155075e-05 2.50718233604044e-05 -5.54616989569855e-06 7.56534955209039e-06 -3.02018381423726e-06 2.14127484603544e-06 -8.49912734924581e-06 -5.54616989569855e-06 1.62796898059382e-05 -6.29436656285283e-07 1.29681826281086e-06 7.36179859750072e-06 -1.73857393566876e-05 7.56534955209039e-06 -6.29436656285283e-07 7.95961164600628e-05 2.0499576903202e-06 3.57367766537905e-05 3.76572058652522e-06 -3.02018381423726e-06 1.29681826281086e-06 2.0499576903202e-06 1.87871032771358e-05 5.0752025216835e-07 -2.49999376050487e-05 2.14127484603544e-06 7.36179859750072e-06 3.57367766537905e-05 5.0752025216835e-07 9.04480808009205e-05 3543 3410 0 270 0 3565 3432 0 196 0 0 0 0 0 0 0 0 0 3509 0 26 54 0 0 2318 +295 296 0.998244612896281 0.0524174757654986 0.0275699303214096 0.124889090265772 -0.0526722076530439 0.998574863546792 0.00859537279356956 -0.0331684192523425 -0.0270800916635938 -0.0100324536818853 0.999582922277393 -0.0170011998141257 3.20867107146271e-05 3.99395834529121e-06 4.94447925869171e-06 4.06243564405347e-06 -8.55708813947858e-09 2.06781903614106e-06 3.99395834529121e-06 3.19025777835863e-05 2.73440701549309e-08 -4.45281652381484e-06 -2.04074938326964e-06 4.38547543579032e-06 4.94447925869171e-06 2.73440701549309e-08 1.27376246074225e-05 1.71435924747008e-06 2.7435454213167e-06 9.84195311174197e-07 4.06243564405347e-06 -4.45281652381484e-06 1.71435924747008e-06 4.56178146169111e-05 4.09403850858049e-06 7.49373232660299e-06 -8.55708813947858e-09 -2.04074938326964e-06 2.7435454213167e-06 4.09403850858049e-06 1.51974500173113e-05 -1.5206427184917e-06 2.06781903614106e-06 4.38547543579032e-06 9.84195311174197e-07 7.49373232660299e-06 -1.5206427184917e-06 8.26644128786216e-05 3349 3203 0 310 0 3369 3233 0 211 0 0 0 0 0 0 0 0 0 3413 0 1 26 0 0 2659 +296 297 0.998042165066035 0.0619939552232879 0.00828168256294225 0.130997860828894 -0.0619695104074018 0.998072987737652 -0.00317662215324344 -0.0191610773013639 -0.00846265503062006 0.00265719103764477 0.999960660629018 -0.0179895500719477 2.5191977199383e-05 4.99284815710459e-06 3.49838040904494e-06 -5.16682692084497e-06 2.23144195604427e-06 6.35809164466881e-06 4.99284815710459e-06 3.21092895888487e-05 5.117781827257e-06 -8.89890230068266e-06 -1.1096709470316e-06 1.05181704552255e-05 3.49838040904494e-06 5.117781827257e-06 1.46091185909531e-05 4.71199627922778e-06 1.32963419143744e-06 6.40599272762572e-06 -5.16682692084497e-06 -8.89890230068266e-06 4.71199627922778e-06 4.98428074965707e-05 1.83128406018715e-06 -2.10547220428308e-06 2.23144195604427e-06 -1.1096709470316e-06 1.32963419143744e-06 1.83128406018715e-06 1.47410325855327e-05 -8.63927971500934e-06 6.35809164466881e-06 1.05181704552255e-05 6.40599272762572e-06 -2.10547220428308e-06 -8.63927971500934e-06 9.34504238071339e-05 3412 3350 0 176 0 3422 3393 0 134 0 0 0 0 0 0 0 0 0 3245 0 0 3 0 0 3556 +306 307 0.997451073527748 0.0713103293829871 -0.00248854206996613 0.082804385670521 -0.0713199715044703 0.997445352650343 -0.00402866489483015 0.0040671987085383 0.00219489930193857 0.00419587887374954 0.999988788445916 0.0342575255824603 6.08032390606394e-05 -3.69530509002855e-05 -3.73798471394515e-07 -6.89001521078266e-06 1.06715252532356e-06 1.35131469080316e-05 -3.69530509002855e-05 5.85403435795651e-05 5.47798787639139e-06 2.73469346471126e-06 -1.87901075416442e-06 -2.40146615189855e-05 -3.73798471394515e-07 5.47798787639139e-06 1.28715486308874e-05 -1.32457622358601e-06 3.08569038261735e-06 -7.6944567581607e-06 -6.89001521078266e-06 2.73469346471126e-06 -1.32457622358601e-06 4.78910202099585e-05 1.50703161397909e-06 8.89039902991569e-06 1.06715252532356e-06 -1.87901075416442e-06 3.08569038261735e-06 1.50703161397909e-06 1.39367202777052e-05 5.92052875861598e-06 1.35131469080316e-05 -2.40146615189855e-05 -7.6944567581607e-06 8.89039902991569e-06 5.92052875861598e-06 0.000176882257944653 3363 3359 0 241 0 3393 3455 0 228 0 0 0 0 0 0 0 0 0 3491 0 0 0 0 0 3638 +298 299 0.999691643521785 0.0240909621990417 0.00602025024696393 0.121284632279466 -0.0242003899154027 0.999530004883886 0.0188178230611538 -0.00587271827091461 -0.00556408129471556 -0.0189577128668718 0.999804804010364 -0.0496752001906826 3.92592809052756e-05 -3.50144147557073e-07 4.76475468734554e-06 4.57202124133993e-06 7.39295261171294e-07 8.09855932354758e-06 -3.50144147557073e-07 5.74675224717421e-05 1.97112167964658e-06 7.66084560309717e-06 -1.29773693476899e-06 -1.66818976129858e-06 4.76475468734554e-06 1.97112167964658e-06 1.15733006823335e-05 -1.81249577887253e-06 3.82825902513356e-06 1.19844808172974e-06 4.57202124133993e-06 7.66084560309717e-06 -1.81249577887253e-06 8.17092346915925e-05 7.54144944010036e-07 2.41938449512058e-05 7.39295261171294e-07 -1.29773693476899e-06 3.82825902513356e-06 7.54144944010036e-07 1.37885779745475e-05 -4.35062549943201e-06 8.09855932354758e-06 -1.66818976129858e-06 1.19844808172974e-06 2.41938449512058e-05 -4.35062549943201e-06 0.000188390877293731 3221 3238 0 185 18 3221 3238 0 136 83 0 0 0 0 0 0 0 0 2669 0 0 0 0 0 3201 +305 306 0.998395325470515 0.0553488818405296 -0.0119697684868287 0.0937473929547386 -0.0552873248484325 0.998455807220734 0.00541412396383579 0.000900650380194595 0.0122509505643062 -0.00474365957831971 0.999913702228385 -0.0099532748461185 3.01985399251463e-05 -7.99820912019763e-06 4.74695171967502e-06 4.77685435268857e-07 1.42919185971739e-06 8.71371577499609e-06 -7.99820912019763e-06 2.77013470046504e-05 -2.98753476526589e-06 -4.46302677859916e-06 -9.98377336080462e-09 -1.15884819502117e-05 4.74695171967502e-06 -2.98753476526589e-06 1.18385874188795e-05 5.81795399201738e-06 3.31730818526247e-06 5.92852478422549e-07 4.77685435268857e-07 -4.46302677859916e-06 5.81795399201738e-06 7.07117838593033e-05 -4.53008928500428e-07 -1.7313735439675e-05 1.42919185971739e-06 -9.98377336080462e-09 3.31730818526247e-06 -4.53008928500428e-07 1.26367195289944e-05 -5.37436818346976e-07 8.71371577499609e-06 -1.15884819502117e-05 5.92852478422549e-07 -1.7313735439675e-05 -5.37436818346976e-07 8.17879077321419e-05 3480 3480 0 218 0 3480 3553 0 193 0 0 0 0 0 0 0 0 0 3389 0 0 0 0 0 3656 +308 309 0.996646805668533 0.0817569688520605 0.0033079895454589 0.0680544571949426 -0.0818069447546575 0.996448186721581 0.0199658450655446 0.00736737311874026 -0.00166389321113767 -0.0201695122250422 0.999795190144454 -0.0287914781782548 3.25715405714672e-05 -1.79323668016316e-05 -2.37069046875006e-06 -3.65660527812158e-06 -1.94254060541232e-07 1.50058792326836e-05 -1.79323668016316e-05 3.76211050490225e-05 4.82508533447117e-06 -1.07784020548709e-05 -6.02828387386171e-06 -7.31688133361755e-06 -2.37069046875006e-06 4.82508533447117e-06 1.56776847033705e-05 -2.77944892084265e-06 -1.92203551927754e-06 -1.16402894722159e-06 -3.65660527812158e-06 -1.07784020548709e-05 -2.77944892084265e-06 6.6413369932368e-05 1.8521238606065e-05 -2.14521315581903e-05 -1.94254060541232e-07 -6.02828387386171e-06 -1.92203551927754e-06 1.8521238606065e-05 3.0905943184962e-05 -1.73194972252307e-05 1.50058792326836e-05 -7.31688133361755e-06 -1.16402894722159e-06 -2.14521315581903e-05 -1.73194972252307e-05 0.000139242453907887 3360 3379 0 252 0 3421 3496 0 260 0 0 0 0 0 0 0 0 0 3638 0 0 4 0 0 3614 +301 302 0.998972659993162 -0.01453124250372 0.042923974390596 0.116085982450078 0.0149977698835622 0.99983169157774 -0.0105667126067922 0.00926452820481105 -0.0427632024608328 0.0111996208905886 0.999022460712071 0.00035135337529012 4.96067957756211e-05 -1.51659352705665e-05 -1.43050546475327e-06 1.39944550481577e-05 4.1295518251156e-06 -3.41587080989995e-05 -1.51659352705665e-05 3.22846157173867e-05 3.57812137850387e-06 -1.28992221895723e-05 -5.58268036420254e-07 1.93889408601193e-05 -1.43050546475327e-06 3.57812137850387e-06 1.05527223224663e-05 3.4488374779866e-06 1.85368514863873e-06 1.06492885136205e-06 1.39944550481577e-05 -1.28992221895723e-05 3.4488374779866e-06 5.2849680027553e-05 -8.01881237093586e-07 -2.49727326005329e-05 4.1295518251156e-06 -5.58268036420254e-07 1.85368514863873e-06 -8.01881237093586e-07 1.41702547745699e-05 -5.50948198835546e-06 -3.41587080989995e-05 1.93889408601193e-05 1.06492885136205e-06 -2.49727326005329e-05 -5.50948198835546e-06 0.00014236035359 3296 3326 0 57 124 3296 3326 0 25 191 0 0 0 0 0 0 0 0 2607 0 0 0 0 0 3438 +311 312 0.997692831810816 0.0678263374230724 0.00293279816662247 0.0290880591417183 -0.0678306368670315 0.997695878841893 0.00139213652929403 -0.0133959370236049 -0.00283161712233942 -0.0015878582036231 0.999994730311514 0.017061939002484 2.77401957799604e-05 -8.44611857677026e-06 -7.29369818024119e-07 -1.90313565320356e-06 -2.62291350709192e-06 -2.37700836174742e-06 -8.44611857677026e-06 2.58739499447458e-05 3.89241797183826e-06 -4.05987268762142e-06 -2.27603401135919e-06 -1.01032482498181e-05 -7.29369818024119e-07 3.89241797183826e-06 1.77539066493469e-05 -5.19442840059581e-07 -3.09455067339251e-06 -2.67261036895046e-06 -1.90313565320356e-06 -4.05987268762142e-06 -5.19442840059581e-07 3.71279067367669e-05 9.41484476339176e-06 5.9903383582965e-06 -2.62291350709192e-06 -2.27603401135919e-06 -3.09455067339251e-06 9.41484476339176e-06 3.28198427450917e-05 -3.82510940534821e-06 -2.37700836174742e-06 -1.01032482498181e-05 -2.67261036895046e-06 5.9903383582965e-06 -3.82510940534821e-06 0.000105978438546204 3558 3610 0 218 0 3690 3765 0 265 0 0 0 0 0 0 0 0 0 3656 0 0 48 0 0 3294 +313 314 0.99813403181337 0.0610540627146685 0.000925182155516547 0.0116367006563172 -0.061060446791546 0.998077805556517 0.0105979192818235 -0.0243736914860254 -0.000276357747040554 -0.0106346359373786 0.999943412471363 -0.00224560344575665 1.69722969042028e-05 -1.19908414375857e-05 1.60645049997414e-06 5.93317674009087e-07 1.2647945163017e-06 4.8323359505116e-06 -1.19908414375857e-05 1.86878557814367e-05 -1.93235681516404e-07 3.60204555927062e-07 -6.03279139745752e-08 1.66731231797447e-06 1.60645049997414e-06 -1.93235681516404e-07 1.37614309051939e-05 1.07319310957068e-06 -4.85132792161348e-07 -1.16241458124496e-06 5.93317674009087e-07 3.60204555927062e-07 1.07319310957068e-06 2.27015333698787e-05 -3.77455593770868e-06 1.54981760737335e-06 1.2647945163017e-06 -6.03279139745752e-08 -4.85132792161348e-07 -3.77455593770868e-06 2.01730008291765e-05 4.85309187454526e-06 4.8323359505116e-06 1.66731231797447e-06 -1.16241458124496e-06 1.54981760737335e-06 4.85309187454526e-06 7.36602214587293e-05 3264 3278 0 62 0 3281 3295 0 81 0 0 0 0 0 0 0 0 0 3624 0 0 3 0 0 2777 +303 304 0.999609266476714 0.0226888577419152 0.0163257498526912 0.0925181445892186 -0.0228385875997431 0.999698255742866 0.00904413517817383 -0.000246952817469406 -0.0161156225549735 -0.00941345839951277 0.999825821586253 -0.0410076613220745 4.29937049116949e-05 -3.92627162297867e-06 2.83255615677348e-06 -1.74955021059983e-06 -3.01342700108631e-07 -1.15563671244465e-05 -3.92627162297867e-06 3.37192721718342e-05 5.52220694794945e-06 -9.61395632403829e-06 -3.76362555697526e-06 -4.69835495829598e-06 2.83255615677348e-06 5.52220694794945e-06 1.28897504085714e-05 -4.00424151762567e-07 -4.92504380829331e-07 -1.19508192576705e-07 -1.74955021059983e-06 -9.61395632403829e-06 -4.00424151762567e-07 6.90849677424149e-05 4.12341484382713e-06 -7.49106322347359e-06 -3.01342700108631e-07 -3.76362555697526e-06 -4.92504380829331e-07 4.12341484382713e-06 1.71224465471949e-05 -1.69024831555788e-06 -1.15563671244465e-05 -4.69835495829598e-06 -1.19508192576705e-07 -7.49106322347359e-06 -1.69024831555788e-06 0.000128280993020663 3447 3486 0 136 0 3447 3486 0 98 63 0 0 0 0 0 0 0 0 2811 0 0 0 0 0 3623 +304 305 0.999225481699994 0.0387559606745767 -0.00681265246474527 0.0953703284164154 -0.038672169845167 0.999179552802475 0.0120284887210816 0.000302832487188033 0.00727323867897169 -0.011755712383233 0.999904447047557 -0.0438629259070452 4.89738634382869e-05 -1.24308227506284e-05 6.67435904414244e-07 7.66481483571336e-06 3.45120907663481e-06 -1.38473667804212e-05 -1.24308227506284e-05 2.43815543717562e-05 1.58781800571249e-06 -7.9375710172913e-06 -2.70689355236784e-06 6.61058778339986e-06 6.67435904414244e-07 1.58781800571249e-06 1.45012365574949e-05 8.0859200429829e-06 -2.54622630405189e-08 -5.6226764357331e-08 7.66481483571336e-06 -7.9375710172913e-06 8.0859200429829e-06 6.99317162824252e-05 -4.42426001355222e-06 -1.61589224822357e-05 3.45120907663481e-06 -2.70689355236784e-06 -2.54622630405189e-08 -4.42426001355222e-06 1.71504586404329e-05 -8.56346846520431e-06 -1.38473667804212e-05 6.61058778339986e-06 -5.6226764357331e-08 -1.61589224822357e-05 -8.56346846520431e-06 0.000142367156511996 3564 3597 0 183 0 3564 3617 0 141 22 0 0 0 0 0 0 0 0 3164 0 0 0 0 0 3606 +307 308 0.997674854472468 0.0681523082627291 0.000384228840636263 0.0683489255942054 -0.0681524807022613 0.997616524893706 0.0107939164872698 0.00136785913736847 0.000352317283043078 -0.0107950052092716 0.999941670166347 0.0516758276330308 5.18283369102997e-05 -1.77449567890863e-05 2.62832441915982e-06 1.07136682770393e-05 2.54784380808673e-06 2.65908376097564e-05 -1.77449567890863e-05 6.01497554234416e-05 -4.29186319076002e-06 -5.75004539954964e-08 5.29121689308046e-06 1.14729631310278e-05 2.62832441915982e-06 -4.29186319076002e-06 1.57665632609329e-05 5.34935245709843e-06 -1.23143199167674e-06 -4.61664084767606e-06 1.07136682770393e-05 -5.75004539954964e-08 5.34935245709843e-06 7.14445718662124e-05 8.79428724953787e-06 1.90173456151626e-05 2.54784380808673e-06 5.29121689308046e-06 -1.23143199167674e-06 8.79428724953787e-06 2.20637364049226e-05 1.21190102754005e-05 2.65908376097564e-05 1.14729631310278e-05 -4.61664084767606e-06 1.90173456151626e-05 1.21190102754005e-05 0.000148691958622804 3253 3260 0 225 0 3296 3365 0 220 0 0 0 0 0 0 0 0 0 3639 0 0 1 0 0 3638 +316 317 0.995893024116886 0.0889011504074504 0.0171368016722884 0.0148510553821663 -0.0890028739718382 0.996017447866386 0.00526611531249133 -0.0501345502712294 -0.0166003897567663 -0.0067697121034243 0.999839286114504 0.0024681240967647 2.24070694614822e-05 -1.76075345466117e-05 -1.10279681661532e-06 1.6080413286998e-06 2.88267306950882e-06 1.7158508058283e-05 -1.76075345466117e-05 2.58430085792969e-05 6.9471528073442e-07 1.87541348232858e-07 1.90764086184376e-07 -1.24149742509977e-05 -1.10279681661532e-06 6.9471528073442e-07 1.05229063163452e-05 -2.84383795239371e-06 3.40847203101041e-06 -6.43324888130844e-07 1.6080413286998e-06 1.87541348232858e-07 -2.84383795239371e-06 2.06666820241071e-05 6.51111783249322e-06 1.25657218001591e-07 2.88267306950882e-06 1.90764086184376e-07 3.40847203101041e-06 6.51111783249322e-06 3.42037340542515e-05 -2.36704263442845e-06 1.7158508058283e-05 -1.24149742509977e-05 -6.43324888130844e-07 1.25657218001591e-07 -2.36704263442845e-06 0.000100375274046233 1847 1846 0 244 0 1847 1846 0 268 0 0 0 0 0 0 0 0 0 3190 0 0 0 0 0 2478 +309 310 0.99586109137347 0.0865935391557691 0.0276087968756198 0.0440845872932594 -0.0869830569098943 0.996121910874097 0.0132320250584672 1.54271061413933e-05 -0.0263559196206667 -0.015578756465652 0.99953122404852 -0.0239992395257945 4.27235726583221e-05 -2.53176229982225e-05 7.59845390304131e-07 -9.01096529557707e-06 -5.2110585279023e-06 1.43872232646248e-05 -2.53176229982225e-05 5.77893217446327e-05 2.66848743693934e-06 -8.65142268410841e-06 -3.12024487568519e-06 -3.33590067790184e-05 7.59845390304131e-07 2.66848743693934e-06 1.30941356536887e-05 -1.7209935685794e-06 2.58132461447729e-06 -3.55179289557904e-06 -9.01096529557707e-06 -8.65142268410841e-06 -1.7209935685794e-06 4.03449540897247e-05 6.20560358448039e-06 -5.24678891053293e-07 -5.2110585279023e-06 -3.12024487568519e-06 2.58132461447729e-06 6.20560358448039e-06 2.10568958449559e-05 -4.15665699878415e-06 1.43872232646248e-05 -3.33590067790184e-05 -3.55179289557904e-06 -5.24678891053293e-07 -4.15665699878415e-06 0.000119073724971853 3178 3209 0 238 0 3295 3334 0 256 0 0 0 0 0 0 0 0 0 3627 0 0 62 0 0 3573 +315 316 0.996577574368072 0.0826603240296824 -0.000639607659071922 0.0128963596257485 -0.0826519442960305 0.996542273180555 0.00849434330701982 -0.0409735135618084 0.00133954124069285 -0.00841240723215055 0.999963717858716 -0.00672054755347978 4.12619156038603e-05 -2.51007511409432e-05 -3.3884094139368e-06 -1.88509291398317e-07 2.99412931464984e-08 1.84672756237458e-05 -2.51007511409432e-05 6.31528116557242e-05 2.27883219764057e-06 -6.65812077791559e-06 -6.58786639515688e-06 2.7493294108656e-05 -3.3884094139368e-06 2.27883219764057e-06 1.25102240057801e-05 -4.71785714459599e-07 2.55169088012725e-06 -1.9947351118892e-06 -1.88509291398317e-07 -6.65812077791559e-06 -4.71785714459599e-07 2.30782569288688e-05 1.21011329065352e-06 -3.01994567954665e-06 2.99412931464984e-08 -6.58786639515688e-06 2.55169088012725e-06 1.21011329065352e-06 2.76310916454489e-05 -2.0564388711657e-05 1.84672756237458e-05 2.7493294108656e-05 -1.9947351118892e-06 -3.01994567954665e-06 -2.0564388711657e-05 0.000210243243657771 2361 2395 0 204 0 2361 2395 0 212 0 0 0 0 0 0 0 0 0 3251 0 0 0 0 0 2689 +310 311 0.997262381299814 0.0739437206565618 0.000262715983746732 0.030715477958099 -0.0739435121065192 0.997231796456723 0.00781672265402219 -0.0121047608907466 0.000316008823949186 -0.00781474959043512 0.999969414445893 -0.00732620457524604 4.69363245234215e-05 -3.05173459328765e-05 -3.32937971919706e-06 -2.48910789975278e-06 -2.80582780938301e-06 2.08526785926426e-05 -3.05173459328765e-05 4.70871173016116e-05 5.22897929472373e-06 5.71690251019743e-07 6.78051974147795e-07 -1.89359502869563e-05 -3.32937971919706e-06 5.22897929472373e-06 1.46893076183772e-05 3.41211424950833e-07 6.64640735962927e-08 -7.32327129078376e-06 -2.48910789975278e-06 5.71690251019743e-07 3.41211424950833e-07 3.3933671499273e-05 6.17901902357503e-06 5.17872417099753e-06 -2.80582780938301e-06 6.78051974147795e-07 6.64640735962927e-08 6.17901902357503e-06 2.4099338575435e-05 1.93797605467786e-06 2.08526785926426e-05 -1.89359502869563e-05 -7.32327129078376e-06 5.17872417099753e-06 1.93797605467786e-06 0.000140930188951003 3246 3284 0 223 0 3381 3420 0 266 0 0 0 0 0 0 0 0 0 3631 0 0 76 0 0 3569 +314 315 0.997097026829892 0.0761414260236921 4.82707727908036e-05 0.014265498987318 -0.0761321005463437 0.996964576022117 0.0162953190653317 -0.0283290010395583 0.00119262458061577 -0.0162516891466142 0.999867221308155 -0.0153710098107569 2.49337492801842e-05 -1.28470553646622e-05 -3.09154826140313e-06 8.16959135260543e-07 1.34352877750913e-06 7.06306779239238e-06 -1.28470553646622e-05 3.32347368589324e-05 2.32893130274559e-06 -9.01818931475569e-07 -4.74201875466856e-08 2.48218161116192e-05 -3.09154826140313e-06 2.32893130274559e-06 1.13488207555625e-05 -2.43362006912177e-06 2.35621778395542e-06 -3.15352076582706e-06 8.16959135260543e-07 -9.01818931475569e-07 -2.43362006912177e-06 1.84864767062215e-05 -3.51984665935232e-06 5.05027232411178e-06 1.34352877750913e-06 -4.74201875466856e-08 2.35621778395542e-06 -3.51984665935232e-06 1.89917813417238e-05 -5.85086784913855e-06 7.06306779239238e-06 2.48218161116192e-05 -3.15352076582706e-06 5.05027232411178e-06 -5.85086784913855e-06 0.000168240084979239 2856 2885 0 93 0 2856 2885 0 104 0 0 0 0 0 0 0 0 0 3435 0 0 0 0 0 2594 +321 322 0.994896574066082 0.09815766370826 -0.0233640742788685 0.0349815805970953 -0.0985358248488193 0.995010863544773 -0.0156228246245035 -0.0590570939485968 0.0217140077584761 0.0178452930270511 0.999604945657955 0.00104832633886122 5.77945045555741e-05 -1.68175210277609e-05 -1.23578687146411e-06 3.78709629099827e-06 -2.87224248548845e-06 -7.02086190214844e-06 -1.68175210277609e-05 7.98544549769055e-05 3.80192491964158e-06 6.92099273158205e-06 1.01638246451184e-06 2.29406690873612e-05 -1.23578687146411e-06 3.80192491964158e-06 1.27613519938201e-05 4.2542615026984e-06 -9.77829492021459e-07 -1.23840034986036e-06 3.78709629099827e-06 6.92099273158205e-06 4.2542615026984e-06 2.89875164848078e-05 -6.12990417284459e-06 6.25830566551377e-06 -2.87224248548845e-06 1.01638246451184e-06 -9.77829492021459e-07 -6.12990417284459e-06 4.88210187063682e-05 1.13497475727741e-06 -7.02086190214844e-06 2.29406690873612e-05 -1.23840034986036e-06 6.25830566551377e-06 1.13497475727741e-06 0.000153451829296659 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2522 0 0 0 0 0 2884 +312 313 0.998185259396536 0.0602157859986125 -0.000497031224864589 0.0160771474813039 -0.0602173796011538 0.998175850810278 -0.00434028261161828 -0.0176347818331729 0.00023477103684378 0.00436233604247377 0.999990457407876 0.000597580426359001 2.20505614163414e-05 -1.48811380093625e-05 -1.85767362435522e-06 9.67671344846734e-07 1.89619284448145e-08 1.05023742372785e-05 -1.48811380093625e-05 2.84823463963845e-05 2.76253505755742e-06 1.22395690205361e-06 1.52493657746144e-06 -5.03747411392427e-06 -1.85767362435522e-06 2.76253505755742e-06 1.31178194605527e-05 -1.93764638621353e-06 4.48955983390706e-06 -6.6827503113278e-06 9.67671344846734e-07 1.22395690205361e-06 -1.93764638621353e-06 2.23877310730304e-05 1.05859359201825e-06 -2.74199268190043e-06 1.89619284448145e-08 1.52493657746144e-06 4.48955983390706e-06 1.05859359201825e-06 1.83779431683019e-05 -9.29139513497934e-07 1.05023742372785e-05 -5.03747411392427e-06 -6.6827503113278e-06 -2.74199268190043e-06 -9.29139513497934e-07 8.20403930133587e-05 3349 3368 0 109 0 3428 3451 0 152 0 0 0 0 0 0 0 0 0 3700 0 0 21 0 0 3019 +319 320 0.992532442103006 0.121974806597971 -0.00122389886469299 0.0328759475040599 -0.121980942696337 0.992485038482255 -0.00970041276390244 -0.0599525810631163 3.14953410257164e-05 0.00977726670724349 0.999952200889512 0.0191852750514798 2.16492697583938e-05 -1.92621002641105e-05 -6.19204778502726e-07 1.30436653922102e-06 5.1058626835316e-06 8.51754360482757e-06 -1.92621002641105e-05 3.32677745139463e-05 1.65824229078619e-06 2.42848904500373e-07 -9.78684744563426e-06 2.83999193999636e-06 -6.19204778502726e-07 1.65824229078619e-06 1.01316026171926e-05 -1.38563655655018e-06 2.71859100045541e-07 -2.39548702949885e-06 1.30436653922102e-06 2.42848904500373e-07 -1.38563655655018e-06 1.85099467457342e-05 -1.05868463418754e-07 2.00368839460249e-06 5.1058626835316e-06 -9.78684744563426e-06 2.71859100045541e-07 -1.05868463418754e-07 4.27619926941361e-05 -9.56779621690947e-06 8.51754360482757e-06 2.83999193999636e-06 -2.39548702949885e-06 2.00368839460249e-06 -9.56779621690947e-06 8.67294254374488e-05 142 18 0 411 0 142 18 0 284 0 0 0 0 0 0 0 0 0 2531 0 0 0 0 0 2889 +323 324 0.994781439093142 0.0953662131760282 -0.0362653253155236 0.0348679448319526 -0.0956384928397293 0.995398973246544 -0.00584489068087649 -0.0284487092853234 0.035541062492861 0.00928274981838357 0.999325103974021 0.0323789552619317 2.8371136301199e-05 1.40807784592123e-05 -3.88131025722968e-06 1.97737789839432e-06 -1.08629784839541e-06 2.66848207201975e-06 1.40807784592123e-05 5.36518254162885e-05 -2.29908538728329e-06 4.002736276468e-07 -1.51758874939014e-06 -1.64520058111716e-06 -3.88131025722968e-06 -2.29908538728329e-06 1.17793626072193e-05 -2.10831121681779e-06 1.64713164140886e-06 -1.80833663707193e-08 1.97737789839432e-06 4.002736276468e-07 -2.10831121681779e-06 2.16865510528122e-05 -4.08964495527044e-06 1.11656438303965e-05 -1.08629784839541e-06 -1.51758874939014e-06 1.64713164140886e-06 -4.08964495527044e-06 4.77307591649719e-05 -6.18946228105894e-06 2.66848207201975e-06 -1.64520058111716e-06 -1.80833663707193e-08 1.11656438303965e-05 -6.18946228105894e-06 9.15317503992503e-05 67 67 0 0 0 29 29 0 0 0 0 0 0 0 0 0 0 0 2109 0 205 259 0 0 2777 +317 318 0.993849715315236 0.110524319096288 0.00686427389656294 0.0234922437756511 -0.110553008142351 0.993862380379028 0.00394984278299785 -0.0517402667399472 -0.00638558991028344 -0.0046844162534004 0.999968639751199 0.00194302905209614 3.47874572464702e-05 -2.94474111382271e-05 -2.13241663162733e-06 9.63940894361097e-08 -2.40436362261652e-06 2.2889560278003e-05 -2.94474111382271e-05 4.70943450291857e-05 1.28057124640887e-06 -6.83151825041947e-06 -1.1733882324307e-06 -3.40292787230082e-05 -2.13241663162733e-06 1.28057124640887e-06 1.13413292545996e-05 -1.75178974147757e-06 1.19046603007235e-07 -1.99437201806167e-06 9.63940894361097e-08 -6.83151825041947e-06 -1.75178974147757e-06 2.28585653270629e-05 9.96890351088169e-06 7.31161652353067e-06 -2.40436362261652e-06 -1.1733882324307e-06 1.19046603007235e-07 9.96890351088169e-06 5.3014085961023e-05 1.02286595140552e-06 2.2889560278003e-05 -3.40292787230082e-05 -1.99437201806167e-06 7.31161652353067e-06 1.02286595140552e-06 0.000130978680041548 1278 1227 0 321 0 1278 1227 0 320 0 0 0 0 0 0 0 0 0 3105 0 0 0 0 0 2400 +324 325 0.995344683404972 0.0953203192243373 -0.0142477352735687 0.0308021999694106 -0.0951818512341335 0.995408649235257 0.0101012980989536 -0.0278855537710947 0.0151451778826969 -0.00869814753905005 0.999847471275639 0.042131678802574 1.91807167141147e-05 4.70872513378649e-06 -3.59902577421005e-06 1.4483313389839e-06 -3.07044386088888e-06 6.75420863243852e-06 4.70872513378649e-06 2.93798802869966e-05 -1.70260489675255e-06 4.10547132074086e-06 3.93326331531012e-06 7.00374089564309e-06 -3.59902577421005e-06 -1.70260489675255e-06 1.30291011646682e-05 1.56297478363704e-06 -1.2921653696423e-06 -2.53824253737277e-06 1.4483313389839e-06 4.10547132074086e-06 1.56297478363704e-06 3.00699350619161e-05 -8.12063071395709e-06 3.16486154678684e-06 -3.07044386088888e-06 3.93326331531012e-06 -1.2921653696423e-06 -8.12063071395709e-06 5.87203076843862e-05 1.67618395207726e-06 6.75420863243852e-06 7.00374089564309e-06 -2.53824253737277e-06 3.16486154678684e-06 1.67618395207726e-06 6.7773405947371e-05 305 305 0 0 0 400 400 0 0 0 0 0 0 0 0 0 0 0 1844 0 121 173 0 0 2960 +318 319 0.992339336506686 0.123174744017551 -0.00951964587997316 0.0292321971629633 -0.123226898055156 0.992365422110594 -0.00509907785446014 -0.0600138697771456 0.00881888979257425 0.00623309196726355 0.999941686173426 0.0192211522023461 9.34820084668446e-05 -7.83615856535815e-05 -9.69476209707686e-06 9.57840187082384e-06 1.05031777569205e-05 0.000141756387813419 -7.83615856535815e-05 0.000104000638473383 1.01628434776829e-05 -5.88217710078615e-06 -9.30043069420299e-06 -0.000124007095989135 -9.69476209707686e-06 1.01628434776829e-05 1.23939460606003e-05 -2.63303068581373e-06 -1.46417591559524e-07 -1.27551843056783e-05 9.57840187082384e-06 -5.88217710078615e-06 -2.63303068581373e-06 2.03939943690662e-05 6.68278933728335e-07 2.75378460377785e-05 1.05031777569205e-05 -9.30043069420299e-06 -1.46417591559524e-07 6.68278933728335e-07 4.94576736168404e-05 4.95295097042013e-06 0.000141756387813419 -0.000124007095989135 -1.27551843056783e-05 2.75378460377785e-05 4.95295097042013e-06 0.000403591508062938 696 579 0 404 0 696 579 0 345 0 0 0 0 0 0 0 0 0 2413 0 0 0 0 0 2160 +320 321 0.993992342826526 0.109333001665841 0.0050514501849257 0.0367454695199516 -0.109337900102827 0.994004390951152 0.00070311516405758 -0.0439753180012235 -0.00494428997308396 -0.00125120604489226 0.999986994155472 0.0356643297161552 2.67017289010038e-05 -9.39985458366395e-06 -2.06195374268502e-06 2.42733534015287e-06 -5.14782517135197e-06 1.24895027205572e-06 -9.39985458366395e-06 5.55761355234443e-05 2.65019050244166e-06 -9.53450426546683e-07 1.28934784040271e-06 -1.24055288914758e-06 -2.06195374268502e-06 2.65019050244166e-06 1.10730403689025e-05 5.17846122246364e-07 -3.97543967382763e-07 -3.17450837430127e-06 2.42733534015287e-06 -9.53450426546683e-07 5.17846122246364e-07 2.34470960427562e-05 -1.89848203826909e-06 -7.27318235621387e-07 -5.14782517135197e-06 1.28934784040271e-06 -3.97543967382763e-07 -1.89848203826909e-06 6.48993829337626e-05 7.53995563572925e-06 1.24895027205572e-06 -1.24055288914758e-06 -3.17450837430127e-06 -7.27318235621387e-07 7.53995563572925e-06 7.21269600960141e-05 0 0 0 18 0 0 0 0 2 0 0 0 0 0 0 0 0 0 3015 0 0 0 0 0 2444 +322 323 0.99526586828043 0.097180197092581 0.00136408542603153 0.0368813019402446 -0.097141817427954 0.995117664043844 -0.0174442544901565 -0.033509523325501 -0.0030526615921953 0.0172291613542387 0.999846906909369 0.0252078904092245 5.28579773470524e-05 -1.61743683703879e-05 -4.36809132285492e-06 -2.0960816202325e-06 3.52110374624793e-06 2.89965508874984e-05 -1.61743683703879e-05 7.43503566516753e-05 2.63478408068426e-06 7.55039901569647e-06 -4.35392182947754e-06 2.04308003077979e-05 -4.36809132285492e-06 2.63478408068426e-06 1.46400053298379e-05 3.0736197500551e-06 -6.82176431724956e-07 -6.05220440804223e-06 -2.0960816202325e-06 7.55039901569647e-06 3.0736197500551e-06 2.80602482151732e-05 -2.20501950821258e-06 1.64971698155293e-05 3.52110374624793e-06 -4.35392182947754e-06 -6.82176431724956e-07 -2.20501950821258e-06 5.43028685732843e-05 3.08406003176646e-06 2.89965508874984e-05 2.04308003077979e-05 -6.05220440804223e-06 1.64971698155293e-05 3.08406003176646e-06 0.000194146639594478 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2341 0 26 7 0 0 3061 +331 332 0.999957416674484 0.00837848039993318 -0.003868579051859 0.00523634326723987 -0.00840345667288913 0.999943657134199 -0.00648571299317679 0.0192510627839593 0.00381402066583572 0.00651794624639714 0.999971484404975 0.0719382525604076 3.60008623774562e-05 5.90983605377746e-06 -2.22000932140855e-06 8.21764946083727e-07 4.87536419150235e-06 7.11649982048096e-06 5.90983605377746e-06 2.91508066203531e-05 -2.82963773979358e-06 3.72078247964988e-06 5.32531585750964e-06 1.19148709535164e-05 -2.22000932140855e-06 -2.82963773979358e-06 1.53121244440768e-05 3.45721819800591e-06 1.64221170288534e-06 -2.64943922630777e-06 8.21764946083727e-07 3.72078247964988e-06 3.45721819800591e-06 3.76824821134006e-05 -1.34606601374698e-05 -1.08557615931541e-06 4.87536419150235e-06 5.32531585750964e-06 1.64221170288534e-06 -1.34606601374698e-05 4.61355275844926e-05 5.04282270377224e-06 7.11649982048096e-06 1.19148709535164e-05 -2.64943922630777e-06 -1.08557615931541e-06 5.04282270377224e-06 5.49266030340486e-05 3132 3083 0 0 64 3101 3087 0 0 30 0 0 0 0 0 0 0 0 546 0 79 45 0 0 3307 +325 326 0.995888236685785 0.0889786755225085 -0.0170122112947764 0.0362620886136538 -0.0890948771618369 0.996003861445944 -0.00619764860942274 -0.0348506060284761 0.0163927695767112 0.00768786622079543 0.999836073473335 0.0531189689011062 2.552490041473e-05 -3.91645878086933e-07 -5.27866281622053e-06 3.94603150627125e-06 1.61888529273809e-06 2.067619623501e-06 -3.91645878086933e-07 4.09408812692064e-05 -4.97811079473838e-06 7.66904586179396e-07 3.63628530276377e-07 1.46672916562251e-05 -5.27866281622053e-06 -4.97811079473838e-06 1.40861373037321e-05 2.45653025937426e-07 -1.00265915400493e-06 -3.52700121274855e-06 3.94603150627125e-06 7.66904586179396e-07 2.45653025937426e-07 2.83910798460273e-05 -7.38380199881728e-06 5.6583032720456e-06 1.61888529273809e-06 3.63628530276377e-07 -1.00265915400493e-06 -7.38380199881728e-06 4.74037846896874e-05 -6.33920645204206e-06 2.067619623501e-06 1.46672916562251e-05 -3.52700121274855e-06 5.6583032720456e-06 -6.33920645204206e-06 6.45053521284538e-05 713 713 0 0 0 753 753 0 0 0 0 0 0 0 0 0 0 0 1479 0 171 163 0 0 2984 +329 330 0.998897189339592 0.0462561484780539 0.00804822076235114 0.0323040881072167 -0.0461718402398307 0.998879750892066 -0.0103636106966096 -0.0102262829430286 -0.00851858546537278 0.00998058043299894 0.999913907151955 0.0909985285202357 3.14883881756287e-05 8.97967773689919e-06 -6.09965428927833e-06 -1.03871668003077e-06 9.16820428724638e-06 1.70541841955805e-05 8.97967773689919e-06 2.79506060410136e-05 -4.69986234159431e-06 7.6001924233172e-06 6.70700176783829e-06 3.17741986462137e-05 -6.09965428927833e-06 -4.69986234159431e-06 1.53567884579852e-05 -3.93549152725136e-06 -2.73817036573903e-06 -1.00731850461856e-05 -1.03871668003077e-06 7.6001924233172e-06 -3.93549152725136e-06 3.98269174757531e-05 -1.12379922050664e-05 1.18967207492491e-05 9.16820428724638e-06 6.70700176783829e-06 -2.73817036573903e-06 -1.12379922050664e-05 4.40827894821498e-05 1.23984892692539e-05 1.70541841955805e-05 3.17741986462137e-05 -1.00731850461856e-05 1.18967207492491e-05 1.23984892692539e-05 0.000119164008165294 2372 2375 0 0 3 2356 2359 0 0 0 0 0 0 0 0 0 0 0 774 0 128 102 0 0 3057 +327 328 0.998735369614013 0.049503716268644 0.00877744595853751 0.0399877972438755 -0.0498567661787889 0.997694588328582 0.0460414083847951 -0.0334704109344887 -0.00647798951488979 -0.0464207980915398 0.998900968643233 0.090237227966259 3.08884782780289e-05 1.64589491148941e-06 -3.94432788245734e-06 -2.11129592526455e-06 1.86660783803166e-06 1.52157170610118e-06 1.64589491148941e-06 3.15008514152782e-05 -4.06849563874961e-06 4.57685517357272e-06 1.03637036551115e-06 1.70628877172569e-05 -3.94432788245734e-06 -4.06849563874961e-06 1.30846962773307e-05 1.34061323071185e-07 6.47226052848309e-07 -5.54614275649233e-06 -2.11129592526455e-06 4.57685517357272e-06 1.34061323071185e-07 3.62456625869027e-05 -1.84725789356859e-05 9.64036576723e-06 1.86660783803166e-06 1.03637036551115e-06 6.47226052848309e-07 -1.84725789356859e-05 4.69781708166149e-05 -4.18583652178558e-06 1.52157170610118e-06 1.70628877172569e-05 -5.54614275649233e-06 9.64036576723e-06 -4.18583652178558e-06 9.75223596896198e-05 1427 1427 0 0 5 1383 1383 0 0 5 0 0 0 0 0 0 0 0 1099 0 154 121 0 0 3090 +330 331 0.99891282979906 0.0424129102048911 0.0193469250989629 0.0265386921549758 -0.0415468195183205 0.998203784083941 -0.0431632624857332 0.00279348101653556 -0.0211428534201309 0.0423125334676623 0.99888068820095 0.0838110071411078 3.03203725294464e-05 1.41638324720215e-05 -4.31718172419879e-06 4.93025765748411e-06 2.6997965228286e-06 1.77381020229682e-05 1.41638324720215e-05 3.17253105152632e-05 -5.4977986641646e-06 5.78110129318161e-06 3.22696735982326e-06 2.84903182015633e-05 -4.31718172419879e-06 -5.4977986641646e-06 1.72048698995812e-05 2.09456728408911e-06 -1.204608476318e-06 -9.64379475905138e-06 4.93025765748411e-06 5.78110129318161e-06 2.09456728408911e-06 3.37968927123887e-05 -9.95571603867628e-06 3.85007518040639e-06 2.6997965228286e-06 3.22696735982326e-06 -1.204608476318e-06 -9.95571603867628e-06 4.72495476073962e-05 4.68982350354452e-06 1.77381020229682e-05 2.84903182015633e-05 -9.64379475905138e-06 3.85007518040639e-06 4.68982350354452e-06 9.29397575788354e-05 2704 2704 0 0 11 2683 2683 0 0 0 0 0 0 0 0 0 0 0 554 0 143 119 0 0 3339 +335 336 0.999734665364255 -0.0215239510123923 -0.00820477920712938 0.00607131328884454 0.0215718722734356 0.999750490017195 0.00579758889513062 0.00567996539698795 0.00807794501344171 -0.00597304304308086 0.999949533507149 0.00990328858173998 5.37549680308517e-05 3.18286926864749e-05 -1.25952495501881e-05 1.92162547449622e-05 1.47862920685511e-06 3.07976211031596e-05 3.18286926864749e-05 8.07612851581329e-05 -1.74211854059541e-05 3.86735200221403e-05 2.92356035448296e-06 6.20430707113847e-05 -1.25952495501881e-05 -1.74211854059541e-05 1.80678064879793e-05 -6.90087592084788e-06 -2.29697076040543e-07 -1.72271737649335e-05 1.92162547449622e-05 3.86735200221403e-05 -6.90087592084788e-06 6.12239260541492e-05 -1.49279884860592e-05 3.67318211984786e-05 1.47862920685511e-06 2.92356035448296e-06 -2.29697076040543e-07 -1.49279884860592e-05 4.69108701597776e-05 -3.87912812434973e-06 3.07976211031596e-05 6.20430707113847e-05 -1.72271737649335e-05 3.67318211984786e-05 -3.87912812434973e-06 9.75087218014894e-05 2661 2622 0 0 100 2625 2624 0 4 64 0 0 0 0 0 23 35 0 500 0 47 17 0 0 3337 +336 337 0.999536203463768 -0.028657540661029 -0.0103016177612033 0.0058357194323959 0.0286324058722783 0.999586681173072 -0.00257917726569208 -0.00294559281415257 0.0103712727859984 0.00228302095133008 0.999943610668189 0.0157235077560424 4.26150684689105e-05 9.11751217384807e-06 -1.09913503954982e-05 2.56722639727256e-06 7.01102488036004e-06 1.33448125511475e-05 9.11751217384807e-06 2.57070169932478e-05 -7.10385180445337e-06 3.42352665392224e-06 3.50132135218144e-06 5.17611269070978e-06 -1.09913503954982e-05 -7.10385180445337e-06 1.60841357500265e-05 4.53742074406425e-08 -3.81885910779872e-06 -6.18861693548116e-06 2.56722639727256e-06 3.42352665392224e-06 4.53742074406425e-08 3.35860428211165e-05 -7.56748023943096e-06 7.42769897068703e-06 7.01102488036004e-06 3.50132135218144e-06 -3.81885910779872e-06 -7.56748023943096e-06 4.61910735402442e-05 2.37540270166369e-06 1.33448125511475e-05 5.17611269070978e-06 -6.18861693548116e-06 7.42769897068703e-06 2.37540270166369e-06 3.73563592579322e-05 2001 1957 0 3 102 2015 1999 0 1 66 0 0 0 0 0 34 37 0 584 0 33 27 0 0 3284 +326 327 0.99789903187138 0.0615165712847736 -0.0203281491417004 0.038571956695896 -0.0610440549285917 0.997867714247938 0.0231008272464452 -0.0309064662062474 0.021705887404963 -0.0218113804918531 0.999526446940251 0.0777636200027094 2.17047355448801e-05 6.43446735686422e-06 -4.1164992790622e-06 6.05599156601351e-07 -2.73458838378378e-06 3.29186929743786e-06 6.43446735686422e-06 2.37652253959185e-05 -2.39825423498751e-06 1.56351488379238e-06 -7.90282793141099e-07 3.80049027891885e-06 -4.1164992790622e-06 -2.39825423498751e-06 1.58133829441469e-05 1.67238924210993e-07 3.09689100949993e-06 -3.51514271057522e-06 6.05599156601351e-07 1.56351488379238e-06 1.67238924210993e-07 2.38670072836618e-05 -6.65787862974493e-06 6.72921682966745e-06 -2.73458838378378e-06 -7.90282793141099e-07 3.09689100949993e-06 -6.65787862974493e-06 3.8085451649822e-05 -2.95029023079071e-06 3.29186929743786e-06 3.80049027891885e-06 -3.51514271057522e-06 6.72921682966745e-06 -2.95029023079071e-06 5.61861284367831e-05 919 919 0 0 0 868 868 0 0 0 0 0 0 0 0 0 0 0 1273 0 194 148 0 0 3124 +328 329 0.998884788274879 0.0467291622103211 -0.00675019645424558 0.0345311478234976 -0.0465895031353386 0.998722876372967 0.0195457004711834 -0.0322344678681415 0.00765492982669902 -0.019209414577973 0.999786177360399 0.0697206754667683 2.59180825099919e-05 1.2076476845375e-06 -2.86857343820908e-06 2.94122737355989e-06 2.2773760375236e-06 -6.25634445544678e-06 1.2076476845375e-06 3.15814896427415e-05 -4.52474181731901e-06 1.01895671977893e-05 2.30481553493088e-07 2.49502094661698e-05 -2.86857343820908e-06 -4.52474181731901e-06 1.52569047758508e-05 -7.48460080720035e-07 -8.31344204964046e-08 -1.42501551385158e-06 2.94122737355989e-06 1.01895671977893e-05 -7.48460080720035e-07 3.54660835971345e-05 -2.04646513400788e-06 1.72674665686339e-05 2.2773760375236e-06 2.30481553493088e-07 -8.31344204964046e-08 -2.04646513400788e-06 3.74086824429873e-05 6.30517347927118e-07 -6.25634445544678e-06 2.49502094661698e-05 -1.42501551385158e-06 1.72674665686339e-05 6.30517347927118e-07 9.26267626922448e-05 1925 1926 0 0 2 1897 1898 0 0 2 0 0 0 0 0 0 0 0 1013 0 147 116 0 0 3266 +338 339 0.999798183777556 0.0198287724641527 0.0032266852440925 0.00165378103297586 -0.0198028134191526 0.999772792520395 -0.00788745311598115 0.00509183499777294 -0.00338235063022918 0.00782196385413748 0.999963687633545 0.01120313793247 4.9108399698472e-05 8.24770958461436e-06 -1.18708576674907e-05 6.16447264842309e-06 5.95108484485037e-07 2.76934886984769e-05 8.24770958461436e-06 3.39060158162722e-05 -9.6123359739953e-06 5.69771296894264e-06 -1.74295270802821e-06 1.14125670467555e-05 -1.18708576674907e-05 -9.6123359739953e-06 1.84527874809789e-05 3.39384246098223e-07 7.84244238442692e-07 -1.00767075253143e-05 6.16447264842309e-06 5.69771296894264e-06 3.39384246098223e-07 3.32552636885875e-05 -9.19846049944288e-07 7.99397890694137e-06 5.95108484485037e-07 -1.74295270802821e-06 7.84244238442692e-07 -9.19846049944288e-07 3.15596092655036e-05 -1.49470867271167e-06 2.76934886984769e-05 1.14125670467555e-05 -1.00767075253143e-05 7.99397890694137e-06 -1.49470867271167e-06 5.54897431531276e-05 2029 1996 0 26 53 1975 1994 0 30 10 0 0 0 0 0 1 3 0 430 0 94 65 0 0 3314 +332 333 0.99962667514713 0.0222308251383004 -0.015883977712303 0.00812284624721766 -0.0229187959201998 0.998745121992992 -0.04452987860719 0.0117617388509676 0.0148741093132618 0.0448772961403999 0.998881769361752 0.0445851198897741 4.59356198874603e-05 2.45723566253674e-07 -5.40224262611553e-07 -1.74653534531224e-06 -2.68951950756118e-07 -4.27705245264746e-07 2.45723566253674e-07 3.4533361446659e-05 1.94437294848878e-06 7.65612546819688e-06 7.36937224389563e-06 1.26663792267733e-05 -5.40224262611553e-07 1.94437294848878e-06 1.35418150626405e-05 3.25496098891556e-06 2.14427268851043e-06 -1.90025790850625e-06 -1.74653534531224e-06 7.65612546819688e-06 3.25496098891556e-06 2.83253841592845e-05 -1.92830509377548e-06 2.39302568296322e-06 -2.68951950756118e-07 7.36937224389563e-06 2.14427268851043e-06 -1.92830509377548e-06 3.73897867299867e-05 3.47989570267724e-06 -4.27705245264746e-07 1.26663792267733e-05 -1.90025790850625e-06 2.39302568296322e-06 3.47989570267724e-06 4.07012821074828e-05 3042 3011 0 33 44 2998 2993 0 27 14 0 0 0 0 0 0 5 0 554 0 136 109 0 0 3254 +341 342 0.999992129651027 -0.000987580354901308 -0.00384256698662417 0.00855101614138399 0.000947553806779081 0.999945422452512 -0.0104045306501641 0.00285749599697204 0.00385263257881405 0.010400807723901 0.999938488318608 0.00221340824783987 0.00016452199769452 -0.000108541988092163 -1.47974231397869e-05 -4.27272841642114e-05 -4.44089001203734e-05 -6.69056429226464e-06 -0.000108541988092163 0.00101496097482229 -9.32912254525494e-05 0.000482763355491184 0.000124203696254257 0.000562923696053182 -1.47974231397869e-05 -9.32912254525494e-05 2.77724028881202e-05 -4.31613034297472e-05 -5.52214524576139e-06 -6.14410768065386e-05 -4.27272841642114e-05 0.000482763355491184 -4.31613034297472e-05 0.000275148107242223 5.35802005742305e-05 0.00028772090227593 -4.44089001203734e-05 0.000124203696254257 -5.52214524576139e-06 5.35802005742305e-05 7.04347212776804e-05 5.50578044257548e-05 -6.69056429226464e-06 0.000562923696053182 -6.14410768065386e-05 0.00028772090227593 5.50578044257548e-05 0.000403822490436251 1430 1381 0 2 77 1391 1405 0 12 24 0 0 0 0 0 2 9 0 339 0 64 36 0 0 3257 +333 334 0.999725657114772 -0.000205943182246052 -0.0234215305615161 0.0150255770520253 0.000113271364622292 0.999992160864646 -0.00395795134552737 0.00579065129450778 0.0234221620700631 0.0039542125210074 0.999717843457494 0.0309114746686526 5.58781496662484e-05 3.59402782602069e-06 -4.10138700685246e-06 -1.40697352552861e-07 -4.09745278388113e-06 -1.97367014703313e-07 3.59402782602069e-06 4.03591412829083e-05 -6.33939292037404e-06 7.15471294401644e-06 6.99309610661135e-06 2.38378561116568e-05 -4.10138700685246e-06 -6.33939292037404e-06 1.59299323594695e-05 2.86662220732843e-06 1.21727029584701e-06 -4.27354835239976e-06 -1.40697352552861e-07 7.15471294401644e-06 2.86662220732843e-06 3.91657808868389e-05 -7.22559057142605e-06 5.27514430675416e-06 -4.09745278388113e-06 6.99309610661135e-06 1.21727029584701e-06 -7.22559057142605e-06 4.56719495167652e-05 3.3353295272516e-06 -1.97367014703313e-07 2.38378561116568e-05 -4.27354835239976e-06 5.27514430675416e-06 3.3353295272516e-06 5.31577966430091e-05 2448 2392 0 8 87 2400 2410 0 19 55 0 0 0 0 0 22 27 0 544 0 64 28 0 0 3201 +339 340 0.999209268745109 0.0364053832984058 0.0159839081816585 0.0100499586282306 -0.036350245040518 0.999332162362373 -0.00372678864945858 -0.000363863003832915 -0.0161089086954341 0.00314282278208466 0.999865303791267 0.00173255396448268 7.81373607886364e-05 7.10124028819866e-06 -1.13833214927508e-05 8.50280741642003e-06 -9.05159802085401e-06 3.61915775411136e-05 7.10124028819866e-06 5.91234099016349e-05 -9.87106004681946e-06 1.79526157134811e-05 1.22621679056094e-06 2.93730936180628e-05 -1.13833214927508e-05 -9.87106004681946e-06 1.90686853634602e-05 -7.45455352887541e-07 5.45903789133316e-06 -1.26571291646361e-05 8.50280741642003e-06 1.79526157134811e-05 -7.45455352887541e-07 3.70031258297694e-05 -6.17838145802791e-07 1.92414665551433e-05 -9.05159802085401e-06 1.22621679056094e-06 5.45903789133316e-06 -6.17838145802791e-07 3.45737999520049e-05 -1.82789384194305e-06 3.61915775411136e-05 2.93730936180628e-05 -1.26571291646361e-05 1.92414665551433e-05 -1.82789384194305e-06 7.70541463349278e-05 1978 1970 0 32 5 1949 1944 0 36 5 0 0 0 0 0 0 2 0 363 0 116 97 0 0 3274 +334 335 0.999853925605978 -0.00947532931360236 -0.0142248228359663 0.0122640912200142 0.00968815673883584 0.999841035264573 0.0149680934013278 0.00442593966552406 0.0140807339765933 -0.0151037192593716 0.99978678256677 0.00878835844879948 4.24878917943918e-05 2.77045879799189e-06 -4.9222354302174e-06 -4.36533126462677e-07 2.05869244446735e-06 -6.67186850356901e-06 2.77045879799189e-06 3.62751399028382e-05 -6.63142244147936e-06 9.88768316584383e-06 1.14465969839383e-05 3.18874623395464e-05 -4.9222354302174e-06 -6.63142244147936e-06 1.4616936057265e-05 -7.963237871299e-07 -2.31567547740549e-07 -5.2260548789098e-06 -4.36533126462677e-07 9.88768316584383e-06 -7.963237871299e-07 3.31839099457702e-05 2.85062671172573e-06 7.05347982520515e-06 2.05869244446735e-06 1.14465969839383e-05 -2.31567547740549e-07 2.85062671172573e-06 3.42191983704733e-05 1.27065596922742e-05 -6.67186850356901e-06 3.18874623395464e-05 -5.2260548789098e-06 7.05347982520515e-06 1.27065596922742e-05 6.23790585764145e-05 2770 2710 0 10 80 2721 2729 0 19 51 0 0 0 0 0 6 18 0 571 0 105 71 0 0 3365 +337 338 0.999885431520882 0.000791722883501939 -0.01511611746369 0.00145158251538643 -0.00123310901995922 0.999572455948623 -0.0292127498018042 0.00136548547915423 0.0150865262550804 0.0292280427622798 0.999458912733205 0.0174620372452094 3.37209064484895e-05 1.08877621141079e-05 -3.2660021122064e-06 2.45175493451315e-06 1.80478354876509e-06 1.67118718827016e-05 1.08877621141079e-05 2.47447085939014e-05 -5.22319297567546e-06 1.06752043915995e-06 5.07043699531955e-06 6.54647824929245e-06 -3.2660021122064e-06 -5.22319297567546e-06 1.53146870786331e-05 1.59264812978855e-06 2.19669303640964e-07 -5.46105752484175e-06 2.45175493451315e-06 1.06752043915995e-06 1.59264812978855e-06 3.28242608190888e-05 -6.10391033532041e-06 -2.22008014679835e-06 1.80478354876509e-06 5.07043699531955e-06 2.19669303640964e-07 -6.10391033532041e-06 3.69494214068872e-05 -1.13704070039852e-06 1.67118718827016e-05 6.54647824929245e-06 -5.46105752484175e-06 -2.22008014679835e-06 -1.13704070039852e-06 4.58065250157492e-05 1505 1456 0 10 59 1440 1457 0 16 19 0 0 0 0 0 5 14 0 510 0 74 52 0 0 3336 +343 344 0.999922395089071 0.0122908963390774 0.00203412549209019 -0.00371021897393711 -0.0123003672578744 0.999913250387417 0.0047109091472074 -0.00143008752366514 -0.00197604773650067 -0.00473556404812395 0.999986834747583 0.0042899735646691 7.05231831899507e-05 2.4603622515263e-05 -1.44096134818906e-05 1.61774530615632e-05 -1.0555217666574e-05 2.8429112715632e-05 2.4603622515263e-05 3.73269259386575e-05 -1.08623613467552e-05 8.57732256002426e-06 9.41560010027421e-07 1.70949330725765e-05 -1.44096134818906e-05 -1.08623613467552e-05 1.79475803061277e-05 9.26325147650525e-07 1.91826248203578e-06 -1.08239950332318e-05 1.61774530615632e-05 8.57732256002426e-06 9.26325147650525e-07 3.91544840743366e-05 -1.36912101152631e-05 1.94746986885146e-05 -1.0555217666574e-05 9.41560010027421e-07 1.91826248203578e-06 -1.36912101152631e-05 4.40545344836907e-05 -5.84269414023141e-06 2.8429112715632e-05 1.70949330725765e-05 -1.08239950332318e-05 1.94746986885146e-05 -5.84269414023141e-06 6.43516612324578e-05 2173 2147 0 13 58 2126 2131 0 25 12 0 0 0 0 0 1 9 0 307 0 116 92 0 0 3302 +358 359 0.97053091409889 0.240976647786403 4.28540257198597e-10 0.128136275242889 -0.235697545790638 0.949269385972226 0.208168921225489 -0.255897026819834 0.05016384840343 -0.20203437350496 0.978092889369827 0.0541142868067595 0.905321288284095 5.76644282284837e-10 1.17261854989582 -0.00485785053484519 0.866905218064825 -0.000458861881116885 5.76644282284837e-10 3.6729350407968e-19 7.46899239915334e-10 -3.09420729564659e-12 5.52175171123449e-10 -2.92272018264397e-13 1.17261854989582 7.46899239915334e-10 1.5188356679052 -0.00629213708271182 1.12286008609277 -0.00059434143502533 -0.00485785053484519 -3.09420729564659e-12 -0.00629213708271182 2.60666706110751e-05 -0.00465171429384832 2.46220039609212e-06 0.866905218064825 5.52175171123449e-10 1.12286008609277 -0.00465171429384832 0.830119281224931 -0.000439390705000677 -0.000458861881116885 -2.92272018264397e-13 -0.00059434143502533 2.46220039609212e-06 -0.000439390705000677 2.32574036054318e-07 832 826 0 16 0 852 846 0 16 0 0 0 0 0 0 0 0 0 7 0 215 222 0 0 496 +345 346 0.999988094099465 -0.0048796932615954 -1.5905736851365e-05 -0.00575879476970349 0.00487948276308372 0.999966418750432 -0.00658422504179422 -0.000383372479725438 4.80342012861172e-05 0.00658406903889697 0.999978323628871 0.00302676191489708 4.46173474204399e-05 1.93655343494974e-05 -1.45169544749776e-05 7.34183121465827e-06 3.40000772082317e-06 2.68614394924763e-05 1.93655343494974e-05 3.64898847365007e-05 -1.39218675591439e-05 1.33569546749518e-05 2.42351482354783e-06 1.49591931554842e-05 -1.45169544749776e-05 -1.39218675591439e-05 2.55755643643713e-05 3.95853259889751e-06 -1.21598314383465e-06 -8.2995068233617e-06 7.34183121465827e-06 1.33569546749518e-05 3.95853259889751e-06 4.0714693519148e-05 -3.13088028872885e-06 1.23235100933743e-05 3.40000772082317e-06 2.42351482354783e-06 -1.21598314383465e-06 -3.13088028872885e-06 3.27059717886936e-05 1.75553542203331e-06 2.68614394924763e-05 1.49591931554842e-05 -8.2995068233617e-06 1.23235100933743e-05 1.75553542203331e-06 5.44004412507405e-05 1586 1547 0 7 69 1572 1572 0 11 33 0 0 0 0 0 7 17 0 345 0 90 57 0 0 3221 +340 341 0.999842296498107 0.017677397902468 0.00170051074378152 0.0098732608310516 -0.0176974503815434 0.999763931740383 0.0126048022992408 -0.00396861726834959 -0.00147728920144415 -0.0126329091822889 0.999919110339535 0.00314875114473167 6.32230453114839e-05 1.32436249664317e-05 -1.26546518512335e-05 4.50332935955096e-06 4.395571063269e-06 2.02154933283633e-05 1.32436249664317e-05 5.60959444889537e-05 -9.18800485412066e-06 7.50773717778743e-06 1.52648689402605e-05 2.634662413284e-05 -1.26546518512335e-05 -9.18800485412066e-06 1.79492007100926e-05 -4.97215058615323e-08 -4.26563260779396e-07 -1.04407795867718e-05 4.50332935955096e-06 7.50773717778743e-06 -4.97215058615323e-08 3.19133167135122e-05 -4.62718316992257e-07 1.2420018934183e-05 4.395571063269e-06 1.52648689402605e-05 -4.26563260779396e-07 -4.62718316992257e-07 3.77528415386769e-05 1.47675477855206e-05 2.02154933283633e-05 2.634662413284e-05 -1.04407795867718e-05 1.2420018934183e-05 1.47675477855206e-05 6.24108686498544e-05 2206 2194 0 20 40 2188 2209 0 25 5 0 0 0 0 0 0 1 0 332 0 90 58 0 0 3271 +342 343 0.999963479000969 -0.00557663190784906 -0.00647625206764054 6.3805750472519e-05 0.00556867790500797 0.999983719066338 -0.00124556358570692 -0.000552048521715149 0.00648309267784555 0.00120945393468408 0.999978253128792 0.000887648434580061 4.69015680093148e-05 1.58430789308508e-05 -1.41181618662881e-05 1.58560672835374e-05 1.0493019405515e-06 1.3512521655855e-05 1.58430789308508e-05 4.10406784777364e-05 -1.23141827364167e-05 1.11647782797138e-05 1.28760225903621e-05 1.43982892915879e-05 -1.41181618662881e-05 -1.23141827364167e-05 1.79769940757432e-05 -3.56898592699693e-06 -5.24954384640505e-06 -1.05905179305194e-05 1.58560672835374e-05 1.11647782797138e-05 -3.56898592699693e-06 4.13770470137916e-05 -7.38672491009526e-06 1.28860846056163e-05 1.0493019405515e-06 1.28760225903621e-05 -5.24954384640505e-06 -7.38672491009526e-06 4.96327922096911e-05 9.77533536952628e-06 1.3512521655855e-05 1.43982892915879e-05 -1.05905179305194e-05 1.28860846056163e-05 9.77533536952628e-06 6.44655750155736e-05 2005 1968 0 1 74 1981 1993 0 9 54 0 0 0 0 0 6 13 0 340 0 61 26 0 0 3253 +351 352 0.999988900683911 0.00236144604749733 0.00407701870835188 -0.00157428142415394 -0.00232605779160679 0.999959770430254 -0.00866296578683614 -0.00256756057408909 -0.00409731181796033 0.00865338625270751 0.999954164420664 -0.000590909504134653 8.53605763326921e-05 6.57459073562384e-05 -2.19852364049702e-05 2.19839704768573e-05 6.07294668143931e-06 6.60041167686843e-05 6.57459073562384e-05 0.000126356204925811 -2.72656006844381e-05 4.89152683523933e-05 -1.62167596761642e-06 7.5619202616237e-05 -2.19852364049702e-05 -2.72656006844381e-05 1.90680743573275e-05 -4.69214905056001e-06 -1.39148762370077e-06 -2.01013368328219e-05 2.19839704768573e-05 4.89152683523933e-05 -4.69214905056001e-06 6.15159092128705e-05 -1.85933132905954e-05 4.00496078338074e-05 6.07294668143931e-06 -1.62167596761642e-06 -1.39148762370077e-06 -1.85933132905954e-05 4.25996042686182e-05 -1.79267195418135e-06 6.60041167686843e-05 7.5619202616237e-05 -2.01013368328219e-05 4.00496078338074e-05 -1.79267195418135e-06 0.000107674249036233 1429 1409 0 7 32 1448 1448 0 15 32 0 0 0 0 0 7 17 0 283 0 90 90 0 0 3325 +349 350 0.999965652488669 0.00199761783486569 0.00804384024556944 -0.00140301755617816 -0.00193917869429905 0.999971719567279 -0.00726633687985411 -1.92829236522778e-06 -0.0080581281264319 0.00725048885564124 0.999941246765255 -0.00173922876304257 5.85846841138884e-05 4.11304391105099e-05 -1.56500572223408e-05 2.18777041006225e-05 -1.13817182893357e-05 2.46127715234956e-05 4.11304391105099e-05 5.45059247488603e-05 -1.64014177317931e-05 2.4986509691534e-05 -9.7237525475729e-06 3.07092699503981e-05 -1.56500572223408e-05 -1.64014177317931e-05 1.82020788926875e-05 -6.17929295503068e-06 -3.45535175160734e-07 -9.1797101906702e-06 2.18777041006225e-05 2.4986509691534e-05 -6.17929295503068e-06 6.06902868033487e-05 -3.29906193333666e-05 3.76944060284701e-05 -1.13817182893357e-05 -9.7237525475729e-06 -3.45535175160734e-07 -3.29906193333666e-05 5.50358006838686e-05 -1.05753527830545e-05 2.46127715234956e-05 3.07092699503981e-05 -9.1797101906702e-06 3.76944060284701e-05 -1.05753527830545e-05 7.47651957036621e-05 1768 1743 0 4 61 1730 1744 0 19 22 0 0 0 0 0 4 14 0 305 0 70 41 0 0 3364 +344 345 0.999982962601545 0.00463328456868376 -0.00355065919831667 -0.00502052722412046 -0.00462917175321488 0.999988605927689 0.00116566876795859 -0.00094468826558416 0.0035560196169638 -0.00114921229672919 0.999993016993409 0.00561204436031243 5.44744696835628e-05 -7.03585586324963e-07 -6.50512343770446e-06 5.26873861792099e-07 -2.01502873872373e-07 1.87430678852492e-05 -7.03585586324963e-07 3.18530057458139e-05 -4.74974954702126e-06 3.11060296613854e-06 6.16816059194297e-06 -1.14141132952803e-06 -6.50512343770446e-06 -4.74974954702126e-06 1.85863807082772e-05 5.24436753816351e-06 2.58564060083796e-06 -6.80256019310031e-06 5.26873861792099e-07 3.11060296613854e-06 5.24436753816351e-06 2.71577191593959e-05 -1.94893070003958e-06 9.00957657097757e-06 -2.01502873872373e-07 6.16816059194297e-06 2.58564060083796e-06 -1.94893070003958e-06 2.9449425995136e-05 7.05284319247188e-07 1.87430678852492e-05 -1.14141132952803e-06 -6.80256019310031e-06 9.00957657097757e-06 7.05284319247188e-07 4.89914824070735e-05 1929 1901 0 7 56 1893 1901 0 13 26 0 0 0 0 0 2 9 0 289 0 78 56 0 0 3178 +346 347 0.99996985678829 0.00104969834386647 0.00769309093887073 0.00212126934679836 -0.00106107670250087 0.999998349091209 0.00147510375492839 0.0065214289109781 -0.00769152982431069 -0.00148322225012907 0.99996931973972 -3.48953921202948e-05 3.72095779684591e-05 3.7284620837733e-06 -3.94944233506354e-06 1.22998712644676e-05 -2.51887446429888e-06 5.4430094371293e-06 3.7284620837733e-06 3.84058670687985e-05 -1.22619693256173e-05 9.77772798379609e-06 1.1952919246109e-05 1.3530774730203e-05 -3.94944233506354e-06 -1.22619693256173e-05 2.11313044457732e-05 2.10434393727548e-06 -5.13670541148786e-06 -1.08020084911473e-05 1.22998712644676e-05 9.77772798379609e-06 2.10434393727548e-06 3.77315725169622e-05 -4.33836172044752e-06 5.5098124572127e-06 -2.51887446429888e-06 1.1952919246109e-05 -5.13670541148786e-06 -4.33836172044752e-06 4.39993785359403e-05 1.21070848891075e-05 5.4430094371293e-06 1.3530774730203e-05 -1.08020084911473e-05 5.5098124572127e-06 1.21070848891075e-05 4.61592949726386e-05 1905 1871 0 3 66 1876 1895 0 16 33 0 0 0 0 0 5 15 0 325 0 59 28 0 0 3309 +348 349 0.999921286628979 0.000854100826078023 0.0125176298885001 0.000435319049240401 -0.00086179622776402 0.999999442979086 0.000609383934478475 0.00564161924442166 -0.0125171024405966 -0.000620123614033202 0.99992146571278 -1.08710349162294e-05 6.36760863771683e-05 2.60479884273135e-05 -1.5911514778699e-05 1.2356021357898e-05 -8.92248978499778e-06 2.84633780975997e-05 2.60479884273135e-05 8.2456906223047e-05 -1.68971753230464e-05 2.46806389151417e-05 5.74017524937835e-06 2.66232672055382e-05 -1.5911514778699e-05 -1.68971753230464e-05 2.14334510315841e-05 -3.53485063010018e-06 -4.39426988043426e-06 -1.0070499241292e-05 1.2356021357898e-05 2.46806389151417e-05 -3.53485063010018e-06 4.84407680689015e-05 -1.00206925179806e-05 2.26685083524581e-05 -8.92248978499778e-06 5.74017524937835e-06 -4.39426988043426e-06 -1.00206925179806e-05 3.93046984661888e-05 -5.93200788706318e-06 2.84633780975997e-05 2.66232672055382e-05 -1.0070499241292e-05 2.26685083524581e-05 -5.93200788706318e-06 6.41591864045181e-05 1872 1839 0 5 64 1826 1838 0 17 20 0 0 0 0 0 8 19 0 311 0 64 38 0 0 3276 +354 355 0.999987359879729 0.000488489344586959 0.00500414417549064 -0.00364361398252829 -0.000488557661127338 0.999999880578451 1.24295877088058e-05 0.00511750439655965 -0.00500413750616685 -1.48742435716439e-05 0.999987479114902 0.00277103808423369 5.47821886884586e-05 2.26627361762894e-05 -9.83934303890574e-06 7.76448404640203e-06 9.01666926535369e-08 2.00607317325486e-05 2.26627361762894e-05 6.51913945497932e-05 -1.24664346362126e-05 2.00687094987659e-05 6.94991851002848e-06 2.82505435871287e-05 -9.83934303890574e-06 -1.24664346362126e-05 1.42925047491373e-05 -2.40162103606634e-07 2.00865080239731e-06 -7.60197424950222e-06 7.76448404640203e-06 2.00687094987659e-05 -2.40162103606634e-07 4.26547930605079e-05 -9.0680164843166e-06 2.01030838993712e-05 9.01666926535369e-08 6.94991851002848e-06 2.00865080239731e-06 -9.0680164843166e-06 4.13641327810939e-05 3.90812724436124e-06 2.00607317325486e-05 2.82505435871287e-05 -7.60197424950222e-06 2.01030838993712e-05 3.90812724436124e-06 7.14332252229039e-05 1903 1886 0 4 37 1890 1906 0 16 19 0 0 0 0 0 4 17 0 286 0 59 49 0 0 3256 +350 351 0.999966383538627 0.00279355095370227 0.00770894712323023 -0.00126390752061371 -0.00275384008784882 0.999982910271093 -0.00515708546814453 0.00283010769305871 -0.00772322196044159 0.00513568289755704 0.99995698737682 -0.004810729985289 4.63577473829154e-05 1.07099629519666e-05 -9.42610570391871e-06 7.26492108084092e-06 -7.91578362958675e-06 1.32498230646536e-05 1.07099629519666e-05 4.790003512976e-05 -7.93136139396352e-06 2.05949378644577e-05 -1.48447962990779e-07 1.23169912121818e-05 -9.42610570391871e-06 -7.93136139396352e-06 1.48340480620985e-05 9.14745008377561e-07 -1.28361000955157e-06 -6.49193487997365e-06 7.26492108084092e-06 2.05949378644577e-05 9.14745008377561e-07 5.25200711632091e-05 -2.86814609823325e-05 1.96682459634405e-05 -7.91578362958675e-06 -1.48447962990779e-07 -1.28361000955157e-06 -2.86814609823325e-05 5.95538289877837e-05 -4.09179597365368e-06 1.32498230646536e-05 1.23169912121818e-05 -6.49193487997365e-06 1.96682459634405e-05 -4.09179597365368e-06 6.29262481495795e-05 2314 2316 0 3 29 2309 2328 0 15 31 0 0 0 0 0 9 16 0 292 0 36 42 0 0 3359 +347 348 0.999974776015297 0.00273062680687283 0.00655675303778001 0.0030845781950085 -0.00269039541368824 0.999977550036151 -0.00613687185904341 0.00377617310130774 -0.00657336334571999 0.00611907680437998 0.999959673083563 0.00377905001501403 6.09259609273029e-05 6.11018569515082e-06 -1.16341227047256e-05 -3.08483611252426e-06 -1.81552345185169e-06 1.01385999491215e-05 6.11018569515082e-06 9.65957279661727e-05 -1.62496623436082e-05 2.83662477654457e-05 1.2952129365478e-05 3.25565640773067e-05 -1.16341227047256e-05 -1.62496623436082e-05 1.96074655476251e-05 -3.81467702186243e-06 -4.53312077228641e-06 -9.39451713511144e-06 -3.08483611252426e-06 2.83662477654457e-05 -3.81467702186243e-06 4.24792505184689e-05 -5.12972317157903e-06 1.91194643337648e-05 -1.81552345185169e-06 1.2952129365478e-05 -4.53312077228641e-06 -5.12972317157903e-06 4.15314413887313e-05 7.07361304085428e-06 1.01385999491215e-05 3.25565640773067e-05 -9.39451713511144e-06 1.91194643337648e-05 7.07361304085428e-06 6.58628826682651e-05 1463 1449 0 3 58 1425 1448 0 17 14 0 0 0 0 0 4 14 0 308 0 70 44 0 0 3261 +353 354 0.999996418449219 0.00081604752362115 -0.0025489517793052 -0.0013280929751406 -0.000829715235043385 0.999985260609971 -0.00536564399089862 -0.00336321784329722 0.00254453558881936 0.00536773967769688 0.999982356199043 0.000745049875000822 5.27719307227529e-05 5.39953120909984e-05 -1.77678885110813e-05 2.35096974581302e-05 8.41555741091378e-06 4.17996987744192e-05 5.39953120909984e-05 0.000161991387660551 -3.34665639798356e-05 6.69159270835877e-05 2.22830544059863e-05 0.000101306446988509 -1.77678885110813e-05 -3.34665639798356e-05 1.97308516047358e-05 -1.06925659673556e-05 -7.44872526291006e-06 -2.30831729802442e-05 2.35096974581302e-05 6.69159270835877e-05 -1.06925659673556e-05 6.33043204221339e-05 -2.17638111057641e-06 5.26873415407713e-05 8.41555741091378e-06 2.22830544059863e-05 -7.44872526291006e-06 -2.17638111057641e-06 4.54984471754288e-05 1.33685184316648e-05 4.17996987744192e-05 0.000101306446988509 -2.30831729802442e-05 5.26873415407713e-05 1.33685184316648e-05 0.000113996943648275 1809 1782 0 6 53 1810 1815 0 13 25 0 0 0 0 0 6 15 0 318 0 91 70 0 0 3376 +352 353 0.999999346575763 0.000412762007333232 0.00106605608331015 -0.00171476998310539 -0.000411599986233386 0.999999321233549 -0.00109000820730079 0.00037033965881628 -0.00106650527368271 0.00108956870639379 0.999998837702592 -0.000472860785201098 4.07169778145222e-05 1.88463434797824e-05 -1.00839470755661e-05 1.67507287597343e-05 1.1934504826632e-07 1.84093019608712e-05 1.88463434797824e-05 4.77662689321851e-05 -1.24899522282395e-05 1.67982394252531e-05 1.02874966107672e-05 1.85419173550365e-05 -1.00839470755661e-05 -1.24899522282395e-05 1.58662973426151e-05 -2.13232880810981e-06 -2.85398643780218e-06 -9.2649295000168e-06 1.67507287597343e-05 1.67982394252531e-05 -2.13232880810981e-06 4.35640269778891e-05 -9.63177641335428e-06 2.25695787578336e-05 1.1934504826632e-07 1.02874966107672e-05 -2.85398643780218e-06 -9.63177641335428e-06 5.34882118022251e-05 2.03560490101776e-06 1.84093019608712e-05 1.85419173550365e-05 -9.2649295000168e-06 2.25695787578336e-05 2.03560490101776e-06 5.88059401255935e-05 2025 2004 0 7 42 1998 2024 0 20 18 0 0 0 0 0 2 13 0 297 0 50 29 0 0 3388 +363 364 0.999737140410722 9.54354613568824e-05 0.0229268614394881 -0.0124772931237014 -0.00128678763341518 0.998648648288968 0.0519540320687734 0.00335526838933578 -0.0228909209290334 -0.0519698774550158 0.998386266720617 -0.00347558281791883 7.53149120848352e-05 2.35828817568735e-05 -7.06734082803228e-06 4.31188689643238e-06 -1.03953155779202e-05 2.74296571007675e-05 2.35828817568735e-05 5.43011282313147e-05 -4.3521143328978e-06 1.4158115891523e-05 1.15265607697837e-06 3.28176463508869e-05 -7.06734082803228e-06 -4.3521143328978e-06 1.37207708904351e-05 2.96267060402804e-06 -2.1886292009355e-07 -4.14377700127409e-06 4.31188689643238e-06 1.4158115891523e-05 2.96267060402804e-06 3.55598164718789e-05 -1.13468907748933e-05 1.61667224951624e-05 -1.03953155779202e-05 1.15265607697837e-06 -2.1886292009355e-07 -1.13468907748933e-05 5.09653560904825e-05 -1.00912139540983e-05 2.74296571007675e-05 3.28176463508869e-05 -4.14377700127409e-06 1.61667224951624e-05 -1.00912139540983e-05 8.06838218741075e-05 2591 2566 0 11 50 2609 2636 0 33 27 0 0 0 0 0 10 29 0 511 0 76 49 0 0 3002 +356 357 0.99995891866959 0.00203637745009143 0.00883256135135676 -0.00637326746909971 -0.00207706597832472 0.999987263153568 0.00459992690797057 -0.00227555514095704 -0.00882308166495177 -0.00461808374953777 0.999950412036725 -0.00293097012377719 4.77035337084047e-05 3.54430321459244e-05 -9.10358974593343e-06 6.89887007381107e-06 9.10130081954761e-06 1.89733296481601e-05 3.54430321459244e-05 8.90284558059302e-05 -1.34016788572676e-05 2.42940765437519e-05 8.16969676518979e-06 4.10363152443265e-05 -9.10358974593343e-06 -1.34016788572676e-05 1.30301651212688e-05 -1.94353892039483e-07 -3.33685568858368e-07 -6.15201704971748e-06 6.89887007381107e-06 2.42940765437519e-05 -1.94353892039483e-07 4.83015800588435e-05 -6.15659090152584e-06 2.10569534140929e-05 9.10130081954761e-06 8.16969676518979e-06 -3.33685568858368e-07 -6.15659090152584e-06 3.69107947263579e-05 4.09417561168681e-06 1.89733296481601e-05 4.10363152443265e-05 -6.15201704971748e-06 2.10569534140929e-05 4.09417561168681e-06 6.82482603346046e-05 1888 1875 0 7 50 1857 1879 0 19 24 0 0 0 0 0 7 18 0 301 0 71 40 0 0 3282 +355 356 0.999829381672701 0.000441188805783038 0.0184665344995413 -0.00376019516180298 -0.000355370950178876 0.999989124462597 -0.00465023311428715 0.0048462309224439 -0.0184683852968489 0.00464287722938002 0.999818664776548 0.00437622373216941 5.45946503903043e-05 9.85985170459251e-06 -9.4259241212192e-06 7.81004514139128e-06 4.55971778844935e-06 1.93344124942361e-05 9.85985170459251e-06 5.48232975491464e-05 -9.83746647685749e-06 1.83999317957413e-05 5.74672475639407e-06 1.57590264011671e-05 -9.4259241212192e-06 -9.83746647685749e-06 1.64943664112154e-05 -1.41266225354946e-07 -1.49593339605739e-06 -7.30305047006761e-06 7.81004514139128e-06 1.83999317957413e-05 -1.41266225354946e-07 3.81462609791238e-05 -1.80931724548507e-06 2.0057259185483e-05 4.55971778844935e-06 5.74672475639407e-06 -1.49593339605739e-06 -1.80931724548507e-06 3.65422974210323e-05 3.0466188052985e-06 1.93344124942361e-05 1.57590264011671e-05 -7.30305047006761e-06 2.0057259185483e-05 3.0466188052985e-06 7.02508298527965e-05 2053 2038 0 1 31 2048 2069 0 19 5 0 0 0 0 0 8 23 0 269 0 44 38 0 0 3246 +357 358 0.999989790579188 -0.0013905925069853 -0.00429941738748586 0.000636374693657337 0.00140046693095253 0.999996386901334 0.0022945319027743 -0.00166273741253609 0.0042962110943956 -0.00230052966880608 0.99998812499623 -0.00688698750559582 4.67092426164735e-05 3.11053672475757e-05 -8.36507036023853e-06 4.33487902957149e-06 1.59917907597009e-05 2.75086361266197e-05 3.11053672475757e-05 6.09237677688335e-05 -1.15654801936836e-05 -1.70965272776671e-05 5.6667278147685e-05 3.68759672566764e-05 -8.36507036023853e-06 -1.15654801936836e-05 1.41736224094321e-05 9.19490296124605e-06 -1.4201239074529e-05 -7.98539023351383e-06 4.33487902957149e-06 -1.70965272776671e-05 9.19490296124605e-06 0.000289913597822164 -0.000330361271523662 9.12742048592171e-06 1.59917907597009e-05 5.6667278147685e-05 -1.4201239074529e-05 -0.000330361271523662 0.000462260312148326 1.54284567925036e-05 2.75086361266197e-05 3.68759672566764e-05 -7.98539023351383e-06 9.12742048592171e-06 1.54284567925036e-05 7.35033156915459e-05 2286 2251 0 8 70 2276 2290 0 22 37 0 0 0 0 0 8 22 0 333 0 89 60 0 0 3347 +366 367 0.99998468122809 -0.000253639969216509 0.00552928349073518 -0.00298212738308859 0.000228829124600182 0.999989905645611 0.00448734265612011 0.00606734367273576 -0.00553036584564127 -0.00448600865444063 0.999974645068547 -0.00461513706836495 2.68617752436445e-05 8.96347908695951e-06 -8.74966472329821e-07 -2.35635501332827e-07 -2.63798258896498e-06 1.20565534638151e-05 8.96347908695951e-06 3.77662157112512e-05 1.25376269908575e-06 4.16932195072666e-06 3.3381623393378e-06 1.43688260142443e-05 -8.74966472329821e-07 1.25376269908575e-06 1.28475375517371e-05 4.19800337311188e-06 1.0766439097958e-06 -2.96559585831704e-06 -2.35635501332827e-07 4.16932195072666e-06 4.19800337311188e-06 2.2990032414729e-05 -2.39555109631812e-06 6.28913781023911e-06 -2.63798258896498e-06 3.3381623393378e-06 1.0766439097958e-06 -2.39555109631812e-06 3.38154921925089e-05 -3.90989715760593e-06 1.20565534638151e-05 1.43688260142443e-05 -2.96559585831704e-06 6.28913781023911e-06 -3.90989715760593e-06 4.55870775205559e-05 3029 3006 0 22 64 3000 3046 0 38 33 0 0 0 0 0 22 51 0 595 0 59 33 0 0 2729 +359 360 0.999864259694073 0.00278721191303853 0.016238646377569 -0.00994446614781802 -0.00285369694472633 0.999987635440797 0.00407251510381793 0.00475654957551375 -0.0162270946312511 -0.004118302474926 0.99985985067136 0.0036445241738883 5.53834489944589e-05 3.02879698871428e-05 -7.05739999972655e-06 8.29981287054882e-06 8.28538459192218e-06 3.1892432382813e-05 3.02879698871428e-05 7.34404240285314e-05 -1.22599007605891e-05 1.41814679295025e-05 1.09225071199165e-05 2.90827937897405e-05 -7.05739999972655e-06 -1.22599007605891e-05 1.46048226208408e-05 1.1052782640498e-06 1.68713377959757e-06 -8.59197867882088e-06 8.29981287054882e-06 1.41814679295025e-05 1.1052782640498e-06 3.65772570409745e-05 -1.39058259440815e-06 1.8802685576626e-05 8.28538459192218e-06 1.09225071199165e-05 1.68713377959757e-06 -1.39058259440815e-06 3.18485483536225e-05 3.75354880710504e-06 3.1892432382813e-05 2.90827937897405e-05 -8.59197867882088e-06 1.8802685576626e-05 3.75354880710504e-06 7.692868512414e-05 2114 2086 0 3 63 2072 2090 0 22 24 0 0 0 0 0 12 26 0 302 0 78 48 0 0 3346 +360 361 0.999876625732496 0.00110071843413748 0.0156691331198398 -0.00757313757294164 -0.00143830315653918 0.999766745162156 0.021549629971274 0.00976911318569982 -0.0156417581437765 -0.0215695082650878 0.999644982839095 -0.00323123486884108 4.25125483640739e-05 2.14586706192853e-05 -3.66182885067556e-06 1.11956598458917e-05 -3.84193477052545e-06 1.4973034947128e-05 2.14586706192853e-05 0.000105793539341565 -8.71530427642983e-06 3.35175460341113e-05 9.89944644294554e-06 5.60357730826281e-05 -3.66182885067556e-06 -8.71530427642983e-06 1.30944464681482e-05 1.25094071778315e-06 1.2905432751041e-06 -6.38240797874556e-06 1.11956598458917e-05 3.35175460341113e-05 1.25094071778315e-06 5.38664145829203e-05 -1.02896473654692e-05 3.01026129672833e-05 -3.84193477052545e-06 9.89944644294554e-06 1.2905432751041e-06 -1.02896473654692e-05 4.65819999548929e-05 -9.0801340596975e-06 1.4973034947128e-05 5.60357730826281e-05 -6.38240797874556e-06 3.01026129672833e-05 -9.0801340596975e-06 9.20539847274716e-05 2023 1994 0 10 65 2012 2029 0 26 37 0 0 0 0 0 6 19 0 349 0 99 68 0 0 3348 +361 362 0.999993208771309 -0.00100014216922651 0.00354712938893324 -0.00983420135051563 0.000944783819270995 0.999878271425356 0.0155740076722746 0.000626360108399727 -0.00356227382374555 -0.0155705506351754 0.999872425941491 -0.00280369005670993 5.59354801169739e-05 1.64474695116756e-05 -5.9471380633489e-06 1.19350457141985e-05 -6.5698064595097e-06 1.70238173512654e-05 1.64474695116756e-05 4.14690059932795e-05 -9.22889990467718e-06 9.66114889757165e-06 7.84152137083823e-06 2.18074993843437e-05 -5.9471380633489e-06 -9.22889990467718e-06 1.42399655541438e-05 -3.52817721835351e-11 1.28937446091704e-06 -8.98968757896719e-06 1.19350457141985e-05 9.66114889757165e-06 -3.52817721835351e-11 2.77389442311206e-05 -3.60306460669969e-06 1.04323107648338e-05 -6.5698064595097e-06 7.84152137083823e-06 1.28937446091704e-06 -3.60306460669969e-06 3.49858400965813e-05 3.37982477693069e-06 1.70238173512654e-05 2.18074993843437e-05 -8.98968757896719e-06 1.04323107648338e-05 3.37982477693069e-06 5.54163922167672e-05 2314 2284 0 6 60 2261 2275 0 25 11 0 0 0 0 0 7 24 0 364 0 96 73 0 0 3258 +362 363 0.999875748774059 6.87237735613043e-05 0.0157633210510166 -0.0103886231793906 -0.00060073352196942 0.99943020695036 0.0337476007205829 -0.00290401609848439 -0.0157520199577723 -0.0337528770951937 0.999306067806579 -0.00382083143914846 5.42778978360352e-05 2.39579973031294e-05 -6.69928373703138e-06 8.34851435302308e-06 1.67970618646742e-06 2.77990050520959e-05 2.39579973031294e-05 8.09128946836811e-05 -7.61153431881751e-06 1.90087414014786e-05 1.4716491811028e-05 5.27899625822175e-05 -6.69928373703138e-06 -7.61153431881751e-06 1.20660105077955e-05 2.21376763161413e-06 1.03320525556877e-06 -9.88428577101159e-06 8.34851435302308e-06 1.90087414014786e-05 2.21376763161413e-06 3.51364997690984e-05 -4.45844338644176e-06 2.79808188553286e-05 1.67970618646742e-06 1.4716491811028e-05 1.03320525556877e-06 -4.45844338644176e-06 3.59785717949495e-05 6.00609586973284e-06 2.77990050520959e-05 5.27899625822175e-05 -9.88428577101159e-06 2.79808188553286e-05 6.00609586973284e-06 9.68715164489173e-05 2474 2453 0 13 56 2436 2461 0 29 28 0 0 0 0 0 16 34 0 425 0 100 83 0 0 3237 +367 368 0.999990792157787 -0.000349433268035032 0.00427708966852589 -0.000297273614695825 0.000341981481451402 0.999998422736142 0.00174286370508926 0.00388436153292667 -0.00427769193698714 -0.00174138497161412 0.999989334408159 0.00131700659080047 4.27002489199672e-05 2.68708083403942e-05 -1.50138956105931e-06 3.57746399507942e-06 -1.18432789041925e-06 3.12165795256973e-05 2.68708083403942e-05 4.24368511857372e-05 -5.31759830236219e-08 5.83540878160456e-06 4.46591871620734e-06 2.39924481524032e-05 -1.50138956105931e-06 -5.31759830236219e-08 9.65240561471069e-06 2.68019394421046e-06 5.10889945785256e-06 -2.71700265735691e-06 3.57746399507942e-06 5.83540878160456e-06 2.68019394421046e-06 2.6200055555959e-05 -2.57438635512666e-06 1.3461899859976e-05 -1.18432789041925e-06 4.46591871620734e-06 5.10889945785256e-06 -2.57438635512666e-06 2.22914137135043e-05 -5.53972439990989e-06 3.12165795256973e-05 2.39924481524032e-05 -2.71700265735691e-06 1.3461899859976e-05 -5.53972439990989e-06 6.77992660503332e-05 2877 2853 0 16 46 2823 2854 0 49 0 0 0 0 0 0 14 46 0 514 0 77 56 0 0 2868 +364 365 0.99995941121956 0.00279247305609523 0.00856609640748876 -0.00967413471756528 -0.0030005547544032 0.999698372298746 0.0243754198815722 0.00795994187152665 -0.00849544493227036 -0.0244001335543087 0.999666174729312 -0.00113537036096901 0.000110528549033725 3.98819227107685e-05 -5.50523718855646e-06 1.11798806395608e-05 -2.29659596886384e-05 4.40094824157689e-05 3.98819227107685e-05 7.02515821058569e-05 -2.13294112706051e-06 2.02488972000569e-05 -3.45694923510655e-06 4.41009997212893e-05 -5.50523718855646e-06 -2.13294112706051e-06 1.06007695402996e-05 3.34679891187874e-06 1.9102706894424e-06 -8.52360608398725e-07 1.11798806395608e-05 2.02488972000569e-05 3.34679891187874e-06 3.69978318537102e-05 -1.68904937380641e-06 2.1461614600252e-05 -2.29659596886384e-05 -3.45694923510655e-06 1.9102706894424e-06 -1.68904937380641e-06 4.68437797365915e-05 -1.15023868615287e-05 4.40094824157689e-05 4.41009997212893e-05 -8.52360608398725e-07 2.1461614600252e-05 -1.15023868615287e-05 7.86964608805337e-05 2118 2103 0 20 48 2071 2093 0 41 4 0 0 0 0 0 10 38 0 504 0 104 91 0 0 2750 +369 370 0.999999170944543 1.52589562562708e-05 -0.00128758587743245 -0.003920536410473 -1.27902353222437e-05 0.999998161874405 0.00191731171740267 0.00232617596575192 0.00128761276686351 -0.00191729365931856 0.999997333015637 0.00139895328127021 4.34874218466301e-05 2.91951805392077e-05 -1.21184033824006e-05 1.17044987585436e-05 5.47164114125344e-06 3.22551488471278e-05 2.91951805392077e-05 3.47656186049791e-05 -1.22265782231268e-05 1.02972348828556e-05 7.77009981969495e-06 3.33043489778383e-05 -1.21184033824006e-05 -1.22265782231268e-05 1.43406941172296e-05 -2.21478892384078e-06 -3.06639101577691e-06 -8.05969224339915e-06 1.17044987585436e-05 1.02972348828556e-05 -2.21478892384078e-06 2.46926801718631e-05 4.69256848022332e-06 1.43422262760124e-05 5.47164114125344e-06 7.77009981969495e-06 -3.06639101577691e-06 4.69256848022332e-06 3.61898894914385e-05 7.37660124551064e-06 3.22551488471278e-05 3.33043489778383e-05 -8.05969224339915e-06 1.43422262760124e-05 7.37660124551064e-06 5.53768152308403e-05 2967 2946 0 15 53 2947 2964 0 38 29 0 0 0 0 0 17 45 0 644 0 79 64 0 0 2088 +365 366 0.999999506484756 0.000680003766581588 -0.000724310100933494 -0.00190047673119068 -0.000681258013833865 0.999998266631909 -0.00173280717233644 0.00373269689015984 0.000723130530033529 0.00173329975923045 0.999998236375535 -0.00255543423262032 2.96825009206625e-05 1.44578524929883e-05 -7.5258397613214e-06 2.33695955881473e-06 5.57936637770997e-06 1.84977048600274e-05 1.44578524929883e-05 2.45116874889156e-05 -5.95403908146959e-06 7.69502883906361e-06 4.36857763633795e-06 2.13005579152646e-05 -7.5258397613214e-06 -5.95403908146959e-06 1.39702840060823e-05 1.01005445582733e-06 -4.34622410819192e-07 -5.70205643511436e-06 2.33695955881473e-06 7.69502883906361e-06 1.01005445582733e-06 2.61363146014946e-05 6.88921606192914e-06 1.00240633743202e-05 5.57936637770997e-06 4.36857763633795e-06 -4.34622410819192e-07 6.88921606192914e-06 3.14151356980848e-05 2.25675058244339e-06 1.84977048600274e-05 2.13005579152646e-05 -5.70205643511436e-06 1.00240633743202e-05 2.25675058244339e-06 5.64391850512823e-05 3207 3182 0 15 56 3191 3236 0 45 35 0 0 0 0 0 17 45 0 641 0 54 30 0 0 2637 +371 372 0.99999961600711 0.000317400155106295 0.00081684929707244 -0.000266931756816439 -0.000316903146440696 0.999999764647918 -0.000608503496481558 -0.00149805893160494 -0.000817042243929423 0.000608244400708131 0.999999481240226 -0.00173575068963913 2.64825640515401e-05 9.84393564858091e-06 -8.76521684628586e-06 3.17976219163297e-06 6.40540408059929e-06 9.49100951644977e-06 9.84393564858091e-06 2.26119740671312e-05 -1.05198894144203e-05 6.55796902154689e-06 1.12935381168667e-05 1.34725893513425e-05 -8.76521684628586e-06 -1.05198894144203e-05 1.49424649418041e-05 -1.95319238250865e-06 -5.68644611834052e-06 -5.34848626697111e-06 3.17976219163297e-06 6.55796902154689e-06 -1.95319238250865e-06 2.34377615969334e-05 8.32663452341208e-06 4.49585314603198e-06 6.40540408059929e-06 1.12935381168667e-05 -5.68644611834052e-06 8.32663452341208e-06 3.6648964307113e-05 7.28082885091012e-06 9.49100951644977e-06 1.34725893513425e-05 -5.34848626697111e-06 4.49585314603198e-06 7.28082885091012e-06 2.66245731394041e-05 2177 2153 0 17 56 2153 2201 0 49 33 0 0 0 0 0 6 38 0 681 0 57 33 0 0 2741 +370 371 0.999994262301451 0.000243642419001345 -0.00337875754497417 -0.0103341208736755 -0.000247091854945897 0.999999448723131 -0.00102053860761147 0.00300172486638742 0.00337850703584824 0.00102136761553778 0.999993771229803 -0.00301440626275936 3.13645969394003e-05 2.24486837492033e-05 -9.01718699767354e-06 7.87373110751323e-06 5.57323433922613e-06 1.88021275339779e-05 2.24486837492033e-05 3.5030861932746e-05 -9.06071103473617e-06 1.19308166591724e-05 1.76729237820883e-06 2.34203250362534e-05 -9.01718699767354e-06 -9.06071103473617e-06 1.36881396750652e-05 -2.59731261588922e-06 -3.23734236546033e-06 -3.82199242629664e-06 7.87373110751323e-06 1.19308166591724e-05 -2.59731261588922e-06 3.42582172790001e-05 -1.64590450923468e-06 9.31338182082366e-06 5.57323433922613e-06 1.76729237820883e-06 -3.23734236546033e-06 -1.64590450923468e-06 4.10448238725225e-05 7.64239845663226e-06 1.88021275339779e-05 2.34203250362534e-05 -3.82199242629664e-06 9.31338182082366e-06 7.64239845663226e-06 5.17976881610198e-05 1964 1945 0 16 51 1950 1983 0 50 30 0 0 0 0 0 12 43 0 651 0 102 82 0 0 2479 +368 369 0.999997306147946 0.000793271624317019 -0.00218137960520644 8.72672230915648e-05 -0.000794903942464423 0.999999404662324 -0.000747531082797095 0.0004781529720495 0.0021807853113527 0.000749263056307142 0.999997341386615 0.00153314615685431 2.59489954085921e-05 7.95387895755759e-06 -6.97552214014324e-06 1.26548573531732e-06 4.20727599218638e-06 9.5426014301461e-06 7.95387895755759e-06 2.99013335839316e-05 -6.48711041647619e-06 5.24622620253656e-06 7.48356247323745e-06 9.37608688636557e-06 -6.97552214014324e-06 -6.48711041647619e-06 1.55002793771743e-05 -1.55867892100631e-06 2.94271952793025e-07 -4.43064596148446e-06 1.26548573531732e-06 5.24622620253656e-06 -1.55867892100631e-06 2.90452898133148e-05 -1.17682029486788e-06 1.23419688364823e-06 4.20727599218638e-06 7.48356247323745e-06 2.94271952793025e-07 -1.17682029486788e-06 4.04231343995136e-05 1.44383554578267e-05 9.5426014301461e-06 9.37608688636557e-06 -4.43064596148446e-06 1.23419688364823e-06 1.44383554578267e-05 3.81099603134743e-05 1855 1841 0 26 48 1827 1850 0 41 24 0 0 0 0 0 12 45 0 625 0 63 51 0 0 2331 +376 377 0.999999836434976 0.000516694947054024 0.000245267920917547 -0.00388768070756228 -0.000516772063431229 0.999999817031473 0.000314457716259879 0.00724538683970897 -0.000245105397328183 -0.000314584412435181 0.999999920479993 0.00208104235675758 3.27734332178785e-05 2.54321589717683e-05 -1.1154986381791e-05 9.37088666230613e-06 6.17032026077187e-06 2.03469842168239e-05 2.54321589717683e-05 3.2072208249842e-05 -1.16634186103079e-05 1.16204157225625e-05 6.46738105311858e-06 2.34386358480455e-05 -1.1154986381791e-05 -1.16634186103079e-05 1.48436187801096e-05 -5.12571592457111e-06 -4.53769543004622e-06 -5.54424060546972e-06 9.37088666230613e-06 1.16204157225625e-05 -5.12571592457111e-06 3.15552865745436e-05 -1.09308920430531e-05 6.30059680771228e-06 6.17032026077187e-06 6.46738105311858e-06 -4.53769543004622e-06 -1.09308920430531e-05 4.65413893076952e-05 7.15444374759002e-06 2.03469842168239e-05 2.34386358480455e-05 -5.54424060546972e-06 6.30059680771228e-06 7.15444374759002e-06 3.40090981617832e-05 2114 2093 0 6 47 2075 2097 0 37 5 0 0 0 0 0 19 49 0 658 0 97 83 0 0 2695 +375 376 0.999999811978251 -0.000170686351043487 -0.00058899035000188 -0.0028546202233321 0.00017043879488894 0.999999897136414 -0.000420330559467446 0.00370383774805531 0.000589062034105648 0.000420230093630704 0.99999973820626 0.00457732403134503 3.19488717012502e-05 2.05589426911029e-05 -7.95981447180631e-06 6.2548351500595e-06 7.03502377304698e-06 1.4907459668146e-05 2.05589426911029e-05 3.07114580692997e-05 -8.92681375000729e-06 9.7423686841043e-06 7.73416511872636e-06 1.87845028993353e-05 -7.95981447180631e-06 -8.92681375000729e-06 1.17903426210208e-05 -2.42363060839714e-06 -2.49710287038857e-06 -3.65839450946933e-06 6.2548351500595e-06 9.7423686841043e-06 -2.42363060839714e-06 2.53131837183325e-05 7.30960871446856e-07 1.8054946394231e-06 7.03502377304698e-06 7.73416511872636e-06 -2.49710287038857e-06 7.30960871446856e-07 3.2891228853236e-05 9.30651208929088e-06 1.4907459668146e-05 1.87845028993353e-05 -3.65839450946933e-06 1.8054946394231e-06 9.30651208929088e-06 3.59589872357003e-05 2816 2790 0 13 55 2795 2822 0 48 26 0 0 0 0 0 14 45 0 648 0 94 90 0 0 2661 +372 373 0.999986681973359 0.00077708713247425 0.0051021575338699 -0.00350394984361999 -0.000789383441780691 0.999996788115617 0.0024084501721448 0.00687044748370468 -0.00510026957069181 -0.00241244565501584 0.999984083551467 -0.00778561221866061 3.20418405057579e-05 2.02626109123898e-05 -1.04883111206919e-05 7.87212663102308e-06 3.43799492887616e-06 1.74108875420771e-05 2.02626109123898e-05 2.81418949304223e-05 -1.04539782295021e-05 9.58198986502181e-06 5.38968740086061e-06 1.9138798364157e-05 -1.04883111206919e-05 -1.04539782295021e-05 1.26068761999776e-05 -2.28266381723831e-06 -2.09628522137483e-06 -6.2730100271109e-06 7.87212663102308e-06 9.58198986502181e-06 -2.28266381723831e-06 3.61442744669844e-05 -1.31407690096393e-05 8.50530911290784e-06 3.43799492887616e-06 5.38968740086061e-06 -2.09628522137483e-06 -1.31407690096393e-05 4.48367537342098e-05 1.22173530726275e-07 1.74108875420771e-05 1.9138798364157e-05 -6.2730100271109e-06 8.50530911290784e-06 1.22173530726275e-07 4.3449160315591e-05 2090 2064 0 11 56 2065 2087 0 40 28 0 0 0 0 0 23 53 0 660 0 99 80 0 0 2696 +373 374 0.999992324418515 0.000393495085098681 0.0038982387913199 0.00151759221132047 -0.000398313968697368 0.999999157479336 0.00123547019382901 0.00403263576979891 -0.0038977493555241 -0.00123701343384076 0.999991638638907 -0.00393951362954883 2.34202384487316e-05 1.55301041333789e-05 -6.03220883584734e-06 3.48313880686644e-06 6.21650773505699e-06 1.19366796069775e-05 1.55301041333789e-05 2.56860655191326e-05 -7.39800971878586e-06 4.5656739849328e-06 5.04539226698206e-06 1.76617148840161e-05 -6.03220883584734e-06 -7.39800971878586e-06 1.1073885520078e-05 -2.93952264750059e-07 -7.06347661002632e-07 -3.25216598160177e-06 3.48313880686644e-06 4.5656739849328e-06 -2.93952264750059e-07 2.46593661331741e-05 2.69729691246818e-06 3.97178664042522e-06 6.21650773505699e-06 5.04539226698206e-06 -7.06347661002632e-07 2.69729691246818e-06 2.72788779678901e-05 4.6706611484703e-06 1.19366796069775e-05 1.76617148840161e-05 -3.25216598160177e-06 3.97178664042522e-06 4.6706611484703e-06 3.24077818539699e-05 2658 2633 0 16 56 2632 2654 0 40 25 0 0 0 0 0 12 43 0 659 0 54 31 0 0 2712 +380 381 0.99999676340243 -3.40048926298101e-05 0.00254401814682424 -0.00134625158434938 3.36458494737875e-05 0.999999989468792 0.000141174974098713 -0.000150152083748944 -0.00254402292067249 -0.000141088921520508 0.999996754015379 -0.00326557805236119 2.82363693768565e-05 2.04215603980995e-05 -6.3177554969116e-06 7.81693307275562e-06 5.89889745300016e-06 1.85592702389515e-05 2.04215603980995e-05 2.47785988197386e-05 -7.41678164938648e-06 7.08306597846853e-06 2.91240750565573e-06 1.95414431523962e-05 -6.3177554969116e-06 -7.41678164938648e-06 1.08467982744329e-05 -6.79774417993654e-07 -3.24280538039525e-08 -2.70021113067435e-06 7.81693307275562e-06 7.08306597846853e-06 -6.79774417993654e-07 2.96346642396552e-05 -2.30543007084545e-06 7.2376434273995e-06 5.89889745300016e-06 2.91240750565573e-06 -3.24280538039525e-08 -2.30543007084545e-06 2.72241404034605e-05 5.32100627839661e-06 1.85592702389515e-05 1.95414431523962e-05 -2.70021113067435e-06 7.2376434273995e-06 5.32100627839661e-06 3.44795046947297e-05 2755 2737 0 20 49 2728 2750 0 40 27 0 0 0 0 0 17 51 0 665 0 96 81 0 0 2895 +377 378 0.999998803501023 -0.000450786224963253 0.00147979333052869 0.000770042685142487 0.000450420026306202 0.999999867860944 0.000247790019133116 0.00252708920459245 -0.00147990483531751 -0.000247123194101747 0.999998874405269 -0.00241119850586643 3.26161318157294e-05 2.18804841807074e-05 -7.21260135505521e-06 4.31816134190723e-06 8.16569648610796e-06 1.70319995581384e-05 2.18804841807074e-05 3.06344334756194e-05 -8.34434747826118e-06 3.87764788437377e-06 8.93471266096182e-06 1.68559191619188e-05 -7.21260135505521e-06 -8.34434747826118e-06 1.19828725529703e-05 -2.99017342847914e-07 -2.39877152269657e-07 -2.74828638620866e-06 4.31816134190723e-06 3.87764788437377e-06 -2.99017342847914e-07 2.60136592526037e-05 -2.73639174495053e-06 7.9210945428556e-08 8.16569648610796e-06 8.93471266096182e-06 -2.39877152269657e-07 -2.73639174495053e-06 3.65015777326793e-05 7.92790431461759e-06 1.70319995581384e-05 1.68559191619188e-05 -2.74828638620866e-06 7.9210945428556e-08 7.92790431461759e-06 3.75294518317274e-05 2677 2653 0 21 55 2650 2677 0 53 24 0 0 0 0 0 15 46 0 672 0 79 56 0 0 2820 +374 375 0.999999457664614 0.000607770595169978 -0.000845745458967763 -0.0040650342568725 -0.000609924201189297 0.999996566625573 -0.00254847592382169 0.00419719304336525 0.000844193666477935 0.00254899038231649 0.999996394986044 0.00241876919362378 2.71732968734909e-05 1.39065803158651e-05 -5.99931210797515e-06 9.32006220880078e-07 2.65460015860802e-06 8.49298711177232e-06 1.39065803158651e-05 2.37293759645359e-05 -7.87267879519878e-06 5.92202186981792e-06 2.97309686144992e-06 1.50987183374374e-05 -5.99931210797515e-06 -7.87267879519878e-06 1.16112691593703e-05 -3.93559303687958e-07 -1.20965654665941e-06 -3.19648912201304e-06 9.32006220880078e-07 5.92202186981792e-06 -3.93559303687958e-07 3.50801351586896e-05 -1.11319171982873e-05 2.14624713131154e-06 2.65460015860802e-06 2.97309686144992e-06 -1.20965654665941e-06 -1.11319171982873e-05 3.63576885067517e-05 3.84650862143651e-06 8.49298711177232e-06 1.50987183374374e-05 -3.19648912201304e-06 2.14624713131154e-06 3.84650862143651e-06 3.1901321934249e-05 2718 2693 0 16 62 2685 2712 0 46 23 0 0 0 0 0 14 46 0 664 0 81 62 0 0 2606 +386 387 0.99999988809606 7.24008476996303e-05 -0.00046751041148313 0.00104869692204057 -7.27651001186086e-05 0.999999693805699 -0.000779162209132766 -0.000786149438341006 0.00046745385632967 0.000779196140383343 0.999999587170048 -0.00327031130106254 2.34737659288957e-05 1.78427069384489e-05 -8.18597376854551e-06 7.42817358316697e-06 6.82902522125046e-06 1.50229924788972e-05 1.78427069384489e-05 2.22541907964089e-05 -9.57809629364103e-06 4.45822522576166e-06 8.79178155528268e-06 1.56282176215906e-05 -8.18597376854551e-06 -9.57809629364103e-06 1.37782363183774e-05 -1.11160434784891e-06 -2.47439918403265e-06 -4.67560930549643e-06 7.42817358316697e-06 4.45822522576166e-06 -1.11160434784891e-06 2.67357997764648e-05 -1.2739556391639e-06 2.06053515792328e-06 6.82902522125046e-06 8.79178155528268e-06 -2.47439918403265e-06 -1.2739556391639e-06 3.51234167608327e-05 6.84460483690665e-06 1.50229924788972e-05 1.56282176215906e-05 -4.67560930549643e-06 2.06053515792328e-06 6.84460483690665e-06 2.94178223052712e-05 2549 2537 0 26 55 2524 2555 0 46 24 0 0 0 0 0 15 46 0 650 0 90 85 0 0 2731 +378 379 0.999999231915944 -0.000157312425369571 -0.00122939835801961 -0.00137292987958264 0.000156887276065467 0.999999927867092 -0.000345907782080289 -3.52087430801359e-06 0.00122945268493168 0.000345714639434448 0.999999184463409 -0.00198704283284618 3.24264630681292e-05 1.73282480393488e-05 -9.1913771256972e-06 3.27539510892968e-06 5.46887511741618e-06 1.24414090430501e-05 1.73282480393488e-05 2.72500065786021e-05 -1.03029585402724e-05 3.62610313613474e-06 1.18560411018955e-05 2.08836442625936e-05 -9.1913771256972e-06 -1.03029585402724e-05 1.34060203173314e-05 5.29835704172958e-07 -4.44179358788108e-06 -5.61954690268405e-06 3.27539510892968e-06 3.62610313613474e-06 5.29835704172958e-07 2.66286491847387e-05 -3.86575568704175e-06 2.20432089700953e-07 5.46887511741618e-06 1.18560411018955e-05 -4.44179358788108e-06 -3.86575568704175e-06 3.97109951635659e-05 9.07389718773632e-06 1.24414090430501e-05 2.08836442625936e-05 -5.61954690268405e-06 2.20432089700953e-07 9.07389718773632e-06 3.59948876938062e-05 2125 2098 0 16 55 2085 2108 0 44 24 0 0 0 0 0 16 48 0 652 0 84 78 0 0 2824 +382 383 0.99998968797125 0.000256168161665014 -0.00453412935803908 -0.0215336683195865 -0.000252818244747905 0.999999694699831 0.000739380267567782 0.0226035388530445 0.00453431737945254 -0.000738226332431446 0.999989447438214 -0.000991782279934055 0.000137345251550953 8.54145782228642e-05 3.9534777128891e-06 0.000274850085575274 -0.000352972151411156 0.000115008637533706 8.54145782228642e-05 9.3881819452227e-05 -1.14155875618141e-06 -1.67008127795875e-05 2.34613716669836e-05 7.23200488621633e-05 3.9534777128891e-06 -1.14155875618141e-06 1.43006452176189e-05 1.57193776328341e-05 -2.23440552795467e-05 6.88920263868239e-06 0.000274850085575274 -1.67008127795875e-05 1.57193776328341e-05 0.00281125746438884 -0.00352131840164399 0.000311416782696523 -0.000352972151411156 2.34613716669836e-05 -2.23440552795467e-05 -0.00352131840164399 0.00448840796258731 -0.000405928395497694 0.000115008637533706 7.23200488621633e-05 6.88920263868239e-06 0.000311416782696523 -0.000405928395497694 0.000133101817186574 2801 2779 0 10 54 2781 2814 0 44 29 0 0 0 0 0 25 53 0 632 0 100 80 0 0 2665 +387 388 0.999989007147492 -0.000245451793796422 0.00468244995609396 0.0053327488724522 0.000239458673146722 0.999999151580194 0.00128042900482245 -0.00523158398001503 -0.00468276026700674 -0.00127929367600169 0.999988217512573 -0.00316622887221132 2.69637565259022e-05 1.87539564846412e-05 -1.95323532402716e-07 2.34313370380762e-06 -9.27982305789352e-08 1.71962920863747e-05 1.87539564846412e-05 2.64298813267017e-05 -2.92362530109822e-07 2.90090243551211e-06 -2.88750830324246e-06 1.96877719975194e-05 -1.95323532402716e-07 -2.92362530109822e-07 1.16077032206966e-05 2.01827204117043e-06 2.46038973322483e-06 9.25319276678858e-07 2.34313370380762e-06 2.90090243551211e-06 2.01827204117043e-06 2.73863534782225e-05 -3.86962690932643e-06 -7.52334246551391e-07 -9.27982305789352e-08 -2.88750830324246e-06 2.46038973322483e-06 -3.86962690932643e-06 2.79673427726286e-05 4.37114624045754e-07 1.71962920863747e-05 1.96877719975194e-05 9.25319276678858e-07 -7.52334246551391e-07 4.37114624045754e-07 3.75143802536704e-05 2217 2196 0 22 57 2195 2223 0 46 29 0 0 0 0 0 14 46 0 661 0 96 79 0 0 2649 +389 390 0.999995795008402 0.000486930649577129 0.00285882214511298 0.00378578431234592 -0.000489190121361013 0.999999568529786 0.00078970454439236 0.00389867547098484 -0.0028584363802696 -0.000791099731243503 0.999995601741665 0.00489755636754544 2.70690420124148e-05 1.00403986049756e-05 -1.84011187679233e-06 2.15217918104432e-07 2.15938084990648e-06 8.59433378574323e-06 1.00403986049756e-05 1.92408122873085e-05 -4.71170058142899e-06 2.22694051886491e-06 3.81042124728928e-06 1.19810484863514e-05 -1.84011187679233e-06 -4.71170058142899e-06 9.82835168946648e-06 3.38918068312589e-06 2.31881810095489e-06 -7.55710309560534e-07 2.15217918104432e-07 2.22694051886491e-06 3.38918068312589e-06 2.37592584516412e-05 3.83272510879535e-06 8.96017674937701e-06 2.15938084990648e-06 3.81042124728928e-06 2.31881810095489e-06 3.83272510879535e-06 2.6024324873948e-05 1.30428761626863e-05 8.59433378574323e-06 1.19810484863514e-05 -7.55710309560534e-07 8.96017674937701e-06 1.30428761626863e-05 4.31431578472567e-05 2948 2928 0 13 51 2930 2971 0 48 31 0 0 0 0 0 15 47 0 403 0 54 30 0 0 2468 +388 389 0.999999975764753 8.62295477485838e-05 -0.000202570872148434 0.00242294988651099 -8.65975190099679e-05 0.999998345140503 -0.00181720035340554 -0.00402908652003087 0.00020241384055746 0.00181721785150019 0.999998328372561 -0.00544691042699134 2.80629533053572e-05 7.88656226885085e-06 -1.07500508443532e-06 -2.562080334886e-06 1.88258537834223e-06 5.23630862337126e-06 7.88656226885085e-06 2.37665796695075e-05 -2.13815878360552e-06 1.54368169289954e-06 9.27747532227339e-07 1.78944330796606e-05 -1.07500508443532e-06 -2.13815878360552e-06 8.92120456862023e-06 4.96631660084306e-06 3.40458362624093e-06 9.06513935360876e-07 -2.562080334886e-06 1.54368169289954e-06 4.96631660084306e-06 2.20931349305444e-05 -1.31838982750949e-06 2.00710296735023e-06 1.88258537834223e-06 9.27747532227339e-07 3.40458362624093e-06 -1.31838982750949e-06 2.49471048857485e-05 2.56637686553075e-06 5.23630862337126e-06 1.78944330796606e-05 9.06513935360876e-07 2.00710296735023e-06 2.56637686553075e-06 3.37132877460497e-05 2918 2896 0 15 50 2899 2927 0 50 28 0 0 0 0 0 17 50 0 500 0 81 68 0 0 2657 +383 384 0.999999274892819 0.000182267184842895 0.0011903749452302 0.000621471999799888 -0.000183457546013906 0.999999483215724 0.000999955805700092 0.00208307472922263 -0.00119019207093348 -0.00100017346389124 0.999998791547208 0.001539826566042 2.81534891827538e-05 2.20309326884053e-05 -6.77705399328094e-06 5.15371782173423e-06 6.22353370698952e-06 2.01496741893843e-05 2.20309326884053e-05 2.58717623318768e-05 -8.19069576013647e-06 6.92187075755651e-06 3.44601162571886e-06 2.01220213391558e-05 -6.77705399328094e-06 -8.19069576013647e-06 1.12950018898546e-05 -4.35563244522146e-07 -1.02844871105736e-06 -3.36968865038201e-06 5.15371782173423e-06 6.92187075755651e-06 -4.35563244522146e-07 2.31144408803875e-05 -7.51379417861507e-07 7.64290589990673e-06 6.22353370698952e-06 3.44601162571886e-06 -1.02844871105736e-06 -7.51379417861507e-07 2.49644001901372e-05 3.61854634518487e-06 2.01496741893843e-05 2.01220213391558e-05 -3.36968865038201e-06 7.64290589990673e-06 3.61854634518487e-06 3.83535904423929e-05 3172 3155 0 16 55 3152 3196 0 43 33 0 0 0 0 0 17 48 0 668 0 56 33 0 0 2831 +379 380 0.999997472065488 9.43261038720868e-05 0.0022465451742236 -0.00138164898997837 -0.000102959380460494 0.999992609936833 0.00384310695763579 0.00386797730262333 -0.00224616606680678 -0.00384332854541239 0.999990091732759 0.00139931545563028 3.25473429845818e-05 1.40249588292025e-05 -7.11363150084836e-06 3.03335510633184e-06 2.52884739143115e-06 1.20465496930231e-05 1.40249588292025e-05 2.55850813800046e-05 -8.85431487370474e-06 5.7079738075193e-06 7.24027358754944e-06 1.8231463664502e-05 -7.11363150084836e-06 -8.85431487370474e-06 1.22531923461059e-05 -9.28233838194406e-07 -2.56615107325627e-06 -3.73015443879645e-06 3.03335510633184e-06 5.7079738075193e-06 -9.28233838194406e-07 2.25063446374258e-05 4.72269248250991e-06 4.41821036877848e-06 2.52884739143115e-06 7.24027358754944e-06 -2.56615107325627e-06 4.72269248250991e-06 3.20615591403209e-05 1.02558383676792e-05 1.20465496930231e-05 1.8231463664502e-05 -3.73015443879645e-06 4.41821036877848e-06 1.02558383676792e-05 3.39143329248854e-05 2993 2965 0 15 59 2965 3014 0 46 35 0 0 0 0 0 19 50 0 654 0 59 33 0 0 2742 +385 386 0.999999763578924 1.04507800127792e-05 0.000687555727408223 0.000454625782898393 -1.05432893026997e-05 0.999999990893298 0.000134544573987516 0.00140738171714712 -0.000687554315051114 -0.000134551791277288 0.99999975458241 0.00305221251768732 3.37522288728616e-05 2.42163006405013e-05 -9.15815913828793e-06 6.12983232602997e-06 3.79525089201839e-06 2.21300272601033e-05 2.42163006405013e-05 3.16482605327348e-05 -1.05170536675876e-05 7.98636208815954e-06 7.79544698922987e-06 1.95420338038821e-05 -9.15815913828793e-06 -1.05170536675876e-05 1.38885296102952e-05 -1.35431271250475e-06 -1.91251474541853e-06 -6.24990028844673e-06 6.12983232602997e-06 7.98636208815954e-06 -1.35431271250475e-06 2.86000540690207e-05 3.49752484293353e-06 -2.26526253197315e-07 3.79525089201839e-06 7.79544698922987e-06 -1.91251474541853e-06 3.49752484293353e-06 3.49206001831693e-05 3.88753826463803e-06 2.21300272601033e-05 1.95420338038821e-05 -6.24990028844673e-06 -2.26526253197315e-07 3.88753826463803e-06 3.52129666608736e-05 2139 2116 0 20 48 2079 2103 0 46 0 0 0 0 0 0 16 46 0 627 0 110 102 0 0 2716 +381 382 0.99999990861851 -8.39078065377976e-05 -0.000419192617788962 -0.00282227891148028 8.42522301137759e-05 0.999999658867183 0.000821685511560735 0.00169623371676211 0.000419123528959664 -0.000821720754386785 0.999999574555144 -0.00119754908353833 2.73465759588908e-05 1.69635669063316e-05 -6.22610535536729e-06 3.65740847116262e-06 7.60906108787353e-06 1.84153516033781e-05 1.69635669063316e-05 2.10334482936513e-05 -8.050800132272e-06 4.07714861865444e-06 6.63523857986455e-06 1.81148979822124e-05 -6.22610535536729e-06 -8.050800132272e-06 1.05802172211507e-05 -1.3265126614994e-06 -1.78138584649429e-06 -3.51300934098032e-06 3.65740847116262e-06 4.07714861865444e-06 -1.3265126614994e-06 2.15292282063561e-05 2.84627719823674e-06 3.86154239833552e-06 7.60906108787353e-06 6.63523857986455e-06 -1.78138584649429e-06 2.84627719823674e-06 2.57035410174828e-05 6.61886671737971e-06 1.84153516033781e-05 1.81148979822124e-05 -3.51300934098032e-06 3.86154239833552e-06 6.61886671737971e-06 4.04029003695411e-05 3134 3122 0 18 54 3121 3174 0 51 32 0 0 0 0 0 17 47 0 653 0 56 33 0 0 2818 +384 385 0.999997477925464 -0.000228847248016945 0.00223422730457218 0.00446976150275652 0.000226104228686632 0.999999220567005 0.00122790156817063 -0.00494670219630663 -0.00223450656503641 -0.00122739330306995 0.999996750237765 -0.00540291968353257 2.7285630641595e-05 1.84584288368514e-05 -8.07363001549142e-06 8.3890559027745e-06 2.24379397329413e-06 1.78334193748007e-05 1.84584288368514e-05 2.47297389011515e-05 -8.76671333598211e-06 8.20288238464199e-06 5.37311273889057e-07 1.71152904983173e-05 -8.07363001549142e-06 -8.76671333598211e-06 1.28900864376656e-05 -3.94462033231101e-06 -1.54968361159566e-06 -4.76535121433817e-06 8.3890559027745e-06 8.20288238464199e-06 -3.94462033231101e-06 2.87712191975883e-05 -4.9682581048553e-06 3.71422621173273e-06 2.24379397329413e-06 5.37311273889057e-07 -1.54968361159566e-06 -4.9682581048553e-06 3.5193239078359e-05 2.10752876894826e-06 1.78334193748007e-05 1.71152904983173e-05 -4.76535121433817e-06 3.71422621173273e-06 2.10752876894826e-06 3.21795933132009e-05 2147 2123 0 18 54 2127 2156 0 55 28 0 0 0 0 0 21 53 0 652 0 99 82 0 0 2747 +390 391 0.999998901540948 -4.83693311450781e-05 0.00148141057930236 0.00122587867707738 4.72141354949e-05 0.999999694826195 0.000779819428901205 0.00199875489503277 -0.00148144784655885 -0.00077974862878168 0.999998598651195 -0.004615499250843 2.39988437826411e-05 4.720482401625e-06 -1.03515848749374e-06 -4.20681665743466e-07 -2.89223505976863e-06 -7.97191512643339e-07 4.720482401625e-06 2.23677280187977e-05 -2.74502011522009e-06 1.4746478196311e-06 1.28087517334859e-06 1.01533504516555e-05 -1.03515848749374e-06 -2.74502011522009e-06 8.79350043498865e-06 3.07224673081456e-06 4.27575304560597e-06 1.88706518995422e-06 -4.20681665743466e-07 1.4746478196311e-06 3.07224673081456e-06 1.97704195401888e-05 -1.36489845889988e-06 8.2042006280361e-07 -2.89223505976863e-06 1.28087517334859e-06 4.27575304560597e-06 -1.36489845889988e-06 2.35390087368727e-05 3.11128682139686e-06 -7.97191512643339e-07 1.01533504516555e-05 1.88706518995422e-06 8.2042006280361e-07 3.11128682139686e-06 3.30926805172115e-05 2265 2247 0 21 51 2213 2242 0 52 7 0 0 0 0 0 19 52 0 410 0 88 72 0 0 2516 +392 393 0.999990361057461 -3.3660124262862e-05 0.00439051923628263 0.00341319499096092 1.74754828752703e-05 0.999993205579841 0.00368625674111459 -0.000526052249739632 -0.00439061348511019 -0.00368614448305396 0.99998356729102 -0.00526058959799768 2.85013260716871e-05 5.45699809557618e-06 -2.6016671113028e-06 2.15774705666864e-07 -5.72102580868413e-06 3.08557824722557e-06 5.45699809557618e-06 2.22729340874223e-05 -1.52755095024965e-06 2.954754353625e-06 1.62426084051807e-06 1.22301713315358e-05 -2.6016671113028e-06 -1.52755095024965e-06 9.20234988244159e-06 4.006666109925e-06 5.48501330114246e-06 6.52488825856351e-07 2.15774705666864e-07 2.954754353625e-06 4.006666109925e-06 2.14314141190241e-05 -1.99708817277335e-06 6.92685741681919e-07 -5.72102580868413e-06 1.62426084051807e-06 5.48501330114246e-06 -1.99708817277335e-06 2.29219983819671e-05 3.37318875156986e-06 3.08557824722557e-06 1.22301713315358e-05 6.52488825856351e-07 6.92685741681919e-07 3.37318875156986e-06 2.91667534093929e-05 2168 2146 0 17 48 2139 2169 0 50 23 0 0 0 0 0 17 49 0 458 0 76 66 0 0 2369 +394 395 0.99999951749225 -0.00055864590374291 0.000808040853741943 -0.00140855439285183 0.000558342852494143 0.999999773731041 0.000375221435759232 0.00173412519992221 -0.000808250286825463 -0.000374770090876771 0.999999603139348 -0.00464932691221507 2.51113429961597e-05 1.62970793733059e-05 6.12988586199485e-07 -1.74744279892294e-06 1.04430362530041e-06 1.90614701928353e-05 1.62970793733059e-05 2.49112570727952e-05 -1.38813545948734e-06 6.85823643279435e-07 1.2343597729817e-06 1.80768425380877e-05 6.12988586199485e-07 -1.38813545948734e-06 9.69679054801016e-06 1.94690101703676e-06 6.50080159503744e-06 1.69317559586276e-06 -1.74744279892294e-06 6.85823643279435e-07 1.94690101703676e-06 3.14431273242957e-05 -8.58066367481478e-06 -3.08768442404302e-06 1.04430362530041e-06 1.2343597729817e-06 6.50080159503744e-06 -8.58066367481478e-06 2.30709185515306e-05 2.2768898666562e-06 1.90614701928353e-05 1.80768425380877e-05 1.69317559586276e-06 -3.08768442404302e-06 2.2768898666562e-06 4.17412909215319e-05 2083 2063 0 16 48 2069 2091 0 43 35 0 0 0 0 0 17 48 0 448 0 97 82 0 0 2565 +396 397 0.999999624152734 0.00086224541591549 9.07040998159823e-05 -0.00347784414578768 -0.000862443922833493 0.999997182231093 0.00221172339003408 0.00462394972007173 -8.87967958784602e-05 -0.00221180078596355 0.999997550023205 -0.00309765968094336 2.72559265082142e-05 1.6783532114434e-05 -1.70614405889326e-06 -6.23216655273403e-07 2.5637584470914e-06 1.55284590390947e-05 1.6783532114434e-05 3.03877304882082e-05 -5.76599875158902e-06 7.70020308830342e-06 -8.19359368956062e-07 2.00271294531396e-05 -1.70614405889326e-06 -5.76599875158902e-06 1.27380624396946e-05 2.79808991213164e-06 3.28195348544204e-06 1.40462895967961e-06 -6.23216655273403e-07 7.70020308830342e-06 2.79808991213164e-06 4.09591608742603e-05 -1.71425970382217e-05 3.5874626398769e-06 2.5637584470914e-06 -8.19359368956062e-07 3.28195348544204e-06 -1.71425970382217e-05 4.03041727864498e-05 3.00196007243274e-07 1.55284590390947e-05 2.00271294531396e-05 1.40462895967961e-06 3.5874626398769e-06 3.00196007243274e-07 4.0497012934175e-05 2610 2599 0 6 44 2628 2660 0 42 32 0 0 0 0 0 13 44 0 462 0 50 32 0 0 2419 +391 392 0.999999834234374 0.000466698688023938 0.000337229237032098 -0.00118024108818763 -0.000466588507570936 0.99999983777212 -0.000326727560067258 -0.000546688321975298 -0.000337381665647739 0.000326570158620644 0.999999889762766 -0.00325097760662101 2.33113839340239e-05 1.15998977532701e-05 4.45180913702006e-07 -6.78039826214247e-07 1.03194487190937e-07 6.4629298311239e-06 1.15998977532701e-05 1.96822017448385e-05 -2.4366434076632e-06 3.43323570164093e-06 -2.07284094280808e-06 1.34650722003359e-05 4.45180913702006e-07 -2.4366434076632e-06 9.29690285158849e-06 2.86752955072931e-06 5.74270749821801e-06 6.33905414423944e-07 -6.78039826214247e-07 3.43323570164093e-06 2.86752955072931e-06 2.34896572548384e-05 -2.15781063437212e-06 5.51307288671787e-07 1.03194487190937e-07 -2.07284094280808e-06 5.74270749821801e-06 -2.15781063437212e-06 1.83004955696605e-05 -1.9519336999052e-06 6.4629298311239e-06 1.34650722003359e-05 6.33905414423944e-07 5.51307288671787e-07 -1.9519336999052e-06 3.39256869734476e-05 2664 2644 0 23 55 2636 2662 0 46 30 0 0 0 0 0 14 46 0 427 0 91 93 0 0 2318 +393 394 0.999996168430412 -1.9601044422885e-05 0.00276816551074001 0.000485192179175788 1.36090578421722e-05 0.999997657141074 0.00216460785275849 0.00282025890417438 -0.00276820145389341 -0.00216456188678832 0.999993825847214 -0.00333744933891707 2.56774098106458e-05 1.27500639508851e-05 4.70087261102237e-08 -3.05869795591819e-06 1.29502935969182e-06 1.0763206846874e-05 1.27500639508851e-05 2.76965331874361e-05 -8.08044939378889e-08 4.82584478500235e-06 -5.7599893269867e-08 2.16902749561274e-05 4.70087261102237e-08 -8.08044939378889e-08 1.04099179637655e-05 2.80259222287581e-06 3.66544749503346e-06 1.62324898581873e-06 -3.05869795591819e-06 4.82584478500235e-06 2.80259222287581e-06 3.26409687916893e-05 -1.49907323239304e-05 2.10543817010706e-06 1.29502935969182e-06 -5.7599893269867e-08 3.66544749503346e-06 -1.49907323239304e-05 3.38211800874191e-05 -1.22918312201749e-07 1.0763206846874e-05 2.16902749561274e-05 1.62324898581873e-06 2.10543817010706e-06 -1.22918312201749e-07 3.66697380417664e-05 1960 1943 0 12 48 1944 1972 0 44 25 0 0 0 0 0 18 49 0 462 0 77 57 0 0 2431 +401 402 0.999998824876324 -0.000227831643441959 -0.00151602728020104 0.00351112223300891 0.000228550355922866 0.999999861582339 0.000473919863632643 -0.00536911351110512 0.0015159190964147 -0.000474265795292669 0.999998738529829 -0.00552605527995263 2.25360932052098e-05 2.05213824100227e-05 -1.11945184188379e-06 3.90285460061962e-06 -2.6447971282722e-06 1.84999757268152e-05 2.05213824100227e-05 2.62895118338362e-05 -3.42190338518938e-06 3.47130214548005e-06 -4.82546115451953e-06 2.28966372659522e-05 -1.11945184188379e-06 -3.42190338518938e-06 1.35458998796268e-05 6.61681350563334e-06 1.21425888521765e-06 1.4909110975928e-06 3.90285460061962e-06 3.47130214548005e-06 6.61681350563334e-06 2.7944875068391e-05 -1.3609597051055e-05 7.73869070079728e-06 -2.6447971282722e-06 -4.82546115451953e-06 1.21425888521765e-06 -1.3609597051055e-05 4.58144679059971e-05 -3.7784297315287e-06 1.84999757268152e-05 2.28966372659522e-05 1.4909110975928e-06 7.73869070079728e-06 -3.7784297315287e-06 3.52448133297806e-05 2280 2263 0 11 49 2363 2414 0 53 27 0 0 0 0 0 16 47 0 472 0 63 52 0 0 2515 +403 404 0.999999954890898 -0.000300114952637269 1.22154563451924e-05 -9.80364510207088e-05 0.000300121905479502 0.999999790673656 -0.00057321853319829 -0.00332082267286743 -1.20434223352339e-05 0.000573222173466951 0.999999835635634 -0.000855894258619617 1.55146631148871e-05 9.96563241432203e-06 -3.05929197885704e-07 -6.13909116736867e-07 1.44494781323207e-06 9.64925477259046e-06 9.96563241432203e-06 2.25646581537536e-05 -2.73235805531069e-06 4.04339301570646e-06 3.86048799012085e-07 1.49222113034958e-05 -3.05929197885704e-07 -2.73235805531069e-06 1.20029633828422e-05 1.61017008632333e-06 1.94004948066676e-06 1.51518935815344e-06 -6.13909116736867e-07 4.04339301570646e-06 1.61017008632333e-06 3.26029090645778e-05 -9.34239434961612e-06 -3.26840939982627e-06 1.44494781323207e-06 3.86048799012085e-07 1.94004948066676e-06 -9.34239434961612e-06 3.54223158107325e-05 2.39544447832795e-06 9.64925477259046e-06 1.49222113034958e-05 1.51518935815344e-06 -3.26840939982627e-06 2.39544447832795e-06 3.19604108114045e-05 2515 2515 0 16 25 2498 2530 0 48 22 0 0 0 0 0 11 41 0 431 0 61 57 0 0 2495 +395 396 0.999999561495258 0.000608513409048924 0.000711843186610592 -0.000655082628269092 -0.000609685761458245 0.999998456404236 0.0016478690531946 0.000396634268602926 -0.000710839337397239 -0.00164830233125147 0.999998388902133 0.000306101995294461 2.21294243755861e-05 1.07332529925381e-05 3.85102219080173e-07 -1.22775583748272e-06 -1.63844169242371e-06 7.92195714042506e-06 1.07332529925381e-05 2.57321145764846e-05 -2.55906674872538e-06 3.32325789425085e-06 -4.11589146569631e-07 1.53028414903633e-05 3.85102219080173e-07 -2.55906674872538e-06 1.27952999666633e-05 4.37853842620649e-06 4.56866016474721e-06 6.19798038729275e-07 -1.22775583748272e-06 3.32325789425085e-06 4.37853842620649e-06 3.06185283242395e-05 -2.91723613856008e-06 6.85105055610686e-07 -1.63844169242371e-06 -4.11589146569631e-07 4.56866016474721e-06 -2.91723613856008e-06 3.24649158145548e-05 5.35822539203976e-08 7.92195714042506e-06 1.53028414903633e-05 6.19798038729275e-07 6.85105055610686e-07 5.35822539203976e-08 3.02083272318801e-05 2408 2391 0 19 49 2441 2471 0 41 39 0 0 0 0 0 17 46 0 466 0 91 72 0 0 2454 +402 403 0.999993831626813 -3.50321769968054e-05 0.00351219035243108 0.00776025189240233 3.38634060031882e-05 0.99999994403725 0.00033283444174282 -0.0063851623499526 -0.00351220181579433 -0.000332713453967909 0.999993776850717 -0.0031297984230984 2.90798468966564e-05 1.65297256414196e-05 -1.67121646346171e-06 1.67597847711976e-06 -1.9453238125505e-06 1.52006439016594e-05 1.65297256414196e-05 2.91160963720856e-05 -3.39115214549951e-06 3.8339916072296e-06 -3.91668376808699e-06 2.24702941507363e-05 -1.67121646346171e-06 -3.39115214549951e-06 9.86421163332747e-06 2.95613126813101e-06 4.18575044904655e-06 3.9029707500121e-07 1.67597847711976e-06 3.8339916072296e-06 2.95613126813101e-06 2.53684340683404e-05 -4.90544338515795e-06 5.73168303510252e-06 -1.9453238125505e-06 -3.91668376808699e-06 4.18575044904655e-06 -4.90544338515795e-06 2.73058338622797e-05 -1.26087823655019e-06 1.52006439016594e-05 2.24702941507363e-05 3.9029707500121e-07 5.73168303510252e-06 -1.26087823655019e-06 4.04747741383127e-05 2598 2593 0 19 31 2623 2656 0 44 24 0 0 0 0 0 10 41 0 447 0 43 35 0 0 2586 +406 407 0.999998326296554 0.000105480328808061 -0.00182654810824385 -0.00274973369246686 -0.000106559774856718 0.999999819747739 -0.000590888741112825 0.000566114124803819 0.00182648545186572 0.000591082388695482 0.999998157284554 0.00277115481647428 2.50674632888461e-05 1.55978687732915e-05 -2.62883041632033e-06 1.25292603536769e-06 -2.77392410549573e-06 1.61166167525668e-05 1.55978687732915e-05 2.08502854527251e-05 -3.34433720432358e-06 1.67929622143993e-06 -1.28009378529605e-07 1.25976495635787e-05 -2.62883041632033e-06 -3.34433720432358e-06 1.27186786793488e-05 5.51305000263568e-06 1.3840546200728e-06 -5.6242377531708e-07 1.25292603536769e-06 1.67929622143993e-06 5.51305000263568e-06 2.27486183649334e-05 -4.86748142568165e-06 -4.9904147379115e-06 -2.77392410549573e-06 -1.28009378529605e-07 1.3840546200728e-06 -4.86748142568165e-06 2.86899842777944e-05 -5.70454383596763e-07 1.61166167525668e-05 1.25976495635787e-05 -5.6242377531708e-07 -4.9904147379115e-06 -5.70454383596763e-07 3.1825079151086e-05 2189 2189 0 22 32 2232 2263 0 39 39 0 0 0 0 0 11 41 0 485 0 63 62 0 0 2454 +405 406 0.999999909886699 -0.000301648409019932 -0.000298721997237699 0.00933290770736804 0.000301213947928392 0.999998898480742 -0.00145337794808072 -0.0111581857146607 0.00029916007733541 0.00145328783787992 0.999998899228248 -0.00120794658493108 2.61679239438722e-05 7.1293905398535e-06 -5.81628262477078e-07 -3.40731794480455e-06 -2.30119758446368e-06 9.9701087562438e-06 7.1293905398535e-06 2.147149316652e-05 -1.66684478856652e-06 3.51961749453851e-06 -2.03774063456973e-06 1.24079131659344e-05 -5.81628262477078e-07 -1.66684478856652e-06 9.73914720442242e-06 3.23972115369561e-06 4.41633451399581e-06 2.37662332858286e-06 -3.40731794480455e-06 3.51961749453851e-06 3.23972115369561e-06 2.87239582130011e-05 -1.01039667876166e-05 -1.04987271139029e-06 -2.30119758446368e-06 -2.03774063456973e-06 4.41633451399581e-06 -1.01039667876166e-05 2.95005974902217e-05 -3.41384135735503e-08 9.9701087562438e-06 1.24079131659344e-05 2.37662332858286e-06 -1.04987271139029e-06 -3.41384135735503e-08 2.70359299651925e-05 2672 2667 0 14 33 2724 2772 0 53 23 0 0 0 0 0 17 50 0 463 0 38 37 0 0 2624 +407 408 0.999999910462851 -0.000163695932074387 -0.000390228052032097 0.0044594851608191 0.000164117615291974 0.999999402446432 0.00108082014569458 4.43632837019005e-05 0.000390050892988778 -0.00108088409221834 0.999999339774722 -0.00168661307096926 2.4941321856266e-05 1.99914993744951e-05 -1.32296596799996e-06 8.90474390496701e-07 -9.05438858365615e-07 2.06994318190507e-05 1.99914993744951e-05 2.55018303101127e-05 -2.13344710437534e-06 7.40508282802735e-07 -1.46445002251551e-06 2.30652443069805e-05 -1.32296596799996e-06 -2.13344710437534e-06 1.05966388286013e-05 4.78124899805601e-06 4.51355435122876e-06 2.42952190210637e-06 8.90474390496701e-07 7.40508282802735e-07 4.78124899805601e-06 2.72311435528358e-05 -5.46174644163434e-06 8.16647533289118e-06 -9.05438858365615e-07 -1.46445002251551e-06 4.51355435122876e-06 -5.46174644163434e-06 2.95577448032398e-05 -2.13896503475017e-06 2.06994318190507e-05 2.30652443069805e-05 2.42952190210637e-06 8.16647533289118e-06 -2.13896503475017e-06 4.38971460464978e-05 1984 1985 0 16 27 2036 2082 0 46 24 0 0 0 0 0 16 47 0 494 0 38 36 0 0 2534 +397 398 0.999999735492267 -0.000236714058129224 -0.000687736759857371 -0.0022805705736821 0.000236976191003749 0.99999989930389 0.000381096436852292 0.000948473815178898 0.000687646479720849 -0.000381259313287101 0.99999969089178 0.00421323279777635 3.01981522416291e-05 2.66699738202413e-05 -5.50971496803088e-06 7.00740312414935e-06 2.70112653944229e-06 2.53248502129569e-05 2.66699738202413e-05 3.35794205173239e-05 -6.91397599429282e-06 9.89038354791239e-06 9.57070736206185e-07 3.01320821422819e-05 -5.50971496803088e-06 -6.91397599429282e-06 1.06116789796609e-05 1.59260649693382e-06 1.36309620655398e-06 -3.85919794778067e-06 7.00740312414935e-06 9.89038354791239e-06 1.59260649693382e-06 2.50534363095479e-05 -2.50233302168808e-06 1.03091644850945e-05 2.70112653944229e-06 9.57070736206185e-07 1.36309620655398e-06 -2.50233302168808e-06 2.59308527639711e-05 1.66689375948042e-06 2.53248502129569e-05 3.01320821422819e-05 -3.85919794778067e-06 1.03091644850945e-05 1.66689375948042e-06 4.55275109149289e-05 2912 2893 0 13 47 2989 3026 0 48 34 0 0 0 0 0 16 48 0 472 0 51 35 0 0 2376 +411 412 0.999999439091094 0.000267019455710344 -0.00102494785616869 0.000604564286941139 -0.000268586149309293 0.999998795428193 -0.00152872615056764 -0.000774156162018839 0.00102453842192074 0.00152900057988946 0.99999830623769 -0.000482718775388739 3.79317462863964e-05 2.10287516738764e-05 -6.46461058360227e-06 4.15699295860971e-06 8.38260968929382e-06 2.70923563336148e-05 2.10287516738764e-05 3.08830203165461e-05 -6.74904584993485e-06 8.30168166221144e-06 6.55028976173918e-06 2.92681015259639e-05 -6.46461058360227e-06 -6.74904584993485e-06 1.03799072261221e-05 6.83914248936999e-07 8.48224862234324e-07 -4.18245380275832e-06 4.15699295860971e-06 8.30168166221144e-06 6.83914248936999e-07 2.02436352798934e-05 1.70930988125908e-06 5.86780513558605e-06 8.38260968929382e-06 6.55028976173918e-06 8.48224862234324e-07 1.70930988125908e-06 2.35019938809479e-05 9.21747047059132e-06 2.70923563336148e-05 2.92681015259639e-05 -4.18245380275832e-06 5.86780513558605e-06 9.21747047059132e-06 5.68425074648702e-05 2347 2346 0 16 45 2347 2385 0 49 36 0 0 0 0 0 22 54 0 584 0 24 23 0 0 2359 +400 401 0.999992717673749 0.000206914369753525 0.00381074610984478 0.00440028845834142 -0.000203728370663084 0.99999962944332 -0.000836425713370513 -0.00745511497097206 -0.00381091776624668 0.000835643265149614 0.999992389274095 0.00512868919156529 4.89149949834722e-05 2.73847884704726e-05 -7.71883071063937e-06 1.4528507745631e-06 2.93319810554304e-06 3.42290987088445e-05 2.73847884704726e-05 4.87489085983012e-05 -6.31077315732857e-06 1.21899800367312e-05 7.85823966317746e-06 4.00754524003407e-05 -7.71883071063937e-06 -6.31077315732857e-06 1.44598602087187e-05 4.73756996998952e-06 -1.99105674213602e-06 -4.28436913347402e-06 1.4528507745631e-06 1.21899800367312e-05 4.73756996998952e-06 3.24375084320754e-05 -6.00964102544043e-07 9.75198016693858e-06 2.93319810554304e-06 7.85823966317746e-06 -1.99105674213602e-06 -6.00964102544043e-07 4.3439702264365e-05 6.29614421812145e-06 3.42290987088445e-05 4.00754524003407e-05 -4.28436913347402e-06 9.75198016693858e-06 6.29614421812145e-06 6.01094150603333e-05 1541 1527 0 18 40 1571 1608 0 52 28 0 0 0 0 0 11 39 0 496 0 98 82 0 0 2551 +398 399 0.99998223036713 -0.000448245593510743 0.00594457953665804 0.00756878453916874 0.000450695126956977 0.999999814087993 -0.00041072847599627 -0.00360211304704503 -0.00594439432425984 0.000413400370531023 0.999982246480532 0.00045051629148137 3.98880274278873e-05 2.8846333800779e-05 -3.64275373799735e-06 8.29330798522979e-06 -1.41494516345788e-07 3.38484196187902e-05 2.8846333800779e-05 3.65000337718414e-05 -4.66292738422197e-06 1.027341943156e-05 2.4461195700949e-06 3.6729219226307e-05 -3.64275373799735e-06 -4.66292738422197e-06 1.08330874949813e-05 4.70158176694342e-06 2.55242629452046e-06 -4.1727673558429e-08 8.29330798522979e-06 1.027341943156e-05 4.70158176694342e-06 2.71696314511245e-05 -7.16007986153866e-06 1.03964702421676e-05 -1.41494516345788e-07 2.4461195700949e-06 2.55242629452046e-06 -7.16007986153866e-06 4.14268610984951e-05 5.55946370260216e-06 3.38484196187902e-05 3.6729219226307e-05 -4.1727673558429e-08 1.03964702421676e-05 5.55946370260216e-06 5.8193767821251e-05 2746 2724 0 20 44 2726 2759 0 51 28 0 0 0 0 0 19 51 0 486 0 46 30 0 0 2558 +399 400 0.999999912331768 0.000280620995844774 0.000310786602271366 -0.0019737097008601 -0.000280547304974201 0.999999932531509 -0.000237129052685014 0.00320824894185962 -0.000310853124693971 0.00023704184155264 0.999999923590747 0.00489339236508884 2.81560933816233e-05 1.93792377654053e-05 -5.15497954129367e-06 2.56253342637476e-06 6.18281387837215e-06 1.56681924011851e-05 1.93792377654053e-05 2.93414371749225e-05 -7.13883859365691e-06 5.40019729896347e-06 6.83022872632064e-06 2.52252282107093e-05 -5.15497954129367e-06 -7.13883859365691e-06 1.39612197911335e-05 3.13238982276752e-06 -4.57035508622877e-07 -2.52277735215058e-06 2.56253342637476e-06 5.40019729896347e-06 3.13238982276752e-06 2.38228605633748e-05 -2.49940690136621e-06 6.82835793070801e-06 6.18281387837215e-06 6.83022872632064e-06 -4.57035508622877e-07 -2.49940690136621e-06 3.67210362039731e-05 8.32738546923537e-06 1.56681924011851e-05 2.52252282107093e-05 -2.52277735215058e-06 6.82835793070801e-06 8.32738546923537e-06 4.17537348886519e-05 3113 3093 0 13 44 3166 3215 0 50 25 0 0 0 0 0 17 50 0 505 0 51 35 0 0 2410 +404 405 0.999996253913848 -0.000435036547997436 0.00270238810564435 0.00558184739220764 0.000431012621337602 0.999998797912254 0.00148943014874008 -0.00277909688045081 -0.00270303281368712 -0.00148825980582514 0.999995239336847 -0.00354675681856905 2.64665047044783e-05 7.05185790933915e-06 -1.69900375338563e-06 -2.77640660531139e-06 -1.4285774942866e-06 1.3763854040369e-05 7.05185790933915e-06 2.1819562895073e-05 -1.61977701327705e-06 1.97860493909527e-06 -5.93842650725466e-07 1.03237321613212e-05 -1.69900375338563e-06 -1.61977701327705e-06 1.04418916929825e-05 5.00329868906749e-06 4.75459429245173e-06 1.21483775386459e-06 -2.77640660531139e-06 1.97860493909527e-06 5.00329868906749e-06 2.86147514683314e-05 -9.61484747559391e-06 -2.33919674722031e-06 -1.4285774942866e-06 -5.93842650725466e-07 4.75459429245173e-06 -9.61484747559391e-06 2.98882286616326e-05 3.40958970159072e-07 1.3763854040369e-05 1.03237321613212e-05 1.21483775386459e-06 -2.33919674722031e-06 3.40958970159072e-07 2.86194360463156e-05 2054 2057 0 22 26 2105 2154 0 50 25 0 0 0 0 0 20 52 0 457 0 33 31 0 0 2622 +413 414 0.999992170704754 -1.31553938543774e-05 0.00395706407968174 0.00373306516719672 1.63024132208119e-05 0.999999683647608 -0.000795260280955965 0.00154985555916153 -0.00395705236589285 0.000795318564322196 0.999991854569303 0.000169657693851974 5.7772608821975e-05 3.93626156277018e-05 -1.04936620994425e-05 1.18735301831511e-05 8.48910709422476e-06 5.46874487890789e-05 3.93626156277018e-05 4.2019321364247e-05 -9.65494579089946e-06 1.43271341717171e-05 5.55647929317801e-06 4.75146835709178e-05 -1.04936620994425e-05 -9.65494579089946e-06 1.21956116985692e-05 -1.8185232134337e-06 -1.93741119956042e-06 -6.20414088308646e-06 1.18735301831511e-05 1.43271341717171e-05 -1.8185232134337e-06 3.00365687098429e-05 -1.19122825515048e-06 1.83883002759256e-05 8.48910709422476e-06 5.55647929317801e-06 -1.93741119956042e-06 -1.19122825515048e-06 3.48824372506223e-05 3.71990783195033e-06 5.46874487890789e-05 4.75146835709178e-05 -6.20414088308646e-06 1.83883002759256e-05 3.71990783195033e-06 9.24264119912593e-05 2649 2645 0 9 25 2708 2751 0 45 23 0 0 0 0 0 17 48 0 603 0 21 20 0 0 2535 +412 413 0.999999932860218 8.82837473603715e-05 0.000355648054306979 0.00171858411204045 -8.81765889803236e-05 0.999999950718895 -0.000301308971570308 -0.000910344066845741 -0.000355674637465374 0.000301277591508183 0.999999891363677 -0.0033563430122504 2.80277276195552e-05 1.63260859239896e-05 -6.77100710507313e-06 3.80407643266591e-06 8.23582087967416e-06 1.46021412719992e-05 1.63260859239896e-05 2.71454767050272e-05 -7.63276601473983e-06 7.9797603244095e-06 1.05073713464399e-05 2.12431637752534e-05 -6.77100710507313e-06 -7.63276601473983e-06 1.25333045850978e-05 -7.93274469435302e-07 -4.15319643772414e-07 -3.1148292701057e-06 3.80407643266591e-06 7.9797603244095e-06 -7.93274469435302e-07 2.80465631331248e-05 -2.18274258708135e-06 4.82464696412249e-06 8.23582087967416e-06 1.05073713464399e-05 -4.15319643772414e-07 -2.18274258708135e-06 3.19278035178009e-05 1.08349678277452e-05 1.46021412719992e-05 2.12431637752534e-05 -3.1148292701057e-06 4.82464696412249e-06 1.08349678277452e-05 3.65398664999097e-05 2027 2030 0 19 42 2053 2093 0 54 37 0 0 0 0 0 16 48 0 600 0 28 30 0 0 2420 +408 409 0.999999614053799 -2.18735844925315e-06 0.000878571265816157 0.00335085115387942 3.2684508017819e-06 0.999999242914114 -0.00123051229782309 -0.00335468104946511 -0.000878567909090781 0.0012305146944785 0.999998856975355 0.00235234075339223 2.56481159438636e-05 1.88375902959304e-05 -2.0112404296927e-06 3.05693291593954e-06 1.59697154737081e-06 1.89906984403548e-05 1.88375902959304e-05 2.68817257337076e-05 -2.88718388165067e-06 5.84238172814486e-06 -5.43396168438913e-07 2.3845454708649e-05 -2.0112404296927e-06 -2.88718388165067e-06 1.04155687696136e-05 2.93106760159723e-06 3.34329353578831e-06 7.32353956657127e-07 3.05693291593954e-06 5.84238172814486e-06 2.93106760159723e-06 2.6412054982813e-05 -5.17311384578689e-06 1.38917478128854e-06 1.59697154737081e-06 -5.43396168438913e-07 3.34329353578831e-06 -5.17311384578689e-06 2.66115323221242e-05 -8.37681004911556e-07 1.89906984403548e-05 2.3845454708649e-05 7.32353956657127e-07 1.38917478128854e-06 -8.37681004911556e-07 4.58470643757393e-05 2476 2472 0 16 18 2493 2536 0 53 17 0 0 0 0 0 15 47 0 510 0 37 36 0 0 2436 +409 410 0.999999903703967 -0.000393056703190047 0.000195188330060742 0.00296219398149628 0.000392879575370114 0.999999511786522 0.000906682059538439 -0.00178782753834592 -0.000195544612228332 -0.000906605286720322 0.999999569914487 -0.000629109302351456 2.19031463581109e-05 1.4636278014693e-05 -9.52275481362255e-07 2.01444309264936e-06 1.22325115621224e-06 1.60486799183728e-05 1.4636278014693e-05 2.42907558269365e-05 -2.07204255283751e-06 3.32513484782955e-06 7.51750070637832e-07 2.59898132737082e-05 -9.52275481362255e-07 -2.07204255283751e-06 8.81621313200313e-06 4.37440109409109e-06 3.50363125689879e-06 3.49433381395006e-07 2.01444309264936e-06 3.32513484782955e-06 4.37440109409109e-06 1.81532413336474e-05 9.37084106048724e-07 7.48828388594149e-06 1.22325115621224e-06 7.51750070637832e-07 3.50363125689879e-06 9.37084106048724e-07 1.95479281859475e-05 -9.02184271900149e-07 1.60486799183728e-05 2.59898132737082e-05 3.49433381395006e-07 7.48828388594149e-06 -9.02184271900149e-07 4.81539038591557e-05 2885 2881 0 12 32 2883 2920 0 52 31 0 0 0 0 0 9 39 0 500 0 24 23 0 0 2415 +410 411 0.999991119380912 -0.000257274059349406 0.0042065388824438 0.00150706791636153 0.000240331689501 0.99999186015891 0.00402763660246801 0.00443127743556105 -0.00420754084830406 -0.00402658986996495 0.999983041443218 0.00513575039492685 4.28087319536948e-05 1.97941612495406e-05 -4.8277509383194e-06 4.65457831621034e-06 -7.4692612512551e-07 2.15348161384363e-05 1.97941612495406e-05 4.2018818918997e-05 -6.19547709410353e-06 1.17697789584479e-05 1.24738337131118e-05 3.426448798492e-05 -4.8277509383194e-06 -6.19547709410353e-06 1.1696833170269e-05 3.41343884133196e-06 3.14639550075133e-06 -8.03967905430581e-07 4.65457831621034e-06 1.17697789584479e-05 3.41343884133196e-06 2.87832412593385e-05 -1.12004452292902e-06 1.35302861629845e-05 -7.4692612512551e-07 1.24738337131118e-05 3.14639550075133e-06 -1.12004452292902e-06 3.33482480780505e-05 6.94325731155137e-06 2.15348161384363e-05 3.426448798492e-05 -8.03967905430581e-07 1.35302861629845e-05 6.94325731155137e-06 5.92535970855652e-05 2565 2562 0 13 46 2568 2606 0 49 40 0 0 0 0 0 16 48 0 548 0 26 28 0 0 2420 +416 417 0.0146924717117381 0.999841530867118 -0.0100520857685227 0.265737844212306 -0.999571558801696 0.0149415397130259 0.0251684172277955 0.29151498060134 0.0253146224492505 0.00967799278270196 0.999632685713082 -0.0553972659799212 0.000650837008771795 -2.22811474042522e-05 0.000702010068269705 0.0017080551732617 -0.00025719582765485 0.000303040516732823 -2.22811474042522e-05 0.000199251783681876 -0.000244672717523558 -0.00037809891290385 -1.82005014296458e-05 3.31313845085582e-05 0.000702010068269705 -0.000244672717523558 0.00182948737565552 0.00296811139286441 -0.00113299767233818 0.000282925687325695 0.0017080551732617 -0.00037809891290385 0.00296811139286441 0.00729115972298634 -0.00107409034116313 0.000769561714105325 -0.00025719582765485 -1.82005014296458e-05 -0.00113299767233818 -0.00107409034116313 0.00179195943030335 -3.76275523403394e-05 0.000303040516732823 3.31313845085582e-05 0.000282925687325695 0.000769561714105325 -3.76275523403394e-05 0.000252154464081005 122 117 0 91 0 217 212 0 91 0 0 0 0 0 0 0 0 0 0 178 863 863 0 0 0 +417 418 0.999999312849286 -0.000685004147547377 -0.000951351813388447 -0.0012221158779578 0.000686228474012725 0.999998936097821 0.00128720383262368 -0.00262539027341386 0.000950469061279094 -0.00128785579282379 0.99999871901719 0.00037890970060188 2.66823417496544e-05 1.86270904731181e-05 -1.08197719510986e-05 8.25618386475518e-06 9.78077178913439e-06 1.66083758765199e-05 1.86270904731181e-05 1.97069621762941e-05 -1.09436349504059e-05 6.40910966077021e-06 7.44582243010545e-06 1.73438102652307e-05 -1.08197719510986e-05 -1.09436349504059e-05 1.6789936577445e-05 -1.73453565507547e-06 -8.71736921627959e-06 -6.10901383024245e-06 8.25618386475518e-06 6.40910966077021e-06 -1.73453565507547e-06 2.58869580162419e-05 4.26392787792727e-06 8.42849941476573e-06 9.78077178913439e-06 7.44582243010545e-06 -8.71736921627959e-06 4.26392787792727e-06 3.7669413677904e-05 9.03842318022945e-06 1.66083758765199e-05 1.73438102652307e-05 -6.10901383024245e-06 8.42849941476573e-06 9.03842318022945e-06 3.21404620727013e-05 2236 2235 0 13 47 2284 2327 0 48 48 0 0 0 0 0 18 50 0 629 0 51 49 0 0 2382 +419 420 0.99999069526593 -2.67747322055125e-05 0.00431377615032596 0.00375246923449377 2.86411856983919e-05 0.999999906013448 -0.000432611578741021 -0.000737173915514085 -0.00431376416182985 0.000432731105069108 0.999990602047113 -0.00358903165740858 7.28741893448004e-05 4.85111602080246e-05 -9.78488484188777e-06 2.23988398361115e-05 -2.3822896780268e-06 6.14802168964999e-05 4.85111602080246e-05 5.24531693027488e-05 -1.19324105127832e-05 2.4188701229137e-05 -1.43648693160997e-07 5.72023015575234e-05 -9.78488484188777e-06 -1.19324105127832e-05 1.48131533199161e-05 -4.37443696884184e-07 -2.28049803605069e-06 -6.01851899676439e-06 2.23988398361115e-05 2.4188701229137e-05 -4.37443696884184e-07 3.65979316744352e-05 -4.80517407548883e-08 2.69310042158498e-05 -2.3822896780268e-06 -1.43648693160997e-07 -2.28049803605069e-06 -4.80517407548883e-08 4.24127318227417e-05 -3.6306140468996e-06 6.14802168964999e-05 5.72023015575234e-05 -6.01851899676439e-06 2.69310042158498e-05 -3.6306140468996e-06 9.51697739125446e-05 2115 2114 0 20 57 2112 2142 0 48 43 0 0 0 0 0 15 46 0 613 0 26 25 0 0 2442 +420 421 0.999998253986647 0.000517032502540576 0.00179574526254032 0.00127245454401896 -0.000516944077671652 0.999999865149102 -4.97051222968926e-05 -0.000377444574985041 -0.00179577071954623 4.87767356326082e-05 0.999998386412875 0.00297222052482618 3.85606372087347e-05 2.12760816655805e-05 -1.05743374045583e-05 7.36261947656118e-06 9.59220526380123e-06 2.99091472778451e-05 2.12760816655805e-05 2.26661568629273e-05 -1.06932142135015e-05 5.60862560448176e-06 8.21676036686954e-06 1.78736745247149e-05 -1.05743374045583e-05 -1.06932142135015e-05 1.41016135436723e-05 -2.08851930359052e-07 -3.68682074509229e-06 -3.71350636452317e-06 7.36261947656118e-06 5.60862560448176e-06 -2.08851930359052e-07 2.09571616055487e-05 4.18365143191789e-06 6.64499195752107e-06 9.59220526380123e-06 8.21676036686954e-06 -3.68682074509229e-06 4.18365143191789e-06 3.54582417211085e-05 8.88666616006596e-06 2.99091472778451e-05 1.78736745247149e-05 -3.71350636452317e-06 6.64499195752107e-06 8.88666616006596e-06 4.78154464190369e-05 2954 2949 0 16 40 2950 2982 0 46 36 0 0 0 0 0 10 43 0 634 0 28 27 0 0 2451 +414 415 0.99999950132341 -0.000482146556095246 0.000874578544053759 0.00316806058463151 0.000479952295199356 0.99999674125923 0.00250741235436726 -0.000297600475232371 -0.000875784634260369 -0.00250699134799987 0.999996473991611 -0.00273243256693806 5.10145309944762e-05 4.365700224076e-05 -6.93608688801756e-06 1.4924172590509e-05 -5.31503465386338e-07 4.69983840928146e-05 4.365700224076e-05 4.91235502922436e-05 -8.63941544415598e-06 1.41928295094684e-05 7.7069227317266e-07 4.99016071191282e-05 -6.93608688801756e-06 -8.63941544415598e-06 1.22663244834366e-05 1.75042248510624e-06 -1.08375080709381e-06 -5.22890360945004e-06 1.4924172590509e-05 1.41928295094684e-05 1.75042248510624e-06 3.1112124185329e-05 -6.10648414525692e-06 1.90279252942689e-05 -5.31503465386338e-07 7.7069227317266e-07 -1.08375080709381e-06 -6.10648414525692e-06 4.33581558805234e-05 -5.15232942996522e-08 4.69983840928146e-05 4.99016071191282e-05 -5.22890360945004e-06 1.90279252942689e-05 -5.15232942996522e-08 7.58170515325188e-05 2663 2660 0 12 55 2722 2772 0 49 58 0 0 0 0 0 19 51 0 586 0 26 24 0 0 2474 +426 427 0.999999417075001 0.000593855663494285 -0.000901767768671809 -3.1183151302961e-05 -0.000594125726097512 0.999999778734106 -0.000299242977923434 0.00309011899518861 0.000901589862004157 0.000299778566917555 0.999999548634164 0.00133774474111937 3.70806274051811e-05 2.69908496210786e-05 -9.96329871643484e-06 7.6111112033644e-06 1.01251022067356e-05 2.6420052123196e-05 2.69908496210786e-05 3.51595283239902e-05 -1.04404481577333e-05 1.41222896872346e-05 2.89501949092678e-06 2.9876930193287e-05 -9.96329871643484e-06 -1.04404481577333e-05 1.2644603388848e-05 -1.62146866532608e-06 -2.47878815860056e-06 -5.22286008934576e-06 7.6111112033644e-06 1.41222896872346e-05 -1.62146866532608e-06 3.18538807220768e-05 -2.47927303787922e-06 1.12236581479015e-05 1.01251022067356e-05 2.89501949092678e-06 -2.47878815860056e-06 -2.47927303787922e-06 3.53069615449394e-05 7.11362266649126e-06 2.6420052123196e-05 2.9876930193287e-05 -5.22286008934576e-06 1.12236581479015e-05 7.11362266649126e-06 4.76324365240375e-05 2681 2681 0 21 38 2776 2827 0 51 38 0 0 0 0 0 23 54 0 655 0 30 27 0 0 2563 +415 416 0.999999300600438 0.000687417177422117 -0.000962422080047521 -0.0054781225175395 -0.00068787930912371 0.999999648245974 -0.000479927061567639 0.00611131871995328 0.000962091831405648 0.000480588756142371 0.99999942170671 0.00612827935205027 2.97626669808796e-05 2.10037709776777e-05 -1.06817419007818e-05 7.47683318016411e-06 9.09439727461223e-06 1.76836843790175e-05 2.10037709776777e-05 3.49407958166668e-05 -1.09473970908866e-05 1.43297661830034e-05 8.16395026341401e-06 2.67377277075769e-05 -1.06817419007818e-05 -1.09473970908866e-05 1.52323796500828e-05 -1.22239220541338e-06 -3.53056679624933e-06 -6.14442921031783e-06 7.47683318016411e-06 1.43297661830034e-05 -1.22239220541338e-06 2.79668928741121e-05 3.64172029576942e-06 7.29684246537516e-06 9.09439727461223e-06 8.16395026341401e-06 -3.53056679624933e-06 3.64172029576942e-06 3.30603842589427e-05 8.72779068673344e-06 1.76836843790175e-05 2.67377277075769e-05 -6.14442921031783e-06 7.29684246537516e-06 8.72779068673344e-06 4.93867583705738e-05 2743 2738 0 13 53 2758 2800 0 45 51 0 0 0 0 0 20 52 0 612 0 55 54 0 0 2448 +421 422 0.999999177288494 0.000174287956341968 0.00127084461837569 0.0016263704214488 -0.000174309903908474 0.999999984660807 1.71593229132473e-05 0.000966844618877099 -0.00127084160821863 -1.73808295993866e-05 0.999999192329431 -0.00413923297023416 5.17889929382722e-05 4.09587225698826e-05 -1.02218415939802e-05 1.21283186164413e-05 1.23573009855152e-05 4.24060723592592e-05 4.09587225698826e-05 4.85690651906447e-05 -1.10810309544507e-05 1.33755897736364e-05 9.01954079828233e-06 4.03715971262646e-05 -1.02218415939802e-05 -1.10810309544507e-05 1.48943757746417e-05 -3.30461881901841e-06 -3.54425774145185e-06 -3.54480108134579e-06 1.21283186164413e-05 1.33755897736364e-05 -3.30461881901841e-06 3.52940650325823e-05 -3.62103611462123e-06 1.06761897507907e-05 1.23573009855152e-05 9.01954079828233e-06 -3.54425774145185e-06 -3.62103611462123e-06 4.28256666968172e-05 8.94217993697614e-06 4.24060723592592e-05 4.03715971262646e-05 -3.54480108134579e-06 1.06761897507907e-05 8.94217993697614e-06 7.30005378171715e-05 2243 2245 0 22 23 2338 2380 0 47 21 0 0 0 0 0 11 42 0 598 0 55 53 0 0 2573 +422 423 0.999999923693873 -0.000374596511136353 -0.000110858925232359 -0.00210402113915851 0.000374636293895312 0.999999865363066 0.000359056398541353 0.000294938286364516 0.000110724409032458 -0.000359097902920045 0.999999929394398 -0.00068435981056946 2.87257143060147e-05 1.95713616496761e-05 -6.7654843706134e-06 6.87475801183352e-06 4.98037883274769e-06 1.97927898386691e-05 1.95713616496761e-05 2.56890616652643e-05 -8.1062108561484e-06 6.23911926953389e-06 5.68789988341102e-06 1.95906452413617e-05 -6.7654843706134e-06 -8.1062108561484e-06 1.45056173062822e-05 -8.42671754413609e-07 -2.584564152872e-06 -1.18171172358557e-06 6.87475801183352e-06 6.23911926953389e-06 -8.42671754413609e-07 2.79717590381969e-05 2.8897676059847e-06 6.31529868096986e-06 4.98037883274769e-06 5.68789988341102e-06 -2.584564152872e-06 2.8897676059847e-06 3.32673290356977e-05 5.62064220339618e-06 1.97927898386691e-05 1.95906452413617e-05 -1.18171172358557e-06 6.31529868096986e-06 5.62064220339618e-06 3.86427874415711e-05 2165 2165 0 15 39 2221 2258 0 53 32 0 0 0 0 0 22 54 0 614 0 54 53 0 0 2478 +429 430 0.997187997229121 -0.0730580474732488 -0.0166919106627001 -0.00106961905330412 0.0723124910803797 0.996514429075961 -0.0415920217969909 -0.00316970086930022 0.0196723617271805 0.0402680312755403 0.998995237146438 -0.00912074095135402 4.8220105376174e-05 2.24894068107792e-05 -4.99917806952799e-06 7.30406545834878e-06 -3.758664871628e-06 3.31253825779411e-05 2.24894068107792e-05 2.88039403931804e-05 -5.17597060045359e-06 4.63368814441978e-06 -1.60401949824096e-06 2.46821129562515e-05 -4.99917806952799e-06 -5.17597060045359e-06 1.00177242218881e-05 1.50851803755328e-06 2.38240650535488e-06 -8.88525763420868e-07 7.30406545834878e-06 4.63368814441978e-06 1.50851803755328e-06 3.69329216458151e-05 -1.82439802059777e-05 1.64869610430402e-05 -3.758664871628e-06 -1.60401949824096e-06 2.38240650535488e-06 -1.82439802059777e-05 4.21919813395079e-05 -1.17655160341578e-05 3.31253825779411e-05 2.46821129562515e-05 -8.88525763420868e-07 1.64869610430402e-05 -1.17655160341578e-05 6.98909551701485e-05 2680 2660 0 0 144 2704 2684 0 0 156 0 0 0 0 0 129 144 0 491 0 0 0 0 0 2494 +418 419 0.999997262221168 0.000518899608672208 -0.00228173034421816 -0.00606478460459502 -0.00051685469416556 0.999999464385588 0.000896710523030987 0.00915396189360488 0.00228219442482999 -0.00089552874499667 0.999996994803921 0.000122268794111239 3.24587517368036e-05 2.22159237179269e-05 -6.71440863309268e-06 8.57620700571038e-06 3.81423644882397e-06 2.4586291218771e-05 2.22159237179269e-05 2.906557195885e-05 -7.42484362190047e-06 6.50899725725247e-06 2.04184505293445e-06 1.93650592787246e-05 -6.71440863309268e-06 -7.42484362190047e-06 1.29470317371577e-05 9.01656209292064e-07 -9.19116721189859e-07 -2.29811827231901e-06 8.57620700571038e-06 6.50899725725247e-06 9.01656209292064e-07 2.76071662222871e-05 -4.49405486752397e-06 1.20250571576328e-05 3.81423644882397e-06 2.04184505293445e-06 -9.19116721189859e-07 -4.49405486752397e-06 3.99800531905812e-05 -3.14379485112437e-06 2.4586291218771e-05 1.93650592787246e-05 -2.29811827231901e-06 1.20250571576328e-05 -3.14379485112437e-06 4.74419180371245e-05 2823 2816 0 15 26 2818 2847 0 49 29 0 0 0 0 0 15 47 0 591 0 32 30 0 0 2455 +424 425 0.999991940121863 -7.76527158271548e-05 0.00401418252811214 -0.00191681782088834 6.44472618098558e-05 0.999994586766217 0.0032897241242992 0.00513984434268889 -0.00401441625441624 -0.00328943890645131 0.999986531936214 0.00183593897416968 5.53322349341629e-05 1.86540535831514e-05 -7.34017315638791e-06 9.59199625909813e-06 -4.20759826679614e-08 2.52576413003609e-05 1.86540535831514e-05 3.73593954645296e-05 -9.86978197357451e-06 1.08000482069428e-05 1.02822611116694e-05 2.77572416950251e-05 -7.34017315638791e-06 -9.86978197357451e-06 1.40077189977667e-05 -1.23511052895568e-06 -3.38466699996649e-06 -3.1609981241027e-06 9.59199625909813e-06 1.08000482069428e-05 -1.23511052895568e-06 2.97921824681278e-05 -6.01464458436785e-07 1.68131352930802e-05 -4.20759826679614e-08 1.02822611116694e-05 -3.38466699996649e-06 -6.01464458436785e-07 4.55478967297636e-05 -2.06714354224077e-06 2.52576413003609e-05 2.77572416950251e-05 -3.1609981241027e-06 1.68131352930802e-05 -2.06714354224077e-06 5.12090923466574e-05 2895 2896 0 17 45 2897 2934 0 43 40 0 0 0 0 0 12 42 0 619 0 27 25 0 0 2185 +423 424 0.99999979539456 0.000293322341277167 0.000568482931145199 -0.00261941997364625 -0.000294023248361119 0.999999196319701 0.00123325191342234 0.00733737013419252 -0.000568120733928038 -0.00123341880829034 0.999999077958012 -0.00463604905539726 2.26223966734424e-05 1.6346269325231e-05 -6.87896265106746e-06 2.71431906291591e-06 1.1315982268849e-05 1.42952618981763e-05 1.6346269325231e-05 2.17178686704242e-05 -7.7479527772794e-06 3.81235531803284e-06 8.19674929827506e-06 1.83267670539557e-05 -6.87896265106746e-06 -7.7479527772794e-06 1.21040406181698e-05 -3.42035542666615e-08 1.3522516256888e-07 -2.01141309267362e-06 2.71431906291591e-06 3.81235531803284e-06 -3.42035542666615e-08 2.62870677781507e-05 -2.48241856728369e-06 6.82825689299004e-06 1.1315982268849e-05 8.19674929827506e-06 1.3522516256888e-07 -2.48241856728369e-06 3.87436197780669e-05 1.02696773920369e-05 1.42952618981763e-05 1.83267670539557e-05 -2.01141309267362e-06 6.82825689299004e-06 1.02696773920369e-05 3.64803231154579e-05 2663 2664 0 16 43 2664 2694 0 47 36 0 0 0 0 0 12 42 0 621 0 57 60 0 0 2466 +427 428 0.999999438130104 0.00018084041838412 0.00104452679208917 0.000732009011783923 -0.000181335871150697 0.99999987109877 0.000474257045117657 -0.000695359365323063 -0.00104444089260592 -0.000474446188822684 0.999999342021802 0.000929302414117513 4.55391065082467e-05 1.93813193784519e-05 -9.48297693998585e-06 5.01615502698749e-06 5.6452568954039e-06 3.21781505852095e-05 1.93813193784519e-05 2.38505623899686e-05 -9.20359233713893e-06 5.4843395754717e-06 6.08602988993432e-06 2.26900937790844e-05 -9.48297693998585e-06 -9.20359233713893e-06 1.42716471347393e-05 -1.26880086046919e-06 -5.25858488106674e-06 -3.693377276091e-06 5.01615502698749e-06 5.4843395754717e-06 -1.26880086046919e-06 2.11023465079968e-05 8.28968593868921e-06 6.11676511390026e-06 5.6452568954039e-06 6.08602988993432e-06 -5.25858488106674e-06 8.28968593868921e-06 4.08969533754033e-05 4.54303040111927e-06 3.21781505852095e-05 2.26900937790844e-05 -3.693377276091e-06 6.11676511390026e-06 4.54303040111927e-06 5.95197083198328e-05 3180 3180 0 16 55 3179 3233 0 50 50 0 0 0 0 0 17 50 0 635 0 30 30 0 0 2429 +425 426 0.999998069287029 0.000460778449135654 0.0019102631848898 0.000481324142672799 -0.000464340990232889 0.999998153221367 0.00186492393929579 0.00917622516188329 -0.00190940034029606 -0.00186580735216183 0.999996436470283 -2.17453982868333e-05 4.83365158853199e-05 3.13750821752858e-05 -1.19449947268299e-05 1.15807690663362e-05 1.42237986217997e-05 2.96313175759295e-05 3.13750821752858e-05 3.76753881512044e-05 -1.32413028731058e-05 1.31271081005682e-05 1.52288399496217e-05 3.00463134053729e-05 -1.19449947268299e-05 -1.32413028731058e-05 1.68651836139136e-05 -4.26706279814687e-06 -5.69549468132694e-06 -7.14279366925786e-06 1.15807690663362e-05 1.31271081005682e-05 -4.26706279814687e-06 3.84435140205134e-05 -2.26782941930922e-06 1.30956928920448e-05 1.42237986217997e-05 1.52288399496217e-05 -5.69549468132694e-06 -2.26782941930922e-06 5.33883458609524e-05 1.27469757016562e-05 2.96313175759295e-05 3.00463134053729e-05 -7.14279366925786e-06 1.30956928920448e-05 1.27469757016562e-05 5.45994495824364e-05 2589 2589 0 18 32 2585 2616 0 47 42 0 0 0 0 0 13 42 0 641 0 29 29 0 0 2195 +430 431 0.99126530909117 -0.131865084633961 -0.00216482028485324 -0.00591906065754108 0.131299643199124 0.988290795922851 -0.0777284143023714 -0.0116700852544475 0.0123891358927933 0.0767652404976153 0.996972219855284 -0.0223404826814149 9.29392577657781e-05 7.04729352595704e-05 -8.74500355245117e-06 1.11638563267469e-05 8.21542553141674e-06 8.747425913156e-05 7.04729352595704e-05 8.87694290716891e-05 -7.62309842912729e-06 1.21276006055761e-05 5.6453289094753e-06 7.33013095755737e-05 -8.74500355245117e-06 -7.62309842912729e-06 1.19036465123642e-05 -1.28324560887681e-06 3.51001572500513e-06 -8.15085801153124e-06 1.11638563267469e-05 1.21276006055761e-05 -1.28324560887681e-06 3.48488515059041e-05 -1.62107554099648e-05 1.88491234679778e-05 8.21542553141674e-06 5.6453289094753e-06 3.51001572500513e-06 -1.62107554099648e-05 4.39781619026736e-05 -3.26866700264685e-06 8.747425913156e-05 7.33013095755737e-05 -8.15085801153124e-06 1.88491234679778e-05 -3.26866700264685e-06 0.000125362007294276 2231 2210 0 0 243 2226 2205 0 0 222 0 0 0 0 0 154 154 0 505 0 9 27 0 0 2792 +428 429 0.999971360579508 -0.00756667510801605 -0.000153129280867091 0.00223477897545709 0.00756698267417873 0.999969124928355 0.00211895333310572 0.000109085829328375 0.000137091121548914 -0.00212005137412544 0.999997743291551 -0.0056774858239405 2.38488594319076e-05 1.1314355047174e-05 -3.14991847977762e-06 4.26024639377429e-06 -1.55611684363467e-06 1.06128951238688e-05 1.1314355047174e-05 2.33452009261877e-05 -5.18266025461662e-06 5.90228416552432e-06 3.49427110363456e-06 1.13794981127571e-05 -3.14991847977762e-06 -5.18266025461662e-06 1.03753108197076e-05 1.8372350704246e-06 1.29479606339195e-06 2.71761953652156e-07 4.26024639377429e-06 5.90228416552432e-06 1.8372350704246e-06 2.56878098164183e-05 -1.21483597868639e-06 7.38025060153712e-06 -1.55611684363467e-06 3.49427110363456e-06 1.29479606339195e-06 -1.21483597868639e-06 3.18055446473256e-05 -2.8966848972145e-06 1.06128951238688e-05 1.13794981127571e-05 2.71761953652156e-07 7.38025060153712e-06 -2.8966848972145e-06 4.41323658432576e-05 2697 2692 0 4 41 2708 2725 0 36 40 0 0 0 0 0 22 54 0 618 0 21 18 0 0 2646 +435 436 0.997540656082277 -0.0653189626556663 0.0254179578355118 -0.0343983433440827 0.064416090647159 0.997314343096191 0.034852092051251 0.0286263647161418 -0.0276261964207377 -0.0331290532946469 0.999069196351846 -0.112447489194247 6.64907788272287e-05 -3.71400776485766e-05 -7.06585610952567e-06 -5.11038073388926e-07 -7.1282918688853e-06 -4.45102818606716e-05 -3.71400776485766e-05 6.65328715384228e-05 6.37842517184701e-06 1.60200569212462e-05 -1.39328707432363e-05 4.75955905582818e-05 -7.06585610952567e-06 6.37842517184701e-06 1.17987361499473e-05 6.43008974360446e-07 2.01316277922935e-06 6.53926794233359e-06 -5.11038073388926e-07 1.60200569212462e-05 6.43008974360446e-07 3.78042814410165e-05 -1.36407349931472e-05 1.18243201628523e-05 -7.1282918688853e-06 -1.39328707432363e-05 2.01316277922935e-06 -1.36407349931472e-05 6.39376847286134e-05 -4.43461401595399e-06 -4.45102818606716e-05 4.75955905582818e-05 6.53926794233359e-06 1.18243201628523e-05 -4.43461401595399e-06 0.000102919240831072 1200 1204 0 0 113 1200 1204 0 0 88 0 0 0 0 0 0 0 0 2282 0 0 0 0 0 2700 +436 437 0.999085799941954 -0.0352918705658735 0.0241256756652875 -0.0397665840908909 0.0340934224284711 0.998245941455792 0.0484012284364098 0.0386652498293138 -0.0257915277069591 -0.0475344531787348 0.998536565609663 -0.101087010832681 3.15493005926548e-05 -1.03434740878116e-05 -5.15724267328021e-06 1.22517555853146e-06 9.86149465153931e-06 -1.70431696718168e-05 -1.03434740878116e-05 2.97091191628712e-05 1.97157968360939e-06 2.66790469300564e-06 -7.0262175284596e-06 1.73726377954863e-05 -5.15724267328021e-06 1.97157968360939e-06 1.08181251957814e-05 5.42152905573366e-07 -1.5247450360771e-06 7.00938915321359e-07 1.22517555853146e-06 2.66790469300564e-06 5.42152905573366e-07 2.478481785342e-05 -4.41483046782255e-06 1.56020107478058e-06 9.86149465153931e-06 -7.0262175284596e-06 -1.5247450360771e-06 -4.41483046782255e-06 5.40141419443616e-05 -5.18292723370119e-06 -1.70431696718168e-05 1.73726377954863e-05 7.00938915321359e-07 1.56020107478058e-06 -5.18292723370119e-06 6.60507848303197e-05 1225 1247 0 0 102 1225 1247 0 0 121 0 0 0 0 0 0 0 0 2411 0 0 0 0 0 2542 +431 432 0.989524973201997 -0.136266074477148 0.0476642880590484 -0.0168422695916674 0.137683584995697 0.990085322230214 -0.0278259793543149 -0.0103840934397466 -0.043399975026722 0.0340970915311352 0.998475753594847 -0.0448533127391719 7.1959429193435e-05 -3.60540489674344e-06 -6.07871627320472e-06 -8.98488128198767e-06 2.11884684943075e-06 1.8796358386947e-05 -3.60540489674344e-06 4.83336529033446e-05 -2.27506715293211e-06 1.38652155102332e-05 -6.63723046797134e-06 9.7470513289183e-06 -6.07871627320472e-06 -2.27506715293211e-06 1.09868807731753e-05 9.76322333914696e-07 3.32516507587555e-06 -4.94016711827384e-07 -8.98488128198767e-06 1.38652155102332e-05 9.76322333914696e-07 3.32378931190748e-05 2.17137372488451e-06 2.74457142093246e-06 2.11884684943075e-06 -6.63723046797134e-06 3.32516507587555e-06 2.17137372488451e-06 3.58000400750358e-05 -5.05708458003929e-06 1.8796358386947e-05 9.7470513289183e-06 -4.94016711827384e-07 2.74457142093246e-06 -5.05708458003929e-06 4.40501176212601e-05 2568 2551 0 0 275 2560 2543 0 0 262 0 0 0 0 0 0 0 0 900 0 0 0 0 0 2989 +432 433 0.992109530235425 -0.12493047459014 0.010538336430682 -0.0159334003157414 0.124975853805928 0.992152655435944 -0.00376088777878537 -0.00891400337498066 -0.00998578897849455 0.0050482502005975 0.999937397634666 -0.0609323231337938 4.49673969701825e-05 1.57394228096756e-05 -7.888612565383e-06 -1.42052516629327e-06 9.61661143112576e-07 1.07854331571516e-05 1.57394228096756e-05 2.9559200522878e-05 -1.09264275195792e-06 -3.7071031703765e-07 9.92382754828002e-07 1.45084425622242e-05 -7.888612565383e-06 -1.09264275195792e-06 1.46785026890279e-05 2.50933736934669e-06 1.95322471620312e-07 2.3236800919986e-06 -1.42052516629327e-06 -3.7071031703765e-07 2.50933736934669e-06 2.83579115917248e-05 6.31204151867887e-06 2.57811091689302e-06 9.61661143112576e-07 9.92382754828002e-07 1.95322471620312e-07 6.31204151867887e-06 4.35473050527918e-05 -2.82188523499125e-06 1.07854331571516e-05 1.45084425622242e-05 2.3236800919986e-06 2.57811091689302e-06 -2.82188523499125e-06 4.7638784217895e-05 2383 2355 0 0 257 2383 2355 0 0 222 0 0 0 0 0 0 0 0 1401 0 0 0 0 0 2883 +433 434 0.992392557182732 -0.111251743572145 -0.0527262932555921 -0.0161947794401591 0.11382479832016 0.992311411064002 0.0486001929990408 0.00146023644847376 0.046914046251545 -0.0542320295058798 0.997425666022276 -0.0788052061946188 4.6002187229117e-05 -1.11221682443928e-05 -4.11229261246406e-06 -1.98700980665631e-06 -7.58163749040511e-07 6.47409529781751e-06 -1.11221682443928e-05 4.49568104590308e-05 -1.70445442628762e-06 9.13735866959331e-06 -8.00823768976071e-06 -2.76999855006061e-06 -4.11229261246406e-06 -1.70445442628762e-06 1.03918950234541e-05 1.16463262541954e-06 9.65496123152703e-07 3.75181209988853e-07 -1.98700980665631e-06 9.13735866959331e-06 1.16463262541954e-06 2.85642910056416e-05 -1.92668404380529e-06 2.25703485436713e-06 -7.58163749040511e-07 -8.00823768976071e-06 9.65496123152703e-07 -1.92668404380529e-06 5.61748570225591e-05 -3.87144826844262e-06 6.47409529781751e-06 -2.76999855006061e-06 3.75181209988853e-07 2.25703485436713e-06 -3.87144826844262e-06 3.98872135614577e-05 2273 2266 0 0 295 2273 2266 0 0 259 0 0 0 0 0 0 0 0 1693 0 0 0 0 0 2941 +437 438 0.997339750124906 -0.0728263625583357 -0.00312149600526762 -0.0367910470985004 0.0728739010677798 0.99714674137079 0.0196918946975258 0.0480669844574992 0.00167850050715196 -0.0198669849281877 0.999801223016811 -0.100417141679022 2.9186829695186e-05 1.57775874913805e-06 -2.13631955408822e-06 2.23521778995938e-06 8.11676038527794e-07 -1.38722442953493e-06 1.57775874913805e-06 3.59249480234722e-05 7.9492819384492e-07 3.54380333509796e-06 5.54874238889336e-06 -8.11246536289007e-06 -2.13631955408822e-06 7.9492819384492e-07 1.1040425765342e-05 -1.10747776361308e-06 1.65511956983117e-06 -2.24587894468287e-06 2.23521778995938e-06 3.54380333509796e-06 -1.10747776361308e-06 2.3973348904832e-05 8.29044061086282e-06 1.31845822479378e-06 8.11676038527794e-07 5.54874238889336e-06 1.65511956983117e-06 8.29044061086282e-06 5.46749116783678e-05 -6.7600987321429e-06 -1.38722442953493e-06 -8.11246536289007e-06 -2.24587894468287e-06 1.31845822479378e-06 -6.7600987321429e-06 6.17334297585959e-05 919 919 0 0 173 919 919 0 0 185 0 0 0 0 0 0 0 0 2355 0 0 0 0 0 2464 +434 435 0.996962988117191 -0.0778673107445134 -0.00121747355564732 -0.0226658121390503 0.0777454257906231 0.996066953241092 -0.0425002756419706 0.0287977036306338 0.00452206734536602 0.0422765487998506 0.999095713297028 -0.0914603948100569 4.01660295710758e-05 -1.06661793570667e-05 -7.74794861464899e-06 5.33164508306114e-07 -6.7170219129132e-07 -7.26549561080267e-06 -1.06661793570667e-05 2.97295800853161e-05 2.00162025877331e-06 -1.16114980457012e-06 -3.4829833166438e-07 1.13353653153975e-05 -7.74794861464899e-06 2.00162025877331e-06 1.24980873022894e-05 2.85895730061122e-06 1.11853774315625e-06 1.73807275880365e-07 5.33164508306114e-07 -1.16114980457012e-06 2.85895730061122e-06 2.3040794011768e-05 1.50408086635666e-06 3.87568697933586e-06 -6.7170219129132e-07 -3.4829833166438e-07 1.11853774315625e-06 1.50408086635666e-06 4.20352327079058e-05 2.47365869266943e-06 -7.26549561080267e-06 1.13353653153975e-05 1.73807275880365e-07 3.87568697933586e-06 2.47365869266943e-06 3.90351552908993e-05 1940 1897 0 0 156 1940 1897 0 0 155 0 0 0 0 0 0 0 0 2066 0 0 0 0 0 2927 +439 440 0.99294535965887 -0.118496697976441 -0.00424797605904769 -0.0375413138579308 0.118501793133496 0.992953366857785 0.000967610425774796 0.0648429442196336 0.00410338348978078 -0.00146417706241594 0.999990509169695 -0.0642029732037662 2.31644200048119e-05 -9.57086899734346e-06 1.37538071397735e-06 2.38395973097816e-06 2.73430765837945e-06 8.22380579258794e-06 -9.57086899734346e-06 3.53807169025731e-05 -7.95562601909711e-08 -4.16459359576946e-06 -9.18504030521669e-06 1.66236619667804e-06 1.37538071397735e-06 -7.95562601909711e-08 1.18508109410631e-05 1.01151545010416e-06 4.54721700795478e-06 -8.09446439702291e-07 2.38395973097816e-06 -4.16459359576946e-06 1.01151545010416e-06 2.62943477502436e-05 1.68252448925159e-05 -1.0217121012163e-06 2.73430765837945e-06 -9.18504030521669e-06 4.54721700795478e-06 1.68252448925159e-05 5.71326404889812e-05 -8.89836714052963e-06 8.22380579258794e-06 1.66236619667804e-06 -8.09446439702291e-07 -1.0217121012163e-06 -8.89836714052963e-06 6.12291236305952e-05 283 239 0 0 252 283 239 0 0 238 0 0 0 0 0 366 246 0 2702 0 0 0 0 0 2607 +438 439 0.99415737958323 -0.0953923708157846 -0.0505113869374937 -0.025729383077944 0.0963159981026814 0.995219403853273 0.0161730239417199 0.0624707182251176 0.0487271292986734 -0.0209435857502726 0.998592526051658 -0.0786110425211278 5.61051021713005e-05 -7.75731104464584e-06 -5.3317026775808e-06 7.91058113461147e-06 -6.56643371121261e-06 7.39689551419077e-05 -7.75731104464584e-06 4.01366708963305e-05 4.42102363421712e-07 -1.04689043675199e-07 -2.53853510976267e-06 7.40887496924965e-06 -5.3317026775808e-06 4.42102363421712e-07 1.31386193377774e-05 -1.97361746911059e-06 1.01773641581215e-06 -8.27423331616272e-06 7.91058113461147e-06 -1.04689043675199e-07 -1.97361746911059e-06 2.62104935675525e-05 3.53233128771881e-07 1.59716219748612e-05 -6.56643371121261e-06 -2.53853510976267e-06 1.01773641581215e-06 3.53233128771881e-07 4.82827583313306e-05 -2.96165139355163e-05 7.39689551419077e-05 7.40887496924965e-06 -8.27423331616272e-06 1.59716219748612e-05 -2.96165139355163e-05 0.000262388907670926 349 323 0 0 249 349 323 0 0 257 0 0 0 0 0 0 0 0 2444 0 0 0 0 0 2731 +443 444 0.995256478561893 -0.0971873410370204 -0.0043775133048839 0.00160294182289151 0.0971516718906159 0.995239541205273 -0.0077335806956761 0.0715091080484853 0.00510828047768062 0.00727161355355994 0.999960513773864 -0.0335351485255796 3.48699628376095e-05 -1.54265358377058e-05 -1.80788633477437e-06 4.93582624511577e-06 5.80024118423567e-06 -1.06072828334762e-05 -1.54265358377058e-05 4.75897100752043e-05 3.94960939039842e-06 8.4130175440883e-06 -7.53359072822561e-07 -1.06441213115644e-05 -1.80788633477437e-06 3.94960939039842e-06 1.98122966926472e-05 7.93044223395588e-06 -1.03553491936148e-05 -3.43381293504668e-06 4.93582624511577e-06 8.4130175440883e-06 7.93044223395588e-06 4.47711669796044e-05 8.88184497603049e-07 -8.40048145620111e-06 5.80024118423567e-06 -7.53359072822561e-07 -1.03553491936148e-05 8.88184497603049e-07 5.07106596993033e-05 -2.10285067134963e-08 -1.06072828334762e-05 -1.06441213115644e-05 -3.43381293504668e-06 -8.40048145620111e-06 -2.10285067134963e-08 0.00012291913006482 1948 1948 0 0 0 1978 1978 0 0 0 0 0 0 0 0 126 139 0 3491 0 0 0 0 0 1664 +441 442 0.992395061272251 -0.123069411449723 -0.00244178784175713 -0.0124203085606567 0.123004383891729 0.992235648752716 -0.018393990532021 0.0793783940699313 0.00468656653226998 0.0179537547519965 0.999827834571755 -0.0371578310538328 1.97330040210854e-05 -6.95472476274701e-06 -2.24048669502107e-06 2.55090669296207e-06 2.39535592399165e-06 -3.78483428946292e-06 -6.95472476274701e-06 3.18631463165639e-05 4.38948187965879e-06 1.95538506611847e-06 1.13397536955039e-06 2.94300427640084e-06 -2.24048669502107e-06 4.38948187965879e-06 1.67973350512413e-05 -1.1893565969166e-07 -6.46690521572427e-06 -1.27677630757602e-06 2.55090669296207e-06 1.95538506611847e-06 -1.1893565969166e-07 3.13516924492004e-05 1.44600695919515e-05 -8.31395489904949e-07 2.39535592399165e-06 1.13397536955039e-06 -6.46690521572427e-06 1.44600695919515e-05 5.71083575445235e-05 -6.91305379387687e-06 -3.78483428946292e-06 2.94300427640084e-06 -1.27677630757602e-06 -8.31395489904949e-07 -6.91305379387687e-06 7.41809430308933e-05 934 934 0 0 0 877 877 0 0 0 0 0 0 0 0 295 299 0 3078 0 0 0 0 0 2252 +445 446 0.997166001557971 -0.0752326200782449 -0.000134955739899779 0.0277873975197698 0.0752299425321793 0.997111831010381 0.0104140388769204 0.0812524124628844 -0.000648909465390593 -0.010394678219525 0.9999457633198 0.02471920733241 6.90509676860303e-05 -3.82204515077114e-05 -1.7361153481097e-06 2.13975767907555e-06 -8.56724160780981e-07 7.14495217081005e-06 -3.82204515077114e-05 7.85202598622526e-05 6.58571129141916e-07 -1.67164984959071e-05 -4.01567159899072e-06 -4.5517894704424e-05 -1.7361153481097e-06 6.58571129141916e-07 1.4890662626702e-05 5.41360017882679e-06 1.19659385054294e-06 -3.68725335191768e-06 2.13975767907555e-06 -1.67164984959071e-05 5.41360017882679e-06 7.00566204929106e-05 1.79805753704271e-05 2.07462151580739e-05 -8.56724160780981e-07 -4.01567159899072e-06 1.19659385054294e-06 1.79805753704271e-05 3.4029430065738e-05 1.83443890990509e-05 7.14495217081005e-06 -4.5517894704424e-05 -3.68725335191768e-06 2.07462151580739e-05 1.83443890990509e-05 0.000238589890982471 2538 2538 0 0 0 2538 2538 0 0 0 0 0 0 0 0 45 77 0 3652 0 0 0 0 0 1363 +440 441 0.990881483450535 -0.134533058714135 0.00739877475571643 -0.0323969820788598 0.134633825635493 0.990775354500916 -0.0154249767693849 0.0756387903072063 -0.00525535437608755 0.0162804492138156 0.999853653403226 -0.0557684395696346 1.70860102515608e-05 -4.60829786610204e-06 -6.43437454629867e-07 3.06222085460695e-07 -2.35005459338814e-06 -3.89581715109381e-06 -4.60829786610204e-06 3.60587774562542e-05 -1.74892081985887e-06 -5.26591294404547e-06 -7.45878565572136e-06 -6.85000302452312e-06 -6.43437454629867e-07 -1.74892081985887e-06 1.07631083439074e-05 5.38814203494942e-06 4.11258631687712e-06 -1.52435638298433e-06 3.06222085460695e-07 -5.26591294404547e-06 5.38814203494942e-06 2.75897616770898e-05 1.39267556443853e-05 -4.26542887205701e-06 -2.35005459338814e-06 -7.45878565572136e-06 4.11258631687712e-06 1.39267556443853e-05 5.59930735107303e-05 -7.63875702239066e-06 -3.89581715109381e-06 -6.85000302452312e-06 -1.52435638298433e-06 -4.26542887205701e-06 -7.63875702239066e-06 4.1603955074626e-05 369 369 0 0 29 199 199 0 0 10 0 0 0 0 0 398 352 0 2829 0 0 0 0 0 2692 +447 448 0.997530118347937 -0.0678983302258439 -0.0179855425631939 0.0321164078324779 0.0680678973030957 0.997640194145662 0.00898912574958841 0.0712992397183742 0.0173327535459727 -0.0101911617369634 0.999797837503645 -0.0205206341824047 2.71801995714303e-05 -9.44927232993461e-06 -5.02208058133902e-07 -6.96080090766058e-06 -1.25851231026301e-07 -2.01665864603342e-05 -9.44927232993461e-06 1.82258758876969e-05 1.29710227580283e-06 -6.37816373018089e-06 -1.94310128404548e-06 -7.53250222035083e-06 -5.02208058133902e-07 1.29710227580283e-06 1.0980818064273e-05 1.64448777204178e-06 1.70750983501439e-06 5.04884848513563e-06 -6.96080090766058e-06 -6.37816373018089e-06 1.64448777204178e-06 5.1148874573097e-05 8.91917632567157e-06 1.40031033237566e-05 -1.25851231026301e-07 -1.94310128404548e-06 1.70750983501439e-06 8.91917632567157e-06 2.0794568326601e-05 -8.24275624652448e-06 -2.01665864603342e-05 -7.53250222035083e-06 5.04884848513563e-06 1.40031033237566e-05 -8.24275624652448e-06 0.000121622253475658 3190 3324 0 0 203 3227 3361 0 0 316 0 0 0 0 0 210 238 0 3767 0 0 0 0 0 2049 +442 443 0.993233825838709 -0.113558027297483 0.0243134046588669 -0.00387474197644977 0.114266197291091 0.992995854564799 -0.030041121379841 0.0890056606832823 -0.0207316995549123 0.0326160582141527 0.999252915622534 -0.0266721361095578 2.07255094205967e-05 -6.9960371779166e-06 5.71028477108351e-07 4.42441133072252e-06 -4.79108460787172e-08 -6.15772327910794e-06 -6.9960371779166e-06 3.57994236072069e-05 5.9180143188266e-06 -1.21705984261486e-06 -6.89093512029018e-06 2.95042428656113e-06 5.71028477108351e-07 5.9180143188266e-06 1.33369883460315e-05 8.82656569049242e-07 -5.00127815792366e-06 7.83522560370864e-07 4.42441133072252e-06 -1.21705984261486e-06 8.82656569049242e-07 4.13516791098394e-05 1.54429701935002e-05 9.78198821951095e-06 -4.79108460787172e-08 -6.89093512029018e-06 -5.00127815792366e-06 1.54429701935002e-05 5.43361165485787e-05 2.04651800904525e-06 -6.15772327910794e-06 2.95042428656113e-06 7.83522560370864e-07 9.78198821951095e-06 2.04651800904525e-06 6.98999380898021e-05 1453 1453 0 0 0 1466 1466 0 0 0 0 0 0 0 0 264 299 0 3272 0 0 0 0 0 1871 +446 447 0.996867631660432 -0.077881237996993 -0.0137636374471675 0.0392073387919775 0.0782684489657211 0.996472312706213 0.0302816760835936 0.077866960502456 0.0113567092162146 -0.0312640812752766 0.999446638084191 -0.00432314505228844 4.99466081295344e-05 -3.1082279861111e-05 1.94077557506674e-06 -8.72323210580733e-06 3.65467240515139e-08 -9.22676767365035e-06 -3.1082279861111e-05 5.49910011713823e-05 -1.57906254158637e-07 9.47986539194562e-06 1.97619269676769e-06 7.47629550126704e-06 1.94077557506674e-06 -1.57906254158637e-07 1.31316348872243e-05 -5.632573742559e-07 -2.23069668506714e-06 3.64567822796989e-06 -8.72323210580733e-06 9.47986539194562e-06 -5.632573742559e-07 4.98105741859262e-05 1.72498572465017e-05 2.39484166926507e-05 3.65467240515139e-08 1.97619269676769e-06 -2.23069668506714e-06 1.72498572465017e-05 3.8135939628763e-05 -3.90589822550318e-06 -9.22676767365035e-06 7.47629550126704e-06 3.64567822796989e-06 2.39484166926507e-05 -3.90589822550318e-06 0.000172875376497643 2888 2914 0 0 0 2904 2930 0 0 0 0 0 0 0 0 134 168 0 3748 0 0 0 0 0 1773 +444 445 0.997165801455219 -0.0728598290354992 -0.0187565914037745 0.00790581368328809 0.0730720260179089 0.997267241159474 0.0108870897769009 0.0776443827900352 0.0179121026629586 -0.0122268157379622 0.999764803118764 -0.0141401670203298 3.13197350638144e-05 -1.19641124900846e-05 2.16308866492079e-06 2.78470847301469e-06 -7.43371193871381e-06 3.09484441064669e-06 -1.19641124900846e-05 5.05919443796501e-05 -2.34954947563572e-06 -5.67032953559741e-06 1.14643447792645e-05 -6.25807895650071e-06 2.16308866492079e-06 -2.34954947563572e-06 1.54674610767783e-05 7.41989817283598e-06 -4.09140661622382e-07 -7.5065740151954e-06 2.78470847301469e-06 -5.67032953559741e-06 7.41989817283598e-06 5.35263320402977e-05 7.82476266101811e-06 1.19073799184319e-07 -7.43371193871381e-06 1.14643447792645e-05 -4.09140661622382e-07 7.82476266101811e-06 3.7559064118893e-05 9.32474503190795e-06 3.09484441064669e-06 -6.25807895650071e-06 -7.5065740151954e-06 1.19073799184319e-07 9.32474503190795e-06 0.000102430946115605 2219 2219 0 0 0 2232 2232 0 0 0 0 0 0 0 0 90 122 0 3683 0 0 0 0 0 1513 +451 452 0.997890147450576 -0.0624769040013339 0.0176604101729034 0.112282122347351 0.0626151776947276 0.998010401864832 -0.00738764454034246 0.0486483574135449 -0.0171637158950142 0.00847786742081291 0.999816749519966 0.0423114102526676 3.80077212611319e-05 -1.26465904674686e-05 2.90102671122706e-06 5.7943730491306e-06 3.02788870216484e-06 2.28670451216876e-05 -1.26465904674686e-05 3.21281436756906e-05 4.97369804694279e-07 1.00509750324419e-05 1.15048370207838e-06 6.98984890534861e-06 2.90102671122706e-06 4.97369804694279e-07 1.53532242834861e-05 4.4556983367229e-06 5.34814133048393e-07 -6.82209310027237e-06 5.7943730491306e-06 1.00509750324419e-05 4.4556983367229e-06 0.000102866276274855 1.1014423224111e-05 5.51701170928053e-05 3.02788870216484e-06 1.15048370207838e-06 5.34814133048393e-07 1.1014423224111e-05 1.57682304375049e-05 1.04267793816836e-05 2.28670451216876e-05 6.98984890534861e-06 -6.82209310027237e-06 5.51701170928053e-05 1.04267793816836e-05 0.000173752133918704 3314 3393 0 0 281 3302 3381 0 0 379 0 0 0 0 0 90 73 0 3787 0 0 0 0 0 3521 +448 449 0.997726318460992 -0.0671637181559266 -0.00558823887699113 0.0587041169493208 0.0670492373625002 0.997575730923984 -0.0186295689855052 0.0761693624188543 0.00682592260300111 0.0182125241235215 0.999810837481605 -0.00690758846635522 2.98012953019555e-05 -1.57512752796574e-05 -7.57395064772965e-07 1.93713812464572e-06 5.67092888633638e-06 -1.3022183781118e-05 -1.57512752796574e-05 3.71030385195771e-05 1.19690278298282e-06 -4.87065357298295e-06 -8.01489345134811e-07 -4.04480830563921e-06 -7.57395064772965e-07 1.19690278298282e-06 1.11805785236624e-05 3.47787283290707e-07 2.06970536947679e-06 1.01247097381354e-06 1.93713812464572e-06 -4.87065357298295e-06 3.47787283290707e-07 4.56922881457417e-05 8.51989102359647e-06 4.89935391855397e-06 5.67092888633638e-06 -8.01489345134811e-07 2.06970536947679e-06 8.51989102359647e-06 1.91040366918394e-05 -6.18981489164023e-06 -1.3022183781118e-05 -4.04480830563921e-06 1.01247097381354e-06 4.89935391855397e-06 -6.18981489164023e-06 0.00010763690742222 3080 3197 0 0 232 3107 3224 0 0 365 0 0 0 0 0 194 208 0 3781 0 0 0 0 0 3418 +458 459 0.9994615524819 0.0259491508814346 0.0200810029381514 0.0925762348197011 -0.0260195184447383 0.999656149244955 0.00325083630033091 0.0140702505393981 -0.0199897416284809 -0.00377158392193132 0.999793071282426 -0.0156290005597819 3.55146925063044e-05 -9.08043337129409e-06 5.09518767441632e-06 -4.64948893974959e-07 2.91192086614762e-08 -2.54932718605086e-05 -9.08043337129409e-06 5.08401897982781e-05 3.70629003816945e-06 6.51278862037678e-06 -1.1680892873429e-06 5.10379810546982e-05 5.09518767441632e-06 3.70629003816945e-06 1.24400948084341e-05 -2.41021071723992e-06 2.49573398962496e-06 9.65102587626164e-07 -4.64948893974959e-07 6.51278862037678e-06 -2.41021071723992e-06 0.000241271494481868 6.80465669507675e-06 2.29113934717562e-05 2.91192086614762e-08 -1.1680892873429e-06 2.49573398962496e-06 6.80465669507675e-06 1.24949686207678e-05 -7.72277602267986e-06 -2.54932718605086e-05 5.10379810546982e-05 9.65102587626164e-07 2.29113934717562e-05 -7.72277602267986e-06 0.000465467905240071 3281 3277 0 128 15 3281 3277 0 70 64 0 0 0 0 0 0 0 0 3684 0 0 0 0 0 3765 +449 450 0.997421798775154 -0.0717349272099721 -0.00196355451049922 0.0760505668863151 0.0716487105172113 0.99701266089952 -0.0288481591662259 0.0696789754565195 0.00402710930526498 0.0286330966582214 0.999581876669642 0.000861407968282789 4.37264811065206e-05 -2.76409454985738e-05 3.67066998787949e-06 -5.29841170798212e-06 -3.0491644096065e-06 1.51177159791229e-05 -2.76409454985738e-05 4.76378972455104e-05 1.2139383437954e-06 1.00839945684804e-05 3.87120179165807e-06 -2.05696403366347e-06 3.67066998787949e-06 1.2139383437954e-06 1.52418098436695e-05 3.82612785214062e-06 4.44193535262854e-07 -1.8361978503333e-06 -5.29841170798212e-06 1.00839945684804e-05 3.82612785214062e-06 6.74078185969656e-05 1.25953156667237e-05 2.89806995012478e-05 -3.0491644096065e-06 3.87120179165807e-06 4.44193535262854e-07 1.25953156667237e-05 1.97943623253462e-05 1.0014159788373e-05 1.51177159791229e-05 -2.05696403366347e-06 -1.8361978503333e-06 2.89806995012478e-05 1.0014159788373e-05 0.000161279830203096 3091 3190 0 0 265 3104 3203 0 0 382 0 0 0 0 0 183 183 0 3781 0 0 0 0 0 3316 +450 451 0.997302232927769 -0.0689555280752411 -0.0251672673357787 0.0747788182133972 0.0684273329191899 0.997429157593615 -0.0212785265386885 0.0559406126505813 0.0265698382917974 0.0194989930497953 0.999456768931599 -0.0652234938266525 8.05603585502466e-05 -4.09629008845955e-05 -2.8777807592456e-06 -2.27096576479457e-05 1.49887095388269e-06 -8.7316745802415e-05 -4.09629008845955e-05 0.000100247361607821 6.35861643291453e-07 5.20472977488562e-05 9.64413882728135e-06 0.00015061254502259 -2.8777807592456e-06 6.35861643291453e-07 1.64875907290489e-05 5.5052302990165e-06 7.50323927808463e-07 2.51803357567923e-06 -2.27096576479457e-05 5.20472977488562e-05 5.5052302990165e-06 0.000123684964540041 1.54356084453257e-05 0.000178390780116758 1.49887095388269e-06 9.64413882728135e-06 7.50323927808463e-07 1.54356084453257e-05 2.0996546492113e-05 2.3350485367094e-05 -8.7316745802415e-05 0.00015061254502259 2.51803357567923e-06 0.000178390780116758 2.3350485367094e-05 0.00107543786012546 3033 3122 0 0 245 3033 3122 0 0 350 0 0 0 0 0 154 143 0 3784 0 0 0 0 0 3464 +459 460 0.999439751104898 0.0286720508840727 0.0172654976609557 0.141270062742008 -0.0284665051475307 0.999522289543127 -0.0120353974239036 0.0161647467897391 -0.0176023292795281 0.0115371662277544 0.999778501368862 0.0328653604162949 3.52895008052859e-05 1.65809808939776e-06 8.63337025425398e-06 2.12183386803476e-05 1.50990890662053e-06 2.17484124688752e-06 1.65809808939776e-06 2.53342755475679e-05 1.43948546421916e-06 2.83756370515674e-06 1.44120935598721e-07 -9.49928407346706e-06 8.63337025425398e-06 1.43948546421916e-06 1.33137325193491e-05 2.5273241933302e-06 1.40348896900714e-06 -2.016058884123e-08 2.12183386803476e-05 2.83756370515674e-06 2.5273241933302e-06 0.000292923110233679 9.66250352684976e-06 1.87231985663573e-05 1.50990890662053e-06 1.44120935598721e-07 1.40348896900714e-06 9.66250352684976e-06 1.2996751330223e-05 -2.44426222359728e-07 2.17484124688752e-06 -9.49928407346706e-06 -2.016058884123e-08 1.87231985663573e-05 -2.44426222359728e-07 9.97813885180876e-05 3520 3523 0 210 67 3520 3523 0 147 121 0 0 0 0 0 0 0 0 3601 0 0 0 0 0 3720 +460 461 0.999906651672611 0.0097476587593565 0.00957450205386189 0.105231915723542 -0.00974210865074493 0.999952348495342 -0.000626145100690731 0.0149618713256064 -0.00958014926320805 0.000532810811807376 0.999953967366865 0.0230397437326977 3.31760473297162e-05 -8.00633939847505e-06 7.68522020644856e-06 3.97041452308348e-06 5.46376843871248e-07 4.74538284115502e-07 -8.00633939847505e-06 2.42869546400837e-05 1.19002478088316e-06 -2.79971873767433e-07 2.16407371832835e-07 -3.70449840953864e-06 7.68522020644856e-06 1.19002478088316e-06 1.19569447019668e-05 1.36670920885872e-06 2.33869953973009e-06 -1.35590841110734e-06 3.97041452308348e-06 -2.79971873767433e-07 1.36670920885872e-06 0.000181602148776097 3.10039479357528e-06 4.33724323401805e-07 5.46376843871248e-07 2.16407371832835e-07 2.33869953973009e-06 3.10039479357528e-06 1.15204798986825e-05 -8.00998624032174e-07 4.74538284115502e-07 -3.70449840953864e-06 -1.35590841110734e-06 4.33724323401805e-07 -8.00998624032174e-07 8.7461792322325e-05 3504 3506 0 106 63 3504 3506 0 52 119 0 0 0 0 0 0 0 0 3689 0 0 0 0 0 3710 +462 463 0.97986483748233 -0.00838971290609889 -0.199485620993292 0.0826509332146552 0.00480334871814404 0.999818149470902 -0.0184552385428149 0.0086040841033387 0.199604178580555 0.0171254403135667 0.979726947259923 0.0914635163655987 4.95800000927452e-05 -2.03366306588157e-05 -1.68345187895918e-05 2.21468909069213e-05 -7.86160678174003e-09 1.69231032372621e-05 -2.03366306588157e-05 0.000101373882104324 5.38986298544633e-06 -5.77048045280459e-06 -4.22093843824694e-06 -0.000106656842811114 -1.68345187895918e-05 5.38986298544633e-06 1.78831592340088e-05 -2.13823310449426e-06 5.04811960339252e-06 -4.46140249722923e-06 2.21468909069213e-05 -5.77048045280459e-06 -2.13823310449426e-06 0.000258616098183691 1.13301157934025e-05 4.89250830480302e-05 -7.86160678174003e-09 -4.22093843824694e-06 5.04811960339252e-06 1.13301157934025e-05 1.39821468139583e-05 6.72357299841134e-06 1.69231032372621e-05 -0.000106656842811114 -4.46140249722923e-06 4.89250830480302e-05 6.72357299841134e-06 0.000325119857729606 2323 2322 0 23 30 2309 2323 0 3 72 0 0 0 0 0 0 0 0 3721 0 0 0 0 0 3721 +461 462 0.916888281854173 0.00812653402155365 -0.399061195862613 0.00368927890773237 -0.0196281244253275 0.999501114425831 -0.0247438677871243 0.000736702251841286 0.398661028105389 0.0305201852274746 0.916590368138153 0.335272777220835 3.27576952442184e-05 1.31314919962848e-05 -1.61740110657113e-05 2.02928248971742e-05 -3.64575069500607e-06 1.47163995096628e-05 1.31314919962848e-05 0.000265465000808295 -1.01919294170613e-06 0.000164499860306517 1.30363784112323e-05 0.000765486987407233 -1.61740110657113e-05 -1.01919294170613e-06 2.74433174031675e-05 -6.82898603901617e-06 6.72764495059232e-06 -3.82717488496621e-05 2.02928248971742e-05 0.000164499860306517 -6.82898603901617e-06 0.000545144877303248 3.09850405175599e-05 0.000916952876367686 -3.64575069500607e-06 1.30363784112323e-05 6.72764495059232e-06 3.09850405175599e-05 1.51584669392619e-05 6.30150832041186e-05 1.47163995096628e-05 0.000765486987407233 -3.82717488496621e-05 0.000916952876367686 6.30150832041186e-05 0.00491704157912015 714 702 0 8 0 726 722 0 0 0 0 0 0 0 0 0 0 0 2780 0 1 10 0 0 3086 +455 456 0.999756211961298 -0.019886398005609 0.00959415546874595 0.0665352833049507 0.0198726120722495 0.999801349282908 0.00153011813328705 0.0174758893952551 -0.00962267812107634 -0.00133908417899712 0.999952804345955 -0.0297266352534484 3.91321474949695e-05 -5.08833615939321e-06 5.4912099536547e-06 -1.50916410472191e-05 2.99154148185382e-06 -2.3849402204259e-06 -5.08833615939321e-06 1.55069288219356e-05 1.79814856733889e-06 7.11023972735635e-06 -2.39847094679423e-06 3.52994022896286e-06 5.4912099536547e-06 1.79814856733889e-06 1.2852139755232e-05 9.2166366233346e-06 -6.89580780239334e-07 5.01275792174876e-06 -1.50916410472191e-05 7.11023972735635e-06 9.2166366233346e-06 0.000219567204975655 -3.83007535293245e-06 7.21172772865382e-05 2.99154148185382e-06 -2.39847094679423e-06 -6.89580780239334e-07 -3.83007535293245e-06 1.3171960271408e-05 -3.01697624136121e-06 -2.3849402204259e-06 3.52994022896286e-06 5.01275792174876e-06 7.21172772865382e-05 -3.01697624136121e-06 9.97389715893872e-05 3522 3531 0 0 79 3486 3530 0 0 143 0 0 0 0 0 0 0 0 3813 0 0 0 0 0 3668 +452 453 0.9984886792694 -0.0544200536353647 -0.00766910250119277 0.0893953891219373 0.0544167293775825 0.998518105940046 -0.000641618071563647 0.0321158827007244 0.00769265459361898 0.000223320905494617 0.999970386158048 -0.0328480774726822 7.13993335370622e-05 -1.58001936513371e-05 2.32090946880464e-06 4.94298333703193e-06 3.41954503052414e-06 -1.38452511297505e-05 -1.58001936513371e-05 4.83419219602672e-05 -3.29775917756497e-07 2.34071402659196e-05 2.19177520755924e-06 9.99860898584497e-05 2.32090946880464e-06 -3.29775917756497e-07 1.68077135018309e-05 1.1996024430511e-05 -1.13924973411824e-06 5.02324632924762e-06 4.94298333703193e-06 2.34071402659196e-05 1.1996024430511e-05 0.000130750227907804 2.4790215048989e-06 0.000113562063066364 3.41954503052414e-06 2.19177520755924e-06 -1.13924973411824e-06 2.4790215048989e-06 1.64877317568825e-05 1.00566460967485e-05 -1.38452511297505e-05 9.99860898584497e-05 5.02324632924762e-06 0.000113562063066364 1.00566460967485e-05 0.000625946176454141 3302 3370 0 0 199 3280 3348 0 0 285 0 0 0 0 0 65 38 0 3798 0 0 0 0 0 3532 +453 454 0.998978207365189 -0.0451332679588239 0.00235145333585765 0.127168640718909 0.0451677489514118 0.998824326112242 -0.0176022731795578 0.0353753115849621 -0.001554240681475 0.017690497160412 0.999842302888871 -0.0141713771986265 0.000114199038772411 -2.28995755675475e-05 -1.20691650399563e-05 -2.37394510955571e-05 1.04135456099603e-05 -3.42188940826411e-05 -2.28995755675475e-05 5.52506284990268e-05 4.41920188740094e-06 1.40894687945813e-05 -1.6196283267342e-06 8.39835084554873e-06 -1.20691650399563e-05 4.41920188740094e-06 1.8659075261231e-05 8.96266947333837e-06 -2.28054720779783e-06 5.9054434917426e-06 -2.37394510955571e-05 1.40894687945813e-05 8.96266947333837e-06 0.000159153214496268 6.48433186530466e-06 9.69505646418388e-05 1.04135456099603e-05 -1.6196283267342e-06 -2.28054720779783e-06 6.48433186530466e-06 1.78259886473652e-05 6.50173987898843e-06 -3.42188940826411e-05 8.39835084554873e-06 5.9054434917426e-06 9.69505646418388e-05 6.50173987898843e-06 0.000198499736016352 3302 3350 0 0 245 3274 3338 0 0 319 0 0 0 0 0 1 0 0 3803 0 0 0 0 0 3489 +454 455 0.998327554023835 -0.0407887785386218 0.0409679194262411 0.143080689271001 0.0402387834808879 0.999089733068555 0.0141614116874814 0.0252799789577751 -0.0415082543690522 -0.0124892282520329 0.999060100292721 0.0562111165351417 0.000109570217740386 -7.36193514043799e-06 -1.38117670946214e-05 -3.86945777324365e-05 1.9812635020214e-05 -5.43900916170695e-05 -7.36193514043799e-06 5.22268102096794e-05 6.08148711072865e-06 1.37647670695647e-05 -3.22249838265906e-06 3.5166922599947e-05 -1.38117670946214e-05 6.08148711072865e-06 1.69878152172002e-05 5.15040703451779e-06 -3.51199782543149e-06 9.1067995109441e-06 -3.86945777324365e-05 1.37647670695647e-05 5.15040703451779e-06 0.00025368182384775 2.11247081822324e-06 0.000108764914333033 1.9812635020214e-05 -3.22249838265906e-06 -3.51199782543149e-06 2.11247081822324e-06 1.75388819053242e-05 -3.82637833874785e-06 -5.43900916170695e-05 3.5166922599947e-05 9.1067995109441e-06 0.000108764914333033 -3.82637833874785e-06 0.000323308230635968 3314 3329 0 12 247 3310 3329 0 2 315 0 0 0 0 0 0 0 0 3776 0 0 0 0 0 3488 +457 458 0.999170141045042 -0.00429890562008244 0.0405036869247829 0.108576718919709 0.00380499196895237 0.999917560935495 0.0122634974182415 0.0168646480139411 -0.0405530674566969 -0.0120992042416281 0.999104127694692 0.00831280622829272 3.41428019471612e-05 -4.54258349613357e-06 9.86201249427377e-06 1.3341903187393e-05 -4.68269354702022e-07 2.00979360022707e-05 -4.54258349613357e-06 2.87934860650439e-05 -1.99870321995243e-06 1.03061825115264e-05 -4.09099616322882e-07 -2.66271826127303e-07 9.86201249427377e-06 -1.99870321995243e-06 1.26468600884908e-05 2.38761497852055e-06 1.25645308065329e-06 1.88969735811301e-06 1.3341903187393e-05 1.03061825115264e-05 2.38761497852055e-06 0.000448264215533615 8.08240983742118e-07 8.74439785932087e-05 -4.68269354702022e-07 -4.09099616322882e-07 1.25645308065329e-06 8.08240983742118e-07 1.25132782812535e-05 1.59401150178497e-06 2.00979360022707e-05 -2.66271826127303e-07 1.88969735811301e-06 8.74439785932087e-05 1.59401150178497e-06 0.000107463541979083 3470 3460 0 75 106 3470 3460 0 22 161 0 0 0 0 0 0 0 0 3723 0 0 0 0 0 3651 +466 467 0.978040983623244 -0.0146932711782732 0.207894064694882 -0.0565127495219924 0.0165866914217777 0.999835288890902 -0.00736727603155647 0.00740265703839013 -0.207751572848335 0.0106537725960405 0.978123602163098 -0.26049452959655 3.22746534522917e-05 4.42002817016823e-06 1.55304531692375e-05 5.0616928951547e-05 2.43461593863898e-06 4.72667795721659e-05 4.42002817016823e-06 0.000113024895081869 -4.57191498249796e-06 -7.19382572121669e-06 2.03225387428009e-07 0.000159523843693868 1.55304531692375e-05 -4.57191498249796e-06 1.61924695469864e-05 8.86868324229116e-06 4.30615764442373e-06 4.8995400875432e-06 5.0616928951547e-05 -7.19382572121669e-06 8.86868324229116e-06 0.00251506883185865 -4.48932013001296e-05 0.000527747883412396 2.43461593863898e-06 2.03225387428009e-07 4.30615764442373e-06 -4.48932013001296e-05 1.13660385156377e-05 -2.34890775684285e-05 4.72667795721659e-05 0.000159523843693868 4.8995400875432e-06 0.000527747883412396 -2.34890775684285e-05 0.00156835594731695 1736 1746 0 0 2 1712 1736 0 0 14 0 0 0 0 0 18 0 0 3005 0 0 1 0 0 3371 +464 465 0.999518870238115 -0.0310097444704749 -0.000650988324217181 0.0678140669293322 0.0310092793993879 0.99951884253698 -0.00071274446116041 0.00288824094565208 0.000672777119939976 0.000692214859756137 0.999999534104659 0.0300610703171999 3.96300240132813e-05 -6.2728703597963e-06 -1.07077646905163e-07 -1.82106858063666e-05 1.78221856386052e-06 6.87412227049296e-06 -6.2728703597963e-06 2.39971765807509e-05 7.86115312441879e-07 -4.14112442000246e-06 -2.98436764027443e-07 -9.98871939181064e-06 -1.07077646905163e-07 7.86115312441879e-07 1.26078327221993e-05 1.40044032039828e-06 2.84710558094848e-06 -1.17193546305495e-06 -1.82106858063666e-05 -4.14112442000246e-06 1.40044032039828e-06 0.000658697328361565 -2.50787067810255e-06 4.1866020532709e-05 1.78221856386052e-06 -2.98436764027443e-07 2.84710558094848e-06 -2.50787067810255e-06 1.26107434453627e-05 3.52979826224859e-06 6.87412227049296e-06 -9.98871939181064e-06 -1.17193546305495e-06 4.1866020532709e-05 3.52979826224859e-06 0.000163851893564771 3385 3370 0 0 105 3340 3370 0 0 150 0 0 0 0 0 0 0 0 3802 0 0 0 0 0 3642 +456 457 0.999155920213167 -0.0211499068303034 0.035215458878855 0.135555042636926 0.0206415803950251 0.999678331263174 0.0147363211715949 0.0194203235202647 -0.0355158029864814 -0.0139969798151661 0.999271090492605 0.0280342132539023 4.4388514001175e-05 -4.26540074425183e-06 1.03264849412747e-05 1.84867977722123e-06 -2.76546993256244e-06 -4.3316876024544e-06 -4.26540074425183e-06 7.62667623359309e-05 -3.25611362630492e-06 -5.41072412207992e-07 1.69759168704365e-06 7.24600703228896e-05 1.03264849412747e-05 -3.25611362630492e-06 1.39189168001836e-05 1.40255092069121e-06 7.69108530925583e-07 -7.83543087339911e-06 1.84867977722123e-06 -5.41072412207992e-07 1.40255092069121e-06 0.00038359885442663 2.78383140302058e-06 6.01537316124948e-05 -2.76546993256244e-06 1.69759168704365e-06 7.69108530925583e-07 2.78383140302058e-06 1.3863583849112e-05 6.47128430277494e-06 -4.3316876024544e-06 7.24600703228896e-05 -7.83543087339911e-06 6.01537316124948e-05 6.47128430277494e-06 0.000643558853770876 3259 3258 0 67 182 3259 3258 0 12 243 0 0 0 0 0 0 0 0 3720 0 0 0 0 0 3571 +463 464 0.999261800706207 -0.0352442594009182 0.0152871131568233 0.0353230668766498 0.035305224356043 0.999369590980362 -0.00373654344471642 0.00193301612124219 -0.0151457843163766 0.00427350009074217 0.999876163539474 0.00365977361850069 5.48076557315355e-05 -3.88236419443448e-05 -2.48270338461582e-06 7.82363819343806e-06 1.82760526943843e-07 4.93501238942829e-05 -3.88236419443448e-05 0.000302550796625819 2.8413166801764e-06 -1.693083326567e-05 -9.18401685919104e-07 -9.75813786029595e-05 -2.48270338461582e-06 2.8413166801764e-06 1.20866498751317e-05 7.58154199740958e-06 4.00951868096009e-06 -5.62916260687677e-06 7.82363819343806e-06 -1.693083326567e-05 7.58154199740958e-06 0.0049299414345729 0.000172594289634816 -0.00116454650340566 1.82760526943843e-07 -9.18401685919104e-07 4.00951868096009e-06 0.000172594289634816 1.66657224140773e-05 -4.11355581390851e-05 4.93501238942829e-05 -9.75813786029595e-05 -5.62916260687677e-06 -0.00116454650340566 -4.11355581390851e-05 0.000510278348749221 3097 3130 0 0 64 3047 3090 0 0 117 0 0 0 0 0 9 0 0 3758 0 0 0 0 0 3696 +469 470 0.999509053806009 0.0313297048516363 -0.000317732160446791 0.010758613011983 -0.0313300395540341 0.99950847780885 -0.00110968904552291 -9.81960664049022e-06 0.000282809757765762 0.00111909880906388 0.999999333818026 -0.00658024983251943 4.56398012552625e-05 9.05091464327748e-06 -1.03097855072622e-06 -6.23794441167912e-05 1.62790678156531e-06 -4.74301907027078e-06 9.05091464327748e-06 8.02081218583144e-05 -1.2056525913682e-06 0.000146079324871204 4.16761129798021e-07 -1.84273094417624e-05 -1.03097855072622e-06 -1.2056525913682e-06 1.0537152687493e-05 -6.12946301178794e-06 5.1096403520459e-06 1.56623585389501e-06 -6.23794441167912e-05 0.000146079324871204 -6.12946301178794e-06 0.00371368911789478 -2.80364822679552e-05 0.000398899903074465 1.62790678156531e-06 4.16761129798021e-07 5.1096403520459e-06 -2.80364822679552e-05 9.92896668903205e-06 -3.29249715902836e-06 -4.74301907027078e-06 -1.84273094417624e-05 1.56623585389501e-06 0.000398899903074465 -3.29249715902836e-06 0.00016526900604482 3196 3136 0 46 0 3230 3170 0 1 0 0 0 0 0 0 0 0 0 3773 0 23 58 0 0 3728 +465 466 0.999792261711937 -0.012151968729654 -0.0163634677535984 0.0658226740189231 0.0123483787357491 0.999852276141331 0.0119558955163589 -0.00263549014990042 0.0162157628105508 -0.0121554741163438 0.999794625653428 0.00208820977335086 4.42261979740079e-05 -3.44809167804615e-06 2.32241503893103e-06 -1.32024243931434e-05 -1.49385563441188e-06 5.5882669491581e-06 -3.44809167804615e-06 2.1382135224015e-05 -2.49910458868342e-07 1.66910414989389e-06 1.07587650604626e-08 -1.17307760889258e-05 2.32241503893103e-06 -2.49910458868342e-07 1.42465761492173e-05 6.93788013544386e-07 2.24094756039158e-06 -4.13050586067303e-06 -1.32024243931434e-05 1.66910414989389e-06 6.93788013544386e-07 0.00058617289853287 -5.07870286821901e-06 -2.41039537494005e-05 -1.49385563441188e-06 1.07587650604626e-08 2.24094756039158e-06 -5.07870286821901e-06 1.25382602374432e-05 1.7236770943696e-06 5.5882669491581e-06 -1.17307760889258e-05 -4.13050586067303e-06 -2.41039537494005e-05 1.7236770943696e-06 9.24395382048934e-05 3309 3291 0 24 49 3302 3291 0 0 92 0 0 0 0 0 0 0 0 3742 0 0 0 0 0 3685 +471 472 0.999290391273947 0.0233401655619541 0.0295626551429775 0.106344663333397 -0.0236091987120351 0.999682670811213 0.00878427093939187 -0.00627331504781516 -0.0293482477115361 -0.00947598814380718 0.999524329871445 0.0283675727536064 4.90457038813397e-05 1.51899571862822e-05 1.78002653771395e-06 -1.71550470028944e-06 3.22926079292169e-06 -1.12415963919182e-05 1.51899571862822e-05 0.000274396441275648 -1.15997418736886e-06 -0.000197769661199337 -1.4239154253763e-05 -0.000277082335129533 1.78002653771395e-06 -1.15997418736886e-06 1.38290947963855e-05 -6.96377586727619e-06 4.56090135843183e-06 1.17582441517226e-06 -1.71550470028944e-06 -0.000197769661199337 -6.96377586727619e-06 0.000981964995529418 4.52690437129688e-05 0.000153316508639865 3.22926079292169e-06 -1.4239154253763e-05 4.56090135843183e-06 4.52690437129688e-05 1.35878072756698e-05 1.36981868022762e-05 -1.12415963919182e-05 -0.000277082335129533 1.17582441517226e-06 0.000153316508639865 1.36981868022762e-05 0.000343350528953798 3212 3206 0 176 13 3212 3206 0 122 57 0 0 0 0 0 0 0 0 3645 0 0 0 0 0 3752 +474 475 0.999304496276107 -0.0346485877367793 0.0137840157502271 0.128420505312871 0.0347272114233863 0.999381660978168 -0.00550604098006262 0.00525410745480793 -0.0135847160114312 0.0059808919372785 0.999889836143224 -0.0240955636025475 3.09309217350833e-05 -9.46785279323657e-06 -7.32634472888954e-06 2.10902187771051e-06 -1.51914482161433e-06 9.95460117189644e-06 -9.46785279323657e-06 5.07945580333013e-05 -4.7836908799487e-07 3.48978920432603e-05 -4.0065085076717e-07 7.31274335502258e-06 -7.32634472888954e-06 -4.7836908799487e-07 1.21674546707057e-05 -4.42825717202873e-06 4.11157043836382e-06 -5.00345133560853e-07 2.10902187771051e-06 3.48978920432603e-05 -4.42825717202873e-06 0.000255750991984839 3.62855270666492e-06 -4.10431501670549e-05 -1.51914482161433e-06 -4.0065085076717e-07 4.11157043836382e-06 3.62855270666492e-06 1.06472621168197e-05 1.61944198519463e-06 9.95460117189644e-06 7.31274335502258e-06 -5.00345133560853e-07 -4.10431501670549e-05 1.61944198519463e-06 0.000400099058276176 3307 3302 0 35 192 3307 3302 0 0 240 0 0 0 0 0 0 0 0 3755 0 0 0 0 0 3542 +473 474 0.999466225230258 -0.00859441469439636 0.0315182591530715 0.120130775737977 0.00838988105063872 0.999942918311995 0.00661589099425623 0.00315221391532654 -0.0315733197484136 -0.00634792515334665 0.999481280128003 -0.0162126077214292 3.46488403694596e-05 -1.22179455238333e-05 3.79720283769191e-07 -6.96890873213727e-07 6.47532881302314e-07 1.54715737023642e-05 -1.22179455238333e-05 2.31010257437588e-05 -6.48311842575947e-07 6.12977174378154e-06 3.69515615756066e-07 -1.04602208707547e-05 3.79720283769191e-07 -6.48311842575947e-07 1.16756805082061e-05 3.5785337603507e-06 3.50771849274019e-06 -2.23362508552485e-06 -6.96890873213727e-07 6.12977174378154e-06 3.5785337603507e-06 0.000430514921271747 1.82668661186402e-05 2.16660567438244e-05 6.47532881302314e-07 3.69515615756066e-07 3.50771849274019e-06 1.82668661186402e-05 1.16831154846637e-05 3.16284745027743e-06 1.54715737023642e-05 -1.04602208707547e-05 -2.23362508552485e-06 2.16660567438244e-05 3.16284745027743e-06 0.000131986002236119 3457 3459 0 93 114 3457 3459 0 40 169 0 0 0 0 0 0 0 0 3702 0 0 0 0 0 3638 +467 468 0.999679717931383 -0.0204763287280659 0.0148721726204081 0.0246883554861437 0.0204908162092291 0.99978970294904 -0.000822391725692676 0.0049486250868247 -0.0148522054830461 0.00112687128416627 0.999889064923404 -0.00377276121567366 5.03631731186112e-05 9.14218848444114e-07 1.31921206953626e-06 -4.44229042636939e-05 7.32774424112224e-06 1.00729443694478e-05 9.14218848444114e-07 2.53531207167872e-05 -1.0918883369157e-06 -1.59535037073005e-05 -2.41448413528702e-07 -6.09942189310483e-06 1.31921206953626e-06 -1.0918883369157e-06 1.23121206674921e-05 1.01816190762376e-05 3.87499803321596e-06 1.43340700347244e-06 -4.44229042636939e-05 -1.59535037073005e-05 1.01816190762376e-05 0.000715167802724663 -2.86813295445201e-05 -0.00017633134209273 7.32774424112224e-06 -2.41448413528702e-07 3.87499803321596e-06 -2.86813295445201e-05 1.20639429169461e-05 6.0603955394991e-06 1.00729443694478e-05 -6.09942189310483e-06 1.43340700347244e-06 -0.00017633134209273 6.0603955394991e-06 0.000169520846855563 3466 3459 0 0 42 3406 3441 0 0 74 0 0 0 0 0 0 0 0 3811 0 0 0 0 0 3721 +475 476 0.980514100774666 -0.0152591231662426 -0.195855194830888 0.0266098745413132 0.0122288671486103 0.999786227894391 -0.0166719321305751 -0.00418150311387808 0.196067725519294 0.0139519773832351 0.980491096000769 0.0236888662553788 3.00950104444097e-05 -3.14738205084221e-05 -1.31474662023057e-05 -0.000125214242222984 -2.93504843520504e-06 -9.80431004892826e-06 -3.14738205084221e-05 0.00354160974755502 -2.83889617488439e-05 0.00344460043524023 5.66272381609447e-05 -0.00174559594080892 -1.31474662023057e-05 -2.83889617488439e-05 1.42521231740444e-05 -2.70977045588741e-05 3.96273082615203e-06 8.4781459849078e-06 -0.000125214242222984 0.00344460043524023 -2.70977045588741e-05 0.00636983997390563 9.36141591013465e-05 -0.00119711410909157 -2.93504843520504e-06 5.66272381609447e-05 3.96273082615203e-06 9.36141591013465e-05 1.29166354737948e-05 -1.31996679987435e-05 -9.80431004892826e-06 -0.00174559594080892 8.4781459849078e-06 -0.00119711410909157 -1.31996679987435e-05 0.00159887506320857 2609 2609 0 0 12 2581 2605 0 0 30 0 0 0 0 0 12 0 0 3816 0 0 2 0 0 3761 +468 469 0.999957280138375 -0.00142655619298571 0.0091325152992662 0.0412707165706516 0.00144470546849887 0.999996994155783 -0.00198103647333572 0.00341195623329889 -0.00912966178849834 0.0019941456385257 0.9999563353761 -0.0406014602006141 4.34129957793287e-05 2.67307121308267e-05 1.83882618760358e-06 5.65397885601572e-05 -1.89130701821613e-06 -4.38727370010113e-05 2.67307121308267e-05 0.000254377013378184 7.89749622003874e-06 -0.000206517722497966 9.85376817334281e-06 -9.41942452172966e-05 1.83882618760358e-06 7.89749622003874e-06 1.12953594983154e-05 -1.26707544458802e-05 5.45628349471407e-06 -3.52294033070095e-06 5.65397885601572e-05 -0.000206517722497966 -1.26707544458802e-05 0.00242345467688057 -7.68978302465092e-05 -0.000627527098852073 -1.89130701821613e-06 9.85376817334281e-06 5.45628349471407e-06 -7.68978302465092e-05 1.22296235194142e-05 1.61538835684595e-05 -4.38727370010113e-05 -9.41942452172966e-05 -3.52294033070095e-06 -0.000627527098852073 1.61538835684595e-05 0.000543391759678448 3159 3131 0 13 13 3140 3131 0 0 50 0 0 0 0 0 0 0 0 3785 0 0 0 0 0 3743 +477 478 0.99974897484483 0.000225251961577501 -0.0224039406860793 0.0461258580888092 -0.000490854887286939 0.999929661122923 -0.0118503952708728 0.00240617006491126 0.0223996954932691 0.0118584176073413 0.999678764190607 -0.0295953232425436 2.79709423821664e-05 -1.19537550336742e-06 -9.39633985189833e-06 7.19632546056293e-05 -2.55352730778309e-06 1.10866848055008e-05 -1.19537550336742e-06 5.20155437966704e-05 -1.11738807341632e-06 0.000187314527674264 1.60755673157771e-07 2.99408648617601e-05 -9.39633985189833e-06 -1.11738807341632e-06 1.12127360378739e-05 1.55494872503831e-05 4.45295813086123e-06 1.13771167875689e-06 7.19632546056293e-05 0.000187314527674264 1.55494872503831e-05 0.0096702587651946 2.04047637739358e-05 0.00141765580891957 -2.55352730778309e-06 1.60755673157771e-07 4.45295813086123e-06 2.04047637739358e-05 1.1138470467197e-05 3.83701693855881e-06 1.10866848055008e-05 2.99408648617601e-05 1.13771167875689e-06 0.00141765580891957 3.83701693855881e-06 0.000541721561949195 3351 3335 0 18 3 3346 3335 0 0 45 0 0 0 0 0 0 0 0 3779 0 0 0 0 0 3748 +476 477 0.999654249702676 -0.0105782370386603 -0.0240724313797647 0.178541081723788 0.0111469388467679 0.999658995821447 0.0236143563876507 -0.00276923460987283 0.0238144243206923 -0.0238745256373919 0.999431278387796 -0.0188986069464343 3.42133582510493e-05 -1.46135879895365e-08 -5.10462929714903e-06 -4.71173774983155e-05 -2.09306798222739e-06 3.30182247910179e-05 -1.46135879895365e-08 6.0355171203192e-05 -2.77194861675405e-06 -0.000403972479834004 -4.0832894954684e-06 0.000243479109914848 -5.10462929714903e-06 -2.77194861675405e-06 1.07943202551782e-05 1.44516031642348e-06 4.21751356033934e-06 2.73468972905147e-06 -4.71173774983155e-05 -0.000403972479834004 1.44516031642348e-06 0.00647096969118789 6.16349961362823e-05 -0.00376199913807071 -2.09306798222739e-06 -4.0832894954684e-06 4.21751356033934e-06 6.16349961362823e-05 1.08385925741727e-05 -3.8676612299957e-05 3.30182247910179e-05 0.000243479109914848 2.73468972905147e-06 -0.00376199913807071 -3.8676612299957e-05 0.00244831281566919 3356 3346 0 170 184 3356 3346 0 109 231 0 0 0 0 0 0 0 0 3632 0 0 0 0 0 3551 +470 471 0.998097295606613 0.0322980625489697 -0.0525226014050011 -0.105980286044228 -0.0339589392487057 0.998940996099544 -0.0310431434741151 0.000580415853195004 0.0514643463756074 0.0327676893789388 0.998137114621482 -0.104551737936821 4.67008098466491e-05 7.5036447211665e-05 -1.06023807714454e-05 0.000100826556428382 5.38864242225688e-06 1.96922858622241e-05 7.5036447211665e-05 0.0011230819692861 -3.4138836379602e-05 0.00102551263918189 3.70343006884556e-05 -4.78753200071324e-05 -1.06023807714454e-05 -3.4138836379602e-05 1.29054888355747e-05 -5.05381605731227e-05 2.27320748000716e-06 -5.10777612649241e-06 0.000100826556428382 0.00102551263918189 -5.05381605731227e-05 0.0124025620705019 0.000373335619790814 0.00192538755962842 5.38864242225688e-06 3.70343006884556e-05 2.27320748000716e-06 0.000373335619790814 2.21473250835227e-05 6.2184698315139e-05 1.96922858622241e-05 -4.78753200071324e-05 -5.10777612649241e-06 0.00192538755962842 6.2184698315139e-05 0.000528908976573291 3036 3028 0 0 0 3022 3022 0 0 0 0 0 0 0 0 17 0 0 3820 0 148 189 0 0 3627 +483 484 0.999832866663833 0.01792739688126 -0.00358429628303281 0.0960733636787189 -0.0178750394607633 0.999740215357159 0.014141596865182 -0.00489278386969736 0.00383688715743999 -0.0140751638954209 0.999893578366347 -0.151622495403255 6.40286031921508e-05 -5.20057962308067e-05 -1.10682552948236e-06 -9.84043463630644e-05 -1.14644709895295e-05 -0.000376286030033601 -5.20057962308067e-05 0.000284859826112713 -1.40505598178471e-05 0.000521500762811193 6.18018579405057e-05 0.00169406159292427 -1.10682552948236e-06 -1.40505598178471e-05 1.28023094766745e-05 -2.37744666192489e-05 1.30942766375038e-06 -8.71217269884246e-05 -9.84043463630644e-05 0.000521500762811193 -2.37744666192489e-05 0.00137406608903581 0.000139021365974976 0.00371900151533832 -1.14644709895295e-05 6.18018579405057e-05 1.30942766375038e-06 0.000139021365974976 2.77971870841885e-05 0.00046133706562357 -0.000376286030033601 0.00169406159292427 -8.71217269884246e-05 0.00371900151533832 0.00046133706562357 0.0145449043440291 3328 3339 0 139 10 3328 3339 0 82 63 0 0 0 0 0 0 0 0 3689 0 0 0 0 0 3757 +482 483 0.999037540717755 0.0238592991200032 -0.0368066037841411 0.115043200359352 -0.0235215543457928 0.999677407387331 0.00958215218530097 -0.00115928426928531 0.0370233536808654 -0.0087071812227936 0.999276466388244 0.0224666352198148 3.79911262931698e-05 -2.77891669088942e-06 -1.25340937540444e-05 -5.49838200809351e-06 2.24958922149692e-06 6.92188528412607e-06 -2.77891669088942e-06 2.21562569918418e-05 -1.50512317042935e-06 5.82930722637529e-06 9.47803580333036e-07 -1.18151165881603e-05 -1.25340937540444e-05 -1.50512317042935e-06 1.32105912885702e-05 -1.54236726984452e-06 2.86355497321942e-06 -9.39244178470572e-07 -5.49838200809351e-06 5.82930722637529e-06 -1.54236726984452e-06 0.00023356679479348 7.61117770796552e-06 2.58057968592793e-05 2.24958922149692e-06 9.47803580333036e-07 2.86355497321942e-06 7.61117770796552e-06 1.26773696478771e-05 4.41399956766327e-06 6.92188528412607e-06 -1.18151165881603e-05 -9.39244178470572e-07 2.58057968592793e-05 4.41399956766327e-06 8.51834276287961e-05 3517 3525 0 176 17 3517 3525 0 123 70 0 0 0 0 0 0 0 0 3652 0 0 0 0 0 3736 +472 473 0.999343280578575 0.0200044385213382 0.0302130766705099 0.13288382328328 -0.020816242192489 0.999424106576328 0.0267981203649115 -0.00455637333189863 -0.0296595958070192 -0.0274094442401638 0.999184182592484 -0.00356462472167079 3.87092544104693e-05 -2.36927605207629e-06 -1.24681224848045e-06 1.57554829334838e-06 5.23676702766997e-07 7.22877264796211e-06 -2.36927605207629e-06 3.78754475185936e-05 -1.39683778575288e-06 3.89142301359814e-06 1.89601586514533e-07 -2.24754969168088e-05 -1.24681224848045e-06 -1.39683778575288e-06 1.08051286865057e-05 5.80066911358358e-07 3.98027254307184e-06 2.28929339430717e-06 1.57554829334838e-06 3.89142301359814e-06 5.80066911358358e-07 0.000296660754105961 7.85737701079675e-06 2.11179068907444e-05 5.23676702766997e-07 1.89601586514533e-07 3.98027254307184e-06 7.85737701079675e-06 1.13208666245752e-05 -1.19129680919515e-06 7.22877264796211e-06 -2.24754969168088e-05 2.28929339430717e-06 2.11179068907444e-05 -1.19129680919515e-06 0.000168157786371044 3290 3290 0 193 56 3290 3290 0 131 103 0 0 0 0 0 0 0 0 3623 0 0 0 0 0 3710 +479 480 0.86935051033854 -0.0116496132926716 -0.494058677369654 0.0332760074277006 0.0114909430069152 0.999928337973593 -0.00335814624140687 0.00344154463265106 0.494062393228762 -0.0027577939549681 0.86942207596171 0.0720385963715292 5.10257627877414e-05 -7.44344693976903e-05 4.47727424175278e-07 -5.88155628327151e-05 -3.02070214160487e-07 1.78195808011057e-05 -7.44344693976903e-05 0.00247577540095694 -0.000123412042084062 0.000413214334784177 -5.35537519033818e-05 -0.00175601064339503 4.47727424175278e-07 -0.000123412042084062 2.14557675403334e-05 -3.12717631122493e-05 3.05874214880711e-06 9.01112849428965e-05 -5.88155628327151e-05 0.000413214334784177 -3.12717631122493e-05 0.00153278859098109 -2.54553487022915e-05 -0.000444670915493865 -3.02070214160487e-07 -5.35537519033818e-05 3.05874214880711e-06 -2.54553487022915e-05 1.34429401304075e-05 5.65449410533423e-05 1.78195808011057e-05 -0.00175601064339503 9.01112849428965e-05 -0.000444670915493865 5.65449410533423e-05 0.00228945523529531 685 682 0 0 5 672 681 0 0 10 0 0 0 0 0 15 3 0 3445 0 3 10 0 0 3371 +478 479 0.999915711498089 -0.0106318124207896 0.00745214492073169 0.136511694655395 0.0108266523762225 0.999587208640097 -0.0266119507256402 0.00606218449801703 -0.00716613547142937 0.0266903894266946 0.99961806186896 -0.0321727819976476 3.21368097471613e-05 -2.78183234024901e-06 -8.03350837585441e-06 1.04128605528444e-05 -5.15832461739623e-07 -1.89343985072732e-05 -2.78183234024901e-06 4.32821890539776e-05 -3.11987694845018e-06 5.19045392303701e-06 -1.50709944142786e-06 3.44349050520586e-06 -8.03350837585441e-06 -3.11987694845018e-06 1.20861431589412e-05 -9.0459054922048e-07 3.46416090558608e-06 6.53037013750625e-06 1.04128605528444e-05 5.19045392303701e-06 -9.0459054922048e-07 0.00025366179006016 -2.38864724733687e-06 -6.84119914426923e-05 -5.15832461739623e-07 -1.50709944142786e-06 3.46416090558608e-06 -2.38864724733687e-06 1.07394537295952e-05 4.20272424183792e-06 -1.89343985072732e-05 3.44349050520586e-06 6.53037013750625e-06 -6.84119914426923e-05 4.20272424183792e-06 0.000334895605583172 3342 3326 0 111 149 3342 3326 0 44 190 0 0 0 0 0 0 0 0 3689 0 0 0 0 0 3611 +480 481 0.983125713017099 0.0179471273099691 -0.18204871058577 0.15834700509302 -0.0148731236676534 0.99972306422143 0.0182369146535481 -0.00319567265346271 0.182325595013394 -0.0152215467359224 0.983120380176292 0.0279550478693006 2.92440753889449e-05 -9.9874983209986e-06 -1.08176135066555e-05 -7.17863620499241e-06 -2.37253206440609e-06 -3.11997055300976e-05 -9.9874983209986e-06 6.94220472368763e-05 8.99570496210246e-07 2.65158662932037e-05 2.54396123751933e-06 9.92768183054885e-05 -1.08176135066555e-05 8.99570496210246e-07 1.19345542669865e-05 6.02773741074503e-07 3.90687264468098e-06 -8.69341225063428e-06 -7.17863620499241e-06 2.65158662932037e-05 6.02773741074503e-07 0.000276507920351099 -2.8554982614999e-06 -0.000153172123197248 -2.37253206440609e-06 2.54396123751933e-06 3.90687264468098e-06 -2.8554982614999e-06 1.0793634889923e-05 1.39174919224103e-05 -3.11997055300976e-05 9.92768183054885e-05 -8.69341225063428e-06 -0.000153172123197248 1.39174919224103e-05 0.00110351388818244 2691 2684 0 184 59 2691 2684 0 113 114 0 0 0 0 0 0 0 0 3628 0 0 0 0 0 3689 +481 482 0.999495460317186 0.0270332358063752 -0.016674200645715 0.134370822518948 -0.0273700095755989 0.999419002861514 -0.020311063367725 -1.53494193930572e-05 0.0161154392173553 0.0207571886615945 0.999654656237692 -0.0501272702903999 4.09068558789666e-05 3.81383971374488e-06 -9.4829091838442e-06 -1.69153302681981e-05 3.089730182329e-06 2.05679028563478e-05 3.81383971374488e-06 4.01984038619638e-05 -3.90423898300111e-06 1.19492689339104e-05 2.49614322492856e-06 1.83807682919793e-05 -9.4829091838442e-06 -3.90423898300111e-06 1.27918516752819e-05 -2.45178717756015e-06 3.11663672269527e-06 2.13423220230587e-06 -1.69153302681981e-05 1.19492689339104e-05 -2.45178717756015e-06 0.000250114924250553 -2.76378967815364e-06 -0.000130275221636618 3.089730182329e-06 2.49614322492856e-06 3.11663672269527e-06 -2.76378967815364e-06 1.15929592495226e-05 8.1894785938421e-06 2.05679028563478e-05 1.83807682919793e-05 2.13423220230587e-06 -0.000130275221636618 8.1894785938421e-06 0.000340904927157057 3352 3351 0 204 39 3352 3351 0 142 90 0 0 0 0 0 0 0 0 3608 0 0 0 0 0 3725 +486 487 0.999755079627275 -0.0220548892762857 0.00183374438557257 0.120980838583668 0.0220592500918223 0.999753801490153 -0.00239288348544099 0.00352759778140366 -0.00178051814011495 0.00243274844553167 0.999995455734751 0.000362513764806574 4.38637669947262e-05 -1.01494582953759e-05 -1.04397664394846e-05 -5.57958178881885e-06 3.64510045793973e-06 1.226142508466e-05 -1.01494582953759e-05 8.31204962513298e-05 2.33607975223544e-06 2.54011753192943e-05 2.01204244611084e-06 -8.82546957012325e-05 -1.04397664394846e-05 2.33607975223544e-06 1.46802601918413e-05 -2.58863440438145e-06 1.8915431976528e-06 -4.90785750439675e-06 -5.57958178881885e-06 2.54011753192943e-05 -2.58863440438145e-06 0.000136011729151047 -8.21598144816253e-07 -2.56466255999522e-05 3.64510045793973e-06 2.01204244611084e-06 1.8915431976528e-06 -8.21598144816253e-07 1.22290006757348e-05 -1.15089160594725e-06 1.226142508466e-05 -8.82546957012325e-05 -4.90785750439675e-06 -2.56466255999522e-05 -1.15089160594725e-06 0.000166378987708035 3286 3291 0 64 130 3286 3291 0 15 195 0 0 0 0 0 0 0 0 3705 0 0 0 0 0 3560 +489 490 0.999948559746961 0.00163049308181809 -0.0100109616066061 0.138495521826264 -0.00158214311619043 0.99998705621479 0.00483572394141632 0.0025566289391035 0.0100187166413014 -0.00481963641656081 0.999938196300988 -0.0264652257128688 3.7869362716563e-05 -1.64724245095397e-05 -6.74380890661984e-06 -7.14366152289765e-06 9.78461641430524e-07 6.25526201851793e-06 -1.64724245095397e-05 0.000195365730449162 5.79559507498671e-06 1.34380525655539e-05 3.78442922405865e-06 -0.000139962332341092 -6.74380890661984e-06 5.79559507498671e-06 1.3555534160067e-05 1.65748621308916e-06 2.53930122745938e-06 3.87400126254078e-08 -7.14366152289765e-06 1.34380525655539e-05 1.65748621308916e-06 0.000128188001993854 -1.53410090472379e-06 -4.31250102640348e-05 9.78461641430524e-07 3.78442922405865e-06 2.53930122745938e-06 -1.53410090472379e-06 1.25213629221552e-05 -1.9918827297551e-05 6.25526201851793e-06 -0.000139962332341092 3.87400126254078e-08 -4.31250102640348e-05 -1.9918827297551e-05 0.000404537021805454 3195 3205 0 141 104 3195 3205 0 92 167 0 0 0 0 0 0 0 0 3666 0 0 0 0 0 3570 +488 489 0.999857649069232 -0.00345044639048286 -0.0165159322308676 0.128262095722037 0.00352911391820704 0.999982555988387 0.00473635660443331 0.000552190905163479 0.0164993015822042 -0.00479396898597034 0.999852384559171 0.00730913364162394 3.47259322474956e-05 -4.36461901320713e-06 -1.04033589806678e-05 3.08707733838006e-06 1.61282838781392e-06 5.41399950240127e-06 -4.36461901320713e-06 4.10374860431722e-05 3.60110744297221e-06 1.03346818246005e-05 1.45612402639798e-06 -2.59386558310087e-05 -1.04033589806678e-05 3.60110744297221e-06 1.350569496937e-05 -2.37153834964867e-07 3.2829053592146e-06 -2.37725684337825e-06 3.08707733838006e-06 1.03346818246005e-05 -2.37153834964867e-07 0.000132745222743977 1.06878921467024e-06 -2.35889899274687e-05 1.61282838781392e-06 1.45612402639798e-06 3.2829053592146e-06 1.06878921467024e-06 1.14652521677919e-05 -2.2106710393822e-06 5.41399950240127e-06 -2.59386558310087e-05 -2.37725684337825e-06 -2.35889899274687e-05 -2.2106710393822e-06 6.31882395428155e-05 3283 3296 0 112 102 3283 3296 0 64 153 0 0 0 0 0 0 0 0 3680 0 0 0 0 0 3573 +484 485 0.999236809168779 0.00799514336346458 -0.0382344986209337 0.106263177330644 -0.00755815516075337 0.999904614860207 0.0115600809610579 0.00234992061222934 0.0383232761225147 -0.0112622761401897 0.999201925360124 0.0680508543896551 3.49096237325769e-05 -1.78205993278476e-05 -1.13100408921053e-05 9.30577480095958e-07 -1.45214244164553e-06 2.16453389897987e-05 -1.78205993278476e-05 7.34959624543955e-05 3.31009463705868e-06 4.38563432740631e-06 -1.47125322861262e-06 -4.99439792239455e-05 -1.13100408921053e-05 3.31009463705868e-06 1.18196591451323e-05 -4.50501900038732e-06 4.42671662936087e-06 -1.7721895447925e-06 9.30577480095958e-07 4.38563432740631e-06 -4.50501900038732e-06 0.000112559142930045 1.39045055482931e-06 7.22281023349661e-06 -1.45214244164553e-06 -1.47125322861262e-06 4.42671662936087e-06 1.39045055482931e-06 1.05003169518371e-05 -3.58013736525737e-07 2.16453389897987e-05 -4.99439792239455e-05 -1.7721895447925e-06 7.22281023349661e-06 -3.58013736525737e-07 0.000138277032624729 3181 3194 0 110 47 3181 3194 0 62 106 0 0 0 0 0 0 0 0 3686 0 0 0 0 0 3712 +487 488 0.999932505913938 -0.0115553013778699 0.00120773620410987 0.119423530274813 0.0115137583652124 0.999481250790496 0.0300776110516456 -0.0020408779466727 -0.00155466555233681 -0.0300616754079537 0.999546836664839 0.0769472568852895 3.42321955308046e-05 -1.34631177007766e-05 -4.25029181805426e-06 -2.22151261245451e-06 -1.51699119442098e-06 1.13381773208046e-06 -1.34631177007766e-05 7.5574151093291e-05 -6.46384629450507e-08 2.46750753578536e-05 -2.93943899714675e-07 1.7571745543954e-05 -4.25029181805426e-06 -6.46384629450507e-08 1.0466468543854e-05 -3.3797300416292e-07 4.90515691074308e-06 2.62446930053431e-08 -2.22151261245451e-06 2.46750753578536e-05 -3.3797300416292e-07 0.000184193895004365 5.52980139544809e-06 -0.00011042640690378 -1.51699119442098e-06 -2.93943899714675e-07 4.90515691074308e-06 5.52980139544809e-06 1.02479306642881e-05 -1.80615806409654e-05 1.13381773208046e-06 1.7571745543954e-05 2.62446930053431e-08 -0.00011042640690378 -1.80615806409654e-05 0.000544215226292636 3315 3320 0 85 108 3315 3320 0 34 169 0 0 0 0 0 0 0 0 3706 0 0 0 0 0 3579 +485 486 0.998440398337235 -0.0165820708705038 -0.0533085911821852 0.134655932954903 0.0158134820213033 0.99976531027633 -0.0148073682481474 0.00837827556426402 0.0535416170333478 0.0139412802037659 0.998468294915634 0.00743130911249133 2.34591337470653e-05 -7.89324125067698e-06 -8.09187637012365e-06 5.17727977721575e-06 -2.70608732399214e-06 1.11436266906881e-05 -7.89324125067698e-06 6.32838119530602e-05 -1.23216972973476e-06 2.67589250717803e-06 7.77143993787079e-07 -3.64358948829683e-05 -8.09187637012365e-06 -1.23216972973476e-06 1.0122688599148e-05 -4.28075801840032e-06 4.30660388668265e-06 -2.17014993596147e-06 5.17727977721575e-06 2.67589250717803e-06 -4.28075801840032e-06 0.000207584015685829 9.29914995357349e-06 -6.52117312995332e-05 -2.70608732399214e-06 7.77143993787079e-07 4.30660388668265e-06 9.29914995357349e-06 1.04514411897383e-05 -4.92664130774001e-06 1.11436266906881e-05 -3.64358948829683e-05 -2.17014993596147e-06 -6.52117312995332e-05 -4.92664130774001e-06 0.000269330096099371 3176 3187 0 77 141 3176 3187 0 32 198 0 0 0 0 0 0 0 0 3702 0 0 0 0 0 3603 +494 495 0.999933126630186 0.00468991407273225 0.0105710441097564 0.124993468990924 -0.00480181850877812 0.999932442206756 0.0105855354820565 0.00821766344206246 -0.0105206847015194 -0.0106355878268908 0.999888093470958 0.0168140887381489 3.92008880906152e-05 -2.51229505628402e-05 -4.49644815888231e-06 1.07614821286801e-05 8.96195453281315e-07 2.8041978306359e-05 -2.51229505628402e-05 4.20216346473283e-05 3.06088408937917e-07 -8.48952141264043e-06 -7.34353280897791e-07 -4.22143898703753e-05 -4.49644815888231e-06 3.06088408937917e-07 1.13944610096695e-05 -5.34351854098067e-06 3.79920824248231e-06 8.87107716154311e-07 1.07614821286801e-05 -8.48952141264043e-06 -5.34351854098067e-06 7.88532382224337e-05 1.2425074057351e-07 1.34835124757137e-05 8.96195453281315e-07 -7.34353280897791e-07 3.79920824248231e-06 1.2425074057351e-07 1.10295312926893e-05 5.96756918801649e-07 2.8041978306359e-05 -4.22143898703753e-05 8.87107716154311e-07 1.34835124757137e-05 5.96756918801649e-07 8.10689861518254e-05 3275 3308 0 118 82 3275 3308 0 81 158 0 0 0 0 0 0 0 0 3687 0 0 0 0 0 3658 +492 493 0.999568287633299 0.0191117314072051 -0.0223154672918545 0.142923268782625 -0.0196819328125124 0.999478030623211 -0.0256181151201883 0.0085957829198087 0.0218142127659635 0.0260462669909974 0.999422699410632 -0.00190095007891267 3.77483455443585e-05 -8.96246954365322e-06 -1.00368732145003e-05 -7.85348073292801e-06 2.07288077168751e-06 1.86126948424795e-05 -8.96246954365322e-06 2.50711640600196e-05 1.04983660837934e-06 6.8531955318377e-06 1.36153277084469e-06 -1.47980100723365e-05 -1.00368732145003e-05 1.04983660837934e-06 1.39921066413143e-05 1.16878574204217e-06 2.39428520629683e-06 -3.11145869594905e-06 -7.85348073292801e-06 6.8531955318377e-06 1.16878574204217e-06 8.67196599173901e-05 -4.70016465070111e-06 2.35537098510591e-05 2.07288077168751e-06 1.36153277084469e-06 2.39428520629683e-06 -4.70016465070111e-06 1.31769317082828e-05 4.76335379397211e-06 1.86126948424795e-05 -1.47980100723365e-05 -3.11145869594905e-06 2.35537098510591e-05 4.76335379397211e-06 0.000119075847686723 3425 3447 0 181 73 3425 3447 0 138 140 0 0 0 0 0 0 0 0 3649 0 0 0 0 0 3672 +493 494 0.556350052360128 -0.0187786636370581 -0.830735806999367 0.0103341622818432 -0.0523716679158208 0.99696454447063 -0.0576099424421193 -0.00243663713274104 0.829295983131836 0.0755583143040893 0.553677806581523 0.508560942529439 0.000220147429551974 7.43729800092029e-05 3.86498154134109e-05 -7.7176983904063e-05 -2.97381200849902e-07 0.000177911649351235 7.43729800092029e-05 0.00236283662099955 -0.0004629913725988 0.0034287060280756 0.000472202425965195 -0.00195227490624233 3.86498154134109e-05 -0.0004629913725988 0.000187083434569631 -0.000875074162532116 -0.000117418485467598 0.000564878673558021 -7.7176983904063e-05 0.0034287060280756 -0.000875074162532116 0.00658212751227469 0.000861655038587037 -0.00456919705575151 -2.97381200849902e-07 0.000472202425965195 -0.000117418485467598 0.000861655038587037 0.000135511366728049 -0.000593602302648282 0.000177911649351235 -0.00195227490624233 0.000564878673558021 -0.00456919705575151 -0.000593602302648282 0.00453139971022288 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1674 0 0 0 0 0 2177 +490 491 0.963190766324738 0.0223593691007303 -0.267887301453767 0.162231624796371 -0.027844969531724 0.999472824798771 -0.0166952137016351 0.0028052029438126 0.267372783466345 0.0235399894261491 0.963305591990037 0.049240552684646 3.65872180377472e-05 1.03047969085769e-05 -1.40599350535786e-05 1.45686882278698e-05 8.44362459025845e-07 -2.94483623444123e-06 1.03047969085769e-05 6.91803917743737e-05 -1.44102691618603e-06 1.19116855700225e-05 2.73365646385253e-06 -3.09452265596205e-05 -1.40599350535786e-05 -1.44102691618603e-06 1.51627612394628e-05 -4.41734611544021e-06 3.42246231871738e-06 -1.55641618472416e-06 1.45686882278698e-05 1.19116855700225e-05 -4.41734611544021e-06 0.000174599460099923 4.01357583608867e-06 -1.16028178235435e-05 8.44362459025845e-07 2.73365646385253e-06 3.42246231871738e-06 4.01357583608867e-06 1.30434862728782e-05 -1.313465709596e-06 -2.94483623444123e-06 -3.09452265596205e-05 -1.55641618472416e-06 -1.16028178235435e-05 -1.313465709596e-06 0.00013484711659667 2297 2301 0 175 34 2297 2307 0 132 68 0 0 0 0 0 0 0 0 3634 0 0 0 0 0 3652 +491 492 0.999767123367275 0.0160075774274235 -0.0144726120251011 0.142693065954015 -0.0162077377888187 0.99977312680942 -0.013820424938666 0.00541833819621478 0.0142480970551494 0.0140517747854656 0.999799749627737 -0.0116266223978888 3.52610084726425e-05 -4.78411078342069e-06 -5.35095086872594e-06 4.31895041476521e-06 -6.11047602494228e-07 -8.34844903102807e-06 -4.78411078342069e-06 8.27918746342754e-05 5.84994458142304e-06 2.22840690642609e-05 7.87293729521117e-07 -1.18369309653282e-05 -5.35095086872594e-06 5.84994458142304e-06 1.34278975876376e-05 -1.12830571432009e-06 4.52587068328446e-06 -8.53553891846736e-06 4.31895041476521e-06 2.22840690642609e-05 -1.12830571432009e-06 9.17233880562172e-05 -1.9650956817855e-06 -5.63428907016879e-05 -6.11047602494228e-07 7.87293729521117e-07 4.52587068328446e-06 -1.9650956817855e-06 1.06278838640494e-05 -6.71668570689679e-06 -8.34844903102807e-06 -1.18369309653282e-05 -8.53553891846736e-06 -5.63428907016879e-05 -6.71668570689679e-06 0.00048620558585613 3282 3303 0 177 76 3282 3303 0 132 138 0 0 0 0 0 0 0 0 3646 0 0 0 0 0 3664 +499 500 0.998988255961004 -0.0271262417033164 0.035869645426808 0.121932510460513 0.0270144500574603 0.999628569080414 0.003597689027371 0.0074783833946335 -0.0359539141135517 -0.00262505034198208 0.999350001336177 -0.042069814502134 4.46355809599818e-05 -4.12008875279376e-06 9.10414361272087e-06 1.04194514820322e-05 3.97883456694681e-06 1.34687635906888e-07 -4.12008875279376e-06 5.3320962720003e-05 -6.30832776873316e-06 1.05505744753585e-05 8.56098604262007e-09 -2.67442471395235e-05 9.10414361272087e-06 -6.30832776873316e-06 1.25077104780625e-05 1.9162654459172e-07 5.14881963336606e-06 2.59046968426269e-06 1.04194514820322e-05 1.05505744753585e-05 1.9162654459172e-07 0.000174520314760757 1.68758156293996e-06 1.68885645788135e-05 3.97883456694681e-06 8.56098604262007e-09 5.14881963336606e-06 1.68758156293996e-06 1.05055704618056e-05 9.73405969490297e-07 1.34687635906888e-07 -2.67442471395235e-05 2.59046968426269e-06 1.68885645788135e-05 9.73405969490297e-07 0.00010424229963718 3228 3214 0 46 165 3228 3214 0 0 224 0 0 0 0 0 0 0 0 3743 0 0 0 0 0 3552 +497 498 0.999383394461986 -0.0343787254594548 -0.00713681367427002 0.121104564593651 0.0341237378642229 0.998865614533926 -0.0332122660463895 0.0116119522751668 0.00827051315285905 0.0329482524202087 0.999422839079957 0.00761275618406605 3.32100641583472e-05 -8.97124290006008e-06 -4.47704257803972e-06 5.00490828105124e-07 -2.36868851917114e-07 1.18214831607142e-05 -8.97124290006008e-06 0.000322444348524236 -1.06492519341658e-05 0.000232979916729686 -4.33471404495019e-06 -0.000185791315817162 -4.47704257803972e-06 -1.06492519341658e-05 1.24007367820349e-05 -1.81572245787889e-05 4.47363882413564e-06 6.17028063807597e-06 5.00490828105124e-07 0.000232979916729686 -1.81572245787889e-05 0.00206983616253336 3.42983006352103e-05 -0.000269838337668449 -2.36868851917114e-07 -4.33471404495019e-06 4.47363882413564e-06 3.42983006352103e-05 1.16819963730345e-05 6.88980707235167e-06 1.18214831607142e-05 -0.000185791315817162 6.17028063807597e-06 -0.000269838337668449 6.88980707235167e-06 0.000292008147868107 3134 3142 0 18 177 3132 3142 0 0 238 0 0 0 0 0 0 0 0 3772 0 0 0 0 0 3534 +504 505 0.23099085867875 -0.00961486268553129 -0.972908411733804 -0.313808714003692 -0.0271012609727111 0.999499593058836 -0.0163121160157167 -0.00822584005832562 0.972578400367057 0.0301349944542814 0.230614694346864 0.0790580671459299 6.73575503245718e-05 -2.57280312393163e-05 1.13737762711389e-05 -9.16155146646146e-05 -5.2386961270442e-06 8.42366756359646e-05 -2.57280312393163e-05 0.000742011720808212 3.49613161922938e-05 0.000347834768528832 1.47893953393389e-05 0.000802572811212071 1.13737762711389e-05 3.49613161922938e-05 7.43727407377572e-05 -4.57037343423109e-05 -4.22806439242521e-06 0.000238740519163443 -9.16155146646146e-05 0.000347834768528832 -4.57037343423109e-05 0.00149804743809243 5.90221719188505e-05 0.000249607603338432 -5.2386961270442e-06 1.47893953393389e-05 -4.22806439242521e-06 5.90221719188505e-05 1.47546191969475e-05 -1.68930156185864e-05 8.42366756359646e-05 0.000802572811212071 0.000238740519163443 0.000249607603338432 -1.68930156185864e-05 0.0053520269401514 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2470 0 0 0 0 0 2322 +495 496 0.996762492113499 -0.0203102923114335 -0.0777947706591593 0.148466238096948 0.0187395754469144 0.999606606722338 -0.0208676809713605 0.0121752479117948 0.0781879954197348 0.0193422807155 0.996750978704795 0.0599780151613092 3.27904113683334e-05 -1.36554876061858e-05 -9.96929507111752e-06 -7.11009462742539e-06 -2.85727054815121e-06 -9.75488599303916e-06 -1.36554876061858e-05 4.61830308561246e-05 5.03155208277007e-07 -2.98404175896242e-06 3.95299186516025e-07 -1.9326493221464e-05 -9.96929507111752e-06 5.03155208277007e-07 1.20149642116631e-05 -1.53267039407043e-06 4.82960954168359e-06 7.47538385689278e-08 -7.11009462742539e-06 -2.98404175896242e-06 -1.53267039407043e-06 0.000147644007947652 2.87927161515964e-06 -1.69472063226946e-05 -2.85727054815121e-06 3.95299186516025e-07 4.82960954168359e-06 2.87927161515964e-06 1.07581890380247e-05 -3.32575018283861e-06 -9.75488599303916e-06 -1.9326493221464e-05 7.47538385689278e-08 -1.69472063226946e-05 -3.32575018283861e-06 0.000207331888889786 3120 3150 0 74 164 3120 3150 0 36 239 0 0 0 0 0 0 0 0 3717 0 0 0 0 0 3564 +496 497 0.998803754496754 -0.0439374663855874 0.0214606395711864 0.141056998033731 0.0444586049683395 0.998712184045055 -0.0244418879022421 0.0165913087809504 -0.0203590875890383 0.0253667595008114 0.9994708775472 0.0429650497521179 4.01158529907406e-05 -1.21035794718571e-05 -9.06176453035746e-07 1.37604697079459e-05 1.0688284858517e-06 1.17103917974604e-05 -1.21035794718571e-05 0.000109603960346752 2.43423200903012e-06 4.16346883797357e-05 -4.11620780487427e-07 -7.40587099995799e-05 -9.06176453035746e-07 2.43423200903012e-06 1.11946665790934e-05 7.12406498731441e-09 4.34761704222285e-06 -1.93831152054337e-06 1.37604697079459e-05 4.16346883797357e-05 7.12406498731441e-09 0.000279462260016743 1.18531890945695e-05 0.000140729640505139 1.0688284858517e-06 -4.11620780487427e-07 4.34761704222285e-06 1.18531890945695e-05 1.19639107450636e-05 4.24622973859184e-05 1.17103917974604e-05 -7.40587099995799e-05 -1.93831152054337e-06 0.000140729640505139 4.24622973859184e-05 0.00133103622511587 3226 3240 0 14 234 3219 3240 0 2 312 0 0 0 0 0 0 0 0 3775 0 0 0 0 0 3467 +501 502 0.999220384597987 0.0215266371723655 0.0330942124230273 0.140110894406458 -0.0222926146541407 0.999487962362082 0.0229532661113026 -0.00017953189638267 -0.0325831603091707 -0.0236731279163446 0.99918863117978 0.0291711793229189 4.57499739691951e-05 2.80188828354695e-06 1.2827965313511e-06 8.86049454030607e-06 9.70252822727954e-08 -3.32519337301436e-05 2.80188828354695e-06 4.74128847851075e-05 6.7040609629155e-07 2.37853551101454e-05 -1.61863411378038e-06 -5.45177978827838e-06 1.2827965313511e-06 6.7040609629155e-07 1.33514576663427e-05 -3.2138081492823e-07 3.49922606109067e-06 -2.2225117929781e-06 8.86049454030607e-06 2.37853551101454e-05 -3.2138081492823e-07 0.000281584597046833 -4.12001450461284e-06 3.04591851690603e-05 9.70252822727954e-08 -1.61863411378038e-06 3.49922606109067e-06 -4.12001450461284e-06 1.08545023733757e-05 -4.91473809535799e-06 -3.32519337301436e-05 -5.45177978827838e-06 -2.2225117929781e-06 3.04591851690603e-05 -4.91473809535799e-06 0.000400563520693063 3336 3326 0 205 63 3336 3326 0 142 108 0 0 0 0 0 0 0 0 3596 0 0 0 0 0 3659 +498 499 0.998668811643894 -0.0353419506286144 -0.0375706158525148 0.13850299760285 0.0354540207847106 0.999368614152198 0.00232065889612705 0.0103011297273809 0.0374648776852395 -0.00364959905735546 0.99929128054174 0.000874237100756753 3.69028702885949e-05 9.64354869669514e-07 -6.50216157823834e-06 -6.50608017503633e-06 1.52928290761209e-06 -4.73024705820588e-06 9.64354869669514e-07 6.03436130322933e-05 -4.14057226384029e-06 3.24527074550279e-05 -2.04306387677924e-06 -4.85116569920946e-05 -6.50216157823834e-06 -4.14057226384029e-06 1.33722519744904e-05 -2.46234340371426e-07 3.58764818186641e-06 4.17889093443387e-06 -6.50608017503633e-06 3.24527074550279e-05 -2.46234340371426e-07 0.000220587747342611 -6.05082309252178e-06 -4.84927648795623e-05 1.52928290761209e-06 -2.04306387677924e-06 3.58764818186641e-06 -6.05082309252178e-06 1.14740020323664e-05 6.17864897779511e-06 -4.73024705820588e-06 -4.85116569920946e-05 4.17889093443387e-06 -4.84927648795623e-05 6.17864897779511e-06 0.000159968832700159 3267 3266 0 31 202 3267 3266 0 0 259 0 0 0 0 0 0 0 0 3746 0 0 0 0 0 3508 +505 506 0.999791893276512 0.00757281847775219 0.0189426122504382 0.127443262337904 -0.00779599692561903 0.999900741163998 0.0117358532550094 -0.00100458152772421 -0.0188518585424136 -0.0118810874919087 0.999751692766512 0.0232138037318541 3.77437618288709e-05 -1.07245887111515e-05 5.27513336086384e-06 -8.29487054511844e-06 -4.1420747377552e-07 1.45135635172698e-05 -1.07245887111515e-05 5.1998581783442e-05 -1.18154696731112e-06 3.6009838417808e-06 -3.23127602178383e-07 4.6265847115452e-05 5.27513336086384e-06 -1.18154696731112e-06 1.04754890948993e-05 -4.51393246171577e-06 4.58519345735462e-06 7.55473905734827e-06 -8.29487054511844e-06 3.6009838417808e-06 -4.51393246171577e-06 0.000146223075404407 6.52764972062356e-07 6.12243187492879e-05 -4.1420747377552e-07 -3.23127602178383e-07 4.58519345735462e-06 6.52764972062356e-07 9.80401750905218e-06 -7.42036640076948e-06 1.45135635172698e-05 4.6265847115452e-05 7.55473905734827e-06 6.12243187492879e-05 -7.42036640076948e-06 0.000656263306268705 3337 3339 0 148 78 3337 3339 0 98 134 0 0 0 0 0 0 0 0 3691 0 0 0 0 0 3664 +506 507 0.999515140216954 0.00258489184813704 0.0310290639758335 0.0876487657827058 -0.00284681134713223 0.999960667945282 0.00839989449806309 -0.000748114028759628 -0.0310061307201781 -0.00848415561845644 0.999483185932212 0.0319552348730738 4.00686637949845e-05 -1.26084310877135e-05 5.80851601110821e-07 1.4732853093275e-05 -1.84689022652374e-06 9.83440684789734e-06 -1.26084310877135e-05 4.15403909387361e-05 3.22790107528079e-07 -1.72950295497449e-05 -2.25814505624432e-06 -2.02428567722415e-05 5.80851601110821e-07 3.22790107528079e-07 1.12257798698605e-05 -2.81353555252881e-06 2.67081009305443e-06 1.9341784287802e-06 1.4732853093275e-05 -1.72950295497449e-05 -2.81353555252881e-06 0.000316853916153815 1.14455294165956e-05 -3.8260051897227e-05 -1.84689022652374e-06 -2.25814505624432e-06 2.67081009305443e-06 1.14455294165956e-05 1.22566212914098e-05 -5.09013883938414e-06 9.83440684789734e-06 -2.02428567722415e-05 1.9341784287802e-06 -3.8260051897227e-05 -5.09013883938414e-06 0.00015501717641205 3239 3245 0 83 33 3239 3245 0 36 89 0 0 0 0 0 0 0 0 3735 0 0 0 0 0 3714 +500 501 0.999464766454414 -0.00259744684749074 0.0326103340384285 0.137734890534095 0.00196289082956979 0.999808403802044 0.0194756963007635 0.00470436014164708 -0.0326546731083717 -0.0194012617291465 0.999278371309768 0.0141850722544229 4.21331333495293e-05 1.50958363040394e-05 -6.94244367307252e-07 1.01285705695881e-05 -7.50420354839237e-07 -2.79589553861013e-05 1.50958363040394e-05 7.55711810374475e-05 -1.83336617724675e-06 1.89643178366275e-07 1.53113443728308e-07 -5.11579363188644e-05 -6.94244367307252e-07 -1.83336617724675e-06 1.236574914356e-05 4.45540817199619e-07 3.87259858668494e-06 4.20445825233298e-07 1.01285705695881e-05 1.89643178366275e-07 4.45540817199619e-07 0.000461566942590969 -1.52407294074541e-05 -3.35705293239151e-05 -7.50420354839237e-07 1.53113443728308e-07 3.87259858668494e-06 -1.52407294074541e-05 1.11696166440404e-05 -1.49344226928855e-08 -2.79589553861013e-05 -5.11579363188644e-05 4.20445825233298e-07 -3.35705293239151e-05 -1.49344226928855e-08 0.000180669129792453 3260 3244 0 135 126 3260 3244 0 72 176 0 0 0 0 0 0 0 0 3657 0 0 0 0 0 3594 +502 503 0.999599354766148 0.0279951439757557 0.00417155425198644 0.145750748844662 -0.0280158734481255 0.999594990692342 0.00499654057481978 0.0012232308474965 -0.0040299858609142 -0.00511140847065837 0.999978816134325 0.0811439792460077 3.66100993725937e-05 -6.17989017388433e-07 -9.54060448513525e-06 1.6570267691469e-05 -8.82820569577096e-07 -2.15939844155557e-05 -6.17989017388433e-07 0.00020569296637994 -1.75009350630019e-07 -3.42722266430833e-05 -1.12451426019181e-05 0.00127485681729405 -9.54060448513525e-06 -1.75009350630019e-07 1.29456996660186e-05 1.55965548700886e-06 4.33015526515011e-06 -1.77928467363852e-05 1.6570267691469e-05 -3.42722266430833e-05 1.55965548700886e-06 0.000254276661555274 2.43807195948955e-06 -0.000379213686959026 -8.82820569577096e-07 -1.12451426019181e-05 4.33015526515011e-06 2.43807195948955e-06 1.14306334402116e-05 -8.05138675035092e-05 -2.15939844155557e-05 0.00127485681729405 -1.77928467363852e-05 -0.000379213686959026 -8.05138675035092e-05 0.00982873731255018 3434 3425 0 227 52 3434 3425 0 164 99 0 0 0 0 0 0 0 0 3604 0 0 0 0 0 3701 +508 509 0.999713267368925 -0.01774020378392 -0.016083165616664 0.0885417874474359 0.0178002373433666 0.999835092077928 0.00359724895468239 0.00383644366614039 0.0160166974457243 -0.00388250167123428 0.999864186569209 -0.0115942219026155 4.02125850558108e-05 -1.0266143426639e-05 -3.83931881246919e-06 -7.09440813531118e-06 -2.2489520743614e-06 1.31338670069342e-07 -1.0266143426639e-05 0.000112384708670145 3.1711620754542e-06 3.24879352347215e-05 2.4485644550175e-06 -0.000111260895314886 -3.83931881246919e-06 3.1711620754542e-06 1.2643504881738e-05 1.21733454881508e-06 4.54815241834349e-06 -2.92531570676567e-06 -7.09440813531118e-06 3.24879352347215e-05 1.21733454881508e-06 0.000484794157599579 5.43347528614008e-06 8.93064140352364e-05 -2.2489520743614e-06 2.4485644550175e-06 4.54815241834349e-06 5.43347528614008e-06 1.04313227477857e-05 -3.09692087236455e-06 1.31338670069342e-07 -0.000111260895314886 -2.92531570676567e-06 8.93064140352364e-05 -3.09692087236455e-06 0.000234514736704903 3250 3252 0 27 73 3249 3252 0 0 154 0 0 0 0 0 0 0 0 3789 0 0 0 0 0 3635 +511 512 0.999975319539409 -0.000504543349513645 0.00700754936234853 0.144205544698071 0.000501817472362995 0.999999797749025 0.000390744331724493 0.00128538968517766 -0.00700774509251878 -0.00038721817726594 0.999975370482094 0.0067488140474609 4.91527528552534e-05 -1.11172938815217e-05 -6.95211411937387e-06 6.70995520924028e-06 2.52910835299589e-07 2.1511225678518e-05 -1.11172938815217e-05 0.000332894724574554 1.21684884544333e-05 1.05660216925913e-05 5.48853982628409e-06 -0.000294878856752014 -6.95211411937387e-06 1.21684884544333e-05 1.78241392229889e-05 -4.26982577114795e-05 2.22332948538173e-06 -5.43310412837812e-06 6.70995520924028e-06 1.05660216925913e-05 -4.26982577114795e-05 0.00273276057228602 3.48120069474648e-05 -0.000314044867493271 2.52910835299589e-07 5.48853982628409e-06 2.22332948538173e-06 3.48120069474648e-05 1.20706851617342e-05 -1.1145150182112e-05 2.1511225678518e-05 -0.000294878856752014 -5.43310412837812e-06 -0.000314044867493271 -1.1145150182112e-05 0.000373245639972252 3177 3172 0 156 119 3177 3172 0 93 175 0 0 0 0 0 0 0 0 3670 0 0 0 0 0 3610 +507 508 0.99988839475755 -0.0127527226278912 0.00778242216452734 0.0749277039491967 0.0127845598427126 0.999910052087353 -0.00405496785375057 0.00478183333342473 -0.00773001027159441 0.00415401013996377 0.999961494829155 -0.0762926884493383 5.24668923157094e-05 -8.25251685980718e-06 -5.5576247527966e-06 -1.62473789741314e-05 -1.10227997316142e-07 -1.58369795650834e-05 -8.25251685980718e-06 5.22028260871186e-05 1.31235807665227e-06 -1.64927916056711e-06 -3.89006329331695e-06 0.000210978826143369 -5.5576247527966e-06 1.31235807665227e-06 1.73218401638529e-05 8.53398840729859e-07 2.7553233431589e-06 -1.57339782970467e-06 -1.62473789741314e-05 -1.64927916056711e-06 8.53398840729859e-07 0.000676138807660493 1.52476242765485e-05 -3.02593221089593e-05 -1.10227997316142e-07 -3.89006329331695e-06 2.7553233431589e-06 1.52476242765485e-05 1.35597731310137e-05 -3.58675458942998e-05 -1.58369795650834e-05 0.000210978826143369 -1.57339782970467e-06 -3.02593221089593e-05 -3.58675458942998e-05 0.00226904715250227 3432 3440 0 18 59 3431 3440 0 0 112 0 0 0 0 0 0 0 0 3793 0 0 0 0 0 3686 +509 510 0.999280334934819 -0.00853399552385312 -0.0369592090412408 0.116193905654204 0.00868241440116354 0.999954868186758 0.00385710639850532 0.00169618449318302 0.0369246244763809 -0.00417522574261291 0.999309331287003 0.0319733600084383 3.40380150773592e-05 -8.40563056758782e-06 -7.34205340280071e-06 3.22297452674776e-06 2.11941765556548e-07 7.50363086185407e-07 -8.40563056758782e-06 2.71797593703081e-05 3.34433621142176e-06 1.43320111648059e-05 -7.104076111967e-07 -3.51441778134064e-06 -7.34205340280071e-06 3.34433621142176e-06 1.48079302970673e-05 3.23358127640392e-06 2.87011347501595e-06 2.1306677583739e-06 3.22297452674776e-06 1.43320111648059e-05 3.23358127640392e-06 0.000636715141946614 4.61263269437407e-06 2.568545648044e-05 2.11941765556548e-07 -7.104076111967e-07 2.87011347501595e-06 4.61263269437407e-06 1.14581591005446e-05 -5.56176112338077e-06 7.50363086185407e-07 -3.51441778134064e-06 2.1306677583739e-06 2.568545648044e-05 -5.56176112338077e-06 0.00014844676887599 3458 3456 0 82 99 3458 3456 0 29 152 0 0 0 0 0 0 0 0 3739 0 0 0 0 0 3633 +503 504 0.999468435768842 0.0228345015370815 -0.023268679406823 0.136538404730403 -0.0234679629023034 0.999351104060677 -0.0273244493068375 0.00316416091860991 0.0226296402755456 0.0278559931120549 0.999355763994355 0.00566560645389609 3.85997862318996e-05 -6.88159088567453e-06 -7.18151719353414e-06 -3.03593937328892e-06 -5.00621672843135e-07 -3.47012494612723e-06 -6.88159088567453e-06 4.15368377116813e-05 1.44854432221788e-06 2.73100293235665e-05 7.8482699981169e-07 -3.62855316746809e-05 -7.18151719353414e-06 1.44854432221788e-06 1.21347175433575e-05 -4.46082959766511e-06 1.74080876245655e-06 2.00816840318473e-06 -3.03593937328892e-06 2.73100293235665e-05 -4.46082959766511e-06 0.000424282884574898 1.37627048435106e-05 6.43795659837655e-06 -5.00621672843135e-07 7.8482699981169e-07 1.74080876245655e-06 1.37627048435106e-05 1.3240829824325e-05 -2.81516038346987e-06 -3.47012494612723e-06 -3.62855316746809e-05 2.00816840318473e-06 6.43795659837655e-06 -2.81516038346987e-06 0.000103642788192997 3280 3278 0 199 58 3280 3278 0 139 102 0 0 0 0 0 0 0 0 3620 0 0 0 0 0 3696 +513 514 0.900201194455126 0.0108749797749678 0.435338425040173 -0.0273972164808816 -0.00929228074374781 0.999940211579178 -0.00576426799939586 0.00533491520341402 -0.435375083141128 0.00114371407420131 0.900248426212439 -0.231330550526156 3.87391181111158e-05 -3.18185284644364e-06 1.28553037305575e-05 2.53270937219028e-06 3.99557001221851e-06 7.28379840087532e-05 -3.18185284644364e-06 0.000561347042052225 8.06100109969377e-06 -0.00077453259073634 -4.71467976328483e-05 0.00281193549359848 1.28553037305575e-05 8.06100109969377e-06 2.08282382655522e-05 1.77950140628918e-06 2.63608562162268e-06 4.69993682406636e-06 2.53270937219028e-06 -0.00077453259073634 1.77950140628918e-06 0.00289145777443717 0.000144043980853129 -0.00582168234645351 3.99557001221851e-06 -4.71467976328483e-05 2.63608562162268e-06 0.000144043980853129 1.86565054633771e-05 -0.000351052237675686 7.28379840087532e-05 0.00281193549359848 4.69993682406636e-06 -0.00582168234645351 -0.000351052237675686 0.0214096993603473 601 596 0 15 1 595 602 0 0 9 0 0 0 0 0 0 0 0 3091 0 0 2 0 0 3278 +515 516 0.9998292741956 0.0135678592014323 0.0125433511546908 0.149626514291194 -0.0135764167987915 0.999907657782682 0.000597339482159704 -0.00120597526762955 -0.0125340882558432 -0.000767531264225797 0.999921150655067 -0.0164890913145577 5.8177009329668e-05 -1.30477880059435e-05 -1.25320371755455e-05 3.69459998763692e-05 3.48037861036232e-06 -3.5408397505702e-06 -1.30477880059435e-05 4.47198266388249e-05 4.23055357475226e-06 2.38550123104514e-05 -6.2726593139605e-07 3.98475542458415e-06 -1.25320371755455e-05 4.23055357475226e-06 1.82164580511745e-05 -2.35460643069777e-06 3.11996509983012e-06 1.28789315435743e-05 3.69459998763692e-05 2.38550123104514e-05 -2.35460643069777e-06 0.000388612101527305 2.22830562763691e-05 4.65978952212116e-05 3.48037861036232e-06 -6.2726593139605e-07 3.11996509983012e-06 2.22830562763691e-05 1.48373202628283e-05 -3.42481294008408e-06 -3.5408397505702e-06 3.98475542458415e-06 1.28789315435743e-05 4.65978952212116e-05 -3.42481294008408e-06 0.000431983585638128 3206 3226 0 182 89 3206 3226 0 130 151 0 0 0 0 0 0 0 0 3649 0 0 0 0 0 3651 +510 511 0.999943752796986 -0.00877815820809543 0.00595274564837002 0.119786671188763 0.00888802953742022 0.999785837633071 -0.0186890823552292 0.00832622384597985 -0.00578741507259391 0.0187409393257712 0.999807623005529 -0.0345836260808191 4.14304054451089e-05 -5.22552359005503e-06 -2.65754018198531e-06 1.52860718257673e-06 9.60645817637985e-07 -1.67743186216845e-05 -5.22552359005503e-06 3.86935242447504e-05 5.21766284253156e-06 4.38318813705157e-05 -6.1028085190248e-07 3.15720713691926e-05 -2.65754018198531e-06 5.21766284253156e-06 1.27336113423825e-05 9.23048701925704e-06 3.53750854152377e-06 3.99400668023486e-06 1.52860718257673e-06 4.38318813705157e-05 9.23048701925704e-06 0.000569417707747187 -7.55114819564705e-06 0.000278306289708305 9.60645817637985e-07 -6.1028085190248e-07 3.53750854152377e-06 -7.55114819564705e-06 1.068675164619e-05 -8.27837880211194e-06 -1.67743186216845e-05 3.15720713691926e-05 3.99400668023486e-06 0.000278306289708305 -8.27837880211194e-06 0.000463399608749462 3354 3351 0 86 127 3354 3351 0 32 174 0 0 0 0 0 0 0 0 3725 0 0 0 0 0 3617 +517 518 0.999707524489173 -0.0227138289223472 0.0083034604482926 0.145078304090084 0.0227647613510397 0.999722289881116 -0.00609169561688457 0.00145544790771917 -0.00816278876121543 0.00627894024059039 0.999946970488483 0.00982905199802399 4.92638554368028e-05 -3.22249955956988e-05 -5.60151691680745e-06 -6.35837662440598e-06 -9.16938140262375e-07 3.50741947754716e-05 -3.22249955956988e-05 0.00035948560679419 -5.89623396382062e-07 0.000238802701762413 1.06601193714255e-05 -0.000344645587287764 -5.60151691680745e-06 -5.89623396382062e-07 1.34761951437883e-05 9.47924347683487e-07 4.56094134847626e-06 7.97236759917278e-07 -6.35837662440598e-06 0.000238802701762413 9.47924347683487e-07 0.000317702917133859 6.08942681930248e-06 -0.000216537358207184 -9.16938140262375e-07 1.06601193714255e-05 4.56094134847626e-06 6.08942681930248e-06 1.16146576430842e-05 -9.26683097267153e-06 3.50741947754716e-05 -0.000344645587287764 7.97236759917278e-07 -0.000216537358207184 -9.26683097267153e-06 0.000505085579948454 3132 3149 0 84 167 3132 3149 0 37 236 0 0 0 0 0 0 0 0 3730 0 0 0 0 0 3538 +516 517 0.99955739430222 -0.0027427503792182 0.0296225052301897 0.127618158291993 0.00264071347231219 0.999990447118701 0.00348314566119459 -0.00261169267297824 -0.0296317756489965 -0.00340337945243375 0.999555088466959 0.0233216902183227 5.14609398461561e-05 -1.44050845514673e-05 -5.34633907852962e-06 1.6149715134529e-05 -2.74528466156304e-07 1.72538624508048e-05 -1.44050845514673e-05 3.29496752864214e-05 -1.9000504792855e-06 1.10275771258792e-05 -4.57028837777862e-07 -2.92996703587554e-05 -5.34633907852962e-06 -1.9000504792855e-06 1.33903715731154e-05 -1.22103792631144e-06 5.63559624663211e-06 3.351123718618e-06 1.6149715134529e-05 1.10275771258792e-05 -1.22103792631144e-06 0.000129343817344763 3.4001801636847e-06 -9.33607211050188e-06 -2.74528466156304e-07 -4.57028837777862e-07 5.63559624663211e-06 3.4001801636847e-06 1.12195072197955e-05 -8.35018853487631e-07 1.72538624508048e-05 -2.92996703587554e-05 3.351123718618e-06 -9.33607211050188e-06 -8.35018853487631e-07 7.77048865369725e-05 3233 3252 0 117 98 3233 3252 0 73 159 0 0 0 0 0 0 0 0 3713 0 0 0 0 0 3622 +512 513 0.999458330543005 0.0166997123411392 0.0283578052026561 0.35795488250302 -0.017043416991208 0.999783668986799 0.0119221291957067 -0.00100340680500069 -0.0281525744018622 -0.0123989852414833 0.99952673687077 0.0552040165378031 6.2795507780162e-05 -7.7025744541799e-06 -2.26548556342928e-06 8.19162315817141e-06 1.10130312734667e-06 1.53633465903792e-06 -7.7025744541799e-06 5.51845488169103e-05 3.22879059857345e-06 -2.31664536226956e-05 -8.44726409940406e-07 -5.33209668468133e-05 -2.26548556342928e-06 3.22879059857345e-06 1.46369190314036e-05 -3.24655788313578e-06 4.42631129224803e-06 -2.67589855147017e-06 8.19162315817141e-06 -2.31664536226956e-05 -3.24655788313578e-06 0.00462550998926631 7.53906938374291e-05 0.00105611826599063 1.10130312734667e-06 -8.44726409940406e-07 4.42631129224803e-06 7.53906938374291e-05 1.37336475857708e-05 1.61231573293798e-05 1.53633465903792e-06 -5.33209668468133e-05 -2.67589855147017e-06 0.00105611826599063 1.61231573293798e-05 0.000339623910459586 3219 3217 0 531 383 3219 3217 0 456 447 0 0 0 0 0 0 0 0 3295 0 0 0 0 0 3347 +518 519 0.99936316210631 -0.0256572229897999 -0.024798732494417 0.138278987315206 0.0251393604153163 0.999463917328852 -0.0209735670684653 -0.00106765478505231 0.0253235618108275 0.0203367860321701 0.999472427008917 -0.00588561302956978 3.54813630164247e-05 -7.74265452936858e-06 -4.13455641660722e-06 -1.01068360471297e-05 -2.24417631239519e-06 7.938525593561e-06 -7.74265452936858e-06 3.29800686701209e-05 6.85447594401204e-07 5.09839989564262e-06 4.15942259375756e-07 -7.16774792786333e-06 -4.13455641660722e-06 6.85447594401204e-07 1.18604279677634e-05 -2.93368808662295e-06 5.6593197892004e-06 -2.16181401190086e-06 -1.01068360471297e-05 5.09839989564262e-06 -2.93368808662295e-06 0.000152780161032047 -9.3027574945485e-09 4.67217682011946e-05 -2.24417631239519e-06 4.15942259375756e-07 5.6593197892004e-06 -9.3027574945485e-09 1.06424481323412e-05 1.90807420418619e-06 7.938525593561e-06 -7.16774792786333e-06 -2.16181401190086e-06 4.67217682011946e-05 1.90807420418619e-06 0.000199949756521507 3343 3356 0 80 163 3343 3356 0 29 231 0 0 0 0 0 0 0 0 3743 0 0 0 0 0 3542 +522 523 0.999836293826013 0.00612057972052634 0.0170271563141763 0.14447549607216 -0.00602510081797759 0.999965869683311 -0.00565310787375713 -0.00553670499828277 -0.017061175469349 0.00554959209165961 0.999839046206548 0.0349864807508084 6.89515332995438e-05 3.84481469547629e-05 -6.79422865799453e-06 3.14240823600843e-05 -1.48870138778055e-06 -2.68487282291114e-05 3.84481469547629e-05 0.000145689676459178 -4.67241883589409e-06 7.00597098030007e-05 -3.42028095523199e-06 -0.000108095277494928 -6.79422865799453e-06 -4.67241883589409e-06 1.27059860974989e-05 -3.6910083429356e-06 5.01671726767378e-06 2.9966884696705e-06 3.14240823600843e-05 7.00597098030007e-05 -3.6910083429356e-06 0.000244289331394623 -8.54641772850965e-06 -1.80006368752425e-05 -1.48870138778055e-06 -3.42028095523199e-06 5.01671726767378e-06 -8.54641772850965e-06 1.19949689092479e-05 7.2245445886457e-06 -2.68487282291114e-05 -0.000108095277494928 2.9966884696705e-06 -1.80006368752425e-05 7.2245445886457e-06 0.000308998392332954 3249 3292 0 86 93 3249 3300 0 122 151 0 0 0 0 0 0 19 0 3634 0 0 0 0 0 3606 +514 515 0.998775731458266 0.0201694348152118 -0.0451689290247179 0.148268526746033 -0.0201998424538022 0.999795938857077 -0.00021681729140389 -0.00477472014384277 0.0451553387192108 0.001128957098921 0.998979339546631 -0.0556764132181788 5.19901019014846e-05 -1.72344950380539e-06 -6.31794804995889e-06 1.77819575640892e-06 2.59786529492528e-06 3.31891207257194e-06 -1.72344950380539e-06 0.000118014822549469 2.68330794078551e-06 5.51873715335451e-06 -7.87526936489951e-07 -0.000100583856971093 -6.31794804995889e-06 2.68330794078551e-06 1.57178115670143e-05 -7.25303046415272e-08 3.12114568661184e-06 -1.09791581184512e-06 1.77819575640892e-06 5.51873715335451e-06 -7.25303046415272e-08 0.000227045649083008 9.23967550792775e-06 -7.42658531335219e-06 2.59786529492528e-06 -7.87526936489951e-07 3.12114568661184e-06 9.23967550792775e-06 1.32791990165219e-05 6.53509056943338e-07 3.31891207257194e-06 -0.000100583856971093 -1.09791581184512e-06 -7.42658531335219e-06 6.53509056943338e-07 0.000149897788831006 3173 3185 0 211 65 3173 3185 0 158 119 0 0 0 0 0 0 0 0 3643 0 0 0 0 0 3671 +523 524 0.999705561767958 0.0235803767595151 0.00572325100713027 0.141409480307924 -0.0235824959047062 0.999721848337161 0.000303058138402679 -0.0100197956283944 -0.00571451285026222 -0.000437937449937457 0.999983576141966 0.0120809879113694 7.16690592046089e-05 -1.73915777816231e-05 2.44938353248713e-06 -2.80636390911221e-06 2.45704557211289e-06 2.23959898840383e-05 -1.73915777816231e-05 5.72472261337769e-05 -2.9816465490144e-06 -1.14914428003893e-06 -7.41324238436368e-07 -1.59841860707469e-05 2.44938353248713e-06 -2.9816465490144e-06 1.29616528895115e-05 -1.25732952774517e-06 4.54866736504624e-06 5.55346090521548e-07 -2.80636390911221e-06 -1.14914428003893e-06 -1.25732952774517e-06 0.000105271233494452 -4.43141116867089e-06 1.65456236309033e-05 2.45704557211289e-06 -7.41324238436368e-07 4.54866736504624e-06 -4.43141116867089e-06 1.09412496771969e-05 2.82678707755763e-06 2.23959898840383e-05 -1.59841860707469e-05 5.55346090521548e-07 1.65456236309033e-05 2.82678707755763e-06 0.000214834924761781 3298 3305 0 173 43 3298 3305 0 164 98 0 0 0 0 0 0 0 0 3485 0 0 0 0 0 3664 +519 520 0.999185071270427 -0.0323480290562337 -0.0241412171708254 0.128766667390898 0.0322673813767874 0.999472338973191 -0.00372286536736177 -0.0011918091619796 0.0242489061484605 0.0029408576360667 0.999701626440093 -0.00233138322811176 4.6309939735317e-05 1.38822207290896e-06 -8.08407895980086e-06 -2.69953908166282e-06 -1.80012714279581e-06 4.48624019558689e-06 1.38822207290896e-06 3.41303537653316e-05 -3.24217934391167e-06 5.48607933974265e-06 8.14373927654476e-07 -2.61123644531986e-05 -8.08407895980086e-06 -3.24217934391167e-06 1.23016895814829e-05 -1.05755125051066e-06 5.12440284362835e-06 4.32952941756445e-06 -2.69953908166282e-06 5.48607933974265e-06 -1.05755125051066e-06 8.75425539255301e-05 -6.62711530232329e-07 -1.10742364123076e-05 -1.80012714279581e-06 8.14373927654476e-07 5.12440284362835e-06 -6.62711530232329e-07 1.136840519979e-05 -1.67320402971141e-06 4.48624019558689e-06 -2.61123644531986e-05 4.32952941756445e-06 -1.10742364123076e-05 -1.67320402971141e-06 7.2508011208975e-05 3241 3292 0 41 164 3241 3292 0 4 225 0 0 0 0 0 0 0 0 3767 0 0 0 0 0 3520 +527 528 0.999421575213493 -0.000489058509626693 0.0340040559279853 0.134443367016836 7.20066959070321e-05 0.99992478057281 0.0122649097613433 0.000606986084620992 -0.0340074964208648 -0.0122553669138183 0.999346434510572 0.0117408778853584 5.30218706907451e-05 -1.01465505941474e-05 3.19282027045564e-06 -5.6256859741668e-06 -2.78320059750798e-06 6.25223247527173e-06 -1.01465505941474e-05 3.00541136869466e-05 -2.38190334858451e-06 5.73756139761571e-06 1.6175333375374e-06 -1.00228214287208e-05 3.19282027045564e-06 -2.38190334858451e-06 1.41326250539233e-05 -8.8131050003965e-06 3.21277228434459e-06 7.3805236155675e-07 -5.6256859741668e-06 5.73756139761571e-06 -8.8131050003965e-06 0.000102149080885791 6.50936352063841e-06 2.45707351135385e-05 -2.78320059750798e-06 1.6175333375374e-06 3.21277228434459e-06 6.50936352063841e-06 1.39603304907787e-05 -8.05305248396595e-07 6.25223247527173e-06 -1.00228214287208e-05 7.3805236155675e-07 2.45707351135385e-05 -8.05305248396595e-07 0.000281071580923195 3297 3378 0 50 111 3297 3385 0 79 184 0 0 0 0 0 0 18 0 3227 0 0 0 0 0 3600 +526 527 0.999778712296566 0.0149727892653433 0.0147764007875847 0.14988133830828 -0.0154389351722612 0.999370101523614 0.0319537081013854 -0.00536358857008943 -0.0142886570175938 -0.0321747690325423 0.999380117131783 0.0202463273697527 9.64017133469967e-05 -2.33884089516254e-06 8.39633012188469e-07 2.44023827577225e-05 6.60529204533808e-06 3.57992137543266e-06 -2.33884089516254e-06 2.92789910785039e-05 3.64416738693072e-06 1.14669781710039e-05 8.1570844059407e-07 -6.91173189378186e-06 8.39633012188469e-07 3.64416738693072e-06 1.74906090907922e-05 -1.43682343156244e-05 5.32064381706066e-08 1.17567318508133e-06 2.44023827577225e-05 1.14669781710039e-05 -1.43682343156244e-05 0.000132214047438913 1.19486603333956e-05 2.14593662224224e-05 6.60529204533808e-06 8.1570844059407e-07 5.32064381706066e-08 1.19486603333956e-05 1.63577676009217e-05 -1.44958149464032e-06 3.57992137543266e-06 -6.91173189378186e-06 1.17567318508133e-06 2.14593662224224e-05 -1.44958149464032e-06 0.000158918801604409 3472 3556 0 144 74 3472 3556 0 121 149 0 0 0 0 0 0 0 0 3221 0 0 0 0 0 3629 +521 522 0.99912241620843 -0.00554965243689991 0.0415162472733099 0.13409946846319 0.00528691125852923 0.999965314212536 0.00643575490276738 -0.00156508841565852 -0.0415505234524601 -0.00621061427345705 0.9991171013806 0.101836644190536 5.32139840328761e-05 -1.61671437696021e-05 2.25010248301187e-08 4.96551016291154e-06 -4.38567977716069e-06 -0.00012664480502287 -1.61671437696021e-05 0.000141355434080915 -2.67650115428069e-06 9.16032402972305e-06 2.69554452881573e-05 0.000863159805158394 2.25010248301187e-08 -2.67650115428069e-06 1.35777140495973e-05 3.26418081123833e-06 2.32547712017299e-06 -2.66920240830277e-05 4.96551016291154e-06 9.16032402972305e-06 3.26418081123833e-06 0.000140545711490095 -3.81482367089892e-06 0.00011817471175508 -4.38567977716069e-06 2.69554452881573e-05 2.32547712017299e-06 -3.81482367089892e-06 1.88393999752963e-05 0.000198305845848947 -0.00012664480502287 0.000863159805158394 -2.66920240830277e-05 0.00011817471175508 0.000198305845848947 0.00709415520118317 3352 3416 0 57 122 3352 3438 0 95 172 0 0 0 0 0 13 46 0 3714 0 0 0 0 0 3571 +520 521 0.999657669932119 -0.0230455989345057 -0.0123872238874137 0.129542194842591 0.0228469127918275 0.999611753610855 -0.0159486870592438 0.0001406479771979 0.0127499616379671 0.0156602175202316 0.999796077240479 -0.0149353962825355 5.17379160459398e-05 -1.43475733739189e-06 -1.95084703783264e-06 -1.51189689104702e-05 3.5731618638916e-06 1.26725960489995e-05 -1.43475733739189e-06 7.24605761912158e-05 -3.10498212316053e-06 -7.86545575094154e-06 1.45702877218631e-06 -4.10716224102347e-05 -1.95084703783264e-06 -3.10498212316053e-06 1.36983393673068e-05 4.36108433125557e-06 4.05905265653061e-06 -4.55378618414347e-06 -1.51189689104702e-05 -7.86545575094154e-06 4.36108433125557e-06 0.000161113006926617 -8.9221038791058e-06 -7.03205287448262e-06 3.5731618638916e-06 1.45702877218631e-06 4.05905265653061e-06 -8.9221038791058e-06 1.23809258959312e-05 1.37280100893527e-05 1.26725960489995e-05 -4.10716224102347e-05 -4.55378618414347e-06 -7.03205287448262e-06 1.37280100893527e-05 0.000328699101658536 3238 3300 0 33 145 3238 3300 0 33 205 0 0 0 0 0 5 8 0 3744 0 0 0 0 0 3542 +529 530 0.99947090310522 -0.0309124416978599 -0.0101160661480615 0.126085876525102 0.0308643775374584 0.999511700748374 -0.0048734244959757 0.00793345312558629 0.0102617759311328 0.00455861989742026 0.999936955482379 -0.0487407708633903 3.78990698937747e-05 9.46528689284281e-06 1.60925424104678e-06 -5.50793253493149e-06 -1.23433350294397e-06 7.94054987302125e-06 9.46528689284281e-06 0.000157289578363147 6.46950159992459e-07 5.82284306203829e-06 -5.10766799101066e-08 -9.82559100284322e-05 1.60925424104678e-06 6.46950159992459e-07 1.17418405557475e-05 -5.98327038512937e-07 5.43579996452064e-06 2.1531132297688e-07 -5.50793253493149e-06 5.82284306203829e-06 -5.98327038512937e-07 0.00020744226522927 -2.2668781321261e-06 -1.12949500708587e-05 -1.23433350294397e-06 -5.10766799101066e-08 5.43579996452064e-06 -2.2668781321261e-06 1.15861424781806e-05 2.74402700055361e-07 7.94054987302125e-06 -9.82559100284322e-05 2.1531132297688e-07 -1.12949500708587e-05 2.74402700055361e-07 0.000163290658315027 3147 3156 0 39 175 3146 3156 0 1 236 0 0 0 0 0 0 4 0 3305 0 0 0 0 0 3525 +524 525 0.999731515963315 0.0225920764488624 -0.00514723920381534 0.138351472204523 -0.0226617431279675 0.999646495417425 -0.013904301423037 -0.00755292663417657 0.0048312925904519 0.0140172137527187 0.999890082124288 -0.0152465680858034 0.000102799214788016 -1.60466797993843e-05 -2.20578934926176e-06 1.7192450879381e-05 5.71962696440354e-06 1.47727902807451e-05 -1.60466797993843e-05 3.61421050239503e-05 -2.17897508930183e-07 6.4106429350585e-06 -6.47132642377306e-07 -8.74254262058003e-06 -2.20578934926176e-06 -2.17897508930183e-07 1.36423177390715e-05 -2.67845648823034e-06 4.42203016141321e-06 4.28400247019943e-06 1.7192450879381e-05 6.4106429350585e-06 -2.67845648823034e-06 0.000118248223566488 9.14002667098415e-07 4.42909553983993e-05 5.71962696440354e-06 -6.47132642377306e-07 4.42203016141321e-06 9.14002667098415e-07 1.27638500322685e-05 2.81265112918725e-06 1.47727902807451e-05 -8.74254262058003e-06 4.28400247019943e-06 4.42909553983993e-05 2.81265112918725e-06 0.000174351115966613 3319 3333 0 207 38 3319 3333 0 153 96 0 0 0 0 0 0 0 0 3316 0 0 0 0 0 3678 +528 529 0.999666944626595 -0.0239579632687722 0.00959248752624055 0.140155407578371 0.0241023177967703 0.999593524758198 -0.0152270659781971 0.0108143340201732 -0.00922377893015703 0.0154531957048708 0.999838047208024 0.0013436031375871 3.61132904714594e-05 -7.90319550314283e-07 -8.2928397448025e-07 -1.978602868811e-06 7.25261332376539e-07 4.57036276135371e-06 -7.90319550314283e-07 1.62248001659338e-05 -1.0847321587551e-07 4.19087507837151e-06 1.57723318595958e-06 1.98278492216107e-06 -8.2928397448025e-07 -1.0847321587551e-07 1.42936393927356e-05 -1.53074709481919e-06 1.88070745549527e-06 -1.69431988020056e-06 -1.978602868811e-06 4.19087507837151e-06 -1.53074709481919e-06 0.000173690884080518 2.06339410975644e-06 4.54101837671411e-05 7.25261332376539e-07 1.57723318595958e-06 1.88070745549527e-06 2.06339410975644e-06 1.54327045599064e-05 -1.00473022036683e-06 4.57036276135371e-06 1.98278492216107e-06 -1.69431988020056e-06 4.54101837671411e-05 -1.00473022036683e-06 0.000143678411128398 3492 3511 0 24 174 3500 3531 0 46 245 0 0 0 0 0 8 29 0 3370 0 0 0 0 0 3524 +525 526 0.998607330241671 0.0196539777747721 -0.048960403850776 0.146016774000232 -0.0196332340064908 0.999806840247155 0.000904609001714197 -0.00547035742208981 0.0489687258364835 5.79018857401803e-05 0.998800310641383 0.00395956301985614 6.50907027458609e-05 5.57843334731845e-07 -2.23710711361887e-06 -8.37152125712125e-06 5.44545692421115e-06 2.80472842897841e-05 5.57843334731845e-07 5.82915985610457e-05 1.6218193144318e-06 1.72223780104273e-05 1.07972482106409e-07 -3.44698609970769e-05 -2.23710711361887e-06 1.6218193144318e-06 1.80167433105017e-05 -6.11755879793154e-07 2.07416217735133e-06 8.04048889487296e-08 -8.37152125712125e-06 1.72223780104273e-05 -6.11755879793154e-07 0.000165781741496694 2.46938489632107e-06 -6.1636788110252e-06 5.44545692421115e-06 1.07972482106409e-07 2.07416217735133e-06 2.46938489632107e-06 1.5194228759518e-05 4.86242672556221e-06 2.80472842897841e-05 -3.44698609970769e-05 8.04048889487296e-08 -6.1636788110252e-06 4.86242672556221e-06 0.000123868751547161 3108 3157 0 197 54 3108 3157 0 148 126 0 0 0 0 0 0 0 0 3330 0 0 0 0 0 3639 +532 533 0.99940810542205 -0.0128015745580586 0.0319305262334175 0.184985655575815 0.0124150478302501 0.999847592760633 0.0122742754629608 -0.002353591428297 -0.032082789842548 -0.0118705913754331 0.999414720552142 0.0421526197862307 0.000117707838326867 -1.77036988656302e-07 -1.27804911560647e-06 -3.67334484697075e-05 4.50612933140117e-06 6.11062656038235e-05 -1.77036988656302e-07 2.69033378244974e-05 -1.45465933102219e-06 1.05284548471585e-05 -6.89636468303858e-07 5.0757226912508e-07 -1.27804911560647e-06 -1.45465933102219e-06 1.21206422969985e-05 -5.37324833320953e-06 2.11770431563744e-06 -3.13332466349077e-06 -3.67334484697075e-05 1.05284548471585e-05 -5.37324833320953e-06 0.000306328323039102 -1.96943481234808e-05 0.000102102010342015 4.50612933140117e-06 -6.89636468303858e-07 2.11770431563744e-06 -1.96943481234808e-05 1.60640389725118e-05 -4.89856873751676e-06 6.11062656038235e-05 5.0757226912508e-07 -3.13332466349077e-06 0.000102102010342015 -4.89856873751676e-06 0.000207419803472633 3430 3414 0 183 206 3430 3414 0 118 252 0 0 0 0 0 0 0 0 2972 0 0 0 0 0 3519 +534 535 0.999713480360868 0.0219447153107486 0.00955963674470221 0.153476611325436 -0.0220521804689506 0.999693127371617 0.0112850530579306 -0.00887126495814159 -0.009309055877225 -0.0114926305033127 0.999890624479892 0.0240397854023607 8.60472047576758e-05 6.44026859727924e-05 5.66132688953666e-07 2.98916381169692e-05 -6.36290515353819e-07 -3.18088757732454e-05 6.44026859727924e-05 0.000347260404947212 1.34080897259459e-05 3.6417763582115e-05 7.80795536047829e-06 -0.000268387087724194 5.66132688953666e-07 1.34080897259459e-05 1.97870842677159e-05 -5.71633516870796e-06 -1.65727572884176e-06 -1.51626901428941e-05 2.98916381169692e-05 3.6417763582115e-05 -5.71633516870796e-06 0.00019901819865272 3.88460573785939e-07 -7.30391861441475e-05 -6.36290515353819e-07 7.80795536047829e-06 -1.65727572884176e-06 3.88460573785939e-07 1.74576665634365e-05 -6.67002387032047e-06 -3.18088757732454e-05 -0.000268387087724194 -1.51626901428941e-05 -7.30391861441475e-05 -6.67002387032047e-06 0.000370707468638554 3308 3299 0 239 70 3308 3299 0 174 119 0 0 0 0 0 0 0 0 2907 0 0 0 0 0 3664 +536 537 0.999409530189972 0.0320928306867796 -0.0122735970265417 0.185961363038186 -0.0319910676083467 0.99945285931154 0.00839961947150409 -0.00852237826974108 0.0125364492077471 -0.00800201427751674 0.999889396487813 0.0490689541072442 4.15534215301318e-05 3.98188128411727e-06 -1.86897590735249e-06 1.07110752920954e-06 1.12154774556674e-06 -1.42974577066008e-06 3.98188128411727e-06 0.000117542104662611 -1.21358789532807e-06 1.77812086784059e-05 2.19238400425208e-06 -5.27991524731484e-05 -1.86897590735249e-06 -1.21358789532807e-06 1.57472627607423e-05 -9.94721835250433e-06 -4.31408996416736e-07 1.99808996468678e-06 1.07110752920954e-06 1.77812086784059e-05 -9.94721835250433e-06 0.000145973867733329 1.03291673832862e-05 -6.39051668620758e-06 1.12154774556674e-06 2.19238400425208e-06 -4.31408996416736e-07 1.03291673832862e-05 1.63012263866958e-05 -1.46945225563155e-06 -1.42974577066008e-06 -5.27991524731484e-05 1.99808996468678e-06 -6.39051668620758e-06 -1.46945225563155e-06 0.000218276836221434 3275 3284 0 269 82 3275 3284 0 230 138 0 0 0 0 0 0 0 0 3199 0 0 0 0 0 3642 +530 531 0.999299652156503 -0.0348875604227219 -0.0135300897130404 0.105380084169809 0.0347521550578889 0.999344752302444 -0.0101170037263291 0.0101381800656875 0.0138741817317074 0.00963971852893198 0.999857281269661 -0.0111397240858839 0.00016622443865839 9.18726155425234e-06 5.51770608153288e-06 -5.24972473701424e-05 9.43082372386422e-06 8.22190198566739e-05 9.18726155425234e-06 5.48241228435205e-05 -3.11027638044086e-06 -9.31172268555681e-05 5.57305643030984e-06 1.45060847534507e-05 5.51770608153288e-06 -3.11027638044086e-06 1.56169371910144e-05 2.05330842738613e-05 1.83445793628393e-06 2.98033225155506e-06 -5.24972473701424e-05 -9.31172268555681e-05 2.05330842738613e-05 0.002930589070186 -9.82366919917956e-05 -0.000544591293099168 9.43082372386422e-06 5.57305643030984e-06 1.83445793628393e-06 -9.82366919917956e-05 1.93959378319151e-05 2.73190815730692e-05 8.22190198566739e-05 1.45060847534507e-05 2.98033225155506e-06 -0.000544591293099168 2.73190815730692e-05 0.000473058250445973 3368 3368 0 7 152 3346 3368 0 0 211 0 0 0 0 0 0 0 0 3230 0 0 0 0 0 3540 +535 536 0.999141413316006 0.040059153561614 -0.0105688416026051 0.160010188974993 -0.0403294495662379 0.998828608885921 -0.0267384660872846 -0.00406433841569355 0.00948534103647312 0.0271417443607374 0.999586591555968 0.00735317179836607 6.75951845268579e-05 -6.23641584955949e-06 1.14610250394936e-06 -1.56829751154549e-05 2.35481810856671e-06 3.60126476915123e-05 -6.23641584955949e-06 0.000158434943586448 -9.56145002227965e-07 4.53753866424427e-05 1.96350251340383e-06 -7.31505476017865e-05 1.14610250394936e-06 -9.56145002227965e-07 1.58768816421823e-05 -2.45603216069814e-06 -5.11569017380966e-07 2.31169461848141e-06 -1.56829751154549e-05 4.53753866424427e-05 -2.45603216069814e-06 0.000371398623234566 -2.99482770665537e-07 -4.7998260772224e-05 2.35481810856671e-06 1.96350251340383e-06 -5.11569017380966e-07 -2.99482770665537e-07 1.56120712735729e-05 6.29319775672296e-07 3.60126476915123e-05 -7.31505476017865e-05 2.31169461848141e-06 -4.7998260772224e-05 6.29319775672296e-07 0.000147599654625572 3274 3275 0 282 36 3274 3275 0 219 82 0 0 0 0 0 0 0 0 2990 0 0 0 0 0 3708 +538 539 0.999946387255488 -0.00487342988826147 0.00913631741029531 0.151963954682588 0.00490832349973221 0.999980731348629 -0.00380069623668386 0.00110068167347481 -0.00911761893914426 0.00384533647237352 0.999951040007607 -0.00244988643788006 5.68708715410108e-05 -9.06536059718931e-07 -2.17430977139521e-06 -3.56320158033541e-05 -1.40611597231217e-06 -2.99128510651249e-06 -9.06536059718931e-07 3.4601278532683e-05 3.08886227415018e-06 9.48474389853495e-06 -8.94700886454365e-08 3.52763097428319e-05 -2.17430977139521e-06 3.08886227415018e-06 1.24220826338598e-05 -5.51472894195769e-06 1.31032729209207e-06 5.5864492378394e-06 -3.56320158033541e-05 9.48474389853495e-06 -5.51472894195769e-06 0.000205024677560966 8.42150007491523e-06 5.99249206931194e-05 -1.40611597231217e-06 -8.94700886454365e-08 1.31032729209207e-06 8.42150007491523e-06 1.38879417435609e-05 -5.38910603791555e-06 -2.99128510651249e-06 3.52763097428319e-05 5.5864492378394e-06 5.99249206931194e-05 -5.38910603791555e-06 0.000273561878936743 3389 3404 0 139 140 3389 3404 0 93 205 0 0 0 0 0 0 0 0 3304 0 0 0 0 0 3584 +531 532 0.999327679775954 -0.0262557272019982 -0.02558955299928 0.134326421512061 0.0261484533481604 0.999647861958571 -0.00451779472276564 0.0105819513555849 0.0256991599300013 0.00384563008520349 0.999662325141915 -0.046935184446554 8.12257631652867e-05 1.10407847086686e-05 1.3796595415435e-06 1.20483269957908e-05 1.41454202569185e-06 6.15100740079198e-05 1.10407847086686e-05 2.38086041957153e-05 1.18449500093599e-06 -4.46161195726282e-06 4.74578450963352e-07 2.55454691642331e-05 1.3796595415435e-06 1.18449500093599e-06 1.27408954195756e-05 -4.80981687019953e-06 2.86910035146241e-06 3.35558566446469e-06 1.20483269957908e-05 -4.46161195726282e-06 -4.80981687019953e-06 0.000120608212332078 -1.10233619862024e-06 -3.36785628721064e-05 1.41454202569185e-06 4.74578450963352e-07 2.86910035146241e-06 -1.10233619862024e-06 1.31635735260938e-05 7.26368769725074e-06 6.15100740079198e-05 2.55454691642331e-05 3.35558566446469e-06 -3.36785628721064e-05 7.26368769725074e-06 0.00033241295975371 3464 3455 0 54 184 3464 3455 0 2 236 0 0 0 0 0 0 0 0 3184 0 0 0 0 0 3529 +533 534 0.999878945758694 0.0137580661459083 0.0072670106926239 0.162512565489766 -0.0138734859398273 0.999774477643459 0.0160785646320226 -0.00640920862168939 -0.00704416186350886 -0.0161774370242484 0.999844323039826 0.0240587359784586 7.00499835986223e-05 4.52506789792011e-06 5.27843639336043e-06 -6.4504459771931e-06 -2.66637370022699e-06 2.81616367839645e-05 4.52506789792011e-06 3.75356101012321e-05 3.93765138880158e-06 -6.5849510511323e-06 -1.43055739276469e-06 -5.21004299813463e-06 5.27843639336043e-06 3.93765138880158e-06 1.55557020266022e-05 -1.00942821708089e-05 1.59458521920266e-07 7.4197778661153e-06 -6.4504459771931e-06 -6.5849510511323e-06 -1.00942821708089e-05 0.000210595057418186 -6.93462982646454e-06 3.1636025906149e-05 -2.66637370022699e-06 -1.43055739276469e-06 1.59458521920266e-07 -6.93462982646454e-06 1.51652555052293e-05 -9.23619495747388e-06 2.81616367839645e-05 -5.21004299813463e-06 7.4197778661153e-06 3.1636025906149e-05 -9.23619495747388e-06 0.000175971680755797 3363 3347 0 224 100 3363 3347 0 160 145 0 0 0 0 0 0 0 0 2776 0 0 0 0 0 3615 +542 543 0.999828109121823 -0.0167178115437742 -0.00801666932502244 0.152839215058906 0.0168309749434902 0.999756617609481 0.0142626725582056 0.00433897871628958 0.00777627753693947 -0.0143951492954341 0.99986614563372 0.0188886246692357 7.35401635652928e-05 3.28415720052971e-05 5.40512036063118e-06 -6.65562342542819e-05 -2.5457692218253e-06 5.06153878590972e-05 3.28415720052971e-05 7.13508875157527e-05 1.0679036900041e-06 -1.6609614326418e-05 3.1211371997633e-07 -1.39828326771967e-05 5.40512036063118e-06 1.0679036900041e-06 1.45414731523374e-05 -7.46218538500532e-06 -2.08150834011256e-06 5.78046822658329e-06 -6.65562342542819e-05 -1.6609614326418e-05 -7.46218538500532e-06 0.000258704874638428 1.71491738577623e-06 -8.63884269782598e-05 -2.5457692218253e-06 3.1211371997633e-07 -2.08150834011256e-06 1.71491738577623e-06 1.62293426705008e-05 -4.92182119161633e-06 5.06153878590972e-05 -1.39828326771967e-05 5.78046822658329e-06 -8.63884269782598e-05 -4.92182119161633e-06 0.000230446303652176 3258 3244 0 120 174 3258 3244 0 57 232 0 0 0 0 0 0 0 0 3439 0 0 0 0 0 3542 +540 541 0.999546864230395 -0.0293646024316343 -0.006617124089489 0.138085630528217 0.0293270601231163 0.999553612111688 -0.00570088230118594 0.00492659073530443 0.00678157442772387 0.0055042382314824 0.999961856077407 -0.00184945063515915 5.01349751553318e-05 1.04210016077841e-05 -1.34531912507178e-06 1.01612025625436e-05 6.30431165296707e-08 3.25823377239776e-05 1.04210016077841e-05 3.00324404233071e-05 8.47293144121071e-07 3.54460293764578e-06 9.18801451456645e-07 6.01532838435239e-06 -1.34531912507178e-06 8.47293144121071e-07 1.08868223602509e-05 -9.01636364304133e-07 3.65803263008264e-06 3.72266738669208e-07 1.01612025625436e-05 3.54460293764578e-06 -9.01636364304133e-07 0.000148693434853968 -2.80505523469808e-06 -1.70412927335292e-05 6.30431165296707e-08 9.18801451456645e-07 3.65803263008264e-06 -2.80505523469808e-06 1.16590723559477e-05 -6.0411000356003e-07 3.25823377239776e-05 6.01532838435239e-06 3.72266738669208e-07 -1.70412927335292e-05 -6.0411000356003e-07 0.000178173173670687 3375 3378 0 63 183 3375 3378 0 12 245 0 0 0 0 0 0 0 0 3524 0 0 0 0 0 3528 +537 538 0.999894056906951 0.0141781046325136 0.00329489168092253 0.150681262374491 -0.0142164386104352 0.999827915305698 0.0119177451179665 -0.00412385960170305 -0.00312535364322871 -0.0119633241404964 0.999923552597955 0.0238157455516566 4.49065553610712e-05 4.6471224390426e-06 1.06972252826661e-06 -2.40466838053711e-05 -4.28934704263505e-07 1.79443324375372e-05 4.6471224390426e-06 0.000123721200125502 9.86003732033206e-07 4.65477219778718e-06 1.73660597504342e-06 -7.08470579130688e-05 1.06972252826661e-06 9.86003732033206e-07 1.24933148483805e-05 -5.74082971022751e-06 1.71481849476105e-06 2.54316091851512e-07 -2.40466838053711e-05 4.65477219778718e-06 -5.74082971022751e-06 0.000110543430406276 4.71400945038791e-06 -2.32300736060511e-05 -4.28934704263505e-07 1.73660597504342e-06 1.71481849476105e-06 4.71400945038791e-06 1.32549864267726e-05 -9.22996565508526e-07 1.79443324375372e-05 -7.08470579130688e-05 2.54316091851512e-07 -2.32300736060511e-05 -9.22996565508526e-07 0.000116379901030009 3283 3296 0 197 87 3283 3296 0 147 151 0 0 0 0 0 0 0 0 3169 0 0 0 0 0 3638 +543 544 0.999767265218929 -0.00931741870385721 -0.0194576747161882 0.150397312335311 0.0096052130956859 0.999845075385944 0.0147500884018604 0.000521621121566345 0.0193172274938833 -0.014933550655261 0.999701872453371 -0.0879378563816129 7.36966530473699e-05 3.85536540960488e-05 3.99421472560962e-06 -1.26655379724547e-05 4.33483541201783e-06 5.1105803539791e-05 3.85536540960488e-05 0.000115598848799163 5.69654220168281e-06 -2.23795575256143e-05 3.99769701119621e-06 0.000205102166224222 3.99421472560962e-06 5.69654220168281e-06 1.39028792393602e-05 -8.30329885911662e-06 1.55612143610042e-06 7.53964810545765e-06 -1.26655379724547e-05 -2.23795575256143e-05 -8.30329885911662e-06 0.000213105161921795 -2.21122203810419e-06 -0.000151036120603456 4.33483541201783e-06 3.99769701119621e-06 1.55612143610042e-06 -2.21122203810419e-06 1.37638429210273e-05 -1.03824595552613e-06 5.1105803539791e-05 0.000205102166224222 7.53964810545765e-06 -0.000151036120603456 -1.03824595552613e-06 0.00122615036447448 3374 3354 0 133 153 3374 3354 0 66 194 0 0 0 0 0 0 0 0 3555 0 0 0 0 0 3568 +541 542 0.999347020449031 -0.0277511677993129 -0.023138828955202 0.173897694896086 0.0278375926098073 0.999606604229098 0.00342128912293337 0.0052176994748067 0.0230347814692069 -0.00406318438502107 0.999726407261166 0.00428868243982785 0.000105185900739589 3.02079024028641e-05 2.1969288962125e-06 -1.3786777495535e-05 4.12341059861056e-06 2.67746285069593e-05 3.02079024028641e-05 9.92282518064458e-05 2.66886895673391e-06 -1.45829095630589e-05 2.554707973923e-06 7.16245186747763e-05 2.1969288962125e-06 2.66886895673391e-06 1.57443430168998e-05 -9.7922047826372e-06 3.15443370062748e-06 -3.34405196100312e-07 -1.3786777495535e-05 -1.45829095630589e-05 -9.7922047826372e-06 0.000254512587446047 -2.90688438543306e-06 0.00013629422150326 4.12341059861056e-06 2.554707973923e-06 3.15443370062748e-06 -2.90688438543306e-06 1.40665628790951e-05 4.51644706490763e-06 2.67746285069593e-05 7.16245186747763e-05 -3.34405196100312e-07 0.00013629422150326 4.51644706490763e-06 0.00072020885826299 3276 3273 0 105 229 3276 3273 0 49 283 0 0 0 0 0 0 0 0 3432 0 0 0 0 0 3486 +539 540 0.999663725056524 -0.0196534701251289 0.016916793967982 0.148717775805558 0.0199518329778177 0.999645088511894 -0.0176528007656601 0.00611141032309679 -0.0165638512109881 0.0179843856188497 0.99970105566963 0.0176987447326121 0.000115501344422085 1.82522035078466e-05 -3.85947079421193e-06 -4.57243604548822e-06 1.01343037544963e-05 0.000129296637188781 1.82522035078466e-05 0.000366708341812404 2.4302742458825e-06 -8.78343208877247e-05 -1.61646330946779e-06 -0.000169596235051879 -3.85947079421193e-06 2.4302742458825e-06 1.59124251868436e-05 -1.59644769586631e-06 -2.46576344485955e-08 -2.63355704650583e-06 -4.57243604548822e-06 -8.78343208877247e-05 -1.59644769586631e-06 0.000147833230557736 -9.77520086657977e-07 2.31353201023131e-05 1.01343037544963e-05 -1.61646330946779e-06 -2.46576344485955e-08 -9.77520086657977e-07 1.47848561132334e-05 9.45348107992773e-06 0.000129296637188781 -0.000169596235051879 -2.63355704650583e-06 2.31353201023131e-05 9.45348107992773e-06 0.000375533190092293 3232 3238 0 92 177 3232 3238 0 46 242 0 0 0 0 0 0 0 0 3429 0 0 0 0 0 3532 +544 545 0.999560454064624 0.00950561123352833 0.028080990459718 0.126106060321213 -0.0093947620560665 0.999947557767041 -0.00407678324676172 -0.00155554425030663 -0.0281182701465017 0.00381117708958848 0.999597337838172 -0.0631178560682642 9.22561205410017e-05 0.000153961833061718 4.86687984492403e-06 2.33512516348241e-05 -6.84020720112563e-07 2.01037365038375e-06 0.000153961833061718 0.00124090934564048 1.48840390890802e-05 0.000270108682591327 1.05317208311166e-06 -0.000528349991121015 4.86687984492403e-06 1.48840390890802e-05 1.38408292778048e-05 -5.16865091053728e-06 1.18140686239052e-06 -1.77738724585549e-06 2.33512516348241e-05 0.000270108682591327 -5.16865091053728e-06 0.000324013434755316 -2.27028982257514e-06 -0.000207101984225034 -6.84020720112563e-07 1.05317208311166e-06 1.18140686239052e-06 -2.27028982257514e-06 1.34507315424797e-05 -1.69974050637162e-05 2.01037365038375e-06 -0.000528349991121015 -1.77738724585549e-06 -0.000207101984225034 -1.69974050637162e-05 0.00121366621202456 3249 3231 0 160 81 3249 3231 0 91 122 0 0 0 0 0 0 0 0 3636 0 0 0 0 0 3639 +545 546 0.999685613297114 0.0243588338613999 0.00594321290933045 0.140725386289015 -0.0242127220770384 0.999429905587348 -0.0235288739059856 -0.00699157269668914 -0.00651296064727937 0.0233775753784774 0.999705491788972 -0.030689062077474 6.74188507167755e-05 2.49622868711476e-05 8.25399081178434e-06 -6.2877058930583e-05 -3.11159312034746e-06 5.19633345270162e-05 2.49622868711476e-05 8.09434800958427e-05 2.1006772247108e-06 -4.00256655869061e-05 1.72350930583129e-06 5.05494108541051e-05 8.25399081178434e-06 2.1006772247108e-06 1.46254223608447e-05 -6.93082129021728e-06 -7.23512059743401e-08 1.13127837733697e-06 -6.2877058930583e-05 -4.00256655869061e-05 -6.93082129021728e-06 0.000297736588363486 -1.27347455605531e-06 -0.000281134055363973 -3.11159312034746e-06 1.72350930583129e-06 -7.23512059743401e-08 -1.27347455605531e-06 1.39012260260451e-05 5.30663794926261e-06 5.19633345270162e-05 5.05494108541051e-05 1.13127837733697e-06 -0.000281134055363973 5.30663794926261e-06 0.000755409741785593 3330 3317 0 224 49 3330 3317 0 156 96 0 0 0 0 0 0 0 0 3611 0 0 0 0 0 3683 +555 556 0.999703097088086 0.0079841366067307 0.023021104124982 0.0317529705232358 -0.00808948721419985 0.999957213624982 0.00448677121921067 0.00464707042300058 -0.0229842961410502 -0.0046716680112464 0.999724910987464 0.00879697554280125 4.73012487293565e-05 1.87102404574833e-05 -3.52044797453149e-08 -1.26496547767472e-05 8.62609990162147e-07 -3.72169431848223e-05 1.87102404574833e-05 5.84755675418974e-05 -2.88802858254259e-07 2.99812259911496e-05 -4.20974371853139e-08 -2.75507759999349e-05 -3.52044797453149e-08 -2.88802858254259e-07 1.26258162508027e-05 -6.97213871287997e-06 4.24024577076548e-06 4.06529678725341e-06 -1.26496547767472e-05 2.99812259911496e-05 -6.97213871287997e-06 0.000939559628456599 -3.16229685940718e-05 3.56956737915363e-05 8.62609990162147e-07 -4.20974371853139e-08 4.24024577076548e-06 -3.16229685940718e-05 1.22948944805359e-05 -1.62162426743204e-05 -3.72169431848223e-05 -2.75507759999349e-05 4.06529678725341e-06 3.56956737915363e-05 -1.62162426743204e-05 0.000339211013386368 3265 3231 0 20 0 3261 3249 0 0 15 0 0 0 0 0 0 0 0 3811 0 0 0 0 0 3765 +546 547 0.998862056098479 0.0341541169855582 -0.0332879734987939 0.126961804542296 -0.034967381137153 0.999096306955834 -0.0241630230646602 -0.0100628822538065 0.0324326246722135 0.0252995201565372 0.999153671432338 0.0235684002517605 4.07773172668693e-05 1.25286376052642e-05 -6.97893897826047e-06 4.03608438580388e-05 2.89222750568177e-06 -1.28139270049604e-05 1.25286376052642e-05 4.49647735170243e-05 -9.5825392169822e-07 2.76161471143057e-05 2.3639938119127e-06 2.29559579609515e-05 -6.97893897826047e-06 -9.5825392169822e-07 1.36964455799942e-05 -1.29182160948186e-05 4.8989403996242e-07 -2.33478824450617e-08 4.03608438580388e-05 2.76161471143057e-05 -1.29182160948186e-05 0.000494675674188851 1.74663439921781e-05 5.71401315966559e-05 2.89222750568177e-06 2.3639938119127e-06 4.8989403996242e-07 1.74663439921781e-05 1.47631197094169e-05 1.00546914404012e-05 -1.28139270049604e-05 2.29559579609515e-05 -2.33478824450617e-08 5.71401315966559e-05 1.00546914404012e-05 0.000280294685515998 3393 3390 0 231 8 3393 3393 0 166 49 0 0 0 0 0 0 0 0 3622 0 0 0 0 0 3739 +554 555 0.999391870045165 -0.00925373009528898 0.0336193183594164 0.0877862632975334 0.00914446901507989 0.999952400526744 0.00340225913676192 0.0113637195374277 -0.0336492016853371 -0.00309275930602095 0.999428919966705 -0.0121116253542564 4.4055990524857e-05 4.45875771810463e-06 4.36753066642898e-07 2.57480934906693e-05 2.49412274491235e-06 -8.10499373582665e-06 4.45875771810463e-06 5.84277799632688e-05 9.59014967862139e-07 -5.07708264997269e-06 2.83602204960032e-06 -4.3776464625746e-05 4.36753066642898e-07 9.59014967862139e-07 1.21357112654325e-05 2.80409768964347e-06 3.73650464243228e-06 -9.8575332033175e-07 2.57480934906693e-05 -5.07708264997269e-06 2.80409768964347e-06 0.0015885485487869 -7.94349500826226e-05 -0.000127788193534758 2.49412274491235e-06 2.83602204960032e-06 3.73650464243228e-06 -7.94349500826226e-05 1.55111811851104e-05 1.64692504401571e-06 -8.10499373582665e-06 -4.3776464625746e-05 -9.8575332033175e-07 -0.000127788193534758 1.64692504401571e-06 0.000246138882205165 3255 3238 0 36 93 3254 3238 0 0 139 0 0 0 0 0 0 0 0 3778 0 0 0 0 0 3649 +547 548 0.999524273821819 0.0258825611362326 -0.0167725689742306 0.134075841831596 -0.0256933313739989 0.999604855971036 0.0114010807395999 -0.0133207490969624 0.0170610305630119 -0.0109647137743844 0.999794326993294 0.0512095865110331 5.03272190968463e-05 2.44663394040781e-05 -2.94262698028977e-06 3.65586647111859e-05 8.36934148491528e-06 -4.81686915948826e-06 2.44663394040781e-05 0.000545285820027524 1.58785628585213e-06 9.53007074206235e-05 -3.97748748435277e-06 -0.000330756212956415 -2.94262698028977e-06 1.58785628585213e-06 1.21187193149004e-05 -2.84402503109656e-06 2.44780325419202e-06 -2.42447150026949e-06 3.65586647111859e-05 9.53007074206235e-05 -2.84402503109656e-06 0.000557940578145928 9.83193276993038e-06 -3.51369175734049e-05 8.36934148491528e-06 -3.97748748435277e-06 2.44780325419202e-06 9.83193276993038e-06 1.28604266280831e-05 1.05379322434311e-05 -4.81686915948826e-06 -0.000330756212956415 -2.42447150026949e-06 -3.51369175734049e-05 1.05379322434311e-05 0.000412898124544963 3105 3113 0 224 21 3105 3113 0 163 78 0 0 0 0 0 0 0 0 3629 0 0 0 0 0 3704 +553 554 0.999857620752172 -0.01559283284324 0.00644994478486992 0.050565814529947 0.0155562814114069 0.999862867189385 0.00567881365001943 0.0134085988610664 -0.00653760907780592 -0.00557766794864192 0.999963073962134 0.011445002568166 3.65370408204233e-05 8.04379646115151e-06 -6.42490739345544e-07 2.46617829713053e-05 -1.54316247526865e-06 -9.12274894870445e-06 8.04379646115151e-06 5.65335586309868e-05 2.60043543337522e-06 -1.51132202620495e-05 1.65033089765825e-06 -3.10595163595545e-06 -6.42490739345544e-07 2.60043543337522e-06 1.20961372436255e-05 1.03942219248444e-05 4.35092521292677e-06 -4.65260769032976e-06 2.46617829713053e-05 -1.51132202620495e-05 1.03942219248444e-05 0.00107482744468539 -3.77184765737606e-05 -0.000162307685301733 -1.54316247526865e-06 1.65033089765825e-06 4.35092521292677e-06 -3.77184765737606e-05 1.18380963507378e-05 -1.56067768635562e-06 -9.12274894870445e-06 -3.10595163595545e-06 -4.65260769032976e-06 -0.000162307685301733 -1.56067768635562e-06 0.000364376686113206 3313 3301 0 0 52 3269 3301 0 0 105 0 0 0 0 0 0 0 0 3838 0 0 0 0 0 3683 +558 559 0.932827572607938 0.0202075904876815 0.359755991012053 0.0472265315249624 -0.0223455342305835 0.999748714592619 0.00178459249021281 -0.0107569466008795 -0.359629527267065 -0.00970365689255689 0.933044716056299 -0.108763363903976 0.000737865716797216 3.91980675676768e-05 -9.45877263374048e-05 -0.000537135976054977 7.09367794749028e-05 -0.00175019397395293 3.91980675676768e-05 0.00360348403445256 0.000101504391421056 -0.00101095894186876 3.30391134929569e-05 -0.00990214450375446 -9.45877263374048e-05 0.000101504391421056 3.83372972250793e-05 4.18648575440485e-05 -5.3942425233827e-06 -2.71237643766765e-05 -0.000537135976054977 -0.00101095894186876 4.18648575440485e-05 0.00126674449942707 -3.72356923135603e-05 0.00530303467443283 7.09367794749028e-05 3.30391134929569e-05 -5.3942425233827e-06 -3.72356923135603e-05 1.92382228596296e-05 -0.00020295179001123 -0.00175019397395293 -0.00990214450375446 -2.71237643766765e-05 0.00530303467443283 -0.00020295179001123 0.0382459747640016 1552 1538 0 85 3 1571 1565 0 52 14 0 0 0 0 0 0 0 0 3506 0 2 20 0 0 3629 +551 552 0.999641496684501 -0.0258630508314344 0.00692681081460569 0.0680803934271337 0.025656873116631 0.99926840810832 0.028361477721383 0.00277379317484063 -0.00765525755594125 -0.0281735897314142 0.999573732084531 0.00384734062998186 3.12999851405713e-05 -7.25680967741931e-06 1.11154851371087e-06 -9.05836411944022e-06 -1.5015753774047e-06 2.22868717785149e-06 -7.25680967741931e-06 3.00973570541652e-05 -9.0666189758789e-07 1.16856632288443e-05 1.8531152468327e-06 4.55554408027704e-06 1.11154851371087e-06 -9.0666189758789e-07 1.22209413454491e-05 -5.88531541366231e-06 3.40096477940175e-06 -5.46258987041947e-06 -9.05836411944022e-06 1.16856632288443e-05 -5.88531541366231e-06 0.000811049833640337 1.90471311914872e-06 -2.08848971451923e-05 -1.5015753774047e-06 1.8531152468327e-06 3.40096477940175e-06 1.90471311914872e-06 1.03385754670958e-05 7.41585924053198e-07 2.22868717785149e-06 4.55554408027704e-06 -5.46258987041947e-06 -2.08848971451923e-05 7.41585924053198e-07 0.00025012927087072 3414 3419 0 0 76 3382 3419 0 0 138 0 0 0 0 0 0 0 0 3826 0 0 0 0 0 3638 +552 553 0.999696809973616 -0.0204035970127913 -0.0137833725015373 0.106550088389911 0.0205556941035242 0.999728362224305 0.0109847714691872 0.0114990038733397 0.0135554995665545 -0.0112647677848921 0.999844664654592 0.042339465548585 4.16423029661896e-05 -6.51069094334284e-06 -3.35310259915948e-07 -3.58195809649754e-06 -1.93263583472741e-07 8.33711068073465e-06 -6.51069094334284e-06 4.56753859986477e-05 2.28242075862807e-06 -1.52079211015534e-05 9.52324237710095e-07 -2.11637780688228e-05 -3.35310259915948e-07 2.28242075862807e-06 1.25775729436849e-05 -7.64495446279745e-06 3.27509772850358e-06 -5.40443301473706e-06 -3.58195809649754e-06 -1.52079211015534e-05 -7.64495446279745e-06 0.000486508697027949 -8.65762717820558e-06 -2.36424024650458e-05 -1.93263583472741e-07 9.52324237710095e-07 3.27509772850358e-06 -8.65762717820558e-06 1.09771442574104e-05 2.60971840742579e-06 8.33711068073465e-06 -2.11637780688228e-05 -5.40443301473706e-06 -2.36424024650458e-05 2.60971840742579e-06 0.000204274394833711 3297 3294 0 28 130 3297 3294 0 0 184 0 0 0 0 0 0 0 0 3780 0 0 0 0 0 3600 +549 550 0.999628666031299 -0.00730409800258363 0.0262522418253237 0.0918247725371948 0.00711952648717707 0.999949326898179 0.00711730134796656 -0.00263297688455356 -0.0263028970093601 -0.00692775492118741 0.999630013465316 -0.00892891432213226 5.27000228287845e-05 -1.10663403069924e-05 3.79603302507244e-06 1.77660324744838e-05 7.73778166203009e-06 -1.47063111634198e-05 -1.10663403069924e-05 4.25706931917449e-05 6.14381165979087e-06 4.58194322562884e-05 -4.08960649669871e-06 5.76923893326084e-06 3.79603302507244e-06 6.14381165979087e-06 1.58687801308535e-05 1.00458529573132e-05 -2.51211416400293e-07 -5.73390705702475e-07 1.77660324744838e-05 4.58194322562884e-05 1.00458529573132e-05 0.0011328299945461 2.45278346043577e-05 0.00010389126175885 7.73778166203009e-06 -4.08960649669871e-06 -2.51211416400293e-07 2.45278346043577e-05 1.49860981692301e-05 -3.15159045415631e-07 -1.47063111634198e-05 5.76923893326084e-06 -5.73390705702475e-07 0.00010389126175885 -3.15159045415631e-07 0.000306415772141762 3327 3337 0 64 56 3327 3337 0 18 115 0 0 0 0 0 0 0 0 3772 0 0 0 0 0 3651 +548 549 0.999878626826167 0.0139123881343863 -0.00701263663804278 0.0434663610609488 -0.0138542627138706 0.999869823151267 0.00827019686035102 -0.0101375659114905 0.00712678194377292 -0.0081720381700095 0.999941211657602 -0.0391437772602151 6.72134545072215e-05 1.0575588257848e-05 -1.13163921648191e-05 -2.86651858899312e-05 1.04106895589505e-05 -3.97801411056039e-05 1.0575588257848e-05 7.37824650638248e-05 -4.20247680044026e-06 0.000220819657309271 1.18328306530502e-05 9.77582175403551e-05 -1.13163921648191e-05 -4.20247680044026e-06 1.54891507940324e-05 9.87162089739214e-06 5.66758309220773e-09 1.52417919048765e-05 -2.86651858899312e-05 0.000220819657309271 9.87162089739214e-06 0.00428912246395286 0.000155492995120324 0.00207454910397141 1.04106895589505e-05 1.18328306530502e-05 5.66758309220773e-09 0.000155492995120324 2.07743978368095e-05 6.64328000299793e-05 -3.97801411056039e-05 9.77582175403551e-05 1.52417919048765e-05 0.00207454910397141 6.64328000299793e-05 0.00133062143953496 3301 3271 0 66 0 3301 3315 0 21 0 0 0 0 0 0 0 0 0 3786 0 0 0 0 0 3792 +550 551 0.999437485138765 -0.0121569700425633 0.0312557415347227 0.169551531253727 0.0127012331717348 0.999770116545682 -0.0172740481112596 0.00763753170745927 -0.031038556271489 0.0176613176636713 0.999362139508479 -0.031523609764684 4.16949064053137e-05 -1.8499418470521e-05 -2.22753488835436e-06 8.20435654168103e-06 5.11146366497349e-06 -2.93210054356991e-06 -1.8499418470521e-05 7.7085747155179e-05 3.05997483745894e-06 4.60344040853622e-05 -2.12364862604087e-06 -1.89131123533057e-05 -2.22753488835436e-06 3.05997483745894e-06 1.36642441356463e-05 -3.23447529650987e-06 1.02162882897965e-06 2.64722058639629e-07 8.20435654168103e-06 4.60344040853622e-05 -3.23447529650987e-06 0.000662604674024875 1.71687163233288e-05 0.000357555187663868 5.11146366497349e-06 -2.12364862604087e-06 1.02162882897965e-06 1.71687163233288e-05 1.25948168565605e-05 1.53796565799392e-05 -2.93210054356991e-06 -1.89131123533057e-05 2.64722058639629e-07 0.000357555187663868 1.53796565799392e-05 0.000621577828022338 3314 3328 0 139 195 3314 3328 0 90 256 0 0 0 0 0 0 0 0 3683 0 0 0 0 0 3517 +561 562 0.999922430692056 -0.0121820855445797 -0.00259410691263374 0.139475253550123 0.0121679132165755 0.999911329064059 -0.00541072058988818 0.00778118277675678 0.0026597907518297 0.0053787360162491 0.999981997193962 0.0703156460338702 2.95921384814525e-05 -4.0188749323157e-06 -5.60430120527543e-06 -2.86918825688753e-05 -2.04968779357138e-06 7.16284255938635e-06 -4.0188749323157e-06 3.35216641393711e-05 -6.63030377547198e-08 -2.25060965568702e-05 -3.30523440264549e-07 7.1094124135941e-06 -5.60430120527543e-06 -6.63030377547198e-08 1.07879281911078e-05 7.45812369524305e-07 4.07020458613892e-06 1.04132304193748e-06 -2.86918825688753e-05 -2.25060965568702e-05 7.45812369524305e-07 0.000967559151257796 2.60455192833814e-05 0.00016624026661298 -2.04968779357138e-06 -3.30523440264549e-07 4.07020458613892e-06 2.60455192833814e-05 1.0605010405583e-05 7.48494026323551e-06 7.16284255938635e-06 7.1094124135941e-06 1.04132304193748e-06 0.00016624026661298 7.48494026323551e-06 0.000463068905488224 3408 3419 0 98 145 3408 3419 0 49 210 0 0 0 0 0 0 0 0 3732 0 0 0 0 0 3574 +560 561 -0.942133936034483 -0.108378008341149 -0.317234698417715 0.38568269640246 -0.112138741598836 0.993671701909636 -0.00643828056529818 0.0153429902175258 0.315924910706329 0.0295085772617703 -0.948325205118573 0.486648337843075 0.000178410930084814 -0.00161430429892136 3.64339694612033e-05 0.00220097961564712 0.000110307416263939 0.00259031465004996 -0.00161430429892136 0.0201943653083367 -0.000417116745542749 -0.0270914950705516 -0.00134207549651775 -0.0319437422167733 3.64339694612033e-05 -0.000417116745542749 2.20846474159821e-05 0.000648009699387678 2.86582681890898e-05 0.000760929383605349 0.00220097961564712 -0.0270914950705516 0.000648009699387678 0.0535316782315013 0.00273012799834858 0.0592602974505283 0.000110307416263939 -0.00134207549651775 2.86582681890898e-05 0.00273012799834858 0.000154312111327426 0.00303296800144095 0.00259031465004996 -0.0319437422167733 0.000760929383605349 0.0592602974505283 0.00303296800144095 0.068108311928338 0 0 0 59 751 0 0 0 30 854 0 0 0 0 0 2 0 0 2794 0 111 125 0 0 1929 +562 563 0.999628811338237 -0.0218643017339179 -0.0162539795801265 0.12082367502678 0.0223729885208711 0.999243738987778 0.0318025074226938 0.0115751545284115 0.0155463477108917 -0.0321543527910876 0.999362000813238 0.0308996470690758 4.25374947453392e-05 -1.61947277277152e-05 -4.45913311057061e-06 9.41074283959913e-06 -3.15414675499383e-07 6.59666375588683e-06 -1.61947277277152e-05 2.75032641556381e-05 3.40077482562212e-06 -1.54669685906403e-06 -5.32990137023804e-07 -1.03914726965774e-05 -4.45913311057061e-06 3.40077482562212e-06 1.42116153864883e-05 4.48071560434847e-06 1.61795002643478e-06 -8.31968945194274e-07 9.41074283959913e-06 -1.54669685906403e-06 4.48071560434847e-06 0.000245386563422317 2.92488599632154e-08 -1.93867515003823e-05 -3.15414675499383e-07 -5.32990137023804e-07 1.61795002643478e-06 2.92488599632154e-08 1.24796576202782e-05 -5.72086988121023e-06 6.59666375588683e-06 -1.03914726965774e-05 -8.31968945194274e-07 -1.93867515003823e-05 -5.72086988121023e-06 0.00013810418063099 3376 3379 0 38 152 3376 3379 0 0 216 0 0 0 0 0 0 0 0 3769 0 0 0 0 0 3581 +557 558 0.997898670118042 0.0341602047915263 -0.0550574662079985 0.063888659021306 -0.0345820236126584 0.999379224731042 -0.00672672422763219 -0.0121423815130198 0.054793501617413 0.00861658775746311 0.99846052831142 0.0220990651183259 2.645247189815e-05 -2.86750447280502e-06 -6.80735329402431e-06 -1.69874369747e-05 -3.76172626667976e-06 2.06855410004062e-06 -2.86750447280502e-06 4.97448279075059e-05 1.55994980126022e-06 1.02840829499586e-05 1.42326412277559e-06 -3.53181672759585e-05 -6.80735329402431e-06 1.55994980126022e-06 1.21112943135097e-05 -7.05700169383258e-06 3.95089121895281e-06 -5.52777352790356e-07 -1.69874369747e-05 1.02840829499586e-05 -7.05700169383258e-06 0.00150585109152468 3.99889504669443e-05 5.66749487379316e-05 -3.76172626667976e-06 1.42326412277559e-06 3.95089121895281e-06 3.99889504669443e-05 1.17896283270753e-05 -1.42440839630878e-06 2.06855410004062e-06 -3.53181672759585e-05 -5.52777352790356e-07 5.66749487379316e-05 -1.42440839630878e-06 9.81698485438008e-05 3474 3427 0 171 0 3497 3479 0 83 0 0 0 0 0 0 0 0 0 3698 0 0 14 0 0 3794 +556 557 0.998958079740976 0.0376473830264846 0.0257959196672424 0.0113830686427609 -0.037011846367065 0.999009847863223 -0.0246869824158373 0.00161017050159181 -0.0266997780650409 0.0237065059331029 0.999362358420469 -0.0252233339653198 4.53016952412563e-05 1.00212043163777e-05 -6.05571582621399e-06 1.47626471588425e-05 1.23299174684803e-07 3.23787919805071e-06 1.00212043163777e-05 3.69744440326556e-05 -9.27249163655597e-07 -2.41797114108021e-05 -1.24864178193279e-07 -1.08211519273695e-05 -6.05571582621399e-06 -9.27249163655597e-07 1.79476677032734e-05 2.31399875634095e-06 2.10570639376709e-06 -2.46052120747968e-06 1.47626471588425e-05 -2.41797114108021e-05 2.31399875634095e-06 0.00149033309750003 -2.15757556941994e-06 -3.27771050457403e-05 1.23299174684803e-07 -1.24864178193279e-07 2.10570639376709e-06 -2.15757556941994e-06 1.29864874098191e-05 -6.18945691543617e-06 3.23787919805071e-06 -1.08211519273695e-05 -2.46052120747968e-06 -3.27771050457403e-05 -6.18945691543617e-06 0.000283501404268699 3358 3310 0 74 0 3401 3353 0 18 0 0 0 0 0 0 0 0 0 3765 0 19 64 0 0 3736 +559 560 0.9984834405057 0.00532447540646017 0.0547947898759215 -0.0159567684718965 -0.00557892092054306 0.999974349842967 0.00449169205284856 -0.0172616256431458 -0.0547694684770878 -0.00479057593419588 0.998487534075892 0.196035223205037 3.77776115398647e-05 -2.21853385278593e-05 3.51927557995832e-06 -4.56435540457626e-05 -9.83481983934153e-07 -7.41420159972062e-05 -2.21853385278593e-05 0.000158147371785453 1.18861954225402e-06 0.000382439426851654 1.02935997344248e-05 0.000751166788510175 3.51927557995832e-06 1.18861954225402e-06 1.19295266761632e-05 4.149374581475e-06 4.36325103626525e-06 1.28998519216893e-05 -4.56435540457626e-05 0.000382439426851654 4.149374581475e-06 0.00197947092523678 6.06293446841159e-05 0.00330929839558546 -9.83481983934153e-07 1.02935997344248e-05 4.36325103626525e-06 6.06293446841159e-05 1.30875937594159e-05 9.18194073618165e-05 -7.41420159972062e-05 0.000751166788510175 1.28998519216893e-05 0.00330929839558546 9.18194073618165e-05 0.006721797304516 3242 3204 0 11 0 3259 3253 0 0 0 0 0 0 0 0 0 0 0 3822 0 0 35 0 0 3787 +565 566 0.999750698805782 0.00200042799960706 0.0222382221674687 0.124618444443501 -0.00232701067069106 0.999889689566938 0.0146694825767591 0.0130161235445436 -0.0222064238158646 -0.014717574037515 0.999645070890544 0.0286965792410053 3.33567429461035e-05 7.87187108202732e-06 4.05268053616442e-06 -1.56107593475608e-05 -6.83928703452354e-07 9.74172772680073e-06 7.87187108202732e-06 3.70795507968624e-05 3.97254587189539e-06 -5.17298467938166e-06 -4.80925760900164e-07 -2.22129834633355e-05 4.05268053616442e-06 3.97254587189539e-06 1.23670331597969e-05 -7.84072704194114e-07 4.22123370219792e-06 -5.05473353922987e-06 -1.56107593475608e-05 -5.17298467938166e-06 -7.84072704194114e-07 0.000304103603873579 -5.28023365171559e-06 -3.38346992235426e-05 -6.83928703452354e-07 -4.80925760900164e-07 4.22123370219792e-06 -5.28023365171559e-06 9.96962215623861e-06 -2.93537037499691e-06 9.74172772680073e-06 -2.22129834633355e-05 -5.05473353922987e-06 -3.38346992235426e-05 -2.93537037499691e-06 0.000238276322929266 3314 3297 0 114 105 3314 3297 0 55 147 0 0 0 0 0 0 0 0 3689 0 0 0 0 0 3655 +564 565 0.999791094866087 -0.020158907595298 -0.00337417709010854 0.121059056291202 0.0202136098048829 0.999650295503438 0.0170498292820145 0.0220125723011004 0.0030292911921962 -0.0171144717842572 0.999848947716813 -0.054440269179839 3.67406039519222e-05 -3.92821876432681e-06 1.23325368183077e-06 8.87657826745505e-06 2.21459577992684e-06 -5.24297880656771e-06 -3.92821876432681e-06 2.90441722490165e-05 2.61410002655959e-06 4.65178386014077e-07 -1.82013563766548e-06 1.7457546762465e-05 1.23325368183077e-06 2.61410002655959e-06 1.73934066658194e-05 2.10012134713591e-06 9.14588046901366e-08 -1.64915572378485e-06 8.87657826745505e-06 4.65178386014077e-07 2.10012134713591e-06 0.000529045350386482 -6.56930224057495e-06 -7.34664702250321e-05 2.21459577992684e-06 -1.82013563766548e-06 9.14588046901366e-08 -6.56930224057495e-06 1.29438273279201e-05 -9.3213929577407e-06 -5.24297880656771e-06 1.7457546762465e-05 -1.64915572378485e-06 -7.34664702250321e-05 -9.3213929577407e-06 0.000320576778137085 3415 3398 0 36 167 3415 3398 0 0 220 0 0 0 0 0 0 0 0 3768 0 0 0 0 0 3589 +566 567 0.999586803533831 0.02772776980223 0.00757581565333222 0.0944091067868458 -0.0276001216562805 0.999483448601033 -0.0164641810347272 0.00840980609954674 -0.00802841737687133 0.0162482846596278 0.999835755391876 -0.0166802801689801 4.07770549392985e-05 8.74258794846756e-06 2.30291931883158e-06 -1.54342304743842e-05 -8.71651173431915e-07 -4.77925796556217e-06 8.74258794846756e-06 1.94990314067833e-05 1.83454050400564e-06 -1.80253998339893e-05 -3.7493638678493e-07 -9.59754746280029e-06 2.30291931883158e-06 1.83454050400564e-06 1.26041164205749e-05 -1.10316710904621e-05 4.00724625700751e-06 4.90303632041304e-07 -1.54342304743842e-05 -1.80253998339893e-05 -1.10316710904621e-05 0.00122104676556834 1.88568195016759e-05 -0.000221618370980681 -8.71651173431915e-07 -3.7493638678493e-07 4.00724625700751e-06 1.88568195016759e-05 1.06882064661179e-05 -4.92361026176278e-06 -4.77925796556217e-06 -9.59754746280029e-06 4.90303632041304e-07 -0.000221618370980681 -4.92361026176278e-06 0.00010564975616493 3453 3438 0 154 5 3453 3438 0 93 46 0 0 0 0 0 0 0 0 3674 0 0 0 0 0 3764 +563 564 0.999630936462028 -0.0172589027195807 -0.0209790644444538 0.121353039657797 0.0169873638205149 0.999770493294226 -0.0130533600521066 0.0233048691303381 0.0211995362797859 0.0126921635325314 0.999694697718451 -0.0269584590039893 4.14046537426832e-05 2.23604903362189e-06 -3.12244488095505e-06 -6.54449888265744e-06 2.34636274876098e-07 3.97679423344731e-06 2.23604903362189e-06 7.79193099254756e-05 3.68783589839005e-06 9.68937954554405e-07 -6.6536010645335e-07 -1.27506409861279e-05 -3.12244488095505e-06 3.68783589839005e-06 1.30065069535036e-05 5.38002487664499e-07 3.56144853752982e-06 4.92631646558983e-06 -6.54449888265744e-06 9.68937954554405e-07 5.38002487664499e-07 0.000209336205406919 7.1769411430251e-07 -1.36880791604787e-05 2.34636274876098e-07 -6.6536010645335e-07 3.56144853752982e-06 7.1769411430251e-07 1.04584949404509e-05 -9.83922732366169e-06 3.97679423344731e-06 -1.27506409861279e-05 4.92631646558983e-06 -1.36880791604787e-05 -9.83922732366169e-06 0.000271434318660151 3256 3253 0 47 149 3256 3253 0 3 207 0 0 0 0 0 0 0 0 3754 0 0 0 0 0 3604 +570 571 0.994216519300031 -0.00148196330951329 0.107383967777696 0.0853415656139251 -0.00116901765213395 0.999696203747721 0.0246197808707519 0.00443185547057023 -0.107387830542669 -0.0246029265971367 0.993912747606245 0.12479162761702 6.26648522745114e-05 -0.000365542124056464 -6.75580186700875e-07 9.27056727845384e-05 1.10500396625173e-05 0.000155154615250124 -0.000365542124056464 0.00666886721531328 5.71011669946389e-05 -0.00226458309160065 -0.000200188716639613 -0.0025018884676385 -6.75580186700875e-07 5.71011669946389e-05 1.47885678218422e-05 -9.6937008132381e-06 3.58591178500187e-06 -1.68718618662307e-05 9.27056727845384e-05 -0.00226458309160065 -9.6937008132381e-06 0.00147195154002816 0.000122954022396894 0.000487197523819728 1.10500396625173e-05 -0.000200188716639613 3.58591178500187e-06 0.000122954022396894 2.26238435621126e-05 4.2063905638475e-05 0.000155154615250124 -0.0025018884676385 -1.68718618662307e-05 0.000487197523819728 4.2063905638475e-05 0.00152141894997698 3031 3048 0 78 35 3031 3048 0 30 92 0 0 0 0 0 0 0 0 3703 0 0 0 0 0 3730 +568 569 0.999463856114742 0.0264755499028321 -0.0192625433832848 0.125687245361888 -0.0266526231950899 0.999604288448492 -0.00899467576981919 -0.00548549852722327 0.019016781985153 0.00950325063997908 0.999773999577006 0.0267071075997248 4.29345683850298e-05 -2.04862352010819e-05 -3.59446778968538e-06 -1.21308439713974e-06 -2.03806606820241e-07 -3.48983675147038e-06 -2.04862352010819e-05 5.4301978021118e-05 1.9254909677674e-06 -2.00541114823876e-05 -1.20412643412605e-06 5.42294454920414e-05 -3.59446778968538e-06 1.9254909677674e-06 1.230708118911e-05 -7.21373651909707e-07 4.45615991964162e-06 5.68726221109263e-06 -1.21308439713974e-06 -2.00541114823876e-05 -7.21373651909707e-07 0.000226911745508488 5.25752159231251e-06 -0.000107986723434348 -2.03806606820241e-07 -1.20412643412605e-06 4.45615991964162e-06 5.25752159231251e-06 1.06435139176716e-05 -6.68603254756989e-06 -3.48983675147038e-06 5.42294454920414e-05 5.68726221109263e-06 -0.000107986723434348 -6.68603254756989e-06 0.000647406666418263 3303 3310 0 198 21 3303 3310 0 139 70 0 0 0 0 0 0 0 0 3643 0 0 0 0 0 3742 +571 572 0.998557191562723 -0.00288423094935351 0.0536210442848534 0.129315657442754 0.00391213289800494 0.999810407906799 -0.0190746810570849 0.0174191432797473 -0.0535558623733739 0.0192569325976895 0.998379156509376 -0.0016786509781369 5.27571170947016e-05 -0.000128331047233207 3.99790186055699e-07 1.10963457697302e-05 4.43814404257448e-06 0.000100462380377761 -0.000128331047233207 0.00160040742809119 -2.58445485393131e-05 -0.000198034477213527 -5.62847945592707e-05 -0.00126967840858514 3.99790186055699e-07 -2.58445485393131e-05 1.29584323590651e-05 1.6198957071197e-06 5.48590916312265e-06 1.8185237326412e-05 1.10963457697302e-05 -0.000198034477213527 1.6198957071197e-06 0.000340510216269564 2.66807949459592e-05 0.000131937021271593 4.43814404257448e-06 -5.62847945592707e-05 5.48590916312265e-06 2.66807949459592e-05 1.46785209266861e-05 5.80880829738174e-05 0.000100462380377761 -0.00126967840858514 1.8185237326412e-05 0.000131937021271593 5.80880829738174e-05 0.00135660824749796 3130 3146 0 91 128 3130 3146 0 49 190 0 0 0 0 0 0 0 0 3727 0 0 0 0 0 3637 +567 568 0.969545269835311 0.0420484693983049 -0.241275560223644 0.101200562078639 -0.0559769338577347 0.997120231590746 -0.051164700998866 -0.00471266707154189 0.238429345123163 0.0631123599121154 0.969106948386226 0.202759496889089 3.28559083682808e-05 2.97627463219955e-05 -1.42279336424515e-05 -7.50143843734542e-06 -5.52161059562659e-06 -8.0182445325583e-05 2.97627463219955e-05 0.00167640909033831 -7.7616144724922e-06 7.3722153420584e-05 -4.18734694172819e-05 -0.00310027771258733 -1.42279336424515e-05 -7.7616144724922e-06 1.56671943804272e-05 -2.08679723279016e-06 5.88823009705634e-06 9.74707754837517e-06 -7.50143843734542e-06 7.3722153420584e-05 -2.08679723279016e-06 0.000252375852750821 2.59655890493109e-06 -0.000125926846358362 -5.52161059562659e-06 -4.18734694172819e-05 5.88823009705634e-06 2.59655890493109e-06 1.49048562059347e-05 0.000189425409057583 -8.0182445325583e-05 -0.00310027771258733 9.74707754837517e-06 -0.000125926846358362 0.000189425409057583 0.0115760925905772 1856 1825 0 166 0 1872 1848 0 117 4 0 0 0 0 0 0 0 0 3314 0 1 15 0 0 3519 +569 570 0.999766803624492 0.0178923727469892 0.0120913757674147 0.0848914020390391 -0.0178471872915451 0.99983337286184 -0.00383463394568188 -0.00390895415456405 -0.0121579717159785 0.00361794267501084 0.999919543870682 0.0375249571058171 3.83360116453194e-05 -1.02789441704504e-05 -4.17829118246408e-06 -3.04718928619585e-06 -5.01594166798393e-08 1.78362885144695e-05 -1.02789441704504e-05 3.03809655046335e-05 1.78577508696146e-06 -9.86375570249755e-06 -9.93344443336265e-07 -2.08995091558797e-06 -4.17829118246408e-06 1.78577508696146e-06 1.23083734132984e-05 3.0091012139702e-07 4.66374718658546e-06 -4.20938392208895e-06 -3.04718928619585e-06 -9.86375570249755e-06 3.0091012139702e-07 0.000234760949340537 1.41493359421383e-05 -2.849579212828e-05 -5.01594166798393e-08 -9.93344443336265e-07 4.66374718658546e-06 1.41493359421383e-05 1.2259211505947e-05 5.12771302462717e-06 1.78362885144695e-05 -2.08995091558797e-06 -4.20938392208895e-06 -2.849579212828e-05 5.12771302462717e-06 0.000181078448006773 3523 3536 0 121 0 3523 3538 0 74 44 0 0 0 0 0 0 0 0 3717 0 0 0 0 0 3775 +573 574 0.999334218021439 -0.0298040199035769 -0.0210437897980869 0.119102414184776 0.0302376842952003 0.999330450907049 0.0205993285904434 0.0255419319894578 0.0204157571484054 -0.0212219294009866 0.999566319246781 0.0259816352595124 3.33214931258457e-05 -1.24454650280271e-05 -4.2321837517303e-06 -1.57839243333941e-05 -4.40894740772712e-06 8.82497683428737e-06 -1.24454650280271e-05 2.65587683521534e-05 2.75476086997576e-06 -5.84185370348494e-06 2.03873913427734e-07 -1.58433384543491e-05 -4.2321837517303e-06 2.75476086997576e-06 1.47793365750307e-05 -1.21725087353411e-06 4.72720777880054e-06 -2.74139356836514e-07 -1.57839243333941e-05 -5.84185370348494e-06 -1.21725087353411e-06 0.000261769601231512 7.06542343816302e-06 -2.22683865949762e-05 -4.40894740772712e-06 2.03873913427734e-07 4.72720777880054e-06 7.06542343816302e-06 1.14974146238443e-05 -4.37432798859239e-06 8.82497683428737e-06 -1.58433384543491e-05 -2.74139356836514e-07 -2.22683865949762e-05 -4.37432798859239e-06 8.52680593811089e-05 3382 3383 0 3 183 3368 3383 0 0 245 0 0 0 0 0 0 0 0 3788 0 0 0 0 0 3589 +577 578 0.999603126117005 0.0280887550911544 0.00214757876245058 0.138743512817809 -0.0280271392172907 0.999301197594253 -0.024730466109367 0.0083643447150522 -0.00284072603508096 0.0246604607442986 0.999691848497062 0.0205597163623765 3.63361483433133e-05 -6.26966448344704e-06 -4.57513245644776e-06 3.85458415579529e-06 -6.75337019551143e-07 8.78858148327198e-06 -6.26966448344704e-06 0.000151349612758741 2.59227823745973e-06 9.01475578051546e-06 4.24861676822972e-06 -0.00012574960767716 -4.57513245644776e-06 2.59227823745973e-06 1.24386868213136e-05 -4.90475580982616e-07 4.4426893388867e-06 -9.46796388097626e-07 3.85458415579529e-06 9.01475578051546e-06 -4.90475580982616e-07 0.000161367053797122 1.18287999072545e-06 -4.71153415611169e-06 -6.75337019551143e-07 4.24861676822972e-06 4.4426893388867e-06 1.18287999072545e-06 1.08629783437965e-05 -4.44396483350191e-06 8.78858148327198e-06 -0.00012574960767716 -9.46796388097626e-07 -4.71153415611169e-06 -4.44396483350191e-06 0.000160951842669429 3292 3275 0 216 52 3292 3275 0 140 89 0 0 0 0 0 0 0 0 3586 0 0 0 0 0 3737 +579 580 0.999660321985567 0.022835630628138 -0.0125608368163753 0.142423020264317 -0.0227262942755236 0.999703173981886 0.00877949195830136 -0.00790704184245239 0.0127575936686614 -0.00849104848406946 0.999882566054347 -0.0815609873110226 3.22689576335584e-05 -1.8537672750902e-05 2.05388767602889e-06 2.88223629808076e-06 3.08888949777109e-06 -7.05839215653535e-05 -1.8537672750902e-05 0.00015239261024084 1.33667953809902e-06 -3.99906919384121e-05 -9.42319907497683e-06 0.000639317453512223 2.05388767602889e-06 1.33667953809902e-06 1.11174813813176e-05 -1.2027707608312e-06 4.57986040268448e-06 8.31057739468302e-06 2.88223629808076e-06 -3.99906919384121e-05 -1.2027707608312e-06 0.000123993452290587 5.12491241809929e-06 -0.000213695165273582 3.08888949777109e-06 -9.42319907497683e-06 4.57986040268448e-06 5.12491241809929e-06 1.10734813768649e-05 -5.37873406731496e-05 -7.05839215653535e-05 0.000639317453512223 8.31057739468302e-06 -0.000213695165273582 -5.37873406731496e-05 0.00518457113244381 3214 3212 0 224 55 3214 3212 0 155 99 0 0 0 0 0 0 0 0 3597 0 0 0 0 0 3720 +581 582 0.998209669882149 0.00568059090230791 0.0595414632064995 0.131914656322903 -0.00529637268562945 0.999964135554133 -0.00660878520239397 0.0042193408770241 -0.0595768695900115 0.0062815995158144 0.998203956171973 0.0259713101224659 5.52929058288589e-05 -9.43750287678337e-06 -3.31678697715877e-06 -1.14117057414902e-06 -2.48372562094502e-07 2.88069861564847e-05 -9.43750287678337e-06 0.000138960825807629 2.55144226987539e-06 2.73596531062792e-05 3.79153408157466e-06 -0.000116459705662019 -3.31678697715877e-06 2.55144226987539e-06 1.56758299310372e-05 -2.12674911753145e-06 4.24134711180163e-06 -2.68338942587414e-06 -1.14117057414902e-06 2.73596531062792e-05 -2.12674911753145e-06 0.000139233174239361 6.86356136835216e-06 -2.09392637341527e-05 -2.48372562094502e-07 3.79153408157466e-06 4.24134711180163e-06 6.86356136835216e-06 1.33485000759357e-05 -2.85081904977803e-06 2.88069861564847e-05 -0.000116459705662019 -2.68338942587414e-06 -2.09392637341527e-05 -2.85081904977803e-06 0.000190391696688972 3211 3219 0 143 95 3211 3219 0 92 152 0 0 0 0 0 0 0 0 3670 0 0 0 0 0 3676 +572 573 0.999684451568593 -0.0128469755233271 0.0215859331951431 0.134008435891143 0.0119324391946833 0.999047415670468 0.0419747321256904 0.0199132922365532 -0.02210461912966 -0.0417039142294978 0.99888546357982 0.0277492757698442 4.70598023613917e-05 -1.62286932971373e-05 -3.0924152470396e-06 -3.51682375048574e-07 -3.32695472386935e-06 3.87553550330312e-05 -1.62286932971373e-05 4.03604877718558e-05 2.09405022962463e-06 2.32206139825976e-05 1.86016362918669e-06 2.48894425403312e-05 -3.0924152470396e-06 2.09405022962463e-06 1.10893684610106e-05 -7.92219020503934e-07 4.31246790257496e-06 1.81437366112734e-06 -3.51682375048574e-07 2.32206139825976e-05 -7.92219020503934e-07 0.000190674847490698 8.2079353738703e-06 7.34228432163082e-05 -3.32695472386935e-06 1.86016362918669e-06 4.31246790257496e-06 8.2079353738703e-06 1.06398134646828e-05 3.52357612730683e-06 3.87553550330312e-05 2.48894425403312e-05 1.81437366112734e-06 7.34228432163082e-05 3.52357612730683e-06 0.000453859680112752 3270 3279 0 83 162 3270 3279 0 36 228 0 0 0 0 0 0 0 0 3716 0 0 0 0 0 3617 +574 575 0.998561542774127 -0.0340642173009885 -0.0414062120004651 0.131862264664058 0.0344434473793471 0.999370671741168 0.00847994081541063 0.0279816145277658 0.0410912913545263 -0.00989391546748584 0.999106408853201 0.0446889381901133 3.79223481587632e-05 -2.75762713930849e-05 -5.79067628597404e-06 -8.34482307049769e-07 -1.91881610169751e-06 2.36050987663589e-05 -2.75762713930849e-05 0.000429592302697775 2.07777175767423e-05 -0.000116554280068508 1.07105078220402e-05 -0.000227763577976566 -5.79067628597404e-06 2.07777175767423e-05 1.18840310074524e-05 -8.34630123883106e-06 5.35089707866336e-06 -1.11431685364018e-05 -8.34482307049769e-07 -0.000116554280068508 -8.34630123883106e-06 0.00046303299382349 -6.30833011643629e-07 4.830099372651e-05 -1.91881610169751e-06 1.07105078220402e-05 5.35089707866336e-06 -6.30833011643629e-07 1.04524214033256e-05 -2.02410939240431e-05 2.36050987663589e-05 -0.000227763577976566 -1.11431685364018e-05 4.830099372651e-05 -2.02410939240431e-05 0.000491761244568333 3193 3175 0 11 213 3181 3175 0 0 266 0 0 0 0 0 0 0 0 3771 0 0 0 0 0 3566 +583 584 0.998821142378048 0.0464326238433604 -0.0141540447092881 0.115456576322857 -0.0464155994133088 0.998921044904181 0.00152911040864993 -0.00397079154649407 0.0142097737390424 -0.00087033933588551 0.99989865728469 0.0274213737220763 5.67939053996251e-05 -1.28707218044091e-06 -4.37213374856127e-06 1.01469180480843e-07 -1.95459912809887e-06 2.16516579496772e-05 -1.28707218044091e-06 2.52173190716071e-05 2.44240635379637e-06 4.17788737566877e-07 8.94339272404914e-07 -9.33923014190411e-06 -4.37213374856127e-06 2.44240635379637e-06 1.3186171579958e-05 -6.13104867385391e-06 4.0380793866209e-06 -3.01266872243319e-06 1.01469180480843e-07 4.17788737566877e-07 -6.13104867385391e-06 7.45706119022926e-05 5.05860489795076e-06 3.89001221653417e-06 -1.95459912809887e-06 8.94339272404914e-07 4.0380793866209e-06 5.05860489795076e-06 1.2510443507348e-05 -9.19779816190308e-08 2.16516579496772e-05 -9.33923014190411e-06 -3.01266872243319e-06 3.89001221653417e-06 -9.19779816190308e-08 7.3526591601688e-05 3375 3420 0 121 0 3375 3443 0 134 19 0 0 0 0 0 0 0 0 3581 0 0 0 0 0 3805 +576 577 0.999919715576334 0.0108884443971803 0.00648106321163825 0.138202996084156 -0.0109443897656821 0.999902606066185 0.00866017983117198 0.0122634092716128 -0.00638613610883547 -0.00873041583550958 0.99994149684116 0.0532217378706098 5.11804514139999e-05 5.63418618618869e-06 -6.15075110071908e-06 1.61326761634709e-05 -3.0122975746416e-07 -4.06657623176581e-06 5.63418618618869e-06 0.000187028394377719 1.63512802518519e-05 1.83762112853333e-05 9.04277266483749e-07 -5.43747458973882e-05 -6.15075110071908e-06 1.63512802518519e-05 1.79954709746637e-05 -4.96761778766893e-06 3.76933580380352e-06 -5.8873584492698e-06 1.61326761634709e-05 1.83762112853333e-05 -4.96761778766893e-06 0.000235644173407099 4.09162486938534e-06 -6.29301599200855e-05 -3.0122975746416e-07 9.04277266483749e-07 3.76933580380352e-06 4.09162486938534e-06 1.19237471844499e-05 -1.26171037002301e-05 -4.06657623176581e-06 -5.43747458973882e-05 -5.8873584492698e-06 -6.29301599200855e-05 -1.26171037002301e-05 0.000257528705209337 3134 3104 0 163 102 3134 3104 0 85 140 0 0 0 0 0 0 0 0 3625 0 0 0 0 0 3674 +580 581 0.999275682040398 0.0161133791916602 0.0344741975065887 0.145196211350628 -0.0158455554041571 0.999842222390038 -0.00802799477354013 -2.649743053949e-05 -0.0345981163740355 0.00747591714614156 0.999373344154322 -0.00567426456004934 5.84972346771235e-05 -9.68556743743289e-06 1.11306328593584e-06 1.97840627781338e-07 2.48636135368993e-06 3.92703081204975e-05 -9.68556743743289e-06 0.000563287093146244 9.38902389645729e-06 -0.000171597843112074 -1.39616738123525e-05 -4.59510464233262e-05 1.11306328593584e-06 9.38902389645729e-06 1.2791083365162e-05 -7.99822140592752e-06 4.52240534334936e-06 -2.95896536779834e-06 1.97840627781338e-07 -0.000171597843112074 -7.99822140592752e-06 0.000163517486954042 9.74771483917923e-06 5.74591242582301e-05 2.48636135368993e-06 -1.39616738123525e-05 4.52240534334936e-06 9.74771483917923e-06 1.11335030999045e-05 5.78980132073219e-06 3.92703081204975e-05 -4.59510464233262e-05 -2.95896536779834e-06 5.74591242582301e-05 5.78980132073219e-06 0.000817822959379984 3092 3097 0 200 84 3092 3097 0 142 134 0 0 0 0 0 0 0 0 3615 0 0 0 0 0 3695 +584 585 0.997369689343166 0.0717866481059051 0.010018978652354 0.0933961548761912 -0.0718426097081583 0.997401677346814 0.0053416716563526 -0.00635956119195555 -0.00960948540966792 -0.00604741097346503 0.999935541227873 0.0099718256576965 5.79216606523523e-05 -1.49880450041484e-05 -4.55216370876092e-06 -1.84551723444419e-05 -4.05734238365733e-06 1.12611701476375e-05 -1.49880450041484e-05 4.20185112285627e-05 -1.52712064437386e-07 7.24524410502088e-06 1.10989023847645e-06 8.37426069597904e-07 -4.55216370876092e-06 -1.52712064437386e-07 1.52685047984429e-05 -5.18931998439606e-06 3.37636231279581e-06 -1.78608504582673e-06 -1.84551723444419e-05 7.24524410502088e-06 -5.18931998439606e-06 6.59912132841792e-05 5.90710933584909e-06 -1.38283878156562e-05 -4.05734238365733e-06 1.10989023847645e-06 3.37636231279581e-06 5.90710933584909e-06 1.51176167343713e-05 -2.00520084087788e-06 1.12611701476375e-05 8.37426069597904e-07 -1.78608504582673e-06 -1.38283878156562e-05 -2.00520084087788e-06 0.00029331305091513 3412 3395 0 254 0 3449 3465 0 242 0 0 0 0 0 0 0 0 0 3426 0 0 17 0 0 3789 +575 576 0.999394540519523 -0.0218338802332361 0.0270893716009271 0.123272278057907 0.0215802372119904 0.999720830586041 0.00962051216052025 0.0229588819283995 -0.0272918621872279 -0.00903009226515386 0.999586720446023 0.0667839719089609 4.34639795671818e-05 -5.85642254183642e-06 -2.55113369849115e-06 -1.64359469868622e-05 -4.05655838017961e-07 2.89292625312969e-05 -5.85642254183642e-06 5.98104028806258e-05 5.03772011042332e-07 -1.67584922659488e-05 -7.71250977244856e-06 0.000161783913229936 -2.55113369849115e-06 5.03772011042332e-07 1.28040692030256e-05 -3.72167122330627e-06 4.60332962669308e-06 4.73555131727888e-06 -1.64359469868622e-05 -1.67584922659488e-05 -3.72167122330627e-06 0.000275555567339837 6.5391796619562e-07 -6.11519624178768e-05 -4.05655838017961e-07 -7.71250977244856e-06 4.60332962669308e-06 6.5391796619562e-07 1.25658478592438e-05 -6.02651014801497e-05 2.89292625312969e-05 0.000161783913229936 4.73555131727888e-06 -6.11519624178768e-05 -6.02651014801497e-05 0.00139475488895703 3413 3387 0 52 175 3413 3387 0 1 221 0 0 0 0 0 0 0 0 3727 0 0 0 0 0 3608 +578 579 0.997628274965277 0.0356098956463863 -0.0589046714773966 0.159364815097003 -0.0374468072074392 0.998836720341387 -0.0303799724757997 0.00164482453007421 0.0577543212216664 0.0325137114109562 0.9978012311831 -0.0880602631804211 5.92548688374581e-05 -1.21657925258519e-05 -5.20205550190385e-06 -1.21071854344981e-05 -2.41356431878761e-07 2.75915600066352e-05 -1.21657925258519e-05 4.82398021903395e-05 -1.07263241891243e-08 5.19688174256614e-07 -5.22581395473231e-07 -2.79528100139032e-05 -5.20205550190385e-06 -1.07263241891243e-08 1.23673937983504e-05 1.00958322485867e-06 4.53961016762819e-06 -1.35052027354034e-07 -1.21071854344981e-05 5.19688174256614e-07 1.00958322485867e-06 0.000139576259186946 1.15568567363279e-06 -6.53616883836691e-06 -2.41356431878761e-07 -5.22581395473231e-07 4.53961016762819e-06 1.15568567363279e-06 1.08164458620049e-05 8.98418797815333e-07 2.75915600066352e-05 -2.79528100139032e-05 -1.35052027354034e-07 -6.53616883836691e-06 8.98418797815333e-07 0.000159458784486167 3295 3282 0 274 43 3295 3282 0 193 85 0 0 0 0 0 0 0 0 3530 0 0 0 0 0 3742 +582 583 0.99434831907044 0.0258931710738172 0.10296098316126 0.0894275282291963 -0.0275594484974149 0.99951068959153 0.0147938565215977 -0.00459107695971334 -0.102527543422777 -0.0175477942774959 0.994575375602918 0.333486852454522 9.95164791793014e-05 -0.00017698406287692 -5.48889057593562e-06 8.77749213715649e-05 1.72222307424697e-05 -0.000519897371491983 -0.00017698406287692 0.000930250654608305 2.66105858086683e-05 -0.000727472705266817 -0.000122840023390773 0.00359581655067654 -5.48889057593562e-06 2.66105858086683e-05 1.22112324574087e-05 -2.92497773221668e-05 4.5407607078283e-07 0.000124680982107824 8.77749213715649e-05 -0.000727472705266817 -2.92497773221668e-05 0.00103623728632328 0.000157746855586919 -0.00449400213987656 1.72222307424697e-05 -0.000122840023390773 4.5407607078283e-07 0.000157746855586919 3.77203609397603e-05 -0.000733516708254739 -0.000519897371491983 0.00359581655067654 0.000124680982107824 -0.00449400213987656 -0.000733516708254739 0.0217193432100892 3125 3173 0 126 16 3128 3193 0 76 47 0 0 0 0 0 0 0 0 2844 0 0 1 0 0 2871 +589 590 0.991799837274082 0.126676592077574 -0.0169151944332852 -0.00443570906416895 -0.127249387419852 0.991114923789747 -0.038714354476306 -0.0564323622124531 0.0118606991520925 0.0405493385994947 0.999107138876891 -0.030352726731183 9.08225780257605e-05 -3.12129884660827e-05 -1.29135207259616e-06 1.56211327187975e-05 3.30452583657261e-05 6.83201965986522e-05 -3.12129884660827e-05 5.58231822914232e-05 -5.16270582391587e-06 6.57234534081207e-07 3.79785254103803e-06 5.37607685800834e-06 -1.29135207259616e-06 -5.16270582391587e-06 1.3549172699683e-05 -2.01373456546069e-06 -3.03179436201803e-06 -4.14484392823185e-06 1.56211327187975e-05 6.57234534081207e-07 -2.01373456546069e-06 4.70570774451027e-05 4.17660412264964e-05 2.4892314314539e-05 3.30452583657261e-05 3.79785254103803e-06 -3.03179436201803e-06 4.17660412264964e-05 8.48451543165922e-05 6.33669381040382e-05 6.83201965986522e-05 5.37607685800834e-06 -4.14484392823185e-06 2.4892314314539e-05 6.33669381040382e-05 0.000216810400403242 3445 3481 0 96 0 3595 3631 0 112 0 0 0 0 0 0 0 0 0 2904 0 241 394 0 0 3448 +586 587 0.991429339079412 0.127760112793729 0.0272987031101183 0.0880480222018085 -0.126834118671893 0.991364007523974 -0.0333243293515493 -0.0015900912426886 -0.0313204717921834 0.0295763108744136 0.999071704074225 -0.000842198665783666 4.92261891868142e-05 -5.94186849471615e-06 -1.06591423648968e-05 -2.03657692604852e-05 -9.25087879193078e-06 1.08134148458198e-05 -5.94186849471615e-06 4.33301260325106e-05 -1.63647826183244e-06 -5.80529848708362e-06 -1.37204840414124e-06 -2.21150194247039e-05 -1.06591423648968e-05 -1.63647826183244e-06 1.94898430725957e-05 -5.71887476165308e-06 -3.34722089936075e-07 -1.69521852816376e-06 -2.03657692604852e-05 -5.80529848708362e-06 -5.71887476165308e-06 8.44740489351959e-05 3.02585015239727e-05 2.86107908265054e-05 -9.25087879193078e-06 -1.37204840414124e-06 -3.34722089936075e-07 3.02585015239727e-05 3.40587940325734e-05 1.73977544180355e-05 1.08134148458198e-05 -2.21150194247039e-05 -1.69521852816376e-06 2.86107908265054e-05 1.73977544180355e-05 0.000128572941852926 3409 3435 0 413 0 3511 3537 0 415 0 0 0 0 0 0 0 0 0 3262 0 14 125 0 0 3631 +585 586 0.992190237538178 0.10499883189707 0.0673333337521993 0.0634250269286915 -0.107583284255754 0.993545152745983 0.0359703545118337 -0.0179043957829377 -0.063121862161059 -0.0429333757723792 0.997081920286447 0.139180959186265 8.01220858824884e-05 -6.04159544011458e-05 -3.17784047341439e-06 1.86037588255554e-05 7.25482140825542e-06 -0.000124301989789739 -6.04159544011458e-05 0.000136479625860807 3.37679255278792e-06 -7.06439028847896e-05 -3.53708408382416e-05 0.000369135468753949 -3.17784047341439e-06 3.37679255278792e-06 1.637056380591e-05 -7.83826430621829e-06 2.90997647393521e-06 1.91669006035358e-06 1.86037588255554e-05 -7.06439028847896e-05 -7.83826430621829e-06 0.000199205398733521 7.79068041154252e-05 -0.000462824066770092 7.25482140825542e-06 -3.53708408382416e-05 2.90997647393521e-06 7.79068041154252e-05 4.82042593842569e-05 -0.000222213458935681 -0.000124301989789739 0.000369135468753949 1.91669006035358e-06 -0.000462824066770092 -0.000222213458935681 0.00218344288642083 3057 3059 0 312 0 3135 3137 0 307 0 0 0 0 0 0 0 0 0 3317 0 58 151 0 0 3685 +587 588 0.990400586587886 0.138054844435996 -0.00689478165889919 0.0244750023412967 -0.138220919140922 0.989589203776403 -0.0401021854893545 -0.0291775623127411 0.00128670051276593 0.0406702310902819 0.99917179539099 0.00471871230641723 6.1983205026929e-05 4.37006214272888e-06 -5.67858753584066e-06 1.63390273691103e-05 1.71792230246095e-05 2.37065008244534e-05 4.37006214272888e-06 5.03303384015934e-05 -2.0159510365319e-06 1.62124756042709e-05 1.54449323330833e-05 -9.42216712736259e-06 -5.67858753584066e-06 -2.0159510365319e-06 1.32467406113189e-05 -3.12799818170832e-06 3.62239366152028e-06 3.78455698665229e-06 1.63390273691103e-05 1.62124756042709e-05 -3.12799818170832e-06 6.65607481167799e-05 3.64509233328759e-05 3.04769815055156e-05 1.71792230246095e-05 1.54449323330833e-05 3.62239366152028e-06 3.64509233328759e-05 4.56791696838289e-05 2.37413333003344e-05 2.37065008244534e-05 -9.42216712736259e-06 3.78455698665229e-06 3.04769815055156e-05 2.37413333003344e-05 0.000174284254858347 3127 3175 0 403 0 3248 3296 0 430 0 0 0 0 0 0 0 0 0 3286 0 179 309 0 0 3539 +588 589 0.990567916233057 0.133123421379508 -0.0324554773484275 -0.00371440484992359 -0.133671099910497 0.990907272486694 -0.0153236543193669 -0.0563281698912159 0.030120431245553 0.0195174796834955 0.999355706246973 -0.0185970298626672 4.55264500160612e-05 -3.29958089131938e-06 -2.19459197308319e-07 1.12845405987332e-05 1.26386264370474e-05 3.32779783313214e-05 -3.29958089131938e-06 5.1299806143695e-05 2.48555458978803e-06 1.16046556482045e-05 1.43506058952518e-05 -2.11938170230857e-06 -2.19459197308319e-07 2.48555458978803e-06 1.50307518342767e-05 -4.00307457038872e-06 -1.46068623338677e-07 2.66272625421551e-06 1.12845405987332e-05 1.16046556482045e-05 -4.00307457038872e-06 9.50475270578902e-05 7.74141736694256e-05 3.05455603073473e-05 1.26386264370474e-05 1.43506058952518e-05 -1.46068623338677e-07 7.74141736694256e-05 9.72664145971399e-05 3.2916399329981e-05 3.32779783313214e-05 -2.11938170230857e-06 2.66272625421551e-06 3.05455603073473e-05 3.2916399329981e-05 0.00012168364589766 3194 3220 0 232 0 3333 3359 0 293 0 0 0 0 0 0 0 0 0 3347 0 259 404 0 0 3524 +592 593 0.99929143912551 0.0321750206037679 -0.0195291510213237 -0.0241862049492943 -0.0323236413047146 0.999450481939061 -0.00734277635384124 -0.0577598348361586 0.0192821654196489 0.00796882682240564 0.999782324256537 -0.000717722720864495 3.64696991385492e-05 -1.98011238895726e-05 -3.64400294735088e-06 -1.32785775642212e-06 6.7382966966783e-06 2.08431391606182e-05 -1.98011238895726e-05 4.60054039593883e-05 1.57435215825464e-06 4.25648849587867e-06 2.97948390820372e-07 -1.13886199210799e-05 -3.64400294735088e-06 1.57435215825464e-06 1.31860773291622e-05 -2.91684999214795e-06 -3.5165924435803e-06 -7.19412829286269e-07 -1.32785775642212e-06 4.25648849587867e-06 -2.91684999214795e-06 2.93007686197815e-05 2.46020510615167e-05 -8.73492933531367e-06 6.7382966966783e-06 2.97948390820372e-07 -3.5165924435803e-06 2.46020510615167e-05 7.33700660656722e-05 2.76506351664321e-06 2.08431391606182e-05 -1.13886199210799e-05 -7.19412829286269e-07 -8.73492933531367e-06 2.76506351664321e-06 0.000118523678865696 2673 2676 0 101 0 2692 2695 0 112 0 0 0 0 0 0 0 0 0 3293 0 23 129 0 0 3472 +595 596 0.993257869768973 -0.115897520793103 0.00256297015477988 -0.0314327973508685 0.11586919345433 0.993220888499064 0.00930573250056975 -0.0260641156581874 -0.00362410682030689 -0.00894602275547394 0.99995341617828 0.0217954227706572 3.00897291516383e-05 -1.88033012906319e-05 -7.14665984590503e-07 2.70272002765524e-06 2.39832428322089e-06 -1.75812785385132e-05 -1.88033012906319e-05 4.72367602253984e-05 1.16681479952859e-06 1.10146201995291e-06 -2.3773901860714e-06 9.62726935123994e-06 -7.14665984590503e-07 1.16681479952859e-06 1.36897960760528e-05 -3.89015611730744e-06 -4.137573500364e-06 4.39139493159265e-07 2.70272002765524e-06 1.10146201995291e-06 -3.89015611730744e-06 3.92988928233652e-05 2.22480725506335e-05 -3.53422873196184e-05 2.39832428322089e-06 -2.3773901860714e-06 -4.137573500364e-06 2.22480725506335e-05 5.03455683223395e-05 -8.60912964767509e-06 -1.75812785385132e-05 9.62726935123994e-06 4.39139493159265e-07 -3.53422873196184e-05 -8.60912964767509e-06 0.000265028151010493 2980 3005 0 0 0 3006 3032 0 0 21 0 0 0 0 0 301 330 0 3070 0 0 0 0 0 3378 +598 599 0.988071912217154 -0.144180178137678 -0.0540922593327757 -0.0211286993957685 0.142026397439755 0.98898134977071 -0.041765921945892 0.0128445181884215 0.0595180537133188 0.0335852056401789 0.997662084698163 -0.27261588654264 0.000303482875547133 -0.000317066836027744 3.90601648155243e-05 1.71866150452636e-05 -0.000144642071568928 -0.0020972369437479 -0.000317066836027744 0.000432986848478434 -5.03814753482507e-05 -4.03497737900965e-05 0.000159042754795581 0.00250948764334508 3.90601648155243e-05 -5.03814753482507e-05 2.05344381894581e-05 4.96137223003923e-06 -1.62895943328847e-05 -0.000344305805624704 1.71866150452636e-05 -4.03497737900965e-05 4.96137223003923e-06 0.000134881300678583 3.25938272148862e-05 -0.000246421832183603 -0.000144642071568928 0.000159042754795581 -1.62895943328847e-05 3.25938272148862e-05 0.000130086588992224 0.00141288218375139 -0.0020972369437479 0.00250948764334508 -0.000344305805624704 -0.000246421832183603 0.00141288218375139 0.0220710179669606 2723 2828 0 0 131 2760 2865 0 0 253 0 0 0 0 0 379 400 0 3024 0 0 0 0 0 3001 +590 591 0.99647990665262 0.0836865347025251 -0.00493553918726053 -0.0202277928045267 -0.083741401496077 0.99641260595695 -0.0122186891912955 -0.0590834818893189 0.00389529370635419 0.0125889872334396 0.999913168273814 0.0119464456528085 4.97598996392336e-05 -1.28754991011035e-05 1.82549025373533e-08 -7.99967545163999e-06 -1.57725012458044e-06 7.12024846513822e-05 -1.28754991011035e-05 5.2356718350185e-05 -1.6053179738915e-06 -3.58150774854125e-06 -1.93498810837918e-06 1.91010888108846e-05 1.82549025373533e-08 -1.6053179738915e-06 1.64228756000934e-05 -4.53734039324036e-07 -1.00386010031631e-06 1.02250722956288e-05 -7.99967545163999e-06 -3.58150774854125e-06 -4.53734039324036e-07 4.78945309991447e-05 4.05250088562055e-05 -3.8952777732536e-05 -1.57725012458044e-06 -1.93498810837918e-06 -1.00386010031631e-06 4.05250088562055e-05 8.28119518465823e-05 -2.86005068915301e-05 7.12024846513822e-05 1.91010888108846e-05 1.02250722956288e-05 -3.8952777732536e-05 -2.86005068915301e-05 0.000320840912979215 3417 3452 0 236 0 3519 3554 0 260 0 0 0 0 0 0 0 0 0 3208 0 126 284 0 0 3421 +591 592 0.997934267457784 0.0641714745971018 -0.00303639284834783 -0.0144526763453874 -0.0641610270689482 0.997933693081012 0.00342152292842385 -0.0413824141588783 0.00324968290048128 -0.00321963689343187 0.99998953669492 -0.00224092691869865 3.58134944169685e-05 -1.93579591805612e-05 -8.43732643527553e-07 -5.53513359133607e-06 -8.6115589614309e-06 4.39603522692656e-06 -1.93579591805612e-05 3.94517506873316e-05 3.23957196587817e-07 -5.04606387578188e-06 -9.5751757611993e-06 9.69687641481885e-07 -8.43732643527553e-07 3.23957196587817e-07 1.39894425308563e-05 -5.02356009658986e-06 -3.6114739713091e-06 2.5761557200693e-06 -5.53513359133607e-06 -5.04606387578188e-06 -5.02356009658986e-06 3.93890702357935e-05 4.09313672926504e-05 -1.40438662804304e-05 -8.6115589614309e-06 -9.5751757611993e-06 -3.6114739713091e-06 4.09313672926504e-05 9.69028922338058e-05 -1.83386678600636e-06 4.39603522692656e-06 9.69687641481885e-07 2.5761557200693e-06 -1.40438662804304e-05 -1.83386678600636e-06 0.000178548209827698 2987 3003 0 177 0 3026 3042 0 213 0 0 0 0 0 0 0 0 0 3092 0 28 153 0 0 3407 +601 602 0.993211428225288 -0.116225856500378 0.00475490519748539 -0.0480812479166672 0.116112152443951 0.993042350010869 0.0196178270897604 0.0561067851238545 -0.00700192098757351 -0.0189325477853507 0.999796245110392 0.0443627921226734 5.28084281645276e-05 -1.56390462148325e-05 -6.29514851083976e-07 -1.42559526198141e-05 -2.93409600087906e-06 1.51635322902375e-05 -1.56390462148325e-05 3.6453329178773e-05 2.4820148743805e-06 -2.00558008056467e-05 -7.83172707554928e-07 -6.30021802579813e-06 -6.29514851083976e-07 2.4820148743805e-06 1.40712605537495e-05 -2.09697623937149e-06 3.97686965160484e-06 -5.33449624813958e-06 -1.42559526198141e-05 -2.00558008056467e-05 -2.09697623937149e-06 0.000276731227436519 1.41632025386063e-05 -0.000143016796533916 -2.93409600087906e-06 -7.83172707554928e-07 3.97686965160484e-06 1.41632025386063e-05 1.2622136673504e-05 -1.00205705467333e-05 1.51635322902375e-05 -6.30021802579813e-06 -5.33449624813958e-06 -0.000143016796533916 -1.00205705467333e-05 0.000423771670150828 3118 3171 0 0 221 3094 3147 0 0 295 0 0 0 0 0 320 349 0 3340 0 0 0 0 0 3587 +600 601 0.992920057763711 -0.118771877127253 0.00173207799429022 -0.0287318950144386 0.118699884035371 0.992657520915244 0.0232676535213756 0.051961627911617 -0.00448290313292431 -0.0228973224214078 0.999727771048414 0.0380688298089323 0.000135662248919 -0.000124427133130768 -2.60936651954465e-06 3.41899982359236e-06 4.80265274662397e-06 0.000112082552925132 -0.000124427133130768 0.000289708418052289 -1.09333142139559e-06 3.05835545681313e-05 -5.86140326260059e-07 -0.00014751054108905 -2.60936651954465e-06 -1.09333142139559e-06 1.34444383347083e-05 -1.00200569845936e-05 3.28872773805803e-06 9.40745150881713e-07 3.41899982359236e-06 3.05835545681313e-05 -1.00200569845936e-05 0.000152429213789315 2.40495746992546e-05 1.37193257002981e-05 4.80265274662397e-06 -5.86140326260059e-07 3.28872773805803e-06 2.40495746992546e-05 1.78744274757449e-05 1.09047973378718e-05 0.000112082552925132 -0.00014751054108905 9.40745150881713e-07 1.37193257002981e-05 1.09047973378718e-05 0.000214761912591229 2828 2904 0 0 213 2830 2906 0 0 311 0 0 0 0 0 343 320 0 3350 0 0 0 0 0 3508 +594 595 0.997942799131966 -0.0633771217635608 0.00967006192445987 -0.0301719348552197 0.0637304948716004 0.997076939148777 -0.042142632109623 -0.0318356222792731 -0.00697091701837105 0.0426722140821507 0.999064806937593 0.0528113907646526 8.24878250567738e-05 -4.72900373026377e-05 2.26344366239745e-06 1.53190620357381e-06 1.11163098140801e-05 3.13868337439027e-05 -4.72900373026377e-05 6.83672862780025e-05 -3.19326853250412e-06 1.14664229467743e-05 1.62030900713353e-05 1.19821228028315e-05 2.26344366239745e-06 -3.19326853250412e-06 1.2530486237023e-05 -5.48696934676667e-06 -9.98586420132656e-07 2.15537555386642e-06 1.53190620357381e-06 1.14664229467743e-05 -5.48696934676667e-06 3.59247796039225e-05 3.31290625671258e-05 1.28507561238633e-05 1.11163098140801e-05 1.62030900713353e-05 -9.98586420132656e-07 3.31290625671258e-05 8.54943510452325e-05 5.89609967883604e-05 3.13868337439027e-05 1.19821228028315e-05 2.15537555386642e-06 1.28507561238633e-05 5.89609967883604e-05 0.000371248939726237 2721 2724 0 0 0 2730 2758 0 0 0 0 0 0 0 0 158 183 0 2786 0 0 0 0 0 3463 +593 594 0.999801212559376 -0.0114240880773361 -0.0163409172448494 -0.0190360782439073 0.0113174583339619 0.999914154190182 -0.00660298318886492 -0.037545986825216 0.0164149475070981 0.00641673294867902 0.999844675455445 0.000835790334054025 2.42072601388108e-05 -1.73419215999577e-05 -4.63202841861599e-06 -6.45206293557395e-07 -1.67769197046452e-07 2.09645317107147e-06 -1.73419215999577e-05 3.04816490128284e-05 3.68168585656194e-06 -2.12571869803833e-06 -4.35252583585424e-06 5.40216876682344e-06 -4.63202841861599e-06 3.68168585656194e-06 1.41399335986092e-05 -7.82979524765935e-07 3.31623898776446e-06 -4.55019533572182e-07 -6.45206293557395e-07 -2.12571869803833e-06 -7.82979524765935e-07 2.95093790054917e-05 2.58427321030116e-05 2.41525979413907e-06 -1.67769197046452e-07 -4.35252583585424e-06 3.31623898776446e-06 2.58427321030116e-05 6.99934131662065e-05 2.0850935520819e-05 2.09645317107147e-06 5.40216876682344e-06 -4.55019533572182e-07 2.41525979413907e-06 2.0850935520819e-05 0.000216698231234976 2598 2598 0 0 0 2615 2631 0 0 0 0 0 0 0 0 21 29 0 3234 0 0 7 0 0 3531 +605 606 0.990285501008698 -0.130409642810533 -0.0482488502866274 -0.0402226400626625 0.128600951374923 0.990934141117173 -0.0388757414570331 0.0882324369613309 0.0528812045760766 0.0322932350562561 0.998078516536743 0.064796207052622 4.37630726397028e-05 1.28454046075826e-05 3.68232155978588e-06 8.18823195893062e-06 -4.11501783914365e-06 -8.53746100859366e-06 1.28454046075826e-05 2.81234047697974e-05 -1.81654983868735e-06 -1.06724758793824e-05 4.52421054463016e-06 -1.25961460316898e-05 3.68232155978588e-06 -1.81654983868735e-06 1.67380472794618e-05 -5.73824626382682e-07 1.16514184753344e-06 2.10303418067787e-06 8.18823195893062e-06 -1.06724758793824e-05 -5.73824626382682e-07 9.72016226327103e-05 -2.84022115477397e-05 3.45964994601884e-07 -4.11501783914365e-06 4.52421054463016e-06 1.16514184753344e-06 -2.84022115477397e-05 3.37995500100564e-05 -1.09000016134774e-06 -8.53746100859366e-06 -1.25961460316898e-05 2.10303418067787e-06 3.45964994601884e-07 -1.09000016134774e-06 9.14374423682901e-05 2879 2844 0 0 361 2723 2688 0 0 351 0 0 0 0 0 56 56 0 1553 0 0 0 0 0 3562 +596 597 0.990005511039393 -0.14018723240952 0.0153827169573571 -0.0279209333424907 0.139978089704401 0.990056662337117 0.0139262257842994 -0.000919986585042284 -0.0171820404590885 -0.0116337969402809 0.999784692948644 0.0181554439924624 5.33544433195628e-05 -3.53042826487774e-05 2.79180052113408e-06 4.75615447867234e-06 -7.31960918780439e-07 -1.2458557753727e-05 -3.53042826487774e-05 6.90046363321678e-05 -2.026842687915e-06 -8.91856979586093e-06 -6.02255467237657e-06 4.38636802708165e-05 2.79180052113408e-06 -2.026842687915e-06 1.39708669065082e-05 -4.00922708009573e-06 -8.89743722877186e-07 -3.93465610867489e-06 4.75615447867234e-06 -8.91856979586093e-06 -4.00922708009573e-06 4.46056085071169e-05 2.27449921847596e-05 -3.5342760358424e-05 -7.31960918780439e-07 -6.02255467237657e-06 -8.89743722877186e-07 2.27449921847596e-05 4.40750741375114e-05 1.17481600461473e-06 -1.2458557753727e-05 4.38636802708165e-05 -3.93465610867489e-06 -3.5342760358424e-05 1.17481600461473e-06 0.000394754927556747 3311 3386 0 0 22 3344 3419 0 0 59 0 0 0 0 0 160 167 0 2713 0 0 0 0 0 3289 +607 608 0.996564578654232 -0.0821430276791761 0.0105623659949685 0.0132357033680051 0.0822710913797234 0.996533808550775 -0.0123221726361986 0.0602968771382845 -0.00951357424435026 0.0131488181592561 0.999868291569501 0.0805390130326955 8.56208986588579e-05 -2.70504335815322e-05 -2.84443183071041e-06 1.71213129691475e-06 1.30839817712235e-06 4.0393142012868e-05 -2.70504335815322e-05 4.88122641818729e-05 3.41929102105669e-06 -2.2891724826698e-06 8.83691531651808e-07 -2.17189645657249e-05 -2.84443183071041e-06 3.41929102105669e-06 1.39537870150509e-05 2.42400707682251e-06 2.01435530872501e-06 -3.29759554772354e-06 1.71213129691475e-06 -2.2891724826698e-06 2.42400707682251e-06 2.06254141390329e-05 -2.90103555239458e-07 9.86415061039095e-06 1.30839817712235e-06 8.83691531651808e-07 2.01435530872501e-06 -2.90103555239458e-07 1.82573012634451e-05 -1.37676132999098e-06 4.0393142012868e-05 -2.17189645657249e-05 -3.29759554772354e-06 9.86415061039095e-06 -1.37676132999098e-06 0.000140143821730019 2102 2091 0 0 135 2102 2091 0 0 106 0 0 0 0 0 0 0 0 1448 0 0 0 0 0 3605 +606 607 0.993027453652287 -0.112498313476654 -0.0352222338553902 0.00303230721140943 0.111209068598585 0.993121108220425 -0.0366470663010055 0.0748724787058713 0.0391026770731943 0.0324745111116945 0.998707357925116 0.0385125264323342 6.39855091557868e-05 6.2484497557996e-06 -4.57510625957891e-07 8.31038550308088e-06 6.8227041797109e-07 3.80441552116283e-05 6.2484497557996e-06 4.89301854229691e-05 -2.04722673526113e-06 4.9871117619726e-06 -9.98401648659559e-07 4.88332777900269e-05 -4.57510625957891e-07 -2.04722673526113e-06 1.22718160059677e-05 -7.69217901559637e-07 4.83387776518164e-06 -8.1951256954173e-06 8.31038550308088e-06 4.9871117619726e-06 -7.69217901559637e-07 4.94864668502308e-05 -1.28384802558597e-05 3.89759695370328e-05 6.8227041797109e-07 -9.98401648659559e-07 4.83387776518164e-06 -1.28384802558597e-05 2.5067116077274e-05 -7.02950210165285e-06 3.80441552116283e-05 4.88332777900269e-05 -8.1951256954173e-06 3.89759695370328e-05 -7.02950210165285e-06 0.000394610004175551 2398 2362 0 0 285 2398 2362 0 0 247 0 0 0 0 0 0 0 0 1495 0 0 0 0 0 3596 +597 598 0.987422519898792 -0.157548087568497 -0.0132426319222502 -0.0339173510276665 0.157600337321451 0.987498444353806 0.00299267020871895 0.00723748047537051 0.0126055889542652 -0.00504207321668975 0.999907834065117 -0.00981184721108583 2.66335598858386e-05 -1.10192986767915e-05 -8.67501589407841e-07 7.59361281942046e-06 4.56666210447426e-06 -2.93616099349879e-06 -1.10192986767915e-05 2.79414625869441e-05 7.28227335422807e-07 -3.03045855275608e-06 -1.17604576670604e-06 9.65652057188995e-06 -8.67501589407841e-07 7.28227335422807e-07 1.32608643321403e-05 -9.02019747568908e-07 7.86152182452918e-07 -2.06585340947954e-06 7.59361281942046e-06 -3.03045855275608e-06 -9.02019747568908e-07 8.23837325574759e-05 3.68317425548716e-05 -4.88051460468665e-06 4.56666210447426e-06 -1.17604576670604e-06 7.86152182452918e-07 3.68317425548716e-05 4.14685048040014e-05 1.1565061158888e-05 -2.93616099349879e-06 9.65652057188995e-06 -2.06585340947954e-06 -4.88051460468665e-06 1.1565061158888e-05 0.000172939745396383 3130 3268 0 0 127 3170 3308 0 0 303 0 0 0 0 0 370 414 0 3219 0 0 0 0 0 3274 +599 600 0.991435761415203 -0.130230521648289 0.0097540872598035 -0.0482385963230697 0.129945465722299 0.991188667322941 0.0256749237347808 0.0267918596003144 -0.0130117994632568 -0.0241875381505986 0.999622756880285 -0.00611492277241915 5.30194907418592e-05 -2.45728668019289e-05 1.29964901035306e-06 1.15964142812264e-05 3.30107671411088e-06 2.14533631886283e-05 -2.45728668019289e-05 3.83672835184414e-05 -2.44704382556735e-06 -9.53618221979477e-07 -4.70585889590307e-07 -8.27748075012766e-06 1.29964901035306e-06 -2.44704382556735e-06 1.43608362322616e-05 -6.65032568718275e-06 4.21095478353061e-06 -4.82361048105475e-06 1.15964142812264e-05 -9.53618221979477e-07 -6.65032568718275e-06 9.62757204144805e-05 2.12065119134832e-05 -7.28847832125349e-06 3.30107671411088e-06 -4.70585889590307e-07 4.21095478353061e-06 2.12065119134832e-05 2.060677558704e-05 5.50296409862541e-06 2.14533631886283e-05 -8.27748075012766e-06 -4.82361048105475e-06 -7.28847832125349e-06 5.50296409862541e-06 0.000161195182732356 3090 3190 0 0 132 3113 3213 0 0 253 0 0 0 0 0 371 376 0 3129 0 0 0 0 0 3507 +604 605 0.987076427788567 -0.148415207133689 -0.0604404830856471 -0.0154977647255874 0.148951739139784 0.988834474799789 0.00444531828557579 0.0804813964908914 0.0591058805145125 -0.0133905839637652 0.998161904276913 0.0466673248801796 6.86371106007904e-05 3.73759998925353e-05 6.20736555887844e-06 -3.7649097208419e-06 2.22184463134412e-06 -1.2597627252777e-05 3.73759998925353e-05 0.000630761962514992 4.23705502694705e-05 0.00024977525571666 -8.03991522329244e-06 -0.00102679128380468 6.20736555887844e-06 4.23705502694705e-05 1.87963414208936e-05 1.20988286055792e-05 4.14281177496862e-06 -6.64436202056992e-05 -3.7649097208419e-06 0.00024977525571666 1.20988286055792e-05 0.000306093583974244 -6.44501611707754e-05 -0.000387312963547489 2.22184463134412e-06 -8.03991522329244e-06 4.14281177496862e-06 -6.44501611707754e-05 3.82181701831293e-05 -9.79977831657388e-06 -1.2597627252777e-05 -0.00102679128380468 -6.64436202056992e-05 -0.000387312963547489 -9.79977831657388e-06 0.00190593321556137 2560 2542 0 0 435 2450 2432 0 0 439 0 0 0 0 0 472 338 0 2593 0 0 0 0 0 3505 +608 609 0.99751579783263 -0.0704272450661675 0.00149540185976063 0.0302591467261774 0.070440943832672 0.997427047007176 -0.0133176323161018 0.0408957569780838 -0.000553630106242875 0.0133898861434486 0.999910198189203 0.0910466598943318 3.12426742040055e-05 1.14799005127255e-05 -1.7927081450858e-06 2.19446742624662e-07 9.82073195840224e-07 -3.02898556558653e-06 1.14799005127255e-05 3.54684502630241e-05 -1.78673523057494e-06 -6.82109773573561e-07 -2.34131311564416e-06 1.53193397312867e-05 -1.7927081450858e-06 -1.78673523057494e-06 1.49270230516936e-05 8.47747665678009e-07 2.50899831434771e-06 3.13496319043494e-06 2.19446742624662e-07 -6.82109773573561e-07 8.47747665678009e-07 2.84496277757649e-05 -4.17465374143503e-06 1.42060935567616e-05 9.82073195840224e-07 -2.34131311564416e-06 2.50899831434771e-06 -4.17465374143503e-06 2.3098320914271e-05 -5.91280809981636e-06 -3.02898556558653e-06 1.53193397312867e-05 3.13496319043494e-06 1.42060935567616e-05 -5.91280809981636e-06 0.000139489457604955 1798 1786 0 0 94 1798 1786 0 0 78 0 0 0 0 0 0 0 0 1450 0 0 0 0 0 3531 +602 603 0.992075229986275 -0.125632526851175 -0.00179059896941349 -0.0310569062525506 0.12561495684797 0.991421912383507 0.0361036599517757 0.0691900797350859 -0.00276055497374929 -0.036042472762279 0.999346446180411 0.106272978927123 4.6515237904457e-05 -1.09490378443755e-05 -4.63291662099079e-06 7.74824600839584e-06 2.16149614409262e-06 5.59544941709062e-06 -1.09490378443755e-05 3.46185859657371e-05 2.03394867813557e-06 1.82894943780971e-06 3.51693489015245e-07 -7.32773306973685e-06 -4.63291662099079e-06 2.03394867813557e-06 1.3542867337881e-05 -2.26836131527347e-06 3.19359007647267e-06 9.14456679987442e-07 7.74824600839584e-06 1.82894943780971e-06 -2.26836131527347e-06 0.000105969028780995 -4.71954719007255e-06 1.72429396862305e-05 2.16149614409262e-06 3.51693489015245e-07 3.19359007647267e-06 -4.71954719007255e-06 1.34260802842582e-05 -7.64727182396618e-06 5.59544941709062e-06 -7.32773306973685e-06 9.14456679987442e-07 1.72429396862305e-05 -7.64727182396618e-06 0.000182985164167805 2994 3023 0 0 323 3052 3081 0 0 375 0 0 0 0 0 341 270 0 3447 0 0 0 0 0 3549 +603 604 0.989546077109421 -0.14062431664519 -0.0319900429107204 -0.0102975942309819 0.141841941077059 0.989095008509409 0.0396475458668613 0.0726516961212355 0.0260657827208091 -0.0437706032611635 0.998701511594583 0.0523069535352441 8.95193788809132e-05 -8.38173947765448e-06 -4.35991112870314e-06 4.56036702081561e-05 -1.01694100156397e-05 3.36204330374579e-05 -8.38173947765448e-06 3.95508946038688e-05 3.22091503136258e-06 5.96949271549552e-06 -3.88302902694488e-07 -1.39837735454682e-05 -4.35991112870314e-06 3.22091503136258e-06 1.3272312214806e-05 -1.67498521050851e-06 4.5394536652696e-06 -2.206185913203e-06 4.56036702081561e-05 5.96949271549552e-06 -1.67498521050851e-06 0.000173518252859824 -2.77450433077054e-05 6.59030658443765e-05 -1.01694100156397e-05 -3.88302902694488e-07 4.5394536652696e-06 -2.77450433077054e-05 1.92369305823654e-05 -2.69174426066671e-05 3.36204330374579e-05 -1.39837735454682e-05 -2.206185913203e-06 6.59030658443765e-05 -2.69174426066671e-05 0.000187735276525087 2946 2950 0 0 402 2889 2893 0 0 425 0 0 0 0 0 425 319 0 3399 0 0 0 0 0 3524 +611 612 0.998265347620402 -0.0543617342379154 0.022607467592909 0.0157875556622837 0.0547636933754503 0.998344963997856 -0.0175576407298638 0.0116901789676763 -0.0216155876209238 0.0187652527498452 0.99959023187556 0.057353052891639 4.49305466764265e-05 2.08398354357495e-05 -4.74498823616243e-06 5.96384684385737e-07 1.74517729545968e-06 2.32695812493506e-06 2.08398354357495e-05 4.99999320686585e-05 -7.56366885327334e-06 -5.79205909372622e-07 3.7033522216899e-06 -3.91199228688903e-07 -4.74498823616243e-06 -7.56366885327334e-06 1.7329660961037e-05 3.65683112259382e-06 1.74833143379005e-06 1.2875253340161e-06 5.96384684385737e-07 -5.79205909372622e-07 3.65683112259382e-06 2.31904107036755e-05 -2.94376409283467e-06 1.61133132164663e-05 1.74517729545968e-06 3.7033522216899e-06 1.74833143379005e-06 -2.94376409283467e-06 3.11012407341284e-05 -4.45950633519354e-06 2.32695812493506e-06 -3.91199228688903e-07 1.2875253340161e-06 1.61133132164663e-05 -4.45950633519354e-06 0.000118787996713895 1072 1064 0 0 143 1072 1064 0 0 121 0 0 0 0 0 0 0 0 1478 0 0 0 0 0 3134 +610 611 0.997785279402942 -0.0654317799657273 -0.0119673880738532 0.0231795738757409 0.0652517090582061 0.99775811107454 -0.0148649335669195 0.0176132854460474 0.0129131975814195 0.0140511193675932 0.999817891104546 0.0582417299452697 4.0919375872057e-05 3.07015078664265e-05 -2.57643086471169e-06 2.92909284742711e-06 6.31120266239577e-06 5.05450511792979e-07 3.07015078664265e-05 5.99076774551619e-05 -4.89564797651623e-06 4.23988253835472e-06 2.60695477653204e-06 2.11127621942291e-05 -2.57643086471169e-06 -4.89564797651623e-06 2.01710821998348e-05 -1.58537573550177e-06 2.57793593046917e-06 -2.39888938392365e-06 2.92909284742711e-06 4.23988253835472e-06 -1.58537573550177e-06 2.50965172660345e-05 -2.97514647955783e-06 2.08080072191798e-05 6.31120266239577e-06 2.60695477653204e-06 2.57793593046917e-06 -2.97514647955783e-06 2.67376599272378e-05 -1.00500798517611e-05 5.05450511792979e-07 2.11127621942291e-05 -2.39888938392365e-06 2.08080072191798e-05 -1.00500798517611e-05 0.000171438794435153 1306 1270 0 0 137 1306 1270 0 0 132 0 0 0 0 0 0 0 0 1445 0 0 0 0 0 3223 +614 615 0.999762063610897 -0.0178281777477556 0.0125687009143978 0.0133289906613804 0.0176636472137833 0.999758396873256 0.013082180572246 -2.35161502618936e-06 -0.012798895717528 -0.0128570587465515 0.999835428612529 0.0363167432300515 5.58571948881993e-05 4.19481502555819e-05 -5.18373781991768e-06 1.93299672260955e-06 5.74656430217755e-06 3.07398171209225e-05 4.19481502555819e-05 7.59606044589203e-05 -6.13877970393231e-06 7.54611075224476e-06 -5.89333813329135e-06 3.45819248195146e-05 -5.18373781991768e-06 -6.13877970393231e-06 1.95750965752586e-05 -1.84868779875211e-06 -2.29949411682778e-06 1.48160193832326e-06 1.93299672260955e-06 7.54611075224476e-06 -1.84868779875211e-06 2.24954138158075e-05 -6.34375666233973e-07 7.3862183360976e-06 5.74656430217755e-06 -5.89333813329135e-06 -2.29949411682778e-06 -6.34375666233973e-07 4.08407718379295e-05 -6.65604180133466e-06 3.07398171209225e-05 3.45819248195146e-05 1.48160193832326e-06 7.3862183360976e-06 -6.65604180133466e-06 8.7273972561693e-05 716 751 0 0 36 716 751 0 0 46 0 0 0 0 0 0 0 0 1607 0 0 1 0 0 3123 +609 610 0.997226736330686 -0.0718059992500037 -0.0195636095584646 0.0363930582232907 0.0721527993522763 0.997237627936033 0.0176376578418155 0.0218868969727321 0.0182430779441887 -0.0190003131611891 0.999653028908981 0.0897520400562445 4.38939980210065e-05 1.70808604748615e-05 8.95781446223942e-08 5.23797651730202e-07 8.42889801509149e-06 4.89466170054212e-06 1.70808604748615e-05 2.99091614348344e-05 9.09936747148351e-07 -1.50317338164513e-06 2.54230616496586e-06 -6.09601059052316e-06 8.95781446223942e-08 9.09936747148351e-07 1.5209704949662e-05 2.10824016740246e-06 1.5901402387619e-06 -2.39195907816824e-06 5.23797651730202e-07 -1.50317338164513e-06 2.10824016740246e-06 1.5773297365545e-05 4.9495358367569e-06 3.57986048833893e-06 8.42889801509149e-06 2.54230616496586e-06 1.5901402387619e-06 4.9495358367569e-06 1.67939563818415e-05 -7.07588898879391e-06 4.89466170054212e-06 -6.09601059052316e-06 -2.39195907816824e-06 3.57986048833893e-06 -7.07588898879391e-06 0.000128431698532621 1537 1527 0 0 125 1537 1527 0 0 116 0 0 0 0 0 0 0 0 1457 0 0 0 0 0 3364 +615 616 0.999784626744989 -0.0151231791649689 0.0142123036952791 0.00443184623604861 0.0148903539413721 0.999755489787914 0.0163474156498372 0.00914703695359395 -0.0144560535376451 -0.0161322686213728 0.999765358684349 0.00553250485144274 0.000208063730890189 8.71515743964569e-05 8.40661616587153e-06 -2.84996004143308e-05 4.75464741922546e-05 0.000189516519318409 8.71515743964569e-05 9.46430127674943e-05 8.34348850959844e-08 -3.73414730948971e-06 1.59856365071441e-05 6.08256157248079e-05 8.40661616587153e-06 8.34348850959844e-08 2.10957276424452e-05 1.59882958690724e-06 2.1507095423725e-06 4.63704520370915e-06 -2.84996004143308e-05 -3.73414730948971e-06 1.59882958690724e-06 2.99040090508899e-05 -5.65572907803856e-06 -3.35646960523895e-05 4.75464741922546e-05 1.59856365071441e-05 2.1507095423725e-06 -5.65572907803856e-06 4.63358507820788e-05 4.3886678350645e-05 0.000189516519318409 6.08256157248079e-05 4.63704520370915e-06 -3.35646960523895e-05 4.3886678350645e-05 0.000275649424027703 647 696 0 0 18 647 696 0 0 46 0 0 0 0 0 0 0 0 1538 0 0 0 0 0 2940 +612 613 0.998445330882121 -0.044612987682929 0.0334156036859103 0.0201691519190126 0.0432391363542741 0.998232683565042 0.0407662427735348 -0.0150104250684537 -0.0351752516270672 -0.0392580029107074 0.99860978909704 0.0439924350664514 4.08578891900739e-05 2.39948644647905e-05 -5.53675904829604e-06 2.98775612684799e-06 3.92483106388047e-07 3.33312040323246e-05 2.39948644647905e-05 5.18655975703272e-05 -2.25035757173643e-06 -2.84108597424969e-06 1.94666648584945e-06 2.80613835659269e-05 -5.53675904829604e-06 -2.25035757173643e-06 1.44724979719132e-05 1.60635991715044e-06 1.04006075380957e-06 -4.46966550491701e-06 2.98775612684799e-06 -2.84108597424969e-06 1.60635991715044e-06 2.43459635627814e-05 -9.64169401051546e-06 8.53641302174554e-06 3.92483106388047e-07 1.94666648584945e-06 1.04006075380957e-06 -9.64169401051546e-06 4.1499867874307e-05 -1.28655726848903e-05 3.33312040323246e-05 2.80613835659269e-05 -4.46966550491701e-06 8.53641302174554e-06 -1.28655726848903e-05 0.000190974841541299 930 929 0 0 125 930 929 0 0 124 0 0 0 0 0 0 0 0 1562 0 0 0 0 0 3296 +619 620 0.99957748375168 0.0267996796696188 -0.0112530505315502 0.00497504648987314 -0.026988610163209 0.999491395669166 -0.0169871982610915 -0.0219263492538669 0.0107920757094332 0.0172837250877557 0.999792380421542 0.00859387004444994 4.62046766678882e-05 3.21828016545016e-05 -5.048840569461e-06 -6.44803770546522e-06 1.30146252955183e-05 1.05895492582423e-05 3.21828016545016e-05 4.69638339400358e-05 -8.05214584212747e-06 1.69409773212229e-06 -4.60428370757929e-06 4.84311162921369e-06 -5.048840569461e-06 -8.05214584212747e-06 1.81447937577536e-05 1.11064632222588e-06 2.1330948741429e-06 2.34500084424697e-07 -6.44803770546522e-06 1.69409773212229e-06 1.11064632222588e-06 3.87383928640136e-05 -2.59468178919873e-05 5.29671689799243e-06 1.30146252955183e-05 -4.60428370757929e-06 2.1330948741429e-06 -2.59468178919873e-05 6.36627345037871e-05 -6.69188406811738e-06 1.05895492582423e-05 4.84311162921369e-06 2.34500084424697e-07 5.29671689799243e-06 -6.69188406811738e-06 5.59857953304893e-05 676 676 0 0 0 732 733 0 0 0 0 0 0 0 0 0 0 0 1423 0 56 86 0 0 3251 +621 622 0.999311500962054 0.03158245743684 0.0194697824131875 -0.0103981323973477 -0.0319808388976031 0.999278197525951 0.0205014607453206 -0.00456095986951939 -0.0188082425646903 -0.0211100054840485 0.999600228931592 -0.00752450961835923 0.000102002274965034 5.1854419202513e-05 -1.25305425050389e-05 1.27804004876372e-05 -1.64173685143731e-05 9.00767454052853e-05 5.1854419202513e-05 8.83394552410302e-05 -7.282061155916e-06 6.77757271371356e-06 -1.30168448339358e-05 5.06954819592339e-05 -1.25305425050389e-05 -7.282061155916e-06 2.33984685961219e-05 -2.48539645422097e-06 1.64175321762278e-06 -5.62231376530616e-06 1.27804004876372e-05 6.77757271371356e-06 -2.48539645422097e-06 2.95681469312763e-05 -4.77532332227797e-06 2.39445917763755e-05 -1.64173685143731e-05 -1.30168448339358e-05 1.64175321762278e-06 -4.77532332227797e-06 4.11915601714082e-05 -3.39495458665907e-05 9.00767454052853e-05 5.06954819592339e-05 -5.62231376530616e-06 2.39445917763755e-05 -3.39495458665907e-05 0.000174551798369182 1018 1018 0 0 1 1030 1036 0 0 1 0 0 0 0 0 0 0 0 1379 0 72 77 0 0 3194 +613 614 0.999658734153025 -0.0235102012955383 0.0113879614775763 0.0125512151887787 0.0234484009227504 0.999709752074061 0.00553028952096765 0.00246115861440396 -0.0115146743652373 -0.00526137273561122 0.999919861904543 0.050988754379219 5.00569368689938e-05 2.75967240078918e-05 -7.00151203213044e-06 2.27142068964274e-06 6.36158634508652e-06 -5.68809694801779e-08 2.75967240078918e-05 5.4318360711432e-05 -6.77955913366088e-06 2.29349210683793e-06 4.09014047520975e-06 -6.36514104561078e-06 -7.00151203213044e-06 -6.77955913366088e-06 1.75789666162453e-05 1.16996653061189e-06 8.45395682278672e-07 -1.6699834380491e-06 2.27142068964274e-06 2.29349210683793e-06 1.16996653061189e-06 1.9525307590126e-05 1.3769166417854e-06 1.1258299858417e-05 6.36158634508652e-06 4.09014047520975e-06 8.45395682278672e-07 1.3769166417854e-06 3.10233717938079e-05 -4.38546873771412e-06 -5.68809694801779e-08 -6.36514104561078e-06 -1.6699834380491e-06 1.1258299858417e-05 -4.38546873771412e-06 0.000135178414044731 822 843 0 0 73 822 843 0 0 68 0 0 0 0 0 0 0 0 1646 0 0 3 0 0 2692 +616 617 0.999933643319838 -0.00447131669501126 -0.0106167925537127 0.00793384540622966 0.00455252696562088 0.999960471360396 0.00763742200761653 -0.00503877362877857 0.0105822235538165 -0.00768524844803628 0.999914473093049 0.00475669837221774 4.48996682562433e-05 1.42822606248514e-05 -8.73916230565168e-06 -3.67518527836624e-07 1.5192885429995e-05 1.83140948116105e-05 1.42822606248514e-05 6.58176293356242e-05 3.17159572268505e-07 -4.1743342408211e-06 7.14946478476934e-07 -7.71802228315542e-06 -8.73916230565168e-06 3.17159572268505e-07 2.30819677617959e-05 -2.71475472443625e-06 -3.54840200980039e-06 -4.57623804491844e-06 -3.67518527836624e-07 -4.1743342408211e-06 -2.71475472443625e-06 2.68920424534669e-05 -4.60375864822884e-06 3.27911332678885e-06 1.5192885429995e-05 7.14946478476934e-07 -3.54840200980039e-06 -4.60375864822884e-06 4.77241949493569e-05 1.17779585667517e-06 1.83140948116105e-05 -7.71802228315542e-06 -4.57623804491844e-06 3.27911332678885e-06 1.17779585667517e-06 6.10602983491283e-05 606 629 0 0 0 606 657 0 0 17 0 0 0 0 0 0 0 0 1619 0 0 2 0 0 3297 +617 618 0.999785557277393 0.00716255350107535 -0.019430318753876 0.00480576088887564 -0.00717321079860299 0.999974157542209 -0.000478847144945868 -0.0082339817026737 0.0194263868583892 0.000618122231965995 0.999811098867448 0.0164507302887467 0.000166999007332502 7.65659352980531e-05 7.12441416706582e-08 -7.03473945037433e-07 2.54327499432309e-06 9.52389065996527e-05 7.65659352980531e-05 8.31902043038384e-05 -2.9276309573375e-06 -7.97872906402162e-06 1.79528352908251e-05 3.97058032823295e-05 7.12441416706582e-08 -2.9276309573375e-06 1.84319940662596e-05 4.44248932896301e-07 1.5066143209291e-06 1.28360721587734e-06 -7.03473945037433e-07 -7.97872906402162e-06 4.44248932896301e-07 2.69460162346287e-05 -7.5245106138574e-06 -1.81106994958538e-06 2.54327499432309e-06 1.79528352908251e-05 1.5066143209291e-06 -7.5245106138574e-06 5.80276661885489e-05 9.75339884997532e-06 9.52389065996527e-05 3.97058032823295e-05 1.28360721587734e-06 -1.81106994958538e-06 9.75339884997532e-06 0.000135893398723757 601 601 0 0 0 634 668 0 0 0 0 0 0 0 0 0 0 0 1482 0 0 17 0 0 3114 +618 619 0.999714532594967 0.0229732483308747 -0.00656377784162936 0.00647594867113719 -0.0230554199986998 0.999653133602645 -0.0127302822865543 0.0034351563089356 0.00626904515136525 0.0128779788608215 0.999897423105666 0.00515894893517078 6.97934974228942e-05 4.82604671999964e-05 -2.3211781030203e-06 2.48679312299609e-06 7.6826471169878e-06 3.47969103239467e-05 4.82604671999964e-05 9.66299493367113e-05 -2.19283518437471e-06 1.2031996913173e-06 1.06147260850355e-05 2.44845632598887e-05 -2.3211781030203e-06 -2.19283518437471e-06 2.19800813724529e-05 2.06160325079028e-06 6.77411584801147e-07 -1.85577933408125e-06 2.48679312299609e-06 1.2031996913173e-06 2.06160325079028e-06 2.36752253629181e-05 7.02477062545055e-06 4.27429451290572e-06 7.6826471169878e-06 1.06147260850355e-05 6.77411584801147e-07 7.02477062545055e-06 3.47591356879947e-05 5.61750564991586e-06 3.47969103239467e-05 2.44845632598887e-05 -1.85577933408125e-06 4.27429451290572e-06 5.61750564991586e-06 8.2180106936517e-05 611 611 0 0 0 643 643 0 0 0 0 0 0 0 0 0 0 0 1470 0 35 83 0 0 3141 +620 621 0.998868846803351 0.0452609896522939 0.014576340468006 -0.0267309270057369 -0.0450723162580402 0.998898846457259 -0.0130223213557903 0.0145519958322005 -0.0151496928311927 0.0123506016879021 0.999808956473719 -0.00283517620008344 5.6984220357371e-05 5.17141646487954e-05 -6.5149341177921e-06 -9.73145187927329e-06 1.79275713717471e-05 3.61048381473555e-05 5.17141646487954e-05 9.35160839870549e-05 -7.28647194708726e-06 -1.49614098713962e-05 1.72026633623424e-05 4.46578306065763e-05 -6.5149341177921e-06 -7.28647194708726e-06 2.20100337636591e-05 1.70055640247325e-06 -1.75324925644266e-06 -2.79442202304798e-06 -9.73145187927329e-06 -1.49614098713962e-05 1.70055640247325e-06 4.12426168589601e-05 -2.39018453647578e-05 -6.50303886114671e-06 1.79275713717471e-05 1.72026633623424e-05 -1.75324925644266e-06 -2.39018453647578e-05 6.12688721231099e-05 8.86175464528892e-06 3.61048381473555e-05 4.46578306065763e-05 -2.79442202304798e-06 -6.50303886114671e-06 8.86175464528892e-06 8.94817513470168e-05 809 809 0 0 0 866 869 0 0 0 0 0 0 0 0 0 0 0 1341 0 97 112 0 0 3223 +628 629 0.999320736030398 -0.0256666283282765 -0.0264441057689907 0.0141320523870136 0.0262563405924103 0.999408712098672 0.0221997918902072 0.0158930924551634 0.025858675881777 -0.0228790378191759 0.999403761504883 0.0184628011550012 6.42491329761187e-05 5.15584302050041e-05 -6.39702639924573e-06 4.74796958668677e-06 5.4968429851134e-06 1.53898210525205e-05 5.15584302050041e-05 0.000106101174406173 -1.33725666636574e-06 2.50182673972429e-06 1.32992816963873e-05 7.76638686649084e-06 -6.39702639924573e-06 -1.33725666636574e-06 2.24412061819252e-05 -1.51649768276858e-06 1.14145567029833e-06 -8.21926547237305e-07 4.74796958668677e-06 2.50182673972429e-06 -1.51649768276858e-06 1.93199346789262e-05 9.9758101113508e-06 1.20194405468111e-06 5.4968429851134e-06 1.32992816963873e-05 1.14145567029833e-06 9.9758101113508e-06 3.87882401019354e-05 -2.51267138642093e-06 1.53898210525205e-05 7.76638686649084e-06 -8.21926547237305e-07 1.20194405468111e-06 -2.51267138642093e-06 5.28044721285141e-05 0 0 0 0 0 0 14 0 0 35 0 0 0 0 0 0 0 0 1397 0 0 0 0 0 2647 +629 630 0.999794604710474 -0.0168179110863376 -0.0113095649128589 0.00438019304058158 0.0171550266038271 0.999390501650294 0.0304028004202956 0.00134079154169427 0.0107913601574644 -0.0305905717152587 0.999473743260965 0.01197908848567 5.13133646218496e-05 3.79687125103207e-05 -9.77566138603612e-06 -4.28149004328096e-06 8.39218820250023e-06 1.06543180363671e-05 3.79687125103207e-05 8.17731239088265e-05 -1.57485493975887e-05 3.5342759420321e-06 8.78822216596575e-06 9.89507961188603e-06 -9.77566138603612e-06 -1.57485493975887e-05 2.46487645191255e-05 -2.50433097006375e-06 -4.08605013707114e-06 -1.63176037233663e-06 -4.28149004328096e-06 3.5342759420321e-06 -2.50433097006375e-06 2.18224588731286e-05 -6.06391238520211e-06 6.13918803103592e-06 8.39218820250023e-06 8.78822216596575e-06 -4.08605013707114e-06 -6.06391238520211e-06 5.40401107303892e-05 4.87049400678483e-06 1.06543180363671e-05 9.89507961188603e-06 -1.63176037233663e-06 6.13918803103592e-06 4.87049400678483e-06 6.50716602696202e-05 0 0 0 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 1434 0 0 0 0 0 2397 +623 624 0.999088108800036 -0.0379063329238576 0.0196484294189869 0.0195084913804733 0.0371833307872514 0.998661920750589 0.0359411735243979 -0.0153051864589511 -0.0209845363525878 -0.0351778050340084 0.999160733449357 0.00821291779990148 7.60605035123177e-05 5.59340568167206e-05 1.06339301749324e-06 -2.71862810092799e-06 8.59674896038856e-07 5.8009604030946e-05 5.59340568167206e-05 8.1694124353895e-05 -6.40190795310079e-06 -3.96177306292401e-06 1.03656894925303e-06 4.17354592390408e-05 1.06339301749324e-06 -6.40190795310079e-06 1.84298234713203e-05 3.68620603922016e-06 3.8432298236433e-06 -2.10193333852264e-07 -2.71862810092799e-06 -3.96177306292401e-06 3.68620603922016e-06 2.25668597471794e-05 -3.94327339498863e-06 1.31757824858904e-06 8.59674896038856e-07 1.03656894925303e-06 3.8432298236433e-06 -3.94327339498863e-06 3.25153734737877e-05 -1.09554838929539e-05 5.8009604030946e-05 4.17354592390408e-05 -2.10193333852264e-07 1.31757824858904e-06 -1.09554838929539e-05 0.000126528610200989 1010 1021 0 0 82 1010 1021 0 0 93 0 0 0 0 0 0 0 0 1332 0 0 0 0 0 3253 +625 626 0.997075082127485 -0.0713424734443321 0.0274140854911264 0.00951940020886901 0.0709246488143438 0.99735456139913 0.0159239771072208 0.020943607886731 -0.0284776191250607 -0.0139330663959538 0.999497321091845 0.00942688843360275 7.21664945509812e-05 4.75705003715553e-05 -7.61802744708873e-06 -2.02505845763825e-06 6.56365080960373e-06 3.75587528533144e-05 4.75705003715553e-05 7.21166029017141e-05 -6.80890569918205e-06 -3.89876646251765e-07 6.43158664737981e-06 2.07022767659381e-05 -7.61802744708873e-06 -6.80890569918205e-06 1.76678473789331e-05 1.90173714689623e-06 4.91613507098946e-06 6.09932695438826e-07 -2.02505845763825e-06 -3.89876646251765e-07 1.90173714689623e-06 2.1407929995616e-05 6.13527065858008e-06 -1.87973747767235e-06 6.56365080960373e-06 6.43158664737981e-06 4.91613507098946e-06 6.13527065858008e-06 2.83905563655623e-05 9.08761464065795e-06 3.75587528533144e-05 2.07022767659381e-05 6.09932695438826e-07 -1.87973747767235e-06 9.08761464065795e-06 8.11511022013469e-05 462 515 0 0 170 462 515 0 0 197 0 0 0 0 0 0 0 0 1373 0 0 0 0 0 3069 +631 632 0.99986205138521 -0.0123538838926972 -0.011102240878558 0.00693031808847006 0.0123961783002032 0.99991613700482 0.00374882927161992 0.00881573779518777 0.0110549972098296 -0.00388593748327722 0.999931340906248 0.00289559844508846 5.22863369594862e-05 2.80407299721095e-05 -5.85655582587284e-06 4.42029932470935e-06 -2.43241510380919e-06 7.51497168652769e-06 2.80407299721095e-05 7.5451216012762e-05 -4.10551698555974e-06 9.89668090983245e-06 -2.96570683221605e-06 -2.02502921410146e-05 -5.85655582587284e-06 -4.10551698555974e-06 2.20583528589632e-05 -7.18008241896176e-06 -2.56907239785879e-06 -1.17390292739111e-05 4.42029932470935e-06 9.89668090983245e-06 -7.18008241896176e-06 2.34881751629388e-05 3.63377112114923e-06 7.93875598905064e-06 -2.43241510380919e-06 -2.96570683221605e-06 -2.56907239785879e-06 3.63377112114923e-06 3.95329808809415e-05 -1.14776468782517e-05 7.51497168652769e-06 -2.02502921410146e-05 -1.17390292739111e-05 7.93875598905064e-06 -1.14776468782517e-05 7.22907750390938e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1552 0 0 0 0 0 2137 +622 623 0.999790738646379 0.000670506650851238 0.0204457657660434 0.00570699612172005 -0.000931397258524721 0.999918239864702 0.0127532774228469 -0.00643261149485627 -0.0204355429601359 -0.0127696517849332 0.999709620128373 0.00503815688316813 6.78372449535217e-05 4.02610719914988e-05 -6.52960156121125e-06 -5.43765573325003e-07 -9.84671924626683e-07 3.36456589979649e-05 4.02610719914988e-05 7.39871992422437e-05 -1.03002386417105e-05 -6.70561880273719e-06 1.12439150706318e-05 2.74847712369775e-05 -6.52960156121125e-06 -1.03002386417105e-05 1.84299869539084e-05 2.34624819341784e-06 3.33246462492631e-06 -5.97623613426722e-07 -5.43765573325003e-07 -6.70561880273719e-06 2.34624819341784e-06 2.06774408656679e-05 4.22618507300803e-06 1.12893187163784e-07 -9.84671924626683e-07 1.12439150706318e-05 3.33246462492631e-06 4.22618507300803e-06 2.72145321799361e-05 -2.40642864813776e-06 3.36456589979649e-05 2.74847712369775e-05 -5.97623613426722e-07 1.12893187163784e-07 -2.40642864813776e-06 0.000116765742458549 1096 1097 0 0 19 1113 1134 0 0 20 0 0 0 0 0 0 0 0 1344 0 20 17 0 0 3337 +626 627 0.998461307298688 -0.040020049294075 -0.0383850684758324 0.0169981900059335 0.0402658391023226 0.999173020071755 0.00565138585434068 0.0265138494521786 0.038127156054188 -0.00718829709935381 0.999247040704165 0.0285072877625486 6.73110519348498e-05 3.59452783157393e-05 -1.20823712146476e-06 3.3467148786435e-06 1.77716545879069e-05 1.54084806156537e-05 3.59452783157393e-05 8.19320269829469e-05 3.32177204844577e-07 2.66320229131169e-06 2.11571449345119e-05 -6.88498068128338e-06 -1.20823712146476e-06 3.32177204844577e-07 2.11863935721321e-05 -2.45032987718021e-07 3.29385686274479e-06 -3.34064869531567e-06 3.3467148786435e-06 2.66320229131169e-06 -2.45032987718021e-07 2.0312395866317e-05 8.9125527214222e-06 3.10533294988691e-06 1.77716545879069e-05 2.11571449345119e-05 3.29385686274479e-06 8.9125527214222e-06 3.95438608642e-05 6.07936672901912e-06 1.54084806156537e-05 -6.88498068128338e-06 -3.34064869531567e-06 3.10533294988691e-06 6.07936672901912e-06 4.45537328377119e-05 214 318 0 0 60 214 318 0 0 115 0 0 0 0 0 0 0 0 1419 0 1 0 0 0 2696 +624 625 0.995552260635372 -0.0770628557958014 0.0541942118717116 -0.00347427657063728 0.076904620594073 0.997025905636752 0.00500228152907145 0.0314431284444852 -0.0544185232717882 -0.000812247382212858 0.998517883955569 0.0173743137432503 7.43988769119047e-05 6.78156439757117e-05 -6.95761466226455e-06 -6.37937827181602e-06 1.22737348619519e-05 3.19644206081389e-05 6.78156439757117e-05 8.44402906932901e-05 -1.02921816125471e-05 -8.40015788617905e-06 1.07723621931832e-05 3.42531669600356e-05 -6.95761466226455e-06 -1.02921816125471e-05 1.97025188090464e-05 2.66838436808608e-06 3.48617223728733e-06 2.67625510202368e-06 -6.37937827181602e-06 -8.40015788617905e-06 2.66838436808608e-06 2.48547485056758e-05 -5.04231359069225e-06 -5.22070704872547e-06 1.22737348619519e-05 1.07723621931832e-05 3.48617223728733e-06 -5.04231359069225e-06 4.17896446355419e-05 5.35482824414818e-06 3.19644206081389e-05 3.42531669600356e-05 2.67625510202368e-06 -5.22070704872547e-06 5.35482824414818e-06 7.84962813412385e-05 729 769 0 0 180 729 769 0 0 188 0 0 0 0 0 0 0 0 1343 0 0 0 0 0 3090 +627 628 0.997019787526022 -0.0428761267743738 -0.0641340863690597 0.01699900273906 0.0416769802088091 0.998932531494985 -0.0199205130881602 0.0201448931631154 0.0649197396963413 0.0171882306782534 0.997742447790967 0.031791693215494 8.20511423668816e-05 4.87242948527365e-05 -4.25686038815282e-06 5.86124542944533e-06 2.58254323511232e-05 2.57665411063996e-05 4.87242948527365e-05 0.00012520571644187 4.58733067367406e-06 -9.07127098711588e-07 2.19405526235659e-05 -1.22739862370035e-05 -4.25686038815282e-06 4.58733067367406e-06 1.98629802846025e-05 -4.1194662990602e-06 -1.24736436505655e-06 -5.33604498567845e-06 5.86124542944533e-06 -9.07127098711588e-07 -4.1194662990602e-06 2.86242401967238e-05 -5.20622143499657e-06 -7.91664153201985e-06 2.58254323511232e-05 2.19405526235659e-05 -1.24736436505655e-06 -5.20622143499657e-06 7.29708024212176e-05 1.77864949198137e-05 2.57665411063996e-05 -1.22739862370035e-05 -5.33604498567845e-06 -7.91664153201985e-06 1.77864949198137e-05 7.30821151926074e-05 2 126 0 0 34 2 126 0 0 107 0 0 0 0 0 0 0 0 1403 0 0 0 0 0 2812 +630 631 0.999842967773158 -0.0149051637199722 -0.00958519113235504 0.001224266781577 0.0148683375252787 0.999881847098706 -0.00390184337384161 0.00782148658767785 0.00964221622851009 0.00375871480168767 0.999946448430736 0.00734951098718047 7.48566592397018e-05 6.65281722156993e-05 -2.25755966216101e-06 9.40898887826043e-06 5.52388909457169e-07 2.04986919879908e-05 6.65281722156993e-05 9.49125664849211e-05 -8.60308184376626e-06 1.36593531478123e-05 -3.10004203108155e-06 2.14157465670167e-05 -2.25755966216101e-06 -8.60308184376626e-06 2.34273704178891e-05 -4.81614907863482e-06 -3.54864640722596e-07 -6.5354040880657e-06 9.40898887826043e-06 1.36593531478123e-05 -4.81614907863482e-06 2.04836278233342e-05 2.06652579796101e-06 8.54065650513792e-06 5.52388909457169e-07 -3.10004203108155e-06 -3.54864640722596e-07 2.06652579796101e-06 4.00082358484637e-05 -1.96605403299964e-05 2.04986919879908e-05 2.14157465670167e-05 -6.5354040880657e-06 8.54065650513792e-06 -1.96605403299964e-05 6.96882483567487e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1531 0 0 0 0 0 2163 +633 634 0.999844812889216 0.0102505443153993 -0.0143274729023012 0.00106549044664585 -0.0103507323039254 0.999922373115029 -0.00693614336509278 0.00239525103737307 0.0142552614602684 0.00708336680164744 0.999873298691116 0.00282719747579801 6.04486805620487e-05 2.82812844524247e-05 -9.93143205560671e-06 1.07173278315763e-05 -2.44728862503618e-06 1.78134490420088e-05 2.82812844524247e-05 8.92747281385366e-05 -6.20214813450494e-06 1.53587515173606e-05 6.87734171375523e-07 -2.59785698567832e-05 -9.93143205560671e-06 -6.20214813450494e-06 2.60890694268616e-05 -7.84524474871745e-06 -1.91097187456349e-07 -1.07797078531758e-05 1.07173278315763e-05 1.53587515173606e-05 -7.84524474871745e-06 1.97962216100301e-05 5.51579258695265e-06 6.48426933523914e-07 -2.44728862503618e-06 6.87734171375523e-07 -1.91097187456349e-07 5.51579258695265e-06 3.28571055100547e-05 -7.77287606493374e-06 1.78134490420088e-05 -2.59785698567832e-05 -1.07797078531758e-05 6.48426933523914e-07 -7.77287606493374e-06 8.36238854719093e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1617 0 0 0 0 0 2049 +635 636 0.999996249525424 0.00128572210242052 -0.00241823360371467 -0.00557349369614594 -0.00128978664002939 0.999997757056289 -0.00167998000397112 0.000761732015906618 0.00241606819233009 0.00168309270864337 0.999995664897316 0.00610910412998585 9.01850543017971e-05 6.7151411571897e-05 -4.46329732166581e-06 1.88536528096022e-05 1.16641365340159e-06 1.48380947462031e-05 6.7151411571897e-05 0.000120831524094783 -9.33954491321049e-06 2.37206681303354e-05 9.16990945248398e-06 4.15493475833591e-06 -4.46329732166581e-06 -9.33954491321049e-06 2.02164682604139e-05 -7.20960277161409e-06 1.4630884855827e-06 -7.05626432598324e-06 1.88536528096022e-05 2.37206681303354e-05 -7.20960277161409e-06 2.53728380529075e-05 1.36335862502849e-06 9.12569031187124e-06 1.16641365340159e-06 9.16990945248398e-06 1.4630884855827e-06 1.36335862502849e-06 5.28071501818314e-05 -1.71141019453934e-05 1.48380947462031e-05 4.15493475833591e-06 -7.05626432598324e-06 9.12569031187124e-06 -1.71141019453934e-05 7.68798894849698e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1508 0 0 0 0 0 2148 +636 637 0.999971900176332 0.00661907429215939 0.00351947627510202 -0.00135935041629208 -0.00661321042297363 0.99997672938058 -0.00167515528246994 -0.002364916623902 -0.00353048235197463 0.00165183317371597 0.999992403541911 0.00551230548774519 7.57843813031189e-05 5.33488075646093e-05 -7.12507554105489e-06 2.7230423125588e-06 1.32145524711159e-05 -1.63115601700286e-06 5.33488075646093e-05 0.000105598840724725 -3.12856335128017e-06 5.09045824644626e-06 2.20690070881916e-05 -2.42479694479055e-05 -7.12507554105489e-06 -3.12856335128017e-06 1.96564909291933e-05 -4.45267955248165e-06 -1.6825409657503e-06 -3.01320927375273e-06 2.7230423125588e-06 5.09045824644626e-06 -4.45267955248165e-06 2.01965395666304e-05 3.3214922450799e-06 7.16754652044976e-07 1.32145524711159e-05 2.20690070881916e-05 -1.6825409657503e-06 3.3214922450799e-06 4.49598709526348e-05 -6.58296193459228e-06 -1.63115601700286e-06 -2.42479694479055e-05 -3.01320927375273e-06 7.16754652044976e-07 -6.58296193459228e-06 6.69747548875926e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1571 0 0 0 0 0 2152 +632 633 0.998623381717928 0.00820629657236922 -0.0518073178500411 0.00756424586828041 -0.00905717443060656 0.999827578148475 -0.0162105387044421 0.00272105511439901 0.0516653566481683 0.016657450895049 0.998525523084962 0.0170873546558081 5.0364713361112e-05 1.57316787749661e-05 -5.50350804544971e-06 4.82898666676239e-06 -2.77363936885692e-06 -1.93219404469347e-08 1.57316787749661e-05 7.10056141971534e-05 -3.67733909491381e-06 5.35325134860042e-06 1.5586877147906e-05 -1.95558630004809e-05 -5.50350804544971e-06 -3.67733909491381e-06 2.03411853731189e-05 -3.71594999077767e-06 1.86177206973791e-06 -4.17999870526423e-06 4.82898666676239e-06 5.35325134860042e-06 -3.71594999077767e-06 1.95025976722602e-05 3.48065851915378e-06 2.14248414026515e-06 -2.77363936885692e-06 1.5586877147906e-05 1.86177206973791e-06 3.48065851915378e-06 3.63925158809537e-05 -1.43178628662946e-05 -1.93219404469347e-08 -1.95558630004809e-05 -4.17999870526423e-06 2.14248414026515e-06 -1.43178628662946e-05 4.88623004074497e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1561 0 0 0 0 0 2051 +634 635 0.999674002509885 -0.00349271931752548 0.0252920860672829 -0.00447112694781505 0.00358609708507754 0.99998691752117 -0.00364756003455533 0.00385494118550296 -0.0252790152807078 0.00373707081526043 0.999673449526474 -0.0077306522138245 5.33758134346871e-05 2.55140660600145e-05 -7.91001008529714e-06 3.03495912838489e-06 1.56421100690703e-06 -9.36220412002108e-06 2.55140660600145e-05 5.96860100986899e-05 -4.39096430922253e-06 9.23411049214703e-06 7.392653126447e-06 -1.47737963106097e-05 -7.91001008529714e-06 -4.39096430922253e-06 2.16439863186314e-05 -6.72552871824625e-06 -5.8545973190326e-06 -9.89002593546569e-07 3.03495912838489e-06 9.23411049214703e-06 -6.72552871824625e-06 1.89546264504235e-05 1.6697450546431e-06 7.52360991718769e-07 1.56421100690703e-06 7.392653126447e-06 -5.8545973190326e-06 1.6697450546431e-06 4.15737392935533e-05 -7.0982371052125e-06 -9.36220412002108e-06 -1.47737963106097e-05 -9.89002593546569e-07 7.52360991718769e-07 -7.0982371052125e-06 4.96245678578329e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1603 0 0 0 0 0 2013 +637 638 0.999925355292078 0.0121813190820899 -0.000948319266367953 -0.00109376585116962 -0.0121723691140521 0.999886021974157 0.00893176862928043 -0.00575384302961283 0.00105701190245077 -0.00891955862787167 0.999959661286255 0.0106038880053566 0.000138600066418329 0.000126957673797499 -1.4415432491065e-05 2.01535229865293e-05 6.73745656471321e-06 1.19344327774209e-05 0.000126957673797499 0.000155211444313612 -1.41659102881769e-05 1.94741066116103e-05 1.20456268201827e-05 -1.41078015452674e-06 -1.4415432491065e-05 -1.41659102881769e-05 2.24247017611484e-05 -4.65885508751074e-06 -1.67833576095777e-06 1.2201770054504e-06 2.01535229865293e-05 1.94741066116103e-05 -4.65885508751074e-06 2.70887776933547e-05 -6.098405034712e-06 8.92391477837925e-06 6.73745656471321e-06 1.20456268201827e-05 -1.67833576095777e-06 -6.098405034712e-06 5.74209476309541e-05 -4.35807615161655e-06 1.19344327774209e-05 -1.41078015452674e-06 1.2201770054504e-06 8.92391477837925e-06 -4.35807615161655e-06 6.26203774785355e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1540 0 0 0 0 0 2029 +638 639 0.999930557075685 -0.00217934098712025 0.0115815154091431 -0.310876015143914 0.00207450816541118 0.999956841223492 0.0090560535669793 0.8154206647957 -0.011600751793828 -0.00903139873985275 0.999891922356921 0.123335155605192 0.00011661886002316 7.94121793000173e-06 -1.60886909955494e-05 0.00013234151121491 -0.000357889177244162 2.06281326476559e-05 7.94121793000173e-06 0.000292156618899991 2.22681038798087e-05 -8.09836042170811e-05 0.000384367077429558 4.37531026387883e-06 -1.60886909955494e-05 2.22681038798087e-05 2.34037158833431e-05 -3.4137882156806e-05 8.53617918313274e-05 -4.37763070341219e-06 0.00013234151121491 -8.09836042170811e-05 -3.4137882156806e-05 0.000457107575076797 -0.00119213161588524 -5.51977968831252e-05 -0.000357889177244162 0.000384367077429558 8.53617918313274e-05 -0.00119213161588524 0.00344736709915766 0.000146627037673963 2.06281326476559e-05 4.37531026387883e-06 -4.37763070341219e-06 -5.51977968831252e-05 0.000146627037673963 0.000122268030488078 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1112 0 0 0 0 0 939 +642 643 0.999846955444983 0.00878505988611512 0.0151290584702586 -0.00566034456929821 -0.00893113282860125 0.999913891742234 0.00961477858808618 0.00184012094064458 -0.015043289327704 -0.00974842672934513 0.999839320902367 0.00138216220939872 7.99138117053172e-05 6.34760589472571e-05 -1.26450686482199e-05 1.53610375178922e-05 -1.6464221101359e-05 2.73092167840364e-05 6.34760589472571e-05 8.78374969288546e-05 -1.43652794924481e-05 1.81536260429061e-05 -1.02464432492724e-05 1.23235996816467e-05 -1.26450686482199e-05 -1.43652794924481e-05 2.33802490515129e-05 -7.83942823966152e-06 -7.3826230634709e-07 -1.15117427187185e-05 1.53610375178922e-05 1.81536260429061e-05 -7.83942823966152e-06 2.2500077664562e-05 -7.96475834656172e-06 1.37138265217593e-05 -1.6464221101359e-05 -1.02464432492724e-05 -7.3826230634709e-07 -7.96475834656172e-06 5.39820823962465e-05 -3.32252472535411e-05 2.73092167840364e-05 1.23235996816467e-05 -1.15117427187185e-05 1.37138265217593e-05 -3.32252472535411e-05 8.72245418127547e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1541 0 0 0 0 0 1918 +640 641 0.999982030256272 0.00164607593972138 0.00576451199548373 -5.90575187605913e-05 -0.00164961973728415 0.999998453289337 0.000610060370210307 -0.00527725689244082 -0.00576349887375438 -0.000619558660345357 0.999983198972762 0.0092638889755912 8.71814898007623e-05 5.08628278672673e-05 -7.06495695440754e-06 1.10597043563876e-05 -9.12779657447983e-06 1.05037827820369e-05 5.08628278672673e-05 0.000126959424825375 -3.06463032963771e-06 1.70892748964597e-05 9.54910459354802e-06 -2.17247526389361e-05 -7.06495695440754e-06 -3.06463032963771e-06 2.17303532653339e-05 -5.72403389013796e-06 6.41553454293495e-06 -8.39505417335099e-06 1.10597043563876e-05 1.70892748964597e-05 -5.72403389013796e-06 2.01996431184543e-05 -1.1108241437991e-07 -2.93677634172675e-07 -9.12779657447983e-06 9.54910459354802e-06 6.41553454293495e-06 -1.1108241437991e-07 4.99231600524196e-05 -2.02879426216074e-05 1.05037827820369e-05 -2.17247526389361e-05 -8.39505417335099e-06 -2.93677634172675e-07 -2.02879426216074e-05 8.45338795324942e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1497 0 0 0 0 0 2009 +639 640 0.999958291336422 -0.00337673668511752 0.00848606133040059 0.00121796195907845 0.00330269885369204 0.999956494881846 0.00872356142268315 0.00226604024739057 -0.0085151493131806 -0.0086951706695663 0.999925940377187 -0.00326915235328624 7.50894846328416e-05 3.92795085571147e-05 -1.35562409784257e-05 5.81589451563213e-06 4.91889775443273e-06 -6.79043163593254e-06 3.92795085571147e-05 7.28947391697358e-05 -1.34737182363205e-05 1.03195590703304e-05 1.31624945394486e-05 -1.97776154663502e-05 -1.35562409784257e-05 -1.34737182363205e-05 2.54135304372599e-05 -5.63317698959973e-06 -2.38781513594586e-06 -6.03115751352656e-06 5.81589451563213e-06 1.03195590703304e-05 -5.63317698959973e-06 1.99930920437027e-05 5.5986756178637e-06 1.96838263880331e-06 4.91889775443273e-06 1.31624945394486e-05 -2.38781513594586e-06 5.5986756178637e-06 3.35238488279905e-05 -1.8372938343586e-05 -6.79043163593254e-06 -1.97776154663502e-05 -6.03115751352656e-06 1.96838263880331e-06 -1.8372938343586e-05 5.95583546174465e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1598 0 0 0 0 0 2010 +646 647 0.99996510570927 -0.000608433657278631 0.00833169684596618 -0.00476555673943377 0.000739936712781464 0.999875064432061 -0.0157894908291428 0.0068412336053915 -0.00832104906303709 0.0157951047944354 0.999840624703269 -0.00489697758617846 9.67502408656081e-05 8.48869075420212e-05 -9.16319174511505e-06 5.65887564759422e-06 1.42913659549562e-05 2.65027164103015e-05 8.48869075420212e-05 0.000124839051519228 -5.37718192966852e-06 1.2026135979255e-05 1.50670046855235e-05 5.77444741710456e-06 -9.16319174511505e-06 -5.37718192966852e-06 2.03540512816934e-05 -4.88954206164034e-06 -1.96425197241703e-06 -4.44146544398803e-06 5.65887564759422e-06 1.2026135979255e-05 -4.88954206164034e-06 2.63793252423525e-05 -8.44487945370335e-06 9.68744029748963e-06 1.42913659549562e-05 1.50670046855235e-05 -1.96425197241703e-06 -8.44487945370335e-06 6.32132963146847e-05 -1.48138866950152e-05 2.65027164103015e-05 5.77444741710456e-06 -4.44146544398803e-06 9.68744029748963e-06 -1.48138866950152e-05 9.73812585408869e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1475 0 0 0 0 0 1981 +648 649 0.999999308916318 -0.000501758149267421 0.00106320536384823 -0.000650259635065556 0.000509334375375081 0.999974397389759 -0.0071375866707902 0.00150607419076389 -0.00105959680073753 0.00713812326516042 0.999973961886444 0.000118492798385887 0.000120052960444452 9.71147609643879e-05 -5.58279049158693e-06 -2.95325606851728e-06 2.75918826399266e-05 7.53384117641291e-06 9.71147609643879e-05 0.000115270601605498 -5.87545225987742e-06 1.35775503899074e-06 1.80028548488573e-05 -2.88087402163536e-06 -5.58279049158693e-06 -5.87545225987742e-06 1.89663494629705e-05 8.73777898875029e-07 -4.03939070797738e-06 -5.37568438912082e-06 -2.95325606851728e-06 1.35775503899074e-06 8.73777898875029e-07 2.3370868681061e-05 -1.73415062290114e-06 -2.43285628730976e-06 2.75918826399266e-05 1.80028548488573e-05 -4.03939070797738e-06 -1.73415062290114e-06 5.6728667121728e-05 1.04844808977088e-05 7.53384117641291e-06 -2.88087402163536e-06 -5.37568438912082e-06 -2.43285628730976e-06 1.04844808977088e-05 5.54471411148584e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1475 0 0 0 0 0 2110 +643 644 0.999997759835196 0.00168973465478286 0.00127480248866579 -0.00347994766435737 -0.00167419228495025 0.999925438019101 -0.0120960936876836 0.00500914625956167 -0.00129514662555856 0.0120939323259489 0.999926026962052 0.00466196420216695 0.000126698760316902 0.000100998893754051 -1.08756712032027e-05 1.62345252278071e-05 -9.7214880075298e-06 6.82658723035433e-05 0.000100998893754051 0.000144000010872118 -1.19132664560239e-05 1.4818864974126e-05 1.11914077424171e-05 5.04494797117866e-05 -1.08756712032027e-05 -1.19132664560239e-05 1.96209838347857e-05 -4.20037238066181e-06 9.00125757235884e-07 -1.71467264672232e-05 1.62345252278071e-05 1.4818864974126e-05 -4.20037238066181e-06 2.08699107637214e-05 -3.6805927319233e-06 1.11308960755916e-05 -9.7214880075298e-06 1.11914077424171e-05 9.00125757235884e-07 -3.6805927319233e-06 4.99025956713005e-05 -1.51920338987828e-05 6.82658723035433e-05 5.04494797117866e-05 -1.71467264672232e-05 1.11308960755916e-05 -1.51920338987828e-05 0.000150008081473196 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1443 0 0 0 0 0 1862 +653 654 0.999709340974168 -0.000659884468763867 0.0240997535564564 0.00050930677488122 0.00139549635667838 0.999533195016794 -0.0305195781333724 0.00113414058184767 -0.0240683642757988 0.0305443384608083 0.999243592538416 0.000102341023401705 0.000132473973616433 0.00011169265523536 -9.37322981191292e-06 1.04389574612716e-05 2.30937002253105e-05 6.12282805535332e-06 0.00011169265523536 0.000143508929888262 -8.15770444697455e-06 1.34303307160304e-05 1.3251778410383e-05 -1.41102901717478e-05 -9.37322981191292e-06 -8.15770444697455e-06 1.9224272776683e-05 -2.19079702488907e-06 -6.18829200528369e-07 -5.41447488027353e-06 1.04389574612716e-05 1.34303307160304e-05 -2.19079702488907e-06 2.62488116209953e-05 -6.81502645971667e-06 2.66459426736656e-07 2.30937002253105e-05 1.3251778410383e-05 -6.18829200528369e-07 -6.81502645971667e-06 6.06546858286714e-05 -9.05095046203682e-07 6.12282805535332e-06 -1.41102901717478e-05 -5.41447488027353e-06 2.66459426736656e-07 -9.05095046203682e-07 5.75229884219261e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1326 0 0 0 0 0 2344 +641 642 0.999942249822303 0.00186287890791694 0.0105842667429539 -0.00231068279114932 -0.0019131802977409 0.999986915440623 0.00474433227081276 -0.0024269785629545 -0.0105752901359678 -0.00476430789537972 0.999932730041785 -0.00213971161731121 5.77951417914804e-05 3.92185460758907e-05 -9.62649024580371e-06 9.97311462142145e-06 -4.31966042345145e-06 4.68318606776726e-06 3.92185460758907e-05 9.57169218896082e-05 -8.87276691278575e-06 1.59744032724819e-05 1.32788332106377e-05 -2.05029437210376e-05 -9.62649024580371e-06 -8.87276691278575e-06 2.22938596894477e-05 -9.39380354507503e-06 -6.56262988047143e-07 -1.10618437026559e-05 9.97311462142145e-06 1.59744032724819e-05 -9.39380354507503e-06 1.99709773592042e-05 2.07519114140799e-06 1.13589662362198e-06 -4.31966042345145e-06 1.32788332106377e-05 -6.56262988047143e-07 2.07519114140799e-06 4.27331130208557e-05 -2.07263898438583e-05 4.68318606776726e-06 -2.05029437210376e-05 -1.10618437026559e-05 1.13589662362198e-06 -2.07263898438583e-05 6.77409698434359e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1569 0 0 0 0 0 1961 +654 655 0.999989251578959 -0.00187465908720081 0.00424056362528806 0.00170610306762969 0.00192212570441035 0.9999352375281 -0.0112172270369831 -0.00487286640670755 -0.00421926051930736 0.0112252573658494 0.999928093133572 0.00445934025218984 0.000104471463193692 9.25414509668713e-05 -7.16724396632337e-06 9.74470571101558e-06 2.62496979235382e-05 8.28585873508266e-06 9.25414509668713e-05 0.000113962476579037 -6.00765115184345e-06 7.77492220789374e-06 2.7501079572313e-05 -5.20330436745791e-06 -7.16724396632337e-06 -6.00765115184345e-06 1.84361395292911e-05 -1.88382889268384e-07 -4.77223825358219e-07 -3.03458001405321e-06 9.74470571101558e-06 7.77492220789374e-06 -1.88382889268384e-07 2.84362340698584e-05 -6.56902742624117e-06 -2.4101750591791e-06 2.62496979235382e-05 2.7501079572313e-05 -4.77223825358219e-07 -6.56902742624117e-06 7.84499284220371e-05 4.71273817278729e-06 8.28585873508266e-06 -5.20330436745791e-06 -3.03458001405321e-06 -2.4101750591791e-06 4.71273817278729e-06 5.04065811542386e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1173 0 0 0 0 0 2455 +645 646 0.99997842896728 -0.00125713586999585 0.00644679839417466 0.000366419703752249 0.00131278569540517 0.999961854138296 -0.00863521059499507 2.70451926774352e-05 -0.00643569684251074 0.00864348758929782 0.999941934278408 -0.000505597053235862 0.000149100103437906 7.64713075138113e-05 -1.10698541459732e-05 -7.27500488431942e-08 2.36628259797434e-05 8.36001657234522e-05 7.64713075138113e-05 0.000119138832027015 -1.32006438454808e-05 1.24575306970997e-05 8.17394278524145e-06 4.34162244264605e-06 -1.10698541459732e-05 -1.32006438454808e-05 2.19612229301747e-05 -3.29318745607977e-06 -5.532289080477e-06 -4.40743888625864e-06 -7.27500488431942e-08 1.24575306970997e-05 -3.29318745607977e-06 2.15842616565435e-05 -8.18164738163523e-07 -8.90765536805472e-07 2.36628259797434e-05 8.17394278524145e-06 -5.532289080477e-06 -8.18164738163523e-07 4.83683278738459e-05 1.42012116073851e-05 8.36001657234522e-05 4.34162244264605e-06 -4.40743888625864e-06 -8.90765536805472e-07 1.42012116073851e-05 0.000150275775157829 0 0 0 0 0 0 7 0 0 0 0 0 0 0 0 0 0 0 1481 0 0 0 0 0 1865 +651 652 0.999996922453487 -0.000695350880045432 0.00238150597503312 -0.00132923809637055 0.000710711941534237 0.999978911223092 -0.00645538516405157 0.00291339943702962 -0.00237696699423005 0.00645705786203876 0.999976327935654 -0.000820469535123722 0.000139372295358918 8.77549683781829e-05 -7.32679784667408e-06 9.39834525396186e-06 2.34646165445942e-05 1.73397121325713e-05 8.77549683781829e-05 9.73075856346934e-05 -6.41243929676172e-06 7.94358967611707e-06 1.68761994305779e-05 -1.31088142881139e-05 -7.32679784667408e-06 -6.41243929676172e-06 1.71114081768709e-05 4.34272173906887e-07 4.44252821797361e-07 -4.53309497929816e-06 9.39834525396186e-06 7.94358967611707e-06 4.34272173906887e-07 2.16335778323765e-05 6.084947754658e-07 1.28328516695592e-06 2.34646165445942e-05 1.68761994305779e-05 4.44252821797361e-07 6.084947754658e-07 4.71805152523603e-05 -8.81576041623705e-07 1.73397121325713e-05 -1.31088142881139e-05 -4.53309497929816e-06 1.28328516695592e-06 -8.81576041623705e-07 5.10069423321216e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1347 0 0 0 0 0 2204 +649 650 0.999973643831886 -0.000768866820824241 0.00721945187611392 -0.001513479822434 0.000830721860105543 0.999962942574828 -0.00856874426515053 0.0012383762121287 -0.00721259611865464 0.00857451578237762 0.999937226097882 -0.00245063604635165 9.57864135202898e-05 7.08099077665763e-05 -2.72493750008669e-06 7.75819790513789e-06 1.61679305277079e-06 -3.80966226094751e-06 7.08099077665763e-05 7.8726447108206e-05 -5.41734230499577e-06 6.4353284581615e-06 3.23210164471651e-07 -1.08710790910529e-05 -2.72493750008669e-06 -5.41734230499577e-06 1.71285078909316e-05 1.40793731988236e-06 1.037557700606e-06 -8.33204306627772e-07 7.75819790513789e-06 6.4353284581615e-06 1.40793731988236e-06 1.99996976516581e-05 -1.93287664781169e-06 -1.35387561572106e-06 1.61679305277079e-06 3.23210164471651e-07 1.037557700606e-06 -1.93287664781169e-06 4.74768460707715e-05 8.68011086810978e-07 -3.80966226094751e-06 -1.08710790910529e-05 -8.33204306627772e-07 -1.35387561572106e-06 8.68011086810978e-07 4.60955584839629e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1458 0 0 0 0 0 2137 +647 648 0.999943704135868 0.000221721898291966 0.0106084588154562 -0.00139461337377612 -4.0822097130976e-05 0.999854644347225 -0.0170495897558127 0.00495890704266474 -0.0106106970834059 0.0170481968748881 0.999798365717168 -0.00115122828588252 0.000105108715012857 7.33385154297414e-05 -6.11208886576602e-06 -4.56866880948362e-07 1.0038650947886e-05 -1.27977010220962e-05 7.33385154297414e-05 0.000128374309110763 -1.11935089698166e-06 5.82130605502866e-06 1.32143061790389e-05 -4.36473912628959e-05 -6.11208886576602e-06 -1.11935089698166e-06 1.90264430723107e-05 -1.47255660794304e-06 -5.43870708050251e-06 -8.25058321566967e-06 -4.56866880948362e-07 5.82130605502866e-06 -1.47255660794304e-06 2.28135560346912e-05 -2.75991204148487e-06 -7.07340989467202e-07 1.0038650947886e-05 1.32143061790389e-05 -5.43870708050251e-06 -2.75991204148487e-06 4.68810991540626e-05 -4.42805401646852e-06 -1.27977010220962e-05 -4.36473912628959e-05 -8.25058321566967e-06 -7.07340989467202e-07 -4.42805401646852e-06 6.4091076392939e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1522 0 0 0 0 0 2060 +644 645 0.999998950216946 0.000979173885780655 -0.00106807467329095 -0.00328064164486604 -0.000988562747001184 0.99996056467551 -0.00882563524793807 0.00917586389150696 0.00105939072185943 0.00882668184176877 0.999960482908681 0.00529722906891398 0.000215750324608997 0.000168229444871311 -8.87979769520514e-06 1.65987303537302e-05 4.73852707414167e-06 4.06353266114406e-05 0.000168229444871311 0.000180670491454174 -1.03680158919927e-05 1.26728960565039e-05 1.59933385848411e-05 1.14645426613392e-05 -8.87979769520514e-06 -1.03680158919927e-05 2.15727872996033e-05 -4.44818576530832e-06 4.14426319590459e-07 -8.69980501743466e-06 1.65987303537302e-05 1.26728960565039e-05 -4.44818576530832e-06 2.37802206292628e-05 -1.34423856140628e-05 1.36665714941266e-05 4.73852707414167e-06 1.59933385848411e-05 4.14426319590459e-07 -1.34423856140628e-05 6.95985637276708e-05 -2.49002670909304e-05 4.06353266114406e-05 1.14645426613392e-05 -8.69980501743466e-06 1.36665714941266e-05 -2.49002670909304e-05 0.000106113157461258 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1516 0 0 0 0 0 1776 +650 651 0.999990511448818 -0.000844246991344498 0.0042736704772933 0.00102197629541691 0.000895187340004704 0.999928413642119 -0.0119317320948131 -0.00435033138213872 -0.00426329121186647 0.0119354446156691 0.999919681529406 0.00177236847709462 8.53026723928287e-05 6.32946378603453e-05 -5.40377922836253e-07 -1.5417666424174e-06 3.02492533110194e-05 -7.83822224894318e-06 6.32946378603453e-05 7.7756675229156e-05 -4.51527034246666e-06 3.0180490998087e-06 1.88162943213512e-05 -1.92883210027078e-05 -5.40377922836253e-07 -4.51527034246666e-06 1.79450474632307e-05 6.56381601552109e-07 3.73925032916955e-07 -4.90189396053195e-06 -1.5417666424174e-06 3.0180490998087e-06 6.56381601552109e-07 1.8011104662179e-05 3.67511826377656e-06 2.10698886801442e-06 3.02492533110194e-05 1.88162943213512e-05 3.73925032916955e-07 3.67511826377656e-06 3.92135016679864e-05 2.60137088123062e-06 -7.83822224894318e-06 -1.92883210027078e-05 -4.90189396053195e-06 2.10698886801442e-06 2.60137088123062e-06 4.79330196618743e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1442 0 0 0 0 0 2188 +652 653 0.99997316108811 -0.0010881047650619 0.00724521438419338 -0.00614146140827301 0.0012398526616398 0.99977927100807 -0.0209731263274939 0.010210915801522 -0.00722079419663085 0.0209815464299428 0.999753787109895 0.00287642445774676 5.78858312273217e-05 3.38913837620414e-05 -1.30242036142244e-05 3.90052934825793e-06 1.58417123925665e-05 1.01022764376732e-05 3.38913837620414e-05 8.48104213353339e-05 -9.67325190814714e-06 8.20401605844182e-06 8.92650359245844e-06 -3.10698154398116e-05 -1.30242036142244e-05 -9.67325190814714e-06 2.17772629585523e-05 -4.47585821593592e-06 -4.09828232602249e-06 -7.43814877913191e-06 3.90052934825793e-06 8.20401605844182e-06 -4.47585821593592e-06 2.65174591299137e-05 -3.8134216272107e-06 -8.51835385110773e-07 1.58417123925665e-05 8.92650359245844e-06 -4.09828232602249e-06 -3.8134216272107e-06 5.93084536854298e-05 7.07832693456818e-06 1.01022764376732e-05 -3.10698154398116e-05 -7.43814877913191e-06 -8.51835385110773e-07 7.07832693456818e-06 6.02329652356726e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1366 0 0 0 0 0 2169 +657 658 0.999999739254554 -0.00064948258571867 0.0003156947808135 -0.00286481374647104 0.000650373910868923 0.999995779741038 -0.00283152147976026 0.00245063486424831 -0.000313854424607579 0.00283172606110316 0.999995941403221 0.00596040108669901 2.86471738736783e-05 1.55101147605331e-05 -1.15098866473095e-05 2.96843978384068e-06 6.07163223459939e-06 9.66975454012055e-06 1.55101147605331e-05 6.00532312006792e-05 -8.97092754779988e-06 2.18162316421592e-06 1.24203014254464e-05 -1.4240473873745e-05 -1.15098866473095e-05 -8.97092754779988e-06 1.81638825733197e-05 -2.4765717893321e-06 -1.1051352748114e-06 -2.12416175541745e-06 2.96843978384068e-06 2.18162316421592e-06 -2.4765717893321e-06 2.33341340002242e-05 9.95764022035366e-06 2.03942695511593e-06 6.07163223459939e-06 1.24203014254464e-05 -1.1051352748114e-06 9.95764022035366e-06 3.39060429979979e-05 5.08744215858354e-06 9.66975454012055e-06 -1.4240473873745e-05 -2.12416175541745e-06 2.03942695511593e-06 5.08744215858354e-06 5.45552258598852e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1282 0 0 0 0 0 2578 +659 660 0.999999059570755 0.000606232742149195 0.00123017863209897 0.00262433499768323 -0.00060726330022164 0.999999464887332 0.000837529900304811 -0.0030378050932401 -0.00122967023576671 -0.000838276155003191 0.999998892601486 -0.00128711090142276 2.16755492878397e-05 7.49260667760273e-06 -9.78742228657652e-06 -9.38870094033221e-07 1.97195890038183e-06 1.84318094890922e-06 7.49260667760273e-06 4.67150029238424e-05 -6.52940782645034e-06 -2.66411066370035e-06 5.0856253674435e-06 -2.35932259568622e-05 -9.78742228657652e-06 -6.52940782645034e-06 1.8193931311759e-05 -1.86176911702659e-06 -1.01319459280602e-06 -3.34100303721248e-07 -9.38870094033221e-07 -2.66411066370035e-06 -1.86176911702659e-06 2.2118956565356e-05 6.63464390363944e-06 3.79353782085742e-06 1.97195890038183e-06 5.0856253674435e-06 -1.01319459280602e-06 6.63464390363944e-06 3.7209882223151e-05 4.33094561805851e-06 1.84318094890922e-06 -2.35932259568622e-05 -3.34100303721248e-07 3.79353782085742e-06 4.33094561805851e-06 5.0672622427635e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1330 0 0 0 0 0 2738 +658 659 0.999994857141816 0.000169071624912711 -0.00320267149490843 -0.00125231490430156 -0.000179481749403469 0.999994701193143 -0.00325044180647611 0.000363753044084925 0.00320210496709284 0.00325099991099753 0.999989588707482 0.00614338926976731 2.85455747992161e-05 1.23673142616451e-05 -9.48756543677034e-06 -7.59935461810085e-07 1.22273373006984e-05 5.04582119794235e-06 1.23673142616451e-05 6.91445894833748e-05 -8.48489760070478e-06 3.81339422760256e-06 9.61974329374159e-06 -2.33950213093277e-05 -9.48756543677034e-06 -8.48489760070478e-06 2.39334336858366e-05 -6.82460439852143e-06 -1.57579341333335e-06 -2.43945712433666e-06 -7.59935461810085e-07 3.81339422760256e-06 -6.82460439852143e-06 3.02407733361817e-05 4.24447364498928e-06 4.24241013381943e-06 1.22273373006984e-05 9.61974329374159e-06 -1.57579341333335e-06 4.24447364498928e-06 4.52406778294057e-05 8.04376719254124e-06 5.04582119794235e-06 -2.33950213093277e-05 -2.43945712433666e-06 4.24241013381943e-06 8.04376719254124e-06 5.99094477893045e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1339 0 0 0 0 0 2671 +656 657 0.999952437605364 -0.000633608802642592 -0.00973247486388444 -0.00311429618464776 0.000581786700023586 0.999985644501853 -0.00532656685402862 -0.00102399537785927 0.00973571010900614 0.00532065128531973 0.999938451415173 0.0121440293184032 2.68042794768638e-05 9.36263191338413e-06 -1.18958069890596e-05 4.70636477433147e-06 2.31846635936133e-06 1.19231621117715e-05 9.36263191338413e-06 6.17869519839863e-05 -7.51714172381823e-06 -2.49412073901752e-06 1.37611609459469e-05 -1.57306111877302e-05 -1.18958069890596e-05 -7.51714172381823e-06 2.22096041306407e-05 -6.65589467949015e-06 -1.27488882699176e-06 -4.72582817738896e-06 4.70636477433147e-06 -2.49412073901752e-06 -6.65589467949015e-06 2.81098355883722e-05 1.15434608287164e-05 3.64126476325933e-06 2.31846635936133e-06 1.37611609459469e-05 -1.27488882699176e-06 1.15434608287164e-05 4.08205204308159e-05 6.02057715024544e-06 1.19231621117715e-05 -1.57306111877302e-05 -4.72582817738896e-06 3.64126476325933e-06 6.02057715024544e-06 5.61533013029201e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1195 0 0 0 0 0 2560 +660 661 0.999974433918011 0.000436287464459881 -0.00713730786797008 -0.00141235519412097 -0.000446370372463856 0.999998904671966 -0.00141117268956913 1.16621868568444e-05 0.00713668437332203 0.00141432249418386 0.999973533363778 0.00579017153894511 4.90301189400306e-05 1.93712795388557e-05 -9.52647473937447e-06 -4.02101453999279e-06 2.16938024103867e-05 2.9423924600598e-05 1.93712795388557e-05 6.44566180502548e-05 -7.49054548491455e-06 6.23036488449019e-06 8.00051014324396e-08 -1.73464390386776e-05 -9.52647473937447e-06 -7.49054548491455e-06 2.12779006702943e-05 -3.97323513147553e-06 -2.32834137147514e-06 -2.92050206962827e-06 -4.02101453999279e-06 6.23036488449019e-06 -3.97323513147553e-06 3.21584087244734e-05 -3.4229767159927e-06 -2.06538847436009e-06 2.16938024103867e-05 8.00051014324396e-08 -2.32834137147514e-06 -3.4229767159927e-06 6.65708701201498e-05 2.1187553326254e-05 2.9423924600598e-05 -1.73464390386776e-05 -2.92050206962827e-06 -2.06538847436009e-06 2.1187553326254e-05 8.93288821288256e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1174 0 0 0 0 0 2753 +663 664 0.999977945901716 -0.000216313202068055 0.00663783991849707 0.00475059447227027 0.000188560645741035 0.999991240536619 0.00418130301653108 -0.00556052362236188 -0.0066386862456257 -0.00417995916628204 0.999969227419674 -0.00925433377187748 2.66343959757546e-05 8.33540170697731e-06 -1.0095229055966e-05 3.82177040162144e-06 9.48863980751591e-07 8.83721316914575e-06 8.33540170697731e-06 4.99171000817324e-05 -4.91758256163068e-06 6.06965875742935e-07 7.64490923542076e-06 -1.10527751077079e-05 -1.0095229055966e-05 -4.91758256163068e-06 2.39748129762793e-05 -4.12995918836898e-06 -1.69918282432791e-06 -5.01018162443742e-06 3.82177040162144e-06 6.06965875742935e-07 -4.12995918836898e-06 2.56843757213147e-05 7.83528037393193e-06 5.39745536263652e-06 9.48863980751591e-07 7.64490923542076e-06 -1.69918282432791e-06 7.83528037393193e-06 4.99909878057246e-05 6.31083872249819e-06 8.83721316914575e-06 -1.10527751077079e-05 -5.01018162443742e-06 5.39745536263652e-06 6.31083872249819e-06 4.95108356087389e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1317 0 0 0 0 0 2694 +655 656 0.999977671322892 0.00038593486620347 -0.00667142487967343 -0.00306148751082924 -0.000397972221161003 0.999998295255099 -0.00180308208542586 0.00145237512069556 0.00667071763435249 0.00180569686676585 0.999976120207412 0.00650599855363518 4.82340416619085e-05 1.49240878082335e-05 -7.91884737816072e-06 -3.7312459960992e-07 2.26632532761533e-05 2.9784266094917e-05 1.49240878082335e-05 4.91564945713341e-05 -8.50644699538146e-06 6.35643930737618e-06 3.67945588292615e-06 -1.57109857468767e-05 -7.91884737816072e-06 -8.50644699538146e-06 1.90803637765387e-05 -2.1225146589435e-06 -1.64441863015614e-07 -2.7115845209808e-06 -3.7312459960992e-07 6.35643930737618e-06 -2.1225146589435e-06 3.22502723919554e-05 -1.74792468406081e-06 -5.36065932806654e-06 2.26632532761533e-05 3.67945588292615e-06 -1.64441863015614e-07 -1.74792468406081e-06 6.05153692830449e-05 3.36345030111717e-05 2.9784266094917e-05 -1.57109857468767e-05 -2.7115845209808e-06 -5.36065932806654e-06 3.36345030111717e-05 9.05826497602204e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1263 0 0 0 0 0 2702 +665 666 0.999993907689467 -0.00118520968414213 -0.00328327000920484 -0.00796212999090084 0.00117564518996962 0.999995064675888 -0.00291350000070932 0.0084591648139803 0.00328670691361878 0.00290962229016889 0.999990365781487 0.00465701218382974 2.70312660575218e-05 1.07563622360076e-05 -8.22535513264135e-06 4.21744986746221e-06 4.96793869003834e-06 8.52519965861625e-06 1.07563622360076e-05 4.23146494423157e-05 -7.39849524440393e-06 2.05345558054909e-06 8.305984451974e-06 -1.90268591150444e-05 -8.22535513264135e-06 -7.39849524440393e-06 2.61991647671024e-05 -4.66083854387546e-06 -4.02368225705473e-06 -6.28340526577522e-06 4.21744986746221e-06 2.05345558054909e-06 -4.66083854387546e-06 3.1769247424343e-05 4.91041790566303e-06 9.08495428737687e-06 4.96793869003834e-06 8.305984451974e-06 -4.02368225705473e-06 4.91041790566303e-06 6.28313722123601e-05 -6.86406577075298e-06 8.52519965861625e-06 -1.90268591150444e-05 -6.28340526577522e-06 9.08495428737687e-06 -6.86406577075298e-06 6.44306069315239e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 816 0 0 0 0 0 2627 +667 668 0.999937747916745 0.00103836784435225 -0.0111095491991236 0.00222868664595737 -0.00108315401041772 0.999991308753051 -0.00402606454875079 -0.00226118829477023 0.0111052721073213 0.00403784727061428 0.999930181923139 0.0103798978728012 2.47058133607472e-05 8.47926252230053e-06 -8.44632425056191e-06 8.26596801876292e-07 6.77246720436792e-06 3.75502619977874e-06 8.47926252230053e-06 3.81507832949685e-05 -7.0662599547293e-06 7.29411593784577e-07 -2.36517932991015e-06 -2.02105437074159e-05 -8.44632425056191e-06 -7.0662599547293e-06 2.18991258247178e-05 -4.6239166892511e-06 -3.64797016294711e-06 -5.4133546067423e-06 8.26596801876292e-07 7.29411593784577e-07 -4.6239166892511e-06 3.13850439823287e-05 -7.05789752441697e-06 2.65822842132185e-06 6.77246720436792e-06 -2.36517932991015e-06 -3.64797016294711e-06 -7.05789752441697e-06 7.60522693011039e-05 1.18870118248299e-05 3.75502619977874e-06 -2.02105437074159e-05 -5.4133546067423e-06 2.65822842132185e-06 1.18870118248299e-05 4.4118959593567e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1103 0 0 0 0 0 2612 +661 662 0.99999466464418 -0.000935447485222212 -0.00312979570856025 -0.0015038365515267 0.000930590469838199 0.999998361157054 -0.0015529599425571 -4.41883784541454e-05 0.00313124329178955 0.0015500390989043 0.999993896328492 0.00397220802797962 4.03698405348568e-05 1.27883035391463e-05 -1.06226105131379e-05 4.94314410652974e-07 1.39878255576379e-05 2.597199207969e-05 1.27883035391463e-05 5.59017707396175e-05 -6.51844101765288e-06 7.47389641351807e-06 1.39455495466376e-06 -2.80089924314203e-05 -1.06226105131379e-05 -6.51844101765288e-06 2.43156932395255e-05 -4.56676759736378e-06 -4.1975838930589e-06 -4.24192974709751e-06 4.94314410652974e-07 7.47389641351807e-06 -4.56676759736378e-06 2.49393074292739e-05 1.06342550788158e-05 -5.88893110215847e-06 1.39878255576379e-05 1.39455495466376e-06 -4.1975838930589e-06 1.06342550788158e-05 3.73957287731502e-05 1.31134917627166e-05 2.597199207969e-05 -2.80089924314203e-05 -4.24192974709751e-06 -5.88893110215847e-06 1.31134917627166e-05 0.000103350484752632 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1295 0 0 0 0 0 2698 +666 667 0.999970719371209 -0.000601850051575885 0.0076287729512312 0.00267466475244696 0.000587597033024359 0.999998078113413 0.00187042754657998 -0.00829966957792595 -0.00762988400651017 -0.00186589013493355 0.999969151186201 -0.000650209369258559 6.19514204676094e-05 1.5219996445121e-05 -9.14616574163096e-06 -9.04113797761038e-07 1.8247915242347e-05 3.65525362159219e-05 1.5219996445121e-05 6.43428192029343e-05 -4.79853573140068e-06 2.90363216482054e-06 9.31118048089234e-06 -3.73259571842273e-05 -9.14616574163096e-06 -4.79853573140068e-06 2.14145873232314e-05 -4.23106305359773e-06 -3.1324533666675e-06 -2.92465452331132e-06 -9.04113797761038e-07 2.90363216482054e-06 -4.23106305359773e-06 3.47712396486334e-05 -1.23710963747635e-05 -1.62595624711264e-06 1.8247915242347e-05 9.31118048089234e-06 -3.1324533666675e-06 -1.23710963747635e-05 9.5064372955684e-05 2.84735626021582e-06 3.65525362159219e-05 -3.73259571842273e-05 -2.92465452331132e-06 -1.62595624711264e-06 2.84735626021582e-06 0.00011201291313521 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 905 0 0 0 0 0 2547 +662 663 0.999986377769716 0.000159569091769062 -0.0052171651985135 -0.00186246530357317 -0.000174427838078301 0.999995930027871 -0.00284771884529353 -0.000217663016479829 0.00521668955688679 0.00284859007185811 0.999982335686321 0.00802197784385985 2.2285864251815e-05 8.45438695792008e-06 -9.21283918255818e-06 1.81731380144293e-06 4.67520225148168e-06 3.89752578291876e-06 8.45438695792008e-06 4.20051124843254e-05 -6.11633211366971e-06 7.29071515913391e-07 5.25501770837032e-06 -1.28929786373298e-05 -9.21283918255818e-06 -6.11633211366971e-06 1.66385392611744e-05 -3.80644579021531e-06 -2.01977217526997e-06 -3.81344385773733e-06 1.81731380144293e-06 7.29071515913391e-07 -3.80644579021531e-06 2.16458432233739e-05 8.28801681357956e-06 5.24938473685198e-06 4.67520225148168e-06 5.25501770837032e-06 -2.01977217526997e-06 8.28801681357956e-06 3.71687423110851e-05 8.02349394177859e-06 3.89752578291876e-06 -1.28929786373298e-05 -3.81344385773733e-06 5.24938473685198e-06 8.02349394177859e-06 3.98564221036848e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1338 0 0 0 0 0 2721 +664 665 0.999997704033312 -0.00114949477249302 0.00180847722471156 -0.000915563430499929 0.00114535825242188 0.99999672964217 0.00228666994518583 -0.000558429966871918 -0.00181109982549231 -0.00228459334075417 0.999995750266315 -0.00252471345103886 2.63297150321263e-05 1.71939115591225e-06 -1.46855382676071e-05 5.1420473903069e-06 5.13911611255401e-06 7.64377528732726e-06 1.71939115591225e-06 5.84499145895094e-05 -5.11729859883287e-06 -3.28049532996844e-07 1.01991187889492e-05 -1.98553159213122e-05 -1.46855382676071e-05 -5.11729859883287e-06 2.25037414555634e-05 -9.78428082287145e-06 -5.50517121221275e-06 -5.81733829608325e-06 5.1420473903069e-06 -3.28049532996844e-07 -9.78428082287145e-06 2.7660300734979e-05 1.0974745585785e-05 6.98892846351794e-06 5.13911611255401e-06 1.01991187889492e-05 -5.50517121221275e-06 1.0974745585785e-05 3.47712030781904e-05 9.49336838588822e-07 7.64377528732726e-06 -1.98553159213122e-05 -5.81733829608325e-06 6.98892846351794e-06 9.49336838588822e-07 4.54035153484914e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1235 0 0 0 0 0 2698 +675 676 0.999961122723463 0.000696315029473055 -0.00879023247760426 0.00315208094621654 -0.00073736479349752 0.999988835061068 -0.0046675525031669 -0.0127777952755285 0.00878688424823664 0.00467385264939313 0.999950471656782 0.00995917145743237 3.42493147031095e-05 6.85266662980212e-06 -9.97578164898916e-06 1.31488417994629e-06 4.34369621534724e-06 1.25797907844547e-07 6.85266662980212e-06 6.70008386084584e-05 -6.29799063673273e-06 -2.27297000428016e-06 7.69984897627405e-06 -3.03726915938114e-05 -9.97578164898916e-06 -6.29799063673273e-06 2.71578691097682e-05 -7.82738713828157e-06 4.4960327830236e-07 -2.39527972202825e-06 1.31488417994629e-06 -2.27297000428016e-06 -7.82738713828157e-06 3.23938091498248e-05 -1.33960701967927e-06 4.10403514660723e-06 4.34369621534724e-06 7.69984897627405e-06 4.4960327830236e-07 -1.33960701967927e-06 5.96815632406409e-05 4.85519187064574e-06 1.25797907844547e-07 -3.03726915938114e-05 -2.39527972202825e-06 4.10403514660723e-06 4.85519187064574e-06 4.9405636544695e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1239 0 0 0 0 0 2668 +674 675 0.999987777860406 8.13057882348777e-05 0.0049434319229623 0.00458613752248441 -8.81123783198971e-05 0.999999048475174 0.00137669348617819 -0.00690082371382972 -0.00494331528601505 -0.00137711223758202 0.999986833511256 -0.00267745169603402 2.63140347774378e-05 7.05595989924558e-06 -1.16423194963489e-05 3.7896055923301e-06 5.86602496945434e-06 4.80319108974883e-06 7.05595989924558e-06 5.73298181573305e-05 -7.91136283113498e-06 1.64496261389833e-06 9.08871877086811e-06 -2.7909330146529e-05 -1.16423194963489e-05 -7.91136283113498e-06 2.4356294625583e-05 -8.87893859931229e-06 -1.01698412095768e-06 -6.15779710880969e-06 3.7896055923301e-06 1.64496261389833e-06 -8.87893859931229e-06 2.81443685181031e-05 3.33681081656733e-06 5.36216153180017e-06 5.86602496945434e-06 9.08871877086811e-06 -1.01698412095768e-06 3.33681081656733e-06 4.43484171244834e-05 1.22356912125875e-06 4.80319108974883e-06 -2.7909330146529e-05 -6.15779710880969e-06 5.36216153180017e-06 1.22356912125875e-06 4.96924525211835e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1211 0 0 0 0 0 2587 +668 669 0.999970820405547 0.000352719996256973 -0.00763111564991459 -0.0011413737839846 -0.000354639990981281 0.999999905802932 -0.000250249083619249 -0.00134601133126757 0.00763102666323004 0.000252948080237739 0.999970851299844 0.00403313684573653 3.07454124964755e-05 2.0023766271926e-05 -1.1010247789799e-05 5.70491826392874e-06 5.16767207132989e-06 -5.72758471798902e-06 2.0023766271926e-05 6.26188085980597e-05 -5.29485457195757e-06 1.67119981397983e-06 1.49032434511155e-05 -3.19229740159578e-05 -1.1010247789799e-05 -5.29485457195757e-06 2.42351882772293e-05 -9.52784701035894e-06 -2.56378503092617e-06 -6.04213920421709e-06 5.70491826392874e-06 1.67119981397983e-06 -9.52784701035894e-06 3.15332657400465e-05 -5.39976729054634e-06 2.65659685492218e-06 5.16767207132989e-06 1.49032434511155e-05 -2.56378503092617e-06 -5.39976729054634e-06 6.87282385048207e-05 1.15839509130799e-06 -5.72758471798902e-06 -3.19229740159578e-05 -6.04213920421709e-06 2.65659685492218e-06 1.15839509130799e-06 4.46761837556765e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1286 0 0 0 0 0 2696 +673 674 0.999999968890673 -3.72399799351268e-05 0.000246641109426834 0.00374329207954404 3.66868453074665e-05 0.99999748538046 0.00224229499237721 -0.0125432306270549 -0.000246723992238805 -0.00224228587413669 0.999997455637428 -0.00433884458464443 2.60785389186334e-05 7.17216753002275e-06 -1.08860117997621e-05 4.63681743912266e-06 4.30005762948858e-06 5.97968981096381e-06 7.17216753002275e-06 6.35692182566789e-05 -6.31724500878511e-06 7.7291001794712e-06 7.74543463893135e-07 -3.20806893753845e-05 -1.08860117997621e-05 -6.31724500878511e-06 2.24275057225286e-05 -8.32864597844917e-06 -7.15603239033813e-06 -3.12702006935472e-06 4.63681743912266e-06 7.7291001794712e-06 -8.32864597844917e-06 3.11858931005452e-05 -1.09346650311486e-06 -4.40598510724622e-06 4.30005762948858e-06 7.74543463893135e-07 -7.15603239033813e-06 -1.09346650311486e-06 6.19170625291972e-05 8.96496636390086e-06 5.97968981096381e-06 -3.20806893753845e-05 -3.12702006935472e-06 -4.40598510724622e-06 8.96496636390086e-06 5.60840321282687e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1161 0 0 0 0 0 2692 +669 670 0.999999838999321 0.000567338727526917 1.13181091259607e-05 0.00226794816171984 -0.000567337183131743 0.999999829817175 -0.000135993170014362 -0.00347532618779197 -1.13952613918412e-05 0.000135986726935219 0.999999990688879 -0.00107480040890309 2.28316700654698e-05 4.90833454865726e-06 -1.13197862686104e-05 5.1893409944348e-06 3.40928437992893e-06 2.55704044987852e-06 4.90833454865726e-06 4.63740644546945e-05 -5.55822981199204e-06 -1.41387250978309e-06 2.61450590616805e-06 -2.44969561642105e-05 -1.13197862686104e-05 -5.55822981199204e-06 2.62443339316577e-05 -9.18236101997744e-06 -2.28516458828047e-06 -6.98420526069774e-06 5.1893409944348e-06 -1.41387250978309e-06 -9.18236101997744e-06 3.01373390677564e-05 3.26978185602978e-06 4.38888537162223e-06 3.40928437992893e-06 2.61450590616805e-06 -2.28516458828047e-06 3.26978185602978e-06 4.26105564541959e-05 1.8602166469487e-06 2.55704044987852e-06 -2.44969561642105e-05 -6.98420526069774e-06 4.38888537162223e-06 1.8602166469487e-06 3.95505892823309e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1302 0 0 0 0 0 2652 +676 677 0.999928543647946 -0.000334550449068254 -0.0119497143938584 -0.00138797624947891 0.000286284467548138 0.999991795871752 -0.00404057302774046 -0.00571914566171369 0.0119509681323899 0.00403686328550909 0.999920435882532 0.0115002040811216 5.45697887753428e-05 2.52857543930722e-05 -1.3984179427973e-05 4.40675347863572e-06 1.9757632801793e-05 3.77038486985256e-06 2.52857543930722e-05 5.73621426426094e-05 -6.38483825806107e-06 2.32930061399819e-06 9.7726915265325e-06 -2.61016682581514e-05 -1.3984179427973e-05 -6.38483825806107e-06 2.73810910897706e-05 -9.39013859370643e-06 -4.25544975720139e-06 -8.11544465564475e-06 4.40675347863572e-06 2.32930061399819e-06 -9.39013859370643e-06 3.40475439726967e-05 -5.40464996779043e-06 5.90793343932132e-06 1.9757632801793e-05 9.7726915265325e-06 -4.25544975720139e-06 -5.40464996779043e-06 6.57081447765543e-05 3.64509793062417e-06 3.77038486985256e-06 -2.61016682581514e-05 -8.11544465564475e-06 5.90793343932132e-06 3.64509793062417e-06 5.44364892711826e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1301 0 0 0 0 0 2684 +670 671 0.999928958009951 -0.000432194408692231 0.0119118487703497 0.00548957361435865 0.000400697584122289 0.999996417947575 0.00264641898906264 -0.00945723523821824 -0.0119129498689731 -0.00264145793316644 0.999925549391257 -0.00853510812124717 2.82587067853202e-05 -3.54125936190053e-06 -1.34477971996281e-05 7.80142902012769e-07 7.24240358172073e-06 1.03922336620392e-05 -3.54125936190053e-06 8.25898768705758e-05 -9.62776097528881e-07 5.78688069625479e-06 3.31488867356393e-06 -3.70123770551233e-05 -1.34477971996281e-05 -9.62776097528881e-07 2.5375264903679e-05 -6.86413650500306e-06 -7.91590130874101e-06 -8.81606211424399e-06 7.80142902012769e-07 5.78688069625479e-06 -6.86413650500306e-06 2.61210681644686e-05 1.67925794774345e-06 -6.79521878518042e-07 7.24240358172073e-06 3.31488867356393e-06 -7.91590130874101e-06 1.67925794774345e-06 5.1567194900854e-05 1.0016332500149e-05 1.03922336620392e-05 -3.70123770551233e-05 -8.81606211424399e-06 -6.79521878518042e-07 1.0016332500149e-05 4.82089494816026e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1151 0 0 0 0 0 2705 +671 672 0.999926081493888 0.000971314389326032 -0.0121197399573946 0.0021410785606254 -0.000994833449534976 0.999997633656483 -0.00193468029449977 -0.00911008345362108 0.0121178320951177 0.00194659440853188 0.999924681621333 0.00136597938969438 3.44517972068547e-05 1.03894265076652e-05 -1.34403592671731e-05 4.4487162364229e-06 7.3875185217764e-06 1.36635406976346e-05 1.03894265076652e-05 6.30909300382402e-05 -5.9148393220588e-06 4.24997733157861e-06 4.69942478886402e-06 -1.55938880808748e-05 -1.34403592671731e-05 -5.9148393220588e-06 2.91685627367072e-05 -1.21016931505205e-05 -4.62584307961412e-06 -1.07050357038045e-05 4.4487162364229e-06 4.24997733157861e-06 -1.21016931505205e-05 3.5732631719805e-05 4.37250133656034e-06 9.40099039599655e-06 7.3875185217764e-06 4.69942478886402e-06 -4.62584307961412e-06 4.37250133656034e-06 5.65360319517801e-05 6.45565125779014e-06 1.36635406976346e-05 -1.55938880808748e-05 -1.07050357038045e-05 9.40099039599655e-06 6.45565125779014e-06 6.93214077983736e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1251 0 0 0 0 0 2704 +677 678 0.99999749673495 4.84718021518138e-06 0.0022375210251183 0.00577836192919591 -3.61553906862653e-06 0.999999848494372 -0.000550452688044454 -0.0101293147913445 -0.00223752335426465 0.000550443220270796 0.999997345247226 -0.00856724464211673 3.24755458224711e-05 4.02470786538746e-06 -8.8060158084734e-06 -1.55711185821164e-06 7.26970346511152e-06 6.24684476735484e-06 4.02470786538746e-06 4.8657247383994e-05 -5.73741618008918e-06 4.05961597114042e-07 5.57290002570304e-06 -2.05336178893733e-05 -8.8060158084734e-06 -5.73741618008918e-06 2.50287616638103e-05 -6.86307094979023e-06 -9.57069896572272e-07 -4.78975776837958e-06 -1.55711185821164e-06 4.05961597114042e-07 -6.86307094979023e-06 3.06530544915814e-05 -8.78961643375365e-06 -4.21533550060388e-06 7.26970346511152e-06 5.57290002570304e-06 -9.57069896572272e-07 -8.78961643375365e-06 6.12852257727173e-05 3.99776654650225e-06 6.24684476735484e-06 -2.05336178893733e-05 -4.78975776837958e-06 -4.21533550060388e-06 3.99776654650225e-06 4.7268470303984e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1311 0 0 0 0 0 2700 +672 673 0.999982294875178 1.62610914066756e-05 -0.00595060263747631 0.00127572752278904 -8.9707898998732e-06 0.999999249449361 0.00122516131140571 -0.00798371697439469 0.00595061809370777 -0.00122508623816573 0.999981544483703 0.000269160302003509 3.66227174644947e-05 1.15637280575075e-05 -9.36918962950923e-06 7.28057044699819e-07 1.48373576655623e-05 4.91513698193612e-06 1.15637280575075e-05 9.19793274240357e-05 -5.67995879514263e-06 1.20298499050646e-05 -3.68180014207195e-06 -4.69546086018113e-05 -9.36918962950923e-06 -5.67995879514263e-06 2.69887436894675e-05 -1.15742981402325e-05 -2.63810871443709e-06 -2.92930907531054e-06 7.28057044699819e-07 1.20298499050646e-05 -1.15742981402325e-05 3.85489482355255e-05 -7.87774435514853e-06 -7.3021194340131e-06 1.48373576655623e-05 -3.68180014207195e-06 -2.63810871443709e-06 -7.87774435514853e-06 7.29767827547816e-05 1.73624601691602e-05 4.91513698193612e-06 -4.69546086018113e-05 -2.92930907531054e-06 -7.3021194340131e-06 1.73624601691602e-05 6.93921250460254e-05 0 0 0 0 0 0 9 0 0 0 0 0 0 0 0 0 0 0 1195 0 0 0 0 0 2683 +682 683 0.999997485471844 -0.00020045510672392 0.00223357734119849 0.00505739240215115 0.000199231841812318 0.999999830067205 0.000547879761855355 -0.0130300190327811 -0.00223368678693659 -0.000547433384468751 0.999997355476517 0.000357971280368071 3.47757192849868e-05 1.35601463343717e-05 -1.25841516037703e-05 2.36569886606232e-06 1.37182913036222e-05 7.26528903564437e-06 1.35601463343717e-05 5.11321463275046e-05 -6.29060039685093e-06 9.26422683524491e-09 8.36641077790468e-06 -1.82248855515584e-05 -1.25841516037703e-05 -6.29060039685093e-06 2.60406178870124e-05 -9.70101019810217e-06 -3.52751371328955e-06 -8.90049709561692e-06 2.36569886606232e-06 9.26422683524491e-09 -9.70101019810217e-06 2.9749889527403e-05 -1.61893585354597e-06 4.07240309506038e-06 1.37182913036222e-05 8.36641077790468e-06 -3.52751371328955e-06 -1.61893585354597e-06 5.46411690862308e-05 1.19557754805211e-05 7.26528903564437e-06 -1.82248855515584e-05 -8.90049709561692e-06 4.07240309506038e-06 1.19557754805211e-05 5.07061099796821e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1150 0 0 0 0 0 2625 +683 684 0.999998022856574 -0.000447403300616957 0.00193755341355129 0.00460701670027403 0.000447012623058342 0.999999879675156 0.000202062833578505 -0.0155992953419921 -0.00193764358399416 -0.000201196323237594 0.99999810252689 -0.00517011647124904 3.84033640625983e-05 1.42520042021912e-07 -1.40091292360022e-05 3.25299900304802e-06 1.10869107109909e-05 2.11280390018916e-05 1.42520042021912e-07 7.04278631028868e-05 -7.77478444109685e-06 5.76716179511282e-06 6.12889631861763e-06 -3.87530795078776e-05 -1.40091292360022e-05 -7.77478444109685e-06 2.61751587711651e-05 -7.49159698619938e-06 -3.88094475014607e-06 -9.85294521524343e-06 3.25299900304802e-06 5.76716179511282e-06 -7.49159698619938e-06 3.20846963469245e-05 -6.28801302530316e-06 5.81713353775312e-07 1.10869107109909e-05 6.12889631861763e-06 -3.88094475014607e-06 -6.28801302530316e-06 6.88741258990314e-05 1.94612203115872e-05 2.11280390018916e-05 -3.87530795078776e-05 -9.85294521524343e-06 5.81713353775312e-07 1.94612203115872e-05 7.93146243291514e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1232 0 0 0 0 0 2637 +684 685 0.999998116586278 0.000655752917203252 -0.0018266942841736 0.00618359301761503 -0.000656564701648258 0.999999685965881 -0.000443836605748038 -0.0145416905972532 0.00182640266338029 0.000445035112807775 0.999998233096969 8.94375382026782e-05 2.19819737109194e-05 1.02966235815969e-05 -9.7198493640526e-06 4.01295579203175e-06 1.52875300364124e-06 5.50118971485031e-07 1.02966235815969e-05 3.88390704628782e-05 -6.96122593975492e-06 1.35637806854225e-06 3.46880766589249e-06 -1.40246770936929e-05 -9.7198493640526e-06 -6.96122593975492e-06 2.16485138445674e-05 -6.5420011776316e-06 4.47322217309553e-06 -3.83350752599053e-06 4.01295579203175e-06 1.35637806854225e-06 -6.5420011776316e-06 3.02465669182387e-05 -1.54407322641289e-05 5.60240121565282e-07 1.52875300364124e-06 3.46880766589249e-06 4.47322217309553e-06 -1.54407322641289e-05 8.0122905133791e-05 9.94999281277086e-06 5.50118971485031e-07 -1.40246770936929e-05 -3.83350752599053e-06 5.60240121565282e-07 9.94999281277086e-06 3.26012698559469e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1281 0 0 0 0 0 2662 +680 681 0.999995645438681 -0.000322685914840483 0.00293342418969898 0.00655499015427085 0.000317605513901444 0.999998449300085 0.00173220211401643 -0.0128514074646875 -0.00293397859806219 -0.00173126289933885 0.999994197232344 -0.00408767222010367 3.15348866209823e-05 8.90367231079106e-06 -1.12154214049194e-05 1.29718351816948e-06 6.54201471063405e-06 1.5566457527787e-06 8.90367231079106e-06 5.83922299655484e-05 -6.37093889126674e-06 6.50119629468014e-06 -8.04342691252874e-06 -2.7307778382349e-05 -1.12154214049194e-05 -6.37093889126674e-06 2.57817867892296e-05 -5.86217430704393e-06 -4.87591773236969e-06 -6.90576222745552e-06 1.29718351816948e-06 6.50119629468014e-06 -5.86217430704393e-06 2.91454188465623e-05 -3.50038797633945e-06 -1.60646665783765e-06 6.54201471063405e-06 -8.04342691252874e-06 -4.87591773236969e-06 -3.50038797633945e-06 5.70205434392768e-05 1.12722480945014e-05 1.5566457527787e-06 -2.7307778382349e-05 -6.90576222745552e-06 -1.60646665783765e-06 1.12722480945014e-05 4.38618851975305e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1287 0 0 0 0 0 2627 +681 682 0.999996370296355 0.000518754960421686 0.00264391516639343 0.00497423979830868 -0.000515690709596063 0.999999194773697 -0.00115953225500602 -0.00997433955974584 -0.00264451455055245 0.0011581646037593 0.999995832590088 0.00229731425152225 3.48413442860247e-05 2.00600875507514e-06 -9.67529791899191e-06 6.74083015728723e-07 3.83461956552686e-06 2.89400278856252e-06 2.00600875507514e-06 7.63184881055548e-05 -3.35139825055516e-06 1.59830246371524e-06 5.19942124423468e-06 -4.00059300381251e-05 -9.67529791899191e-06 -3.35139825055516e-06 2.12449757477457e-05 -4.99063864834223e-06 -3.3364593214196e-06 -5.08314180577641e-06 6.74083015728723e-07 1.59830246371524e-06 -4.99063864834223e-06 2.92740541181947e-05 -5.16223552633632e-06 -5.71184553156327e-07 3.83461956552686e-06 5.19942124423468e-06 -3.3364593214196e-06 -5.16223552633632e-06 5.80355499570041e-05 1.03900420185952e-05 2.89400278856252e-06 -4.00059300381251e-05 -5.08314180577641e-06 -5.71184553156327e-07 1.03900420185952e-05 4.88816982134889e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1303 0 0 0 0 0 2630 +678 679 0.999999897275509 -0.000173308828234913 -0.000418823377283077 0.00386173560451395 0.000174034143646345 0.999998484288906 0.00173237755896984 -0.0109173507651216 0.000418522506143032 -0.00173245027058004 0.999998411726225 -0.0052706798757956 3.46574190261207e-05 8.05304366144535e-06 -1.29186037635878e-05 2.91486484744522e-06 6.26901407393617e-06 5.85128999532273e-06 8.05304366144535e-06 5.6527237869299e-05 -4.07879099095973e-06 3.773504602123e-07 7.64810560109733e-07 -2.51897888001247e-05 -1.29186037635878e-05 -4.07879099095973e-06 3.09511809404292e-05 -4.47624448059203e-06 -9.05104365067239e-06 -7.81741764736342e-06 2.91486484744522e-06 3.773504602123e-07 -4.47624448059203e-06 2.77182711770062e-05 -4.77655975782125e-06 -8.11127279023799e-07 6.26901407393617e-06 7.64810560109733e-07 -9.05104365067239e-06 -4.77655975782125e-06 7.58860151176707e-05 1.47190720000533e-05 5.85128999532273e-06 -2.51897888001247e-05 -7.81741764736342e-06 -8.11127279023799e-07 1.47190720000533e-05 4.76773367034776e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1222 0 0 0 0 0 2726 +679 680 0.999928277548727 0.00122756482087153 -0.0119135571113948 0.00297453257129284 -0.00128156077393406 0.999988937595913 -0.00452573615892544 -0.0123547366596893 0.0119078696843147 0.00454067950950629 0.999918789136985 0.0111923447128411 2.88353383297127e-05 1.61698281117868e-05 -1.42307625968402e-05 4.92468326235835e-06 1.02983926701419e-05 3.23906762203908e-06 1.61698281117868e-05 5.39783766596818e-05 -9.99561225028898e-06 5.14335788974866e-06 5.7201950722663e-06 -2.28715264605012e-05 -1.42307625968402e-05 -9.99561225028898e-06 3.06987973258586e-05 -1.11559834423858e-05 -5.61008348654628e-06 -7.39266462793478e-06 4.92468326235835e-06 5.14335788974866e-06 -1.11559834423858e-05 3.59491723130192e-05 -5.91970028389822e-06 3.96535933826614e-06 1.02983926701419e-05 5.7201950722663e-06 -5.61008348654628e-06 -5.91970028389822e-06 7.00309485451797e-05 1.12873336078224e-05 3.23906762203908e-06 -2.28715264605012e-05 -7.39266462793478e-06 3.96535933826614e-06 1.12873336078224e-05 5.01550836225031e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1276 0 0 0 0 0 2662 +687 688 0.999950022614972 0.000948317078862382 -0.00995253570884998 0.00681914544813808 -0.000970361290099907 0.999997086395922 -0.00221033903135457 -0.0209869802543524 0.00995041060884784 0.00221988611977996 0.999948029366692 0.0031428409667338 3.60802944415664e-05 1.74346196745011e-05 -1.37170322743107e-05 5.66213835044435e-06 3.2938448408296e-06 -4.69847379438846e-07 1.74346196745011e-05 5.89310320121194e-05 -8.79812399360757e-06 2.15970070679214e-06 9.79669410522959e-06 -1.44164148137084e-05 -1.37170322743107e-05 -8.79812399360757e-06 2.54481235176979e-05 -8.10588027902993e-06 -4.38751639665261e-06 -4.8323087229943e-06 5.66213835044435e-06 2.15970070679214e-06 -8.10588027902993e-06 3.22146426563907e-05 -1.12785079605786e-05 4.55927502047419e-06 3.2938448408296e-06 9.79669410522959e-06 -4.38751639665261e-06 -1.12785079605786e-05 8.69670327738524e-05 4.80075360781122e-06 -4.69847379438846e-07 -1.44164148137084e-05 -4.8323087229943e-06 4.55927502047419e-06 4.80075360781122e-06 4.20502633273302e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1143 0 0 0 0 0 2714 +693 694 0.999997641744354 -0.00113792777619994 0.00184976379748233 0.00586432000146712 0.00113519278997933 0.999998262038631 0.00147893781066791 -0.0205087616599985 -0.00185144350707834 -0.00147683448442841 0.99999719555449 -0.00517358568486761 2.49189649125918e-05 7.56934716436646e-06 -9.3739097161458e-06 -1.04991602024308e-06 3.9296996423202e-06 7.47636037981164e-06 7.56934716436646e-06 5.85226111304172e-05 -4.69725246717301e-06 -1.91832637294181e-06 6.49207800694741e-06 -3.06504088121022e-05 -9.3739097161458e-06 -4.69725246717301e-06 2.58280448243862e-05 -7.13688120804189e-06 1.05990618544564e-06 -1.78789272469998e-06 -1.04991602024308e-06 -1.91832637294181e-06 -7.13688120804189e-06 3.82292808101674e-05 -2.57066563219451e-05 -5.20801544376345e-07 3.9296996423202e-06 6.49207800694741e-06 1.05990618544564e-06 -2.57066563219451e-05 0.000109995197595997 8.13799505585569e-06 7.47636037981164e-06 -3.06504088121022e-05 -1.78789272469998e-06 -5.20801544376345e-07 8.13799505585569e-06 6.05513211788996e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 995 0 0 0 0 0 2502 +691 692 0.999999078256655 0.000296713652856131 -0.00132493277113538 0.00566119376733218 -0.000298904964525223 0.999998587448346 -0.00165401243484483 -0.0142918178957922 0.00132444013152799 0.00165440693925283 0.999997754395487 0.00449515448732938 3.13316507459573e-05 4.26448144807591e-06 -1.18308631058604e-05 4.98791525720147e-07 1.65216065987672e-06 2.35947387485868e-06 4.26448144807591e-06 7.79972433381164e-05 -5.66363952362517e-06 -1.20344332390823e-06 2.19891840694154e-05 -4.2076360714775e-05 -1.18308631058604e-05 -5.66363952362517e-06 2.42722360809621e-05 -6.49522775571131e-06 -9.19877440503564e-07 -6.76892379404619e-06 4.98791525720147e-07 -1.20344332390823e-06 -6.49522775571131e-06 3.06935702501857e-05 -3.12314331937795e-06 8.1032144964248e-06 1.65216065987672e-06 2.19891840694154e-05 -9.19877440503564e-07 -3.12314331937795e-06 6.61774445295908e-05 -2.43748093734162e-06 2.35947387485868e-06 -4.2076360714775e-05 -6.76892379404619e-06 8.1032144964248e-06 -2.43748093734162e-06 5.40990900949511e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1288 0 0 0 0 0 2689 +697 698 0.99980769785213 0.0162112656779625 -0.0110345901936935 0.00210513805277432 -0.0163163213261836 0.999821766218706 -0.00949807631514674 -0.0141209341944851 0.0108786476183839 0.00967629373397377 0.99989400656548 0.00242373411453037 9.03667695652218e-05 7.18691590582947e-05 -7.98461218942774e-06 1.16054174707529e-06 1.63581393017969e-06 1.97500055552522e-05 7.18691590582947e-05 0.000107888072773345 -6.31690232731684e-06 -4.01049379076617e-06 1.97897252232234e-05 4.04433167443336e-07 -7.98461218942774e-06 -6.31690232731684e-06 2.34438857634134e-05 -6.72528081638298e-07 8.00254960791103e-06 1.37934716414188e-06 1.16054174707529e-06 -4.01049379076617e-06 -6.72528081638298e-07 3.11454296134461e-05 -2.22831089198027e-05 8.48545865942058e-06 1.63581393017969e-06 1.97897252232234e-05 8.00254960791103e-06 -2.22831089198027e-05 8.74158173215245e-05 -1.86582097691884e-06 1.97500055552522e-05 4.04433167443336e-07 1.37934716414188e-06 8.48545865942058e-06 -1.86582097691884e-06 6.8418930192407e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1335 0 0 0 0 0 2509 +696 697 0.999990727934763 -0.00150054887448319 0.00403638422068946 0.00823068771419177 0.00151237394271645 0.999994569275936 -0.00292816387738748 -0.0171036231557959 -0.00403196844719003 0.00293424124957915 0.999987566652071 0.00247798128841249 5.25808138618673e-05 1.40503086787799e-05 -1.38812801818077e-05 4.65679568869058e-06 4.37661335009046e-06 1.63305503025729e-05 1.40503086787799e-05 0.000116586761783529 5.67680483544725e-06 3.1579591884988e-06 2.67424195849285e-05 -6.36925835583542e-05 -1.38812801818077e-05 5.67680483544725e-06 2.9659780127748e-05 -3.34109143347509e-06 6.35372872784447e-07 -9.1739106575538e-06 4.65679568869058e-06 3.1579591884988e-06 -3.34109143347509e-06 3.03808545776195e-05 -1.04706417172348e-05 -3.24362111018383e-06 4.37661335009046e-06 2.67424195849285e-05 6.35372872784447e-07 -1.04706417172348e-05 7.35820503150661e-05 -8.99540204118019e-06 1.63305503025729e-05 -6.36925835583542e-05 -9.1739106575538e-06 -3.24362111018383e-06 -8.99540204118019e-06 9.18461423214978e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1235 0 0 0 0 0 2524 +685 686 0.999936731656948 -0.000339805506231324 0.0112435410543037 0.00605478555383276 0.000300402494029416 0.999993808823471 0.00350600528638535 -0.0101412134388586 -0.0112446628034574 -0.00350240587946571 0.999930642950546 -0.00652642182281085 4.63239710628087e-05 1.50804728429903e-05 -1.43563393405534e-05 -1.02614144584554e-06 1.60462946608533e-05 1.33464236487336e-05 1.50804728429903e-05 7.29732710324236e-05 -1.05622112537157e-05 9.27294075212913e-06 7.26085218247598e-06 -2.3566613217671e-05 -1.43563393405534e-05 -1.05622112537157e-05 2.72738023780341e-05 -4.90135044033232e-06 -1.11263766352445e-05 -3.93241732954244e-06 -1.02614144584554e-06 9.27294075212913e-06 -4.90135044033232e-06 3.51737105274346e-05 -1.6341422344298e-05 -4.42751526545112e-06 1.60462946608533e-05 7.26085218247598e-06 -1.11263766352445e-05 -1.6341422344298e-05 0.000106397725009054 1.75272016805108e-05 1.33464236487336e-05 -2.3566613217671e-05 -3.93241732954244e-06 -4.42751526545112e-06 1.75272016805108e-05 6.11680533904034e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1181 0 0 0 0 0 2648 +688 689 0.999999063760181 -0.000347720335086113 0.00132346867350409 0.00924595011241292 0.000347680754249002 0.99999993910493 3.01368487384842e-05 -0.0201267464599675 -0.00132347907210651 -2.96766759365376e-05 0.999999123760836 -0.00409904072816744 3.13098931628671e-05 1.48508141015136e-05 -1.20690474016786e-05 5.77788790608302e-06 9.40307860461038e-06 3.66533309849105e-06 1.48508141015136e-05 5.90165848180802e-05 -9.5310476973456e-06 3.32582953934296e-06 3.31072847794376e-06 -2.93761805554679e-05 -1.20690474016786e-05 -9.5310476973456e-06 2.77032164117345e-05 -6.95158949809766e-06 -5.43670911734173e-06 -1.12424739311744e-05 5.77788790608302e-06 3.32582953934296e-06 -6.95158949809766e-06 3.70861919398159e-05 -5.70929223964192e-06 -1.62288900884125e-06 9.40307860461038e-06 3.31072847794376e-06 -5.43670911734173e-06 -5.70929223964192e-06 7.30711101375032e-05 2.213050320851e-05 3.66533309849105e-06 -2.93761805554679e-05 -1.12424739311744e-05 -1.62288900884125e-06 2.213050320851e-05 7.31103026567456e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1258 0 0 0 0 0 2671 +686 687 0.999959694308712 -0.00172689145567692 0.00881065286618691 0.00822101265156617 0.00170375116210021 0.999995081655107 0.00263322949498501 -0.018776564030242 -0.0088151568338731 -0.00261811220079026 0.99995771835538 -0.00953838822919362 2.94974374253043e-05 6.86669013354205e-06 -1.08951996127371e-05 1.47359895191353e-06 3.81771098498209e-06 3.45714236035983e-06 6.86669013354205e-06 5.89942830169461e-05 -4.36930033061957e-06 3.88801499067329e-06 1.65184251234838e-06 -2.77560754942194e-05 -1.08951996127371e-05 -4.36930033061957e-06 2.41066096473259e-05 -3.36993754054151e-06 -3.05449430552976e-06 -5.5641692612364e-06 1.47359895191353e-06 3.88801499067329e-06 -3.36993754054151e-06 2.91586511843019e-05 -3.27184057180958e-06 -1.37589474827559e-06 3.81771098498209e-06 1.65184251234838e-06 -3.05449430552976e-06 -3.27184057180958e-06 6.54582265104108e-05 8.49622903878209e-06 3.45714236035983e-06 -2.77560754942194e-05 -5.5641692612364e-06 -1.37589474827559e-06 8.49622903878209e-06 4.75788278658178e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1129 0 0 0 0 0 2669 +698 699 0.998204646442954 0.0499242076300239 -0.0330916501886982 0.00368358215132036 -0.050290488240595 0.998681211172152 -0.0103298230500798 -0.0292662040845101 0.0325323010594007 0.0119754726101997 0.999398938084058 -0.00845671243169702 9.09220393265339e-05 6.37837965233285e-05 -1.55099876549965e-05 4.64756488996575e-06 1.33757419253106e-05 8.6120944013543e-06 6.37837965233285e-05 9.00946003874813e-05 -9.36561168395586e-06 5.30183605677014e-06 1.29505678773032e-05 -2.48507208142512e-06 -1.55099876549965e-05 -9.36561168395586e-06 1.93614122207472e-05 -4.58573817822365e-06 -3.50855604750051e-07 -1.09196907420528e-06 4.64756488996575e-06 5.30183605677014e-06 -4.58573817822365e-06 4.52738834261069e-05 -4.66945798939476e-05 5.67994838435318e-07 1.33757419253106e-05 1.29505678773032e-05 -3.50855604750051e-07 -4.66945798939476e-05 0.000138625698220277 5.94507984174855e-06 8.6120944013543e-06 -2.48507208142512e-06 -1.09196907420528e-06 5.67994838435318e-07 5.94507984174855e-06 4.40307025084374e-05 0 0 0 0 0 18 18 0 0 0 0 0 0 0 0 0 0 0 1317 0 0 93 0 0 2514 +699 700 0.998798167876104 0.0481695248190248 -0.00905078593529617 -0.00439605459607394 -0.0476664251462997 0.997642527352378 0.0493690138825231 -0.0319473168018859 0.0114075308945192 -0.048878262005414 0.99873959756396 -0.0428505138555091 0.000111455135336153 7.49118080798639e-05 -1.70170875813713e-05 -3.54308211851043e-06 2.78816467754674e-05 2.11945427715019e-05 7.49118080798639e-05 8.8073550182016e-05 -1.19999884542991e-05 9.63830326816368e-07 1.62763081342679e-05 6.86176783871108e-06 -1.70170875813713e-05 -1.19999884542991e-05 2.22647029665968e-05 -3.42462249632669e-06 -4.32498520559192e-07 2.40249497220602e-06 -3.54308211851043e-06 9.63830326816368e-07 -3.42462249632669e-06 5.09712403784053e-05 -5.01116326618436e-05 -5.65447356073549e-06 2.78816467754674e-05 1.62763081342679e-05 -4.32498520559192e-07 -5.01116326618436e-05 0.000124191302342474 1.52019813391575e-05 2.11945427715019e-05 6.86176783871108e-06 2.40249497220602e-06 -5.65447356073549e-06 1.52019813391575e-05 5.73867114439259e-05 16 16 0 0 0 137 137 0 0 0 0 0 0 0 0 0 0 0 1438 0 53 94 0 0 2648 +689 690 0.999981459467694 -0.000737466899398312 0.00604457305625966 0.00657742026857203 0.00072081001430593 0.999995938604371 0.00275739146400705 -0.016470104460965 -0.00604658199179046 -0.00275298335171037 0.999977929720892 -0.0077113171159448 3.57613853580055e-05 1.99643625028639e-05 -1.29090575948815e-05 4.05657926972908e-06 5.90435966000936e-06 9.99291699451538e-07 1.99643625028639e-05 6.69284093582987e-05 -1.23628857691232e-05 -1.94653834678233e-06 3.22437189744901e-05 -1.80752423231633e-05 -1.29090575948815e-05 -1.23628857691232e-05 2.70401261626934e-05 -1.04135853761612e-05 -5.92098547249155e-06 -4.96605065609985e-06 4.05657926972908e-06 -1.94653834678233e-06 -1.04135853761612e-05 4.07218849271551e-05 -1.9020904557649e-05 6.87817129550626e-06 5.90435966000936e-06 3.22437189744901e-05 -5.92098547249155e-06 -1.9020904557649e-05 0.00012523712070352 1.31876368085495e-05 9.99291699451538e-07 -1.80752423231633e-05 -4.96605065609985e-06 6.87817129550626e-06 1.31876368085495e-05 5.1532729069517e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1189 0 0 0 0 0 2610 +690 691 0.999999252046025 0.000192240302657308 0.00120787046357792 0.00560733298003523 -0.000194118739711421 0.999998771773096 0.00155523960026057 -0.0136607333102212 -0.00120757000030746 -0.00155547290730505 0.999998061137485 -0.00134343581253574 2.97418836505508e-05 1.00992985151373e-05 -1.17013480636021e-05 2.765257940855e-06 -2.61561601833943e-07 2.03306051672982e-06 1.00992985151373e-05 6.5533644317705e-05 -1.02290776209098e-05 2.45695011726473e-06 1.05796987439203e-05 -2.7230668034651e-05 -1.17013480636021e-05 -1.02290776209098e-05 2.39101095985919e-05 -7.41948424838823e-06 1.4880919578631e-06 -1.73010292291874e-06 2.765257940855e-06 2.45695011726473e-06 -7.41948424838823e-06 3.26724417473538e-05 -1.51655374474983e-05 5.91640904633561e-07 -2.61561601833943e-07 1.05796987439203e-05 1.4880919578631e-06 -1.51655374474983e-05 7.56554515665235e-05 3.04724519540942e-06 2.03306051672982e-06 -2.7230668034651e-05 -1.73010292291874e-06 5.91640904633561e-07 3.04724519540942e-06 4.57645664146418e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1225 0 0 0 0 0 2689 +694 695 0.9999739328803 0.000929423889182386 -0.00716028848163137 0.0106462147314162 -0.000927528703287015 0.999999533934139 0.000267996286641587 -0.0273496873355432 0.00716053422661637 -0.000261347927659776 0.999974328893922 0.00169233831760514 3.15090572846004e-05 1.78431433577758e-05 -1.69919763711228e-05 5.86312993937243e-06 5.12790401898772e-06 2.48410198598352e-06 1.78431433577758e-05 4.77520358205589e-05 -1.32437568219334e-05 -6.39829760729121e-07 1.40175283057897e-05 -1.52996673539958e-05 -1.69919763711228e-05 -1.32437568219334e-05 2.77274224872824e-05 -7.81621051346909e-06 1.81249528466707e-06 -6.66530462019042e-06 5.86312993937243e-06 -6.39829760729121e-07 -7.81621051346909e-06 3.54982068337163e-05 -1.56555979987606e-05 9.00424504733204e-06 5.12790401898772e-06 1.40175283057897e-05 1.81249528466707e-06 -1.56555979987606e-05 8.26855219894827e-05 1.51223045101724e-06 2.48410198598352e-06 -1.52996673539958e-05 -6.66530462019042e-06 9.00424504733204e-06 1.51223045101724e-06 4.63876309553191e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1171 0 0 0 0 0 2615 +700 701 0.998568933234708 0.0209370682318618 -0.0492110226712579 -0.0104025843996036 -0.0200833994767241 0.999640233934724 0.0177780697599203 -0.0237587531072128 0.0495655388748575 -0.0167643035281708 0.998630169523864 -0.0562043933700515 6.86024449076975e-05 6.04377541786628e-05 -1.19418423802464e-05 9.7888000116087e-08 1.28299638380267e-05 1.84336924483801e-06 6.04377541786628e-05 6.95225233872063e-05 -1.40543960840573e-05 4.22941563406247e-06 5.43564147212005e-06 3.45187226842053e-06 -1.19418423802464e-05 -1.40543960840573e-05 1.99181496112676e-05 -2.35501453432629e-07 -3.09795352609574e-06 -2.31169206325044e-06 9.7888000116087e-08 4.22941563406247e-06 -2.35501453432629e-07 5.15344895531692e-05 -4.44592172655534e-05 -1.6319096402414e-06 1.28299638380267e-05 5.43564147212005e-06 -3.09795352609574e-06 -4.44592172655534e-05 0.00010553455533975 1.22711597217207e-05 1.84336924483801e-06 3.45187226842053e-06 -2.31169206325044e-06 -1.6319096402414e-06 1.22711597217207e-05 4.34838766824569e-05 261 260 0 0 11 344 353 0 0 2 0 0 0 0 0 0 0 0 1495 0 25 54 0 0 2769 +692 693 0.999999534178107 0.000666342289270872 0.000698306181259486 0.00541844257549142 -0.000668628973070972 0.999994398847214 0.00327951360666162 -0.0108059995696969 -0.000696116991335515 -0.00327997898673725 0.99999437856369 -0.00412900962848908 2.95910405498018e-05 6.20922497645224e-06 -1.37028733538089e-05 1.5872561410428e-07 8.17985554851366e-06 9.83938833305048e-06 6.20922497645224e-06 5.16289414871904e-05 -8.99329355891071e-06 2.87686678404659e-06 5.29615134979953e-06 -1.49776221058772e-05 -1.37028733538089e-05 -8.99329355891071e-06 2.29532913962465e-05 -4.73824993872241e-06 -6.7215887204078e-06 -7.03900909997816e-06 1.5872561410428e-07 2.87686678404659e-06 -4.73824993872241e-06 2.99422968507909e-05 -5.57054233776706e-06 5.19083586883051e-06 8.17985554851366e-06 5.29615134979953e-06 -6.7215887204078e-06 -5.57054233776706e-06 6.81489789895901e-05 1.50991447776335e-05 9.83938833305048e-06 -1.49776221058772e-05 -7.03900909997816e-06 5.19083586883051e-06 1.50991447776335e-05 5.03760315255939e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1126 0 0 0 0 0 2691 +695 696 0.99999622585763 2.01613341018217e-05 -0.00274733762317902 0.00774256940891183 -1.929820006693e-05 0.999999950453839 0.000314197229654918 -0.0199897226186897 0.00274734382169431 -0.000314143025158737 0.999996176700734 -9.72926789189656e-05 3.02426277216942e-05 3.66532952489397e-06 -1.06011105832385e-05 2.70737421923163e-06 -2.80813528277916e-07 7.01325716455308e-06 3.66532952489397e-06 8.06597186321439e-05 -7.60857285689097e-06 -1.611001697712e-06 2.34249299926919e-05 -4.17716045236435e-05 -1.06011105832385e-05 -7.60857285689097e-06 2.10298524282279e-05 -2.11989191083728e-06 -5.82095179925352e-06 -7.37176217055752e-06 2.70737421923163e-06 -1.611001697712e-06 -2.11989191083728e-06 2.63756361035972e-05 -1.18206849427816e-05 4.90704863250281e-06 -2.80813528277916e-07 2.34249299926919e-05 -5.82095179925352e-06 -1.18206849427816e-05 7.97805643807118e-05 -4.29510779805425e-06 7.01325716455308e-06 -4.17716045236435e-05 -7.37176217055752e-06 4.90704863250281e-06 -4.29510779805425e-06 6.03304224573693e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1280 0 0 0 0 0 2472 +706 707 0.997009992497459 0.0396926943410066 0.0662990563746452 0.0203105019817337 -0.0390663529021073 0.999179139461536 -0.0107176180111578 -0.0349538359082965 -0.0666700452313104 0.00809550991948652 0.997742235142924 -0.109554391963094 0.000114056067309786 1.84581032999843e-06 3.00214670031308e-06 1.41717990322075e-05 -1.22593635203943e-05 6.63918552838671e-05 1.84581032999843e-06 6.98052663797558e-05 5.26355681965177e-06 -1.01099306559902e-05 1.04081508106468e-05 -1.26429292376572e-05 3.00214670031308e-06 5.26355681965177e-06 2.30918621788535e-05 -5.37019143441071e-06 4.74669293468635e-06 -2.59050223105257e-06 1.41717990322075e-05 -1.01099306559902e-05 -5.37019143441071e-06 5.68027141652952e-05 -3.31848529309434e-05 2.80671891111265e-06 -1.22593635203943e-05 1.04081508106468e-05 4.74669293468635e-06 -3.31848529309434e-05 6.64428394357461e-05 1.21371506501435e-05 6.63918552838671e-05 -1.26429292376572e-05 -2.59050223105257e-06 2.80671891111265e-06 1.21371506501435e-05 0.000179589050612995 1036 1035 0 0 6 1028 1027 0 0 6 0 0 0 0 0 0 0 0 1248 0 87 80 0 0 3090 +704 705 0.998075749310659 0.04701786931374 0.040424232870429 -0.0212767958340918 -0.0474663720453399 0.998820683853847 0.010207106866642 0.00744065446244481 -0.0398966435031819 -0.012106257511293 0.999130470142038 -0.0893336593742513 2.68412038315042e-05 1.91110019802894e-05 -1.17602587665791e-06 -5.85788138011631e-06 6.67244185388282e-06 2.28567789480406e-07 1.91110019802894e-05 4.23809047912644e-05 2.14241592608834e-07 -5.27297125395173e-07 4.24029300280962e-06 9.79840250191155e-06 -1.17602587665791e-06 2.14241592608834e-07 1.83244913041145e-05 2.89648467752127e-06 -1.13902115135578e-05 -2.35258872893155e-06 -5.85788138011631e-06 -5.27297125395173e-07 2.89648467752127e-06 5.65975371993305e-05 -5.41680858491517e-05 -1.38157798091166e-05 6.67244185388282e-06 4.24029300280962e-06 -1.13902115135578e-05 -5.41680858491517e-05 0.000100509730358673 3.04674277777627e-05 2.28567789480406e-07 9.79840250191155e-06 -2.35258872893155e-06 -1.38157798091166e-05 3.04674277777627e-05 6.34184773587854e-05 848 848 0 0 2 881 883 0 0 2 0 0 0 0 0 0 0 0 1442 0 103 120 0 0 3533 +702 703 0.998540847298713 0.0269832151441814 -0.0467769427864979 -0.0139513648508917 -0.025360562546608 0.999067502658773 0.0349423381942686 -0.00358058272879509 0.0476761800408554 -0.0337050624038271 0.998294020128873 -0.0723635892096333 4.55663504287111e-05 3.37555735477998e-05 -6.30445840798879e-06 2.44810744651568e-06 1.30141737866611e-06 2.97945636158068e-05 3.37555735477998e-05 8.25192760270992e-05 -1.32609598150369e-05 -1.42327825888684e-07 1.79258435501978e-05 4.04009393163814e-05 -6.30445840798879e-06 -1.32609598150369e-05 2.28772204003746e-05 -2.94839841944428e-06 -6.19082980136852e-06 -3.53233767485234e-06 2.44810744651568e-06 -1.42327825888684e-07 -2.94839841944428e-06 3.67515070143884e-05 -1.99122587771663e-05 1.29227147693513e-05 1.30141737866611e-06 1.79258435501978e-05 -6.19082980136852e-06 -1.99122587771663e-05 6.72932549562299e-05 1.26252165117957e-05 2.97945636158068e-05 4.04009393163814e-05 -3.53233767485234e-06 1.29227147693513e-05 1.26252165117957e-05 0.000128740321181995 571 571 0 0 0 648 668 0 0 0 0 0 0 0 0 0 0 0 1607 0 28 66 0 0 3248 +707 708 0.998705373052947 0.0438691299513066 0.025750286842838 0.0335891431069141 -0.04360823520232 0.998992392869826 -0.0106075827009809 -0.0305557266504573 -0.0261896860941897 0.00947092527340348 0.999612125735154 -0.0676042922137082 3.76474722292122e-05 1.31813660886732e-05 3.80121899640774e-06 -8.47314956912959e-06 6.71027441798439e-06 3.02677849864173e-05 1.31813660886732e-05 5.33477646360886e-05 -1.91401979184525e-06 -2.54268655544465e-07 -4.66739799802114e-06 2.6910275942902e-05 3.80121899640774e-06 -1.91401979184525e-06 2.15654127015717e-05 -5.19983973930488e-07 -4.04033003887414e-06 5.25939005647279e-06 -8.47314956912959e-06 -2.54268655544465e-07 -5.19983973930488e-07 4.00958430915046e-05 -1.92573336748008e-05 2.6138515587796e-06 6.71027441798439e-06 -4.66739799802114e-06 -4.04033003887414e-06 -1.92573336748008e-05 4.50455533213632e-05 -2.93421275934268e-06 3.02677849864173e-05 2.6910275942902e-05 5.25939005647279e-06 2.6138515587796e-06 -2.93421275934268e-06 0.000180759137696619 1116 1116 0 0 5 1096 1096 0 0 1 0 0 0 0 0 0 0 0 1118 0 70 67 0 0 3474 +708 709 0.999415431962849 0.0339207435325905 -0.00426350943568055 0.0767529227918215 -0.0338769506669724 0.999376428344251 0.00995523396996488 -0.0697988192357841 0.00459853977034455 -0.00980497975956296 0.999941356182399 -0.107843789204209 5.05859990586533e-05 2.25285686636698e-05 5.89031659860592e-06 -2.53383760717254e-06 6.02572662782069e-07 -4.05818854280114e-06 2.25285686636698e-05 8.12791399419916e-05 -1.06674953860303e-05 -2.78794920804582e-06 1.84104593026847e-06 -6.46676308556829e-06 5.89031659860592e-06 -1.06674953860303e-05 2.22113870464969e-05 3.70449964134148e-06 1.68635164444691e-06 3.29864190166996e-06 -2.53383760717254e-06 -2.78794920804582e-06 3.70449964134148e-06 3.65166930925367e-05 -1.12317990094614e-05 2.33081462121817e-06 6.02572662782069e-07 1.84104593026847e-06 1.68635164444691e-06 -1.12317990094614e-05 3.38586007283127e-05 2.17523406152908e-06 -4.05818854280114e-06 -6.46676308556829e-06 3.29864190166996e-06 2.33081462121817e-06 2.17523406152908e-06 0.000141601129133263 1152 1150 0 0 7 1149 1147 0 0 6 0 0 0 0 0 0 0 0 1033 0 29 26 0 0 3495 +701 702 0.998462720632732 0.00664974949048264 -0.0550270509694771 -0.0147454685578843 -0.00634517388940403 0.999963578783159 0.00570787837034213 -0.0113068190249656 0.0550630027786065 -0.0053499475596701 0.998468549222314 -0.0751254469680963 6.3373414252535e-05 5.62822219712241e-05 -1.41295681561439e-05 2.88747589543927e-06 4.17199691955484e-06 2.59893141254981e-05 5.62822219712241e-05 0.000103527449373455 -2.11423082980502e-05 8.95316370615697e-06 1.21683757180046e-06 2.26290452144191e-05 -1.41295681561439e-05 -2.11423082980502e-05 2.40512615182249e-05 5.09413871474108e-07 -1.7127086692827e-06 -2.16567849466779e-06 2.88747589543927e-06 8.95316370615697e-06 5.09413871474108e-07 3.79867208723598e-05 -1.85671123854851e-05 4.37527063091767e-06 4.17199691955484e-06 1.21683757180046e-06 -1.7127086692827e-06 -1.85671123854851e-05 7.48001698252367e-05 6.63016062989936e-06 2.59893141254981e-05 2.26290452144191e-05 -2.16567849466779e-06 4.37527063091767e-06 6.63016062989936e-06 6.97466262574684e-05 405 405 0 0 4 447 467 0 0 9 0 0 0 0 0 0 0 0 1596 0 12 37 0 0 3146 +709 710 0.99971678170992 0.0115703490289176 0.0207962350176434 0.0817384148370567 -0.0113049361924084 0.999853718418547 -0.0128351152036289 -0.0632867370518415 -0.0209416996742291 0.0125963799543312 0.999701343615582 -0.0485399663333722 3.16658595699476e-05 1.01999771684184e-05 4.81340116070247e-06 6.89046598226135e-06 -8.14674174196437e-07 9.42646426539149e-06 1.01999771684184e-05 2.92491257372251e-05 -3.14022990511002e-06 2.93896933599995e-06 8.32881678278745e-07 6.61952525974156e-07 4.81340116070247e-06 -3.14022990511002e-06 1.82936624715183e-05 2.40909804006942e-06 2.20779641751448e-06 1.71183581862104e-06 6.89046598226135e-06 2.93896933599995e-06 2.40909804006942e-06 5.14007372956237e-05 -3.03216278955815e-05 1.08841068600966e-05 -8.14674174196437e-07 8.32881678278745e-07 2.20779641751448e-06 -3.03216278955815e-05 4.84363080891388e-05 -1.26155909867644e-05 9.42646426539149e-06 6.61952525974156e-07 1.71183581862104e-06 1.08841068600966e-05 -1.26155909867644e-05 0.000116143460124982 1190 1183 0 0 20 1181 1177 0 0 13 0 0 0 0 0 0 0 0 935 0 13 8 0 0 3562 +703 704 0.998954699696803 0.0416981136299497 -0.0187289955249545 -0.00498791426419183 -0.0413510622524981 0.998972459430545 0.0185503355732114 -0.0150110991419775 0.019483264722833 -0.0177564810419332 0.99965249450834 -0.0850031776809467 3.40382982179342e-05 2.28158091522781e-05 -1.24942552192153e-06 3.46748032700313e-06 2.39325133525076e-07 7.74978996747481e-06 2.28158091522781e-05 5.6409696896563e-05 9.53751857978654e-07 -2.38823056813771e-06 1.59084314547181e-05 1.02847673012548e-05 -1.24942552192153e-06 9.53751857978654e-07 1.84583166828659e-05 -5.37096309851206e-06 -2.55357983047727e-06 -4.21322169947966e-06 3.46748032700313e-06 -2.38823056813771e-06 -5.37096309851206e-06 5.20515152432599e-05 -4.85054200502818e-05 3.72168841013219e-06 2.39325133525076e-07 1.59084314547181e-05 -2.55357983047727e-06 -4.85054200502818e-05 0.000102371943201591 1.17982777587442e-05 7.74978996747481e-06 1.02847673012548e-05 -4.21322169947966e-06 3.72168841013219e-06 1.17982777587442e-05 9.40589270071088e-05 711 711 0 0 0 744 744 0 0 0 0 0 0 0 0 0 0 0 1528 0 87 122 0 0 3287 +710 711 0.99983815913583 -0.015227630283016 -0.00957991711021763 0.0642850739310208 0.0155291631008872 0.999359806029499 0.032230780103311 -0.0495886240237892 0.00908298570189936 -0.0323743319413038 0.999434541129179 -0.103394745169119 0.000106321963893097 8.82416028117252e-05 -8.38708112470194e-07 5.78454066958797e-06 -1.40990433548361e-06 0.000162729928560003 8.82416028117252e-05 0.000117066485696254 -6.8183621254872e-06 7.62803275817323e-06 -9.04832534125444e-07 0.000205590169198621 -8.38708112470194e-07 -6.8183621254872e-06 1.71364641227086e-05 -2.12282022087672e-08 6.01901438272543e-06 2.6485030855793e-06 5.78454066958797e-06 7.62803275817323e-06 -2.12282022087672e-08 6.23090447176491e-05 -3.81680339194691e-05 -4.32030063607699e-06 -1.40990433548361e-06 -9.04832534125444e-07 6.01901438272543e-06 -3.81680339194691e-05 5.36686100224632e-05 4.24171416699895e-06 0.000162729928560003 0.000205590169198621 2.6485030855793e-06 -4.32030063607699e-06 4.24171416699895e-06 0.00103865083683893 1094 1087 0 0 37 1093 1087 0 0 23 0 0 0 0 0 0 0 0 855 0 3 0 0 0 3480 +714 715 0.999933448297569 -0.0100870800502079 -0.00559908847876298 0.0959793138018507 0.0101230778461272 0.999928031562343 0.00643855502253624 -0.0899614189647626 0.00553373930119288 -0.00649480653427617 0.999963596946123 -0.0678383552547929 3.9095598106399e-05 3.04510008836292e-05 3.49798587153858e-06 4.61783177706886e-06 3.46074430626532e-08 3.52897607462977e-05 3.04510008836292e-05 8.68057653205758e-05 6.02024005431476e-07 1.36036370355187e-05 -9.50934724131068e-06 0.000135973164067901 3.49798587153858e-06 6.02024005431476e-07 1.53000307652422e-05 8.56383356111864e-06 6.95839219355851e-07 1.89952464665053e-06 4.61783177706886e-06 1.36036370355187e-05 8.56383356111864e-06 4.748393809125e-05 -2.88113906476145e-05 3.46091375853989e-05 3.46074430626532e-08 -9.50934724131068e-06 6.95839219355851e-07 -2.88113906476145e-05 4.64516460609678e-05 -3.882142045477e-05 3.52897607462977e-05 0.000135973164067901 1.89952464665053e-06 3.46091375853989e-05 -3.882142045477e-05 0.000534747549906447 1218 1214 0 0 16 1218 1214 0 0 14 0 0 0 0 0 0 0 0 801 0 4 0 0 0 3380 +705 706 0.998147743915155 0.043605042074815 0.0424226545932695 -0.00411482888576399 -0.0431329894874813 0.998997507429052 -0.0119802073610519 -0.00468500422865915 -0.0429025236432436 0.0101282010344671 0.999027924038586 -0.0670286667928961 3.56703415220248e-05 3.29358559676606e-05 1.75549636944149e-06 8.80836197956874e-07 1.53829500017263e-06 2.19609213012684e-05 3.29358559676606e-05 4.83384054497236e-05 4.56803630721929e-06 7.47857621898812e-07 3.07727620511969e-06 2.33767844506006e-05 1.75549636944149e-06 4.56803630721929e-06 2.05096248139355e-05 -2.76828870605011e-06 -6.84052632067697e-06 -6.85586083337979e-06 8.80836197956874e-07 7.47857621898812e-07 -2.76828870605011e-06 4.22491150825721e-05 -2.78766347409263e-05 1.23401221561443e-05 1.53829500017263e-06 3.07727620511969e-06 -6.84052632067697e-06 -2.78766347409263e-05 5.94566678257123e-05 8.16742003871764e-07 2.19609213012684e-05 2.33767844506006e-05 -6.85586083337979e-06 1.23401221561443e-05 8.16742003871764e-07 0.000110784003126173 968 968 0 0 2 970 970 0 0 0 0 0 0 0 0 0 0 0 1338 0 91 85 0 0 3526 +713 714 0.999620841544459 0.00751993883101886 0.0264881798152464 0.0877894726604448 -0.0075534658254322 0.999970792484496 0.00116590392100902 -0.0888578871021928 -0.0264786386351549 -0.00136553941969139 0.999648446704201 0.00495816099987499 2.46317367798199e-05 1.40274580396843e-05 3.50433998183409e-06 -1.3673781983914e-06 5.92475021609047e-06 -4.72059872650721e-06 1.40274580396843e-05 3.17825100916573e-05 -7.5104166044711e-06 2.81455718687534e-06 -2.12468619419642e-07 -6.88251500307636e-06 3.50433998183409e-06 -7.5104166044711e-06 1.91800268527345e-05 3.7173750157509e-06 1.96744412493287e-06 4.26126151529641e-07 -1.3673781983914e-06 2.81455718687534e-06 3.7173750157509e-06 4.02313250426363e-05 -1.94633838580393e-05 1.22173813290032e-05 5.92475021609047e-06 -2.12468619419642e-07 1.96744412493287e-06 -1.94633838580393e-05 4.03946151633799e-05 -1.4668432648707e-05 -4.72059872650721e-06 -6.88251500307636e-06 4.26126151529641e-07 1.22173813290032e-05 -1.4668432648707e-05 0.000103717432808685 1202 1187 0 0 44 1174 1174 0 0 13 0 0 0 0 0 0 0 0 758 0 49 28 0 0 3639 +718 719 0.999902701107129 -0.0104189773566548 0.0092754099375512 0.128082121550316 0.0105706190965511 0.999808766790137 -0.01645271593085 -0.135301719173453 -0.00910221569639704 0.0165491619252194 0.999821621545058 -0.0231226436447645 5.68769120947696e-05 -1.16100072359483e-05 3.47059933920573e-06 -1.58585679393411e-05 1.81815885348599e-05 3.94381234051233e-05 -1.16100072359483e-05 7.07601927770929e-05 -5.91915884191776e-06 8.84570927004571e-06 -4.97250553285222e-06 6.09227243374086e-06 3.47059933920573e-06 -5.91915884191776e-06 2.58548602221212e-05 2.31097745356304e-07 -3.17586807545426e-07 8.62098657739044e-06 -1.58585679393411e-05 8.84570927004571e-06 2.31097745356304e-07 8.6673404158876e-05 -6.7543503876096e-05 -9.89356832061743e-06 1.81815885348599e-05 -4.97250553285222e-06 -3.17586807545426e-07 -6.7543503876096e-05 0.000113114019414844 7.30461968228439e-07 3.94381234051233e-05 6.09227243374086e-06 8.62098657739044e-06 -9.89356832061743e-06 7.30461968228439e-07 0.00026434204818306 1872 1846 0 0 84 1858 1846 0 0 57 0 0 0 0 0 0 0 0 1013 0 56 31 0 0 3403 +712 713 0.999931274061427 0.0117070513183401 -0.000626181540215899 0.0761153550955075 -0.0116975477988084 0.999840685379151 0.0134822563410129 -0.0693961477565224 0.000783919247212491 -0.0134740049717943 0.999908914182004 -0.0203518694636788 2.39214819713125e-05 5.12689495771547e-06 5.9437677125355e-06 8.00860161568844e-07 1.34168252961455e-06 -4.89941909991479e-06 5.12689495771547e-06 2.70932056833114e-05 -3.11448286639153e-06 -1.32622444306609e-06 2.24351790158602e-06 -6.04291088022992e-06 5.9437677125355e-06 -3.11448286639153e-06 1.80868210813494e-05 3.99385119393081e-06 2.17273865267922e-06 -8.08845589528345e-08 8.00860161568844e-07 -1.32622444306609e-06 3.99385119393081e-06 3.9861175971817e-05 -1.85949600167294e-05 -6.10484133014405e-06 1.34168252961455e-06 2.24351790158602e-06 2.17273865267922e-06 -1.85949600167294e-05 4.01447644965863e-05 2.63894938224804e-06 -4.89941909991479e-06 -6.04291088022992e-06 -8.08845589528345e-08 -6.10484133014405e-06 2.63894938224804e-06 6.63616721287854e-05 1096 1089 0 0 24 1085 1084 0 0 12 0 0 0 0 0 0 0 0 776 0 39 29 0 0 3476 +715 716 0.999627895981048 -0.0255515220395057 -0.00954930876915982 0.106385638442462 0.0255606799883846 0.999672921052365 0.000838184444626813 -0.105718486107433 0.00952476850298691 -0.00108195937838511 0.999954053018872 0.0204199602920424 4.02885141754513e-05 1.16222882744216e-05 3.05716489924019e-06 -7.41148783849401e-07 5.87636779817831e-06 -9.45677573584815e-06 1.16222882744216e-05 3.20696096308525e-05 -2.58282229782333e-06 -1.79951977039758e-06 5.28980621841388e-06 -7.95716036268058e-06 3.05716489924019e-06 -2.58282229782333e-06 1.56708416060618e-05 2.07409573076914e-06 4.59558468342282e-06 2.38753835451281e-06 -7.41148783849401e-07 -1.79951977039758e-06 2.07409573076914e-06 3.48292991266823e-05 -1.50890891534952e-05 -1.40879520156966e-06 5.87636779817831e-06 5.28980621841388e-06 4.59558468342282e-06 -1.50890891534952e-05 3.55442130324148e-05 -3.43503759645225e-06 -9.45677573584815e-06 -7.95716036268058e-06 2.38753835451281e-06 -1.40879520156966e-06 -3.43503759645225e-06 8.37309681558168e-05 1472 1464 0 0 32 1472 1464 0 0 26 0 0 0 0 0 0 0 0 881 0 4 1 0 0 3438 +711 712 0.999960700322197 -0.00625162460384552 -0.006286095843565 0.0936722236150262 0.0061725125633698 0.999902484290452 -0.0125268510982443 -0.0757708429644551 0.00636379602100303 0.0124875577914633 0.999901776676393 0.00090406285445322 2.02249920367989e-05 6.05960080030096e-06 3.84947551036423e-06 7.60801331873851e-07 -7.38533533908326e-07 -1.11630994546727e-05 6.05960080030096e-06 3.28402473848554e-05 -6.84723487351941e-06 -5.49087709382744e-06 4.30674558776776e-06 4.14360361155135e-06 3.84947551036423e-06 -6.84723487351941e-06 1.79941711968854e-05 2.72916870935278e-06 2.40740244675982e-06 -6.68604520477794e-07 7.60801331873851e-07 -5.49087709382744e-06 2.72916870935278e-06 4.59029701448194e-05 -2.69088001733062e-05 -4.18815733901028e-06 -7.38533533908326e-07 4.30674558776776e-06 2.40740244675982e-06 -2.69088001733062e-05 4.74379254138336e-05 6.7917390103037e-06 -1.11630994546727e-05 4.14360361155135e-06 -6.68604520477794e-07 -4.18815733901028e-06 6.7917390103037e-06 8.22347409293593e-05 1093 1073 0 0 59 1078 1073 0 0 40 0 0 0 0 0 0 0 0 822 0 46 26 0 0 3640 +716 717 0.998769562161724 -0.0453325145547907 0.0201078299032681 0.0948264535575915 0.0450010903188478 0.998848348182752 0.0166396875782736 -0.0984429440715304 -0.0208389915637484 -0.0157143392074672 0.999659339962309 -0.079860612071945 4.60443565893135e-05 1.37988935506145e-05 -4.70553519794718e-06 -2.70335206957198e-06 5.61009481299733e-06 4.31775515159974e-05 1.37988935506145e-05 4.61092713482791e-05 -4.12733502106655e-06 -7.75326087811552e-06 3.87694263489552e-06 1.46812801620891e-05 -4.70553519794718e-06 -4.12733502106655e-06 1.65357257329877e-05 5.18693754545157e-06 -7.96896242266469e-07 7.3096092418255e-06 -2.70335206957198e-06 -7.75326087811552e-06 5.18693754545157e-06 4.83049298490772e-05 -3.0963570250847e-05 7.69901593925336e-06 5.61009481299733e-06 3.87694263489552e-06 -7.96896242266469e-07 -3.0963570250847e-05 5.72227546937367e-05 -2.37680811048073e-05 4.31775515159974e-05 1.46812801620891e-05 7.3096092418255e-06 7.69901593925336e-06 -2.37680811048073e-05 0.000366426789713457 1730 1715 0 0 72 1730 1715 0 0 67 0 0 0 0 0 0 0 0 947 0 5 3 0 0 3346 +717 718 0.999835842297878 -0.007420519415789 -0.0165294993297813 0.133417370682203 0.00730175325590534 0.999947176117928 -0.00723390442090637 -0.141943076819666 0.0165823055056653 0.00711202259422954 0.999837209889058 -0.0215810858592197 4.66997028768213e-05 -1.76149207229003e-05 1.85472446103023e-06 1.41340606134045e-06 3.0802814673848e-06 -9.38602560865915e-06 -1.76149207229003e-05 7.85965275533609e-05 2.19629558300575e-07 -5.22791005459252e-06 5.15801550198597e-06 -3.65031021054541e-06 1.85472446103023e-06 2.19629558300575e-07 1.96219013237489e-05 -2.32655432425698e-06 3.77763273976008e-06 2.32137258302632e-06 1.41340606134045e-06 -5.22791005459252e-06 -2.32655432425698e-06 5.93507207346991e-05 -3.7110490562803e-05 -1.77546540843506e-06 3.0802814673848e-06 5.15801550198597e-06 3.77763273976008e-06 -3.7110490562803e-05 6.29983267582167e-05 -7.33041802294155e-06 -9.38602560865915e-06 -3.65031021054541e-06 2.32137258302632e-06 -1.77546540843506e-06 -7.33041802294155e-06 9.69396883800812e-05 1681 1660 0 0 58 1664 1657 0 0 35 0 0 0 0 0 0 0 0 1053 0 53 30 0 0 3340 +721 722 0.99980789339733 0.017089835181284 0.00959759521284548 0.132036790637073 -0.0169351582314493 0.999729000805407 -0.0159726442487581 -0.140233806617298 -0.00986796412989333 0.0158070390047649 0.999826365326416 0.0193172527496738 7.44799998790165e-05 1.60466778478646e-05 1.01105767942633e-06 -5.71945714963583e-06 -1.08630622989964e-07 -1.25307593440155e-05 1.60466778478646e-05 6.14782702261619e-05 -4.99864250293958e-07 1.07020456355787e-06 6.53141083927963e-06 -3.59712019525178e-05 1.01105767942633e-06 -4.99864250293958e-07 1.55900233204186e-05 -1.00088248477259e-06 1.95575293958283e-06 1.99589218677782e-06 -5.71945714963583e-06 1.07020456355787e-06 -1.00088248477259e-06 5.02382247473562e-05 -2.53068041312139e-05 1.13407609603036e-05 -1.08630622989964e-07 6.53141083927963e-06 1.95575293958283e-06 -2.53068041312139e-05 5.34728970419722e-05 -2.03033451881684e-05 -1.25307593440155e-05 -3.59712019525178e-05 1.99589218677782e-06 1.13407609603036e-05 -2.03033451881684e-05 9.14414137831943e-05 1527 1557 0 78 25 1507 1542 0 113 8 0 0 0 0 0 0 3 0 1864 0 57 40 0 0 3091 +719 720 0.999080633311138 -0.0125977012129322 0.0409778728921494 0.114766830199149 0.0135328454722909 0.999652449312624 -0.0226239403441415 -0.123268332632271 -0.0406786213635439 0.0231576878686509 0.998903884894107 0.0214616082260301 3.64996784321388e-05 -1.75986913400224e-05 -2.31084994431119e-06 2.36064407866124e-06 -1.69787537366937e-06 1.49960343150258e-05 -1.75986913400224e-05 3.73683686627986e-05 5.30505198857657e-07 4.6057208175639e-07 2.29905644271519e-06 -1.81876024713756e-05 -2.31084994431119e-06 5.30505198857657e-07 1.89606869755721e-05 -3.00718431739699e-06 1.09266895105871e-06 -1.48963153110652e-06 2.36064407866124e-06 4.6057208175639e-07 -3.00718431739699e-06 4.44440045301892e-05 -1.95192419585998e-05 -9.53242168906267e-06 -1.69787537366937e-06 2.29905644271519e-06 1.09266895105871e-06 -1.95192419585998e-05 4.83483345907132e-05 4.75641469385415e-06 1.49960343150258e-05 -1.81876024713756e-05 -1.48963153110652e-06 -9.53242168906267e-06 4.75641469385415e-06 9.25671447962041e-05 2265 2245 0 0 58 2256 2245 0 0 38 0 0 0 0 0 0 0 0 968 0 38 17 0 0 3499 +720 721 0.999544760180108 0.0201365896958031 0.0224675355104411 0.146030757238169 -0.0196363957387754 0.999559226025096 -0.0222657950790111 -0.154329843843199 -0.0229059895852648 0.0218144773839116 0.999499596907165 0.0142300317078175 4.57463621011919e-05 2.87501582944372e-06 1.89075720391594e-06 -3.65043506423259e-06 4.15891252648423e-06 -8.03796816726968e-06 2.87501582944372e-06 4.42611809952397e-05 -2.00653991756341e-06 1.12727112864665e-05 -2.50976624225142e-06 9.16656926680153e-06 1.89075720391594e-06 -2.00653991756341e-06 2.6266029484348e-05 -3.68036855435749e-06 -2.19674476007812e-08 1.40699552300986e-06 -3.65043506423259e-06 1.12727112864665e-05 -3.68036855435749e-06 7.66591261471585e-05 -4.75707649971975e-05 -1.07451061562493e-06 4.15891252648423e-06 -2.50976624225142e-06 -2.19674476007812e-08 -4.75707649971975e-05 8.12928577992655e-05 -2.38893846371614e-05 -8.03796816726968e-06 9.16656926680153e-06 1.40699552300986e-06 -1.07451061562493e-06 -2.38893846371614e-05 0.000251537019691034 2091 2129 0 98 21 2067 2112 0 160 1 0 0 0 0 0 0 0 0 1303 0 72 49 0 0 3052 +724 725 0.998752034045421 -0.00135391472644534 0.0499253583366955 0.0923470133899189 0.000909900511496303 0.99995984469266 0.00891521639055195 -0.116530739172078 -0.049935424011348 -0.00885866339493165 0.99871316077824 0.0272226086930175 4.8122474907023e-05 2.89720807735842e-05 -2.310922648663e-06 9.49063399933207e-07 1.77212372638269e-06 -2.41012183805566e-05 2.89720807735842e-05 4.53308368147696e-05 -1.08781673080477e-06 1.75075382605709e-06 5.42006068857311e-07 -3.41062413478899e-05 -2.310922648663e-06 -1.08781673080477e-06 1.31847819072252e-05 4.56875947422784e-06 1.69009169854954e-06 2.20894361606435e-06 9.49063399933207e-07 1.75075382605709e-06 4.56875947422784e-06 2.93009146290004e-05 -1.12287862278607e-05 8.34135920712119e-06 1.77212372638269e-06 5.42006068857311e-07 1.69009169854954e-06 -1.12287862278607e-05 2.95476270953232e-05 -7.11234297074899e-06 -2.41012183805566e-05 -3.41062413478899e-05 2.20894361606435e-06 8.34135920712119e-06 -7.11234297074899e-06 0.000142837728969844 2144 2135 0 0 37 2136 2132 0 0 24 0 0 0 0 0 0 0 0 2046 0 40 29 0 0 3242 +727 728 0.999805011293905 -0.0191818179847825 -0.00469012264165852 0.09775107147554 0.0192085401400081 0.99979913395904 0.00572046505488518 -0.129621063068258 0.00457945163582075 -0.00580944003782972 0.999972639140273 -0.0214258705086444 6.66173061906343e-05 -1.62950676252349e-05 -3.68051615449744e-06 -2.30715955222855e-06 1.21776139737668e-06 -1.06195287278687e-05 -1.62950676252349e-05 4.43658270268477e-05 2.35897367743212e-06 -2.16288727788865e-06 2.21631369321973e-06 -2.64865907422997e-05 -3.68051615449744e-06 2.35897367743212e-06 1.27342551384759e-05 8.66614474116321e-07 6.27753829708267e-07 -1.96496821071349e-06 -2.30715955222855e-06 -2.16288727788865e-06 8.66614474116321e-07 3.81779625220394e-05 -7.49854816430655e-06 1.70003769980593e-06 1.21776139737668e-06 2.21631369321973e-06 6.27753829708267e-07 -7.49854816430655e-06 4.56168575284735e-05 -6.56837107600211e-06 -1.06195287278687e-05 -2.64865907422997e-05 -1.96496821071349e-06 1.70003769980593e-06 -6.56837107600211e-06 0.000158529774730472 2590 2554 0 28 80 2579 2576 0 67 57 0 0 0 0 0 20 42 0 1184 0 59 15 0 0 3022 +729 730 0.999850955278473 0.0115330517240891 0.0128474101146546 0.0829932217000402 -0.0114664014467825 0.999920479160096 -0.00524947560290828 -0.0996910744408258 -0.0129069309514644 0.0051013796343528 0.999903688891705 0.0127704845858527 3.05059573300952e-05 -1.80821495385922e-07 1.07804172318042e-06 2.96827344271051e-07 1.64029526600222e-06 4.25656286811842e-06 -1.80821495385922e-07 3.5965585725182e-05 2.63961986039939e-06 3.05675297623756e-06 -1.97086166604922e-06 6.79352259565905e-06 1.07804172318042e-06 2.63961986039939e-06 1.3498314789121e-05 6.0707779045569e-08 -4.82811877402108e-06 3.06616041760744e-06 2.96827344271051e-07 3.05675297623756e-06 6.0707779045569e-08 6.87734019862031e-05 -5.4526362765515e-05 1.5390070603669e-05 1.64029526600222e-06 -1.97086166604922e-06 -4.82811877402108e-06 -5.4526362765515e-05 0.000101261392519534 -4.98622774710895e-05 4.25656286811842e-06 6.79352259565905e-06 3.06616041760744e-06 1.5390070603669e-05 -4.98622774710895e-05 0.000187595573455845 1425 1444 0 91 54 1391 1429 0 116 20 0 0 0 0 0 1 20 0 2232 0 81 54 0 0 3140 +730 731 0.998743815938716 0.014677877898707 0.0479098113601182 0.102396831756741 -0.0142803974949109 0.999860802400708 -0.00862821360419513 -0.121905592001435 -0.0480297862951607 0.00793320382965951 0.998814399128005 0.0288019019723999 2.83136430450694e-05 1.19853735969052e-05 -1.70877372440203e-06 2.66176314261715e-06 -2.48104980277434e-07 5.70304321631202e-06 1.19853735969052e-05 4.64870260418472e-05 -4.16641756606721e-06 -4.32537222270131e-06 4.00597215425532e-06 2.22744957257298e-05 -1.70877372440203e-06 -4.16641756606721e-06 1.1817774236719e-05 1.07673239407515e-06 -1.66186322278426e-06 -1.37368255977289e-06 2.66176314261715e-06 -4.32537222270131e-06 1.07673239407515e-06 4.99149015241035e-05 -2.97100453630158e-05 -1.56467883382265e-05 -2.48104980277434e-07 4.00597215425532e-06 -1.66186322278426e-06 -2.97100453630158e-05 5.80409893704373e-05 1.24769205026055e-05 5.70304321631202e-06 2.22744957257298e-05 -1.37368255977289e-06 -1.56467883382265e-05 1.24769205026055e-05 0.000194788571204714 1172 1165 0 0 30 1154 1152 0 0 14 0 0 0 0 0 0 0 0 2138 0 60 46 0 0 3457 +728 729 0.999949816801064 0.00337331235081083 -0.00943316719356782 0.101950999881906 -0.00320480644188587 0.999836047322771 0.0178215512694157 -0.133725830954401 0.00949173825955942 -0.0177904254519737 0.999796683164657 0.00574271409636537 5.65289625907987e-05 -2.30234043670238e-06 2.71841492075713e-06 -1.37247198949395e-05 5.43220940548509e-06 -4.73140664414531e-06 -2.30234043670238e-06 6.76222818724114e-05 7.27180031403496e-07 -5.33964508855597e-06 1.79218873625646e-05 -9.54281883016538e-06 2.71841492075713e-06 7.27180031403496e-07 1.58372797942325e-05 -8.24451838371538e-06 -3.79701562435816e-06 -3.52170660254574e-07 -1.37247198949395e-05 -5.33964508855597e-06 -8.24451838371538e-06 5.20147414784134e-05 -1.35675929435366e-05 -8.95120744235356e-06 5.43220940548509e-06 1.79218873625646e-05 -3.79701562435816e-06 -1.35675929435366e-05 5.325559969105e-05 6.6159312694068e-06 -4.73140664414531e-06 -9.54281883016538e-06 -3.52170660254574e-07 -8.95120744235356e-06 6.6159312694068e-06 0.000102218843255882 1976 1964 0 45 71 1932 1957 0 84 19 0 0 0 0 0 1 15 0 1605 0 82 45 0 0 2754 +726 727 0.999628433264515 -0.0211395600286072 0.0172079752129288 0.100637475184354 0.0212441685321781 0.999756795068618 -0.00591912303493898 -0.122236872624622 -0.0170786624917841 0.00628249281123695 0.999834411075938 0.0188529447315194 6.22359262550706e-05 -3.68869115328728e-05 7.89246951302709e-07 3.51624204707245e-06 2.71842259002148e-07 3.42186309409481e-05 -3.68869115328728e-05 6.94850367903424e-05 -2.29552040248059e-06 -2.80932004558509e-06 1.53942602991903e-06 -5.08678118502179e-05 7.89246951302709e-07 -2.29552040248059e-06 1.33188481424701e-05 2.62097214069713e-06 2.78762874654728e-06 3.05099726644198e-06 3.51624204707245e-06 -2.80932004558509e-06 2.62097214069713e-06 2.99714877932028e-05 -9.11693414227447e-06 2.68236711033109e-06 2.71842259002148e-07 1.53942602991903e-06 2.78762874654728e-06 -9.11693414227447e-06 3.41700334905758e-05 -4.54659982455489e-06 3.42186309409481e-05 -5.08678118502179e-05 3.05099726644198e-06 2.68236711033109e-06 -4.54659982455489e-06 0.000131370892776575 2207 2189 0 0 70 2199 2188 0 0 49 0 0 0 0 0 0 0 0 1293 0 27 11 0 0 3295 +732 733 0.997792477942145 0.0664060444694474 0.000638920961677888 0.101175711570519 -0.0663811056187374 0.997604847141015 -0.0194452507719771 -0.11457246614572 -0.00192867283579333 0.0193599126721383 0.999810719087578 0.0773092993757803 3.27995228021593e-05 1.62653667114006e-05 4.10600800724535e-07 5.00576085072333e-06 -5.50579522133233e-06 8.76772853465662e-06 1.62653667114006e-05 3.13876446441129e-05 -1.65121068411907e-07 -2.90557382701865e-06 4.33667432130496e-06 -3.15366177866583e-06 4.10600800724535e-07 -1.65121068411907e-07 1.07282628985727e-05 2.72417893193209e-06 1.70043568208296e-06 -3.25808435018634e-06 5.00576085072333e-06 -2.90557382701865e-06 2.72417893193209e-06 4.35584956264936e-05 -2.29466208524671e-05 -5.8073169164741e-06 -5.50579522133233e-06 4.33667432130496e-06 1.70043568208296e-06 -2.29466208524671e-05 3.63325726199962e-05 4.66939009515456e-06 8.76772853465662e-06 -3.15366177866583e-06 -3.25808435018634e-06 -5.8073169164741e-06 4.66939009515456e-06 0.000159011741749981 1329 1329 0 0 0 1310 1310 0 0 0 0 0 0 0 0 0 0 0 1615 0 72 72 0 0 3671 +722 723 0.999701001387622 -0.00455336957931025 -0.0240244594124261 0.121009905797559 0.00385384128461708 0.999569549999102 -0.0290837174712323 -0.121758214662106 0.0241465469982372 0.0289824350265414 0.999288228054346 0.0294817968994572 3.94205350223215e-05 1.66852449560932e-05 -4.09184387037061e-06 8.40457666864072e-06 -3.55117816539906e-06 -1.87020059839086e-05 1.66852449560932e-05 5.20930403260653e-05 -1.92663497497298e-06 2.40361589496625e-06 -4.38578567058279e-06 -1.79378583470164e-05 -4.09184387037061e-06 -1.92663497497298e-06 1.55255378538558e-05 3.02217585149544e-06 -5.201319477288e-06 -1.88551673420469e-06 8.40457666864072e-06 2.40361589496625e-06 3.02217585149544e-06 6.23114835274679e-05 -4.45111671500352e-05 -2.70468188162052e-05 -3.55117816539906e-06 -4.38578567058279e-06 -5.201319477288e-06 -4.45111671500352e-05 7.22670267201653e-05 2.78683577222671e-05 -1.87020059839086e-05 -1.79378583470164e-05 -1.88551673420469e-06 -2.70468188162052e-05 2.78683577222671e-05 0.000117674356352479 1309 1294 0 0 41 1297 1292 0 8 25 0 0 0 0 0 0 0 0 2342 0 35 17 0 0 3300 +725 726 0.999351174694679 -0.0121745754259282 0.0338970404248606 0.0909774259166858 0.0122332916224207 0.99992400708765 -0.00152532811465779 -0.1141203267461 -0.0338758942678575 0.00193901082383238 0.999424166220018 0.0734521648851054 3.24742458029041e-05 1.69565086079372e-05 5.9300026619562e-07 -2.48066028905629e-06 2.80790202864009e-06 3.64016823161704e-06 1.69565086079372e-05 3.30052088720384e-05 1.45545744454558e-07 2.71727573844327e-06 2.58052802521219e-07 -5.09045894476402e-06 5.9300026619562e-07 1.45545744454558e-07 1.31123959751127e-05 1.92262668593724e-06 -1.04050727660535e-06 -7.81769968505616e-08 -2.48066028905629e-06 2.71727573844327e-06 1.92262668593724e-06 3.1339970554285e-05 -1.38832276981185e-05 -1.01699797162817e-05 2.80790202864009e-06 2.58052802521219e-07 -1.04050727660535e-06 -1.38832276981185e-05 3.86736194348647e-05 1.19480505691539e-06 3.64016823161704e-06 -5.09045894476402e-06 -7.81769968505616e-08 -1.01699797162817e-05 1.19480505691539e-06 0.000130127328189762 1949 1933 0 0 41 1938 1933 0 0 23 0 0 0 0 0 0 0 0 1563 0 19 3 0 0 3359 +723 724 0.999940714020253 0.00828018773166567 -0.00707155822967939 0.106346052392633 -0.00831690437581233 0.999952004296012 -0.00517862974074114 -0.122157114591529 0.00702833879881774 0.00523713619418745 0.999961586691315 0.0752354215400323 6.95843054953062e-05 4.49190705869413e-05 -5.81324890738497e-06 6.56164027516722e-06 9.9394940685131e-06 4.01126716621001e-05 4.49190705869413e-05 7.66031862620406e-05 -7.08466487357391e-06 1.74610612880433e-06 1.18429380403931e-05 2.53993722352647e-05 -5.81324890738497e-06 -7.08466487357391e-06 1.42608477859101e-05 -1.53427462357101e-06 -6.14800451601664e-08 -6.38943252505392e-06 6.56164027516722e-06 1.74610612880433e-06 -1.53427462357101e-06 4.27375808515285e-05 -2.37575599768203e-05 7.85261874415127e-06 9.9394940685131e-06 1.18429380403931e-05 -6.14800451601664e-08 -2.37575599768203e-05 4.24185387562763e-05 2.7374141379247e-05 4.01126716621001e-05 2.53993722352647e-05 -6.38943252505392e-06 7.85261874415127e-06 2.7374141379247e-05 0.00065915165298567 1720 1713 0 0 41 1703 1703 0 0 23 0 0 0 0 0 0 0 0 1888 0 58 45 0 0 3183 +733 734 0.998944919198315 0.0459242959063917 -8.63329211257449e-05 0.111994315138093 -0.0459227272231299 0.998923201710258 0.00659850053556331 -0.118827222105577 0.000389271449117622 -0.0065875739411411 0.999978225931599 0.00438220800633949 2.71478982361481e-05 1.13163738898878e-05 -1.7489994466873e-06 -4.46018533513361e-06 2.09250073117387e-06 2.67960256118838e-05 1.13163738898878e-05 2.68924207901942e-05 -2.64348280532787e-06 7.23471839615674e-06 -6.26781397591145e-06 5.34011070893684e-06 -1.7489994466873e-06 -2.64348280532787e-06 1.48846549519265e-05 5.67662661801326e-06 -4.81990803951003e-06 8.14463415791114e-06 -4.46018533513361e-06 7.23471839615674e-06 5.67662661801326e-06 7.47133848640797e-05 -4.44950387720312e-05 -6.97605378125984e-06 2.09250073117387e-06 -6.26781397591145e-06 -4.81990803951003e-06 -4.44950387720312e-05 6.51504678845364e-05 -1.20466016615691e-05 2.67960256118838e-05 5.34011070893684e-06 8.14463415791114e-06 -6.97605378125984e-06 -1.20466016615691e-05 0.000295872403032981 1449 1449 0 0 16 1392 1392 0 0 0 0 0 0 0 0 0 0 0 1113 0 198 133 0 0 3821 +734 735 0.997385321168979 0.0718005540488111 -0.00819765545360811 0.0813292769918679 -0.0718153601734526 0.997416776292664 -0.0015259138595531 -0.0890072011147194 0.00806691761514911 0.0021106416638653 0.999965234411656 -0.000323770543915257 2.48065587848113e-05 1.58822336683405e-05 -3.2002338309697e-06 -1.72892263326153e-06 4.10882781512915e-06 5.93828331608659e-07 1.58822336683405e-05 2.39605336828399e-05 -9.77985396025911e-07 5.04903619509897e-06 -1.00680837186361e-06 -1.33362062864844e-05 -3.2002338309697e-06 -9.77985396025911e-07 1.10511131609961e-05 8.24730868078595e-07 -2.96574793928413e-07 2.91364116935417e-06 -1.72892263326153e-06 5.04903619509897e-06 8.24730868078595e-07 4.07490752032975e-05 -2.49094616175869e-06 -2.14015301053897e-05 4.10882781512915e-06 -1.00680837186361e-06 -2.96574793928413e-07 -2.49094616175869e-06 2.74473727501438e-05 2.60094989073022e-06 5.93828331608659e-07 -1.33362062864844e-05 2.91364116935417e-06 -2.14015301053897e-05 2.60094989073022e-06 0.000114744682296175 1484 1484 0 0 0 1469 1469 0 0 0 0 0 0 0 0 0 0 0 806 0 135 87 0 0 3759 +731 732 0.9991625935317 0.0403094758980766 -0.00701839296631674 0.0989635503285404 -0.0403464299905903 0.999172190005749 -0.00520579543686711 -0.107461972367124 0.00680274018478293 0.00548460317055758 0.999961820198171 0.0206974895338543 1.99421037354333e-05 1.42192853729363e-05 -1.55668336607595e-06 4.20188417072315e-07 -5.56908370434723e-07 -2.19116728961392e-05 1.42192853729363e-05 3.08577779808189e-05 -7.87048897612906e-07 -9.46097494766019e-07 -1.94162182896589e-06 7.33993544578047e-06 -1.55668336607595e-06 -7.87048897612906e-07 1.37032555740231e-05 5.61869005077288e-07 2.37718863090609e-06 -8.45307093548169e-07 4.20188417072315e-07 -9.46097494766019e-07 5.61869005077288e-07 3.30815178536158e-05 -5.03156183376862e-06 -1.3829436253038e-05 -5.56908370434723e-07 -1.94162182896589e-06 2.37718863090609e-06 -5.03156183376862e-06 3.58659117812088e-05 5.29640803750949e-06 -2.19116728961392e-05 7.33993544578047e-06 -8.45307093548169e-07 -1.3829436253038e-05 5.29640803750949e-06 0.00014727531283189 1270 1270 0 0 15 1249 1249 0 0 1 0 0 0 0 0 0 0 0 2175 0 110 73 0 0 3552 +737 738 0.998012644584612 0.0595985286835535 0.0204640325445705 0.104332437050874 -0.0593107908745986 0.998135820559773 -0.0143914488950015 -0.0904801267799216 -0.0212835930956034 0.0131491100164027 0.999687005802675 0.0583760606003039 2.76892849306587e-05 1.50536645673698e-05 -6.52728519694973e-07 -3.48290447827601e-06 9.45545651876357e-07 2.38259738518943e-06 1.50536645673698e-05 2.03237806624748e-05 -5.80084031817428e-07 2.47577992436126e-06 -8.97245451680917e-07 -3.82865376447242e-06 -6.52728519694973e-07 -5.80084031817428e-07 1.14583161055832e-05 9.79044421984297e-08 3.17593218993091e-06 2.04575433539955e-06 -3.48290447827601e-06 2.47577992436126e-06 9.79044421984297e-08 0.000107223652214042 -2.49135418199376e-05 4.49592416480575e-06 9.45545651876357e-07 -8.97245451680917e-07 3.17593218993091e-06 -2.49135418199376e-05 2.51133737345448e-05 -6.3486240445141e-06 2.38259738518943e-06 -3.82865376447242e-06 2.04575433539955e-06 4.49592416480575e-06 -6.3486240445141e-06 0.000211335800366247 2430 2430 0 0 0 2377 2377 0 0 0 0 0 0 0 0 0 0 0 759 0 218 189 0 0 3785 +741 742 0.998903467241579 0.0423266243574222 0.0200079984820218 0.0837324318415217 -0.0420122794409624 0.998990908256545 -0.0158787152168558 -0.0454292283368667 -0.0206599009902129 0.0150207220621778 0.999673719970574 0.0383419319035868 9.39765033463822e-05 9.98607063789634e-05 -4.31275110952606e-06 4.34410856408754e-06 -2.32965199617173e-06 -0.000138900338741179 9.98607063789634e-05 0.000270575893473137 -1.19776866980275e-05 8.45382088451187e-05 -2.03095583773132e-05 -0.000349404596694559 -4.31275110952606e-06 -1.19776866980275e-05 1.2703140460558e-05 -4.66972758731017e-06 4.75581459610039e-06 1.53660381193745e-05 4.34410856408754e-06 8.45382088451187e-05 -4.66972758731017e-06 0.000359410584548433 -3.96714915581885e-05 4.23695616264799e-05 -2.32965199617173e-06 -2.03095583773132e-05 4.75581459610039e-06 -3.96714915581885e-05 1.95285127639795e-05 1.81032638746743e-05 -0.000138900338741179 -0.000349404596694559 1.53660381193745e-05 4.23695616264799e-05 1.81032638746743e-05 0.000987980827584777 3207 3078 0 226 0 3199 3070 0 141 0 0 0 0 0 0 0 0 0 943 0 101 103 0 0 3809 +743 744 0.997748681093842 0.0670088214913047 0.00271794367950652 0.0267479445288969 -0.0670576466217804 0.997390016459355 0.0267661558083412 -0.028414392058061 -0.000917281334669028 -0.0268881555625229 0.999638027330593 0.0280653397356468 2.47218942023369e-05 6.14850903000594e-06 -7.36454888033925e-06 1.31906759727968e-05 7.37199629499368e-07 -3.43935169599497e-06 6.14850903000594e-06 1.27201514244006e-05 -2.09662772618633e-06 1.62326074656242e-06 2.70325431225279e-08 -8.0863754599978e-06 -7.36454888033925e-06 -2.09662772618633e-06 1.21800632748477e-05 1.86109296613993e-06 2.80573473503958e-06 3.90746151369523e-06 1.31906759727968e-05 1.62326074656242e-06 1.86109296613993e-06 0.000945784949251253 -1.53319125103919e-05 0.000134040470347025 7.37199629499368e-07 2.70325431225279e-08 2.80573473503958e-06 -1.53319125103919e-05 1.23860911412303e-05 -3.12291474564799e-06 -3.43935169599497e-06 -8.0863754599978e-06 3.90746151369523e-06 0.000134040470347025 -3.12291474564799e-06 7.16316878558102e-05 3521 3424 0 200 0 3531 3434 0 81 0 0 0 0 0 0 0 0 0 1783 0 168 185 0 0 3750 +740 741 0.998354751853216 0.0573116882652824 0.0017775939598465 0.111769903138879 -0.0572234153224186 0.997828586266612 -0.0326127761469716 -0.0614409494225964 -0.00364282732791037 0.0324574000400154 0.999466481174682 0.017574667928459 8.31128444287141e-05 9.22482500299309e-05 -5.31597963564946e-06 8.75010622734882e-06 4.21251972979671e-07 -3.26491351163497e-05 9.22482500299309e-05 0.000219728497744733 -1.01807975190704e-05 1.3166338839175e-05 3.11889918502508e-06 -6.13229940848771e-05 -5.31597963564946e-06 -1.01807975190704e-05 1.26212500815376e-05 3.35965237225859e-06 4.00022118744003e-06 -3.70603249925336e-06 8.75010622734882e-06 1.3166338839175e-05 3.35965237225859e-06 4.41382962904029e-05 3.79207104618812e-06 -9.35341327563506e-06 4.21251972979671e-07 3.11889918502508e-06 4.00022118744003e-06 3.79207104618812e-06 1.27636357995545e-05 1.56490027743886e-05 -3.26491351163497e-05 -6.13229940848771e-05 -3.70603249925336e-06 -9.35341327563506e-06 1.56490027743886e-05 0.000449473478224057 3103 2953 0 80 0 3089 2939 0 80 0 0 0 0 0 0 0 0 0 805 0 152 147 0 0 3803 +735 736 0.996151621397617 0.0867120466316899 -0.0127658981604395 0.076814944742454 -0.0866732412431177 0.996230421150762 0.00356331673985603 -0.0867985811378587 0.0130267585880522 -0.00244314197701601 0.999912163451355 -0.0225168272367457 6.10786285341759e-05 4.24295946117863e-05 1.42710408125184e-06 1.42415240220603e-06 -1.45260742455031e-06 6.71798677748638e-06 4.24295946117863e-05 5.83506115667645e-05 1.85224980442051e-06 1.08763099171418e-05 -3.99920963134558e-06 -2.43927072855928e-05 1.42710408125184e-06 1.85224980442051e-06 1.30648673831586e-05 -2.63135198700375e-06 2.21116245494359e-07 1.86824141408397e-06 1.42415240220603e-06 1.08763099171418e-05 -2.63135198700375e-06 4.68844731571565e-05 -2.83339348005568e-06 -3.05894975714153e-06 -1.45260742455031e-06 -3.99920963134558e-06 2.21116245494359e-07 -2.83339348005568e-06 2.27656311218371e-05 -6.8870653197405e-06 6.71798677748638e-06 -2.43927072855928e-05 1.86824141408397e-06 -3.05894975714153e-06 -6.8870653197405e-06 0.000314058810519598 1717 1717 0 0 0 1669 1669 0 0 0 0 0 0 0 0 0 0 0 474 0 279 235 0 0 3760 +745 746 0.999319756373909 0.0332510131324652 -0.0159497538055082 0.122626231518283 -0.0334986585183513 0.999318265673872 -0.0155191419877475 -0.012320244957296 0.0154228531168065 0.0160428805465104 0.999752350127524 0.0482662494545992 3.44197530655851e-05 -2.44412806657129e-06 -9.07847366958567e-06 -1.12522137834663e-05 2.61177666339882e-06 -3.83875860235227e-06 -2.44412806657129e-06 2.34378895857634e-05 5.9103929573242e-07 1.04449694171811e-05 1.21516085420606e-06 -1.91859225474268e-05 -9.07847366958567e-06 5.9103929573242e-07 1.19852800029399e-05 -9.1143832886076e-07 2.79728256560762e-06 2.32081900582463e-06 -1.12522137834663e-05 1.04449694171811e-05 -9.1143832886076e-07 0.000285737818566177 9.85588505309498e-06 5.51348482471384e-05 2.61177666339882e-06 1.21516085420606e-06 2.79728256560762e-06 9.85588505309498e-06 1.20221166530862e-05 1.97726930044419e-06 -3.83875860235227e-06 -1.91859225474268e-05 2.32081900582463e-06 5.51348482471384e-05 1.97726930044419e-06 8.93268105367972e-05 3283 3232 0 254 9 3283 3234 0 155 33 0 0 0 0 0 0 0 0 2959 0 0 0 0 0 3831 +736 737 0.996631120052582 0.0720139238328265 0.039247997616893 0.113305117187917 -0.0720648114842276 0.997399944310131 -0.000118473165346808 -0.10358865697354 -0.0391544823548788 -0.00271032550591905 0.999229493483441 0.00994312838931271 0.000112474839845758 0.000103062563681957 -6.52934164317915e-06 3.17186466772561e-06 1.12406593610609e-05 -9.97923208656383e-05 0.000103062563681957 0.000133847512062821 -7.98909251441395e-06 1.71557782356806e-05 7.81336013447578e-06 -9.23031039332028e-05 -6.52934164317915e-06 -7.98909251441395e-06 1.28371992372954e-05 -6.13935243439038e-07 2.33302695572683e-06 1.01613163325609e-05 3.17186466772561e-06 1.71557782356806e-05 -6.13935243439038e-07 5.14907202287967e-05 -3.90012925866268e-06 -3.54636185751671e-05 1.12406593610609e-05 7.81336013447578e-06 2.33302695572683e-06 -3.90012925866268e-06 2.16363163492293e-05 -7.7688491989795e-06 -9.97923208656383e-05 -9.23031039332028e-05 1.01613163325609e-05 -3.54636185751671e-05 -7.7688491989795e-06 0.000329929208768246 2013 2013 0 0 0 1968 1968 0 0 0 0 0 0 0 0 0 0 0 665 0 246 210 0 0 3812 +738 739 0.998170092093929 0.0594488535350822 -0.0110589810815536 0.107279357942052 -0.0596329666392597 0.998073234461825 -0.0171384929533279 -0.0815900536581095 0.0100188092605239 0.0177666109394749 0.999791963858845 0.0228410772838179 0.000138054967433043 0.000210767406486896 4.70952502907316e-07 -1.33527240322572e-05 6.00518736622885e-06 -0.000188012589452488 0.000210767406486896 0.000504020092452756 1.23528196293198e-05 -5.99737942344968e-05 8.41209563633846e-06 -0.00046284851850362 4.70952502907316e-07 1.23528196293198e-05 1.1590206839598e-05 1.59024777055398e-06 2.93071574266565e-06 -1.15253350468354e-05 -1.33527240322572e-05 -5.99737942344968e-05 1.59024777055398e-06 6.70384778530347e-05 -7.11149684395919e-06 6.5908193584728e-05 6.00518736622885e-06 8.41209563633846e-06 2.93071574266565e-06 -7.11149684395919e-06 1.75660400838949e-05 -7.27881339886258e-06 -0.000188012589452488 -0.00046284851850362 -1.15253350468354e-05 6.5908193584728e-05 -7.27881339886258e-06 0.000723148124376115 2642 2642 0 0 0 2609 2609 0 0 0 0 0 0 0 0 0 0 0 725 0 204 180 0 0 3778 +746 747 0.99953282198372 0.0302314066791738 -0.00449442181600372 0.0105149959111821 -0.0301926127378637 0.999508275771206 0.00846243469297468 -0.0143069687141513 0.00474804310460163 -0.0083227828921507 0.99995409263206 0.0239248332013966 2.79055952660064e-05 -4.04923876800853e-06 -6.71868376196942e-06 4.68254882699627e-06 6.12762032804513e-07 -7.15575184413786e-06 -4.04923876800853e-06 3.77804784048011e-05 -1.10084668336861e-06 -1.95340409856868e-05 3.45525048274399e-07 1.43686908891345e-05 -6.71868376196942e-06 -1.10084668336861e-06 1.23734041727228e-05 4.54148655007293e-07 3.21686765525532e-06 -3.62378191690212e-06 4.68254882699627e-06 -1.95340409856868e-05 4.54148655007293e-07 0.000495552268358653 3.05920062199438e-05 -0.000189596897866011 6.12762032804513e-07 3.45525048274399e-07 3.21686765525532e-06 3.05920062199438e-05 1.36110271424961e-05 -4.44469470916963e-06 -7.15575184413786e-06 1.43686908891345e-05 -3.62378191690212e-06 -0.000189596897866011 -4.44469470916963e-06 0.000394111047251193 3445 3378 0 60 0 3470 3403 0 0 0 0 0 0 0 0 0 0 0 3667 0 44 77 0 0 3835 +739 740 0.997346837924004 0.0653010909514331 0.0321722303165969 0.146542651300931 -0.0651704939386518 0.997861149472076 -0.00509245462019798 -0.0880260210819022 -0.0324359615671194 0.00298226337188524 0.999469366465224 0.037691684923233 7.15344807935621e-05 3.37850104051261e-05 -7.15962222875332e-06 4.31273488487175e-05 6.75723187964379e-06 6.09045019469545e-05 3.37850104051261e-05 8.56512261256682e-05 -2.89940064143561e-06 1.75806927644309e-05 2.52317519577427e-07 -5.70996904697321e-06 -7.15962222875332e-06 -2.89940064143561e-06 1.27180034194611e-05 -3.76198043783398e-06 -3.76486306549514e-07 -8.20302235188312e-06 4.31273488487175e-05 1.75806927644309e-05 -3.76198043783398e-06 0.000311673820503853 -5.67576741032224e-05 0.000521033741558893 6.75723187964379e-06 2.52317519577427e-07 -3.76486306549514e-07 -5.67576741032224e-05 3.30871004449639e-05 -0.00011965690021093 6.09045019469545e-05 -5.70996904697321e-06 -8.20302235188312e-06 0.000521033741558893 -0.00011965690021093 0.00154841598642712 3003 2994 0 0 0 2985 2976 0 0 0 0 0 0 0 0 0 0 0 831 0 179 166 0 0 3789 +748 749 0.999378122073559 -0.0262915746587721 0.023497281176527 0.118886491896786 0.0260251037208403 0.999594270875789 0.0115753016642792 0.0121283490264385 -0.0237920805531181 -0.0109565840599054 0.999656886220813 0.0446473646000854 4.31151855310312e-05 -3.25693483513317e-05 -2.77252266247944e-06 -2.47089939853472e-06 3.58038789741984e-07 3.90971488433586e-05 -3.25693483513317e-05 0.0003247888062411 -6.07708372042833e-06 3.52672836930007e-05 -3.88036689562756e-06 -0.000399605089850827 -2.77252266247944e-06 -6.07708372042833e-06 1.26830133023505e-05 -9.27421727837851e-07 4.10858699866934e-06 1.00986065313746e-05 -2.47089939853472e-06 3.52672836930007e-05 -9.27421727837851e-07 0.000331062939812228 1.3286722490524e-05 -6.39276525692525e-05 3.58038789741984e-07 -3.88036689562756e-06 4.10858699866934e-06 1.3286722490524e-05 1.18592044349731e-05 5.87316346424931e-06 3.90971488433586e-05 -0.000399605089850827 1.00986065313746e-05 -6.39276525692525e-05 5.87316346424931e-06 0.000800083287364286 3234 3195 0 48 177 3234 3195 0 0 213 0 0 0 0 0 0 0 0 3700 0 0 0 0 0 3647 +752 753 0.999345910042081 -0.0358056623056279 -0.0050701705118771 0.134775801075853 0.0357313323200904 0.999262499455764 -0.0140616169785436 0.0194987843039247 0.00556991676737003 0.0138712554686064 0.999888275908328 -0.0373651157066618 3.66939874229155e-05 1.31233555907769e-05 -4.93155239703093e-06 4.19474310926221e-07 -7.25875787843623e-07 -2.64210958567092e-05 1.31233555907769e-05 0.000260664433392674 3.43264250733757e-06 -6.30021964764299e-05 7.25548840204948e-06 -0.000180050100158406 -4.93155239703093e-06 3.43264250733757e-06 1.20864204009495e-05 1.07997829034385e-06 4.2932322250237e-06 -2.82182960279436e-06 4.19474310926221e-07 -6.30021964764299e-05 1.07997829034385e-06 0.000366426766140564 -2.232963729164e-05 3.83633455654395e-05 -7.25875787843623e-07 7.25548840204948e-06 4.2932322250237e-06 -2.232963729164e-05 1.23527980668872e-05 -1.011047932531e-05 -2.64210958567092e-05 -0.000180050100158406 -2.82182960279436e-06 3.83633455654395e-05 -1.011047932531e-05 0.000470543837193428 3223 3132 0 49 225 3223 3132 0 0 248 0 0 0 0 0 0 0 0 1998 0 0 0 0 0 3615 +742 743 0.998441086696329 0.0524542954130936 0.019077297748069 0.0997291363621299 -0.0526106839792039 0.998584714929454 0.00778993199595927 -0.0401575455850339 -0.0186416825392159 -0.00878145785033692 0.999787664291839 0.049585075459321 2.91933358880205e-05 1.0683730591684e-05 -2.03121479827058e-06 8.21530238072303e-06 4.88827666554641e-07 -8.64748663207802e-06 1.0683730591684e-05 1.95521198007384e-05 8.8300239574589e-07 2.08729462383108e-05 -7.90366857386414e-07 5.53070864207085e-06 -2.03121479827058e-06 8.8300239574589e-07 1.10002279886726e-05 -3.43307232493819e-07 3.25074624478488e-06 -4.54692244821552e-06 8.21530238072303e-06 2.08729462383108e-05 -3.43307232493819e-07 0.000188989053520813 -1.02947102518763e-05 6.57638095518966e-05 4.88827666554641e-07 -7.90366857386414e-07 3.25074624478488e-06 -1.02947102518763e-05 1.27325898148528e-05 -8.95093435254689e-07 -8.64748663207802e-06 5.53070864207085e-06 -4.54692244821552e-06 6.57638095518966e-05 -8.95093435254689e-07 0.000179050145772141 3520 3405 0 319 0 3525 3410 0 197 0 0 0 0 0 0 0 0 0 1234 0 100 109 0 0 3817 +744 745 0.998401396188891 0.0472818987213682 -0.030968922186203 0.183857197976938 -0.048204066415235 0.998394665474417 -0.0297398711036605 -0.0238904569696177 0.0295130491326876 0.0311851568142443 0.999077807743402 -0.0540015604360993 4.36915422253077e-05 3.39311993818498e-06 -7.06087718816122e-06 2.08751232949464e-05 1.57905321544456e-06 -1.39963561936817e-05 3.39311993818498e-06 2.73739079495571e-05 3.49878379288293e-06 -1.42643672278898e-05 -3.71265063077831e-07 -9.23271934179223e-09 -7.06087718816122e-06 3.49878379288293e-06 1.16257771303089e-05 -3.12535646062095e-06 3.98621450648241e-06 -9.0480026355636e-07 2.08751232949464e-05 -1.42643672278898e-05 -3.12535646062095e-06 0.000319706253847938 3.74550728353827e-06 -9.85104619823073e-05 1.57905321544456e-06 -3.71265063077831e-07 3.98621450648241e-06 3.74550728353827e-06 1.19719369727676e-05 4.17960141930665e-06 -1.39963561936817e-05 -9.23271934179223e-09 -9.0480026355636e-07 -9.85104619823073e-05 4.17960141930665e-06 0.000278212938737691 3502 3437 0 453 24 3502 3440 0 333 42 0 0 0 0 0 0 0 0 2049 0 0 0 0 0 3828 +753 754 0.999800824584155 0.00588406938892332 0.0190706289426935 0.124740920006089 -0.00548449051453832 0.999765741573446 -0.0209375819972699 0.00702643509722266 -0.0191893596724722 0.0208288190621264 0.999598883938872 0.0231400386586955 3.72138234115216e-05 1.36888610322572e-05 -1.08613797905877e-06 -1.58095535148207e-05 1.43506747753715e-06 -2.29464171211357e-05 1.36888610322572e-05 3.01382952330547e-05 -2.26884394107328e-06 2.7857349802317e-06 4.4899763299285e-07 -1.22013998109552e-05 -1.08613797905877e-06 -2.26884394107328e-06 1.1570114512957e-05 -1.20574955728852e-06 4.02200615586276e-06 -1.22415587955866e-06 -1.58095535148207e-05 2.7857349802317e-06 -1.20574955728852e-06 0.000256731713424269 -9.50591506536354e-06 2.66919462219589e-05 1.43506747753715e-06 4.4899763299285e-07 4.02200615586276e-06 -9.50591506536354e-06 1.1046703394345e-05 -4.78974392029206e-06 -2.29464171211357e-05 -1.22013998109552e-05 -1.22415587955866e-06 2.66919462219589e-05 -4.78974392029206e-06 0.000319225469353855 3224 3136 0 169 111 3224 3136 0 40 122 0 0 0 0 0 0 0 0 1491 0 0 0 0 0 3724 +749 750 -0.989100549603148 -0.0987679523755736 -0.109201622507571 -0.365037688535381 -0.0949927967319317 0.994703433978277 -0.0392612659101739 -0.0145813591009423 0.112500983745901 -0.0284599721602095 -0.993243957263695 0.157701169719743 0.000111199481720442 -0.000586762712980533 -1.23912117718142e-06 6.25134914002315e-05 1.69873990415694e-06 6.92220702171209e-05 -0.000586762712980533 0.00610559672768212 -6.68817426748298e-05 -0.000492389564347737 -2.8375440347367e-05 -0.00121284623884159 -1.23912117718142e-06 -6.68817426748298e-05 1.41423047465393e-05 3.01284281766705e-05 -3.79285937060459e-07 3.44964201624698e-06 6.25134914002315e-05 -0.000492389564347737 3.01284281766705e-05 0.00551136747886834 0.000157150045274703 -0.00173416900848576 1.69873990415694e-06 -2.8375440347367e-05 -3.79285937060459e-07 0.000157150045274703 1.56446263437401e-05 -4.40318847623985e-05 6.92220702171209e-05 -0.00121284623884159 3.44964201624698e-06 -0.00173416900848576 -4.40318847623985e-05 0.00231225939539018 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2551 0 0 0 0 0 3609 +750 751 0.99942545810648 -0.0231970189586705 -0.0247113739011625 0.0710209496077432 0.0234188376802166 0.999687666697036 0.00872508427147436 0.0155748254132236 0.0245012597708698 -0.00929878299928238 0.999656551473741 -0.0470438340930936 4.50022175807921e-05 1.96056615311279e-06 -6.13237362370623e-06 -2.17722742697164e-06 -6.40782199065863e-07 -6.41135110301274e-06 1.96056615311279e-06 2.74670371936812e-05 -9.18310932553815e-07 -5.45756811011598e-06 2.32655279307914e-07 -1.96250075442222e-05 -6.13237362370623e-06 -9.18310932553815e-07 1.51807887362027e-05 -8.51011751151657e-06 1.98617168381795e-06 3.66785446603441e-06 -2.17722742697164e-06 -5.45756811011598e-06 -8.51011751151657e-06 0.000248002801991826 5.14561146387043e-06 -3.77001276527818e-05 -6.40782199065863e-07 2.32655279307914e-07 1.98617168381795e-06 5.14561146387043e-06 1.30028235967162e-05 -1.28191526037403e-06 -6.41135110301274e-06 -1.96250075442222e-05 3.66785446603441e-06 -3.77001276527818e-05 -1.28191526037403e-06 8.50120679398508e-05 3411 3351 0 0 122 3351 3351 0 0 152 0 0 0 0 0 0 0 0 3394 0 0 0 0 0 3714 +755 756 0.999009247412223 0.0325073174434115 -0.0303940437832449 0.146031797751757 -0.0329060251676822 0.99937761862643 -0.0127109754239678 -0.0110107980884033 0.0299619273834045 0.0136985291618525 0.999457169270536 -0.00558842440648434 5.09930869768482e-05 1.13085725138832e-05 -6.22786687086176e-06 2.92633520190128e-06 7.65021722816444e-07 -1.57185059121533e-05 1.13085725138832e-05 6.95102377788552e-05 -3.20854993990448e-06 -6.58051129426398e-06 -2.27082373998457e-07 -5.27844930336232e-05 -6.22786687086176e-06 -3.20854993990448e-06 1.37907920458453e-05 -4.77518366860212e-06 3.45263846229256e-06 3.65560910540657e-08 2.92633520190128e-06 -6.58051129426398e-06 -4.77518366860212e-06 0.000183944210580139 1.01355795490377e-06 1.63315358606537e-05 7.65021722816444e-07 -2.27082373998457e-07 3.45263846229256e-06 1.01355795490377e-06 1.25176425616182e-05 3.49272199655073e-06 -1.57185059121533e-05 -5.27844930336232e-05 3.65560910540657e-08 1.63315358606537e-05 3.49272199655073e-06 0.000125276934716625 3321 3249 0 301 46 3321 3249 0 188 60 0 0 0 0 0 0 0 0 1812 0 0 0 0 0 3824 +751 752 0.998761011467048 -0.0428648310646772 0.0252794032982653 0.133476024121673 0.0423973774143899 0.998924937096321 0.0187465312922722 0.0182414043494931 -0.0260557932464441 -0.0176515241525213 0.999504636974432 0.115121044099511 5.36772432717202e-05 6.56493261224721e-06 1.19348160002753e-06 1.13658073317131e-05 1.91689481381668e-06 1.31937565856365e-05 6.56493261224721e-06 0.000118529786157694 3.0302489350981e-06 0.000115579071940152 -5.96789382521962e-07 -6.57735586912552e-05 1.19348160002753e-06 3.0302489350981e-06 1.35058872384197e-05 1.45286313822773e-06 3.69675922035423e-06 -2.61505893385058e-06 1.13658073317131e-05 0.000115579071940152 1.45286313822773e-06 0.000764839353216961 -1.83407447612683e-05 0.000128058028586686 1.91689481381668e-06 -5.96789382521962e-07 3.69675922035423e-06 -1.83407447612683e-05 1.23373131167169e-05 -1.04346924230247e-05 1.31937565856365e-05 -6.57735586912552e-05 -2.61505893385058e-06 0.000128058028586686 -1.04346924230247e-05 0.000353960430095925 3323 3253 0 27 240 3311 3253 0 0 264 0 0 0 0 0 0 0 0 2641 0 0 0 0 0 3606 +747 748 0.99953572917352 -0.00312262404337379 0.030308007599372 0.133346217111384 0.00290641640426501 0.999970034786813 0.00717511478267618 0.00589164272408465 -0.0303295045993973 -0.00708369589573853 0.999514853518051 0.0202625043923272 3.5705848574273e-05 -1.3660856176657e-05 4.27221239689429e-07 -1.12446161288632e-05 -1.54002164113139e-06 2.44001081467056e-05 -1.3660856176657e-05 4.76455347683521e-05 -1.42035310903228e-06 -1.43136855757391e-05 2.01777133177663e-06 3.80524631729107e-05 4.27221239689429e-07 -1.42035310903228e-06 9.66034006500816e-06 -2.59972435012011e-06 4.36238308692052e-06 -3.47068097837839e-06 -1.12446161288632e-05 -1.43136855757391e-05 -2.59972435012011e-06 0.000394338405653855 2.68473601693014e-05 0.000109532093280269 -1.54002164113139e-06 2.01777133177663e-06 4.36238308692052e-06 2.68473601693014e-05 1.28826400245867e-05 3.36820758111093e-05 2.44001081467056e-05 3.80524631729107e-05 -3.47068097837839e-06 0.000109532093280269 3.36820758111093e-05 0.000717144201761893 3231 3196 0 124 128 3231 3196 0 49 161 0 0 0 0 0 0 0 0 3639 0 0 0 0 0 3710 +756 757 0.99947074294237 0.028230193847693 0.0161644720776595 0.150426776882672 -0.0283127840859461 0.9995870858279 0.00490347870282747 -0.00509922063199424 -0.0160193713837453 -0.00535854470991514 0.999857322691123 0.0997029609312565 4.37103162248843e-05 9.39877203684476e-06 -1.61647404711427e-06 -8.74407269482331e-06 1.89666683101394e-06 9.0420441485189e-07 9.39877203684476e-06 3.43554699674524e-05 -1.4323654242361e-06 -2.68576900417677e-05 3.83920431784195e-07 -6.33837985366902e-06 -1.61647404711427e-06 -1.4323654242361e-06 1.3303043953681e-05 -6.89162240978e-07 2.69611504195766e-06 -4.15697593813796e-06 -8.74407269482331e-06 -2.68576900417677e-05 -6.89162240978e-07 0.000449159726136142 4.75564532783047e-06 -0.000125666664694367 1.89666683101394e-06 3.83920431784195e-07 2.69611504195766e-06 4.75564532783047e-06 1.27577065709575e-05 3.01753213343688e-06 9.0420441485189e-07 -6.33837985366902e-06 -4.15697593813796e-06 -0.000125666664694367 3.01753213343688e-06 0.000172435772509868 3380 3318 0 296 61 3380 3318 0 175 83 0 0 0 0 0 0 0 0 1925 0 0 0 0 0 3785 +758 759 0.998510189774875 -0.00730671774236511 0.0540741416166479 0.148193128286145 0.00668576045529686 0.999909721534015 0.0116554446033793 0.00293596048325543 -0.0541544229299719 -0.0112765534451561 0.998468896771212 -0.0160810849189004 4.3703537596061e-05 -4.66115778457094e-06 -7.87874008164944e-06 9.53124800602043e-06 1.88102484721458e-06 3.36536735179138e-05 -4.66115778457094e-06 3.98417725833565e-05 2.36033889834738e-06 -1.87704869907934e-05 -1.38224971018746e-06 -2.57109221255219e-05 -7.87874008164944e-06 2.36033889834738e-06 1.14415385888325e-05 -4.6992339275673e-07 4.14082015622284e-06 -4.21713191750509e-06 9.53124800602043e-06 -1.87704869907934e-05 -4.6992339275673e-07 0.000120580055249835 3.51325826248891e-06 5.3414117405058e-05 1.88102484721458e-06 -1.38224971018746e-06 4.14082015622284e-06 3.51325826248891e-06 1.07589121432436e-05 1.1578108197345e-05 3.36536735179138e-05 -2.57109221255219e-05 -4.21713191750509e-06 5.3414117405058e-05 1.1578108197345e-05 0.000242890426492819 3328 3285 0 165 179 3328 3285 0 73 199 0 0 0 0 0 0 0 0 2287 0 0 0 0 0 3667 +754 755 0.998843492488223 0.0479155205679001 0.00397245549203599 0.0455512794700261 -0.0477785150047536 0.998425112419276 -0.0294025236076118 0.000691521639933068 -0.0053750365458853 0.0291787213438625 0.999559758695231 0.0842581336000418 4.14945637947238e-05 7.37320145995177e-06 -7.34334305450715e-06 -2.36888262572034e-05 2.24040182113749e-06 -6.980490908346e-05 7.37320145995177e-06 8.64289892685584e-05 -7.27652274375357e-06 8.74481139851683e-05 1.42361387849329e-05 0.000361515356768702 -7.34334305450715e-06 -7.27652274375357e-06 1.18341211273871e-05 -1.47957133834389e-05 2.01300462155797e-06 -2.66287918824693e-05 -2.36888262572034e-05 8.74481139851683e-05 -1.47957133834389e-05 0.000602995328236237 1.85283183920635e-05 0.000563813966613222 2.24040182113749e-06 1.42361387849329e-05 2.01300462155797e-06 1.85283183920635e-05 1.5100335977722e-05 0.000105999869187773 -6.980490908346e-05 0.000361515356768702 -2.66287918824693e-05 0.000563813966613222 0.000105999869187773 0.00371028754989148 3298 3196 0 133 0 3314 3212 0 22 0 0 0 0 0 0 0 0 0 1582 0 72 87 0 0 3753 +760 761 0.996406812781176 -0.0291513225781745 -0.0795214677631234 0.151063194312333 0.0301608722487112 0.99947862813994 0.0115236138732939 0.00719237002169097 0.0791440789222743 -0.0138806442014433 0.996766543623981 0.0282604367182801 3.41004032924067e-05 1.60866608717725e-06 -1.10617582550317e-05 -8.32622332913379e-06 6.01992742616074e-07 2.67898831303946e-05 1.60866608717725e-06 5.96411890388828e-05 -3.41981004424081e-07 5.97443670803603e-06 8.26134162869522e-07 5.43067176046186e-05 -1.10617582550317e-05 -3.41981004424081e-07 1.21337342321523e-05 -1.929987902967e-06 3.09715301432636e-06 -2.75982811326284e-06 -8.32622332913379e-06 5.97443670803603e-06 -1.929987902967e-06 0.000187209482342271 1.01301735654973e-06 -9.3172377290661e-05 6.01992742616074e-07 8.26134162869522e-07 3.09715301432636e-06 1.01301735654973e-06 1.11762274520969e-05 -1.55855962846319e-06 2.67898831303946e-05 5.43067176046186e-05 -2.75982811326284e-06 -9.3172377290661e-05 -1.55855962846319e-06 0.00089027014884874 3008 2937 0 94 210 3002 2937 0 8 237 0 0 0 0 0 0 0 0 2260 0 0 0 0 0 3608 +763 764 0.999460342281478 -0.0199825380239267 -0.0260714859705745 0.12713971099347 0.019713525065987 0.999750165725095 -0.0105348498859188 0.00161074240842846 0.0262754854582031 0.0100152037806759 0.999604569095784 0.0313983375463836 4.00598740045904e-05 6.35824160472455e-05 1.33064319081956e-08 -8.25363166563929e-07 -1.30866126059862e-06 -5.4582871373075e-06 6.35824160472455e-05 0.000933378138389484 1.19871527204879e-05 6.43395445569791e-05 4.52658792774711e-07 -9.53496352003832e-06 1.33064319081956e-08 1.19871527204879e-05 1.07492466776474e-05 -3.20842583847141e-06 3.97161234653962e-06 -2.38365667072923e-06 -8.25363166563929e-07 6.43395445569791e-05 -3.20842583847141e-06 0.000185711660034267 -6.59630196220742e-06 2.77041342716432e-05 -1.30866126059862e-06 4.52658792774711e-07 3.97161234653962e-06 -6.59630196220742e-06 1.08801857145939e-05 -2.60420977885919e-06 -5.4582871373075e-06 -9.53496352003832e-06 -2.38365667072923e-06 2.77041342716432e-05 -2.60420977885919e-06 0.000182784133483341 3049 2956 0 113 168 3049 2956 0 0 184 0 0 0 0 0 0 0 0 1730 0 0 0 0 0 3668 +761 762 0.999147136351799 -0.0238636517894362 -0.0336975673197823 0.152475316414865 0.0245901346775415 0.999470430752014 0.0213115773447893 0.00574923368094655 0.0331711500635581 -0.0221220291938851 0.999204829165575 0.00019166898520267 3.35310092122902e-05 8.56152832565473e-06 -5.23237512527773e-06 3.07782879565897e-06 -1.60050496911477e-06 -1.1246968657345e-05 8.56152832565473e-06 2.82292736538504e-05 2.80955134092399e-06 -3.3965410353133e-06 1.69737290006634e-07 -1.6629705406253e-05 -5.23237512527773e-06 2.80955134092399e-06 1.16270781132742e-05 -7.83643145864355e-06 3.79949691954741e-06 -3.03940520462862e-06 3.07782879565897e-06 -3.3965410353133e-06 -7.83643145864355e-06 0.000167765159547371 -7.00263753001665e-07 1.38565511464788e-05 -1.60050496911477e-06 1.69737290006634e-07 3.79949691954741e-06 -7.00263753001665e-07 1.04285119936094e-05 -9.98104926548855e-07 -1.1246968657345e-05 -1.6629705406253e-05 -3.03940520462862e-06 1.38565511464788e-05 -9.98104926548855e-07 9.56541991947679e-05 3440 3360 0 120 202 3440 3360 0 18 222 0 0 0 0 0 0 0 0 1975 0 0 0 0 0 3636 +757 758 0.999040608947962 0.0185668671377274 0.0396627421842698 0.107640847273151 -0.0190288320372568 0.999755057506027 0.0113017052880877 -0.00490723744562573 -0.0394431898327677 -0.012045598192323 0.999149207245847 -0.00575973858592883 5.06779662190845e-05 1.27231002025625e-05 -6.21240115707458e-06 -1.69153912971053e-05 1.43774750593369e-06 -5.32650764183485e-06 1.27231002025625e-05 5.77709110384801e-05 -2.99892631768657e-06 -1.79889353740184e-05 2.88230600018353e-07 -4.59268687774583e-05 -6.21240115707458e-06 -2.99892631768657e-06 1.30659303123972e-05 3.90275381770034e-06 5.3404360780588e-06 5.58536480629808e-06 -1.69153912971053e-05 -1.79889353740184e-05 3.90275381770034e-06 0.000326631854165477 1.45529470990879e-05 6.54385274673276e-05 1.43774750593369e-06 2.88230600018353e-07 5.3404360780588e-06 1.45529470990879e-05 1.1976460120026e-05 5.66429902814475e-06 -5.32650764183485e-06 -4.59268687774583e-05 5.58536480629808e-06 6.54385274673276e-05 5.66429902814475e-06 0.000251506100058404 3312 3257 0 174 35 3312 3257 0 88 65 0 0 0 0 0 0 0 0 2391 0 0 0 0 0 3816 +766 767 0.996661137304917 0.0236161002591939 -0.0781591785692291 0.148319157841077 -0.0240098905517624 0.999703304185345 -0.00410228675207481 -0.0221934298931429 0.0780391090528418 0.00596518310293662 0.996932452099332 -0.00285034842453559 5.248065069409e-05 0.000109968202987663 -5.31238076610958e-06 0.000101824372898713 1.31803173459131e-06 -3.02805507879359e-05 0.000109968202987663 0.00237841036930212 -6.31614117268311e-05 0.00234658737803789 -3.0188734630055e-05 -0.000462876063207026 -5.31238076610958e-06 -6.31614117268311e-05 1.83285789933788e-05 -7.49295559116966e-05 2.49084163923498e-06 1.19841578760012e-05 0.000101824372898713 0.00234658737803789 -7.49295559116966e-05 0.00291826684718639 -3.15651707578492e-05 -0.000322475665691207 1.31803173459131e-06 -3.0188734630055e-05 2.49084163923498e-06 -3.15651707578492e-05 1.43985176210111e-05 5.27177507672799e-06 -3.02805507879359e-05 -0.000462876063207026 1.19841578760012e-05 -0.000322475665691207 5.27177507672799e-06 0.000206231405519325 3272 3197 0 303 48 3272 3198 0 176 60 0 0 0 0 0 0 0 0 2335 0 0 0 0 0 3791 +768 769 0.985586286543562 0.0114865517546787 -0.168783088329543 0.153093736523813 -0.011437896281164 0.999933790594324 0.00126053811075837 -0.0111613487081615 0.168786392537824 0.000688154382698875 0.985652413448886 0.112814084312626 4.51723970454674e-05 -0.000218756359269143 -5.65862576291218e-06 4.09554312680134e-05 -3.43347927779999e-07 6.00269007665575e-05 -0.000218756359269143 0.00422828084691556 -8.16228816259126e-05 -0.000949071606986358 -5.0639481220625e-05 -0.000821299791321492 -5.65862576291218e-06 -8.16228816259126e-05 1.45728599546787e-05 1.87970011033623e-05 5.65927239223139e-06 1.15655930624198e-05 4.09554312680134e-05 -0.000949071606986358 1.87970011033623e-05 0.000336298183025091 1.56890205372335e-05 0.000199740558472414 -3.43347927779999e-07 -5.0639481220625e-05 5.65927239223139e-06 1.56890205372335e-05 1.14359033874316e-05 1.31040363787845e-05 6.00269007665575e-05 -0.000821299791321492 1.15655930624198e-05 0.000199740558472414 1.31040363787845e-05 0.000396394483704513 2322 2276 0 202 72 2322 2276 0 117 92 0 0 0 0 0 0 0 0 3151 0 0 0 0 0 3692 +765 766 0.999157426724566 0.0318950754131714 0.0258290686152657 0.126527270288394 -0.0312149875423189 0.999166122825199 -0.0263188820277958 -0.0141834139448806 -0.0266469730715679 0.0254904523861046 0.99931985653407 -0.00620071077809712 4.65556601850788e-05 1.71212906058126e-05 2.90130140791541e-06 -9.46435675374739e-07 2.58153669370196e-06 -1.41097967753929e-05 1.71212906058126e-05 6.44252007189141e-05 7.58213737889635e-07 2.70027045289899e-05 -6.24618103224114e-07 -2.65041302965734e-05 2.90130140791541e-06 7.58213737889635e-07 1.14512621069601e-05 -4.66756851401629e-07 4.33853980805519e-06 -2.93077775885682e-06 -9.46435675374739e-07 2.70027045289899e-05 -4.66756851401629e-07 0.000144807337446934 -4.6336239405165e-06 -1.24811275446989e-06 2.58153669370196e-06 -6.24618103224114e-07 4.33853980805519e-06 -4.6336239405165e-06 1.09701190847681e-05 4.75814379230297e-06 -1.41097967753929e-05 -2.65041302965734e-05 -2.93077775885682e-06 -1.24811275446989e-06 4.75814379230297e-06 0.000178364826008723 3245 3160 0 289 28 3245 3160 0 163 41 0 0 0 0 0 0 0 0 1857 0 0 0 0 0 3815 +769 770 0.999837615129285 -0.0105277849803743 -0.0146256321569523 0.142835073892983 0.0105709642745377 0.999939983720881 0.0028781366525893 -0.00480777248721255 0.0145944539771079 -0.00303227632176475 0.999888897434819 0.0473292477835659 5.45449384689651e-05 -1.33489608129565e-05 -9.272023779964e-06 -5.05321648282221e-07 -2.69706980195973e-06 -3.32329970829998e-05 -1.33489608129565e-05 0.000132171432053454 -8.67398579375887e-07 -2.97066978120063e-06 1.36483444274683e-06 -5.78063569971457e-05 -9.272023779964e-06 -8.67398579375887e-07 1.18506852489548e-05 2.48440036360396e-08 5.14148544722449e-06 2.70658434622657e-06 -5.05321648282221e-07 -2.97066978120063e-06 2.48440036360396e-08 0.000121634730365638 3.61654507959555e-06 7.0924909671816e-05 -2.69706980195973e-06 1.36483444274683e-06 5.14148544722449e-06 3.61654507959555e-06 1.02018500471663e-05 6.21360957679901e-06 -3.32329970829998e-05 -5.78063569971457e-05 2.70658434622657e-06 7.0924909671816e-05 6.21360957679901e-06 0.000455883816358526 3277 3226 0 151 142 3277 3226 0 61 171 0 0 0 0 0 0 0 0 3544 0 0 0 0 0 3679 +759 760 0.999661277547034 -0.025060453015997 0.00702167128710024 0.149003886168775 0.0250388913285009 0.999681540133271 0.00314201174573384 0.00636631329159362 -0.00709817540432761 -0.00296513261150592 0.999970411509523 0.0040067492424155 4.13500325518526e-05 -1.06694108219759e-05 -5.69405500185556e-06 8.15500780405539e-06 -6.47430288100669e-07 -4.59980675681031e-07 -1.06694108219759e-05 4.32958387968009e-05 4.25742912500966e-06 -3.24782767735258e-05 -3.97748779507938e-07 1.86170077695618e-06 -5.69405500185556e-06 4.25742912500966e-06 1.32230713618919e-05 -3.03420530248454e-06 3.29382243650947e-06 -1.00460497809583e-05 8.15500780405539e-06 -3.24782767735258e-05 -3.03420530248454e-06 0.000243569681479645 1.08881110535876e-06 -6.97702377023278e-05 -6.47430288100669e-07 -3.97748779507938e-07 3.29382243650947e-06 1.08881110535876e-06 1.137867057785e-05 4.55197197576247e-06 -4.59980675681031e-07 1.86170077695618e-06 -1.00460497809583e-05 -6.97702377023278e-05 4.55197197576247e-06 0.000270217878699012 3371 3316 0 125 201 3371 3316 0 20 228 0 0 0 0 0 0 0 0 2339 0 0 0 0 0 3621 +762 763 0.999290478953689 -0.0264269876741224 -0.0268356664716517 0.146491050385119 0.0260844968894499 0.999574773924731 -0.0130334322166946 0.00739454148840151 0.0271686895990628 0.012324189863625 0.999554889263053 0.00380605313271374 3.87040875619849e-05 9.19864688785861e-06 -9.15297416801755e-06 5.53312938617769e-06 3.98415175839247e-06 -2.28461642200632e-05 9.19864688785861e-06 4.52048062694578e-05 2.35399353718669e-06 -1.01664563421699e-05 1.29608994793914e-06 -2.36465376866057e-05 -9.15297416801755e-06 2.35399353718669e-06 1.29493943962952e-05 -2.64609001056454e-06 1.48951644147612e-06 4.38060087472673e-06 5.53312938617769e-06 -1.01664563421699e-05 -2.64609001056454e-06 0.000141114395250199 -4.82179062897953e-07 2.25700415948501e-05 3.98415175839247e-06 1.29608994793914e-06 1.48951644147612e-06 -4.82179062897953e-07 1.36390611056379e-05 -1.07649480530097e-05 -2.28461642200632e-05 -2.36465376866057e-05 4.38060087472673e-06 2.25700415948501e-05 -1.07649480530097e-05 0.000204728625573419 3466 3375 0 104 207 3466 3375 0 2 225 0 0 0 0 0 0 0 0 1720 0 0 0 0 0 3633 +764 765 0.999897863111846 0.0135775399201848 0.00446248295013876 0.100449230014771 -0.0135185970418939 0.999824323503657 -0.0129834380837177 -0.00466027480460066 -0.00463798214565201 0.0129217854869451 0.999905753849555 0.00370495043061275 3.35012712138186e-05 1.27097680189272e-05 5.77738470354511e-07 1.87596814571299e-05 9.40243587617503e-08 -1.49398194931815e-05 1.27097680189272e-05 2.30107802112571e-05 4.048615651617e-06 -1.73874149591948e-06 9.86991924059632e-08 -1.4118402691906e-05 5.77738470354511e-07 4.048615651617e-06 1.30220422938378e-05 -3.00355643718908e-06 3.66007211285258e-06 -3.99039979671946e-06 1.87596814571299e-05 -1.73874149591948e-06 -3.00355643718908e-06 0.000179415647809998 -8.64679602318857e-06 3.41612228310653e-06 9.40243587617503e-08 9.86991924059632e-08 3.66007211285258e-06 -8.64679602318857e-06 1.18360727711344e-05 -6.16362916084001e-07 -1.49398194931815e-05 -1.4118402691906e-05 -3.99039979671946e-06 3.41612228310653e-06 -6.16362916084001e-07 6.27840457525241e-05 3610 3513 0 157 57 3610 3513 0 47 76 0 0 0 0 0 0 0 0 1628 0 0 0 0 0 3777 +772 773 0.999517460102021 -0.0302940792955546 0.00686408849302727 0.160773160566345 0.0303328490183531 0.999524074588614 -0.00561627885743803 0.0042433376877591 -0.00669068170183426 0.00582177613871874 0.999960670077056 -0.0183536143282451 4.29479499565757e-05 9.58096424997529e-06 6.49782199299907e-06 -3.85161211924904e-06 -6.64225589333921e-07 6.35742715139233e-06 9.58096424997529e-06 6.32323164999603e-05 -4.24527865751623e-07 -4.0800430298651e-06 -1.98858768379657e-06 -5.94768354032176e-05 6.49782199299907e-06 -4.24527865751623e-07 1.25014465755229e-05 -6.28269746984639e-06 3.87970215104001e-06 3.24959794594419e-06 -3.85161211924904e-06 -4.0800430298651e-06 -6.28269746984639e-06 0.000176874231989548 -5.91599762318089e-06 -2.50944895969263e-05 -6.64225589333921e-07 -1.98858768379657e-06 3.87970215104001e-06 -5.91599762318089e-06 1.0459442618587e-05 4.92697905733686e-06 6.35742715139233e-06 -5.94768354032176e-05 3.24959794594419e-06 -2.50944895969263e-05 4.92697905733686e-06 0.000266579724710406 3293 3213 0 125 226 3293 3213 0 32 248 0 0 0 0 0 0 0 0 3598 0 0 0 0 0 3586 +775 776 0.999048982936059 0.0329498689382952 -0.0285558370806132 0.120839632777602 -0.032491778312292 0.99933809392916 0.0163602678504377 -0.0143519048791998 0.0290760044801589 -0.0154168790285961 0.99945830618615 0.119696529742903 4.55687334992706e-05 3.47607413954743e-05 -2.49490497744909e-06 1.32803080746561e-05 -5.95092177966255e-07 -6.53314596267296e-05 3.47607413954743e-05 0.000147444647431396 1.08532779881324e-06 -1.90922565522224e-06 1.36427698348878e-06 0.000132769111494464 -2.49490497744909e-06 1.08532779881324e-06 1.10164977268577e-05 3.70061051289515e-06 3.28134660085079e-06 -2.18667659891598e-05 1.32803080746561e-05 -1.90922565522224e-06 3.70061051289515e-06 0.00012168109946776 -2.37038908909958e-06 -0.000234763181614694 -5.95092177966255e-07 1.36427698348878e-06 3.28134660085079e-06 -2.37038908909958e-06 1.02599219848594e-05 5.29076959879055e-06 -6.53314596267296e-05 0.000132769111494464 -2.18667659891598e-05 -0.000234763181614694 5.29076959879055e-06 0.00566919316771051 3053 2978 0 260 21 3053 2979 0 147 37 0 0 0 0 0 0 0 0 3305 0 0 0 0 0 3783 +767 768 0.999260117803654 0.0384036756894184 0.00209156892540154 0.142875371128422 -0.0384183285240695 0.999233706630689 0.00748542360263425 -0.0214404327367429 -0.00180249838956906 -0.00756023985308536 0.999969796430332 -0.00926023180880504 4.15415360056413e-05 1.94809512757185e-06 6.67506473003714e-06 -6.5163157372752e-07 2.54617188505264e-06 -3.77046525410222e-06 1.94809512757185e-06 4.68321476080018e-05 3.35441680066427e-06 -8.27379606547996e-06 -7.77656788988432e-07 -3.84124025035782e-05 6.67506473003714e-06 3.35441680066427e-06 1.04389220827793e-05 -2.6453690663652e-07 4.37654607576429e-06 -4.88468865076219e-06 -6.5163157372752e-07 -8.27379606547996e-06 -2.6453690663652e-07 0.000108563384588513 -1.0087049456461e-06 3.50073571620525e-06 2.54617188505264e-06 -7.77656788988432e-07 4.37654607576429e-06 -1.0087049456461e-06 1.03416768363404e-05 2.29546927253945e-06 -3.77046525410222e-06 -3.84124025035782e-05 -4.88468865076219e-06 3.50073571620525e-06 2.29546927253945e-06 0.000159799907431146 3190 3131 0 333 10 3190 3132 0 213 31 0 0 0 0 0 0 0 0 2711 0 0 0 0 0 3828 +770 771 0.998975154383399 -0.0307378323083881 -0.0332238858300205 0.148606502266782 0.0303598390668 0.999469113519413 -0.0118224909624043 0.00228819627737939 0.0335696454628706 0.010801702907391 0.99937800762164 0.0259886157089013 3.16705798913995e-05 -1.67342879921988e-06 -3.17257500876199e-06 -8.17326311407329e-06 -3.12453303004989e-06 -1.11209035506056e-05 -1.67342879921988e-06 5.28012245523041e-05 -8.10227758588322e-08 -1.59552377488309e-05 -6.55231205650362e-07 -3.28084259802044e-05 -3.17257500876199e-06 -8.10227758588322e-08 1.22783602443882e-05 -3.6885836577299e-06 3.10497162076859e-06 -3.53053752626722e-06 -8.17326311407329e-06 -1.59552377488309e-05 -3.6885836577299e-06 8.76014699411193e-05 2.83255113183193e-06 3.12840726862723e-05 -3.12453303004989e-06 -6.55231205650362e-07 3.10497162076859e-06 2.83255113183193e-06 1.10731980075667e-05 8.48226655143673e-06 -1.11209035506056e-05 -3.28084259802044e-05 -3.53053752626722e-06 3.12840726862723e-05 8.48226655143673e-06 0.000255580891264865 3188 3136 0 103 202 3188 3136 0 18 234 0 0 0 0 0 0 0 0 3619 0 0 0 0 0 3607 +778 779 0.999415012299236 0.020555326782969 -0.0273333446867314 0.130496404768079 -0.0208948514555122 0.999707306223079 -0.0121945507029809 -0.00329723733521661 0.0270746814121679 0.0127585432178148 0.999551990244324 0.0794784324999506 4.39969244598993e-05 2.9445251826723e-06 -9.89972802745692e-06 9.38664068909669e-06 1.14589170723342e-06 -1.46249457860252e-05 2.9445251826723e-06 9.74838019299667e-05 -3.57121154185582e-06 -5.27425116978155e-06 1.43408224698799e-06 -5.44768431984797e-05 -9.89972802745692e-06 -3.57121154185582e-06 1.28946307632221e-05 -1.78829867423233e-06 4.08797922421211e-06 5.33110946828941e-06 9.38664068909669e-06 -5.27425116978155e-06 -1.78829867423233e-06 0.000112420586019496 4.79361539320578e-06 4.65983020633154e-05 1.14589170723342e-06 1.43408224698799e-06 4.08797922421211e-06 4.79361539320578e-06 1.09643850820731e-05 3.28394498361724e-07 -1.46249457860252e-05 -5.44768431984797e-05 5.33110946828941e-06 4.65983020633154e-05 3.28394498361724e-07 0.000283465236679205 3236 3200 0 205 54 3236 3200 0 114 87 0 0 0 0 0 0 0 0 3585 0 0 0 0 0 3779 +780 781 0.999215690504817 -0.0173265443122627 0.0356061049705851 0.161312936636189 0.0179736741056222 0.999677577417008 -0.0179356697340002 0.00861278783474336 -0.035283861581834 0.0185615751448372 0.999204942461764 -0.0567948188124943 3.27002714129175e-05 -2.77191155327402e-06 1.10359606794741e-06 1.87629910221208e-06 -6.73964463827663e-07 7.2558181994424e-06 -2.77191155327402e-06 0.000107974266925854 -2.05404248009433e-06 -1.57063792067574e-05 -1.5122556560397e-06 -6.96165696813385e-06 1.10359606794741e-06 -2.05404248009433e-06 1.13431882694933e-05 -3.70100926751849e-07 3.72193551363423e-06 1.11457210686102e-06 1.87629910221208e-06 -1.57063792067574e-05 -3.70100926751849e-07 0.00011529246494792 -3.31492570960937e-06 -9.20954857681517e-05 -6.73964463827663e-07 -1.5122556560397e-06 3.72193551363423e-06 -3.31492570960937e-06 1.0758059864557e-05 2.25749064872381e-05 7.2558181994424e-06 -6.96165696813385e-06 1.11457210686102e-06 -9.20954857681517e-05 2.25749064872381e-05 0.000450306668286392 3112 3070 0 134 200 3112 3070 0 56 237 0 0 0 0 0 0 0 0 3629 0 0 0 0 0 3622 +771 772 0.999120857273491 -0.0359698994966235 -0.0215332043896697 0.136492834551439 0.0362130518139062 0.999283435519042 0.0110104666378615 0.00284344379502637 0.021121729081868 -0.0117805699124839 0.999707502589197 -0.0277748645603652 3.3849575460211e-05 8.07140468897217e-06 -5.94017560631058e-06 -1.0770267222393e-05 -6.59225197333146e-07 -6.33636056274708e-06 8.07140468897217e-06 2.89380423017246e-05 -1.53649228644901e-06 -9.10583270283788e-06 -9.70451643703429e-08 -1.71790882142539e-05 -5.94017560631058e-06 -1.53649228644901e-06 1.32078017769471e-05 -8.64382267962765e-07 1.94799777555702e-06 -3.55821343216361e-07 -1.0770267222393e-05 -9.10583270283788e-06 -8.64382267962765e-07 0.000136394895175725 2.81263810828011e-07 -3.05763639505117e-06 -6.59225197333146e-07 -9.70451643703429e-08 1.94799777555702e-06 2.81263810828011e-07 1.22383015388996e-05 2.45708685602723e-06 -6.33636056274708e-06 -1.71790882142539e-05 -3.55821343216361e-07 -3.05763639505117e-06 2.45708685602723e-06 0.000131982295159215 3417 3362 0 58 209 3417 3362 0 0 236 0 0 0 0 0 0 0 0 3670 0 0 0 0 0 3596 +773 774 0.999679912668757 -0.0232715810207109 0.00992500495629589 0.137537589722341 0.023211207851529 0.999711634063938 0.00615536735571501 3.91161635562803e-05 -0.010065388053082 -0.00592302574763726 0.999931800539084 -0.00775922923961076 3.33929682655731e-05 1.91431112507069e-05 2.58115227738139e-06 -3.44879782583842e-06 -2.29296207671488e-06 -1.90524723880119e-05 1.91431112507069e-05 3.98617135334611e-05 4.47068723642689e-06 -2.07213438999285e-07 -7.02537998813274e-07 -3.25316867698148e-05 2.58115227738139e-06 4.47068723642689e-06 1.14768432630418e-05 -4.55072832826227e-06 3.18493867368365e-06 -4.79844263221345e-06 -3.44879782583842e-06 -2.07213438999285e-07 -4.55072832826227e-06 0.00013507597331767 -1.57565337436915e-06 2.53681217677577e-05 -2.29296207671488e-06 -7.02537998813274e-07 3.18493867368365e-06 -1.57565337436915e-06 1.05018199956466e-05 -4.95320713581814e-07 -1.90524723880119e-05 -3.25316867698148e-05 -4.79844263221345e-06 2.53681217677577e-05 -4.95320713581814e-07 0.000116529122216795 3193 3112 0 113 189 3193 3112 0 11 202 0 0 0 0 0 0 0 0 3488 0 0 0 0 0 3623 +774 775 0.999457176215782 -0.00374685777547479 0.0327309328859661 0.15122210583734 0.00391986541372097 0.999978676266034 -0.00522318565323858 -0.00605322193923398 -0.0327106644064832 0.00534865123561514 0.999450551235051 0.0210608722784087 4.09323975708746e-05 1.34844940366237e-05 -1.39071473288388e-07 -1.10938281682551e-05 7.97964032543875e-07 -1.11333387207612e-05 1.34844940366237e-05 5.1985834252486e-05 -2.24681906502553e-06 -2.49164452654197e-06 5.44575456527876e-07 -2.8660156171607e-05 -1.39071473288388e-07 -2.24681906502553e-06 1.06445092109533e-05 8.28188005732276e-07 3.1562012304741e-06 -6.78273441836475e-07 -1.10938281682551e-05 -2.49164452654197e-06 8.28188005732276e-07 0.000113640044477835 -5.21467148860563e-06 1.1254919656011e-05 7.97964032543875e-07 5.44575456527876e-07 3.1562012304741e-06 -5.21467148860563e-06 1.03366512140142e-05 1.16921914903701e-06 -1.11333387207612e-05 -2.8660156171607e-05 -6.78273441836475e-07 1.1254919656011e-05 1.16921914903701e-06 0.000101635058367994 3341 3257 0 204 141 3341 3257 0 90 159 0 0 0 0 0 0 0 0 3194 0 0 0 0 0 3665 +782 783 0.999689159351855 -0.0239795110191278 0.00682405492836224 0.144002640412749 0.0236864174425734 0.998910800081587 0.0402015809278802 0.00737235480010034 -0.00778063642113748 -0.0400274472287239 0.999168286709118 0.0515371157480855 4.3349012869013e-05 1.33579275712325e-05 -1.22472042839491e-06 -7.84914907940201e-07 1.95413576220059e-07 -8.28137478504701e-06 1.33579275712325e-05 4.7663763833128e-05 -5.64739963493216e-07 -6.50181165241793e-06 1.04777280776564e-06 -2.10579277485804e-05 -1.22472042839491e-06 -5.64739963493216e-07 1.29944046615612e-05 -1.59935477158828e-06 3.20354968092998e-06 -1.56866406464224e-06 -7.84914907940201e-07 -6.50181165241793e-06 -1.59935477158828e-06 0.000112145990710863 6.9479626254903e-07 1.57283285270124e-05 1.95413576220059e-07 1.04777280776564e-06 3.20354968092998e-06 6.9479626254903e-07 1.01321415397559e-05 8.12181417050735e-07 -8.28137478504701e-06 -2.10579277485804e-05 -1.56866406464224e-06 1.57283285270124e-05 8.12181417050735e-07 0.000166322867743382 3326 3270 0 101 197 3326 3270 0 8 228 0 0 0 0 0 0 0 0 3680 0 0 0 0 0 3617 +776 777 0.998522958462085 0.0539949578590596 0.00603704811337986 0.14936810692135 -0.0539622016689975 0.998528033561909 -0.0054632391510604 -0.019061841956767 -0.0063231491489073 0.00512939731212308 0.999966852984665 -0.033489761928815 3.83483630124388e-05 8.85217831062038e-06 1.34896101394484e-06 3.54001161690788e-06 -3.37529573763208e-07 -1.85903764992843e-05 8.85217831062038e-06 4.78373822823761e-05 -4.43889887192688e-07 -7.37614706886104e-06 1.50357760884321e-06 -4.0414770926564e-05 1.34896101394484e-06 -4.43889887192688e-07 1.20927938975517e-05 -6.70718919115684e-06 3.18847410987188e-06 -2.1102470339537e-06 3.54001161690788e-06 -7.37614706886104e-06 -6.70718919115684e-06 0.000142212282818053 2.27391534965657e-06 -5.05811871151996e-07 -3.37529573763208e-07 1.50357760884321e-06 3.18847410987188e-06 2.27391534965657e-06 9.96652881461917e-06 -1.57959752220274e-06 -1.85903764992843e-05 -4.0414770926564e-05 -2.1102470339537e-06 -5.05811871151996e-07 -1.57959752220274e-06 0.000131617097637177 3328 3252 0 382 0 3328 3265 0 256 1 0 0 0 0 0 0 0 0 3421 0 0 11 0 0 3838 +779 780 0.999881518594952 0.0071856868173623 0.0136130333583682 0.137556780682394 -0.00682175459207046 0.999623027349411 -0.0265944892239914 0.00345079486002316 -0.0137990012877319 0.0264984734987172 0.999553609600655 0.0241267257782794 5.28611948609683e-05 1.65557075331525e-05 -1.44229043085024e-06 2.42893201046375e-05 9.05278769153181e-07 -9.31376201247278e-06 1.65557075331525e-05 0.000404790690449733 -1.4572572484203e-05 0.000216364878346601 -1.88477928117514e-05 -0.000698846221690493 -1.44229043085024e-06 -1.4572572484203e-05 1.20763147286011e-05 -6.50059354157448e-06 4.27819822114856e-06 2.67752726057719e-05 2.42893201046375e-05 0.000216364878346601 -6.50059354157448e-06 0.00030628660823137 -7.85528585033289e-06 -0.000437198606453796 9.05278769153181e-07 -1.88477928117514e-05 4.27819822114856e-06 -7.85528585033289e-06 1.15708127336418e-05 3.97842287645679e-05 -9.31376201247278e-06 -0.000698846221690493 2.67752726057719e-05 -0.000437198606453796 3.97842287645679e-05 0.00148968574790873 2933 2900 0 173 103 2933 2900 0 102 139 0 0 0 0 0 0 0 0 3616 0 0 0 0 0 3727 +785 786 0.999901497357704 0.00988230878033679 0.00996672237963438 0.130239528101832 -0.00997981427484603 0.999902360106946 0.00978128619346103 -0.00137935760956728 -0.00986908753949451 -0.00987978874920362 0.999902490688672 0.0555638169832689 8.01247944347752e-05 0.00019415305770254 -6.05414970555375e-06 5.7130420283893e-05 1.02396064873618e-06 -0.000183847343545858 0.00019415305770254 0.00268781048554486 -7.0713889212178e-06 0.00138764610365243 -7.55358652452642e-05 -0.00262959993363287 -6.05414970555375e-06 -7.0713889212178e-06 1.46981949298708e-05 -2.70807424077735e-06 2.94775720556385e-06 -3.66774571416666e-06 5.7130420283893e-05 0.00138764610365243 -2.70807424077735e-06 0.00120615122828513 -6.75035507277549e-05 -0.00153039031057406 1.02396064873618e-06 -7.55358652452642e-05 2.94775720556385e-06 -6.75035507277549e-05 1.50187546231631e-05 0.000101733409549544 -0.000183847343545858 -0.00262959993363287 -3.66774571416666e-06 -0.00153039031057406 0.000101733409549544 0.00374632843352089 2842 2768 0 198 90 2842 2768 0 88 110 0 0 0 0 0 0 0 0 3412 0 0 0 0 0 3731 +777 778 0.99946916744796 0.0271520028244982 -0.0180042234906284 0.117609673939007 -0.0273965331012132 0.999533789347001 -0.0134771631903552 -0.0116643844273539 0.0176298977568273 0.0139632623782472 0.999747075018897 0.0634253013666841 5.00534493234391e-05 6.59430790133411e-06 -2.4115543654427e-06 -3.97682453417373e-05 -2.26809099247914e-06 1.0026886666442e-05 6.59430790133411e-06 3.2268477132091e-05 -1.70226092064377e-07 -1.07116947926809e-05 -9.80366579498368e-07 -2.52015783743935e-05 -2.4115543654427e-06 -1.70226092064377e-07 1.41646928632998e-05 -7.85385796743971e-06 2.3241367912399e-06 1.30079078133033e-06 -3.97682453417373e-05 -1.07116947926809e-05 -7.85385796743971e-06 0.00020656188434203 7.89420170324119e-06 -6.63878118990061e-05 -2.26809099247914e-06 -9.80366579498368e-07 2.3241367912399e-06 7.89420170324119e-06 1.21044167871316e-05 -4.06867764789826e-07 1.0026886666442e-05 -2.52015783743935e-05 1.30079078133033e-06 -6.63878118990061e-05 -4.06867764789826e-07 0.000122384121309729 3351 3307 0 232 13 3351 3307 0 140 43 0 0 0 0 0 0 0 0 3559 0 0 0 0 0 3814 +784 785 0.999612361036824 -0.0171121277715033 0.0219613921580218 0.151321106468418 0.0174464015710638 0.999733457972468 -0.0151207170012948 0.00627932119270631 -0.0216967908827057 0.0154980028888824 0.999644467384204 0.0287473938540241 4.76288023407813e-05 1.88061030399614e-05 -6.14821961945934e-07 -3.41149811980515e-06 2.31432607122141e-06 -8.80903183873034e-06 1.88061030399614e-05 9.62652483777128e-05 1.55243657371965e-06 5.18119389674911e-05 -5.56131156481939e-06 -0.000130331922364714 -6.14821961945934e-07 1.55243657371965e-06 1.47828958193264e-05 -4.3090108461883e-06 3.54752268128621e-06 -7.1346474000866e-07 -3.41149811980515e-06 5.18119389674911e-05 -4.3090108461883e-06 0.000163024226384534 -8.01996613512576e-06 -8.02670336663691e-05 2.31432607122141e-06 -5.56131156481939e-06 3.54752268128621e-06 -8.01996613512576e-06 1.17100553673931e-05 1.09304482739442e-05 -8.80903183873034e-06 -0.000130331922364714 -7.1346474000866e-07 -8.02670336663691e-05 1.09304482739442e-05 0.000417241944723858 3367 3292 0 148 183 3367 3292 0 44 203 0 0 0 0 0 0 0 0 3570 0 0 0 0 0 3639 +788 789 0.999742397075592 0.0202680020669287 0.0102150664101367 0.149792074030739 -0.0203819029046891 0.999729842192036 0.0111723168891055 -0.00213689828066726 -0.00998586618838639 -0.0113776413593389 0.99988540931127 -0.00731443322635332 4.66009674428641e-05 -6.92289798112498e-08 -1.52929824651903e-05 -6.47648746419849e-06 1.98271446275568e-06 -1.02089534873292e-05 -6.92289798112498e-08 2.09863460449781e-05 1.0780180133498e-06 -5.57840716054153e-07 9.27159253219388e-07 5.10791343205185e-05 -1.52929824651903e-05 1.0780180133498e-06 1.70622320459963e-05 1.40551476645125e-06 2.54252703765327e-06 1.5014040251852e-06 -6.47648746419849e-06 -5.57840716054153e-07 1.40551476645125e-06 4.82000969831618e-05 2.32843253502793e-06 1.9616326466894e-05 1.98271446275568e-06 9.27159253219388e-07 2.54252703765327e-06 2.32843253502793e-06 1.22261993963265e-05 1.25551514798313e-05 -1.02089534873292e-05 5.10791343205185e-05 1.5014040251852e-06 1.9616326466894e-05 1.25551514798313e-05 0.000627630133253682 3483 3435 0 239 82 3483 3435 0 144 106 0 0 0 0 0 0 0 0 3507 0 0 0 0 0 3759 +789 790 0.999846292795965 0.00275701516028466 0.0173144347170743 0.135650266079639 -0.0024792775413071 0.999868247534869 -0.0160418438598391 0.00547257106471411 -0.0173563811043384 0.0159964508237374 0.999721395987905 0.0758634053559917 3.37590197160547e-05 1.58980542971964e-06 -2.26871047129267e-06 6.02707844397717e-06 -9.83308010977034e-07 4.10161500152116e-06 1.58980542971964e-06 0.000197607247721461 -1.15011682149858e-06 0.000116672441327859 5.38230693609435e-07 -0.000135004648144008 -2.26871047129267e-06 -1.15011682149858e-06 1.22924644266845e-05 -4.05080975304845e-07 3.85104221860667e-06 3.53504097570147e-06 6.02707844397717e-06 0.000116672441327859 -4.05080975304845e-07 0.000328678269727396 1.13813556603343e-05 -9.29501164565705e-05 -9.83308010977034e-07 5.38230693609435e-07 3.85104221860667e-06 1.13813556603343e-05 1.11052318286853e-05 1.40456143799097e-05 4.10161500152116e-06 -0.000135004648144008 3.53504097570147e-06 -9.29501164565705e-05 1.40456143799097e-05 0.000674009033897438 2714 2666 0 164 113 2714 2666 0 74 148 0 0 0 0 0 0 0 0 3589 0 0 0 0 0 3727 +781 782 0.999462823576723 -0.0273600033113326 0.0180414663164672 0.161245076244579 0.0269209441790725 0.999345909156725 0.024145737019721 0.00643689144625771 -0.0186902930033645 -0.0236470731914571 0.999545641217512 -0.00679251924121922 2.84338996087393e-05 -2.97396519212504e-06 7.00650850232061e-07 -6.42145346206405e-06 1.29213543764524e-07 2.65582585612436e-05 -2.97396519212504e-06 0.000589658994189403 -2.24484882254204e-05 3.59904953863912e-05 2.18479025847182e-05 0.000357626213525158 7.00650850232061e-07 -2.24484882254204e-05 1.37623208161238e-05 1.23251199038099e-06 3.08327810934144e-06 -6.22540162772912e-06 -6.42145346206405e-06 3.59904953863912e-05 1.23251199038099e-06 0.000138250719158459 1.40183130291305e-06 1.17457065959146e-05 1.29213543764524e-07 2.18479025847182e-05 3.08327810934144e-06 1.40183130291305e-06 1.43818450474108e-05 8.15447719239363e-05 2.65582585612436e-05 0.000357626213525158 -6.22540162772912e-06 1.17457065959146e-05 8.15447719239363e-05 0.00153727095809377 3238 3188 0 112 218 3238 3188 0 27 255 0 0 0 0 0 0 0 0 3658 0 0 0 0 0 3582 +783 784 0.999303729772698 -0.0258420699332647 -0.0269117647867689 0.124914802534199 0.0256999170021128 0.999653934307138 -0.00561479210172159 0.0114882296139294 0.0270475493983952 0.00491925256774833 0.999622044087522 0.0400731329796797 3.34354500100039e-05 8.44335507633634e-06 -5.7865661439766e-06 -3.12199614257684e-06 -4.73780005841831e-07 -2.27961007217026e-05 8.44335507633634e-06 5.58207156871082e-05 3.92514202160885e-06 -5.91639470196052e-06 -1.90897867589181e-06 -2.65760913125993e-05 -5.7865661439766e-06 3.92514202160885e-06 1.36456327766388e-05 -5.1281617832323e-06 3.03166360799637e-06 -1.6641033728681e-07 -3.12199614257684e-06 -5.91639470196052e-06 -5.1281617832323e-06 0.000119193065003274 -1.21551435170504e-06 -4.80373678577636e-05 -4.73780005841831e-07 -1.90897867589181e-06 3.03166360799637e-06 -1.21551435170504e-06 1.09252170865617e-05 5.66596500356392e-06 -2.27961007217026e-05 -2.65760913125993e-05 -1.6641033728681e-07 -4.80373678577636e-05 5.66596500356392e-06 0.000292007081591121 3189 3121 0 65 176 3189 3121 0 0 200 0 0 0 0 0 0 0 0 3698 0 0 0 0 0 3650 +793 794 0.999272379208492 -0.0285978852073512 -0.0252363450734478 0.153874492144968 0.0292546274009811 0.99923248934504 0.0260499330698569 -0.00350312705188754 0.0244720029141208 -0.0267692584690242 0.99934204748644 -0.0697591300105692 6.36105557969194e-05 2.7155553586811e-05 -5.19701121975901e-06 4.33284726849618e-06 2.57901824653895e-06 -3.79991683465774e-05 2.7155553586811e-05 0.000305384434023373 8.83737531841899e-06 0.000139450654230928 -7.67081581248118e-06 -0.000309531836342728 -5.19701121975901e-06 8.83737531841899e-06 1.52535996938591e-05 2.95462280607173e-06 2.3842138189122e-06 -6.3879883399341e-06 4.33284726849618e-06 0.000139450654230928 2.95462280607173e-06 0.000197276773641335 -1.11696136484297e-05 -0.000182430354255922 2.57901824653895e-06 -7.67081581248118e-06 2.3842138189122e-06 -1.11696136484297e-05 1.16504286750868e-05 7.1067383665006e-06 -3.79991683465774e-05 -0.000309531836342728 -6.3879883399341e-06 -0.000182430354255922 7.1067383665006e-06 0.000547253537647636 2676 2599 0 128 206 2676 2599 0 27 227 0 0 0 0 0 0 0 0 3615 0 0 0 0 0 3592 +786 787 0.996898277919153 0.0406103446649599 -0.0674138219360065 0.0733223333463815 -0.0401557622440793 0.999160720342469 0.00808515202803607 -0.00282659211720503 0.0676855836971463 -0.00535302072783673 0.997692340818884 0.103219660418351 5.11942014647029e-05 6.64733765168323e-05 -7.52922505025812e-06 4.88218791779895e-06 9.98284762558713e-07 -8.21874983357586e-05 6.64733765168323e-05 0.000875208348199451 6.53353828201447e-06 0.000765375445039336 -1.37589178085811e-05 -0.0017081456372692 -7.52922505025812e-06 6.53353828201447e-06 1.60112156140992e-05 9.78982847648579e-06 2.52015828073046e-06 -7.13711139130359e-06 4.88218791779895e-06 0.000765375445039336 9.78982847648579e-06 0.00101740041524852 -1.93946327333659e-05 -0.00162880347381323 9.98284762558713e-07 -1.37589178085811e-05 2.52015828073046e-06 -1.93946327333659e-05 1.13187282878304e-05 3.04850809785386e-05 -8.21874983357586e-05 -0.0017081456372692 -7.13711139130359e-06 -0.00162880347381323 3.04850809785386e-05 0.00369152758843969 2589 2506 0 167 0 2607 2525 0 64 0 0 0 0 0 0 0 0 0 3486 0 18 35 0 0 3819 +792 793 0.998286324326051 -0.0332916115077841 -0.0481257027667833 0.133668831025951 0.0349273263301267 0.998826330100605 0.0335565816671727 0.00315092051610231 0.0469520663976659 -0.0351799786948709 0.9982774526954 0.114573214489474 6.68948890031402e-05 -6.13875150789168e-05 -9.87388295823691e-06 -3.25801447113324e-05 1.68746828059468e-06 -6.81596981603695e-05 -6.13875150789168e-05 0.00137566710395947 -1.96109793646817e-06 0.000513866068156994 -2.68270382804677e-05 -0.000309010966749481 -9.87388295823691e-06 -1.96109793646817e-06 1.629720798718e-05 -1.48965323808841e-06 4.19518245150004e-06 1.7172050795061e-05 -3.25801447113324e-05 0.000513866068156994 -1.48965323808841e-06 0.000516450687412095 -2.15705899163381e-05 -0.000419724124147262 1.68746828059468e-06 -2.68270382804677e-05 4.19518245150004e-06 -2.15705899163381e-05 1.16686236710272e-05 2.02342011355929e-05 -6.81596981603695e-05 -0.000309010966749481 1.7172050795061e-05 -0.000419724124147262 2.02342011355929e-05 0.00148459660979979 2897 2822 0 78 195 2896 2822 0 1 219 0 0 0 0 0 0 0 0 3685 0 0 0 0 0 3599 +795 796 0.913290092022709 0.0104200767135122 0.407176411171418 0.0588328607140193 0.00899792989368022 0.998912604537667 -0.045745445165654 -0.00115287109414539 -0.407210320437461 0.0454426066270407 0.912203225401095 -0.113086504113222 0.000166206645232496 0.000571674779316582 -3.62874256310519e-05 -1.27838304534863e-05 1.68531416756187e-05 0.000394102514985993 0.000571674779316582 0.00288147311968702 -0.00022706257768395 -2.57995041726019e-06 7.48793943294524e-05 0.00228243813988496 -3.62874256310519e-05 -0.00022706257768395 3.44415881789788e-05 -5.32025475765291e-06 -3.96876169866832e-06 -0.000185786516636831 -1.27838304534863e-05 -2.57995041726019e-06 -5.32025475765291e-06 0.00124438202452072 -9.03641586185573e-05 0.000569431678836676 1.68531416756187e-05 7.48793943294524e-05 -3.96876169866832e-06 -9.03641586185573e-05 2.13655981484325e-05 7.20186032118928e-05 0.000394102514985993 0.00228243813988496 -0.000185786516636831 0.000569431678836676 7.20186032118928e-05 0.00431220067624199 1096 1029 0 73 43 1083 1029 0 20 46 0 0 0 0 0 0 0 0 3459 0 0 0 0 0 3296 +790 791 0.999447264849886 -0.0262983095608479 0.0203362655943501 0.148359679395913 0.0264227832258818 0.999633584825311 -0.00587644585572774 0.0026464038402884 -0.0201742734858083 0.00641053847496901 0.999775926738477 -0.0117648978624229 5.99859789900903e-05 -3.00360916497966e-05 -3.82830043679531e-06 -3.4241242881184e-05 -8.96895575185902e-07 1.89372379992583e-05 -3.00360916497966e-05 0.000198544297674867 -1.45659818217504e-06 6.77732670551835e-05 -4.58953607392181e-06 -0.000187907628358573 -3.82830043679531e-06 -1.45659818217504e-06 1.69365648609332e-05 -7.75421143692633e-06 4.47803839554448e-06 3.06285209033499e-06 -3.4241242881184e-05 6.77732670551835e-05 -7.75421143692633e-06 0.000194524865821492 -8.1169485893657e-07 -4.2066203063941e-05 -8.96895575185902e-07 -4.58953607392181e-06 4.47803839554448e-06 -8.1169485893657e-07 1.07901373230704e-05 8.18725905057038e-06 1.89372379992583e-05 -0.000187907628358573 3.06285209033499e-06 -4.2066203063941e-05 8.18725905057038e-06 0.000315405829683985 3157 3104 0 110 197 3157 3104 0 19 226 0 0 0 0 0 0 0 0 3657 0 0 0 0 0 3622 +787 788 0.998698797395208 0.0261565037280205 -0.0437784124208576 0.149133787184343 -0.0270953164252972 0.999412451811082 -0.0209903547558185 0.000393194581556006 0.043203656201503 0.022149231988675 0.998820732470614 -0.035521611672938 5.497552487941e-05 4.86155560542046e-06 -9.19456606380524e-06 -6.57134051449068e-06 2.59652433487288e-06 7.17333773708615e-06 4.86155560542046e-06 2.02265748957955e-05 3.03051074296003e-06 -1.6567001453958e-06 1.31351911303616e-06 2.18482916865885e-05 -9.19456606380524e-06 3.03051074296003e-06 2.04315817357252e-05 -6.08950284396107e-06 -1.04998496501338e-07 -6.13634833674852e-06 -6.57134051449068e-06 -1.6567001453958e-06 -6.08950284396107e-06 0.000104917544408154 4.29810875312674e-06 4.70123509642174e-05 2.59652433487288e-06 1.31351911303616e-06 -1.04998496501338e-07 4.29810875312674e-06 1.38338008060996e-05 1.41661619291723e-05 7.17333773708615e-06 2.18482916865885e-05 -6.13634833674852e-06 4.70123509642174e-05 1.41661619291723e-05 0.000421550764490827 3531 3477 0 259 64 3531 3477 0 157 80 0 0 0 0 0 0 0 0 3363 0 0 0 0 0 3797 +796 797 0.999657810187559 0.0256541066474021 -0.0051116869170899 0.145209557629411 -0.0255581907083903 0.999510903438982 0.0180203439008307 -0.0167436709229598 0.00557148263285253 -0.0178835320536626 0.999824553540549 0.0378374177528827 6.96403204465899e-05 2.75090108744655e-05 -6.77175923866649e-06 3.27004737744795e-05 -6.0271480919198e-07 -3.41516418042563e-05 2.75090108744655e-05 5.30634697582352e-05 -3.14771568170256e-06 1.07053443944109e-05 8.7410517053914e-07 -4.64147331522305e-05 -6.77175923866649e-06 -3.14771568170256e-06 1.7250189654482e-05 2.16502276768729e-06 3.22154489993359e-06 4.35499737814429e-06 3.27004737744795e-05 1.07053443944109e-05 2.16502276768729e-06 9.80153427412533e-05 -2.35789657040909e-06 -2.55380839556761e-05 -6.0271480919198e-07 8.7410517053914e-07 3.22154489993359e-06 -2.35789657040909e-06 1.12011718077354e-05 8.71702961570038e-07 -3.41516418042563e-05 -4.64147331522305e-05 4.35499737814429e-06 -2.55380839556761e-05 8.71702961570038e-07 0.000100765817088727 3115 3036 0 295 58 3115 3036 0 169 72 0 0 0 0 0 0 0 0 3308 0 0 0 0 0 3757 +791 792 0.99947826772524 -0.0313076137199916 -0.00793887070774146 0.140695694602098 0.031174406895427 0.999379706934993 -0.0163816275517846 0.00390289269595533 0.00844681594879351 0.0161255911422444 0.999834294576176 0.00309139301710801 4.53698148292199e-05 4.16050381487449e-06 -8.75746820855516e-06 -1.04118331739566e-07 -5.58082155537287e-08 1.410431783573e-05 4.16050381487449e-06 2.49372961354339e-05 -9.89817350491538e-07 4.29540732031206e-06 1.02312435034149e-06 4.22460794311495e-06 -8.75746820855516e-06 -9.89817350491538e-07 1.33453433547474e-05 -4.60239478195284e-07 4.37555876455418e-06 2.01219384972811e-06 -1.04118331739566e-07 4.29540732031206e-06 -4.60239478195284e-07 8.39113544581533e-05 8.34410512749377e-07 3.98189734307507e-06 -5.58082155537287e-08 1.02312435034149e-06 4.37555876455418e-06 8.34410512749377e-07 1.10467155413e-05 1.14394358331688e-05 1.410431783573e-05 4.22460794311495e-06 2.01219384972811e-06 3.98189734307507e-06 1.14394358331688e-05 0.000213237980135993 3374 3320 0 85 196 3374 3320 0 1 227 0 0 0 0 0 0 0 0 3670 0 0 0 0 0 3613 +802 803 0.99948837147199 -0.0319678657415745 -0.0010251108220839 0.164060460698862 0.031984207035641 0.998895792377835 0.0344123011459413 -0.0140679589673148 -7.61089359914934e-05 -0.0344274821877285 0.999407195630311 -0.035074738671799 7.38734542906141e-05 2.30037328705174e-05 4.30353372022716e-06 2.45015034011006e-05 -4.8200586896578e-06 -6.43802275183326e-05 2.30037328705174e-05 8.48022331161264e-05 7.52037541969183e-06 3.35314978892077e-05 -5.71629613616898e-06 -7.3240421128816e-05 4.30353372022716e-06 7.52037541969183e-06 1.48961688768545e-05 3.11746925679277e-06 3.53385552766619e-06 -9.52190018048081e-06 2.45015034011006e-05 3.35314978892077e-05 3.11746925679277e-06 0.000109885502049403 -9.87192736967175e-06 -7.23181640537303e-05 -4.8200586896578e-06 -5.71629613616898e-06 3.53385552766619e-06 -9.87192736967175e-06 1.27111022141602e-05 1.63104228660123e-05 -6.43802275183326e-05 -7.3240421128816e-05 -9.52190018048081e-06 -7.23181640537303e-05 1.63104228660123e-05 0.000316095033237829 2743 2662 0 141 118 2743 2662 0 51 144 0 0 0 0 0 0 0 0 3645 0 0 0 0 0 3564 +803 804 0.999066810258081 -0.0327681063679444 -0.0281382274815501 0.145458777707651 0.033222590305101 0.99932246258812 0.0158390422764494 -0.00663026858653831 0.0276001473576463 -0.0167590862482065 0.999478546490099 0.00195321941436602 7.94385648012952e-05 1.24251764138466e-05 4.86563476625356e-06 -4.01665119054812e-06 3.65069885971977e-07 7.69556488722247e-06 1.24251764138466e-05 3.45261128952332e-05 3.02122807715279e-06 2.66344772994282e-06 4.33232492098602e-07 -2.11283573783183e-05 4.86563476625356e-06 3.02122807715279e-06 1.85234582090546e-05 -4.94193247694042e-06 5.44834899538229e-06 6.99829488647553e-08 -4.01665119054812e-06 2.66344772994282e-06 -4.94193247694042e-06 8.79537623619983e-05 -4.48038744938084e-06 -3.17735324504662e-05 3.65069885971977e-07 4.33232492098602e-07 5.44834899538229e-06 -4.48038744938084e-06 1.21058393982926e-05 5.71605866231546e-06 7.69556488722247e-06 -2.11283573783183e-05 6.99829488647553e-08 -3.17735324504662e-05 5.71605866231546e-06 0.00017965123697649 3352 3223 0 104 166 3352 3223 0 10 119 0 0 0 0 0 0 0 0 3680 0 12 0 0 0 3552 +794 795 0.999790407614372 -0.0159875829103617 0.0127881990511748 0.167091068069381 0.0163264003803375 0.999506297510886 -0.0268441778920882 -0.00266948316767194 -0.0123527119657617 0.0270473368146565 0.999557828281248 -0.0990277657182515 5.56055098264908e-05 1.03170467198019e-05 1.09485994619444e-05 8.4188736641591e-07 9.19398520734385e-07 -1.46856770380537e-05 1.03170467198019e-05 6.66356823044298e-05 -4.52352816583647e-07 9.75813182562565e-06 -1.1048821002038e-06 -4.13624747446278e-06 1.09485994619444e-05 -4.52352816583647e-07 1.74618320781954e-05 -1.26246487444465e-06 4.16810926690558e-06 -6.29804303256557e-06 8.4188736641591e-07 9.75813182562565e-06 -1.26246487444465e-06 9.45715788037674e-05 -2.64218240257918e-06 8.06800313336952e-06 9.19398520734385e-07 -1.1048821002038e-06 4.16810926690558e-06 -2.64218240257918e-06 1.06936270587848e-05 1.16552397867898e-05 -1.46856770380537e-05 -4.13624747446278e-06 -6.29804303256557e-06 8.06800313336952e-06 1.16552397867898e-05 0.000583489585123166 3068 2981 0 205 196 3068 2981 0 93 215 0 0 0 0 0 0 0 0 3369 0 0 0 0 0 3604 +800 801 0.943897023878939 -0.0465409614410553 -0.326943951191367 0.0485986875328395 0.043122337418539 0.998912973656206 -0.017701273312298 -0.00997904208210602 0.327412388782163 0.00260959181812133 0.944877937991199 0.074524184177727 9.37773508442835e-05 -0.000229215462123761 1.123258212614e-06 0.00015562985166348 -1.83086397954766e-06 -2.29960411683044e-06 -0.000229215462123761 0.0123653195728786 -0.00110661205291212 -0.0012994092263032 -0.000309521317413006 -0.00444337539063688 1.123258212614e-06 -0.00110661205291212 0.000125861752173459 0.000135061222467207 2.62306397981403e-05 0.000390447060986704 0.00015562985166348 -0.0012994092263032 0.000135061222467207 0.00310832695058397 -5.62074154471822e-05 0.000380479827373801 -1.83086397954766e-06 -0.000309521317413006 2.62306397981403e-05 -5.62074154471822e-05 2.51115913234589e-05 0.000138527901421165 -2.29960411683044e-06 -0.00444337539063688 0.000390447060986704 0.000380479827373801 0.000138527901421165 0.0020949082733844 1092 1084 0 0 51 1045 1061 0 0 72 0 0 0 0 0 26 1 0 3683 0 0 0 0 0 3537 +799 800 0.999811125405809 0.0150923489398431 0.0122447751407807 0.152502333109895 -0.014936990588485 0.999808014565532 -0.0126814952859691 -0.0180593354513446 -0.0124338178742402 0.0124961999826573 0.999844610506584 0.0255814000330433 8.25354607157037e-05 3.13169051960325e-07 -5.0581985810362e-06 -9.36765868657066e-07 1.60055307037572e-06 -7.02649786460814e-06 3.13169051960325e-07 3.21762713186234e-05 7.48564370590765e-07 2.79997277322166e-06 2.18777053723396e-07 -5.49709816217824e-06 -5.0581985810362e-06 7.48564370590765e-07 1.67123081970944e-05 -1.19697322211484e-06 4.86916351997787e-06 -3.7780854561083e-06 -9.36765868657066e-07 2.79997277322166e-06 -1.19697322211484e-06 8.61471337550679e-05 2.59869163924282e-06 2.96002220079417e-05 1.60055307037572e-06 2.18777053723396e-07 4.86916351997787e-06 2.59869163924282e-06 1.1599311674156e-05 8.26714106784647e-06 -7.02649786460814e-06 -5.49709816217824e-06 -3.7780854561083e-06 2.96002220079417e-05 8.26714106784647e-06 0.000144796515975117 3075 3023 0 265 80 3075 3023 0 164 109 0 0 0 0 0 0 0 0 3526 0 0 0 0 0 3740 +805 806 0.998996144718717 -0.00897135143439681 0.0438886966151891 0.139027534314809 0.00942778245676772 0.99990349475774 -0.0102038271842752 -0.0124568869379519 -0.0437929190062438 0.0106073571024661 0.998984316303421 0.0277016223647093 0.000110755207317437 2.48371201886892e-05 2.65417308392164e-06 1.3511719419958e-05 3.83356070289627e-06 -1.89197102370504e-05 2.48371201886892e-05 3.75815218610859e-05 -4.67005423430699e-07 6.88830947130147e-06 -2.3678942363931e-07 -3.34473311802847e-05 2.65417308392164e-06 -4.67005423430699e-07 1.78585366408161e-05 -6.87331604164975e-08 5.20195592739211e-06 1.26252545190468e-06 1.3511719419958e-05 6.88830947130147e-06 -6.87331604164975e-08 8.12556895714126e-05 -6.3856225956242e-06 -1.43605080887104e-05 3.83356070289627e-06 -2.3678942363931e-07 5.20195592739211e-06 -6.3856225956242e-06 1.25350730972974e-05 3.036698181397e-06 -1.89197102370504e-05 -3.34473311802847e-05 1.26252545190468e-06 -1.43605080887104e-05 3.036698181397e-06 0.00019144037580379 3252 3127 0 177 76 3248 3127 0 72 60 0 0 0 0 0 0 0 0 3608 0 37 6 0 0 3208 +804 805 0.999656869381891 -0.0251772174330761 0.0072285005309242 0.157550486184909 0.0252964716275602 0.999536967388172 -0.0169097412059602 -0.00629289486566799 -0.00679941326836426 0.0170867945145985 0.999830890417186 -0.0519971809747519 8.6315618259935e-05 1.14516488343527e-05 -9.56146238082329e-07 1.98049789384545e-05 -2.1921765024017e-06 -1.39668491774823e-05 1.14516488343527e-05 4.26581978554459e-05 1.29400607090597e-06 3.42229754342314e-06 3.21774823429574e-07 -3.16489572578768e-05 -9.56146238082329e-07 1.29400607090597e-06 1.38853072837538e-05 1.61232761140141e-06 5.01607411015071e-06 -4.0500994187023e-06 1.98049789384545e-05 3.42229754342314e-06 1.61232761140141e-06 6.40660238141776e-05 -2.5839506029481e-06 1.34399216388579e-06 -2.1921765024017e-06 3.21774823429574e-07 5.01607411015071e-06 -2.5839506029481e-06 1.10624208357294e-05 4.35095175301513e-06 -1.39668491774823e-05 -3.16489572578768e-05 -4.0500994187023e-06 1.34399216388579e-06 4.35095175301513e-06 0.00017037020905784 3154 3025 0 154 115 3154 3025 0 57 79 0 0 0 0 0 0 0 0 3628 0 24 0 0 0 3429 +797 798 0.999626573193535 0.026636800859717 0.00609877080322803 0.158101648251219 -0.0263172591386135 0.998522066143737 -0.0475508706068891 -0.01606536085288 -0.00735636029443823 0.0473726109054781 0.998850198828241 0.0221503913251679 4.92620427976718e-05 9.06799683337953e-06 -9.90466657716379e-07 -8.25805431071645e-06 2.13622454254926e-06 -1.06373839440206e-05 9.06799683337953e-06 2.14052700622849e-05 7.5138934811884e-07 -2.14572494555939e-06 9.69608818570811e-07 -1.25745135059214e-05 -9.90466657716379e-07 7.5138934811884e-07 1.33790355926911e-05 -1.74202185466853e-06 3.6652573071193e-06 3.17628478544859e-06 -8.25805431071645e-06 -2.14572494555939e-06 -1.74202185466853e-06 7.08926669836965e-05 -4.02356020633761e-07 2.76249496718267e-06 2.13622454254926e-06 9.69608818570811e-07 3.6652573071193e-06 -4.02356020633761e-07 1.04082167583048e-05 1.60569742396075e-06 -1.06373839440206e-05 -1.25745135059214e-05 3.17628478544859e-06 2.76249496718267e-06 1.60569742396075e-06 0.000119794070363149 3386 3317 0 330 60 3386 3317 0 207 78 0 0 0 0 0 0 0 0 3465 0 0 0 0 0 3770 +798 799 0.999407221214964 0.0169363452714958 -0.0299727608376249 0.145455707232896 -0.0170917135159707 0.999841746816767 -0.00493504320991877 -0.019604336218534 0.0298844359570791 0.00544440366252008 0.999538533002248 0.0621587451409506 6.38113313604188e-05 5.7175537370442e-05 -2.06032240445323e-06 3.16067605656105e-05 -3.67761736251784e-06 -4.09708376583716e-05 5.7175537370442e-05 0.000175645719176875 -3.88935285169535e-06 0.000143714504285861 -1.53890256490717e-05 -0.000262363936103934 -2.06032240445323e-06 -3.88935285169535e-06 1.74102359292944e-05 -5.73500438878813e-06 4.81229506806765e-06 9.78312644628357e-06 3.16067605656105e-05 0.000143714504285861 -5.73500438878813e-06 0.00027485605054464 -2.28538262493491e-05 -0.000350412388881219 -3.67761736251784e-06 -1.53890256490717e-05 4.81229506806765e-06 -2.28538262493491e-05 1.63476496141554e-05 0.000100043440720845 -4.09708376583716e-05 -0.000262363936103934 9.78312644628357e-06 -0.000350412388881219 0.000100043440720845 0.00174264691065692 3012 2956 0 271 67 3012 2956 0 160 85 0 0 0 0 0 0 0 0 3552 0 0 0 0 0 3738 +808 809 0.999132791334021 0.0213665034354805 -0.035737064961037 0.149830240548965 -0.0224409336382402 0.999299786617435 -0.0299389539528964 -0.0261411238175653 0.0350723506274084 0.0307149637357943 0.998912669468246 -0.0566368082466346 4.50071860035682e-05 2.10424684070913e-05 -1.44801431074892e-06 2.10520553363351e-05 -5.95144637882792e-06 -3.80832877633645e-05 2.10424684070913e-05 5.09242252878322e-05 5.20820641427624e-07 2.37345819339948e-05 -6.19404603631537e-06 -4.78549766088774e-05 -1.44801431074892e-06 5.20820641427624e-07 1.07835733633378e-05 2.08899939432636e-06 6.03924520053796e-06 -1.00261156991685e-06 2.10520553363351e-05 2.37345819339948e-05 2.08899939432636e-06 9.44570082950192e-05 -7.70652004634907e-06 -7.2537216508649e-05 -5.95144637882792e-06 -6.19404603631537e-06 6.03924520053796e-06 -7.70652004634907e-06 1.37522327994843e-05 2.16009380365517e-05 -3.80832877633645e-05 -4.78549766088774e-05 -1.00261156991685e-06 -7.2537216508649e-05 2.16009380365517e-05 0.000257815794713725 3150 3039 0 300 91 3091 3012 0 195 31 0 0 0 0 0 0 0 0 3529 0 150 82 0 0 3492 +801 802 0.999767108479503 -0.0171464313335033 -0.0131045295626622 0.138510741957717 0.0169580212644275 0.999753137104971 -0.01435584771317 -0.0137139866586603 0.0133474460976045 0.0141302774669841 0.999811072623912 -0.019758164340772 6.16057091958077e-05 5.11164737569795e-06 -6.11915405504696e-06 -1.9396442802545e-05 1.04927649583016e-06 -4.14826816722069e-06 5.11164737569795e-06 4.56650232452673e-05 1.37854974410389e-07 1.42838523154421e-05 -7.56969785717006e-07 -7.729635018367e-06 -6.11915405504696e-06 1.37854974410389e-07 1.674840287318e-05 -4.38733524238074e-06 4.95715396032343e-06 -2.31771780294287e-06 -1.9396442802545e-05 1.42838523154421e-05 -4.38733524238074e-06 7.86284195795257e-05 -1.19735905352535e-06 4.08608380603487e-06 1.04927649583016e-06 -7.56969785717006e-07 4.95715396032343e-06 -1.19735905352535e-06 1.27476676767269e-05 1.41417474394341e-05 -4.14826816722069e-06 -7.729635018367e-06 -2.31771780294287e-06 4.08608380603487e-06 1.41417474394341e-05 0.000229976814352144 3306 3254 0 149 146 3306 3254 0 58 177 0 0 0 0 0 0 0 0 3660 0 0 0 0 0 3640 +810 811 0.999537168957504 0.0232015756770105 0.0196757403550917 0.115614388721844 -0.0234518152213747 0.999645761917033 0.0125842379243628 -0.0194287557765665 -0.0193767963100077 -0.0130398453755566 0.999727213892541 0.0203319171167355 4.19126041998822e-05 7.05422382828683e-06 -5.3889387178246e-06 3.40510715444644e-06 -5.39759715059161e-07 -1.41641379306062e-05 7.05422382828683e-06 8.27697760794621e-05 -1.20358738439701e-06 5.68688940918588e-05 -6.49762540941903e-06 -5.70530079532652e-05 -5.3889387178246e-06 -1.20358738439701e-06 1.27183168368516e-05 1.17814053207019e-06 3.95569704464587e-06 -5.8823756235488e-07 3.40510715444644e-06 5.68688940918588e-05 1.17814053207019e-06 0.000124768728547228 -4.08113581380724e-06 -2.32762119088337e-05 -5.39759715059161e-07 -6.49762540941903e-06 3.95569704464587e-06 -4.08113581380724e-06 1.39239848557212e-05 2.13957138833445e-05 -1.41641379306062e-05 -5.70530079532652e-05 -5.8823756235488e-07 -2.32762119088337e-05 2.13957138833445e-05 0.000374472490209632 3075 2983 0 208 78 3006 2946 0 129 7 0 0 0 0 0 0 0 0 3613 0 125 68 0 0 3329 +811 812 0.999942760200412 -0.00410919707151391 0.00987880671984762 0.141615727160373 0.00396216179421011 0.999881768194 0.0148576884862997 -0.00888051578931569 -0.00993869190070538 -0.0148176966046306 0.999840816465619 0.0535526606310044 3.39621991440215e-05 -2.03032627920822e-05 -2.95537605901433e-06 -1.44219827866743e-05 -9.68966816070559e-07 2.30765018696323e-05 -2.03032627920822e-05 0.000124301085242264 -2.18189230913818e-07 5.65496943039334e-05 -4.83153444925332e-06 -0.000115889401111322 -2.95537605901433e-06 -2.18189230913818e-07 1.11385613355145e-05 3.45236971641959e-06 5.56019447141562e-06 1.04257266219091e-06 -1.44219827866743e-05 5.65496943039334e-05 3.45236971641959e-06 0.000125815173459637 -2.47193979508838e-06 -7.54582325353305e-05 -9.68966816070559e-07 -4.83153444925332e-06 5.56019447141562e-06 -2.47193979508838e-06 1.18886029942448e-05 7.20634343806782e-06 2.30765018696323e-05 -0.000115889401111322 1.04257266219091e-06 -7.54582325353305e-05 7.20634343806782e-06 0.000233374245952279 2540 2433 0 157 103 2519 2433 0 81 59 0 0 0 0 0 0 0 0 3656 0 67 25 0 0 3361 +814 815 0.999328894450464 -0.0355415383932902 -0.0088633946686198 0.15048907965681 0.0356596790613242 0.999272159897248 0.0135476102516939 0.00169158610562559 0.00837544062463555 -0.0138545841845479 0.999868942657695 -0.0114369655625193 3.70317276194938e-05 1.02053530026828e-06 -4.39342426367702e-07 -8.86589346424342e-07 -7.38512491033093e-07 -1.94623248375615e-05 1.02053530026828e-06 5.9664068216923e-05 1.13691534751026e-06 4.15816730887576e-06 3.43642345728254e-07 -1.87539956720154e-05 -4.39342426367702e-07 1.13691534751026e-06 1.07242464425945e-05 2.4261677277969e-07 6.00887548568023e-06 -7.60130179316427e-07 -8.86589346424342e-07 4.15816730887576e-06 2.4261677277969e-07 5.26166115606552e-05 -2.65483602559705e-06 -1.33928089017389e-06 -7.38512491033093e-07 3.43642345728254e-07 6.00887548568023e-06 -2.65483602559705e-06 1.25778339033474e-05 5.12280248827603e-06 -1.94623248375615e-05 -1.87539956720154e-05 -7.60130179316427e-07 -1.33928089017389e-06 5.12280248827603e-06 0.000224917713187339 3135 3009 0 84 190 3135 3009 0 3 140 0 0 0 0 0 0 0 0 3702 0 8 0 0 0 2896 +806 807 0.999758633471379 0.0216379344827719 -0.00380454869340825 0.139541659291627 -0.0215967558693314 0.99971109159969 0.0105505198201904 -0.0195575627288683 0.0040317409839598 -0.0104658073685218 0.999937103992428 0.0828443888946608 5.53193479300717e-05 -9.67293858002836e-06 -1.61386970974339e-06 -7.32198478930951e-06 -2.98871607530975e-06 9.36391573818562e-06 -9.67293858002836e-06 5.25549151592396e-05 8.493552896974e-07 2.67621515446281e-05 -5.89487452766482e-06 -4.19539170556962e-05 -1.61386970974339e-06 8.493552896974e-07 1.13644952328995e-05 2.47552383368942e-06 4.68355256959921e-06 -1.67220753099239e-06 -7.32198478930951e-06 2.67621515446281e-05 2.47552383368942e-06 8.6758281790391e-05 -9.86843180180186e-06 -2.63957780497837e-05 -2.98871607530975e-06 -5.89487452766482e-06 4.68355256959921e-06 -9.86843180180186e-06 1.36562191527828e-05 7.79973449783371e-06 9.36391573818562e-06 -4.19539170556962e-05 -1.67220753099239e-06 -2.63957780497837e-05 7.79973449783371e-06 0.000114456685783689 3414 3297 0 273 90 3354 3264 0 163 30 0 0 0 0 0 0 0 0 3534 0 145 91 0 0 3523 +807 808 0.99910137578148 0.0379878634631606 0.0187979557680408 0.147047518347863 -0.0379664606171065 0.999277896792381 -0.00149427253395759 -0.0253356388868395 -0.0188411459248807 0.000779237897120075 0.999822186195394 -0.029909585229009 3.94240892837615e-05 1.68213791321415e-05 1.79641821289065e-06 8.59860520969384e-06 -2.000948337742e-06 -1.12475447544283e-05 1.68213791321415e-05 2.9240799895251e-05 1.71287358504029e-06 9.70222617854482e-06 -9.22888622526119e-07 -1.39399148348603e-05 1.79641821289065e-06 1.71287358504029e-06 1.15897721217947e-05 2.36380112187665e-06 3.80940633082575e-06 -5.05325377808282e-06 8.59860520969384e-06 9.70222617854482e-06 2.36380112187665e-06 9.35235150551881e-05 -7.16918663947012e-06 -2.28405494072463e-05 -2.000948337742e-06 -9.22888622526119e-07 3.80940633082575e-06 -7.16918663947012e-06 1.38084516391967e-05 7.71954051217772e-06 -1.12475447544283e-05 -1.39399148348603e-05 -5.05325377808282e-06 -2.28405494072463e-05 7.71954051217772e-06 0.000182917361496155 3331 3246 0 347 45 3278 3193 0 229 0 0 0 0 0 0 0 0 0 3482 0 181 120 0 0 3500 +817 818 0.999432867173026 0.0336701171441511 0.000516938877470724 0.136779093266275 -0.033669138943065 0.998905203770642 0.0324774223540736 -0.0208178092562035 0.00057714568046487 -0.0324764082286118 0.999472335690905 0.0316935030186033 1.84775116401466e-05 4.76327631569608e-07 6.36036797884969e-07 5.69317141667344e-06 -1.09716119533549e-06 -5.24736959308996e-06 4.76327631569608e-07 1.85247744277596e-05 2.62181082655228e-06 -7.41296727525051e-07 2.29953341403392e-07 -4.13515901658898e-06 6.36036797884969e-07 2.62181082655228e-06 1.01634107980544e-05 3.05400281791552e-06 6.53736417232273e-06 -1.21256262429784e-06 5.69317141667344e-06 -7.41296727525051e-07 3.05400281791552e-06 3.61599684524917e-05 1.81752220207019e-06 -8.83262683971249e-06 -1.09716119533549e-06 2.29953341403392e-07 6.53736417232273e-06 1.81752220207019e-06 1.36522881151274e-05 -3.02566206967423e-06 -5.24736959308996e-06 -4.13515901658898e-06 -1.21256262429784e-06 -8.83262683971249e-06 -3.02566206967423e-06 5.69525870006269e-05 3513 3497 0 280 71 3445 3437 0 185 4 0 0 0 0 0 0 0 0 3537 0 179 116 0 0 3636 +809 810 0.998883206261573 0.0300553413315057 -0.0364556813959864 0.142710552012015 -0.0295923991593774 0.999475247474788 0.0131726837509495 -0.02776532404355 0.0368324606915023 -0.012079161504721 0.999248449434249 0.0195784679768555 5.15894913968579e-05 1.3700537756156e-05 -4.68583263900524e-06 8.85465359580945e-06 -7.86471685026605e-07 -9.49985831282493e-06 1.3700537756156e-05 3.33594122896987e-05 -2.42346397605495e-06 3.98515235783874e-06 -1.16774695671581e-08 -1.50436026398925e-05 -4.68583263900524e-06 -2.42346397605495e-06 1.32392385576797e-05 -1.06464291716068e-07 6.42132257114855e-06 7.54127224429982e-07 8.85465359580945e-06 3.98515235783874e-06 -1.06464291716068e-07 6.20817055059486e-05 1.2234617051321e-06 -5.3797128596747e-06 -7.86471685026605e-07 -1.16774695671581e-08 6.42132257114855e-06 1.2234617051321e-06 1.15430612352979e-05 5.53680749269884e-06 -9.49985831282493e-06 -1.50436026398925e-05 7.54127224429982e-07 -5.3797128596747e-06 5.53680749269884e-06 0.000121977961351456 3093 3007 0 299 61 3036 2963 0 197 5 0 0 0 0 0 0 0 0 3540 0 153 95 0 0 2851 +819 820 0.998317893611004 0.029271365655156 -0.0500456836177653 0.153832821479702 -0.0301315836029261 0.999409392233651 -0.0165213312037787 -0.022299286892042 0.0495325243215726 0.0180014962669003 0.998610271911162 -0.00901238947537171 2.67428333937415e-05 -4.99715270576128e-07 1.87687069067489e-06 -8.09241553590669e-07 4.51687375850561e-07 5.94361866419667e-07 -4.99715270576128e-07 4.09798215360166e-05 1.19294358130756e-06 3.38876367674891e-06 8.40563826276028e-07 -2.51175323943092e-05 1.87687069067489e-06 1.19294358130756e-06 9.88590530068855e-06 -7.29967394737171e-08 6.0093101020924e-06 -1.39399999672846e-06 -8.09241553590669e-07 3.38876367674891e-06 -7.29967394737171e-08 4.1616371507699e-05 2.3861055640511e-06 -1.39279271229143e-05 4.51687375850561e-07 8.40563826276028e-07 6.0093101020924e-06 2.3861055640511e-06 1.30269239144667e-05 -5.66479695031398e-07 5.94361866419667e-07 -2.51175323943092e-05 -1.39399999672846e-06 -1.39279271229143e-05 -5.66479695031398e-07 0.000143364563679037 3268 3194 0 116 57 3217 3162 0 158 10 0 0 0 0 0 0 0 0 3466 0 111 63 0 0 3269 +820 821 0.999179317847426 0.0402725570530384 -0.00433727268698744 0.14392214092193 -0.0403148345175992 0.999135510292696 -0.0101462401890218 -0.0200761812385079 0.00392490812250555 0.0103127697814165 0.99993911908459 0.0422396428651341 3.20066493267944e-05 -1.90023359068969e-06 -3.49547009033313e-06 8.07763193298691e-06 3.96251507615647e-07 -2.58212426281517e-07 -1.90023359068969e-06 1.88891801051462e-05 -1.78454111952733e-07 2.8286260920142e-07 3.2008437624932e-07 -1.53084594530343e-06 -3.49547009033313e-06 -1.78454111952733e-07 1.00539476547652e-05 -1.06908981890566e-07 4.20892219143482e-06 -2.29304158036056e-06 8.07763193298691e-06 2.8286260920142e-07 -1.06908981890566e-07 3.75675024314457e-05 7.20253949586162e-06 -3.03527996216125e-06 3.96251507615647e-07 3.2008437624932e-07 4.20892219143482e-06 7.20253949586162e-06 1.45045397155729e-05 -6.62586061448979e-07 -2.58212426281517e-07 -1.53084594530343e-06 -2.29304158036056e-06 -3.03527996216125e-06 -6.62586061448979e-07 0.000133501867220864 3269 3210 0 277 46 3216 3161 0 221 2 0 0 0 0 0 0 0 0 3184 0 164 113 0 0 2381 +812 813 0.999877307862493 -0.0115548067037956 -0.0105761837961649 0.145738934154253 0.0114723418576912 0.999903573035971 -0.00782496020433201 -0.00238013332960903 0.0106655798694964 0.00770266654717926 0.9999134534219 0.0230002577349246 1.70877140328089e-05 1.1486471590567e-06 -6.7952466555603e-07 -3.3610659623703e-06 -6.34241645132726e-07 3.07054858530798e-07 1.1486471590567e-06 2.1882190695029e-05 1.41510508500716e-07 4.98153657343687e-06 1.28957761756385e-07 -1.22618151111082e-05 -6.7952466555603e-07 1.41510508500716e-07 9.3254789631836e-06 -7.17749483702436e-07 5.64708451939203e-06 1.76173292211974e-06 -3.3610659623703e-06 4.98153657343687e-06 -7.17749483702436e-07 5.17711331587601e-05 -9.10688436378279e-09 -1.26869889534171e-05 -6.34241645132726e-07 1.28957761756385e-07 5.64708451939203e-06 -9.10688436378279e-09 1.07049715564956e-05 -1.66378907835864e-06 3.07054858530798e-07 -1.22618151111082e-05 1.76173292211974e-06 -1.26869889534171e-05 -1.66378907835864e-06 7.5756517362261e-05 3431 3298 0 133 188 3417 3298 0 59 119 0 0 0 0 0 0 0 0 3670 0 78 12 0 0 3511 +813 814 0.999298039015941 -0.0367071842760731 -0.00748410591973053 0.149281969045077 0.0368378592370284 0.999156565031276 0.0181419591481998 0.00255575048117529 0.00681185332550623 -0.0184049226410894 0.999807410193007 -0.0132806041401273 1.84571894046594e-05 -1.36439332254844e-06 -3.97624761811326e-06 1.43094857846596e-06 -1.61710722254722e-06 6.65303315413227e-08 -1.36439332254844e-06 2.46965350618239e-05 2.24500395671416e-07 6.25645759149099e-06 1.86590162803412e-07 -8.94728064872543e-06 -3.97624761811326e-06 2.24500395671416e-07 1.03980867938702e-05 -2.958060691863e-06 5.42057551512925e-06 -2.20927287821704e-06 1.43094857846596e-06 6.25645759149099e-06 -2.958060691863e-06 6.35585948159946e-05 1.44065492052007e-06 -5.79645480057501e-06 -1.61710722254722e-06 1.86590162803412e-07 5.42057551512925e-06 1.44065492052007e-06 1.24062955318215e-05 6.14817248425666e-07 6.65303315413227e-08 -8.94728064872543e-06 -2.20927287821704e-06 -5.79645480057501e-06 6.14817248425666e-07 8.03079583686713e-05 3444 3311 0 71 223 3444 3311 0 3 155 0 0 0 0 0 0 0 0 3721 0 14 0 0 0 3394 +822 823 0.99980443522991 -0.0181736597083165 0.00779803740732052 0.15351698197556 0.0182929768015226 0.999712321817277 -0.0155125950907197 0.0075672182900006 -0.00751387345771873 0.0156522106910168 0.999849263642348 0.0112985439652219 4.46483083288293e-05 -1.53644874036679e-05 -1.03439039676289e-07 6.73616371525816e-06 -9.20945509702257e-06 3.10604822804444e-06 -1.53644874036679e-05 5.87041342107685e-05 -2.65114262499627e-06 8.71858005158652e-06 3.10210125181575e-06 -1.17568487483285e-05 -1.03439039676289e-07 -2.65114262499627e-06 9.67197764176683e-06 6.86247364059175e-07 4.32089978404713e-06 6.84753177451948e-07 6.73616371525816e-06 8.71858005158652e-06 6.86247364059175e-07 4.41845242902616e-05 2.68828551072927e-06 -1.01843212655437e-05 -9.20945509702257e-06 3.10210125181575e-06 4.32089978404713e-06 2.68828551072927e-06 1.86738493117821e-05 8.59868446937435e-06 3.10604822804444e-06 -1.17568487483285e-05 6.84753177451948e-07 -1.01843212655437e-05 8.59868446937435e-06 0.00013012625592486 3494 3444 0 83 194 3494 3444 0 45 140 0 0 0 0 0 0 0 0 3190 0 38 1 0 0 3161 +816 817 0.999560732714983 0.00595538221169204 0.029032310224966 0.142688736252025 -0.00613262536445651 0.999963075674067 0.00601981682443385 -0.0114004395386093 -0.0289953879164468 -0.00619521679791548 0.999560346736705 0.0263325787603194 3.46287820343191e-05 -7.5944496371913e-06 -7.05027949754446e-07 1.41385706192747e-06 -5.52594412118652e-06 2.55268508941096e-05 -7.5944496371913e-06 4.83561158663858e-05 2.46718518270676e-07 7.53252353544888e-06 3.64945953148154e-06 -3.18794225056027e-05 -7.05027949754446e-07 2.46718518270676e-07 9.39421611413489e-06 5.6533438045888e-06 5.72229223933868e-06 -1.35002208280832e-06 1.41385706192747e-06 7.53252353544888e-06 5.6533438045888e-06 3.55055665937905e-05 -1.34781845355464e-07 -2.60402891631122e-05 -5.52594412118652e-06 3.64945953148154e-06 5.72229223933868e-06 -1.34781845355464e-07 1.37779415708938e-05 -1.00686590026494e-05 2.55268508941096e-05 -3.18794225056027e-05 -1.35002208280832e-06 -2.60402891631122e-05 -1.00686590026494e-05 0.000243644146274429 3147 3007 0 206 126 3092 3007 0 115 66 0 0 0 0 0 0 0 0 3583 0 111 50 0 0 3257 +824 825 0.997712428008714 -0.0673136953481 -0.00622715147885452 0.15890146208945 0.0672539632285838 0.997692075309973 -0.00935025634558314 0.0129096741301703 0.00684217998928116 0.00891006634447793 0.999936895654286 -0.0354002910445681 5.24069589840186e-05 1.0197190590987e-05 3.26888249608318e-06 1.3398008833731e-05 -9.14577645494477e-06 1.33733084309811e-05 1.0197190590987e-05 8.11929129364532e-05 1.3022733636327e-07 1.83653915908406e-05 -6.01879776460117e-06 -4.97114761895391e-05 3.26888249608318e-06 1.3022733636327e-07 1.08311632337864e-05 2.48938373912991e-06 3.42025895395705e-06 -1.03909746909163e-06 1.3398008833731e-05 1.83653915908406e-05 2.48938373912991e-06 5.09327594536175e-05 -4.46668229405525e-06 -1.75762745749845e-05 -9.14577645494477e-06 -6.01879776460117e-06 3.42025895395705e-06 -4.46668229405525e-06 2.11764313176019e-05 5.05935151638708e-06 1.33733084309811e-05 -4.97114761895391e-05 -1.03909746909163e-06 -1.75762745749845e-05 5.05935151638708e-06 0.000137744972565487 3082 3072 0 0 170 3109 3099 0 0 131 0 0 0 0 0 135 149 0 3228 0 0 0 0 0 2763 +825 826 0.999203061606553 -0.0359532589533716 -0.0173379597047404 0.147018940891314 0.0357676028407882 0.999300668582873 -0.0109019428014304 0.00574515741709187 0.0177177950974447 0.01027311736786 0.999790249400558 0.0222672382979059 2.96954042765393e-05 4.72706066563871e-06 -1.22659858133593e-06 4.9372068447517e-06 -2.0044853576253e-06 8.19734988019081e-06 4.72706066563871e-06 2.92278034336847e-05 -2.88906123374242e-06 9.51232622221945e-06 -4.95311644376902e-07 -6.78443263155262e-06 -1.22659858133593e-06 -2.88906123374242e-06 9.71963707910817e-06 -1.40042509919246e-06 3.04970599548159e-06 -1.44777977910708e-06 4.9372068447517e-06 9.51232622221945e-06 -1.40042509919246e-06 4.84093988677777e-05 2.98210680982346e-06 1.0773293818134e-05 -2.0044853576253e-06 -4.95311644376902e-07 3.04970599548159e-06 2.98210680982346e-06 1.77113220745898e-05 -5.03727021404413e-07 8.19734988019081e-06 -6.78443263155262e-06 -1.44777977910708e-06 1.0773293818134e-05 -5.03727021404413e-07 0.000108028681172404 3599 3545 0 9 192 3632 3580 0 22 147 0 0 0 0 0 71 114 0 3106 0 9 0 0 0 2135 +815 816 0.999639840492742 -0.0132520963878741 0.0233360502435955 0.145402830807656 0.0133836422997812 0.999895364148036 -0.00548988834655412 -0.00280610959625879 -0.0232608559265696 0.00580023246022232 0.999712603644153 -0.0188597557429501 4.99001393805546e-05 2.06223310757141e-06 -1.25043832092321e-06 1.44117085268291e-05 7.1104284349649e-07 -1.86084676346575e-05 2.06223310757141e-06 2.4862823850547e-05 6.22768860473205e-07 -1.39396643545379e-06 -1.7760111189543e-07 -9.18188041101685e-06 -1.25043832092321e-06 6.22768860473205e-07 1.10376803958207e-05 1.04393098178277e-06 4.42038044395961e-06 -2.41332690624477e-06 1.44117085268291e-05 -1.39396643545379e-06 1.04393098178277e-06 4.68589322415393e-05 -1.68375678430172e-08 -8.98088882515419e-06 7.1104284349649e-07 -1.7760111189543e-07 4.42038044395961e-06 -1.68375678430172e-08 1.3668780125767e-05 2.40250080728658e-06 -1.86084676346575e-05 -9.18188041101685e-06 -2.41332690624477e-06 -8.98088882515419e-06 2.40250080728658e-06 0.000123253308470057 3387 3263 0 146 128 3387 3263 0 53 109 0 0 0 0 0 0 0 0 3631 0 45 3 0 0 2596 +818 819 0.999102381455024 0.0419489199176655 -0.00589232455322794 0.121356661781365 -0.0420943628396084 0.998742730284345 -0.027221743538916 -0.0219238954180464 0.00474299357227914 0.0274453424448012 0.999612053343726 0.12529403510957 7.60881657029133e-05 -9.70576298382889e-06 2.9526866771831e-07 9.92941211684864e-06 4.09517527215427e-07 1.83431181924688e-05 -9.70576298382889e-06 5.84785802198845e-05 -1.27516991699155e-06 6.78353005725868e-07 -1.76893721247106e-07 -1.30546156773111e-05 2.9526866771831e-07 -1.27516991699155e-06 1.26050129833499e-05 5.66606991994554e-06 3.61853157119622e-06 -3.04704191848115e-06 9.92941211684864e-06 6.78353005725868e-07 5.66606991994554e-06 6.19177566439025e-05 3.02032748744019e-07 -5.54781190784745e-05 4.09517527215427e-07 -1.76893721247106e-07 3.61853157119622e-06 3.02032748744019e-07 1.46629339482283e-05 7.95904470658514e-06 1.83431181924688e-05 -1.30546156773111e-05 -3.04704191848115e-06 -5.54781190784745e-05 7.95904470658514e-06 0.000656931969781756 3221 3264 0 113 33 3169 3212 0 109 0 0 0 0 0 0 0 0 0 3543 0 121 108 0 0 2543 +827 828 0.999593116728491 0.0277910704647219 0.00642319168689774 0.14427616189311 -0.0277491816822456 0.999593646339188 -0.00652112829904892 -0.0127933865964344 -0.00660181073551003 0.00634023664793306 0.999958107869655 0.0375765540099769 1.84630969506056e-05 3.54078697242017e-06 -1.65596141032345e-06 5.98847231510782e-06 4.7017779289003e-07 -7.93749065904915e-07 3.54078697242017e-06 2.52718130361935e-05 -2.17543722414983e-06 4.36882255184229e-06 6.06511452489911e-07 -8.65550705682913e-06 -1.65596141032345e-06 -2.17543722414983e-06 1.04154481857944e-05 -5.09719221499449e-07 2.11296770633557e-06 -2.36909518941281e-06 5.98847231510782e-06 4.36882255184229e-06 -5.09719221499449e-07 4.18426512622854e-05 6.59839573921863e-06 -6.56266816127968e-07 4.7017779289003e-07 6.06511452489911e-07 2.11296770633557e-06 6.59839573921863e-06 1.86983903031052e-05 2.24718783377863e-06 -7.93749065904915e-07 -8.65550705682913e-06 -2.36909518941281e-06 -6.56266816127968e-07 2.24718783377863e-06 5.22187627603407e-05 3584 3503 0 198 54 3583 3502 0 172 53 0 0 0 0 0 0 0 0 2804 0 90 79 0 0 2395 +821 822 0.9995808749936 0.0172910577480214 0.0232183907492068 0.136215135424741 -0.0176088444014675 0.999753093801358 0.0135528607112202 -0.00178334023699607 -0.0229783146873997 -0.0139560293983431 0.999638547824942 0.106614871637397 5.05133792075907e-05 -6.14708556209022e-06 -4.62726243262251e-06 7.22167876612736e-06 -9.46126716909747e-06 2.77184538751459e-05 -6.14708556209022e-06 6.04888870189378e-05 9.28806940974925e-07 -8.94382696308539e-06 -7.99406915846605e-07 1.34306183045432e-05 -4.62726243262251e-06 9.28806940974925e-07 1.20999113678018e-05 3.1516336742988e-06 4.9578561702457e-06 -4.94803988971946e-06 7.22167876612736e-06 -8.94382696308539e-06 3.1516336742988e-06 5.31984968041652e-05 -8.35326885287117e-07 -6.28085453349371e-05 -9.46126716909747e-06 -7.99406915846605e-07 4.9578561702457e-06 -8.35326885287117e-07 2.03894044595885e-05 1.71842831707535e-05 2.77184538751459e-05 1.34306183045432e-05 -4.94803988971946e-06 -6.28085453349371e-05 1.71842831707535e-05 0.000580469350775377 3060 3003 0 202 91 3016 2989 0 130 47 0 0 0 0 0 0 0 0 3203 0 120 70 0 0 3173 +829 830 0.998520796017555 0.0193380676213113 -0.050815933142497 0.134720925230193 -0.0209922272998636 0.999260246801825 -0.0322224386809488 -0.0133514047624325 0.0501552221953009 0.0332415147403098 0.998188086176303 0.0489546131483077 3.12509290318565e-05 3.03136695978298e-06 6.56765098254881e-08 1.64668946452587e-06 -1.32692382008282e-06 1.51840030475487e-05 3.03136695978298e-06 6.74720017926011e-05 -3.53664703199006e-06 5.55423165487043e-06 -2.94056302075867e-06 -7.01141094557574e-05 6.56765098254881e-08 -3.53664703199006e-06 1.09982283689711e-05 3.36895413653488e-07 2.62385586034092e-06 4.60553362191347e-06 1.64668946452587e-06 5.55423165487043e-06 3.36895413653488e-07 4.86810399121316e-05 7.473767438932e-07 -2.17431888584933e-05 -1.32692382008282e-06 -2.94056302075867e-06 2.62385586034092e-06 7.473767438932e-07 2.30263232219537e-05 1.5475100789221e-05 1.51840030475487e-05 -7.01141094557574e-05 4.60553362191347e-06 -2.17431888584933e-05 1.5475100789221e-05 0.000190563329726327 3288 3219 0 218 15 3280 3219 0 143 0 0 0 0 0 0 0 0 0 2846 0 30 0 0 0 1223 +828 829 0.999703071372431 0.0231284497802339 0.00767097772717871 0.136840306367033 -0.0230955907758354 0.99972381991194 -0.00434483456461238 -0.0156015276625982 -0.00776934844390558 0.00416637869641063 0.99996113850155 0.0269800835711176 1.73166506408512e-05 3.80098899185848e-06 -3.61879504746428e-06 5.87383575999468e-06 1.76218726133738e-06 7.74834212723714e-06 3.80098899185848e-06 1.69867315675498e-05 -1.30396106353526e-06 3.44085999618155e-06 1.9378668233647e-06 -6.45990686438484e-06 -3.61879504746428e-06 -1.30396106353526e-06 1.18942273053956e-05 -7.32696013495977e-06 2.18538956753795e-06 -3.15394878493101e-06 5.87383575999468e-06 3.44085999618155e-06 -7.32696013495977e-06 6.49147125001135e-05 1.31029656683196e-05 1.31749102859067e-05 1.76218726133738e-06 1.9378668233647e-06 2.18538956753795e-06 1.31029656683196e-05 1.96756501530122e-05 4.01818916705107e-06 7.74834212723714e-06 -6.45990686438484e-06 -3.15394878493101e-06 1.31749102859067e-05 4.01818916705107e-06 5.71980334802892e-05 3800 3710 0 234 83 3750 3683 0 160 33 0 0 0 0 0 0 0 0 2848 0 147 91 0 0 3580 +832 833 0.999271748136957 -0.0114163981526194 0.0364093288667953 0.149872456647859 0.0113688649774388 0.999934228771236 0.00151229653114285 -0.00267559601442595 -0.0364241991598216 -0.00109726245457081 0.999335816295339 -0.00575354346318572 3.4013137622406e-05 2.22110481353703e-05 1.62001960661513e-06 1.17510965752325e-05 -4.08674203407203e-06 -3.1809277147589e-05 2.22110481353703e-05 0.000159322918946781 -5.86680288394612e-06 4.34803106306066e-05 -7.69938250337647e-06 -0.000185086263512933 1.62001960661513e-06 -5.86680288394612e-06 1.25386265707782e-05 -1.94464948882342e-06 -1.78683909714462e-06 -3.32185796311831e-06 1.17510965752325e-05 4.34803106306066e-05 -1.94464948882342e-06 6.75575076720294e-05 4.78422906493567e-06 -8.42044791309167e-05 -4.08674203407203e-06 -7.69938250337647e-06 -1.78683909714462e-06 4.78422906493567e-06 3.13062197724059e-05 5.04945246060797e-05 -3.1809277147589e-05 -0.000185086263512933 -3.32185796311831e-06 -8.42044791309167e-05 5.04945246060797e-05 0.000587281658263932 3299 3200 0 135 82 3293 3200 0 81 42 0 0 0 0 0 0 0 0 3370 0 46 0 0 0 2105 +823 824 0.998662928362498 -0.0471353921593007 -0.0212275839517823 0.153281573029938 0.0478529092703186 0.998252620624831 0.0346670519373177 0.00781817174129403 0.019556446221328 -0.0356365012542892 0.999173451003151 0.00969906514853301 3.96220515640005e-05 1.75487174367651e-07 -1.31725365209997e-06 6.26133297935019e-06 -5.29621811542323e-06 2.55826702665042e-05 1.75487174367651e-07 3.29819109074478e-05 1.23318051040538e-09 7.40762595406402e-06 -1.20964091754744e-07 -2.41110919853168e-06 -1.31725365209997e-06 1.23318051040538e-09 1.00918584635564e-05 4.55540663029186e-07 4.70892610330586e-06 -4.83449837340602e-08 6.26133297935019e-06 7.40762595406402e-06 4.55540663029186e-07 4.21832472330859e-05 1.9678382875202e-06 7.42378585121465e-06 -5.29621811542323e-06 -1.20964091754744e-07 4.70892610330586e-06 1.9678382875202e-06 1.58751452466188e-05 -2.01806618113675e-06 2.55826702665042e-05 -2.41110919853168e-06 -4.83449837340602e-08 7.42378585121465e-06 -2.01806618113675e-06 0.000101489028870602 3520 3474 0 1 223 3557 3513 0 9 161 0 0 0 0 0 88 96 0 3215 0 0 0 0 0 3222 +826 827 0.999375313511179 -0.000404235568069757 0.0353386380331564 0.147494860841137 0.000522607600938268 0.999994284033854 -0.00334047615098561 -0.00669377912702588 -0.0353370856994233 0.0033568576415108 0.9993698123723 0.0281354413138795 2.33227425800151e-05 5.73752554195797e-06 9.74031285607235e-07 6.68810127706095e-06 2.17380810464653e-06 3.53338453290606e-06 5.73752554195797e-06 2.834870770416e-05 -2.14916466200997e-06 -5.27389775511978e-07 4.07205923814802e-07 -1.13001471870822e-05 9.74031285607235e-07 -2.14916466200997e-06 1.2162782168937e-05 8.94759643785635e-07 3.61782556029667e-06 -3.22747951434806e-06 6.68810127706095e-06 -5.27389775511978e-07 8.94759643785635e-07 4.77463547010841e-05 5.21194803059718e-06 6.52647230074755e-06 2.17380810464653e-06 4.07205923814802e-07 3.61782556029667e-06 5.21194803059718e-06 1.78170732515838e-05 3.9638029189666e-07 3.53338453290606e-06 -1.13001471870822e-05 -3.22747951434806e-06 6.52647230074755e-06 3.9638029189666e-07 8.75197214362068e-05 3417 3413 0 65 35 3417 3425 0 92 35 0 0 0 0 0 2 35 0 2870 0 11 11 0 0 3075 +831 832 0.999780543432498 0.0205830517371964 0.00389909669061262 0.141493665927062 -0.0206366465032434 0.999685572645345 0.0142437588385145 -0.0148243258251017 -0.00360469068284935 -0.0143210972321776 0.999890950243649 0.0271293326507484 4.4215373056668e-05 1.07195219735655e-05 -5.98794047469651e-07 3.66332338259644e-06 -9.48546789027788e-07 2.86225231534864e-05 1.07195219735655e-05 2.36951724025987e-05 -2.91384916113201e-07 1.27798103786414e-06 -8.80880363954914e-07 6.59764007482779e-06 -5.98794047469651e-07 -2.91384916113201e-07 1.23496414855511e-05 -7.19502744911347e-06 1.16090177730219e-06 1.12368969834986e-06 3.66332338259644e-06 1.27798103786414e-06 -7.19502744911347e-06 6.98389545683008e-05 1.78239495785847e-05 -1.02358422852962e-06 -9.48546789027788e-07 -8.80880363954914e-07 1.16090177730219e-06 1.78239495785847e-05 2.27471007434496e-05 1.29402006794962e-06 2.86225231534864e-05 6.59764007482779e-06 1.12368969834986e-06 -1.02358422852962e-06 1.29402006794962e-06 0.000123434467696617 3851 3771 0 220 90 3803 3750 0 155 42 0 0 0 0 0 0 0 0 3121 0 132 85 0 0 2078 +830 831 0.998821211096029 0.0307530712104796 -0.0375557835197891 0.141607838927788 -0.0312069161839641 0.999446110133444 -0.0115586037830883 -0.0217085498927507 0.0371795191866319 0.0127169788177285 0.999227682664367 0.00604243560257617 3.09354563739029e-05 4.77751828286656e-06 1.4282355765363e-06 3.41964420932519e-06 -5.99351927502019e-06 1.27607921097176e-05 4.77751828286656e-06 2.79333993314867e-05 1.75578205366035e-06 -4.33033249466113e-06 -4.1335018373329e-06 -2.68986837449167e-06 1.4282355765363e-06 1.75578205366035e-06 1.09800188682355e-05 -3.34990274380587e-06 8.0146710569301e-07 -3.35113227368958e-07 3.41964420932519e-06 -4.33033249466113e-06 -3.34990274380587e-06 5.62780642173615e-05 1.1072980271471e-05 -7.48867111388899e-06 -5.99351927502019e-06 -4.1335018373329e-06 8.0146710569301e-07 1.1072980271471e-05 2.3804590403106e-05 -2.90202227617536e-06 1.27607921097176e-05 -2.68986837449167e-06 -3.35113227368958e-07 -7.48867111388899e-06 -2.90202227617536e-06 0.000127735740726732 3410 3332 0 263 83 3324 3272 0 193 1 0 0 0 0 0 0 0 0 3011 0 98 68 0 0 2553 +834 835 0.998856407771236 -0.00287119012671271 -0.04772455260763 0.13679933517911 0.00588868828502842 0.997983026462652 0.0632076122213735 -0.00122905008538911 0.0474468123757955 -0.0634163635010872 0.996858648372814 0.0588297706511511 3.85807195090332e-05 2.24643849762167e-05 6.33027131694693e-07 -1.43306337801089e-06 2.27190693276328e-08 2.16533444603304e-05 2.24643849762167e-05 6.36005222047295e-05 -5.56053849016127e-07 6.3012800065451e-06 1.31128096575507e-06 -2.72895718202822e-05 6.33027131694693e-07 -5.56053849016127e-07 1.05146685634778e-05 2.83501675552594e-07 5.22548627798546e-07 -1.14299020486897e-06 -1.43306337801089e-06 6.3012800065451e-06 2.83501675552594e-07 4.60318706702354e-05 7.17053387856602e-06 -3.91713890419985e-06 2.27190693276328e-08 1.31128096575507e-06 5.22548627798546e-07 7.17053387856602e-06 1.99183293749018e-05 9.22524168257348e-07 2.16533444603304e-05 -2.72895718202822e-05 -1.14299020486897e-06 -3.91713890419985e-06 9.22524168257348e-07 0.000156365223506873 3316 3226 0 122 155 3307 3226 0 58 121 0 0 0 0 0 0 0 0 3313 0 11 0 0 0 2436 +835 836 0.999960567798636 -0.00494885751114889 -0.0073737139328731 0.136629897099625 0.00505712722201552 0.999878606517747 0.0147376284520165 0.002174218657759 0.00729988438880037 -0.014774337124341 0.999864206105232 0.016207035425286 4.26246427555501e-05 2.89704855929511e-05 6.7497284602291e-06 -1.41884824772271e-05 -4.92283833078395e-06 3.090633267008e-05 2.89704855929511e-05 8.10780310435571e-05 9.28233575050563e-06 -1.18525196713662e-05 -8.3788867663702e-06 -4.07757241045224e-05 6.7497284602291e-06 9.28233575050563e-06 1.23174409398001e-05 -1.61584132408041e-06 -1.00834083913629e-06 1.47995233351836e-06 -1.41884824772271e-05 -1.18525196713662e-05 -1.61584132408041e-06 4.64595603442214e-05 9.30568114582318e-06 -2.62437125138739e-05 -4.92283833078395e-06 -8.3788867663702e-06 -1.00834083913629e-06 9.30568114582318e-06 1.91402476230043e-05 -1.11290299999266e-06 3.090633267008e-05 -4.07757241045224e-05 1.47995233351836e-06 -2.62437125138739e-05 -1.11290299999266e-06 0.000191944927264766 3300 3220 0 125 151 3300 3220 0 59 127 0 0 0 0 0 0 0 0 3383 0 0 0 0 0 2475 +840 841 0.998988125282132 0.0346337167848578 -0.0286920059765266 0.130705532209565 -0.0343803664460108 0.999365763595359 0.00927690446773177 -0.00362249895306854 0.0289951021437897 -0.00828107572309669 0.999545250519725 -0.0462917810397984 3.56370553836302e-05 6.14143078484481e-06 1.85850370685885e-06 6.77375338767893e-06 -1.56104728337077e-06 -2.26975741896271e-05 6.14143078484481e-06 6.0386602507506e-05 -1.27969207544531e-06 7.05172851178905e-06 -3.53332806281267e-06 -5.28716119393655e-05 1.85850370685885e-06 -1.27969207544531e-06 9.23758842304895e-06 2.8690776703515e-06 5.0016906259225e-06 3.50302154776925e-07 6.77375338767893e-06 7.05172851178905e-06 2.8690776703515e-06 2.31451502997906e-05 1.18273003513549e-06 -1.79702842234053e-05 -1.56104728337077e-06 -3.53332806281267e-06 5.0016906259225e-06 1.18273003513549e-06 1.38654052203181e-05 6.88612132774769e-06 -2.26975741896271e-05 -5.28716119393655e-05 3.50302154776925e-07 -1.79702842234053e-05 6.88612132774769e-06 0.000150805535702936 3370 3330 0 212 41 3362 3326 0 170 30 0 0 0 0 0 0 0 0 3653 0 38 27 0 0 2237 +839 840 0.998310214936705 0.0306469829705014 -0.0493708131170159 0.12060227814934 -0.032537433265701 0.998749647005863 -0.037953366677321 0.00374307181572113 0.048145925990779 0.0394956331822762 0.99805914893358 0.0578990764744627 2.15017252885792e-05 -8.96847399041133e-07 4.42693047625163e-07 -1.13361660140564e-06 -5.23455061161736e-06 -2.5419370506425e-06 -8.96847399041133e-07 4.23229613463419e-05 3.4124282776891e-06 -5.50407751347128e-06 -5.162074815283e-06 -2.5692372697381e-05 4.42693047625163e-07 3.4124282776891e-06 1.08481048092778e-05 -1.2127442173468e-06 4.4131525383578e-07 1.64738699345872e-06 -1.13361660140564e-06 -5.50407751347128e-06 -1.2127442173468e-06 4.01546443716732e-05 1.23064862556674e-05 -1.46013130364148e-05 -5.23455061161736e-06 -5.162074815283e-06 4.4131525383578e-07 1.23064862556674e-05 2.15672211277986e-05 -3.16033057859093e-06 -2.5419370506425e-06 -2.5692372697381e-05 1.64738699345872e-06 -1.46013130364148e-05 -3.16033057859093e-06 0.000115381957845923 3290 3242 0 200 48 3282 3238 0 152 35 0 0 0 0 0 0 0 0 3657 0 42 29 0 0 3391 +841 842 0.999605860585589 0.0272052321002658 0.00692811874277229 0.123553765436126 -0.0273052478429453 0.999517933607731 0.0147757854872967 -0.00630182588241747 -0.0065228002559191 -0.014959135767214 0.999866829799809 -0.0244996679131287 2.94631515587861e-05 -4.06550743335298e-05 2.82570395343938e-06 -5.27698199276177e-06 5.81953379840719e-06 0.00013093673985796 -4.06550743335298e-05 0.000222866149422176 1.76117107814176e-06 4.03671130407758e-05 -1.93767889260314e-05 -0.00073807159394331 2.82570395343938e-06 1.76117107814176e-06 8.7502620745864e-06 3.73143840752674e-06 4.44464819982849e-06 -6.25283338709205e-06 -5.27698199276177e-06 4.03671130407758e-05 3.73143840752674e-06 3.43125592575834e-05 -5.65874638803292e-07 -0.000180323964614822 5.81953379840719e-06 -1.93767889260314e-05 4.44464819982849e-06 -5.65874638803292e-07 1.52028012346081e-05 7.22960303332361e-05 0.00013093673985796 -0.00073807159394331 -6.25283338709205e-06 -0.000180323964614822 7.22960303332361e-05 0.00296486336274396 3321 3292 0 187 58 3321 3292 0 152 48 0 0 0 0 0 0 0 0 3671 0 14 10 0 0 3451 +833 834 0.999607491180964 -0.0232678810454512 -0.0156035023809989 0.140799953065118 0.0230417369901769 0.999629060475965 -0.0145196352714019 0.00912814951878755 0.0159355555715708 0.0141544043885201 0.999772829649332 0.0492155807474314 2.05776728186082e-05 3.97151602642012e-06 7.95201515961459e-08 -4.21359542189271e-06 -1.29169297318151e-06 2.01296432203332e-05 3.97151602642012e-06 5.28854805741948e-05 -7.43387005047141e-07 3.5119483015357e-06 -4.50376114380609e-06 -3.9825770999636e-05 7.95201515961459e-08 -7.43387005047141e-07 1.03534940709924e-05 -1.97400437174019e-06 5.80570177506344e-07 4.67811381903408e-06 -4.21359542189271e-06 3.5119483015357e-06 -1.97400437174019e-06 4.98215516209603e-05 1.18029997997896e-05 -2.67812515042082e-05 -1.29169297318151e-06 -4.50376114380609e-06 5.80570177506344e-07 1.18029997997896e-05 2.12869358317246e-05 7.52322230728725e-06 2.01296432203332e-05 -3.9825770999636e-05 4.67811381903408e-06 -2.67812515042082e-05 7.52322230728725e-06 0.000206324848778737 3448 3336 0 85 200 3442 3336 0 22 114 0 0 0 0 0 0 0 0 3316 0 26 0 0 0 3595 +844 845 0.999388599358752 0.0133036128158146 -0.0323332856016732 0.117987115469418 -0.0128366951379435 0.999810928321903 0.0146057134721165 -0.00569610576448807 0.0325214810500379 -0.014181730999457 0.99937041770115 0.0977889619449195 2.25459439385136e-05 3.71635161234076e-07 -1.07667830670665e-06 2.56470230005597e-06 -1.90878443275182e-06 6.46839246276931e-06 3.71635161234076e-07 6.9582779259569e-05 3.02853050729589e-07 5.5648625088381e-06 1.21454095030747e-07 -5.92727524546781e-05 -1.07667830670665e-06 3.02853050729589e-07 9.8619389482869e-06 3.17539703733939e-06 4.74500205500689e-06 -4.19498115764032e-06 2.56470230005597e-06 5.5648625088381e-06 3.17539703733939e-06 2.31728926283272e-05 2.24586309918358e-06 -7.18850840948208e-06 -1.90878443275182e-06 1.21454095030747e-07 4.74500205500689e-06 2.24586309918358e-06 1.25508228713416e-05 1.93959260027219e-06 6.46839246276931e-06 -5.92727524546781e-05 -4.19498115764032e-06 -7.18850840948208e-06 1.93959260027219e-06 0.000221756037531073 3305 3308 0 133 77 3305 3308 0 107 89 0 0 0 0 0 0 0 0 3740 0 0 0 0 0 3345 +845 846 0.999543966517605 0.0257110460514269 -0.0158367013356316 0.114418228547958 -0.0253509037217732 0.999424547811262 0.0225367458330353 -0.0142427192923225 0.0164070313811481 -0.0221249936315212 0.999620575007369 0.0153378801106844 2.00870049032731e-05 -6.3565845856438e-06 7.92291548949672e-07 -6.83682734637076e-08 -8.27421480961543e-07 -2.50471905199678e-06 -6.3565845856438e-06 2.67474706776759e-05 2.22062950564646e-07 1.78123177627838e-07 -1.43946007500406e-06 -2.36845401488768e-05 7.92291548949672e-07 2.22062950564646e-07 9.05243650698678e-06 1.02291812772655e-06 4.03425781151455e-06 -5.69067602448219e-07 -6.83682734637076e-08 1.78123177627838e-07 1.02291812772655e-06 2.42684702611433e-05 4.24782670403917e-06 1.37608809871058e-06 -8.27421480961543e-07 -1.43946007500406e-06 4.03425781151455e-06 4.24782670403917e-06 1.34653527881105e-05 -7.75497943326372e-07 -2.50471905199678e-06 -2.36845401488768e-05 -5.69067602448219e-07 1.37608809871058e-06 -7.75497943326372e-07 9.4683450288522e-05 3301 3320 0 173 29 3301 3320 0 151 44 0 0 0 0 0 0 0 0 3715 0 0 0 0 0 3286 +836 837 0.999362185276386 0.0142912231595861 0.0327258854763177 0.141952162125196 -0.0138080554373968 0.999793003692031 -0.0149428034017669 0.00582536392506407 -0.0329326622768936 0.0144813918208503 0.999352654995366 -0.0343612025933875 3.45646501254213e-05 1.76397052687653e-05 -1.87159738252742e-06 1.35759114702927e-06 3.11137251945293e-06 4.83454562372949e-05 1.76397052687653e-05 9.2227141090041e-05 -2.99422694082414e-06 1.12048664872774e-05 -9.2379381615857e-07 -8.18816037598421e-05 -1.87159738252742e-06 -2.99422694082414e-06 1.09932847411917e-05 -1.94069062797678e-06 1.22654281201096e-07 3.68898290095858e-07 1.35759114702927e-06 1.12048664872774e-05 -1.94069062797678e-06 4.81017594524541e-05 8.99938984092549e-06 -4.74139299130919e-05 3.11137251945293e-06 -9.2379381615857e-07 1.22654281201096e-07 8.99938984092549e-06 1.83853261865845e-05 9.10264578092825e-06 4.83454562372949e-05 -8.18816037598421e-05 3.68898290095858e-07 -4.74139299130919e-05 9.10264578092825e-06 0.000477801341750214 3268 3191 0 182 110 3268 3191 0 116 90 0 0 0 0 0 0 0 0 3439 0 3 0 0 0 2785 +837 838 0.999265220157067 0.0369024697387366 0.0103550717829113 0.131721398075242 -0.0368273178831747 0.999294564731707 -0.00735673536292156 -0.00273461805948922 -0.0106192486541761 0.00696998026181473 0.999919322212133 0.0611716740171299 2.75663030444212e-05 -2.74979969802937e-06 1.07578270382869e-06 -2.77097609002519e-06 -3.27215358398037e-06 3.88255379429434e-05 -2.74979969802937e-06 6.07305318705815e-05 5.41928647621167e-07 -6.0151590474513e-08 -2.06354821303096e-06 5.758955435238e-06 1.07578270382869e-06 5.41928647621167e-07 1.13062633681323e-05 -1.15864376960673e-06 2.21271845054519e-06 -3.30507231767926e-06 -2.77097609002519e-06 -6.0151590474513e-08 -1.15864376960673e-06 4.31857767614093e-05 1.04248867204977e-05 -5.82412416066608e-06 -3.27215358398037e-06 -2.06354821303096e-06 2.21271845054519e-06 1.04248867204977e-05 1.78476047903025e-05 -1.19547277588569e-05 3.88255379429434e-05 5.758955435238e-06 -3.30507231767926e-06 -5.82412416066608e-06 -1.19547277588569e-05 0.000318293453888483 3320 3263 0 241 36 3302 3251 0 174 18 0 0 0 0 0 0 0 0 3649 0 56 38 0 0 3438 +838 839 0.998351837903255 0.0571936435082899 -0.00474287860261659 0.130277856651663 -0.0572754538977732 0.998169536900803 -0.019419010892442 -0.000842893526649583 0.00362355295208461 0.0196586557394797 0.999800183595962 0.0255673179697332 2.6943341272175e-05 6.83926531128426e-06 3.97847895224202e-06 -1.73148754698619e-06 -7.18817431467347e-06 1.19614178038038e-05 6.83926531128426e-06 3.07767032682684e-05 1.41836053680315e-06 -3.38585537502115e-06 -2.76693300741491e-06 -4.81106541699459e-06 3.97847895224202e-06 1.41836053680315e-06 1.10576850412657e-05 -8.66644152273776e-07 -6.93436310186511e-07 4.73605537650237e-06 -1.73148754698619e-06 -3.38585537502115e-06 -8.66644152273776e-07 4.66979505039136e-05 1.28979074220408e-05 -1.82513895156292e-05 -7.18817431467347e-06 -2.76693300741491e-06 -6.93436310186511e-07 1.28979074220408e-05 2.21111230596109e-05 -7.55463866349975e-06 1.19614178038038e-05 -4.81106541699459e-06 4.73605537650237e-06 -1.82513895156292e-05 -7.55463866349975e-06 0.000115091468778935 3590 3543 0 286 7 3571 3524 0 225 0 0 0 0 0 0 0 0 0 3564 0 100 83 0 0 3259 +848 849 0.999209880321364 0.0397440767942364 0.000153061877874576 0.116660228963071 -0.0397415857264218 0.999178030336137 -0.00799187447017749 -0.0134367185673817 -0.0004705657383269 0.00797947701114841 0.999968052746944 0.0244380125545518 1.33853009059093e-05 -7.40707358438808e-06 2.12652254992577e-06 3.78138578841113e-06 2.17910945624879e-06 5.80594770754721e-06 -7.40707358438808e-06 3.46525817852449e-05 -7.14383612201464e-07 -2.84448898836559e-08 1.01307251543398e-06 -1.98333324963825e-05 2.12652254992577e-06 -7.14383612201464e-07 9.2491286178442e-06 8.94076548113676e-07 3.39368314256434e-06 -1.63704725708327e-06 3.78138578841113e-06 -2.84448898836559e-08 8.94076548113676e-07 3.10673946608519e-05 9.40629322259923e-06 7.82118774789091e-06 2.17910945624879e-06 1.01307251543398e-06 3.39368314256434e-06 9.40629322259923e-06 1.57607833634879e-05 1.50062316680499e-06 5.80594770754721e-06 -1.98333324963825e-05 -1.63704725708327e-06 7.82118774789091e-06 1.50062316680499e-06 6.59546776373208e-05 3256 3321 0 194 0 3256 3344 0 195 15 0 0 0 0 0 0 0 0 3731 0 0 0 0 0 3757 +846 847 0.999667531753379 0.0193175506961139 -0.0170780031973823 0.11715018901614 -0.0194595293043394 0.9997771266265 -0.00818680607522309 -0.00854226870939709 0.0169160479237997 0.0085164141258409 0.999820642922058 0.0364850416899341 6.56909653698856e-05 9.64771623727711e-06 2.22022991444883e-06 7.55277324984898e-06 1.20545367133229e-06 -1.08632561620583e-05 9.64771623727711e-06 2.41132876978586e-05 1.56316649281234e-06 -8.91405723159631e-08 -1.6746129107087e-07 -9.78926242639736e-06 2.22022991444883e-06 1.56316649281234e-06 1.21224768234606e-05 -1.37256203986999e-06 1.1205398451852e-06 -3.86093893441491e-06 7.55277324984898e-06 -8.91405723159631e-08 -1.37256203986999e-06 3.8048733573901e-05 1.15800699142576e-05 4.39777414980139e-06 1.20545367133229e-06 -1.6746129107087e-07 1.1205398451852e-06 1.15800699142576e-05 2.07547301461234e-05 2.0869298938067e-06 -1.08632561620583e-05 -9.78926242639736e-06 -3.86093893441491e-06 4.39777414980139e-06 2.0869298938067e-06 0.000119775357781369 3723 3767 0 148 42 3723 3767 0 135 67 0 0 0 0 0 0 0 0 3755 0 0 0 0 0 1322 +847 848 0.99944941526308 0.0298583816384811 -0.0144687033357428 0.114862520343402 -0.0299431807255926 0.999535463513001 -0.00568006231352803 -0.0130679933097226 0.0142923846268361 0.00611017395676058 0.999879189460355 0.0405702536508264 1.31110716073043e-05 -7.29040442699058e-06 1.17431130589374e-07 2.47476755998608e-06 7.59264882572087e-07 7.14378783163268e-06 -7.29040442699058e-06 1.52932952912808e-05 1.0034829891068e-06 -1.20913274358801e-06 -9.94537322904634e-08 -1.04434177704547e-05 1.17431130589374e-07 1.0034829891068e-06 8.73552689349091e-06 1.21429445586478e-06 4.52500260219586e-06 -2.72206371864926e-07 2.47476755998608e-06 -1.20913274358801e-06 1.21429445586478e-06 2.56719640794983e-05 7.09157447288592e-06 2.20615433826324e-06 7.59264882572087e-07 -9.94537322904634e-08 4.52500260219586e-06 7.09157447288592e-06 1.20963185513534e-05 -1.95400478308008e-06 7.14378783163268e-06 -1.04434177704547e-05 -2.72206371864926e-07 2.20615433826324e-06 -1.95400478308008e-06 4.73945703825927e-05 3756 3814 0 174 3 3756 3817 0 174 44 0 0 0 0 0 0 0 0 3735 0 0 0 0 0 3514 +842 843 0.999687701159811 0.0061914968880505 0.0242108553359441 0.123484401228895 -0.0062718294112334 0.999975071584499 0.00324351127827827 -9.53945819545775e-05 -0.0241901696076968 -0.00339434468803502 0.999701612541707 0.0106641307287953 2.46654145699248e-05 -4.76686101828756e-06 2.65713934274322e-06 -1.77440022463868e-06 -3.05509811097924e-06 3.40118807835475e-06 -4.76686101828756e-06 1.67762101319056e-05 1.20488892095378e-06 -3.3272293865973e-06 -8.06140864183363e-07 -6.20058326045534e-06 2.65713934274322e-06 1.20488892095378e-06 1.19268669227522e-05 -2.5112037899386e-06 6.17015482376093e-07 -2.82387617818612e-06 -1.77440022463868e-06 -3.3272293865973e-06 -2.5112037899386e-06 3.93257006753458e-05 1.39553242950367e-05 4.65869197880571e-06 -3.05509811097924e-06 -8.06140864183363e-07 6.17015482376093e-07 1.39553242950367e-05 1.9478515569956e-05 4.81773193394294e-06 3.40118807835475e-06 -6.20058326045534e-06 -2.82387617818612e-06 4.65869197880571e-06 4.81773193394294e-06 0.000115246165252079 3610 3585 0 122 97 3610 3585 0 91 94 0 0 0 0 0 0 0 0 3741 0 0 0 0 0 3073 +849 850 0.999221247450173 0.039183976670202 -0.00463838511007625 0.102295615682039 -0.0391556931864477 0.999214872291389 0.00603909619003852 -0.0171393560627591 0.0048713791896227 -0.00585277404423115 0.99997100693009 0.00567925659460373 5.48271440351062e-05 -1.31739815945498e-05 -3.2152933091603e-06 -1.83972645792025e-06 3.28911236746754e-08 -2.80207770477672e-05 -1.31739815945498e-05 4.97112386260734e-05 3.63604461210397e-06 1.73834200578273e-06 -6.73498166362098e-07 5.82862644152305e-06 -3.2152933091603e-06 3.63604461210397e-06 1.14607258349397e-05 -8.74005329094587e-07 3.52959531470371e-06 -4.44307731310178e-06 -1.83972645792025e-06 1.73834200578273e-06 -8.74005329094587e-07 3.36980015948889e-05 9.63978794250547e-06 2.75569872791808e-05 3.28911236746754e-08 -6.73498166362098e-07 3.52959531470371e-06 9.63978794250547e-06 1.844408202068e-05 1.55108329779795e-05 -2.80207770477672e-05 5.82862644152305e-06 -4.44307731310178e-06 2.75569872791808e-05 1.55108329779795e-05 0.00022566392236062 3337 3428 0 181 0 3337 3457 0 192 14 0 0 0 0 0 0 0 0 3744 0 0 0 0 0 1563 +843 844 0.999830981706531 0.00116295180987385 -0.0183481760085977 0.121532710294367 -0.00122067866755967 0.99999433988789 -0.00313530473389941 -0.00508899089680839 0.0183444259475496 0.00315717203708611 0.999826742141549 0.0583344963578713 3.83956454609433e-05 2.04201874075528e-06 1.23853743853062e-06 1.6262074166118e-06 -9.65377791818023e-06 1.17966581436762e-06 2.04201874075528e-06 7.08894733657718e-05 -2.49257968792251e-06 1.10438350125498e-05 6.08892890846196e-07 1.49841299784869e-06 1.23853743853062e-06 -2.49257968792251e-06 9.8570481265959e-06 1.12775787561264e-07 3.08244510929021e-06 1.78233404404239e-06 1.6262074166118e-06 1.10438350125498e-05 1.12775787561264e-07 3.94006988665701e-05 5.54100263970635e-06 -9.91656964993173e-06 -9.65377791818023e-06 6.08892890846196e-07 3.08244510929021e-06 5.54100263970635e-06 1.73275480051813e-05 -3.58964266978058e-06 1.17966581436762e-06 1.49841299784869e-06 1.78233404404239e-06 -9.91656964993173e-06 -3.58964266978058e-06 0.00022887320370084 3239 3231 0 109 113 3239 3231 0 85 112 0 0 0 0 0 0 0 0 3768 0 0 0 0 0 3146 +851 852 0.999778568981587 0.0203095935988309 0.00550757777799926 0.100796168056883 -0.020227712118921 0.999689722058753 -0.014536136781404 -0.017463135198142 -0.00580109192863237 0.0144215123320668 0.99987917635807 0.0482980525994983 7.18778505672448e-05 7.72108139706292e-06 -2.86207726975882e-06 2.03295422742081e-06 -5.57802709113278e-06 -1.65846742782801e-05 7.72108139706292e-06 3.53303450845304e-05 7.46593316189929e-06 -9.07677020065988e-07 -4.06276580561332e-06 -2.04748230886438e-05 -2.86207726975882e-06 7.46593316189929e-06 1.39115931329482e-05 1.49541347799541e-06 3.86550844623356e-06 -7.68381279622435e-06 2.03295422742081e-06 -9.07677020065988e-07 1.49541347799541e-06 3.21271901670636e-05 9.09922646990788e-06 1.15657665503099e-05 -5.57802709113278e-06 -4.06276580561332e-06 3.86550844623356e-06 9.09922646990788e-06 2.18241722957209e-05 9.25277780430748e-06 -1.65846742782801e-05 -2.04748230886438e-05 -7.68381279622435e-06 1.15657665503099e-05 9.25277780430748e-06 0.000125249621847544 2646 2701 0 109 0 2646 2734 0 125 38 0 0 0 0 0 0 0 0 3758 0 0 0 0 0 1086 +857 858 0.999672726683508 0.0119199605468542 -0.0226352394668587 0.0401855799352708 -0.0118968637797193 0.999928563003751 0.0011547819965136 -0.00159730716940302 0.0226473874291805 -0.00088511570662123 0.999743123213568 0.0327552403151234 3.04984155905621e-05 -1.68317597390509e-05 2.24013612518682e-07 1.33275927561451e-06 -4.47006057766448e-07 1.13389455113939e-06 -1.68317597390509e-05 4.75364184431819e-05 4.81746969394547e-07 3.55341845095292e-06 -6.40221101185734e-07 1.27968755121218e-05 2.24013612518682e-07 4.81746969394547e-07 1.19611874696389e-05 1.1558623758952e-06 1.97973775935234e-06 1.89233375786283e-06 1.33275927561451e-06 3.55341845095292e-06 1.1558623758952e-06 5.35141098972103e-05 1.23358527721074e-05 -3.5469389957347e-06 -4.47006057766448e-07 -6.40221101185734e-07 1.97973775935234e-06 1.23358527721074e-05 2.96881077945362e-05 -3.18646040947403e-06 1.13389455113939e-06 1.27968755121218e-05 1.89233375786283e-06 -3.5469389957347e-06 -3.18646040947403e-06 4.67186853071461e-05 1470 1479 0 38 0 1465 1479 0 44 0 0 0 0 0 0 18 12 0 3536 0 0 0 0 0 1741 +855 856 0.999780826220523 0.0113793826342194 0.0175729670993066 0.0492517572411816 -0.0113239805950667 0.999930603379137 -0.00324898281283428 -0.0134023602337627 -0.0176087190133706 0.00304927478256144 0.999840304717713 0.0594140135983236 2.45059071754182e-05 -1.25606553549008e-05 1.37797904711164e-06 -4.50076363940519e-06 -7.52650277990245e-06 5.11656158542118e-06 -1.25606553549008e-05 7.21560447180738e-05 -5.63134684825167e-06 3.11581045086107e-05 1.48654123308718e-05 4.3290523273011e-05 1.37797904711164e-06 -5.63134684825167e-06 1.01248025354663e-05 -3.76921634115246e-06 1.67776262372035e-06 -6.68234765454573e-06 -4.50076363940519e-06 3.11581045086107e-05 -3.76921634115246e-06 6.30498458511179e-05 1.80504851740249e-05 3.90837347152112e-05 -7.52650277990245e-06 1.48654123308718e-05 1.67776262372035e-06 1.80504851740249e-05 2.75191536080948e-05 1.63665132118756e-05 5.11656158542118e-06 4.3290523273011e-05 -6.68234765454573e-06 3.90837347152112e-05 1.63665132118756e-05 7.75581825018144e-05 1826 1834 0 41 0 1817 1833 0 61 0 0 0 0 0 0 0 3 0 3704 0 0 0 0 0 2411 +860 861 0.999264172027414 -0.00339824861778625 -0.0382042721262828 0.00871922419700605 0.00277263371947169 0.999861394349438 -0.0164165950140212 -0.000489178942679728 0.0382547644696056 0.01629858877107 0.999135090465472 0.0319753814071232 1.96476720728574e-05 -1.25294744963388e-05 -1.31030387967262e-06 7.44893023363314e-06 -4.64981532381272e-06 4.89786629909936e-06 -1.25294744963388e-05 2.93062977741474e-05 2.00678035767607e-06 3.10597188060813e-06 2.84235565949679e-06 3.37483277984141e-06 -1.31030387967262e-06 2.00678035767607e-06 8.60199902597829e-06 3.10297714788094e-08 2.69635931174701e-06 -3.16713364259395e-06 7.44893023363314e-06 3.10597188060813e-06 3.10297714788094e-08 3.48088686553862e-05 -5.60534703439397e-06 3.9709499130034e-06 -4.64981532381272e-06 2.84235565949679e-06 2.69635931174701e-06 -5.60534703439397e-06 2.43550689396709e-05 -4.04538868648911e-07 4.89786629909936e-06 3.37483277984141e-06 -3.16713364259395e-06 3.9709499130034e-06 -4.04538868648911e-07 2.65029992504932e-05 1249 1225 0 8 0 1221 1231 0 24 0 0 0 0 0 0 6 20 0 2633 0 0 0 0 0 2010 +850 851 0.99948363720498 0.0320283980588456 -0.00257695116139071 0.113050538001419 -0.0320856921003223 0.999130959798634 -0.0266051411254392 -0.0149717418116244 0.00172259163685718 0.0266740864819277 0.999642699062224 0.0583389939056408 1.94937244181765e-05 -1.56225263130962e-05 2.80943526755517e-06 -1.86929488382552e-06 -1.25596795972764e-06 1.93865430529264e-05 -1.56225263130962e-05 2.48934364454038e-05 -8.82271272003371e-07 5.87869015280858e-06 4.15917519530644e-06 -1.3608179702749e-05 2.80943526755517e-06 -8.82271272003371e-07 8.85307952580268e-06 1.32220388182391e-06 4.31464467277509e-06 4.1541170070886e-07 -1.86929488382552e-06 5.87869015280858e-06 1.32220388182391e-06 2.97426678496419e-05 1.16634609812419e-05 5.64586330946902e-06 -1.25596795972764e-06 4.15917519530644e-06 4.31464467277509e-06 1.16634609812419e-05 1.56155350591102e-05 -2.96876074763215e-08 1.93865430529264e-05 -1.3608179702749e-05 4.1541170070886e-07 5.64586330946902e-06 -2.96876074763215e-08 7.06879747458171e-05 3379 3535 0 161 0 3379 3546 0 179 35 0 0 0 0 0 0 0 0 3776 0 0 0 0 0 3461 +852 853 0.999461679169187 0.0207465978245145 0.0254151638007075 0.0820571722020461 -0.0205536544065189 0.99975809350678 -0.00782954393473014 -0.0278279926726989 -0.0255714521067211 0.0073029546346895 0.999646321301068 0.0691460334739599 5.08536799927031e-05 -3.26058466249531e-05 -1.24467986577406e-05 5.73626728363335e-06 1.03897148728099e-05 2.3667047350746e-05 -3.26058466249531e-05 4.69223627889773e-05 1.09534916734228e-05 -1.81558323379231e-06 -9.02475105036922e-06 -1.84660276545371e-05 -1.24467986577406e-05 1.09534916734228e-05 1.61998574924612e-05 -4.44909940583267e-06 -3.40166671065145e-07 -7.51343413926002e-06 5.73626728363335e-06 -1.81558323379231e-06 -4.44909940583267e-06 3.51515827984364e-05 6.94488446897559e-06 7.66884063143362e-06 1.03897148728099e-05 -9.02475105036922e-06 -3.40166671065145e-07 6.94488446897559e-06 2.60014927534953e-05 5.86231524697224e-06 2.3667047350746e-05 -1.84660276545371e-05 -7.51343413926002e-06 7.66884063143362e-06 5.86231524697224e-06 9.78694786003869e-05 2178 2202 0 109 0 2178 2202 0 129 0 0 0 0 0 0 0 0 0 3764 0 0 0 0 0 1190 +859 860 0.999669212194907 -0.0164973432770311 0.0197307844348234 0.02128069459614 0.0169437703743027 0.999599252496563 -0.0226769277860761 0.0084104337773715 -0.0193487683100649 0.023003740415676 0.99954812445013 0.0230106521738968 2.52935836765058e-05 -2.28058157247114e-05 1.16267624514368e-06 -5.65153467668194e-06 -3.096630814832e-07 1.20404739718252e-05 -2.28058157247114e-05 4.35058924228222e-05 1.35981086096397e-07 1.24778986666805e-05 1.04954472534341e-06 4.3664398698682e-07 1.16267624514368e-06 1.35981086096397e-07 8.77745775593647e-06 -1.18000294508515e-06 2.32691777930214e-06 -1.30720618539252e-07 -5.65153467668194e-06 1.24778986666805e-05 -1.18000294508515e-06 4.97925039010772e-05 7.17235160563975e-06 -1.13901394092784e-06 -3.096630814832e-07 1.04954472534341e-06 2.32691777930214e-06 7.17235160563975e-06 2.55009989836535e-05 1.41317803153805e-07 1.20404739718252e-05 4.3664398698682e-07 -1.30720618539252e-07 -1.13901394092784e-06 1.41317803153805e-07 3.46837094064007e-05 1322 1298 0 1 0 1268 1266 0 4 0 0 0 0 0 0 30 46 0 3062 0 0 0 0 0 2822 +858 859 0.99987940364206 -0.0112010882136177 0.0107570346857027 0.00674823484471695 0.0111433369217473 0.999923255921002 0.00541371504520789 -0.00371428717381962 -0.0108168486467678 -0.0052931929091088 0.999927486317973 0.0305330023272672 2.22797569290768e-05 -1.46142427225869e-05 5.7419848565759e-07 1.49181805081802e-06 -2.50904347410186e-06 8.97274977571688e-06 -1.46142427225869e-05 4.12745105856771e-05 2.02923758302802e-07 3.8447156173579e-06 1.63162378840587e-06 2.16493601229867e-06 5.7419848565759e-07 2.02923758302802e-07 1.03531080958137e-05 5.96082174963351e-07 1.077194167669e-06 -2.79600765610963e-07 1.49181805081802e-06 3.8447156173579e-06 5.96082174963351e-07 4.92655215413718e-05 3.39506528915382e-06 -9.5270280632877e-07 -2.50904347410186e-06 1.63162378840587e-06 1.077194167669e-06 3.39506528915382e-06 2.71541020187522e-05 1.33803328220913e-06 8.97274977571688e-06 2.16493601229867e-06 -2.79600765610963e-07 -9.5270280632877e-07 1.33803328220913e-06 3.08716586662062e-05 1432 1416 0 0 0 1435 1447 0 22 0 0 0 0 0 0 46 56 0 3482 0 0 0 0 0 3050 +856 857 0.998557415258151 0.0175628393395642 -0.0507408623033976 0.0396638442843293 -0.0161628300220769 0.999480845346596 0.0278711806519178 -0.0150561339327005 0.0512040170166086 -0.0270108581793886 0.998322874716279 0.0645312356390205 3.81930189221828e-05 -3.20617089766938e-05 1.43746030996128e-06 -1.56415428902194e-06 -3.16687679724073e-06 5.89660299908873e-06 -3.20617089766938e-05 7.23446595604982e-05 -7.49829228579006e-07 1.10531766282561e-05 5.4298874476255e-06 -3.16418719977187e-06 1.43746030996128e-06 -7.49829228579006e-07 1.34711953848129e-05 2.63198451927202e-06 6.06280238157721e-07 -1.81603718267132e-06 -1.56415428902194e-06 1.10531766282561e-05 2.63198451927202e-06 5.04564479345641e-05 9.34546738089976e-06 3.23897737588361e-07 -3.16687679724073e-06 5.4298874476255e-06 6.06280238157721e-07 9.34546738089976e-06 2.94965591401087e-05 3.42753842409803e-06 5.89660299908873e-06 -3.16418719977187e-06 -1.81603718267132e-06 3.23897737588361e-07 3.42753842409803e-06 4.36788437809095e-05 1362 1370 0 51 0 1362 1370 0 68 0 0 0 0 0 0 40 30 0 3478 0 0 0 0 0 570 +862 863 0.999737666533071 -0.00281001665921438 -0.02273107831549 -0.00819413274345041 0.0027312600998439 0.999990162502418 -0.00349501311230485 -0.00378000997867346 0.0227406757436318 0.00343201176616861 0.999735506502575 0.0114306634295345 5.0344185850416e-05 -0.000125504143647623 3.55264650404247e-06 -9.76146057165732e-05 -4.10498823888119e-05 6.99815913137616e-06 -0.000125504143647623 0.000432840416000207 -1.07208958091996e-05 0.000391336859600325 0.0001666040754602 1.34213742025058e-05 3.55264650404247e-06 -1.07208958091996e-05 1.04098033033657e-05 -9.55363855443071e-06 -1.3850344559135e-06 -2.04455463122626e-06 -9.76146057165732e-05 0.000391336859600325 -9.55363855443071e-06 0.000425600221685384 0.000169051556849253 3.01258672969958e-05 -4.10498823888119e-05 0.0001666040754602 -1.3850344559135e-06 0.000169051556849253 9.3457884445129e-05 1.27404065435596e-05 6.99815913137616e-06 1.34213742025058e-05 -2.04455463122626e-06 3.01258672969958e-05 1.27404065435596e-05 4.29211784896429e-05 969 956 0 6 0 933 937 0 13 0 0 0 0 0 0 14 24 0 2638 0 0 0 0 0 2371 +853 854 0.999727870560505 0.0108497795094352 0.0206510800965412 0.0725084221738259 -0.0102994381240808 0.999593846587373 -0.0265718542632638 -0.0231577489512633 -0.0209309913497988 0.0263519287578071 0.999433574306896 0.0875953949770146 2.43072461199204e-05 -1.37869305034721e-05 7.20398967994305e-07 4.05775935626233e-06 3.15983161191081e-07 -3.81664621271633e-07 -1.37869305034721e-05 4.35805564527449e-05 5.59112495535337e-07 3.70617180604031e-06 3.81122761159977e-06 4.14651063132557e-05 7.20398967994305e-07 5.59112495535337e-07 1.01786336867675e-05 -5.16336943837001e-07 3.5516263685324e-06 -1.81199313172767e-06 4.05775935626233e-06 3.70617180604031e-06 -5.16336943837001e-07 3.34675178341203e-05 4.12509136589293e-06 1.68693424866603e-05 3.15983161191081e-07 3.81122761159977e-06 3.5516263685324e-06 4.12509136589293e-06 1.82630912459066e-05 1.62063566759566e-05 -3.81664621271633e-07 4.14651063132557e-05 -1.81199313172767e-06 1.68693424866603e-05 1.62063566759566e-05 0.000188121280150833 2042 2065 0 79 0 2042 2065 0 99 0 0 0 0 0 0 0 0 0 3744 0 0 0 0 0 1996 +864 865 0.999771553560059 0.0192991558186018 -0.00918603705605438 -0.00198567102891403 -0.0194640700294836 0.999644613351504 -0.0182152950898079 -0.0110719266147658 0.00883123264291206 0.0183899315390446 0.999791888218741 -0.00195152030980628 3.49765606770452e-05 -3.97024383574461e-05 8.62804496385734e-07 -1.01881981762265e-05 -1.08948934542395e-05 1.33565037749751e-05 -3.97024383574461e-05 7.23524244432836e-05 -2.3222773676848e-06 4.84266753624814e-05 2.79719618327604e-05 -7.6293461663016e-06 8.62804496385734e-07 -2.3222773676848e-06 8.73050460015727e-06 -9.12606447311665e-07 7.37036250278982e-07 -1.82418755871856e-06 -1.01881981762265e-05 4.84266753624814e-05 -9.12606447311665e-07 9.36380952050829e-05 2.83285675172855e-05 7.73639392581521e-06 -1.08948934542395e-05 2.79719618327604e-05 7.37036250278982e-07 2.83285675172855e-05 3.53775613921759e-05 3.38261425416852e-06 1.33565037749751e-05 -7.6293461663016e-06 -1.82418755871856e-06 7.73639392581521e-06 3.38261425416852e-06 3.4574330710993e-05 902 904 0 19 0 900 906 0 26 0 0 0 0 0 0 2 2 0 2393 0 0 0 0 0 2668 +854 855 0.999970646778861 0.00699559527426094 0.00312525637739601 0.0673766208362122 -0.00683771697212015 0.998826159885517 -0.0479536021062101 -0.0158421535550737 -0.00345705181837017 0.0479308248949491 0.998844675020904 0.0782266765542592 2.76311017300472e-05 -1.14691238446762e-05 -3.11758483965529e-06 1.46549967427453e-06 2.05610242769758e-06 2.71163565531269e-05 -1.14691238446762e-05 4.11488445788557e-05 4.66870287971191e-06 -2.47366716858465e-06 -8.98192100502174e-06 -5.32529047553791e-06 -3.11758483965529e-06 4.66870287971191e-06 1.55389546649478e-05 -2.93674681284372e-06 1.80963623606355e-06 -2.82332154258533e-06 1.46549967427453e-06 -2.47366716858465e-06 -2.93674681284372e-06 6.00099045099707e-05 2.03657530304588e-05 -1.38376256475706e-05 2.05610242769758e-06 -8.98192100502174e-06 1.80963623606355e-06 2.03657530304588e-05 2.91035912118431e-05 -3.76192315706471e-06 2.71163565531269e-05 -5.32529047553791e-06 -2.82332154258533e-06 -1.38376256475706e-05 -3.76192315706471e-06 7.50230328726246e-05 1835 1852 0 50 0 1839 1860 0 66 0 0 0 0 0 0 4 17 0 3367 0 0 0 0 0 2935 +866 867 0.999891808588772 0.0134693344442163 -0.00591169575531216 -0.0100950292005362 -0.0135628969745639 0.999778672116383 -0.016082742516718 -0.00499985451609169 0.00569376349446416 0.016161182222583 0.999853187846315 0.00202208357258282 2.88711217734591e-05 -3.27107705840648e-05 3.36283644370169e-06 -9.93699299752873e-06 -4.81583516631897e-06 9.54717689967557e-06 -3.27107705840648e-05 7.30432525326378e-05 -6.25032523871881e-06 4.75293529818279e-05 1.96366248918738e-05 -1.07482461352137e-05 3.36283644370169e-06 -6.25032523871881e-06 8.78730961770212e-06 5.75909649860911e-07 1.41690586710553e-06 3.20378842313866e-07 -9.93699299752873e-06 4.75293529818279e-05 5.75909649860911e-07 7.43034188628679e-05 2.40765568897228e-05 3.33968838240024e-06 -4.81583516631897e-06 1.96366248918738e-05 1.41690586710553e-06 2.40765568897228e-05 2.89494292612487e-05 1.7080733971354e-06 9.54717689967557e-06 -1.07482461352137e-05 3.20378842313866e-07 3.33968838240024e-06 1.7080733971354e-06 4.00004987545035e-05 845 845 0 21 0 840 851 0 31 0 0 0 0 0 0 1 13 0 2311 0 0 0 0 0 2702 +868 869 0.999937804892753 0.0110922417279 -0.00116125781510447 -0.00616756160296444 -0.0110878242998884 0.999931519962675 0.00374373308744728 -0.00911971408731365 0.00120270468449665 -0.00373062442294565 0.999992317941921 -0.00122688813270799 3.23995792771197e-05 -4.81396345195597e-05 3.01529296520761e-06 -2.72041636606306e-05 -1.29005102352282e-05 2.00072925299407e-05 -4.81396345195597e-05 0.000103690921540157 -4.83760684040752e-06 8.15731847320246e-05 4.32951962157193e-05 -2.87547270410474e-05 3.01529296520761e-06 -4.83760684040752e-06 9.01166912560509e-06 -4.49143514547722e-06 3.23089852016289e-07 1.90297226166413e-07 -2.72041636606306e-05 8.15731847320246e-05 -4.49143514547722e-06 0.000131000810729257 5.27074793336945e-05 -1.43429937122375e-05 -1.29005102352282e-05 4.32951962157193e-05 3.23089852016289e-07 5.27074793336945e-05 4.21280269731698e-05 -6.70469142537589e-06 2.00072925299407e-05 -2.87547270410474e-05 1.90297226166413e-07 -1.43429937122375e-05 -6.70469142537589e-06 3.18497277847342e-05 920 922 0 24 0 916 926 0 34 0 0 0 0 0 0 2 13 0 2280 0 0 0 0 0 2853 +863 864 0.999922722247053 -0.0120015386188153 0.00324231473235227 0.00686332303113702 0.0120054741747578 0.999927215138424 -0.0011970861938615 -0.0038443226289056 -0.00322771186473761 0.00123591921151605 0.999994027172073 0.00827472448602639 2.53577215831381e-05 -2.57928688974321e-05 2.09802551511784e-07 -6.18010614175447e-06 -4.27760575104472e-06 9.17255402012722e-06 -2.57928688974321e-05 3.83495441732963e-05 1.67286484441221e-06 1.60359400820604e-05 7.6091748972977e-06 -4.32029819484411e-06 2.09802551511784e-07 1.67286484441221e-06 1.21102601059939e-05 -5.09137185365781e-06 -3.35133612206783e-06 -1.61880992357508e-06 -6.18010614175447e-06 1.60359400820604e-05 -5.09137185365781e-06 8.74511373391469e-05 4.05952705744007e-05 1.10528473663972e-05 -4.27760575104472e-06 7.6091748972977e-06 -3.35133612206783e-06 4.05952705744007e-05 4.59738237907146e-05 1.73191606111592e-06 9.17255402012722e-06 -4.32029819484411e-06 -1.61880992357508e-06 1.10528473663972e-05 1.73191606111592e-06 2.87046028000677e-05 954 949 0 3 0 939 944 0 9 0 0 0 0 0 0 14 26 0 2566 0 0 0 0 0 1612 +861 862 0.99957323897967 0.00266851025095298 -0.0290898430509982 0.01119349258607 -0.00187745188842978 0.99962859938913 0.0271871009438904 0.0039513021273657 0.0291515881230814 -0.0271208837681816 0.999207006867714 0.0152900137225651 2.43635678664895e-05 -3.94637460705422e-05 -6.7908131463905e-07 -1.35996051537744e-05 -5.25720830076714e-06 9.8741797085565e-06 -3.94637460705422e-05 0.000140125128744538 2.82097058024052e-07 9.68951419127237e-05 3.2527737069485e-05 -1.03453464507271e-05 -6.7908131463905e-07 2.82097058024052e-07 9.12318674143254e-06 -4.24362565782096e-06 1.93781600276226e-06 -1.03290238517539e-06 -1.35996051537744e-05 9.68951419127237e-05 -4.24362565782096e-06 0.000145337259830451 3.51819198319875e-05 -3.17347514763164e-06 -5.25720830076714e-06 3.2527737069485e-05 1.93781600276226e-06 3.51819198319875e-05 3.27138505800607e-05 -6.27592318259532e-07 9.8741797085565e-06 -1.03453464507271e-05 -1.03290238517539e-06 -3.17347514763164e-06 -6.27592318259532e-07 3.59861740322234e-05 1065 1053 0 10 0 1014 1018 0 18 0 0 0 0 0 0 2 9 0 2720 0 0 0 0 0 2685 +867 868 0.999810110609728 0.0171225559367586 0.00930380571359093 -0.00263292735329258 -0.0171181297274493 0.999853319951182 -0.000555173156455334 -0.00621290373612306 -0.00931194701434066 0.000395803981798926 0.999956564547686 -0.0014482420087024 2.91678118699756e-05 -2.79464043000827e-05 4.3768988698192e-06 -8.62500306480981e-06 -7.78879479180609e-06 -7.74701302315885e-07 -2.79464043000827e-05 3.60032675682519e-05 -3.63620120407672e-06 1.40320055037365e-05 1.14282892478628e-05 6.2882922415125e-06 4.3768988698192e-06 -3.63620120407672e-06 9.57502103059889e-06 2.60201220285205e-06 1.23906144350778e-06 -1.90580771953196e-07 -8.62500306480981e-06 1.40320055037365e-05 2.60201220285205e-06 4.59089548133441e-05 1.64626121300206e-05 8.13162643427025e-06 -7.78879479180609e-06 1.14282892478628e-05 1.23906144350778e-06 1.64626121300206e-05 2.88777658920659e-05 1.22485127111251e-05 -7.74701302315885e-07 6.2882922415125e-06 -1.90580771953196e-07 8.13162643427025e-06 1.22485127111251e-05 3.81287311551805e-05 909 909 0 28 0 907 911 0 39 0 0 0 0 0 0 1 8 0 2298 0 0 0 0 0 1553 +865 866 0.999763010157795 0.00378023665371004 0.0214390608718613 0.00181243125476838 -0.00370232976749625 0.999986403007765 -0.00367240437364914 -0.00194460533584838 -0.0214526519227376 0.00359215957786306 0.9997634120706 -0.00201904007372968 3.2884512472093e-05 -3.36317256038393e-05 2.63754782674789e-06 -1.56169014426931e-05 -8.0095730400569e-06 9.63355509855313e-06 -3.36317256038393e-05 7.62024676540963e-05 -3.51908550100627e-06 4.61136189653712e-05 2.23907883734987e-05 -2.39214216895908e-05 2.63754782674789e-06 -3.51908550100627e-06 9.03654930083286e-06 -1.51596085873378e-06 1.84399779263133e-06 4.14887916523217e-07 -1.56169014426931e-05 4.61136189653712e-05 -1.51596085873378e-06 8.68875739741333e-05 2.59707980339222e-05 -9.40977595588728e-07 -8.0095730400569e-06 2.23907883734987e-05 1.84399779263133e-06 2.59707980339222e-05 3.58152719873827e-05 -2.64615944619517e-06 9.63355509855313e-06 -2.39214216895908e-05 4.14887916523217e-07 -9.40977595588728e-07 -2.64615944619517e-06 3.41579928660401e-05 868 860 0 7 0 866 873 0 23 0 0 0 0 0 0 6 21 0 2469 0 0 0 0 0 2590 +872 873 0.99993470602913 -0.0114147160331459 -0.000536596981391489 -0.00102529021173286 0.0114088606271735 0.999886125323736 -0.00987796964340626 0.00637114901711326 0.000649290095047467 0.00987120271137045 0.999951067692516 -0.00045350666355339 4.26473330846448e-05 -6.07402055020592e-05 2.53293325611174e-06 -3.60657248674434e-05 -1.69702454731765e-05 1.60060169707848e-05 -6.07402055020592e-05 0.000125608600617214 -2.78011562042021e-06 9.27505727189721e-05 5.02455957353035e-05 -1.16871415178127e-05 2.53293325611174e-06 -2.78011562042021e-06 8.88899016828527e-06 -1.29887317371133e-06 6.37424977183316e-07 8.7931895079547e-08 -3.60657248674434e-05 9.27505727189721e-05 -1.29887317371133e-06 0.000131341876501013 5.60441642216657e-05 1.11273751321131e-05 -1.69702454731765e-05 5.02455957353035e-05 6.37424977183316e-07 5.60441642216657e-05 4.72863083428787e-05 3.4295260769336e-06 1.60060169707848e-05 -1.16871415178127e-05 8.7931895079547e-08 1.11273751321131e-05 3.4295260769336e-06 4.15212320078017e-05 763 761 0 5 0 770 770 0 12 0 0 0 0 0 0 17 23 0 2097 0 0 0 0 0 1776 +869 870 0.999851997657467 -0.000114466297841396 -0.0172037692916131 0.000527661775277647 2.57347246818213e-05 0.999986698052596 -0.00515781500148904 -0.00285970121860767 0.0172041308439671 0.00515660889852025 0.999838700624541 0.0058216025394354 2.80326260977081e-05 -3.50963315757285e-05 4.03764407472364e-06 -1.03592203751634e-05 -5.0880184056301e-06 6.49446738579531e-06 -3.50963315757285e-05 6.78834404918135e-05 -5.81394460996272e-06 3.52124848447803e-05 1.70177074349814e-05 -3.10904170748568e-06 4.03764407472364e-06 -5.81394460996272e-06 8.4222994931541e-06 -8.05152712564813e-07 6.49092352403981e-07 7.89933620073676e-10 -1.03592203751634e-05 3.52124848447803e-05 -8.05152712564813e-07 6.37812325584467e-05 1.78628044447173e-05 1.84410456442491e-06 -5.0880184056301e-06 1.70177074349814e-05 6.49092352403981e-07 1.78628044447173e-05 2.46713908658111e-05 7.22605739387072e-07 6.49446738579531e-06 -3.10904170748568e-06 7.89933620073676e-10 1.84410456442491e-06 7.22605739387072e-07 2.54957544547186e-05 830 826 0 4 0 830 843 0 22 0 0 0 0 0 0 10 25 0 2271 0 0 0 0 0 2648 +873 874 0.999881890287525 0.00332499178128274 -0.0150049959913184 0.00396528473453835 -0.00325192474594342 0.999982749992748 0.004891288417949 0.000747990540291356 0.0150210006488183 -0.00484191559150338 0.999875454940721 0.00294868483655122 3.42360637740255e-05 -4.58303297307859e-05 2.18900037948963e-06 -1.33956924879274e-05 -1.16569989742608e-05 2.61949291304251e-05 -4.58303297307859e-05 0.000102851205819533 -4.97730675932706e-06 5.96042338788818e-05 3.66210844246945e-05 -3.80855016030148e-05 2.18900037948963e-06 -4.97730675932706e-06 8.68304991738545e-06 -2.16622000107324e-06 -1.29279029539804e-08 -1.10817303509913e-06 -1.33956924879274e-05 5.96042338788818e-05 -2.16622000107324e-06 8.55752228228972e-05 3.11214074880452e-05 -3.41728631177722e-06 -1.16569989742608e-05 3.66210844246945e-05 -1.29279029539804e-08 3.11214074880452e-05 3.47110452584631e-05 -8.33167718937859e-06 2.61949291304251e-05 -3.80855016030148e-05 -1.10817303509913e-06 -3.41728631177722e-06 -8.33167718937859e-06 4.93574279692697e-05 746 747 0 8 0 752 762 0 19 0 0 0 0 0 0 11 18 0 2081 0 0 0 0 0 2408 +879 880 0.999999207059833 -0.00064377078902857 0.00108233029913533 -0.00359227414016153 0.000640336044908426 0.999994767894988 0.00317082834573212 -0.00152742084275135 -0.00108436592293556 -0.00317013277635193 0.999994387188611 -0.00108533547346528 8.03920627792805e-05 -0.000130583289031997 8.47714886884896e-06 -0.000100312922715935 -5.62471334205976e-05 -2.61187454504758e-06 -0.000130583289031997 0.000250565766607775 -1.33336688259861e-05 0.000222873228012875 0.00012456037601178 2.01480901258643e-05 8.47714886884896e-06 -1.33336688259861e-05 1.12623063813192e-05 -1.24732018563596e-05 -3.90110710135448e-06 -1.76069562204603e-06 -0.000100312922715935 0.000222873228012875 -1.24732018563596e-05 0.000277142124653292 0.00013607636888896 3.46926863737972e-05 -5.62471334205976e-05 0.00012456037601178 -3.90110710135448e-06 0.00013607636888896 9.28703189583484e-05 2.47307572226455e-05 -2.61187454504758e-06 2.01480901258643e-05 -1.76069562204603e-06 3.46926863737972e-05 2.47307572226455e-05 5.3658991805518e-05 717 713 0 15 0 714 719 0 19 0 0 0 0 0 0 4 16 0 2078 0 0 0 0 0 1293 +881 882 0.999997363944787 0.000316073549269684 0.00227424734571918 0.00292134352060198 -0.000325902203837313 0.999990604217345 0.00432264557692102 -0.000132537632282888 -0.00227285970345568 -0.00432337536441065 0.999988071195965 -0.000459385522173113 3.92448789071757e-05 -5.50960837736247e-05 5.78200910111247e-06 -3.67917964663546e-05 -2.09042238764603e-05 9.85172667201909e-06 -5.50960837736247e-05 0.000102986378090715 -6.0024237105563e-06 8.26780151733916e-05 4.9414082000505e-05 -5.78020480526658e-06 5.78200910111247e-06 -6.0024237105563e-06 8.89347094420482e-06 -2.07345004980363e-06 6.40427443661494e-07 4.77602147040756e-07 -3.67917964663546e-05 8.26780151733916e-05 -2.07345004980363e-06 0.000130344200147887 6.08121944334165e-05 4.86138803856568e-06 -2.09042238764603e-05 4.9414082000505e-05 6.40427443661494e-07 6.08121944334165e-05 5.08172080578236e-05 6.78018260644708e-06 9.85172667201909e-06 -5.78020480526658e-06 4.77602147040756e-07 4.86138803856568e-06 6.78018260644708e-06 4.34150792584503e-05 802 801 0 10 0 803 816 0 27 0 0 0 0 0 0 9 23 0 2107 0 0 0 0 0 2655 +876 877 0.99999995820094 -0.000287009234358725 3.4983105153469e-05 0.00362415067012304 0.000287188675855277 0.999986218880335 -0.0052420961528431 0.0019836205658606 -3.34780930438483e-05 0.00524210598048006 0.999986259507653 -0.000720667603787657 2.58790406060617e-05 -2.68263774842619e-05 -2.80574173044454e-07 -3.6135340963457e-06 -4.71349311420849e-06 1.00781050482374e-05 -2.68263774842619e-05 3.70649721574918e-05 8.78156573205112e-07 1.07292151033833e-05 9.6857977650599e-06 -4.82901006498079e-06 -2.80574173044454e-07 8.78156573205112e-07 7.7056685967756e-06 3.11360465488111e-06 1.19442884781411e-06 -1.82014630935795e-06 -3.6135340963457e-06 1.07292151033833e-05 3.11360465488111e-06 4.05734953283494e-05 1.56011053953543e-05 8.43551196152425e-06 -4.71349311420849e-06 9.6857977650599e-06 1.19442884781411e-06 1.56011053953543e-05 2.52027010427909e-05 8.24601599530084e-06 1.00781050482374e-05 -4.82901006498079e-06 -1.82014630935795e-06 8.43551196152425e-06 8.24601599530084e-06 3.39648619150529e-05 802 800 0 7 0 802 810 0 18 0 0 0 0 0 0 8 20 0 2066 0 0 0 0 0 2632 +870 871 0.999955058030264 -0.00220487756030084 -0.00922065261440591 0.0119031177998912 0.00227642636930448 0.999967327983304 0.00775634249612303 0.00551815715326348 0.00920324957157003 -0.00777698404756693 0.999927406723332 0.00364522001376776 4.02503121099735e-05 -5.79902127990794e-05 2.1246707088003e-06 -1.92118239033866e-05 -1.30756749719993e-05 2.31184101969225e-05 -5.79902127990794e-05 0.000136688460116205 -2.2132462086278e-06 7.2884104510831e-05 4.11888407471251e-05 -3.34919002883158e-05 2.1246707088003e-06 -2.2132462086278e-06 8.68173005997763e-06 2.58811001877038e-07 2.1856167447636e-06 -1.51528246895318e-06 -1.92118239033866e-05 7.2884104510831e-05 2.58811001877038e-07 8.42303142842125e-05 3.21303253013383e-05 -6.7318280027181e-06 -1.30756749719993e-05 4.11888407471251e-05 2.1856167447636e-06 3.21303253013383e-05 3.65095284136287e-05 -5.23174131411847e-06 2.31184101969225e-05 -3.34919002883158e-05 -1.51528246895318e-06 -6.7318280027181e-06 -5.23174131411847e-06 4.18018314168337e-05 765 764 0 8 0 765 777 0 21 0 0 0 0 0 0 5 17 0 2317 0 0 0 0 0 2786 +871 872 0.9999310874828 -0.0106002877848104 -0.00504521400375164 0.00100869307094912 0.0105561340923109 0.999906441479977 -0.00869921375032084 0.00669469232404841 0.00513695615025123 0.00864535631005564 0.999949433469404 0.00488863304690334 4.01691326300124e-05 -4.31711563904141e-05 1.53389427474807e-06 -1.48730346417889e-05 -1.24859338316023e-05 1.43071478022965e-05 -4.31711563904141e-05 5.82775132939725e-05 -1.62598125127286e-06 3.22510415389767e-05 2.25429804681942e-05 -1.05789870513327e-05 1.53389427474807e-06 -1.62598125127286e-06 8.85034325615596e-06 -1.63847903078679e-06 6.23345533470099e-07 -4.25440852253057e-07 -1.48730346417889e-05 3.22510415389767e-05 -1.63847903078679e-06 7.01037788913379e-05 2.33411510707083e-05 7.09713669078642e-06 -1.24859338316023e-05 2.25429804681942e-05 6.23345533470099e-07 2.33411510707083e-05 3.45207370148953e-05 3.22432035336287e-06 1.43071478022965e-05 -1.05789870513327e-05 -4.25440852253057e-07 7.09713669078642e-06 3.22432035336287e-06 3.06142222756417e-05 787 782 0 3 0 795 798 0 13 0 0 0 0 0 0 17 30 0 2216 0 0 0 0 0 1862 +877 878 0.999990874451858 0.00413592096874593 0.00107012651049991 -0.00703414225400084 -0.00413155958486063 0.999983279158663 -0.0040461856709509 -0.00147044759963458 -0.00108684332124425 0.0040417274558473 0.999991241567029 -0.00291328987693508 3.80037866597637e-05 -4.56814273118006e-05 2.54073944103527e-06 -2.302776849323e-05 -1.74304568412597e-05 4.14471780973273e-06 -4.56814273118006e-05 7.38575044723639e-05 -2.33604321384477e-06 5.16211373086411e-05 3.69094650826468e-05 7.07909181336687e-06 2.54073944103527e-06 -2.33604321384477e-06 9.16161917100819e-06 3.13809616041498e-07 1.899429188634e-06 -5.24367689396332e-07 -2.302776849323e-05 5.16211373086411e-05 3.13809616041498e-07 9.24474814003525e-05 4.70887031741932e-05 2.74520624251526e-05 -1.74304568412597e-05 3.69094650826468e-05 1.899429188634e-06 4.70887031741932e-05 5.43002370688979e-05 2.24057488785176e-05 4.14471780973273e-06 7.07909181336687e-06 -5.24367689396332e-07 2.74520624251526e-05 2.24057488785176e-05 5.92265903751237e-05 737 735 0 7 0 733 742 0 20 0 0 0 0 0 0 8 19 0 2048 0 0 0 0 0 1355 +880 881 0.999992369716382 0.000492156758292533 -0.00387534395118701 -0.00457403526641215 -0.000489886699721383 0.999999707898766 0.000586697029902715 -0.00381827850960183 0.0038756315661026 -0.000584794073779447 0.999992318718427 -0.000516283990423173 5.05194490988359e-05 -5.58787520421001e-05 2.80121073952685e-06 -3.35920921277285e-05 -2.07957533250309e-05 8.92211286679851e-06 -5.58787520421001e-05 8.35686656597341e-05 -1.79245810143469e-06 5.37864387321497e-05 3.30726911917351e-05 -8.45372961335225e-07 2.80121073952685e-06 -1.79245810143469e-06 9.71051095950401e-06 -1.31442769835801e-06 -3.93694567131403e-08 1.3828101965913e-06 -3.35920921277285e-05 5.37864387321497e-05 -1.31442769835801e-06 0.000100246359746885 4.94286899915456e-05 1.33343449857409e-05 -2.07957533250309e-05 3.30726911917351e-05 -3.93694567131403e-08 4.94286899915456e-05 4.92147658913479e-05 1.31939428949818e-05 8.92211286679851e-06 -8.45372961335225e-07 1.3828101965913e-06 1.33343449857409e-05 1.31939428949818e-05 4.68725270107973e-05 771 769 0 13 0 767 778 0 24 0 0 0 0 0 0 9 24 0 2086 0 0 0 0 0 1625 +882 883 0.999981187168879 -2.68252679813449e-05 -0.00613388854845958 -0.00703306844683379 1.28323811221214e-05 0.999997397816928 -0.00228127041400163 -0.0044922003123848 0.00613393378264883 0.00228114878445098 0.999978585378994 0.000802505826956599 5.09095589926804e-05 -6.95215262400395e-05 3.66844002521209e-06 -4.66205809257965e-05 -2.44470875654362e-05 2.34974701068874e-05 -6.95215262400395e-05 0.000130712626706246 -5.87655212506796e-06 0.000116559648752496 6.04840082750362e-05 -2.70110606770921e-05 3.66844002521209e-06 -5.87655212506796e-06 9.66886365828414e-06 -7.41992450454285e-06 -1.58542006163613e-06 1.17826906603409e-07 -4.66205809257965e-05 0.000116559648752496 -7.41992450454285e-06 0.000177659664129005 7.84865183930796e-05 -5.20383122626632e-06 -2.44470875654362e-05 6.04840082750362e-05 -1.58542006163613e-06 7.84865183930796e-05 5.85140747430544e-05 -1.15461372396625e-06 2.34974701068874e-05 -2.70110606770921e-05 1.17826906603409e-07 -5.20383122626632e-06 -1.15461372396625e-06 4.68269753115156e-05 797 795 0 11 0 791 804 0 21 0 0 0 0 0 0 8 20 0 2115 0 0 0 0 0 2005 +883 884 0.99999385009116 -0.000629825310532889 -0.00345008694616664 -0.00587751581320134 0.000634578466393856 0.999998850906295 0.00137677022743553 -0.000466574749182479 0.00344921585695742 -0.00137895111130736 0.999993100678102 0.00148228323973716 2.40968530331782e-05 -2.73908463317593e-05 -3.60181837599993e-07 -4.61945690703186e-06 -2.43224451988019e-06 2.34010744896998e-05 -2.73908463317593e-05 7.42125533301775e-05 -7.24415003268842e-07 4.62738093955984e-05 1.67334752589668e-05 -4.67212926454893e-05 -3.60181837599993e-07 -7.24415003268842e-07 8.46840855658512e-06 -1.80788320785722e-06 2.30209373054244e-06 -1.86242976449671e-07 -4.61945690703186e-06 4.62738093955984e-05 -1.80788320785722e-06 8.18475459560802e-05 1.9536887832832e-05 -2.75938862025548e-05 -2.43224451988019e-06 1.67334752589668e-05 2.30209373054244e-06 1.9536887832832e-05 2.29048351892685e-05 -1.1096208127494e-05 2.34010744896998e-05 -4.67212926454893e-05 -1.86242976449671e-07 -2.75938862025548e-05 -1.1096208127494e-05 6.31443376066867e-05 772 772 0 6 0 773 787 0 24 0 0 0 0 0 0 8 20 0 2162 0 0 0 0 0 2830 +874 875 0.99993871723247 0.00853418779289901 0.00705190883366531 0.00779343224290354 -0.00853215442613606 0.999963549824043 -0.000318377364972214 0.00062149203386374 -0.00705436888256917 0.000258189878758304 0.999975084298432 0.00123034531740199 3.15599045928101e-05 -3.26413166233904e-05 -2.07824647639004e-06 -2.50560808099607e-06 -4.43168039215959e-06 1.46578535846758e-05 -3.26413166233904e-05 4.94200394627955e-05 1.2959323715347e-06 2.05932659340667e-05 1.54682849019164e-05 -7.12949071822804e-06 -2.07824647639004e-06 1.2959323715347e-06 9.40462944242268e-06 -2.66481549693245e-06 4.11945865776721e-07 -2.3212271158162e-06 -2.50560808099607e-06 2.05932659340667e-05 -2.66481549693245e-06 6.56036800163736e-05 1.62012886794634e-05 9.97074198958165e-06 -4.43168039215959e-06 1.54682849019164e-05 4.11945865776721e-07 1.62012886794634e-05 2.80054801849482e-05 6.64731583302781e-06 1.46578535846758e-05 -7.12949071822804e-06 -2.3212271158162e-06 9.97074198958165e-06 6.64731583302781e-06 3.19601025264239e-05 759 760 0 12 0 754 763 0 23 0 0 0 0 0 0 4 13 0 2083 0 0 0 0 0 2134 +875 876 0.999997898506508 -0.001717754856482 0.00111906247407195 -0.00092817717399909 0.00171756770914488 0.999998510837991 0.000168175400006512 -6.1816301456698e-05 -0.00111934969171673 -0.000166252981017021 0.999999359707902 0.0025258143645914 2.73640704548184e-05 -2.71810618279724e-05 6.42739565460823e-08 -4.05625306602297e-06 -5.97807455428827e-06 1.74504961646543e-05 -2.71810618279724e-05 3.27249499359587e-05 4.81149048542681e-07 1.04576235404068e-05 1.06641727619483e-05 -1.5214483197116e-05 6.42739565460823e-08 4.81149048542681e-07 8.33951068555146e-06 1.10060219331835e-07 9.2174142380363e-07 -1.62684832095901e-06 -4.05625306602297e-06 1.04576235404068e-05 1.10060219331835e-07 5.35631397426239e-05 1.83352560581256e-05 1.31861807894068e-06 -5.97807455428827e-06 1.06641727619483e-05 9.2174142380363e-07 1.83352560581256e-05 2.71131783507054e-05 7.15806926573618e-07 1.74504961646543e-05 -1.5214483197116e-05 -1.62684832095901e-06 1.31861807894068e-06 7.15806926573618e-07 3.45430948385398e-05 796 794 0 8 0 793 802 0 15 0 0 0 0 0 0 5 15 0 2101 0 0 0 0 0 2649 +878 879 0.99995105405912 0.00264318578273434 0.00953430936006524 0.00673247814138298 -0.00271500022645202 0.999967984880298 0.00752715007202609 0.00432399621290386 -0.00951410846195492 -0.00755266730065531 0.999926216756426 -0.00152838793613669 3.83839136580652e-05 -5.21076848892815e-05 4.85362180166672e-06 -3.66607594652095e-05 -2.00774865620881e-05 1.62396642204022e-05 -5.21076848892815e-05 9.76160849143723e-05 -6.26926368007291e-06 8.91686164719671e-05 4.81975884301018e-05 -2.11322857882722e-05 4.85362180166672e-06 -6.26926368007291e-06 8.67592685020551e-06 -4.96162558256606e-06 -1.02551411745868e-06 2.44434632438144e-07 -3.66607594652095e-05 8.91686164719671e-05 -4.96162558256606e-06 0.000152844551184488 6.89047733715922e-05 -3.75477043741148e-06 -2.00774865620881e-05 4.81975884301018e-05 -1.02551411745868e-06 6.89047733715922e-05 5.33416478501521e-05 -2.30216881381243e-06 1.62396642204022e-05 -2.11322857882722e-05 2.44434632438144e-07 -3.75477043741148e-06 -2.30216881381243e-06 3.7995174886031e-05 710 707 0 11 0 711 720 0 23 0 0 0 0 0 0 5 16 0 2042 0 0 0 0 0 2558 +889 890 0.999891497479164 -1.73506399130574e-05 0.0147306811733102 -0.00287738268045203 -0.000268782536340551 0.999811337128002 0.0194220984001523 -0.00466833478387733 -0.0147282390265292 -0.0194239504033638 0.999702850414014 -0.00363087915851122 4.07823444387711e-05 -4.7983764326314e-05 2.12035740820811e-06 -2.02614821141877e-05 -1.02784658132316e-05 1.20706637853954e-05 -4.7983764326314e-05 9.03052604619651e-05 1.88212222337858e-07 4.762159280809e-05 2.32307932813835e-05 -9.59468995665622e-06 2.12035740820811e-06 1.88212222337858e-07 9.09682633554934e-06 -1.91663791150071e-06 3.8320635609407e-06 3.27273630656177e-07 -2.02614821141877e-05 4.762159280809e-05 -1.91663791150071e-06 7.25471878751693e-05 2.35768278923996e-05 6.12847689981366e-06 -1.02784658132316e-05 2.32307932813835e-05 3.8320635609407e-06 2.35768278923996e-05 2.64800086414165e-05 1.15005949534802e-06 1.20706637853954e-05 -9.59468995665622e-06 3.27273630656177e-07 6.12847689981366e-06 1.15005949534802e-06 2.93187738459974e-05 922 927 0 19 0 922 942 0 37 0 0 0 0 0 0 14 34 0 2691 0 0 0 0 0 2322 +887 888 0.999888377143426 -0.000655947937969895 0.0149265865417688 -0.0118132898012343 0.000205376143962649 0.999544839615956 0.030167389972496 -0.0103696267293271 -0.0149395807881523 -0.0301609570374654 0.999433402281742 -0.000516705045843114 5.51973061114655e-05 -6.67653986483369e-05 6.17951742594206e-06 -5.56671833811882e-05 -2.90216385161359e-05 4.6708836377895e-06 -6.67653986483369e-05 9.4931721618356e-05 -6.64726033671736e-06 8.79192774637213e-05 4.68224980168852e-05 4.33613750774926e-06 6.17951742594206e-06 -6.64726033671736e-06 1.14531925464354e-05 -6.02293766170234e-06 3.63172511407757e-07 -7.00515469740932e-07 -5.56671833811882e-05 8.79192774637213e-05 -6.02293766170234e-06 0.000165318871022773 7.95603749637477e-05 3.10834345044218e-05 -2.90216385161359e-05 4.68224980168852e-05 3.63172511407757e-07 7.95603749637477e-05 5.80218630155817e-05 1.81476702698467e-05 4.6708836377895e-06 4.33613750774926e-06 -7.00515469740932e-07 3.10834345044218e-05 1.81476702698467e-05 4.16811421859418e-05 892 893 0 15 0 889 905 0 28 0 0 0 0 0 0 10 25 0 2484 0 0 0 0 0 1701 +884 885 0.999999839536021 -8.25921335085543e-05 -0.000560452025323996 -0.00297367583197193 8.42549626840527e-05 0.999995593210257 0.00296756822462576 -0.00335723203837973 0.000560204457738755 -0.00296761496930243 0.999995439705782 0.00208990214615996 3.80475420093768e-05 -4.35614219829991e-05 -4.5656263786812e-07 -9.92391803740393e-06 -8.54886101099368e-06 2.17068563107722e-05 -4.35614219829991e-05 7.65821722153934e-05 -2.53227207806799e-07 3.53903569630077e-05 2.42902777161e-05 -1.8004749433287e-05 -4.5656263786812e-07 -2.53227207806799e-07 8.95138289746813e-06 -6.32839741433971e-07 -6.25146661645235e-07 1.40744012282862e-06 -9.92391803740393e-06 3.53903569630077e-05 -6.32839741433971e-07 6.91965079993613e-05 2.75808212200656e-05 -2.31989218917914e-06 -8.54886101099368e-06 2.42902777161e-05 -6.25146661645235e-07 2.75808212200656e-05 3.50101300067244e-05 1.20846683323722e-06 2.17068563107722e-05 -1.8004749433287e-05 1.40744012282862e-06 -2.31989218917914e-06 1.20846683323722e-06 4.02647261415753e-05 805 801 0 10 0 803 811 0 21 0 0 0 0 0 0 6 18 0 2145 0 0 0 0 0 2568 +891 892 0.999991553442385 -0.000197945821128131 0.00410534545896561 -0.00142686099704729 0.000179877407548614 0.99999029895933 0.00440109433530953 0.000344529391287078 -0.00410617681107441 -0.00440031870231441 0.999981888089636 0.00103457635308449 5.48042212138543e-05 -6.64420313017607e-05 -4.63406009986203e-06 -1.74072796011006e-05 -9.53363239028876e-06 8.64845907881104e-06 -6.64420313017607e-05 0.000116886769105257 7.76926023730804e-06 4.17343801235186e-05 1.99786990625905e-05 -3.87912639889451e-06 -4.63406009986203e-06 7.76926023730804e-06 1.04447255849445e-05 -1.56014328511271e-06 3.17249154370654e-06 1.29233384871074e-06 -1.74072796011006e-05 4.17343801235186e-05 -1.56014328511271e-06 5.41930819858314e-05 1.53550379427846e-05 -9.84685219970366e-07 -9.53363239028876e-06 1.99786990625905e-05 3.17249154370654e-06 1.53550379427846e-05 2.41738266638443e-05 -1.89358289429492e-06 8.64845907881104e-06 -3.87912639889451e-06 1.29233384871074e-06 -9.84685219970366e-07 -1.89358289429492e-06 2.89163707015232e-05 942 945 0 20 0 941 961 0 39 0 0 0 0 0 0 12 36 0 3014 0 0 0 0 0 1430 +885 886 0.999985061787835 0.000448057640847246 0.00544751737311801 0.00442537532910397 -0.000455177306298748 0.999999043867239 0.00130578644026344 0.000868710778175641 -0.00544692709697631 -0.00130824652043247 0.999984309615027 -0.000994189434869126 3.61129329147097e-05 -5.37876404532811e-05 1.93895888651092e-06 -1.2444340416971e-05 -5.31044114502916e-06 2.48125760811503e-05 -5.37876404532811e-05 0.000130423203111887 -1.51338042839712e-06 5.76184815360423e-05 2.91717225569944e-05 -4.10875808989832e-05 1.93895888651092e-06 -1.51338042839712e-06 9.8472841684103e-06 -5.00110985230448e-07 2.20756795066283e-06 1.78888949336552e-06 -1.2444340416971e-05 5.76184815360423e-05 -5.00110985230448e-07 7.24903704573294e-05 2.27441989482011e-05 -1.07402951761104e-05 -5.31044114502916e-06 2.91717225569944e-05 2.20756795066283e-06 2.27441989482011e-05 2.83854170360619e-05 -5.48651834222486e-06 2.48125760811503e-05 -4.10875808989832e-05 1.78888949336552e-06 -1.07402951761104e-05 -5.48651834222486e-06 4.35446218526745e-05 831 833 0 14 0 829 842 0 24 0 0 0 0 0 0 3 13 0 2133 0 0 0 0 0 2698 +886 887 0.999708378287358 0.000198396964987657 0.0241478574764891 0.00872818728124849 -0.000787133355247857 0.999702614217246 0.0243734188879008 0.00232867974102452 -0.0241358406346578 -0.0243853186538193 0.999411235393624 -0.00291630021138957 3.5937434653909e-05 -5.10843323016304e-05 2.00539325202683e-06 -2.43600648452223e-05 -1.2679007086429e-05 1.57604012211312e-05 -5.10843323016304e-05 0.000111362066163258 -3.63949444903608e-07 7.3687541358648e-05 3.94624170325323e-05 -1.23976432817895e-05 2.00539325202683e-06 -3.63949444903608e-07 9.02546825255129e-06 9.62938467555342e-09 3.50744119043498e-06 3.66774160259707e-07 -2.43600648452223e-05 7.3687541358648e-05 9.62938467555342e-09 0.000103683056034676 4.38369700426818e-05 2.09296608808307e-06 -1.2679007086429e-05 3.94624170325323e-05 3.50744119043498e-06 4.38369700426818e-05 3.68530051016907e-05 1.15306449185494e-06 1.57604012211312e-05 -1.23976432817895e-05 3.66774160259707e-07 2.09296608808307e-06 1.15306449185494e-06 3.24396012588782e-05 834 830 0 9 0 833 840 0 23 0 0 0 0 0 0 8 22 0 2325 0 0 0 0 0 2604 +893 894 0.999999179484666 -4.90346427971159e-05 -0.0012800881210849 -0.00109099377088536 4.74047964498735e-05 0.999999188319896 -0.00127322909752449 -0.00166710979759824 0.00128014951439684 0.00127316737050367 0.999998370129705 -0.00233517942794578 4.24160102253006e-05 -4.21035148359196e-05 -3.07072301911385e-06 -5.86087691560519e-06 -6.34369020757069e-06 1.40208969343879e-05 -4.21035148359196e-05 6.94798184345871e-05 7.01138901327893e-06 1.3559177697022e-05 6.16421864391355e-06 -1.49359579095305e-05 -3.07072301911385e-06 7.01138901327893e-06 1.2588648367509e-05 -5.58281566904466e-06 3.55165791174359e-06 7.72522434785432e-07 -5.86087691560519e-06 1.3559177697022e-05 -5.58281566904466e-06 5.27603938655064e-05 1.42303253388697e-05 6.09398196122278e-07 -6.34369020757069e-06 6.16421864391355e-06 3.55165791174359e-06 1.42303253388697e-05 2.39368623550189e-05 -4.60602248468418e-06 1.40208969343879e-05 -1.49359579095305e-05 7.72522434785432e-07 6.09398196122278e-07 -4.60602248468418e-06 2.97224470081745e-05 1055 1052 0 13 0 1057 1077 0 39 0 0 0 0 0 0 19 42 0 2897 0 0 0 0 0 2161 +888 889 0.999951490165296 -0.000353040588022068 0.00984340787261673 -0.00405198563666793 0.000152179887090949 0.999791909362825 0.0203988924679191 -0.00693675130244312 -0.00984856118859242 -0.0203964049523187 0.999743463348241 0.00131409991773685 4.41211641499515e-05 -5.17036051264201e-05 6.07643847391093e-06 -2.90969051350709e-05 -1.83870379964037e-05 8.8975916622057e-06 -5.17036051264201e-05 8.21225774359286e-05 -5.17842288121197e-06 5.13879421858514e-05 2.95828584318439e-05 -3.61033760891112e-06 6.07643847391093e-06 -5.17842288121197e-06 9.26429023562176e-06 -3.17137753614607e-06 1.87997253487856e-06 1.71635954913319e-06 -2.90969051350709e-05 5.13879421858514e-05 -3.17137753614607e-06 7.97083546967191e-05 2.87162438716681e-05 8.79999243082704e-06 -1.83870379964037e-05 2.95828584318439e-05 1.87997253487856e-06 2.87162438716681e-05 3.57777994564573e-05 3.43159312591406e-06 8.8975916622057e-06 -3.61033760891112e-06 1.71635954913319e-06 8.79999243082704e-06 3.43159312591406e-06 2.86090092515645e-05 888 889 0 16 0 882 900 0 33 0 0 0 0 0 0 18 36 0 2630 0 0 0 0 0 1940 +892 893 0.999999918203746 0.000213034412343374 -0.00034381512582453 0.00107786961490097 -0.00021261521564532 0.999999234627889 0.00121882665161967 0.000183457145639729 0.000344074514697498 -0.0012187534515971 0.999999198126055 0.00154307146221478 4.72732501724421e-05 -4.88892072605246e-05 -3.69101008233126e-06 -8.70958449056712e-06 -8.22030174588366e-06 2.09729737079962e-05 -4.88892072605246e-05 7.85319548481145e-05 5.24265161249669e-06 2.26205498688748e-05 1.16871671532908e-05 -1.59625944556811e-05 -3.69101008233126e-06 5.24265161249669e-06 1.10909376359935e-05 -5.1489554481231e-06 3.39955547954875e-06 -2.82063892464406e-06 -8.70958449056712e-06 2.26205498688748e-05 -5.1489554481231e-06 5.40640417217594e-05 1.29055720321528e-05 8.13786637337521e-06 -8.22030174588366e-06 1.16871671532908e-05 3.39955547954875e-06 1.29055720321528e-05 2.59043654861206e-05 -1.64711589120882e-06 2.09729737079962e-05 -1.59625944556811e-05 -2.82063892464406e-06 8.13786637337521e-06 -1.64711589120882e-06 3.57664138506806e-05 1061 1060 0 21 0 1059 1083 0 45 0 0 0 0 0 0 18 43 0 2897 0 0 0 0 0 2298 +894 895 0.999999891489512 0.000200708498619153 0.00042040107291262 0.00097358916711191 -0.000200058504850474 0.999998785548512 -0.00154559959109649 -0.000475565779569095 -0.000420710777329307 0.00154551531857264 0.999998717191598 -0.00422474223610195 2.88665059012178e-05 -2.72288236729396e-05 -6.52606846768558e-06 4.36602691822825e-06 2.91929821272308e-06 5.08050236626299e-06 -2.72288236729396e-05 3.44433641197933e-05 7.85565041716741e-06 -2.6383917883241e-06 -2.3412476597151e-06 -5.82747997804602e-06 -6.52606846768558e-06 7.85565041716741e-06 1.24056289642936e-05 -5.26168361566074e-06 1.39987774129458e-06 -6.75038462001537e-07 4.36602691822825e-06 -2.6383917883241e-06 -5.26168361566074e-06 3.03521776448273e-05 1.60638743247797e-06 5.63499829343922e-07 2.91929821272308e-06 -2.3412476597151e-06 1.39987774129458e-06 1.60638743247797e-06 2.15145333730792e-05 -2.57344651660138e-06 5.08050236626299e-06 -5.82747997804602e-06 -6.75038462001537e-07 5.63499829343922e-07 -2.57344651660138e-06 3.50372667278361e-05 1074 1075 0 10 0 1080 1099 0 35 0 0 0 0 0 0 15 38 0 2951 0 0 0 0 0 1264 +890 891 0.999885999341045 -0.000168737514431357 0.0150983392931271 -0.00171742901783391 -0.000156078212136951 0.999768630100755 0.0215095770774867 -0.00710961549717833 -0.0150984754644586 -0.0215094814933291 0.999654629481871 -0.00310553293238996 3.66354942222932e-05 -4.49929419037714e-05 -4.25797984283763e-06 -1.24729292344026e-05 -9.59607550892567e-06 1.78169454509205e-05 -4.49929419037714e-05 9.33807179171728e-05 6.42438647694214e-06 4.46050033051409e-05 2.44048615518614e-05 -1.80562614228308e-05 -4.25797984283763e-06 6.42438647694214e-06 8.95818382453464e-06 1.40267903115372e-06 3.55653620280728e-06 -2.73830889115743e-06 -1.24729292344026e-05 4.46050033051409e-05 1.40267903115372e-06 6.19060461322296e-05 1.44279511810269e-05 -1.6389629436136e-06 -9.59607550892567e-06 2.44048615518614e-05 3.55653620280728e-06 1.44279511810269e-05 2.56727939322718e-05 -2.95495284507114e-06 1.78169454509205e-05 -1.80562614228308e-05 -2.73830889115743e-06 -1.6389629436136e-06 -2.95495284507114e-06 2.85646293729654e-05 918 924 0 19 0 920 942 0 38 0 0 0 0 0 0 16 39 0 2868 0 0 0 0 0 2580 +902 903 0.999999460418349 1.26592323889248e-05 0.00103875057389523 0.00111055420243333 -1.45858856731666e-05 0.999998279763793 0.00185479290144761 0.000286643729093244 -0.00103872530674451 -0.00185480705173251 0.999997740367716 -0.000518163396009008 4.00255471252922e-05 -3.43366387775174e-05 -5.34680730764529e-06 -4.37051827760854e-06 -5.94631016014158e-06 8.94580703137473e-06 -3.43366387775174e-05 4.65765520106559e-05 5.44987775698309e-06 1.36636027353025e-05 9.82930395559491e-06 -3.73348928172987e-06 -5.34680730764529e-06 5.44987775698309e-06 1.03697502234257e-05 -4.13970593140714e-06 3.80010797963613e-06 -3.20329228458072e-06 -4.37051827760854e-06 1.36636027353025e-05 -4.13970593140714e-06 4.27858241046479e-05 1.12178606795847e-05 9.82090802600636e-06 -5.94631016014158e-06 9.82930395559491e-06 3.80010797963613e-06 1.12178606795847e-05 2.39498448694557e-05 3.32478618562606e-07 8.94580703137473e-06 -3.73348928172987e-06 -3.20329228458072e-06 9.82090802600636e-06 3.32478618562606e-07 3.67297667581314e-05 1109 1112 0 22 0 1108 1128 0 39 0 0 0 0 0 0 16 39 0 2932 0 0 0 0 0 2297 +898 899 0.999999477091201 -0.000231289270914625 0.000996153902789403 0.000705985397803768 0.000231666632467519 0.999999901450938 -0.000378719798875312 -0.000667094089998865 -0.000996066210793208 0.000378950376459475 0.999999432124197 -0.00112094938759684 3.01782551402023e-05 -2.89179400646669e-05 -1.1693029262191e-06 -5.51866539743091e-06 -6.05823644406418e-06 1.85151095588923e-05 -2.89179400646669e-05 3.99323766812238e-05 3.6121931053664e-06 8.14639306140978e-06 7.31311060564767e-06 -1.80392133486455e-05 -1.1693029262191e-06 3.6121931053664e-06 1.3410988430265e-05 -7.33721866164992e-06 2.95827130775336e-06 -2.70667028470502e-06 -5.51866539743091e-06 8.14639306140978e-06 -7.33721866164992e-06 3.50464229164644e-05 9.92319283656392e-06 3.90619662244596e-06 -6.05823644406418e-06 7.31311060564767e-06 2.95827130775336e-06 9.92319283656392e-06 2.46018383544556e-05 -1.51463880679955e-06 1.85151095588923e-05 -1.80392133486455e-05 -2.70667028470502e-06 3.90619662244596e-06 -1.51463880679955e-06 2.50368426853468e-05 1116 1119 0 21 0 1115 1140 0 43 0 0 0 0 0 0 14 39 0 3040 0 0 0 0 0 1065 +896 897 0.999996284936971 -0.000414290463976605 0.0026941558359196 -0.000514018988564658 0.000407555580464214 0.999996792241871 0.00249988088055728 0.000364662516037475 -0.00269518287052921 -0.00249877357509668 0.999993246037149 0.000468925979752364 3.89346003184043e-05 -4.23441044579994e-05 -3.85279259212033e-06 -1.38820030749657e-06 -5.291535648182e-06 1.56887295471881e-05 -4.23441044579994e-05 7.00622191075495e-05 5.90623674784611e-06 1.44675640626514e-05 9.63181441159388e-06 -1.41122024141767e-05 -3.85279259212033e-06 5.90623674784611e-06 1.02689948756581e-05 -5.9956806811455e-06 4.80533100275469e-06 -3.69725362755393e-06 -1.38820030749657e-06 1.44675640626514e-05 -5.9956806811455e-06 5.39708281750904e-05 1.25754738858471e-05 1.15342924891417e-05 -5.291535648182e-06 9.63181441159388e-06 4.80533100275469e-06 1.25754738858471e-05 2.25256989908603e-05 -1.80338492500235e-06 1.56887295471881e-05 -1.41122024141767e-05 -3.69725362755393e-06 1.15342924891417e-05 -1.80338492500235e-06 3.10043648205824e-05 1104 1114 0 26 0 1101 1121 0 34 0 0 0 0 0 0 16 38 0 2908 0 0 0 0 0 2116 +901 902 0.999998326620801 -0.000187206967409441 0.00181981019570831 0.0010911823494194 0.000186892226292119 0.999999967550167 0.000173121232529765 0.000482319586862191 -0.00181984254615671 -0.00017278083445339 0.999998329158549 -0.000155399269305325 2.59789075976217e-05 -2.19091243288276e-05 -3.18305517036542e-06 -6.73108255093239e-07 -4.07648477869304e-06 7.90965111056584e-06 -2.19091243288276e-05 3.36852064207153e-05 4.502926553198e-06 4.78849951867786e-06 4.81757466770919e-06 -6.27827475827972e-06 -3.18305517036542e-06 4.502926553198e-06 9.98592131016288e-06 -4.09360962555987e-06 3.91808987620462e-06 -2.53528705799368e-06 -6.73108255093239e-07 4.78849951867786e-06 -4.09360962555987e-06 2.99158899175324e-05 2.08472010011311e-06 1.35013259642784e-06 -4.07648477869304e-06 4.81757466770919e-06 3.91808987620462e-06 2.08472010011311e-06 1.77959984517416e-05 -1.2863176000276e-06 7.90965111056584e-06 -6.27827475827972e-06 -2.53528705799368e-06 1.35013259642784e-06 -1.2863176000276e-06 2.65399448813204e-05 1101 1108 0 22 0 1102 1128 0 45 0 0 0 0 0 0 14 40 0 3002 0 0 0 0 0 2388 +895 896 0.999995393846402 -0.000423163137119993 0.00300553139037975 0.00246892114406512 0.000425058071158831 0.999999711293773 -0.000629871420396913 -0.000783976551754044 -0.00300526398429788 0.000631146044488006 0.999995285010412 -0.000128624439396417 3.25993801945912e-05 -3.94900208514801e-05 -3.85888186269998e-06 -8.20107532776837e-06 -7.87771670227809e-06 1.5386412561192e-05 -3.94900208514801e-05 7.23397559398276e-05 5.31007700917295e-06 2.9343333562788e-05 1.8190303436581e-05 -1.60141492509471e-05 -3.85888186269998e-06 5.31007700917295e-06 1.03490240323048e-05 -4.78379979752046e-06 4.0513154775922e-06 -2.70764412980525e-06 -8.20107532776837e-06 2.9343333562788e-05 -4.78379979752046e-06 6.47551168671644e-05 1.77184817655719e-05 3.15205299652556e-06 -7.87771670227809e-06 1.8190303436581e-05 4.0513154775922e-06 1.77184817655719e-05 2.62665171650351e-05 -6.31947391707814e-06 1.5386412561192e-05 -1.60141492509471e-05 -2.70764412980525e-06 3.15205299652556e-06 -6.31947391707814e-06 3.50743484943144e-05 1043 1049 0 25 0 1041 1066 0 48 0 0 0 0 0 0 11 38 0 2930 0 0 0 0 0 2514 +897 898 0.999999792554732 0.000189228078716776 -0.000615697350314708 0.000474886360957024 -0.00019006070643282 0.999999067234934 -0.00135255542965367 0.000404739245652621 0.000615440834548417 0.00135267216894579 0.999998895754682 -0.00107631965866073 3.77106352604631e-05 -4.25238912355973e-05 -4.59244951542555e-06 -6.96574669235446e-06 -5.95235986358917e-06 1.73769229501676e-05 -4.25238912355973e-05 7.11326630511295e-05 7.0469510824435e-06 1.96033558934633e-05 1.09006144043427e-05 -1.80940524105888e-05 -4.59244951542555e-06 7.0469510824435e-06 1.16068153112609e-05 -7.60856065241746e-06 4.88227827558403e-06 -4.93632287208597e-06 -6.96574669235446e-06 1.96033558934633e-05 -7.60856065241746e-06 4.80273162880348e-05 9.25042471480189e-06 4.0015656828142e-06 -5.95235986358917e-06 1.09006144043427e-05 4.88227827558403e-06 9.25042471480189e-06 2.06356973355512e-05 -1.08119334475014e-06 1.73769229501676e-05 -1.80940524105888e-05 -4.93632287208597e-06 4.0015656828142e-06 -1.08119334475014e-06 3.24436245315426e-05 1054 1051 0 10 0 1056 1083 0 47 0 0 0 0 0 0 13 40 0 3021 0 0 0 0 0 2159 +900 901 0.999997212710335 -0.000131000116199938 -0.00235741607065522 -0.0016446635627884 0.000131175432459365 0.99999998864268 7.42135109233484e-05 0.000768124462190123 0.00235740632190274 -7.45225391413512e-05 0.999997218537044 0.0032838114355646 3.38558609105047e-05 -3.55031810767501e-05 -2.3825065799529e-06 -7.3540144767257e-06 -6.66381567629575e-06 1.74804590920378e-05 -3.55031810767501e-05 6.40509348101348e-05 4.25636041016692e-06 2.18419822644348e-05 1.05631320355899e-05 -1.18212287090449e-05 -2.3825065799529e-06 4.25636041016692e-06 1.01230250400423e-05 -4.52157160027245e-06 4.27879321745162e-06 -2.25092797711278e-06 -7.3540144767257e-06 2.18419822644348e-05 -4.52157160027245e-06 4.69482153600263e-05 1.00468268306573e-05 4.51138426037166e-06 -6.66381567629575e-06 1.05631320355899e-05 4.27879321745162e-06 1.00468268306573e-05 1.9747568361143e-05 -3.47733428615231e-06 1.74804590920378e-05 -1.18212287090449e-05 -2.25092797711278e-06 4.51138426037166e-06 -3.47733428615231e-06 3.27865451830269e-05 1047 1042 0 4 0 1058 1075 0 41 0 0 0 0 0 0 17 41 0 2903 0 0 0 0 0 2160 +899 900 0.999998937204387 -0.000582094407096503 0.0013366960006126 -0.000596108575046455 0.000585280473401948 0.999996986071555 -0.0023843855755952 -0.00357720301365891 -0.00133530403439859 0.00238516538354871 0.999996263967635 -0.00254382463940778 3.53888681924119e-05 -3.127926082883e-05 -3.09966673015599e-06 -1.73990771687062e-06 -7.8713634795628e-06 2.26064544022272e-05 -3.127926082883e-05 6.56426044478245e-05 6.1750119395374e-06 1.16218480732782e-05 6.58035713478724e-06 -2.15839321322714e-05 -3.09966673015599e-06 6.1750119395374e-06 1.16356076351678e-05 -5.73446050379728e-06 4.3218814742889e-06 -4.54508945616538e-06 -1.73990771687062e-06 1.16218480732782e-05 -5.73446050379728e-06 4.14980249301313e-05 5.50520025175467e-06 3.24980355466327e-06 -7.8713634795628e-06 6.58035713478724e-06 4.3218814742889e-06 5.50520025175467e-06 2.22807163482109e-05 -4.45935205825609e-06 2.26064544022272e-05 -2.15839321322714e-05 -4.54508945616538e-06 3.24980355466327e-06 -4.45935205825609e-06 3.39161399681147e-05 1064 1064 0 6 0 1075 1094 0 36 0 0 0 0 0 0 15 38 0 2942 0 0 0 0 0 2113 +903 904 0.999997332221182 0.000231163101727314 -0.00229828504326959 -0.000444511032886833 -0.000231635181142592 0.999999952131152 -0.000205141016228621 0.000185181379478846 0.00229823751221973 0.000205672832630078 0.999997337897968 0.00203633278244795 2.23757239773128e-05 -2.14162036870771e-05 -3.53953152985718e-06 -1.27672927161074e-06 -2.41521968227009e-06 7.82896058832828e-06 -2.14162036870771e-05 4.02146343520523e-05 4.56562112436886e-06 7.5314268312245e-06 3.59338965780066e-06 -1.36287939016731e-05 -3.53953152985718e-06 4.56562112436886e-06 1.03102644950717e-05 -4.99685450900385e-06 4.22155061813965e-06 -1.53034552805146e-06 -1.27672927161074e-06 7.5314268312245e-06 -4.99685450900385e-06 3.53840057865557e-05 5.03331114069124e-06 -2.88781954554181e-06 -2.41521968227009e-06 3.59338965780066e-06 4.22155061813965e-06 5.03331114069124e-06 1.66657204993329e-05 -4.18868820082783e-06 7.82896058832828e-06 -1.36287939016731e-05 -1.53034552805146e-06 -2.88781954554181e-06 -4.18868820082783e-06 3.09820042674986e-05 1045 1046 0 20 0 1040 1067 0 41 0 0 0 0 0 0 11 38 0 2913 0 0 0 0 0 2578 +910 911 0.999999749041449 -0.000173326493716235 0.000686931557667953 -0.000258593191363602 0.00017352886164652 0.99999994156452 -0.000294548281982138 0.000962345599095978 -0.000686880464505832 0.000294667410513959 0.999999720683133 -0.000813492749457432 3.92553378985552e-05 -4.55701248023726e-05 -4.26504965573025e-06 -8.63853474592485e-06 -5.82291976635559e-06 1.58748978913879e-05 -4.55701248023726e-05 9.9598180264827e-05 5.84642621727164e-06 3.8806593893223e-05 1.67866812140967e-05 -2.21174317003066e-05 -4.26504965573025e-06 5.84642621727164e-06 1.02228671168928e-05 -3.81592626699809e-06 3.60247697795607e-06 -1.67586803497482e-06 -8.63853474592485e-06 3.8806593893223e-05 -3.81592626699809e-06 5.84084233585122e-05 1.41205355148532e-05 -2.08064008980483e-06 -5.82291976635559e-06 1.67866812140967e-05 3.60247697795607e-06 1.41205355148532e-05 2.18438982019047e-05 -6.57066508142347e-06 1.58748978913879e-05 -2.21174317003066e-05 -1.67586803497482e-06 -2.08064008980483e-06 -6.57066508142347e-06 4.28713517830964e-05 1082 1084 0 19 0 1078 1099 0 40 0 0 0 0 0 0 18 44 0 3056 0 0 0 0 0 2329 +906 907 0.999999663344337 0.000304328456546766 0.000762033728505355 0.0012883561250818 -0.000304507129684907 0.999999926174515 0.000234363761874335 0.000132006183787455 -0.000761962348685924 -0.000234595727677837 0.999999682189061 -0.00144255878108242 3.13918101558228e-05 -2.80049954070149e-05 -5.09575343977685e-06 2.02851981677655e-06 -2.73437711342842e-06 9.72240749114897e-06 -2.80049954070149e-05 3.97356853197219e-05 5.65735072443454e-06 4.87179902575896e-06 3.02740208228735e-06 -6.92348389404154e-06 -5.09575343977685e-06 5.65735072443454e-06 1.21843430738053e-05 -5.85981806561194e-06 4.43769762167793e-06 -3.35729591130402e-06 2.02851981677655e-06 4.87179902575896e-06 -5.85981806561194e-06 4.11050061260559e-05 8.11891745145753e-06 7.10761942037887e-06 -2.73437711342842e-06 3.02740208228735e-06 4.43769762167793e-06 8.11891745145753e-06 2.10707699778474e-05 -2.02113915925559e-06 9.72240749114897e-06 -6.92348389404154e-06 -3.35729591130402e-06 7.10761942037887e-06 -2.02113915925559e-06 3.03055896396286e-05 1100 1107 0 23 0 1100 1117 0 34 0 0 0 0 0 0 14 38 0 3033 0 0 0 0 0 2335 +912 913 0.999999809918121 -0.000283162331021715 -0.000547706870943312 -0.00208850209099973 0.00028250938428722 0.999999249832938 -0.00119185653857443 -0.000781298093289692 0.000548043948947364 0.00119170157969322 0.999999139747218 -0.00354788048669409 5.1110420867047e-05 -5.37495893782115e-05 -3.69460738729744e-06 -7.0983374627901e-06 -9.61395615337239e-06 9.34342122626691e-06 -5.37495893782115e-05 9.06784645005896e-05 4.72251758449777e-06 2.98312716015747e-05 1.93940095383569e-05 -1.20906237276281e-05 -3.69460738729744e-06 4.72251758449777e-06 1.07424610278198e-05 -2.95159473561262e-06 4.40780683084092e-06 -9.72605415294061e-07 -7.0983374627901e-06 2.98312716015747e-05 -2.95159473561262e-06 5.48633995879573e-05 1.63062691423657e-05 4.65858162372901e-06 -9.61395615337239e-06 1.93940095383569e-05 4.40780683084092e-06 1.63062691423657e-05 2.4223222531751e-05 -3.05203862373615e-06 9.34342122626691e-06 -1.20906237276281e-05 -9.72605415294061e-07 4.65858162372901e-06 -3.05203862373615e-06 3.52622926043284e-05 1056 1056 0 20 0 1054 1071 0 40 0 0 0 0 0 0 20 45 0 2879 0 0 0 0 0 2196 +904 905 0.999999824575366 0.000581264369891686 -0.000113934060036203 0.00106694182753985 -0.000581103665175386 0.999998843442617 0.00140550060753448 0.00188019167452884 0.000114750895689945 -0.00140543415347518 0.999999005793042 0.000587463851287857 3.49797382766277e-05 -3.17716131984803e-05 -1.7618220340604e-06 -6.8270542075325e-06 -4.38769643226774e-06 1.24853431172625e-05 -3.17716131984803e-05 3.9099720051292e-05 3.64376089791063e-06 6.96597812073833e-06 5.35824282045402e-06 -1.2545979721674e-05 -1.7618220340604e-06 3.64376089791063e-06 1.55244968008277e-05 -9.08029403125495e-06 3.40729339618825e-07 -2.75621063740981e-06 -6.8270542075325e-06 6.96597812073833e-06 -9.08029403125495e-06 3.90821840267617e-05 1.26547375393028e-05 3.62276318993881e-06 -4.38769643226774e-06 5.35824282045402e-06 3.40729339618825e-07 1.26547375393028e-05 2.81606305949095e-05 9.8841091901221e-07 1.24853431172625e-05 -1.2545979721674e-05 -2.75621063740981e-06 3.62276318993881e-06 9.8841091901221e-07 3.02499112658828e-05 1089 1092 0 19 0 1089 1117 0 44 0 0 0 0 0 0 14 41 0 2999 0 0 0 0 0 1233 +909 910 0.999999868968265 -0.00046823592006768 0.000206926500435435 2.25957842455424e-05 0.000468294529636707 0.999999850226055 -0.00028328095724658 -0.0016223782031651 -0.000206793827123582 0.000283377822675975 0.999999938466659 0.00045327288521508 2.87509488458428e-05 -2.39556319893402e-05 -1.43965210086138e-06 -5.30844604285791e-06 -4.98248852147838e-06 1.64070954423834e-05 -2.39556319893402e-05 3.13993710745771e-05 2.50346403463881e-06 6.67426127868523e-06 4.38725535175827e-06 -1.1918255299397e-05 -1.43965210086138e-06 2.50346403463881e-06 1.07983150238713e-05 -6.76784388719278e-06 3.709705179175e-06 -2.13464091565686e-06 -5.30844604285791e-06 6.67426127868523e-06 -6.76784388719278e-06 4.35882027498044e-05 9.59987741343496e-06 -1.79900209223111e-06 -4.98248852147838e-06 4.38725535175827e-06 3.709705179175e-06 9.59987741343496e-06 2.227657267716e-05 -5.52187173009951e-06 1.64070954423834e-05 -1.1918255299397e-05 -2.13464091565686e-06 -1.79900209223111e-06 -5.52187173009951e-06 3.01364299072691e-05 1130 1128 0 17 0 1129 1152 0 46 0 0 0 0 0 0 15 40 0 2946 0 0 0 0 0 2327 +913 914 0.999999598564951 -0.000230679783177894 0.000865827219624945 0.000667940912498785 0.000231909238185066 0.999998964701727 -0.00142014561934118 -0.00140180579222313 -0.000865498724351969 0.00142034584257586 0.999998616763866 0.00265241893779533 2.85633151933879e-05 -1.88759263816858e-05 -5.01663107517519e-07 -2.24438900039544e-06 -4.4366560619291e-06 3.35406824174114e-06 -1.88759263816858e-05 2.55165871388364e-05 2.56694383583872e-06 3.8137460571411e-06 1.42372371984387e-06 -9.90021498563298e-07 -5.01663107517519e-07 2.56694383583872e-06 1.32307517509304e-05 -5.62920283666395e-06 3.77962558247945e-06 -2.95629270412146e-06 -2.24438900039544e-06 3.8137460571411e-06 -5.62920283666395e-06 3.13336942258333e-05 4.29737005713455e-06 6.69428169587047e-06 -4.4366560619291e-06 1.42372371984387e-06 3.77962558247945e-06 4.29737005713455e-06 2.27606959089898e-05 3.22913963104338e-06 3.35406824174114e-06 -9.90021498563298e-07 -2.95629270412146e-06 6.69428169587047e-06 3.22913963104338e-06 3.36612300172366e-05 1170 1173 0 13 0 1174 1199 0 40 0 0 0 0 0 0 20 44 0 3026 0 0 0 0 0 1208 +907 908 0.999999279850113 4.68324635468613e-05 -0.00119921056316672 0.00163119014441407 -4.53140531259484e-05 0.999999197378678 0.00126617085583343 0.0015455204962897 0.0011992688985552 -0.00126611560290946 0.999998479351538 0.000706692256309779 3.81614869677102e-05 -3.95456821850089e-05 -6.70526779467664e-07 -7.75840744696662e-06 -5.89085704188025e-06 4.29767668169401e-06 -3.95456821850089e-05 5.65951067873386e-05 2.04610341436117e-06 1.43662797920171e-05 9.40197991437071e-06 -5.43541856547886e-06 -6.70526779467664e-07 2.04610341436117e-06 1.20502789926295e-05 -7.87425143836476e-06 4.17888167994681e-06 -1.41605910377769e-06 -7.75840744696662e-06 1.43662797920171e-05 -7.87425143836476e-06 4.58710878646868e-05 1.20607082043267e-05 7.16385807663221e-06 -5.89085704188025e-06 9.40197991437071e-06 4.17888167994681e-06 1.20607082043267e-05 2.20012303680803e-05 6.89393173748814e-07 4.29767668169401e-06 -5.43541856547886e-06 -1.41605910377769e-06 7.16385807663221e-06 6.89393173748814e-07 3.49780981091364e-05 1068 1067 0 22 0 1063 1081 0 37 0 0 0 0 0 0 12 34 0 2945 0 0 0 0 0 2138 +905 906 0.999999124450016 6.78441286613047e-05 0.0013215507466039 0.00101847560285151 -6.82785915362996e-05 0.99999994364389 0.000328709978199967 0.000490413278966443 -0.00132152837108439 -0.000328799924021573 0.999999072726257 -0.00222266450015053 3.48592399402879e-05 -3.35511750971189e-05 -3.55053759680739e-06 -2.76290482869092e-06 -4.68486453423311e-06 1.70684055168566e-05 -3.35511750971189e-05 5.48282558183627e-05 5.95144534777324e-06 7.32621324198579e-06 4.53295494921539e-06 -2.10585016187039e-05 -3.55053759680739e-06 5.95144534777324e-06 1.20526807256811e-05 -5.79139030002713e-06 4.25622391755917e-06 -1.23068952978764e-06 -2.76290482869092e-06 7.32621324198579e-06 -5.79139030002713e-06 3.85163456666265e-05 8.10340637681446e-06 -1.48550435164265e-06 -4.68486453423311e-06 4.53295494921539e-06 4.25622391755917e-06 8.10340637681446e-06 2.12079367657282e-05 -4.35429047100368e-06 1.70684055168566e-05 -2.10585016187039e-05 -1.23068952978764e-06 -1.48550435164265e-06 -4.35429047100368e-06 3.41123286533712e-05 1084 1083 0 15 0 1083 1109 0 41 0 0 0 0 0 0 14 40 0 3043 0 0 0 0 0 2327 +908 909 0.999999921554676 -8.03992080879476e-06 0.000396012628367432 -0.000741765461957747 8.60747001459798e-06 0.99999897296211 -0.00143317850804533 -0.00114502284719207 -0.000396000699005749 0.001433181804286 0.99999889458607 -0.00229953527819578 4.31056734059317e-05 -4.91694191660101e-05 -3.06020789293457e-06 -9.98475988675023e-06 -8.44897484845647e-06 1.78122848195708e-05 -4.91694191660101e-05 8.42816620512774e-05 3.55824648916585e-06 2.97117278835655e-05 1.78903428913173e-05 -2.391183647182e-05 -3.06020789293457e-06 3.55824648916585e-06 1.00459839132005e-05 -3.64082641762282e-06 3.29717414734145e-06 -2.65023304813535e-07 -9.98475988675023e-06 2.97117278835655e-05 -3.64082641762282e-06 4.84468258476969e-05 1.48800949078723e-05 -2.58890148910138e-06 -8.44897484845647e-06 1.78903428913173e-05 3.29717414734145e-06 1.48800949078723e-05 2.33691499556043e-05 -6.8678808675894e-06 1.78122848195708e-05 -2.391183647182e-05 -2.65023304813535e-07 -2.58890148910138e-06 -6.8678808675894e-06 4.15412480677175e-05 1045 1044 0 21 0 1041 1064 0 43 0 0 0 0 0 0 14 38 0 2913 0 0 0 0 0 2157 +911 912 0.999999969328926 -0.000236612342869788 7.31897913723081e-05 0.000492849192116464 0.000236737942380105 0.999998491300584 -0.0017208578389329 -0.00183723111829996 -7.27825047458968e-05 0.00172087511295296 0.999998516644676 -0.000645961317573945 3.54726537775274e-05 -3.20807152596521e-05 -2.60832124752968e-06 -3.69276901000964e-06 -4.84324121773977e-06 1.23213076874828e-05 -3.20807152596521e-05 4.829703078539e-05 3.74285782206521e-06 1.15586105818812e-05 6.26362125694847e-06 -8.49823101985435e-06 -2.60832124752968e-06 3.74285782206521e-06 1.04727925475923e-05 -4.99576375920857e-06 3.23973783934243e-06 -3.0753276640626e-06 -3.69276901000964e-06 1.15586105818812e-05 -4.99576375920857e-06 4.33001041957372e-05 1.05227811979253e-05 6.49688148908675e-06 -4.84324121773977e-06 6.26362125694847e-06 3.23973783934243e-06 1.05227811979253e-05 2.33938825285778e-05 -1.78110836395995e-06 1.23213076874828e-05 -8.49823101985435e-06 -3.0753276640626e-06 6.49688148908675e-06 -1.78110836395995e-06 3.08186118036023e-05 1097 1098 0 19 0 1097 1118 0 40 0 0 0 0 0 0 19 41 0 2901 0 0 0 0 0 2138 +914 915 0.999999839150295 -0.000567131052458431 -7.8583845193127e-06 -0.00113424382571242 0.000567112948152465 0.999997552037977 -0.00213876154781916 -0.00292014939486117 9.07132336985813e-06 0.00213875674720838 0.999997712816028 -0.00293298463283558 3.77376783417038e-05 -3.65658257755319e-05 -4.80132731604837e-06 -1.13095581875616e-06 -1.8005846065362e-06 1.08389213343589e-05 -3.65658257755319e-05 5.95186921568726e-05 5.15183776342708e-06 1.25226297652604e-05 6.10391631263481e-06 -1.61213476291594e-05 -4.80132731604837e-06 5.15183776342708e-06 1.23667371765038e-05 -5.77923322428642e-06 3.31957302431905e-06 -2.68400712052567e-06 -1.13095581875616e-06 1.25226297652604e-05 -5.77923322428642e-06 3.74556553418038e-05 4.54791240683026e-06 4.97706913146755e-06 -1.8005846065362e-06 6.10391631263481e-06 3.31957302431905e-06 4.54791240683026e-06 1.90459118543352e-05 -1.36700274558169e-06 1.08389213343589e-05 -1.61213476291594e-05 -2.68400712052567e-06 4.97706913146755e-06 -1.36700274558169e-06 3.4812297520319e-05 1045 1042 0 8 0 1052 1072 0 38 0 0 0 0 0 0 12 38 0 2977 0 0 0 0 0 1213 +919 920 0.999999855465001 0.000138712630464752 -0.000519450462249512 0.000205417673842977 -0.00013863444848696 0.999999979058798 0.000150541998123325 0.000674230797881852 0.000519471333448151 -0.000150469962636387 0.999999853754151 -0.00563612346273973 2.50103565209518e-05 -2.00377667826686e-05 -5.79500695889508e-06 3.63224076160712e-06 1.9966990052331e-06 9.18605162051374e-06 -2.00377667826686e-05 2.84630053293644e-05 7.03887039179564e-06 5.04965586350042e-07 -1.28018662833853e-06 -3.02462132203249e-06 -5.79500695889508e-06 7.03887039179564e-06 1.12285059273091e-05 -5.90063057232491e-06 4.47623786811368e-06 -4.77512789411821e-06 3.63224076160712e-06 5.04965586350042e-07 -5.90063057232491e-06 3.27093666891158e-05 5.93366065808097e-06 1.05734288301804e-05 1.9966990052331e-06 -1.28018662833853e-06 4.47623786811368e-06 5.93366065808097e-06 1.89093015731345e-05 -3.52568901673129e-08 9.18605162051374e-06 -3.02462132203249e-06 -4.77512789411821e-06 1.05734288301804e-05 -3.52568901673129e-08 3.11481283435381e-05 1112 1111 0 13 0 1115 1140 0 43 0 0 0 0 0 0 20 46 0 2765 0 0 0 0 0 2057 +917 918 0.999996093644888 -4.74580923626293e-05 0.00279471692562151 0.00201916359625593 4.63552082044998e-05 0.999999921033425 0.00039469524813708 0.000438988837268674 -0.00279473543641583 -0.00039456415663232 0.999996016878551 0.00234054650789363 2.97957655636526e-05 -2.89985789244754e-05 -5.17663978078813e-06 1.09246505448844e-06 -1.37541118461206e-06 1.16137903618803e-05 -2.89985789244754e-05 4.64839524069904e-05 7.07401534757145e-06 5.91757629748885e-06 3.97356072264348e-06 -7.09202267516589e-06 -5.17663978078813e-06 7.07401534757145e-06 1.22932525895356e-05 -7.37221530450363e-06 4.26127166669289e-06 -3.52172392781615e-06 1.09246505448844e-06 5.91757629748885e-06 -7.37221530450363e-06 3.22118759174958e-05 2.10409294873401e-06 7.35288443087602e-06 -1.37541118461206e-06 3.97356072264348e-06 4.26127166669289e-06 2.10409294873401e-06 1.95389207581404e-05 2.69654264753529e-06 1.16137903618803e-05 -7.09202267516589e-06 -3.52172392781615e-06 7.35288443087602e-06 2.69654264753529e-06 2.34161927062557e-05 1126 1124 0 19 0 1121 1142 0 39 0 0 0 0 0 0 10 34 0 2659 0 0 0 0 0 1195 +918 919 0.999999774567321 0.000666119189972997 -8.45608197648341e-05 -0.000174597650303391 -0.000666058301534613 0.99999952038336 0.000718052497745233 0.00270985736924779 8.5039087756214e-05 -0.000717996013436746 0.999999738625005 0.000218375912550121 2.50844915197832e-05 -2.07789912240082e-05 -3.51132043437978e-06 -5.98849840207173e-06 -4.92052008215848e-06 9.67996555004948e-06 -2.07789912240082e-05 2.14583407576412e-05 4.57432069570054e-06 1.99299545949198e-06 2.81537304888721e-06 -9.73136116536371e-06 -3.51132043437978e-06 4.57432069570054e-06 1.08743461542599e-05 -2.43533598533046e-06 2.77587075641451e-06 -5.44239133160926e-06 -5.98849840207173e-06 1.99299545949198e-06 -2.43533598533046e-06 3.68952545690737e-05 6.94990555117266e-06 6.81787507893521e-06 -4.92052008215848e-06 2.81537304888721e-06 2.77587075641451e-06 6.94990555117266e-06 2.2334389924329e-05 6.31120507447154e-07 9.67996555004948e-06 -9.73136116536371e-06 -5.44239133160926e-06 6.81787507893521e-06 6.31120507447154e-07 2.54575940416647e-05 1129 1132 0 10 0 1138 1161 0 42 0 0 0 0 0 0 11 35 0 2745 0 0 0 0 0 2132 +916 917 0.9999983631511 9.07321312833471e-05 -0.0018070591579284 0.000417970615897733 -9.1960426755148e-05 0.999999764810104 -0.000679649186010068 -0.00143456128239982 0.00180699706690718 0.000679814251458381 0.999998136305355 0.00278471170619616 4.19440154249986e-05 -3.31576445883694e-05 -4.95357441500166e-06 -8.24426886632244e-07 -7.87536194276916e-06 1.61286398323627e-05 -3.31576445883694e-05 5.18393994990406e-05 5.43496786501828e-06 1.12591554241037e-05 8.82774300533808e-06 -1.23917079265378e-05 -4.95357441500166e-06 5.43496786501828e-06 1.17498788363557e-05 -5.74345512184423e-06 3.7730183275774e-06 -4.4613057448932e-06 -8.24426886632244e-07 1.12591554241037e-05 -5.74345512184423e-06 4.8318425051281e-05 5.53421879429821e-06 7.78799789417572e-06 -7.87536194276916e-06 8.82774300533808e-06 3.7730183275774e-06 5.53421879429821e-06 2.40001551347869e-05 -1.71285963787181e-06 1.61286398323627e-05 -1.23917079265378e-05 -4.4613057448932e-06 7.78799789417572e-06 -1.71285963787181e-06 3.20621711843126e-05 1042 1037 0 13 0 1041 1066 0 42 0 0 0 0 0 0 18 45 0 2597 0 0 0 0 0 2299 +924 925 0.999991165576376 0.000190060268951854 0.004199124467683 0.00287093150870197 -0.000198628179258626 0.999997899305606 0.00204008118019937 0.0035569217592851 -0.00419872790822798 -0.0020408972217055 0.999989102651865 0.000844798008253369 4.15043605651872e-05 -4.93865291679896e-05 -3.93755595095303e-06 -2.21056670828314e-05 -8.44854272760688e-06 1.40344213524399e-05 -4.93865291679896e-05 7.6574847879478e-05 4.1413686841592e-06 4.64185201745988e-05 1.96521376621818e-05 -1.08564721690575e-05 -3.93755595095303e-06 4.1413686841592e-06 1.17140528677908e-05 -5.78604034871726e-06 1.60848939604696e-07 -7.87753562164382e-07 -2.21056670828314e-05 4.64185201745988e-05 -5.78604034871726e-06 8.47718944187462e-05 2.8727208997379e-05 1.05509949236917e-05 -8.44854272760688e-06 1.96521376621818e-05 1.60848939604696e-07 2.8727208997379e-05 3.33103777281879e-05 -1.23837137385616e-06 1.40344213524399e-05 -1.08564721690575e-05 -7.87753562164382e-07 1.05509949236917e-05 -1.23837137385616e-06 3.32719728370931e-05 1091 1092 0 5 0 1101 1125 0 46 0 0 0 0 0 0 19 46 0 2901 0 0 0 0 0 2168 +915 916 0.999999533233471 -0.000158745970933065 0.000953064822995531 -5.51607292014843e-05 0.000160663773273363 0.999997961996658 -0.0020125083062211 -0.00179385877908288 -0.000952743403061155 0.00201266048984022 0.999997520735807 -0.00358620793846666 2.28655445097561e-05 -2.00889328904579e-05 -3.56533511710844e-06 -8.04926396667682e-07 -4.19194414040231e-06 8.06701314656618e-06 -2.00889328904579e-05 2.89211849830125e-05 4.67855729980258e-06 4.74515317016914e-06 6.08045987059929e-06 -6.11919376357252e-06 -3.56533511710844e-06 4.67855729980258e-06 1.10489776302526e-05 -6.26710302775478e-06 5.05765779788747e-06 -4.9719501328883e-06 -8.04926396667682e-07 4.74515317016914e-06 -6.26710302775478e-06 3.79758820656086e-05 7.69815809905521e-06 8.20938475689596e-06 -4.19194414040231e-06 6.08045987059929e-06 5.05765779788747e-06 7.69815809905521e-06 2.07994737138206e-05 -1.07236587849749e-06 8.06701314656618e-06 -6.11919376357252e-06 -4.9719501328883e-06 8.20938475689596e-06 -1.07236587849749e-06 2.84772885929627e-05 1118 1115 0 17 0 1114 1141 0 48 0 0 0 0 0 0 14 41 0 2842 0 0 0 0 0 2157 +920 921 0.999970956438083 0.000665369497755988 -0.00759233585511636 -0.000168007556994912 -0.000682191877369244 0.99999731788687 -0.00221333081783631 0.000852544195438878 0.00759084280879804 0.00221844596467627 0.999968728312518 -0.00267280458913262 3.75899743878074e-05 -4.14361881587662e-05 1.32969546673162e-07 -8.87840258280374e-06 -9.21901523627389e-07 4.00870670295514e-06 -4.14361881587662e-05 6.74446058665214e-05 1.5144521336729e-06 2.26460764858413e-05 5.97542794411286e-06 5.65035183691137e-06 1.32969546673162e-07 1.5144521336729e-06 1.14110073944983e-05 -6.84612294565625e-06 3.40839636058733e-06 4.27669178874661e-07 -8.87840258280374e-06 2.26460764858413e-05 -6.84612294565625e-06 5.88039551980792e-05 1.4597538087317e-05 9.57588546417436e-06 -9.21901523627389e-07 5.97542794411286e-06 3.40839636058733e-06 1.4597538087317e-05 2.13251989863859e-05 2.24840046341153e-06 4.00870670295514e-06 5.65035183691137e-06 4.27669178874661e-07 9.57588546417436e-06 2.24840046341153e-06 3.41406693745663e-05 1090 1092 0 22 0 1095 1116 0 49 0 0 0 0 0 0 21 42 0 2869 0 0 0 0 0 2097 +921 922 0.999996962882449 -0.000289071202902853 -0.00244758324032853 -0.00296846216036258 0.000287163594356568 0.999999654802349 -0.000779700104875943 -0.00236633252844517 0.00244780778427577 0.00077899488003429 0.999996700696571 -0.000294210884283187 4.06929734966024e-05 -4.06419573222694e-05 -8.54921844129496e-06 -3.78140820671992e-06 -7.5013092641762e-08 2.28530537182241e-06 -4.06419573222694e-05 6.15900132888766e-05 8.09748706495884e-06 2.01730975220928e-05 6.47001694321475e-06 4.24216505297636e-06 -8.54921844129496e-06 8.09748706495884e-06 1.33385606849208e-05 -7.19754585068429e-06 -8.7817585929513e-07 -6.22812074057846e-07 -3.78140820671992e-06 2.01730975220928e-05 -7.19754585068429e-06 5.19517408975373e-05 1.51775894170666e-05 8.57458566138767e-06 -7.5013092641762e-08 6.47001694321475e-06 -8.7817585929513e-07 1.51775894170666e-05 2.96353486369508e-05 -1.88146843371111e-06 2.28530537182241e-06 4.24216505297636e-06 -6.22812074057846e-07 8.57458566138767e-06 -1.88146843371111e-06 2.99993676116079e-05 1132 1126 0 14 0 1126 1151 0 40 0 0 0 0 0 0 17 41 0 2980 0 0 0 0 0 1122 +926 927 0.999999978565046 -0.000198090896114363 -6.02486818920492e-05 -0.00115395495293974 0.000198104905555791 0.999999953323534 0.000232609922761556 0.000226781886667373 6.02026011718087e-05 -0.000232621853335009 0.99999997113136 8.90190695780415e-05 1.58934041685083e-05 -1.48960654017872e-05 -4.16520121146754e-06 2.58177401446114e-07 1.4908801246668e-07 1.03620900615373e-05 -1.48960654017872e-05 2.00537157588096e-05 4.82333737587043e-06 2.91043494049215e-06 1.23674069063086e-06 -1.00849346456963e-05 -4.16520121146754e-06 4.82333737587043e-06 1.05432740159936e-05 -6.2641534248055e-06 3.13165633362922e-06 -1.74412574146431e-06 2.58177401446114e-07 2.91043494049215e-06 -6.2641534248055e-06 3.43472329403345e-05 8.30977180146599e-06 -1.75406156438577e-06 1.4908801246668e-07 1.23674069063086e-06 3.13165633362922e-06 8.30977180146599e-06 2.00844595159448e-05 -3.48598391111457e-06 1.03620900615373e-05 -1.00849346456963e-05 -1.74412574146431e-06 -1.75406156438577e-06 -3.48598391111457e-06 1.95503105121282e-05 1137 1135 0 14 0 1135 1163 0 43 0 0 0 0 0 0 11 39 0 2950 0 0 0 0 0 2576 +922 923 0.999999762905863 4.02081175578515e-05 0.00068743837892655 -0.00143844607019932 -4.04613656954193e-05 0.999999931328048 0.000368384008440957 0.000144054531347487 -0.000687423519691297 -0.000368411735794911 0.999999695860802 -0.00237756657589263 2.44091728527792e-05 -2.27027505160906e-05 -2.87900430605275e-06 -3.02462926366458e-06 -5.07238395107504e-07 1.33533155964951e-05 -2.27027505160906e-05 3.17191954793439e-05 3.79060102992562e-06 6.41765361749262e-06 2.26216074543736e-06 -1.36900558126383e-05 -2.87900430605275e-06 3.79060102992562e-06 1.3049956740284e-05 -3.68916845278474e-06 -1.27861202238799e-06 6.75929012511554e-07 -3.02462926366458e-06 6.41765361749262e-06 -3.68916845278474e-06 4.17615047596723e-05 1.29952160183613e-05 3.40914255877596e-06 -5.07238395107504e-07 2.26216074543736e-06 -1.27861202238799e-06 1.29952160183613e-05 2.61103381257006e-05 -3.7290391916775e-06 1.33533155964951e-05 -1.36900558126383e-05 6.75929012511554e-07 3.40914255877596e-06 -3.7290391916775e-06 2.55469369906819e-05 1159 1168 0 26 0 1156 1177 0 39 0 0 0 0 0 0 10 35 0 2882 0 0 0 0 0 2362 +925 926 0.999996336287467 8.24638831773469e-05 -0.0027056628303263 -0.00180076252079694 -8.75547486186425e-05 0.999998226153892 -0.00188149494720673 -0.00197600970293455 0.00270550287551729 0.00188172494757907 0.999994569667962 -0.00255555638303175 3.33179812155774e-05 -3.53092901148887e-05 -5.00967501739119e-06 -7.62863088676214e-06 -6.16794981430679e-06 1.71018312125893e-05 -3.53092901148887e-05 6.69153382754795e-05 5.84409276076468e-06 2.95272305305726e-05 1.60262777589092e-05 -2.20991137294262e-05 -5.00967501739119e-06 5.84409276076468e-06 1.18220633359978e-05 -6.06580512879487e-06 1.73564898533617e-06 -3.77812309127803e-06 -7.62863088676214e-06 2.95272305305726e-05 -6.06580512879487e-06 6.31176295637152e-05 1.85284689619373e-05 2.93436413051804e-06 -6.16794981430679e-06 1.60262777589092e-05 1.73564898533617e-06 1.85284689619373e-05 2.91687562392141e-05 -2.19087299325198e-06 1.71018312125893e-05 -2.20991137294262e-05 -3.77812309127803e-06 2.93436413051804e-06 -2.19087299325198e-06 3.28010888767561e-05 1027 1027 0 14 0 1028 1052 0 43 0 0 0 0 0 0 13 42 0 2941 0 0 0 0 0 2201 +931 932 0.995231987214661 -0.0769302827023394 -0.0599585125573904 0.01531093647081 0.0770411101695431 0.997027808806036 -0.000464554924669301 0.025670397465054 0.0598160427360497 -0.00415693045068686 0.998200761851356 -0.0826981823634457 2.74686219439228e-05 -2.25653492983559e-05 -6.17968510256414e-07 8.09046866436624e-07 -2.00673496599397e-06 1.40012750521632e-05 -2.25653492983559e-05 3.04717020696493e-05 1.37510933786502e-07 3.29656258401138e-06 2.53382584782976e-06 -1.30452103783934e-05 -6.17968510256414e-07 1.37510933786502e-07 1.00971453955087e-05 -2.11267935283512e-06 3.37046525871304e-06 -1.56402058079099e-06 8.09046866436624e-07 3.29656258401138e-06 -2.11267935283512e-06 5.20098149710589e-05 6.1902661983557e-06 2.38924505886044e-06 -2.00673496599397e-06 2.53382584782976e-06 3.37046525871304e-06 6.1902661983557e-06 1.80031803267279e-05 1.55239366106057e-06 1.40012750521632e-05 -1.30452103783934e-05 -1.56402058079099e-06 2.38924505886044e-06 1.55239366106057e-06 2.83206514698402e-05 1685 1685 0 0 0 1667 1667 0 0 0 0 0 0 0 0 184 184 0 3430 0 0 0 0 0 1483 +932 933 0.994154960078979 -0.0911664188267372 -0.0578325118654812 0.00889322470961445 0.0900846734815556 0.995711642190418 -0.0210493992831863 0.0334815514830143 0.0595035037126773 0.0157165417560426 0.998104364964479 -0.101859132200757 2.97687036918715e-05 -1.95393565695599e-05 -4.11871671929505e-07 7.04134685945836e-06 -1.99400288015326e-06 1.66601745086418e-05 -1.95393565695599e-05 3.91785173025621e-05 1.82524121905065e-07 -4.30660781607914e-06 1.87953566493482e-06 -1.41815876008322e-06 -4.11871671929505e-07 1.82524121905065e-07 1.04105994881412e-05 4.11019308526443e-07 1.57954554172718e-06 -3.5350564412211e-06 7.04134685945836e-06 -4.30660781607914e-06 4.11019308526443e-07 5.63057798683618e-05 3.87564774509609e-06 5.82399372543588e-06 -1.99400288015326e-06 1.87953566493482e-06 1.57954554172718e-06 3.87564774509609e-06 2.10138008263548e-05 7.35932070409783e-06 1.66601745086418e-05 -1.41815876008322e-06 -3.5350564412211e-06 5.82399372543588e-06 7.35932070409783e-06 4.64033056892816e-05 1834 1834 0 0 0 1841 1841 0 0 0 0 0 0 0 0 247 244 0 3560 0 0 0 0 0 1015 +927 928 0.999997568558368 0.000224967286073826 -0.00219368800721544 0.000644487810507507 -0.000228814290415746 0.999998436305488 -0.00175357651625262 -0.00245176741368454 0.00219329007960775 0.00175407419969844 0.999996056343388 -0.00283909953522253 2.70115085301967e-05 -2.7346310642492e-05 -8.30162359524708e-06 -2.83581790945956e-06 1.55094247370023e-06 1.00875368997076e-05 -2.7346310642492e-05 4.13948483351836e-05 9.03661550426205e-06 7.25819286790086e-06 -4.04581455295267e-07 -9.67655012006396e-06 -8.30162359524708e-06 9.03661550426205e-06 1.33379984163506e-05 -2.82694083269328e-06 -9.94521678783925e-07 -4.54026707260782e-07 -2.83581790945956e-06 7.25819286790086e-06 -2.82694083269328e-06 3.40148129729684e-05 4.97510483365115e-06 2.37041832428415e-06 1.55094247370023e-06 -4.04581455295267e-07 -9.94521678783925e-07 4.97510483365115e-06 2.59745714480318e-05 -3.51484743219633e-06 1.00875368997076e-05 -9.67655012006396e-06 -4.54026707260782e-07 2.37041832428415e-06 -3.51484743219633e-06 2.6555654267753e-05 1086 1086 0 9 0 1095 1117 0 40 0 0 0 0 0 0 16 39 0 2876 0 0 0 0 0 2165 +929 930 0.996934377313836 -0.0618761505493439 0.047887256374413 -0.00684448716899264 0.0618225180051673 0.998083767755156 0.00260169390464502 0.0105391335935302 -0.0479564760733584 0.000366792676636721 0.998849358945461 -0.0449374605750261 3.16864876799501e-05 -2.71192012516874e-05 -2.39890347220055e-06 -2.24059724330747e-06 -1.30213100614991e-07 7.29791737943594e-06 -2.71192012516874e-05 6.52117497792021e-05 2.9035575571067e-06 1.70284116464286e-05 3.54660843058459e-06 -7.11374457308234e-06 -2.39890347220055e-06 2.9035575571067e-06 1.04894102690609e-05 -2.04828432657193e-06 1.64502907049776e-06 -1.54904976460317e-06 -2.24059724330747e-06 1.70284116464286e-05 -2.04828432657193e-06 4.30306802088452e-05 2.72574745661145e-06 4.56147933238288e-06 -1.30213100614991e-07 3.54660843058459e-06 1.64502907049776e-06 2.72574745661145e-06 2.09213330918187e-05 6.42203395163616e-07 7.29791737943594e-06 -7.11374457308234e-06 -1.54904976460317e-06 4.56147933238288e-06 6.42203395163616e-07 2.57052562739325e-05 1182 1182 0 0 0 1206 1206 0 0 0 0 0 0 0 0 123 139 0 3169 0 0 0 0 0 1345 +935 936 0.998845297261016 -0.0480083372208725 0.00180878324811632 0.019086553513614 0.0480144482074576 0.998840502640769 -0.00350186345679552 0.0431770680511896 -0.00163856732698141 0.00358466757505561 0.999992232597579 -0.133690536843567 4.00747909855925e-05 -1.30058772804549e-06 8.4636880620091e-07 1.65922515720205e-05 -2.34756834117491e-06 3.27036025306093e-05 -1.30058772804549e-06 9.20852396783337e-05 3.5288597631717e-06 3.7460989655929e-05 -4.45155538353039e-07 5.34805523311307e-05 8.4636880620091e-07 3.5288597631717e-06 9.80490695867135e-06 3.91761253818903e-06 5.85087272361622e-06 1.16821251833799e-06 1.65922515720205e-05 3.7460989655929e-05 3.91761253818903e-06 7.35278652867177e-05 1.28847367644749e-06 7.23700148742997e-05 -2.34756834117491e-06 -4.45155538353039e-07 5.85087272361622e-06 1.28847367644749e-06 1.8482390415646e-05 1.27365692869834e-06 3.27036025306093e-05 5.34805523311307e-05 1.16821251833799e-06 7.23700148742997e-05 1.27365692869834e-06 0.000155882971994309 2749 2749 0 0 0 2746 2746 0 0 0 0 0 0 0 0 136 126 0 3762 0 0 0 0 0 943 +928 929 0.999743245719949 -0.0212464555218938 0.00787596121736378 5.83303009977635e-05 0.0210926394700517 0.999594607709054 0.0191238280469269 0.00207630876993661 -0.00827908192540985 -0.0189527931117869 0.999786101341549 -0.0107189359133159 4.12308287380763e-05 -3.93850405805131e-05 -9.27471692697298e-06 -1.58899531954724e-06 6.29747955966926e-07 2.0203901010887e-05 -3.93850405805131e-05 6.5575382704103e-05 1.08805466485552e-05 1.81339062989691e-05 5.44621292607372e-06 -2.60070095601014e-05 -9.27471692697298e-06 1.08805466485552e-05 1.16726947345552e-05 -2.19495179493423e-06 1.120541829315e-07 -4.14058788929363e-06 -1.58899531954724e-06 1.81339062989691e-05 -2.19495179493423e-06 5.13948247086573e-05 1.50994864603579e-05 -2.11406851113485e-06 6.29747955966926e-07 5.44621292607372e-06 1.120541829315e-07 1.50994864603579e-05 2.66217860965351e-05 -6.27363872027011e-06 2.0203901010887e-05 -2.60070095601014e-05 -4.14058788929363e-06 -2.11406851113485e-06 -6.27363872027011e-06 3.44098617243094e-05 986 984 0 3 0 1013 1014 0 12 0 0 0 0 0 0 47 71 0 3030 0 0 0 0 0 1677 +933 934 0.996427696473499 -0.0732246562331103 -0.0420713135052817 0.0355634671725623 0.073387978680265 0.997300700952083 0.00234871575745001 0.0338867668403879 0.0417857665448637 -0.00542785409044328 0.999111849651595 -0.100468384161825 2.63766381008027e-05 -4.48651703738597e-06 -9.71904566557122e-07 1.11471085084386e-05 -5.92923297548835e-06 1.80916856469414e-05 -4.48651703738597e-06 3.70659989936746e-05 2.80485932741016e-06 4.9960982159597e-06 -8.485909573281e-07 3.59718940705154e-06 -9.71904566557122e-07 2.80485932741016e-06 8.57045576171387e-06 1.49819245625388e-06 2.71981910133195e-06 -3.0312174805001e-07 1.11471085084386e-05 4.9960982159597e-06 1.49819245625388e-06 6.53740253463643e-05 -1.32957377343117e-06 4.13758455128525e-06 -5.92923297548835e-06 -8.485909573281e-07 2.71981910133195e-06 -1.32957377343117e-06 2.29194340083071e-05 -1.34558697476306e-07 1.80916856469414e-05 3.59718940705154e-06 -3.0312174805001e-07 4.13758455128525e-06 -1.34558697476306e-07 6.02011385693912e-05 2121 2121 0 0 0 2116 2116 0 0 0 0 0 0 0 0 179 167 0 3661 0 0 0 0 0 1205 +930 931 0.997201002448684 -0.0726822683416901 -0.0175342118170815 0.0121587401090356 0.0723295220099882 0.997180702664083 -0.0199771489500521 0.0184359719078293 0.0189367621611078 0.0186529917995072 0.999646670046863 -0.059574124237154 2.37213768699754e-05 -2.06386710950198e-05 -1.59524084220709e-06 1.97259724409462e-06 -1.56848253591365e-06 6.09994121352542e-06 -2.06386710950198e-05 6.16430230960941e-05 3.85798921207953e-06 7.20057073527342e-06 -2.38470342673602e-06 -1.1780676478529e-05 -1.59524084220709e-06 3.85798921207953e-06 9.68486247129294e-06 -1.39930281884323e-06 3.80589036675494e-06 -1.94615888283884e-06 1.97259724409462e-06 7.20057073527342e-06 -1.39930281884323e-06 3.90693137210567e-05 1.99806599347782e-06 -3.44899758572828e-06 -1.56848253591365e-06 -2.38470342673602e-06 3.80589036675494e-06 1.99806599347782e-06 1.6735247707917e-05 1.64190415006822e-06 6.09994121352542e-06 -1.1780676478529e-05 -1.94615888283884e-06 -3.44899758572828e-06 1.64190415006822e-06 3.11349701489958e-05 1461 1461 0 0 0 1478 1478 0 0 0 0 0 0 0 0 173 183 0 3477 0 0 0 0 0 2006 +937 938 0.998943567943311 -0.0457254026061423 -0.00457554599949076 0.0494472136919356 0.0457953690548929 0.998813286249959 0.016577194686791 0.0481915022253244 0.00381211723500529 -0.0167692208245882 0.99985211956325 -0.114716853008869 2.67461967366611e-05 1.23817480533535e-06 2.41521052430373e-06 1.57374567383451e-06 -1.18522843383811e-06 6.36011059083074e-06 1.23817480533535e-06 2.42555313527507e-05 2.33389640875095e-06 1.35119530767647e-06 -4.96387996346747e-07 -1.79252220071785e-05 2.41521052430373e-06 2.33389640875095e-06 9.47299171046713e-06 6.86131910622746e-07 5.15865154498264e-06 -1.01823379183971e-06 1.57374567383451e-06 1.35119530767647e-06 6.86131910622746e-07 5.10737370961762e-05 1.91443093827768e-07 -1.24558633792017e-05 -1.18522843383811e-06 -4.96387996346747e-07 5.15865154498264e-06 1.91443093827768e-07 1.43858161407212e-05 -1.64338362379544e-06 6.36011059083074e-06 -1.79252220071785e-05 -1.01823379183971e-06 -1.24558633792017e-05 -1.64338362379544e-06 0.000122608777263377 2745 2865 0 0 65 2730 2850 0 0 65 0 0 0 0 0 104 82 0 3794 0 0 0 0 0 685 +934 935 0.998747853884237 -0.0490409609839579 -0.00988476137296246 0.0120676581369114 0.0488531327298694 0.998636046532482 -0.0184233001509477 0.0419762288729145 0.0107747753623106 0.0179173299278678 0.999781412861905 -0.114071818887517 4.78385522539742e-05 2.00706471533642e-05 3.26959018835044e-06 3.04276784364743e-05 -1.23791713480625e-06 5.95402773369196e-05 2.00706471533642e-05 0.000103762141070393 -1.02772648193658e-06 6.86605230516861e-05 -2.57237239080562e-06 6.73677269632579e-05 3.26959018835044e-06 -1.02772648193658e-06 1.20081995037582e-05 -5.19395169219556e-06 3.07221373136716e-06 -1.64595706116883e-06 3.04276784364743e-05 6.86605230516861e-05 -5.19395169219556e-06 0.000182305042475474 8.1207944850397e-06 7.81252126293692e-05 -1.23791713480625e-06 -2.57237239080562e-06 3.07221373136716e-06 8.1207944850397e-06 1.96437925890522e-05 -2.67687794028642e-06 5.95402773369196e-05 6.73677269632579e-05 -1.64595706116883e-06 7.81252126293692e-05 -2.67687794028642e-06 0.000162732346959988 2506 2506 0 0 0 2507 2507 0 0 0 0 0 0 0 0 144 133 0 3726 0 0 0 0 0 461 +940 941 0.999438974488576 0.028150736199846 0.0181458624658504 0.065820011912329 -0.0276005104742499 0.999172020430374 -0.0298912263155189 0.0294433516731944 -0.0189722980891535 0.0293736215079352 0.999388434125953 -0.0464842106583599 5.54220988238302e-05 7.13650872303987e-06 4.64541383435309e-06 -7.88159309501656e-06 4.70840943317019e-06 -7.95747225344786e-06 7.13650872303987e-06 2.25488477052915e-05 -1.25164474782821e-06 7.17188177350799e-07 -1.77035419835846e-06 -6.29220087772183e-06 4.64541383435309e-06 -1.25164474782821e-06 1.27485716991308e-05 -5.78455601008999e-06 3.95904381875071e-06 -1.04375680210261e-06 -7.88159309501656e-06 7.17188177350799e-07 -5.78455601008999e-06 0.000120041319628218 4.58395102353793e-06 1.58521880737149e-05 4.70840943317019e-06 -1.77035419835846e-06 3.95904381875071e-06 4.58395102353793e-06 1.52885571410061e-05 5.42483846926797e-06 -7.95747225344786e-06 -6.29220087772183e-06 -1.04375680210261e-06 1.58521880737149e-05 5.42483846926797e-06 6.67105633785474e-05 3492 3497 0 85 0 3492 3504 0 47 56 0 0 0 0 0 0 0 0 3770 0 0 0 0 0 890 +942 943 0.998957172704742 0.0452601967433479 0.00600680385082015 0.1188543722484 -0.0452775283970409 0.998970574913437 0.0027813448855833 0.0198042479493994 -0.00587473607951345 -0.00305041765515005 0.99997809097406 0.012266092006875 4.42266251311664e-05 1.30813048664938e-05 8.27043395711533e-06 5.14748631289888e-06 3.28438436718061e-06 1.92841228669552e-05 1.30813048664938e-05 3.06273502178252e-05 -7.71209738602032e-07 -8.23087034327012e-06 1.10181135030297e-06 1.95357793104029e-05 8.27043395711533e-06 -7.71209738602032e-07 1.13788240565097e-05 5.54971117148432e-06 1.70760049945937e-06 -3.07020386085276e-06 5.14748631289888e-06 -8.23087034327012e-06 5.54971117148432e-06 4.7861710278281e-05 2.99585714985001e-06 -4.2678722993216e-06 3.28438436718061e-06 1.10181135030297e-06 1.70760049945937e-06 2.99585714985001e-06 1.33342563839602e-05 1.29274249951524e-05 1.92841228669552e-05 1.95357793104029e-05 -3.07020386085276e-06 -4.2678722993216e-06 1.29274249951524e-05 0.000165901375879869 3645 3612 0 197 38 3645 3612 0 162 43 0 0 0 0 0 0 0 0 3653 0 35 35 0 0 1960 +944 945 0.999339733002002 -0.00602467162484923 0.0358301740897298 0.114743070409924 0.00653006760032314 0.999880601132265 -0.0140050596755833 0.0240423376249168 -0.0357415201218809 0.0142297860558118 0.999259754482378 -0.0234141922966394 4.2094113232353e-05 -7.55980466591163e-07 5.04563414643151e-06 2.5841009668249e-06 2.80618920632937e-06 -1.53576925026493e-07 -7.55980466591163e-07 5.19878235601253e-05 -3.58773220086818e-06 -2.29923901717783e-06 -2.81764516440208e-06 -2.14729209817874e-05 5.04563414643151e-06 -3.58773220086818e-06 1.17712153298202e-05 7.82367816130111e-07 4.59675907136119e-06 -8.81061651472441e-07 2.5841009668249e-06 -2.29923901717783e-06 7.82367816130111e-07 7.08845517769053e-05 4.65141298009518e-06 2.23446074283742e-05 2.80618920632937e-06 -2.81764516440208e-06 4.59675907136119e-06 4.65141298009518e-06 1.20318688767331e-05 1.01484250735185e-05 -1.53576925026493e-07 -2.14729209817874e-05 -8.81061651472441e-07 2.23446074283742e-05 1.01484250735185e-05 0.00013723350022437 3160 3153 0 68 152 3160 3153 0 31 125 0 0 0 0 0 0 0 0 3774 0 0 0 0 0 3412 +936 937 0.998944669318842 -0.039259837658361 0.0238372143193854 0.0258092283088975 0.0392350464253322 0.999228872712284 0.00150700701378764 0.0446690236307834 -0.0238779976436719 -0.000570162412577588 0.999714717378589 -0.110265355072005 1.82216614269055e-05 1.09643871280504e-06 2.83886702648507e-06 9.67455503107279e-06 5.94758045061092e-08 9.31895895553059e-06 1.09643871280504e-06 3.13479623376231e-05 -2.8361136017087e-06 7.41312182504579e-06 -1.28701079610817e-06 1.84553759020866e-06 2.83886702648507e-06 -2.8361136017087e-06 8.44170218675993e-06 2.66998027080518e-06 2.82622523722704e-06 -2.23185453794469e-06 9.67455503107279e-06 7.41312182504579e-06 2.66998027080518e-06 4.72229097557674e-05 -5.13940139132423e-07 2.4798263300683e-05 5.94758045061092e-08 -1.28701079610817e-06 2.82622523722704e-06 -5.13940139132423e-07 1.36217744527298e-05 -1.09088370438215e-06 9.31895895553059e-06 1.84553759020866e-06 -2.23185453794469e-06 2.4798263300683e-05 -1.09088370438215e-06 7.17670990771284e-05 3000 3004 0 0 0 2990 2994 0 0 0 0 0 0 0 0 102 86 0 3797 0 0 0 0 0 939 +939 940 0.999525095638496 -0.00633305120640695 -0.0301575140101327 0.0695633769410471 0.00469256329311807 0.998521207426138 -0.0541606699551131 0.0508302429148752 0.0304559195985674 0.0539934327734738 0.998076723593303 -0.0947086600901126 5.46341646082948e-05 1.74085964940526e-05 2.98501577036122e-06 1.01186309494355e-05 -2.59269617152856e-06 -1.66727365612882e-05 1.74085964940526e-05 3.59439894179662e-05 5.62695578544077e-08 8.03723250051095e-06 -5.2527680411137e-07 7.83360409318809e-07 2.98501577036122e-06 5.62695578544077e-08 1.09956921788278e-05 1.47010291729316e-06 4.07793814284295e-06 -4.35491427333391e-06 1.01186309494355e-05 8.03723250051095e-06 1.47010291729316e-06 6.22573628774819e-05 -1.32783716603809e-06 2.30261991237234e-05 -2.59269617152856e-06 -5.2527680411137e-07 4.07793814284295e-06 -1.32783716603809e-06 1.40572848766871e-05 5.69412384937933e-06 -1.66727365612882e-05 7.83360409318809e-07 -4.35491427333391e-06 2.30261991237234e-05 5.69412384937933e-06 0.000140639702162808 3112 3158 0 1 69 3090 3158 0 0 171 0 0 0 0 0 0 0 0 3850 0 0 0 0 0 689 +938 939 0.998685950819091 -0.050000752205328 -0.0112381677985779 0.0776881139389846 0.0497136056497182 0.998462411146894 -0.0245228656570583 0.0540141400615422 0.0124470498461246 0.0239319515633642 0.999636100110684 -0.0306863628857787 3.92237777819805e-05 1.83943766065653e-05 3.32825639416407e-06 1.07841167949794e-05 1.78621492277694e-06 4.33549543530438e-05 1.83943766065653e-05 4.07031211588112e-05 1.28405396945308e-07 1.06404558697304e-05 -2.61012916043628e-06 3.74366320133239e-05 3.32825639416407e-06 1.28405396945308e-07 9.28264819858037e-06 2.97978092608608e-06 2.74921258404708e-06 4.47630517799879e-07 1.07841167949794e-05 1.06404558697304e-05 2.97978092608608e-06 4.4477744376694e-05 1.09932019507487e-06 3.87884420334506e-05 1.78621492277694e-06 -2.61012916043628e-06 2.74921258404708e-06 1.09932019507487e-06 1.07080912140418e-05 -4.47098207230627e-06 4.33549543530438e-05 3.74366320133239e-05 4.47630517799879e-07 3.87884420334506e-05 -4.47098207230627e-06 0.000197093383535499 3417 3507 0 0 181 3396 3486 0 0 313 0 0 0 0 0 91 59 0 3812 0 0 0 0 0 420 +947 948 0.999655127226123 -0.00784916522606412 -0.0250602716620962 0.136048569217446 0.00835955306506697 0.999758435651761 0.0203270316499185 0.0249811296350541 0.0248946677639298 -0.020529514080913 0.999479261700074 -0.00911441710120272 5.14849816301142e-05 -2.6332751297099e-06 5.97079310611598e-06 -1.72467720502217e-05 7.35525475428037e-06 1.45540013927399e-05 -2.6332751297099e-06 2.65666282462023e-05 -1.14457624626719e-06 2.6743114441831e-06 1.24344013619811e-06 2.95992921194131e-05 5.97079310611598e-06 -1.14457624626719e-06 1.28612117448531e-05 2.0777845731128e-06 4.95618461695566e-06 -3.31214182729211e-06 -1.72467720502217e-05 2.6743114441831e-06 2.0777845731128e-06 0.000143589445086368 3.65725901725155e-06 -2.55411495473443e-05 7.35525475428037e-06 1.24344013619811e-06 4.95618461695566e-06 3.65725901725155e-06 1.20564193066412e-05 1.01052088671066e-05 1.45540013927399e-05 2.95992921194131e-05 -3.31214182729211e-06 -2.55411495473443e-05 1.01052088671066e-05 0.000289535191816297 3546 3556 0 80 146 3546 3556 0 31 220 0 0 0 0 0 0 0 0 3747 0 0 0 0 0 3206 +941 942 0.999137250503918 0.0412545491058811 -0.00477669692799788 0.0881597975876534 -0.0410997918640032 0.998736685554411 0.0289108982310512 0.018596209025755 0.00596336852853457 -0.0286896341186329 0.999570579363925 -0.050520049721656 9.35596337752034e-05 1.59995096734975e-06 -3.05618651376006e-06 2.81625358105829e-05 6.13363362099217e-06 -4.14757303004482e-05 1.59995096734975e-06 3.14001170038736e-05 -2.26325605062175e-06 -3.82498986453853e-06 -1.15015769132085e-06 -2.50185486543709e-05 -3.05618651376006e-06 -2.26325605062175e-06 1.356304221188e-05 4.33315308980543e-06 5.7659784141643e-06 1.10408584141852e-07 2.81625358105829e-05 -3.82498986453853e-06 4.33315308980543e-06 5.11023279723429e-05 4.98509188188692e-06 -7.02665589062743e-06 6.13363362099217e-06 -1.15015769132085e-06 5.7659784141643e-06 4.98509188188692e-06 1.48029590490898e-05 5.10397337945043e-06 -4.14757303004482e-05 -2.50185486543709e-05 1.10408584141852e-07 -7.02665589062743e-06 5.10397337945043e-06 0.000167301480696522 3085 3052 0 155 5 3085 3054 0 114 30 0 0 0 0 0 0 0 0 3709 0 0 0 0 0 1445 +946 947 0.999977842857804 -0.00182852051225171 -0.00640080512040365 0.133340124436911 0.00176302183979602 0.999946183334763 -0.0102236093544548 0.0241348741242132 0.00641915472983111 0.010212098069269 0.999927251106588 0.000777189768038206 9.97275349922074e-05 -1.75233435769283e-05 6.02780226460371e-07 -2.57343209913456e-06 5.36529912117716e-06 -5.4236431403533e-05 -1.75233435769283e-05 5.47864636373903e-05 4.28263651280999e-07 1.4012400616397e-05 1.11347071123365e-06 4.99910196466745e-05 6.02780226460371e-07 4.28263651280999e-07 1.26366194016227e-05 3.80973086716106e-06 2.63701694816272e-06 -3.86954554965656e-07 -2.57343209913456e-06 1.4012400616397e-05 3.80973086716106e-06 0.000114607802911529 5.49758929792924e-06 5.35223279598515e-05 5.36529912117716e-06 1.11347071123365e-06 2.63701694816272e-06 5.49758929792924e-06 1.29406758532188e-05 2.29786112814094e-05 -5.4236431403533e-05 4.99910196466745e-05 -3.86954554965656e-07 5.35223279598515e-05 2.29786112814094e-05 0.000468251129015906 3308 3329 0 94 128 3308 3329 0 50 205 0 0 0 0 0 0 0 0 3729 0 0 0 0 0 3321 +948 949 0.99841215084666 0.00238830134750082 0.0562803079097714 0.124683542788664 -0.0040290692035787 0.999569604401921 0.0290580893580568 0.0298795361260002 -0.0561866856390189 -0.0292387067508391 0.997992061283275 0.0712860755934407 5.25937488324686e-05 5.01504992021374e-07 -2.44437874575285e-06 -2.09442933712241e-05 6.7755943766838e-06 -2.10379756164596e-05 5.01504992021374e-07 3.2722646494292e-05 2.0568538177971e-07 1.31606859274013e-06 -1.31597253396791e-06 8.67306425758413e-06 -2.44437874575285e-06 2.0568538177971e-07 1.42898009979561e-05 6.05852257731365e-06 -1.04907001879026e-06 5.53559612814038e-06 -2.09442933712241e-05 1.31606859274013e-06 6.05852257731365e-06 0.000187175633721299 -4.52942693162099e-06 1.98901386808086e-06 6.7755943766838e-06 -1.31597253396791e-06 -1.04907001879026e-06 -4.52942693162099e-06 1.45363783047595e-05 -3.94812040498647e-06 -2.10379756164596e-05 8.67306425758413e-06 5.53559612814038e-06 1.98901386808086e-06 -3.94812040498647e-06 0.000179163429192793 3227 3231 0 91 124 3227 3231 0 43 192 0 0 0 0 0 0 0 0 3724 0 0 0 0 0 3144 +943 944 0.999823479441057 0.0121412158549254 0.0143387878128467 0.107893116713794 -0.0117917138138852 0.999637286284449 -0.0242126280108883 0.0247037694068745 -0.0146275576809378 0.0240392751019313 0.999603995494648 0.00543180368337811 3.3682153452809e-05 -4.61439274902267e-08 6.75353998214473e-06 -1.27624148934559e-06 3.84082419122088e-06 9.54025513071345e-06 -4.61439274902267e-08 2.1955345138708e-05 4.48076760254353e-07 -3.44043312474843e-06 -1.20757812745663e-06 4.50551926062274e-06 6.75353998214473e-06 4.48076760254353e-07 9.49506164566147e-06 3.5801964444575e-06 3.96145827121733e-06 8.48586108467723e-07 -1.27624148934559e-06 -3.44043312474843e-06 3.5801964444575e-06 5.04232308705312e-05 3.88819210745381e-06 7.3854029505076e-06 3.84082419122088e-06 -1.20757812745663e-06 3.96145827121733e-06 3.88819210745381e-06 1.07773650076743e-05 4.15630025018294e-06 9.54025513071345e-06 4.50551926062274e-06 8.48586108467723e-07 7.3854029505076e-06 4.15630025018294e-06 9.81490915984773e-05 3787 3719 0 107 156 3786 3719 0 73 117 0 0 0 0 0 0 0 0 3733 0 44 10 0 0 2659 +951 952 0.999098487092425 0.0380720484143297 0.0187811666082019 0.144285131353892 -0.0375745582966996 0.998951188613194 -0.0261663015555434 0.0159570232053535 -0.0197576734064523 0.0254370182573476 0.99948116162524 -0.0891309923620133 6.5983136144934e-05 -4.85036882177901e-05 3.85477288758267e-06 3.65470304090828e-05 2.4584388875389e-07 -7.35193942489521e-05 -4.85036882177901e-05 0.000419652768321834 1.51558930335032e-05 -0.000104628320316082 -9.05764168219251e-06 0.000357934267565089 3.85477288758267e-06 1.51558930335032e-05 1.50667473851715e-05 -7.5969904821754e-07 2.01894350116822e-06 1.36342796207585e-05 3.65470304090828e-05 -0.000104628320316082 -7.5969904821754e-07 0.000239893459033389 5.78214355319234e-06 -0.000218207334510278 2.4584388875389e-07 -9.05764168219251e-06 2.01894350116822e-06 5.78214355319234e-06 1.37770102246864e-05 -1.45401364553062e-05 -7.35193942489521e-05 0.000357934267565089 1.36342796207585e-05 -0.000218207334510278 -1.45401364553062e-05 0.00118331129245684 3133 3131 0 230 48 3133 3131 0 167 101 0 0 0 0 0 0 0 0 3599 0 0 0 0 0 2844 +945 946 0.998880167235804 -0.00745394899473345 0.0467209818749262 0.120279544215463 0.00701815943303752 0.999930391469013 0.00948460092983699 0.019758156161075 -0.046788427427578 -0.00914608446329414 0.998862949657181 -0.00541796447486517 5.21376945338549e-05 4.51042592160921e-06 7.72422675623475e-06 5.52519870460226e-06 2.87119500740324e-06 5.174691403719e-05 4.51042592160921e-06 6.3162841121082e-05 -7.68215044663932e-06 3.48354101040931e-05 8.58845785908747e-06 0.000106164415333303 7.72422675623475e-06 -7.68215044663932e-06 1.37996279579323e-05 -2.86110789370406e-06 2.51139965472981e-06 -9.03418590342626e-06 5.52519870460226e-06 3.48354101040931e-05 -2.86110789370406e-06 0.000108095331675302 7.58570212695287e-06 0.000102146479984835 2.87119500740324e-06 8.58845785908747e-06 2.51139965472981e-06 7.58570212695287e-06 1.54891520068087e-05 4.08874810643064e-05 5.174691403719e-05 0.000106164415333303 -9.03418590342626e-06 0.000102146479984835 4.08874810643064e-05 0.000584320375396561 3346 3370 0 74 120 3346 3370 0 33 190 0 0 0 0 0 0 0 0 3762 0 0 0 0 0 3379 +955 956 0.999390540197998 -0.0319599348227553 -0.0140396128464617 0.0754991051098509 0.0320282876349623 0.999476048248387 0.00467094947101472 0.01764744851157 0.0138829735260648 -0.00511776747360494 0.999890529759214 -0.0173645733255517 6.01265438409732e-05 -4.00534406547553e-05 -3.4760172346316e-06 -3.18355270804987e-05 -2.21531812629266e-06 -4.03765572859085e-06 -4.00534406547553e-05 5.88118333074943e-05 6.22590238576584e-07 3.61487240635256e-05 1.44824873916645e-06 -4.19103639188678e-06 -3.4760172346316e-06 6.22590238576584e-07 1.26646034507586e-05 -8.62278254873682e-07 4.15636784072877e-06 -4.38112563376495e-06 -3.18355270804987e-05 3.61487240635256e-05 -8.62278254873682e-07 0.000399740019260782 2.39860121434775e-05 0.000235759363772872 -2.21531812629266e-06 1.44824873916645e-06 4.15636784072877e-06 2.39860121434775e-05 1.37912787070431e-05 1.92375291567324e-05 -4.03765572859085e-06 -4.19103639188678e-06 -4.38112563376495e-06 0.000235759363772872 1.92375291567324e-05 0.000447534765797089 3132 3150 0 0 119 3083 3133 0 0 177 0 0 0 0 0 0 0 0 3823 0 0 0 0 0 3443 +957 958 0.977552306775544 -0.0147062601325512 0.210179003306057 0.13465462735137 0.0117872117956045 0.99981598850997 0.0151344229463032 0.0134356076184819 -0.21036289871529 -0.0123172656359179 0.977545771721895 -0.19202182799818 0.00010140192062347 0.000517661736755055 -2.71161075491332e-06 6.31659879262304e-05 2.09638707847415e-05 0.00041597919303472 0.000517661736755055 0.0104136572068648 -0.000316974640324881 0.000878772708927378 0.000362793988582801 0.00713114202611586 -2.71161075491332e-06 -0.000316974640324881 3.29017424355436e-05 -1.52209867155595e-05 -1.1493484837302e-05 -0.000228698175799504 6.31659879262304e-05 0.000878772708927378 -1.52209867155595e-05 0.000315856011469186 4.02765920869122e-05 0.000735390140153088 2.09638707847415e-05 0.000362793988582801 -1.1493484837302e-05 4.02765920869122e-05 2.8661819383131e-05 0.000297959652322905 0.00041597919303472 0.00713114202611586 -0.000228698175799504 0.000735390140153088 0.000297959652322905 0.00602982509671474 2029 2031 0 70 145 2029 2031 0 32 189 0 0 0 0 0 0 0 0 3374 0 0 0 0 0 3528 +949 950 0.997177741949945 -0.00291649342326506 0.0750202974249038 0.161478461206542 0.00137071294170411 0.999785866217425 0.020648071529935 0.0280719082168867 -0.0750644530096664 -0.0204869660512708 0.996968210183441 0.0633598535410367 8.73355262204723e-05 7.56166345507492e-06 -2.90883800121084e-06 -2.88277631432031e-05 5.18785016829087e-07 -2.51008099035894e-05 7.56166345507492e-06 4.26670165254357e-05 7.33798568501638e-06 1.32836703776394e-06 -2.14839557728882e-06 1.08607039668856e-05 -2.90883800121084e-06 7.33798568501638e-06 1.70359045856479e-05 2.26798982735188e-06 6.11933086042055e-07 -6.93549434545424e-06 -2.88277631432031e-05 1.32836703776394e-06 2.26798982735188e-06 0.000204439829351321 -3.67994356080535e-06 6.23706772086564e-05 5.18785016829087e-07 -2.14839557728882e-06 6.11933086042055e-07 -3.67994356080535e-06 1.48881863603215e-05 -6.99545962228921e-07 -2.51008099035894e-05 1.08607039668856e-05 -6.93549434545424e-06 6.23706772086564e-05 -6.99545962228921e-07 0.000264969224938938 3214 3213 0 138 183 3214 3213 0 85 246 0 0 0 0 0 0 0 0 3678 0 0 0 0 0 2830 +958 959 0.999534721268325 -0.00101018124660251 -0.0304847586984286 0.15511329872302 0.00155398128149376 0.999840003439547 0.0178200074125713 0.0187460269596082 0.0304618798045881 -0.0178590888865121 0.999376368953616 0.041718263865913 7.62303232916434e-05 -4.22264480373077e-05 2.02412356467421e-06 -1.61676513261059e-05 6.26032054766058e-07 -4.55664976259022e-05 -4.22264480373077e-05 8.34988269291636e-05 -2.76829237044879e-06 1.03524356685338e-05 -1.33576722995934e-06 7.59999042344931e-05 2.02412356467421e-06 -2.76829237044879e-06 1.37063086975368e-05 -2.6611899384599e-06 3.87506284207037e-06 -9.18966093920905e-06 -1.61676513261059e-05 1.03524356685338e-05 -2.6611899384599e-06 0.000103388104084713 4.64514873533088e-06 4.47463821373481e-05 6.26032054766058e-07 -1.33576722995934e-06 3.87506284207037e-06 4.64514873533088e-06 1.17543893285838e-05 8.16272365344743e-06 -4.55664976259022e-05 7.59999042344931e-05 -9.18966093920905e-06 4.47463821373481e-05 8.16272365344743e-06 0.000512080773003352 3164 3153 0 139 157 3164 3153 0 73 209 0 0 0 0 0 0 0 0 3652 0 0 0 0 0 3624 +950 951 0.999440452796221 -0.00509667466412729 0.0330576045994261 0.165980375446867 0.0046896493963633 0.99991238640537 0.0123784773561465 0.0216156440022535 -0.0331177973757789 -0.0122165224382999 0.999376789842796 -0.131857223694553 7.01733134475028e-05 -2.31732038710447e-06 2.47609355234307e-06 -2.64704306453398e-05 6.94675597088124e-07 -1.89360370739052e-06 -2.31732038710447e-06 0.000170433016569682 3.21785328961674e-06 -3.43421959914809e-06 4.82327007091526e-06 -0.000120378164681852 2.47609355234307e-06 3.21785328961674e-06 1.43596871427739e-05 1.03279874982972e-06 2.15196333965545e-06 -1.33615932974968e-06 -2.64704306453398e-05 -3.43421959914809e-06 1.03279874982972e-06 0.000366716488801872 -1.40439773455232e-06 -0.000112315433278199 6.94675597088124e-07 4.82327007091526e-06 2.15196333965545e-06 -1.40439773455232e-06 1.36390793272598e-05 -7.84987873129187e-06 -1.89360370739052e-06 -0.000120378164681852 -1.33615932974968e-06 -0.000112315433278199 -7.84987873129187e-06 0.000300704466572842 2914 2906 0 140 190 2914 2906 0 88 252 0 0 0 0 0 0 0 0 3673 0 0 0 0 0 2653 +959 960 0.999921880271979 -0.00932056053811712 0.00832829542014702 0.149269538554389 0.00914886264888509 0.999749593140485 0.0204217856140363 0.0211435028479777 -0.00851655244695783 -0.0203439958388002 0.999756765502354 -0.00163650424789253 6.97543815566123e-05 -2.56623905472326e-05 1.30416505426949e-06 7.06726222325255e-06 2.85713491043333e-06 3.3018457025454e-05 -2.56623905472326e-05 0.000136482525500842 1.52621219436225e-06 3.65153622447498e-05 -1.32371357045642e-06 -3.56547075486673e-05 1.30416505426949e-06 1.52621219436225e-06 1.24346933030081e-05 -2.70047315856545e-06 3.51942077780579e-06 -7.80315956853631e-06 7.06726222325255e-06 3.65153622447498e-05 -2.70047315856545e-06 0.000133508746732707 5.19458058192954e-06 7.55651265057234e-05 2.85713491043333e-06 -1.32371357045642e-06 3.51942077780579e-06 5.19458058192954e-06 1.16210374302609e-05 6.56821208399688e-06 3.3018457025454e-05 -3.56547075486673e-05 -7.80315956853631e-06 7.55651265057234e-05 6.56821208399688e-06 0.000350155393882655 3128 3112 0 107 170 3128 3112 0 42 219 0 0 0 0 0 0 0 0 3676 0 0 0 0 0 3629 +952 953 0.998337236036194 0.0494545040623871 -0.0296144419423258 0.148398189245014 -0.0507761570572352 0.997664965423244 -0.0456771128853013 0.015222085810021 0.0272863522316749 0.0471048701832508 0.998517193736246 -0.10124451123722 6.02564918628932e-05 -2.14964109036877e-05 -3.01887130420453e-06 -7.75016440340966e-06 3.78694798190305e-06 -1.94609364207581e-05 -2.14964109036877e-05 5.76966652185076e-05 2.30526223686313e-06 -1.33316611448947e-05 -2.54371282240593e-06 1.74608046405123e-05 -3.01887130420453e-06 2.30526223686313e-06 1.5397904646125e-05 7.50976059992321e-06 -5.26422308238608e-07 -5.68107447820085e-06 -7.75016440340966e-06 -1.33316611448947e-05 7.50976059992321e-06 0.000181710253274083 1.7060082505083e-06 -5.04575581816117e-05 3.78694798190305e-06 -2.54371282240593e-06 -5.26422308238608e-07 1.7060082505083e-06 1.54667964864766e-05 1.19544084849407e-05 -1.94609364207581e-05 1.74608046405123e-05 -5.68107447820085e-06 -5.04575581816117e-05 1.19544084849407e-05 0.000556278086888933 3313 3321 0 265 25 3313 3322 0 210 66 0 0 0 0 0 0 0 0 3563 0 0 0 0 0 3390 +953 954 0.999673739534242 0.0252666121479612 -0.00374336695897905 0.165609018542646 -0.0251972897904595 0.999528719563568 0.0175338345728733 0.0124999435376281 0.0041846233809842 -0.0174337912737816 0.9998392630063 0.0362318981909962 4.93644160722733e-05 -1.98701294512201e-05 1.37492336756397e-06 2.46497118819411e-06 3.25893513881325e-06 4.83631322016933e-06 -1.98701294512201e-05 7.17223188857043e-05 5.08035676597537e-06 -1.53194159001971e-05 -1.02924519328068e-06 -3.61658025337694e-06 1.37492336756397e-06 5.08035676597537e-06 1.37332035279712e-05 7.86580373195823e-06 3.00617072723092e-06 -4.07274859493031e-06 2.46497118819411e-06 -1.53194159001971e-05 7.86580373195823e-06 0.000183064779482463 1.10520543143849e-05 2.45465548688826e-06 3.25893513881325e-06 -1.02924519328068e-06 3.00617072723092e-06 1.10520543143849e-05 1.26472064335249e-05 8.52922459558597e-06 4.83631322016933e-06 -3.61658025337694e-06 -4.07274859493031e-06 2.45465548688826e-06 8.52922459558597e-06 0.000308173641675836 3184 3199 0 218 109 3184 3199 0 166 165 0 0 0 0 0 0 0 0 3609 0 0 0 0 0 3520 +954 955 0.999545133703404 0.0027197426075309 0.0300354572129876 0.170515223368702 -0.00274543859681945 0.999995899720314 0.000814315338481699 0.0197370606360271 -0.0300331193310905 -0.000896405437385078 0.999548502175125 0.00173894855239501 6.94878555231163e-05 -2.35206433495325e-05 -1.49684415619826e-07 -2.11795556173293e-05 -3.67484988533096e-07 -8.1511191988753e-06 -2.35206433495325e-05 3.77812047100532e-05 1.94298185029317e-06 -4.52295715130699e-06 -1.41315789584954e-06 -8.16375684193582e-06 -1.49684415619826e-07 1.94298185029317e-06 1.28954038678635e-05 3.74086024391259e-06 3.61455865102488e-06 2.03639954659673e-08 -2.11795556173293e-05 -4.52295715130699e-06 3.74086024391259e-06 0.00051125061065033 4.48262914092145e-05 5.42682203545848e-05 -3.67484988533096e-07 -1.41315789584954e-06 3.61455865102488e-06 4.48262914092145e-05 1.59529937455746e-05 4.96857179219444e-06 -8.1511191988753e-06 -8.16375684193582e-06 2.03639954659673e-08 5.42682203545848e-05 4.96857179219444e-06 0.000176944596367823 3429 3444 0 158 172 3429 3444 0 109 242 0 0 0 0 0 0 0 0 3650 0 0 0 0 0 3332 +956 957 0.999437657404891 -0.0169226803152695 0.0289480889174296 0.0954037052226873 0.017891704065227 0.999276891154761 -0.0335496904563817 0.0204557419812311 -0.0283594056120111 0.0340487546765499 0.999017730782747 -0.0609744946597712 4.69530339274941e-05 -1.93318825850634e-05 5.23303316373424e-06 -2.5908862432466e-05 -7.66510061305363e-07 -3.05450900346714e-06 -1.93318825850634e-05 0.00010267623241057 -5.09319043837202e-06 2.74400392794602e-05 1.78564277204011e-06 1.34983215562805e-05 5.23303316373424e-06 -5.09319043837202e-06 1.40769836618061e-05 5.9103460346574e-06 -1.30108166389677e-06 4.11498002135737e-07 -2.5908862432466e-05 2.74400392794602e-05 5.9103460346574e-06 0.000657895652839641 2.69451289475932e-05 0.000358520029133184 -7.66510061305363e-07 1.78564277204011e-06 -1.30108166389677e-06 2.69451289475932e-05 1.653998386193e-05 3.2297986106564e-05 -3.05450900346714e-06 1.34983215562805e-05 4.11498002135737e-07 0.000358520029133184 3.2297986106564e-05 0.000651260514278101 3071 3071 0 23 122 3065 3071 0 1 175 0 0 0 0 0 0 0 0 3774 0 0 0 0 0 3674 +966 967 0.999540147225504 -0.0267924961112447 0.0142005716979103 0.12816154889613 0.0271987817454886 0.99920246823979 -0.0292344614294919 0.017436790712333 -0.0134059820968041 0.0296072561315653 0.999471705466633 -0.0295702394625727 0.000146720717815307 -0.000100010220553207 4.61611701957285e-06 8.56131918976743e-05 1.57819087643363e-05 7.67449692837778e-05 -0.000100010220553207 0.000351831721117507 -1.31496108248859e-05 9.72783157010156e-06 -1.32444924761778e-06 -0.000181161039445918 4.61611701957285e-06 -1.31496108248859e-05 1.29164046872171e-05 -3.80307870882149e-06 3.40586117583296e-06 5.69008855422716e-06 8.56131918976743e-05 9.72783157010156e-06 -3.80307870882149e-06 0.000282695006064513 3.03690952688661e-05 -9.01439824337597e-06 1.57819087643363e-05 -1.32444924761778e-06 3.40586117583296e-06 3.03690952688661e-05 1.66083511534443e-05 6.84065692855791e-06 7.67449692837778e-05 -0.000181161039445918 5.69008855422716e-06 -9.01439824337597e-06 6.84065692855791e-06 0.000409462015318042 3120 3138 0 23 175 3120 3139 0 24 236 0 0 0 0 0 1 24 0 3503 0 0 0 0 0 3590 +968 969 0.999548697581672 -0.0296971167845687 0.00452575048655105 0.136531682607389 0.029662830026997 0.999532096320993 0.0074635741405319 0.0168157739304521 -0.00474527950412978 -0.00732595924404575 0.999961905596199 0.0530136150692771 9.9036169387672e-05 -2.53387363752918e-06 8.51158622976307e-06 5.65640791821436e-06 4.43162283813678e-06 -2.54773684059376e-05 -2.53387363752918e-06 3.78929108360577e-05 1.65261085573025e-07 -1.03119332089711e-05 -4.26066905364559e-08 -3.8199367942205e-05 8.51158622976307e-06 1.65261085573025e-07 1.44442994487603e-05 -5.68332926063636e-06 4.81694886417541e-06 -5.51516053246805e-06 5.65640791821436e-06 -1.03119332089711e-05 -5.68332926063636e-06 0.000356685968677255 2.22331211233601e-05 0.000102038580463263 4.43162283813678e-06 -4.26066905364559e-08 4.81694886417541e-06 2.22331211233601e-05 1.36450778316596e-05 1.04804998714966e-05 -2.54773684059376e-05 -3.8199367942205e-05 -5.51516053246805e-06 0.000102038580463263 1.04804998714966e-05 0.000353344929254405 3140 3138 0 24 197 3140 3138 0 1 253 0 0 0 0 0 0 0 0 3217 0 0 0 0 0 3559 +963 964 0.999442876749597 0.0330871404188622 0.00437918410121078 0.0897459647061689 -0.0331658330750802 0.999263158047009 0.0193175693697388 -0.00477232540613367 -0.00373679420435748 -0.0194520463916075 0.999803807884453 0.00110621772430613 7.24750071505609e-05 -1.53736343882575e-05 2.10131286340755e-06 -4.73280300536529e-05 -2.44099945994836e-06 -4.25878866949672e-05 -1.53736343882575e-05 2.82549354424536e-05 -1.2059623117275e-06 7.20047109116037e-06 1.70092955507018e-06 0.000103691349275277 2.10131286340755e-06 -1.2059623117275e-06 1.49126704811161e-05 4.71229671329684e-09 3.93775648293964e-06 -8.80790712558766e-07 -4.73280300536529e-05 7.20047109116037e-06 4.71229671329684e-09 0.000570370238408974 7.38541479247651e-05 2.79092391249927e-06 -2.44099945994836e-06 1.70092955507018e-06 3.93775648293964e-06 7.38541479247651e-05 2.39006744022055e-05 9.93568829817449e-06 -4.25878866949672e-05 0.000103691349275277 -8.80790712558766e-07 2.79092391249927e-06 9.93568829817449e-06 0.00146695166512219 3418 3404 0 159 0 3418 3428 0 107 12 0 0 0 0 0 0 0 0 3668 0 0 0 0 0 3838 +970 971 0.999709251063954 -0.0240996661121645 0.000787039026689906 0.133011792645201 0.0240928702430903 0.999679829066432 0.00773129750811996 0.00770097260565419 -0.000973108728229476 -0.00771008761244893 0.999969803348287 -0.0646833627207335 4.49112391280137e-05 -1.66651041644657e-05 5.3776346026049e-07 5.91463167049198e-06 -1.95425404610823e-06 -3.9403559256798e-05 -1.66651041644657e-05 3.96726038960531e-05 -3.86835375615531e-07 7.48571823714101e-07 5.8099837464352e-07 4.27788123106265e-05 5.3776346026049e-07 -3.86835375615531e-07 1.28972760290608e-05 -2.77797242970799e-06 5.61065269554298e-06 2.92980457882448e-06 5.91463167049198e-06 7.48571823714101e-07 -2.77797242970799e-06 0.000210637185702789 -1.16598153127355e-07 -5.50326340351122e-05 -1.95425404610823e-06 5.8099837464352e-07 5.61065269554298e-06 -1.16598153127355e-07 1.19249249650656e-05 1.64811702025953e-06 -3.9403559256798e-05 4.27788123106265e-05 2.92980457882448e-06 -5.50326340351122e-05 1.64811702025953e-06 0.000838210952903689 3134 3118 0 65 173 3134 3118 0 35 223 0 0 0 0 0 0 0 0 3315 0 0 0 0 0 3581 +971 972 0.999967014770162 -0.00166722002468379 0.00794919801235608 0.162703017192683 0.00166156725683921 0.999998362075788 0.000717662867817093 0.00139903914312422 -0.00795038149407639 -0.00070443106840699 0.999968147098181 0.0740161564603006 5.00504904651987e-05 -7.27115854720502e-06 -1.4714067522767e-06 3.85813562649818e-06 -1.09813557800328e-06 -1.46589142078478e-05 -7.27115854720502e-06 2.46815198007091e-05 -1.4673325912261e-06 1.37399273144782e-06 1.17935654161823e-06 -1.70101893616146e-06 -1.4714067522767e-06 -1.4673325912261e-06 1.11355480754299e-05 -3.14745007579269e-06 4.51077497129978e-06 -3.80910639980985e-07 3.85813562649818e-06 1.37399273144782e-06 -3.14745007579269e-06 0.000162787628823112 4.33407792486746e-07 -2.13064172832448e-05 -1.09813557800328e-06 1.17935654161823e-06 4.51077497129978e-06 4.33407792486746e-07 1.12309144274524e-05 4.17230556002672e-06 -1.46589142078478e-05 -1.70101893616146e-06 -3.80910639980985e-07 -2.13064172832448e-05 4.17230556002672e-06 0.000174183377761723 3246 3229 0 190 152 3246 3229 0 104 194 0 0 0 0 0 0 0 0 3132 0 0 0 0 0 3609 +969 970 0.999608798909647 -0.0192731354547672 -0.0202680880241433 0.137917074045692 0.019028197784304 0.999744399999833 -0.0122091096340069 0.0169250241940852 0.0204982153245993 0.0118186682293728 0.999720031933836 -0.0858261680925588 0.000100489633217161 -1.85207954066822e-05 7.68504010692422e-08 -4.89711475870589e-05 4.74297891401115e-06 8.78415977776435e-05 -1.85207954066822e-05 4.20025178984378e-05 -8.05389672360784e-07 2.22835761689028e-06 1.77983879495239e-06 1.48259786219587e-05 7.68504010692422e-08 -8.05389672360784e-07 1.29735385593548e-05 1.18304420673877e-06 3.03307582970916e-06 -8.71893122840296e-07 -4.89711475870589e-05 2.22835761689028e-06 1.18304420673877e-06 0.000200113415632865 2.20937203495679e-06 -7.56751828574036e-05 4.74297891401115e-06 1.77983879495239e-06 3.03307582970916e-06 2.20937203495679e-06 1.25801147746657e-05 1.01165864616781e-05 8.78415977776435e-05 1.48259786219587e-05 -8.71893122840296e-07 -7.56751828574036e-05 1.01165864616781e-05 0.000527541528342805 3215 3205 0 72 178 3215 3205 0 12 227 0 0 0 0 0 0 0 0 3113 0 0 0 0 0 3583 +964 965 0.999686157469348 0.0191584848036758 0.0161412212734154 0.0928024783202719 -0.0194275830527203 0.999672069806546 0.0166829813111014 -0.00292226952516977 -0.0158163074356719 -0.0169913303988895 0.999730533249023 -0.0163708701129024 5.85831402483867e-05 -2.29562200559706e-05 -2.99420853313234e-06 -3.88305936809622e-06 8.68288403966436e-07 4.15801256770287e-06 -2.29562200559706e-05 8.05826613660035e-05 1.41774099154969e-06 -1.15535734591642e-05 -1.70374109894706e-06 5.38230272865379e-06 -2.99420853313234e-06 1.41774099154969e-06 1.14995492722735e-05 -2.41575797697102e-06 4.17765990576132e-06 -2.10695972542431e-06 -3.88305936809622e-06 -1.15535734591642e-05 -2.41575797697102e-06 0.000280937646961059 3.99688007563096e-05 -2.32285820258414e-05 8.68288403966436e-07 -1.70374109894706e-06 4.17765990576132e-06 3.99688007563096e-05 1.85153811038021e-05 -2.08100456435861e-06 4.15801256770287e-06 5.38230272865379e-06 -2.10695972542431e-06 -2.32285820258414e-05 -2.08100456435861e-06 0.000187798373252025 3153 3211 0 27 3 3153 3211 0 9 54 0 0 0 0 0 0 0 0 3683 0 0 0 0 0 3800 +960 961 0.998381759839819 0.0139704507103878 0.0551242970575929 0.155326429792578 -0.0142835858741873 0.999883987534621 0.00529061871992797 0.0166645065297505 -0.0550439896239348 -0.00606942985901952 0.998465483242894 0.011567965682822 6.88589153254342e-05 -1.55792606318573e-05 -2.45918610929789e-07 2.26098333604942e-05 4.36951866534934e-06 -1.53422095114975e-05 -1.55792606318573e-05 2.71513423261921e-05 -9.44248928888739e-07 -1.62551015056886e-05 5.18522174330005e-09 2.2754189382034e-06 -2.45918610929789e-07 -9.44248928888739e-07 1.29680379292312e-05 -1.80153709300084e-07 2.09357617480008e-06 -1.07750970846239e-06 2.26098333604942e-05 -1.62551015056886e-05 -1.80153709300084e-07 0.000213099062539711 6.58413123807191e-06 -1.28534812133675e-05 4.36951866534934e-06 5.18522174330005e-09 2.09357617480008e-06 6.58413123807191e-06 1.19226693125987e-05 2.93578379779349e-07 -1.53422095114975e-05 2.2754189382034e-06 -1.07750970846239e-06 -1.28534812133675e-05 2.93578379779349e-07 0.000140766740292996 3432 3413 0 196 126 3432 3413 0 118 178 0 0 0 0 0 0 0 0 3611 0 0 0 0 0 3673 +961 962 0.999139589487254 0.0320806186661264 0.0262852549015485 0.155309922027969 -0.0320884932369742 0.99948502422558 -0.000122272530438256 0.00859007234690968 -0.0262756412104721 -0.000721286898272835 0.999654475518511 -0.0650880034395192 6.83774905202083e-05 -3.43119003065163e-05 1.6930618308297e-06 -3.05614324850635e-05 2.84308250947061e-06 -3.30918385770076e-06 -3.43119003065163e-05 8.63481024231472e-05 1.54226851727412e-07 2.18444523943035e-05 -4.90022902656455e-07 -4.65996840782658e-05 1.6930618308297e-06 1.54226851727412e-07 1.39959324567645e-05 -3.23949280274574e-06 1.45598069747895e-06 5.66306792750799e-06 -3.05614324850635e-05 2.18444523943035e-05 -3.23949280274574e-06 0.000212560925483846 1.39379585590844e-05 -4.74031635961459e-05 2.84308250947061e-06 -4.90022902656455e-07 1.45598069747895e-06 1.39379585590844e-05 1.34188931495111e-05 -1.1008257658555e-05 -3.30918385770076e-06 -4.65996840782658e-05 5.66306792750799e-06 -4.74031635961459e-05 -1.1008257658555e-05 0.000290547544547112 3020 3012 0 248 67 3020 3012 0 179 111 0 0 0 0 0 0 0 0 3567 0 0 0 0 0 3745 +962 963 0.999375168575473 0.0351441359669773 0.0037632621326167 0.158250817552619 -0.0349942430849085 0.99879554592184 -0.0343927375707241 0.0115119537388606 -0.00496743250165598 0.0342395553976534 0.999401309515108 -0.0516339967413686 6.4572723900312e-05 -1.95970733809459e-05 7.22442145966897e-06 -4.80964624058593e-05 -3.36569982622749e-06 1.05017958726835e-05 -1.95970733809459e-05 6.41616339569501e-05 -5.77920624401811e-06 1.04169240870321e-05 3.2156533671677e-06 -3.16845285529615e-05 7.22442145966897e-06 -5.77920624401811e-06 1.41790288950924e-05 -3.73574875778863e-06 3.71918002059146e-06 -3.54988213373868e-07 -4.80964624058593e-05 1.04169240870321e-05 -3.73574875778863e-06 0.000244909466875127 2.18578323413201e-05 9.75311497872808e-05 -3.36569982622749e-06 3.2156533671677e-06 3.71918002059146e-06 2.18578323413201e-05 1.43988217308354e-05 1.66311896990652e-05 1.05017958726835e-05 -3.16845285529615e-05 -3.54988213373868e-07 9.75311497872808e-05 1.66311896990652e-05 0.000281135703719107 3163 3164 0 258 68 3163 3164 0 190 119 0 0 0 0 0 0 0 0 3570 0 0 0 0 0 3731 +965 966 0.995515476864028 -0.00927831266799779 0.0941427014601852 0.131415964431413 0.00854066385448001 0.999929615692159 0.00823533379146309 0.0143617991979837 -0.0942124852931471 -0.00739436107901871 0.995524651145878 -0.144734414951045 0.000169355665060877 -0.000845375161492252 -2.32802855828628e-05 0.000123053251349735 1.64591505958002e-05 0.000338969040930404 -0.000845375161492252 0.00686662943060931 0.000213577809523918 -0.000900167881264449 -0.000106225287651249 -0.00237096101629874 -2.32802855828628e-05 0.000213577809523918 2.26483416935739e-05 -3.1219986550329e-05 4.81540676680875e-08 -7.4451442564832e-05 0.000123053251349735 -0.000900167881264449 -3.1219986550329e-05 0.000356562686637835 4.20905967150019e-05 0.000498631347853385 1.64591505958002e-05 -0.000106225287651249 4.81540676680875e-08 4.20905967150019e-05 1.91501927446275e-05 1.8694031921742e-05 0.000338969040930404 -0.00237096101629874 -7.4451442564832e-05 0.000498631347853385 1.8694031921742e-05 0.00685220802757178 2600 2648 0 18 129 2601 2656 0 30 177 0 0 0 0 0 1 11 0 3505 0 0 0 0 0 3616 +973 974 0.998154343019283 0.00399759319299856 -0.0605964253104651 0.110769215699722 -0.00341668968424619 0.999947242568386 0.00968701767739702 -0.010148012169056 0.0606319531546283 -0.00946209958433795 0.998115341495216 -0.00737883303904511 7.88169165670278e-05 -4.85507969822368e-06 -5.38024320920588e-07 -3.68846954057547e-05 -4.23212811642181e-07 2.86850433805834e-05 -4.85507969822368e-06 4.02919661958072e-05 -3.2610072118692e-06 -3.27477882206291e-05 1.62358362263743e-06 -3.34598375028726e-05 -5.38024320920588e-07 -3.2610072118692e-06 1.33752813012004e-05 1.20155213402411e-06 5.76277834547728e-06 2.34781970610381e-06 -3.68846954057547e-05 -3.27477882206291e-05 1.20155213402411e-06 0.000909435116865291 1.9516382899298e-05 0.000132384939734593 -4.23212811642181e-07 1.62358362263743e-06 5.76277834547728e-06 1.9516382899298e-05 1.33139659638395e-05 3.38842757497821e-06 2.86850433805834e-05 -3.34598375028726e-05 2.34781970610381e-06 0.000132384939734593 3.38842757497821e-06 0.000151004805182426 3155 3224 0 63 57 3155 3224 0 69 98 0 0 0 0 0 2 15 0 3074 0 0 0 0 0 3697 +967 968 0.99884578044233 -0.0413169568038239 -0.0244952234736335 0.133709791397253 0.0415071043017866 0.999111500435544 0.00730547670703174 0.0142195532727674 0.0241716194127101 -0.00831377037855406 0.999673253636937 -0.0221387198605601 0.000116790517318664 -3.40050354208656e-05 -2.00748343254673e-06 7.54220303436303e-05 1.15042000104799e-05 -2.1474403062844e-05 -3.40050354208656e-05 7.19373762166245e-05 -2.36520117291947e-07 -3.24258409271415e-05 -2.6237018813181e-06 -1.80161847987232e-05 -2.00748343254673e-06 -2.36520117291947e-07 1.61607440616779e-05 -8.06222578360475e-06 3.90037728576345e-06 -5.39447441609677e-06 7.54220303436303e-05 -3.24258409271415e-05 -8.06222578360475e-06 0.000596797535915665 4.78845421056803e-05 -0.000127974743989101 1.15042000104799e-05 -2.6237018813181e-06 3.90037728576345e-06 4.78845421056803e-05 1.78349894691537e-05 5.68810975320969e-06 -2.1474403062844e-05 -1.80161847987232e-05 -5.39447441609677e-06 -0.000127974743989101 5.68810975320969e-06 0.000684933388826758 3190 3202 0 17 213 3184 3202 0 0 279 0 0 0 0 0 8 8 0 3371 0 0 0 0 0 3537 +975 976 0.999576295929207 0.0211069227327455 0.0200431142590393 0.0643022619876151 -0.0216454324738622 0.999399924959393 0.0270419164294742 -0.0111986512374635 -0.0194603152458142 -0.0274643005356609 0.99943334361358 -0.0120768821812402 0.000109997844473762 5.95838331697979e-06 -6.42951947634008e-07 -5.6969620880389e-05 -3.09799551904163e-06 5.3837392163192e-05 5.95838331697979e-06 2.07099754844651e-05 3.08318050156696e-07 -1.45031544185043e-06 1.10325698476741e-07 -2.81008455368148e-06 -6.42951947634008e-07 3.08318050156696e-07 1.12259495090084e-05 -4.12221116751028e-06 2.69685026579453e-06 -1.77151774865344e-06 -5.6969620880389e-05 -1.45031544185043e-06 -4.12221116751028e-06 0.000356730166729821 3.28062686896456e-05 4.12531974146021e-05 -3.09799551904163e-06 1.10325698476741e-07 2.69685026579453e-06 3.28062686896456e-05 1.63442088409659e-05 7.0706586371708e-06 5.3837392163192e-05 -2.81008455368148e-06 -1.77151774865344e-06 4.12531974146021e-05 7.0706586371708e-06 9.72654469494404e-05 3624 3603 0 135 0 3624 3634 0 61 6 0 0 0 0 0 0 0 0 2486 0 0 0 0 0 3817 +974 975 0.999352402781905 0.0350880305829389 0.00797528456191051 0.0700548708540633 -0.0352438414805036 0.99917220576274 0.0203168616896995 -0.0134692303190936 -0.00725580400299214 -0.0205847842114507 0.999761781609618 -0.0115697022913364 1.86786357879194e-05 -1.05733546137568e-06 -1.97888950382974e-06 -3.24715858190839e-07 2.93859413182363e-06 2.31492237455953e-06 -1.05733546137568e-06 1.54483109242572e-05 -1.3080270413879e-06 6.30004626076885e-06 1.1098029218453e-06 -1.13390348356713e-06 -1.97888950382974e-06 -1.3080270413879e-06 1.22341441753617e-05 -5.08662599862286e-06 2.69722581739115e-06 -1.75644331854646e-07 -3.24715858190839e-07 6.30004626076885e-06 -5.08662599862286e-06 0.000272950026845001 1.99322704439332e-05 3.39019326939323e-05 2.93859413182363e-06 1.1098029218453e-06 2.69722581739115e-06 1.99322704439332e-05 1.51940415772454e-05 7.20738165435903e-06 2.31492237455953e-06 -1.13390348356713e-06 -1.75644331854646e-07 3.39019326939323e-05 7.20738165435903e-06 7.19825584882101e-05 3698 3651 0 71 0 3711 3696 0 90 0 0 0 0 0 0 0 0 0 3172 0 0 5 0 0 3836 +972 973 0.999980051914355 0.00496777895517191 -0.0039008903621227 0.160062467571227 -0.00510052922428357 0.999381549891687 -0.0347922741096723 -0.00168810038466569 0.00372563752893113 0.0348114766757013 0.999386952444678 0.0437927006503969 7.65376208957458e-05 -1.76732034438742e-05 3.42014092904427e-06 -1.15060458687984e-05 -2.10360697539525e-06 1.74307788507935e-05 -1.76732034438742e-05 2.76126451191636e-05 -5.90027969269374e-07 9.05513135694433e-06 1.07804544148319e-06 -7.27180537341605e-06 3.42014092904427e-06 -5.90027969269374e-07 1.13425326069075e-05 -3.52895055783951e-06 3.97328799440811e-06 -7.01490961978378e-07 -1.15060458687984e-05 9.05513135694433e-06 -3.52895055783951e-06 0.000294889958699399 5.88719605284515e-06 -4.25587151187597e-05 -2.10360697539525e-06 1.07804544148319e-06 3.97328799440811e-06 5.88719605284515e-06 1.16072207327137e-05 4.68601112812225e-06 1.74307788507935e-05 -7.27180537341605e-06 -7.01490961978378e-07 -4.25587151187597e-05 4.68601112812225e-06 0.000149676035938789 3234 3277 0 192 125 3234 3277 0 126 168 0 0 0 0 0 0 0 0 2796 0 0 0 0 0 3643 +979 980 0.999414888854291 -0.0233873656779199 -0.0249581862925364 0.182659090591571 0.0240261995682788 0.99938322250382 0.0256108631675187 0.0101985289121268 0.0243438220226598 -0.026195528330755 0.999360381756652 0.0256681752883906 5.58910554770782e-05 1.37081716847209e-06 -4.04866595028241e-06 -3.78661064194363e-06 5.80344387714659e-06 -8.84338508837837e-06 1.37081716847209e-06 3.78048490122055e-05 2.586032918051e-07 -1.46455366559242e-06 2.84917470960854e-06 -2.09649324426923e-06 -4.04866595028241e-06 2.586032918051e-07 1.33318453223301e-05 4.14924482931019e-07 1.05724212534827e-06 -3.63277660547744e-06 -3.78661064194363e-06 -1.46455366559242e-06 4.14924482931019e-07 0.000246747188124731 -8.24371893993347e-06 1.94778096354318e-05 5.80344387714659e-06 2.84917470960854e-06 1.05724212534827e-06 -8.24371893993347e-06 1.49594307988272e-05 -7.75575060411232e-06 -8.84338508837837e-06 -2.09649324426923e-06 -3.63277660547744e-06 1.94778096354318e-05 -7.75575060411232e-06 0.000200637551657406 3344 3323 0 131 237 3344 3323 0 70 285 0 0 0 0 0 0 0 0 2565 0 0 0 0 0 3519 +980 981 0.999619025925878 -0.0207137272496804 0.0182412858763783 0.152647698509437 0.0208202168418691 0.999767172566036 -0.00566738299144071 0.0102099565459766 -0.0181196461790913 0.00604501139287357 0.999817551486072 -0.00595256049010761 4.31916954970286e-05 9.58694055514315e-05 4.21483831564737e-07 8.91554275048506e-05 5.73847850925875e-07 1.89016524507101e-05 9.58694055514315e-05 0.000747448000614918 1.81399094818562e-05 0.000783694322271941 -2.7801678185185e-05 0.000180338546563719 4.21483831564737e-07 1.81399094818562e-05 1.58999663006043e-05 2.40823858797383e-05 -1.0595731566503e-06 5.93195019570308e-06 8.91554275048506e-05 0.000783694322271941 2.40823858797383e-05 0.00107212064397473 -4.67034487344768e-05 0.00023499023618518 5.73847850925875e-07 -2.7801678185185e-05 -1.0595731566503e-06 -4.67034487344768e-05 1.82331945574679e-05 -2.69703110473145e-05 1.89016524507101e-05 0.000180338546563719 5.93195019570308e-06 0.00023499023618518 -2.69703110473145e-05 0.000459300578356325 3048 3021 0 94 190 3048 3021 0 34 237 0 0 0 0 0 0 0 0 3294 0 0 0 0 0 3554 +981 982 0.999861117300021 -0.00368136200969426 0.0162540359698128 0.127537190988624 0.0040907071678729 0.999673474390941 -0.0252232177568785 0.00152230495108111 -0.0161558728152057 0.0252862051897428 0.999549696413681 0.0409704626145928 0.000108053910010643 3.05793852124447e-05 -6.39359314755614e-06 1.94328119459072e-05 -1.35209149204839e-06 0.000161740308697431 3.05793852124447e-05 5.82679514847421e-05 -6.00342702655886e-06 2.213517586754e-05 6.3494532668331e-07 0.000103156016050598 -6.39359314755614e-06 -6.00342702655886e-06 1.42774006420253e-05 1.88522905264341e-06 1.54342726315307e-06 -2.47605256263862e-06 1.94328119459072e-05 2.213517586754e-05 1.88522905264341e-06 0.000251381728957006 -9.96509541866182e-06 0.000106541461189675 -1.35209149204839e-06 6.3494532668331e-07 1.54342726315307e-06 -9.96509541866182e-06 1.59742473516817e-05 -2.58763619044162e-05 0.000161740308697431 0.000103156016050598 -2.47605256263862e-06 0.000106541461189675 -2.58763619044162e-05 0.00106584075738651 3250 3218 0 131 115 3250 3218 0 59 153 0 0 0 0 0 0 0 0 2995 0 0 0 0 0 3636 +983 984 0.999262826956981 0.0127316199159944 -0.0362175167047287 0.146553678822355 -0.0140939254877877 0.999193048205042 -0.0376113504551648 0.00100125914591147 0.0357094374960925 0.0380940713632869 0.998635908527568 -0.0285044518312959 2.4527195642054e-05 5.25575067300771e-07 -3.59761271568654e-06 1.30690704967489e-05 3.85645541414336e-06 2.3919389214898e-06 5.25575067300771e-07 3.98952567064266e-05 7.85412856695678e-07 2.11316496079253e-05 -4.46298856906003e-07 -1.69113342170848e-05 -3.59761271568654e-06 7.85412856695678e-07 1.53976372573358e-05 -1.10107863593195e-05 -9.98386748578323e-07 -2.77087054036536e-06 1.30690704967489e-05 2.11316496079253e-05 -1.10107863593195e-05 0.000703142605383882 5.2156722955255e-06 4.54591006885915e-05 3.85645541414336e-06 -4.46298856906003e-07 -9.98386748578323e-07 5.2156722955255e-06 1.60310982171049e-05 2.22134871575809e-06 2.3919389214898e-06 -1.69113342170848e-05 -2.77087054036536e-06 4.54591006885915e-05 2.22134871575809e-06 0.000134194693231796 3308 3286 0 189 85 3308 3286 0 122 127 0 0 0 0 0 0 0 0 3312 0 0 0 0 0 3698 +977 978 0.999412356967188 -0.0300433422818397 0.016502676323152 0.170019177778664 0.0300163514176075 0.999547638181973 0.00188086480466413 0.0142354449202594 -0.0165517186076006 -0.00138440939571924 0.999862052496123 0.0283001410557847 3.95631620739489e-05 -2.97069917163048e-06 -1.54824484361525e-07 -1.83719066833019e-05 -2.4907966304179e-06 8.24985314780235e-06 -2.97069917163048e-06 4.02733095627444e-05 -3.34162447483015e-07 2.51711753298035e-05 1.20541413726373e-06 1.77833704580186e-05 -1.54824484361525e-07 -3.34162447483015e-07 1.54855208180381e-05 -9.11504527997699e-06 3.31139215339414e-06 1.11287868862278e-06 -1.83719066833019e-05 2.51711753298035e-05 -9.11504527997699e-06 0.000614339262049873 2.93136183247853e-05 0.000151243530002629 -2.4907966304179e-06 1.20541413726373e-06 3.31139215339414e-06 2.93136183247853e-05 1.48537886759606e-05 7.66105341613962e-06 8.24985314780235e-06 1.77833704580186e-05 1.11287868862278e-06 0.000151243530002629 7.66105341613962e-06 0.000208393761064975 3346 3349 0 96 247 3346 3349 0 45 308 0 0 0 0 0 0 0 0 2839 0 0 0 0 0 3505 +976 977 0.998937168484465 0.00196813094344314 0.0460506230232545 0.157567401494413 -0.00195387174875968 0.999998028301592 -0.000354652109407214 0.00583980727802812 -0.0460512302271051 0.000264298162630366 0.998939044357088 0.0122661218908497 0.000101089396851026 2.0781152991576e-05 1.44350905535337e-06 -6.33348713823812e-05 -4.27808731292039e-07 4.2612095432921e-05 2.0781152991576e-05 0.000111056057672651 3.10741142205685e-06 -7.60895993102653e-05 -6.26576601027033e-06 3.25314289588664e-06 1.44350905535337e-06 3.10741142205685e-06 1.37745649463944e-05 -1.16032476277032e-05 2.5101251539106e-06 -1.33150385252182e-06 -6.33348713823812e-05 -7.60895993102653e-05 -1.16032476277032e-05 0.000556956565696119 4.74698559714484e-05 7.90395137222851e-05 -4.27808731292039e-07 -6.26576601027033e-06 2.5101251539106e-06 4.74698559714484e-05 1.71076251481468e-05 1.47126205843365e-05 4.2612095432921e-05 3.25314289588664e-06 -1.33150385252182e-06 7.90395137222851e-05 1.47126205843365e-05 0.000199335695705278 3174 3186 0 164 140 3174 3186 0 115 202 0 0 0 0 0 0 0 0 2273 0 0 0 0 0 3617 +978 979 0.998627401018012 -0.0510353674415128 -0.0117773174415807 -0.878939587189146 0.0513661293897079 0.99823704159991 0.0297376786145147 -0.0354108079213685 0.0102388811659172 -0.0303018159186896 0.999488351740279 -0.027065716811317 6.15729090178891e-05 -3.51876634141263e-06 -9.58234078963999e-08 0.000109380373492099 2.95235055665505e-06 -7.38830465483745e-06 -3.51876634141263e-06 4.72035114390293e-05 4.78916539515613e-06 -2.50993431539068e-05 -8.11750224764832e-07 -1.87987823739699e-05 -9.58234078963999e-08 4.78916539515613e-06 1.50450516635306e-05 -3.8756043373952e-06 4.70508358323346e-06 -1.78479758387426e-06 0.000109380373492099 -2.50993431539068e-05 -3.8756043373952e-06 0.00130927615858714 1.44973556286751e-05 -0.000258883335100209 2.95235055665505e-06 -8.11750224764832e-07 4.70508358323346e-06 1.44973556286751e-05 1.29473707631123e-05 -1.61106346759827e-06 -7.38830465483745e-06 -1.87987823739699e-05 -1.78479758387426e-06 -0.000258883335100209 -1.61106346759827e-06 0.000140809201028497 1760 1760 0 0 0 1762 1762 0 0 0 0 0 0 0 0 669 616 0 1126 0 567 609 0 0 2199 +982 983 0.982238097381783 0.0203365700568107 0.186533492891063 0.22097966798121 -0.0184192050593749 0.99975825955165 -0.0120064708901895 0.00884044910391483 -0.186732570637252 0.00835741446744756 0.982375234157816 -0.466125059735756 0.000153936340187139 -7.50137493410732e-05 -2.3504642510274e-05 0.000155608113181427 -6.1854844517818e-06 -8.84450806569244e-05 -7.50137493410732e-05 0.00571503693229053 0.000171231079930313 0.00204104816538463 0.000331687541212361 -0.0103340722774714 -2.3504642510274e-05 0.000171231079930313 3.30880664202555e-05 1.53857147573419e-05 9.32540416668417e-06 -0.000296789369317771 0.000155608113181427 0.00204104816538463 1.53857147573419e-05 0.00207841959102584 0.000134595208458399 -0.00478480124135793 -6.1854844517818e-06 0.000331687541212361 9.32540416668417e-06 0.000134595208458399 4.38803186629865e-05 -0.000705188580427531 -8.84450806569244e-05 -0.0103340722774714 -0.000296789369317771 -0.00478480124135793 -0.000705188580427531 0.0220144063744103 1751 1738 0 186 116 1751 1738 0 155 139 0 0 0 0 0 0 0 0 1873 0 0 0 0 0 2195 +984 985 0.99990119032731 -0.000242854921378186 0.014055269599542 0.185214926401679 0.000203263843357307 0.999996008282052 0.00281817383621391 -0.00485538967442109 -0.0140558979022555 -0.00281503844526134 0.999897248367408 -0.0802352243106463 4.0072858185798e-05 -4.04710201614299e-06 4.82037953799946e-06 -1.57427119532236e-05 5.07189003627801e-06 2.71024929860079e-05 -4.04710201614299e-06 0.000288519852178045 7.03632085800924e-06 0.000367572354886711 -6.91166204231933e-06 -0.000313227385564102 4.82037953799946e-06 7.03632085800924e-06 1.27884513683435e-05 8.3272918782098e-06 2.30223843354365e-06 -5.35992537468945e-06 -1.57427119532236e-05 0.000367572354886711 8.3272918782098e-06 0.00102676460966164 -1.48521875250903e-05 -0.000490088342546407 5.07189003627801e-06 -6.91166204231933e-06 2.30223843354365e-06 -1.48521875250903e-05 1.33444843278652e-05 1.0478895984545e-05 2.71024929860079e-05 -0.000313227385564102 -5.35992537468945e-06 -0.000490088342546407 1.0478895984545e-05 0.000542012025365459 3205 3182 0 233 172 3205 3182 0 161 213 0 0 0 0 0 0 0 0 3190 0 0 0 0 0 3593 +988 989 0.999400225830934 -0.0339553665111169 0.00679865385006162 0.141519895170407 0.0339504758057051 0.999423168851791 0.000833519531965617 0.000642698443644111 -0.00682303463595708 -0.000602202075433051 0.999976541500358 -0.0377950625134631 0.000134921864111729 3.13507141604407e-05 -8.89923196660072e-06 5.28644242903689e-05 6.78810973872434e-06 7.43971240975967e-05 3.13507141604407e-05 5.18162110416398e-05 -4.88922650162582e-06 3.62778337791945e-05 -1.45901353862732e-06 7.29067659235532e-05 -8.89923196660072e-06 -4.88922650162582e-06 1.40888058619718e-05 3.07213324156561e-06 6.94067734842144e-07 8.72141899067832e-06 5.28644242903689e-05 3.62778337791945e-05 3.07213324156561e-06 0.000343597144503275 -2.44364137319437e-05 2.32351606001336e-05 6.78810973872434e-06 -1.45901353862732e-06 6.94067734842144e-07 -2.44364137319437e-05 1.62043646243267e-05 -1.00884385316799e-05 7.43971240975967e-05 7.29067659235532e-05 8.72141899067832e-06 2.32351606001336e-05 -1.00884385316799e-05 0.0010123681013017 3429 3383 0 80 207 3429 3383 0 4 239 0 0 0 0 0 0 0 0 3705 0 0 0 0 0 3544 +987 988 0.999400808856976 -0.0334160634297131 0.00902163848105071 0.152742060284723 0.0336456199787314 0.999079223120757 -0.026621010211323 0.00639379696131986 -0.00812376219913986 0.026908597757705 0.999604887870425 -0.0597017922292523 9.68885203402992e-05 4.50439784700838e-05 -3.32992990483039e-06 -1.72319547611756e-05 8.63067303250815e-06 0.000106499048328369 4.50439784700838e-05 0.000576713361927671 5.17227686409485e-06 0.000476065545149957 -2.8729502602025e-05 -0.000391646861731623 -3.32992990483039e-06 5.17227686409485e-06 1.47983349730103e-05 1.93181765791685e-06 1.69889708912305e-06 -9.50981392853783e-06 -1.72319547611756e-05 0.000476065545149957 1.93181765791685e-06 0.00056255297367829 -3.55704198818272e-05 -0.000476611108951777 8.63067303250815e-06 -2.8729502602025e-05 1.69889708912305e-06 -3.55704198818272e-05 1.63320568034086e-05 4.10342638710237e-05 0.000106499048328369 -0.000391646861731623 -9.50981392853783e-06 -0.000476611108951777 4.10342638710237e-05 0.00109977639863149 3141 3102 0 80 221 3141 3102 0 14 261 0 0 0 0 0 0 0 0 3668 0 0 0 0 0 3518 +986 987 0.999376690718685 -0.0273204699946146 0.022356698491584 0.143410109866038 0.0272325649452918 0.999620187631762 0.00422704217408206 0.00169967895351404 -0.0224636919198669 -0.00361557717582808 0.999741121564485 0.00232232107467612 6.98625883681687e-05 1.5602986603029e-05 -7.63275066990958e-07 4.00949224404991e-06 1.99292629108221e-06 4.26390825523792e-05 1.5602986603029e-05 3.11526790694035e-05 -4.42293116049171e-07 6.70349296573803e-06 1.09741035613857e-06 2.04092763632164e-06 -7.63275066990958e-07 -4.42293116049171e-07 1.27848732290394e-05 -1.67980323513942e-06 1.81894523969425e-06 3.30638401695169e-06 4.00949224404991e-06 6.70349296573803e-06 -1.67980323513942e-06 0.000201476769646417 -6.02481266893244e-06 6.47800112153262e-05 1.99292629108221e-06 1.09741035613857e-06 1.81894523969425e-06 -6.02481266893244e-06 1.25996036035359e-05 -3.94500309175643e-06 4.26390825523792e-05 2.04092763632164e-06 3.30638401695169e-06 6.47800112153262e-05 -3.94500309175643e-06 0.00013604709601509 3366 3341 0 86 185 3366 3341 0 19 226 0 0 0 0 0 0 0 0 3640 0 0 0 0 0 3563 +991 992 0.999389521282333 -0.0218327557045682 0.0272748149290501 0.16609820241058 0.0217396019711589 0.999756793309082 0.00370728181795997 -0.0049564624268917 -0.0273491216898253 -0.00311207498091514 0.999621098482874 0.00392051040028042 0.000145797226484796 0.000240021960927027 1.01862587132665e-05 2.79028353803469e-05 3.73848019967733e-08 0.000133297437963212 0.000240021960927027 0.000957207791307851 3.24905327741828e-05 0.000177205525359792 -3.42883020936585e-05 0.000521030768805035 1.01862587132665e-05 3.24905327741828e-05 1.93214727037052e-05 -1.62345093298539e-06 -1.16662576421927e-06 4.56483433026883e-06 2.79028353803469e-05 0.000177205525359792 -1.62345093298539e-06 0.000359381061706635 -4.43370620864361e-05 4.65223963215363e-07 3.73848019967733e-08 -3.42883020936585e-05 -1.16662576421927e-06 -4.43370620864361e-05 2.37631697185298e-05 -2.56293722798052e-05 0.000133297437963212 0.000521030768805035 4.56483433026883e-06 4.65223963215363e-07 -2.56293722798052e-05 0.00145337458041358 3106 3028 0 172 204 3106 3028 0 77 224 0 0 0 0 0 0 0 0 3597 0 0 0 0 0 3571 +985 986 0.999746578846885 0.00499774392398012 -0.021949957622284 0.122599988444183 -0.0046668887177373 0.999875118321393 0.01509860627595 -0.0037787937138283 0.022022675442507 -0.0149923419601548 0.99964505273067 0.0543311791448022 6.90933290157402e-05 2.01202928523023e-05 -5.68925871875758e-06 -3.50197075466966e-06 4.45463116677921e-06 1.30165320108331e-05 2.01202928523023e-05 6.11744480537421e-05 -3.6672795536561e-06 -6.06019747487375e-06 4.42109130214813e-06 -2.35871598720903e-05 -5.68925871875758e-06 -3.6672795536561e-06 1.63534278588937e-05 -7.58342507664119e-06 1.52232504530754e-06 5.98090082555904e-06 -3.50197075466966e-06 -6.06019747487375e-06 -7.58342507664119e-06 0.000169944655931283 2.45331234942199e-06 -3.98466198496174e-05 4.45463116677921e-06 4.42109130214813e-06 1.52232504530754e-06 2.45331234942199e-06 1.620121535032e-05 -1.46783312957969e-06 1.30165320108331e-05 -2.35871598720903e-05 5.98090082555904e-06 -3.98466198496174e-05 -1.46783312957969e-06 0.000175833557366001 3162 3140 0 136 72 3162 3140 0 72 117 0 0 0 0 0 0 0 0 3426 0 0 0 0 0 3698 +993 994 0.982359087033286 0.0155144380841011 0.186359669279766 0.055313809827536 -0.00759105907591944 0.999039540463339 -0.0431552130443951 0.0135401145293772 -0.186850207238941 0.0409792484281474 0.981533341895745 -0.0521347178445221 9.69357489500559e-05 0.000252434811287767 1.14132507596394e-05 0.000215618799089447 -2.6668514849751e-05 -0.000142233691268341 0.000252434811287767 0.00119132250193601 -1.85229943453462e-05 0.0010337883974645 -0.00013548308106581 -0.000603962406113139 1.14132507596394e-05 -1.85229943453462e-05 1.5383224041861e-05 -1.48530184028642e-05 6.15675536979081e-06 7.84238122635271e-06 0.000215618799089447 0.0010337883974645 -1.48530184028642e-05 0.00129111687265168 -0.000166168825096403 -0.000376909843645885 -2.6668514849751e-05 -0.00013548308106581 6.15675536979081e-06 -0.000166168825096403 3.39755796757048e-05 4.72265549428034e-05 -0.000142233691268341 -0.000603962406113139 7.84238122635271e-06 -0.000376909843645885 4.72265549428034e-05 0.000528728865199866 2662 2580 0 60 37 2639 2580 0 8 44 0 0 0 0 0 0 0 0 3743 0 1 3 0 0 3738 +989 990 0.999273546492118 -0.0333855138290206 -0.0183789756906174 0.150843405260914 0.0337426574816754 0.999240738597004 0.0194776639818008 -0.00326048239951036 0.0177147494235275 -0.0200836698460684 0.999641352615215 0.0489333479089676 8.91276839620453e-05 0.000113262460952514 7.59968975956218e-06 3.08329546522595e-05 -3.53809838037349e-06 -5.38414792528797e-05 0.000113262460952514 0.000587909110294169 2.06203728833336e-05 0.000289037236261961 -2.59353900152259e-05 -0.000570494022169536 7.59968975956218e-06 2.06203728833336e-05 1.48427958573539e-05 4.25100805814096e-06 1.09566062639763e-06 -1.9460679286464e-05 3.08329546522595e-05 0.000289037236261961 4.25100805814096e-06 0.000294823814645726 -2.08140843090613e-05 -0.000305918345996689 -3.53809838037349e-06 -2.59353900152259e-05 1.09566062639763e-06 -2.08140843090613e-05 1.4193842542227e-05 1.60179477463716e-05 -5.38414792528797e-05 -0.000570494022169536 -1.9460679286464e-05 -0.000305918345996689 1.60179477463716e-05 0.00103974062973697 3172 3113 0 96 212 3172 3113 0 13 238 0 0 0 0 0 0 0 0 3678 0 0 0 0 0 3539 +994 995 0.999707877104459 0.0178991251102851 -0.0162413600287391 0.284115015946242 -0.0183325755020924 0.999468835666628 -0.0269437043974016 -0.0271372880410803 0.0157504644616228 0.0272335794834399 0.999505004998856 0.106909810278388 4.49784108512001e-05 1.71426402080747e-05 1.34127543239239e-06 -4.31752778595048e-05 9.36363580282307e-06 -2.76696197221104e-05 1.71426402080747e-05 3.40382193790499e-05 1.96760836177882e-06 0.000157100038872762 -2.18270961509059e-05 3.28955694474518e-05 1.34127543239239e-06 1.96760836177882e-06 1.18660500424083e-05 1.62065523920089e-06 2.03540724518503e-06 1.43035048587251e-06 -4.31752778595048e-05 0.000157100038872762 1.62065523920089e-06 0.00545748849833844 -0.000721371871502818 0.00147499206340294 9.36363580282307e-06 -2.18270961509059e-05 2.03540724518503e-06 -0.000721371871502818 0.000107877468457435 -0.000198568299788484 -2.76696197221104e-05 3.28955694474518e-05 1.43035048587251e-06 0.00147499206340294 -0.000198568299788484 0.000604709511513165 3429 3348 0 586 200 3429 3348 0 469 213 0 0 0 0 0 0 0 0 3194 0 0 0 0 0 3623 +992 993 0.999057715949533 -0.00449842651899932 0.0431676309351766 0.171683063612292 0.00481748419020031 0.999961823492643 -0.00728995221838443 -0.00825744444265479 -0.0431331896314152 0.00749104239223899 0.999041246513926 -0.0573454309982064 6.28294950552478e-05 2.36562207577367e-05 4.46801493368288e-06 1.72923657274661e-05 -9.12840383625722e-07 2.82800127007803e-07 2.36562207577367e-05 6.29621879152044e-05 1.9255113746556e-06 -5.06173121973354e-06 -2.89756197314495e-06 2.96635257380311e-06 4.46801493368288e-06 1.9255113746556e-06 1.5429337086786e-05 -5.35189323035763e-06 -2.32983848960749e-07 6.20433416724178e-07 1.72923657274661e-05 -5.06173121973354e-06 -5.35189323035763e-06 0.00025322979443481 -3.06537923137982e-05 9.32504802534173e-05 -9.12840383625722e-07 -2.89756197314495e-06 -2.32983848960749e-07 -3.06537923137982e-05 1.98547396945776e-05 -2.73944248589197e-05 2.82800127007803e-07 2.96635257380311e-06 6.20433416724178e-07 9.32504802534173e-05 -2.73944248589197e-05 0.000401557683500218 3196 3113 0 242 165 3196 3113 0 139 178 0 0 0 0 0 0 0 0 3544 0 0 0 0 0 3618 +995 996 0.999560401583044 0.00846210186264511 -0.0284147218745728 0.169269765995908 -0.00841567941179127 0.999963051087952 0.0017529400767415 -0.00827225622231626 0.0284285055390018 -0.00151304029718713 0.999594683250105 -0.0723229901952167 4.24442928980395e-05 1.04721757178706e-05 -3.15484979731155e-06 2.43278826638691e-05 1.134117329314e-06 -1.46211235450197e-05 1.04721757178706e-05 2.27748008192537e-05 -1.47208265746067e-06 1.47471360660746e-05 -1.98002937097506e-06 1.60447339610961e-05 -3.15484979731155e-06 -1.47208265746067e-06 1.19552651270778e-05 -1.34224166414173e-06 1.856426634026e-06 -7.32867417536852e-07 2.43278826638691e-05 1.47471360660746e-05 -1.34224166414173e-06 0.000302262814038478 -2.3606970027888e-05 0.000112828818856733 1.134117329314e-06 -1.98002937097506e-06 1.856426634026e-06 -2.3606970027888e-05 1.53336605806377e-05 -1.03536852397456e-05 -1.46211235450197e-05 1.60447339610961e-05 -7.32867417536852e-07 0.000112828818856733 -1.03536852397456e-05 0.000398658058430372 3394 3308 0 275 128 3394 3308 0 157 142 0 0 0 0 0 0 0 0 3494 0 0 0 0 0 3695 +996 997 0.99983754372032 0.00188213436648753 0.0179260630798704 0.0404452288528019 -0.00202054884159816 0.999968263653326 0.00770643033644012 0.0102610240660155 -0.0179109896347389 -0.0077413988644285 0.999809615473829 0.049758899451795 5.08616449674078e-05 6.3554153530803e-06 -5.24865113431059e-06 -1.3234782766741e-05 7.21700394766967e-06 1.40574796100518e-06 6.3554153530803e-06 1.93147525874139e-05 -2.67168748222606e-06 8.79597808212459e-06 -1.68538088099396e-06 -6.48112885596644e-06 -5.24865113431059e-06 -2.67168748222606e-06 1.36300158707615e-05 -2.41464815309659e-06 9.19339400528971e-07 -2.10407396100544e-06 -1.3234782766741e-05 8.79597808212459e-06 -2.41464815309659e-06 0.00023670528614544 -2.60011164903621e-05 3.8628137386469e-05 7.21700394766967e-06 -1.68538088099396e-06 9.19339400528971e-07 -2.60011164903621e-05 1.57195664995932e-05 -6.91583198154228e-07 1.40574796100518e-06 -6.48112885596644e-06 -2.10407396100544e-06 3.8628137386469e-05 -6.91583198154228e-07 9.80968039494104e-05 3694 3604 0 1 43 3651 3604 0 0 49 0 0 0 0 0 0 0 0 3791 0 0 0 0 0 3778 +990 991 0.999440281309716 -0.0121315625585178 -0.0311761011905625 0.135255933241654 0.0119529604001724 0.99991110233753 -0.00590882050985195 -0.00210718198712322 0.0312450129337041 0.00553286652961249 0.999496441491783 0.0108037420127448 8.56752588623665e-05 5.95097997026581e-05 -8.91032287735366e-06 4.04104834722244e-05 -1.57218027521225e-06 -5.72575688224978e-05 5.95097997026581e-05 0.000265510294627738 -1.33959783688857e-06 0.000169320067406863 -1.19723620172365e-05 -0.000245147809015992 -8.91032287735366e-06 -1.33959783688857e-06 1.5600705410003e-05 9.09236801249067e-07 2.1747130068603e-06 7.26882171160645e-06 4.04104834722244e-05 0.000169320067406863 9.09236801249067e-07 0.000432265895243616 -4.55731922056929e-05 -9.98392945199219e-05 -1.57218027521225e-06 -1.19723620172365e-05 2.1747130068603e-06 -4.55731922056929e-05 2.06641428088677e-05 -2.36131866383119e-05 -5.72575688224978e-05 -0.000245147809015992 7.26882171160645e-06 -9.98392945199219e-05 -2.36131866383119e-05 0.00099463547027983 3137 3071 0 128 148 3137 3071 0 42 166 0 0 0 0 0 0 0 0 3643 0 0 0 0 0 3631 +997 998 0.999152189522147 -0.016922932027219 0.0375302084286934 0.313068267761051 0.0168598093221392 0.99985586744487 0.00199779020110575 -0.0213507983623578 -0.0375586075716359 -0.00136334429571279 0.999293496571258 0.0779771809488094 4.14562302937142e-05 1.69780624749305e-05 3.62265907417675e-06 -6.34014879388751e-05 1.05446597832567e-05 -1.87775470947645e-05 1.69780624749305e-05 2.66251081503957e-05 -6.73214773426086e-07 -2.4080801524687e-05 3.60790513516926e-06 -5.89092903811401e-06 3.62265907417675e-06 -6.73214773426086e-07 1.1700074822997e-05 -8.13063220631587e-06 4.06099034875373e-06 -8.44553301729117e-07 -6.34014879388751e-05 -2.4080801524687e-05 -8.13063220631587e-06 0.00194782706290738 -0.000255180461188282 -0.000193913770456412 1.05446597832567e-05 3.60790513516926e-06 4.06099034875373e-06 -0.000255180461188282 4.48873389762526e-05 2.38523186818841e-05 -1.87775470947645e-05 -5.89092903811401e-06 -8.44553301729117e-07 -0.000193913770456412 2.38523186818841e-05 0.000136133752667627 3481 3384 0 571 318 3481 3384 0 431 329 0 0 0 0 0 0 0 0 3146 0 0 0 0 0 3501 +999 1000 0.999209602678796 -0.012440078973728 -0.0377546599721163 0.00730974106572383 0.0141989418558876 0.99880888780349 0.0466818561641301 0.0196515345244116 0.0371289639588265 -0.047181035171802 0.998196067892206 -0.0236919255668055 2.24942452543763e-05 1.18448711395561e-05 9.53105824256506e-07 -1.2500860915933e-05 2.15189658664966e-06 -1.12085024397555e-05 1.18448711395561e-05 1.54854410196649e-05 -2.23706856847956e-06 -4.55905000591024e-07 5.50037746832204e-07 -9.92255891984838e-06 9.53105824256506e-07 -2.23706856847956e-06 1.2506585597936e-05 3.47558285505232e-06 1.63536415318507e-06 1.67638823887264e-06 -1.2500860915933e-05 -4.55905000591024e-07 3.47558285505232e-06 0.000360615844410985 -5.94788438198461e-05 -6.73510838840927e-06 2.15189658664966e-06 5.50037746832204e-07 1.63536415318507e-06 -5.94788438198461e-05 2.25400688758804e-05 1.55711763836845e-08 -1.12085024397555e-05 -9.92255891984838e-06 1.67638823887264e-06 -6.73510838840927e-06 1.55711763836845e-08 4.2585450299204e-05 3453 3405 0 0 76 3335 3334 0 0 79 0 0 0 0 0 12 0 0 2325 0 0 0 0 0 3758 +998 999 0.999694925098161 -0.0233388567476441 -0.00808421292978653 0.0370521654131833 0.0231756917957222 0.999536882663587 -0.019720737941259 0.0203340186040251 0.00854072846839636 0.0195273644117956 0.999772843198073 -0.0297174082156416 7.77779878915374e-05 0.000140158663034665 -3.78704096907626e-06 -5.73345573643429e-05 1.3284773103487e-05 -0.000147050560067889 0.000140158663034665 0.000750010630231501 -1.24270671064225e-05 -0.000415645764749226 8.35439259533602e-05 -0.000809029350467304 -3.78704096907626e-06 -1.24270671064225e-05 1.39317819840286e-05 6.97126917411808e-06 2.45298735899912e-06 1.27638993146278e-05 -5.73345573643429e-05 -0.000415645764749226 6.97126917411808e-06 0.000442635374926467 -6.93763127949292e-05 0.000508631181758555 1.3284773103487e-05 8.35439259533602e-05 2.45298735899912e-06 -6.93763127949292e-05 2.56099435164906e-05 -9.93003779410321e-05 -0.000147050560067889 -0.000809029350467304 1.27638993146278e-05 0.000508631181758555 -9.93003779410321e-05 0.000986162245255878 3058 2973 0 0 122 2951 2953 0 0 128 0 0 0 0 0 0 0 0 3066 0 0 0 0 0 3699 +1000 1001 0.999983381943929 -0.00141781892529344 -0.00558798939481972 -0.111313501686272 0.00143295827821806 0.999995311559409 0.00270619470348712 0.0556842490849708 0.00558412630179729 -0.0027141570874537 0.999980725256617 -0.0327797790313696 2.83199657885025e-05 1.31613827624537e-05 3.5796651730788e-06 2.39370188365731e-05 -4.0610865158257e-06 -1.45194935248697e-05 1.31613827624537e-05 2.13879075736069e-05 1.25461232872837e-06 -1.8922564877525e-05 2.96436418596838e-06 -6.51416112668274e-06 3.5796651730788e-06 1.25461232872837e-06 1.10199248259592e-05 -1.19297613675142e-05 5.03878633347341e-06 1.02326017373534e-06 2.39370188365731e-05 -1.8922564877525e-05 -1.19297613675142e-05 0.00122824550545373 -0.000201937646907354 -0.000156762663150407 -4.0610865158257e-06 2.96436418596838e-06 5.03878633347341e-06 -0.000201937646907354 4.52818890573769e-05 2.68767804048903e-05 -1.45194935248697e-05 -6.51416112668274e-06 1.02326017373534e-06 -0.000156762663150407 2.68767804048903e-05 0.0001007650046054 3242 3242 0 0 0 3137 3137 0 0 0 0 0 0 0 0 231 100 0 1635 0 57 50 0 0 3635 +1001 1002 0.999420963612735 -0.0190087965022926 0.0282206156369303 0.0119951364531109 0.0192106475512832 0.999791657245916 -0.00689877685715014 0.0398860356496513 -0.0280835986307542 0.00743691851500353 0.999577912786666 -0.0332382664314726 3.54064258085036e-05 4.31495886222007e-05 5.68636992792732e-06 5.18379168331975e-06 9.56772406881436e-07 -4.0483442180918e-05 4.31495886222007e-05 0.000241902755101935 9.09528203895269e-07 6.1838838815215e-05 -3.8201519162167e-07 -0.000232770479011565 5.68636992792732e-06 9.09528203895269e-07 1.20914216080835e-05 2.82412535230666e-06 3.51202248749469e-06 -9.30050493353263e-07 5.18379168331975e-06 6.1838838815215e-05 2.82412535230666e-06 0.000241763934695232 -3.99260039277032e-05 2.59915911271908e-05 9.56772406881436e-07 -3.8201519162167e-07 3.51202248749469e-06 -3.99260039277032e-05 2.15406180334367e-05 -2.05451627564125e-05 -4.0483442180918e-05 -0.000232770479011565 -9.30050493353263e-07 2.59915911271908e-05 -2.05451627564125e-05 0.000320261053870373 3040 2993 0 0 118 2912 2906 0 0 113 0 0 0 0 0 10 0 0 1100 0 0 0 0 0 3753 +1003 1004 0.999908281790825 0.0124629559940644 0.00530120118563422 -0.0648799869029328 -0.0124859959524185 0.999912647796614 0.00433551397646736 0.0553609129785619 -0.0052467047941297 -0.00440130710743637 0.999976550017324 0.0023939082127195 2.83880879237002e-05 9.13571253480958e-06 5.41896473662113e-06 3.36901619370584e-06 -2.07952274050962e-06 -1.04052178759241e-05 9.13571253480958e-06 1.93950722748755e-05 -1.5064142841649e-06 1.15709978738074e-07 1.18732071693962e-06 -2.29956369222139e-06 5.41896473662113e-06 -1.5064142841649e-06 1.39735800009339e-05 -6.94244371835223e-06 2.59239596440141e-06 -2.2202421634843e-07 3.36901619370584e-06 1.15709978738074e-07 -6.94244371835223e-06 0.000325404750938443 -4.29424531457627e-05 -4.77665289641933e-05 -2.07952274050962e-06 1.18732071693962e-06 2.59239596440141e-06 -4.29424531457627e-05 2.06465706661085e-05 7.39120501433633e-06 -1.04052178759241e-05 -2.29956369222139e-06 -2.2202421634843e-07 -4.77665289641933e-05 7.39120501433633e-06 7.66955316711765e-05 3312 3312 0 0 4 3203 3203 0 0 0 0 0 0 0 0 3 0 0 423 0 68 57 0 0 3694 +1005 1006 0.999782711343221 0.0164628260484887 -0.0127869252634818 0.130485281576704 -0.0167134721180396 0.999665268484902 -0.0197486919761304 0.010085384801103 0.0124575257959267 0.0199581147282444 0.99972320354563 0.0121736893021804 2.75043191064215e-05 1.81190459688267e-05 1.12285961076286e-06 -1.92576895877762e-06 1.701122341552e-07 2.88870210727298e-05 1.81190459688267e-05 4.49761612832051e-05 -1.26455149997596e-06 -1.44468420273547e-05 2.72860722364488e-06 0.000124525091652884 1.12285961076286e-06 -1.26455149997596e-06 1.04324767862817e-05 3.16511507293606e-06 3.51055105372916e-06 4.83294678109721e-06 -1.92576895877762e-06 -1.44468420273547e-05 3.16511507293606e-06 0.00021743070107377 -3.01705201319917e-05 -7.78799568665625e-05 1.701122341552e-07 2.72860722364488e-06 3.51055105372916e-06 -3.01705201319917e-05 1.54734872485324e-05 1.07900471013414e-05 2.88870210727298e-05 0.000124525091652884 4.83294678109721e-06 -7.78799568665625e-05 1.07900471013414e-05 0.000812445136438482 3117 3107 0 0 92 3117 3107 0 0 80 0 0 0 0 0 0 0 0 22 0 0 0 0 0 3821 +1004 1005 0.999396733196443 0.0287608196339243 0.0194675352898901 0.103038838812838 -0.028408531787239 0.999431838730389 -0.0181371181196948 0.0117361056993826 -0.0199781129732433 0.017573132503319 0.999645967338462 0.106049376707653 3.91782113180652e-05 1.3283884215693e-05 3.62999278726362e-06 5.21486796766858e-06 -1.93137292945567e-06 -5.86295020918673e-06 1.3283884215693e-05 2.30957481715828e-05 -2.34276474690404e-06 3.69175906666683e-06 -7.45219794945747e-08 -6.37792243295049e-06 3.62999278726362e-06 -2.34276474690404e-06 1.16060420657346e-05 7.64442688131342e-07 2.68595151596694e-06 4.04849180394168e-06 5.21486796766858e-06 3.69175906666683e-06 7.64442688131342e-07 0.000150078423699449 -1.82472966033141e-05 4.62829454914943e-05 -1.93137292945567e-06 -7.45219794945747e-08 2.68595151596694e-06 -1.82472966033141e-05 1.61230657045702e-05 -1.23248814978544e-05 -5.86295020918673e-06 -6.37792243295049e-06 4.04849180394168e-06 4.62829454914943e-05 -1.23248814978544e-05 0.000154021978594005 3174 3129 0 0 51 3170 3129 0 0 38 0 0 0 0 0 0 0 0 125 0 24 15 0 0 3862 +1007 1008 0.99987105327122 0.00461194962913437 0.0153820268794324 -0.178790680653196 -0.00476706644099444 0.999938004484359 0.0100629153521346 0.0505731090053014 -0.0153346636040181 -0.0101349449162494 0.999831051220003 -0.0522408081082734 5.03254427772581e-05 9.0081040616449e-05 5.73097750529256e-08 0.000275331648743465 -3.80088389552741e-05 5.72604329348474e-05 9.0081040616449e-05 0.000444905988489015 2.0703268526957e-06 0.00170849661493327 -0.000240204610707685 0.000524622831605618 5.73097750529256e-08 2.0703268526957e-06 1.13775678294364e-05 7.86720674778988e-06 4.34891530379354e-06 3.78726007710739e-06 0.000275331648743465 0.00170849661493327 7.86720674778988e-06 0.0113201336311589 -0.0015955882372039 0.00386751743685602 -3.80088389552741e-05 -0.000240204610707685 4.34891530379354e-06 -0.0015955882372039 0.000236956845679561 -0.000559805536943223 5.72604329348474e-05 0.000524622831605618 3.78726007710739e-06 0.00386751743685602 -0.000559805536943223 0.00173334775137431 2582 2582 0 0 0 2574 2574 0 0 0 0 0 0 0 0 0 0 0 0 0 128 119 0 0 3606 +1002 1003 0.999244226431119 -0.0154761779705058 0.0356575918914807 0.119372968635262 0.0154437565256811 0.999880036462049 0.00118451214754688 0.018332998326805 -0.0356716460014062 -0.000632929757109619 0.999363363882964 0.0138525734317354 3.57210379719213e-05 2.0420538600317e-05 5.11561828379885e-06 5.47556516868374e-06 3.78254961777878e-07 -7.49183878235855e-06 2.0420538600317e-05 2.94636420915892e-05 2.97722742642654e-06 5.27296554732672e-06 -7.33113301160079e-07 -3.72774899164928e-06 5.11561828379885e-06 2.97722742642654e-06 1.24581241438097e-05 2.62980116137715e-06 3.92017108908055e-06 -2.00441645442262e-06 5.47556516868374e-06 5.27296554732672e-06 2.62980116137715e-06 0.000151629066197047 -2.8284852045456e-05 3.18750550426803e-05 3.78254961777878e-07 -7.33113301160079e-07 3.92017108908055e-06 -2.8284852045456e-05 1.9636436080744e-05 -1.29387595215749e-05 -7.49183878235855e-06 -3.72774899164928e-06 -2.00441645442262e-06 3.18750550426803e-05 -1.29387595215749e-05 0.000116228870911899 3475 3330 0 4 182 3474 3330 0 0 174 0 0 0 0 0 0 0 0 726 0 0 0 0 0 3697 +1010 1011 0.999993678038543 -0.00340051956931565 -0.00103939867542736 0.354838196619415 0.00340876563264761 0.999961889169724 0.00803744517736106 -0.0341626175316506 0.00101202757346793 -0.00804093743142585 0.999967159023442 0.091106711095744 2.82630315600255e-05 1.63405679150442e-05 8.36045003495849e-06 1.25349960344011e-06 3.71949111438845e-07 -1.16687539794394e-05 1.63405679150442e-05 3.08496124855665e-05 2.69069429847629e-06 1.79667910280271e-05 -4.22652238575773e-06 1.05568635987748e-05 8.36045003495849e-06 2.69069429847629e-06 1.06130954319157e-05 9.08029409198566e-07 5.21402085658408e-06 -7.45094641853389e-06 1.25349960344011e-06 1.79667910280271e-05 9.08029409198566e-07 0.000919115997418501 -0.000131472401278732 0.000251640571330511 3.71949111438845e-07 -4.22652238575773e-06 5.21402085658408e-06 -0.000131472401278732 3.06387233209754e-05 -4.30760713621486e-05 -1.16687539794394e-05 1.05568635987748e-05 -7.45094641853389e-06 0.000251640571330511 -4.30760713621486e-05 0.000350928493240372 2518 2503 0 0 270 2518 2503 0 0 257 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3634 +1012 1013 0.99991027398195 3.91216677442816e-05 0.0133956132684296 -0.0221859607297719 -0.000237543214650113 0.999890280587926 0.0148111565726553 0.0224700686283693 -0.0133935640724711 -0.0148130096635914 0.999800573707649 -0.0273548692638709 2.85455252279636e-05 5.00378529238387e-06 6.22701141633424e-06 -3.26581137426437e-06 1.22490110365472e-06 -1.10122622823066e-05 5.00378529238387e-06 1.43363887128334e-05 -1.59394773109197e-06 -2.36639016241953e-06 -1.49684361107205e-06 -4.63289295949616e-06 6.22701141633424e-06 -1.59394773109197e-06 1.13244185493631e-05 -2.9615813116877e-06 4.39668671007712e-06 8.12156304990792e-07 -3.26581137426437e-06 -2.36639016241953e-06 -2.9615813116877e-06 0.000204901225707277 -1.7926208432011e-05 5.88606434754952e-07 1.22490110365472e-06 -1.49684361107205e-06 4.39668671007712e-06 -1.7926208432011e-05 1.21132258466109e-05 -5.21329838539513e-07 -1.10122622823066e-05 -4.63289295949616e-06 8.12156304990792e-07 5.88606434754952e-07 -5.21329838539513e-07 4.9046338619478e-05 2679 2666 0 0 44 2670 2665 0 0 33 0 0 0 0 0 0 0 0 0 0 41 26 0 0 3835 +1006 1007 0.999722947781405 0.0184379230412681 -0.0146311541985458 0.0135388669042284 -0.0182255058475931 0.999728448115721 0.0145210524663982 0.0257947158723869 0.0148949191289077 -0.0142503691901934 0.999787511605384 -0.106946232520828 4.42399973169281e-05 1.39180491585799e-05 -5.09875012587832e-06 -5.63456178572628e-05 1.04258196547753e-05 -5.00740754459871e-05 1.39180491585799e-05 3.83947869623062e-05 -4.21192436334688e-06 8.48992332449509e-05 -1.14188330440774e-05 2.09554789529968e-05 -5.09875012587832e-06 -4.21192436334688e-06 1.52977607257389e-05 2.19030328765103e-05 -5.68481355758816e-07 1.14576673206349e-05 -5.63456178572628e-05 8.48992332449509e-05 2.19030328765103e-05 0.0017167770227889 -0.000265060493836794 0.000574610658841248 1.04258196547753e-05 -1.14188330440774e-05 -5.68481355758816e-07 -0.000265060493836794 5.61698934812826e-05 -9.71646019246029e-05 -5.00740754459871e-05 2.09554789529968e-05 1.14576673206349e-05 0.000574610658841248 -9.71646019246029e-05 0.000333498331116556 2837 2835 0 0 23 2822 2822 0 0 7 0 0 0 0 0 0 0 0 1 0 53 44 0 0 3814 +1013 1014 0.999670551181358 0.0141871098893709 0.0213896005980919 -0.0694228225665281 -0.0144270173866058 0.999834269705616 0.0111037962681725 0.0262977265254185 -0.0212285249154423 -0.0114087262753308 0.999709553167663 0.005137096253685 2.95249345441871e-05 1.07588753768309e-05 4.92532968194061e-07 1.17645424806071e-05 9.88832943453833e-07 -4.37914606408601e-07 1.07588753768309e-05 2.25554376679995e-05 -2.16810718704078e-06 -1.25961518906342e-05 1.35374036758252e-07 6.08130877854135e-06 4.92532968194061e-07 -2.16810718704078e-06 1.40060204564669e-05 -1.34704343080796e-05 4.07500306840149e-06 3.44114964932505e-06 1.17645424806071e-05 -1.25961518906342e-05 -1.34704343080796e-05 0.000385860371274743 -2.33708645931945e-05 -7.8014625313084e-05 9.88832943453833e-07 1.35374036758252e-07 4.07500306840149e-06 -2.33708645931945e-05 1.48669185152709e-05 2.70256430044568e-06 -4.37914606408601e-07 6.08130877854135e-06 3.44114964932505e-06 -7.8014625313084e-05 2.70256430044568e-06 0.000123658407286683 2435 2435 0 0 0 2419 2419 0 0 0 0 0 0 0 0 0 0 0 0 0 99 86 0 0 3757 +1015 1016 0.998778317191601 0.0379948188025854 0.0315953612429518 0.197543196659458 -0.037107217488598 0.998912748771428 -0.0282201125469701 -0.00299779316367821 -0.0326332272104339 0.0270132205793474 0.999102276243911 -0.022907877587056 3.50405495331283e-05 4.22825560814641e-06 4.54789444277585e-06 7.97556832545264e-06 5.1439830717108e-06 -1.92378296162646e-05 4.22825560814641e-06 4.62825303354028e-05 -1.85201002010713e-06 -2.53655790312105e-05 -1.82808666832561e-06 5.09922570297483e-05 4.54789444277585e-06 -1.85201002010713e-06 1.01528118607916e-05 4.42508094750189e-08 5.01409198149954e-06 3.46618782348384e-06 7.97556832545264e-06 -2.53655790312105e-05 4.42508094750189e-08 0.000241882064270903 7.2990916380036e-07 -0.000112752718903023 5.1439830717108e-06 -1.82808666832561e-06 5.01409198149954e-06 7.2990916380036e-07 1.07867921971478e-05 -2.32596076313522e-05 -1.92378296162646e-05 5.09922570297483e-05 3.46618782348384e-06 -0.000112752718903023 -2.32596076313522e-05 0.000746980842004479 2268 2259 0 0 88 2268 2259 0 0 73 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3868 +1009 1010 0.999999653151778 9.31314922309465e-05 -0.000827661071392059 0.187922904013305 -7.74082868438578e-05 0.999819918972376 0.0189769237240713 -0.00904971100669562 0.000829279374560174 -0.0189768530741334 0.999819579395764 0.0610918267352353 2.33001678706341e-05 1.03926665034521e-05 -7.80580288519265e-07 -3.67124634470358e-07 1.43722735511581e-06 5.04698914249794e-07 1.03926665034521e-05 1.85900781739823e-05 -3.25925881968047e-06 -1.81415012231526e-05 8.74391280613659e-07 1.23955993858018e-05 -7.80580288519265e-07 -3.25925881968047e-06 1.03088100238105e-05 1.92653255876427e-06 4.24382398902169e-06 1.45614248658561e-06 -3.67124634470358e-07 -1.81415012231526e-05 1.92653255876427e-06 0.000218557777660076 -2.27038974735193e-05 -7.18267710547298e-05 1.43722735511581e-06 8.74391280613659e-07 4.24382398902169e-06 -2.27038974735193e-05 1.37646363230254e-05 8.73734809898208e-06 5.04698914249794e-07 1.23955993858018e-05 1.45614248658561e-06 -7.18267710547298e-05 8.73734809898208e-06 0.000194413616656985 2701 2688 0 0 172 2701 2688 0 0 157 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3739 +1014 1015 0.998867775959629 0.0438736994292179 0.0183919723754651 0.1208626897204 -0.0440850576893593 0.998964456270523 0.0112482352688395 -0.000385266422912925 -0.0178794249905048 -0.0120463109096499 0.99976757926804 -0.0534082327206765 3.48999872518827e-05 1.94741790279699e-05 2.84188737182273e-06 -4.76318438387554e-06 1.36092021361131e-06 -2.66436433033438e-05 1.94741790279699e-05 0.000113315244648301 5.44115079526884e-06 -0.000208033665312827 4.23290335507969e-06 0.000154578425703774 2.84188737182273e-06 5.44115079526884e-06 1.01878155666529e-05 -9.23126244217357e-06 5.87543987610123e-06 6.98589805279605e-06 -4.76318438387554e-06 -0.000208033665312827 -9.23126244217357e-06 0.00274230762672715 -0.00012861138675903 -0.0011622812194411 1.36092021361131e-06 4.23290335507969e-06 5.87543987610123e-06 -0.00012861138675903 1.87939563862744e-05 1.05378985689948e-05 -2.66436433033438e-05 0.000154578425703774 6.98589805279605e-06 -0.0011622812194411 1.05378985689948e-05 0.00122852643840064 2177 2177 0 0 17 2163 2163 0 0 3 0 0 0 0 0 0 0 0 0 0 64 53 0 0 3877 +1018 1019 0.999309931568106 -0.00144292825503888 0.0371157463537728 2.49880682331421 0.00130403590911535 0.999992058045491 0.00376607704276158 0.0398496902500144 -0.0371208857611793 -0.00371507792584335 0.999303876724348 -0.0966135163229074 3.66071844532528e-05 2.10702663777684e-06 5.75912193092077e-06 9.02788769720282e-05 -3.2289054589807e-07 -6.1593738340424e-06 2.10702663777684e-06 7.47983681890509e-05 -8.03104244975419e-09 -0.000581547024250927 -8.37415966906175e-06 -6.61918936510527e-06 5.75912193092077e-06 -8.03104244975419e-09 1.07984475536879e-05 -5.17850215800965e-05 3.44780905448766e-06 5.00142444405247e-06 9.02788769720282e-05 -0.000581547024250927 -5.17850215800965e-05 0.019180064306174 0.000394693962515864 -0.00137764276319805 -3.2289054589807e-07 -8.37415966906175e-06 3.44780905448766e-06 0.000394693962515864 2.21560790220964e-05 -3.2162955280658e-05 -6.1593738340424e-06 -6.61918936510527e-06 5.00142444405247e-06 -0.00137764276319805 -3.2162955280658e-05 0.000206966932667553 2243 2238 0 0 3135 2243 2238 0 0 3122 0 0 0 0 0 0 0 0 0 0 0 0 0 0 824 +1011 1012 0.99996776809464 0.00697077699121719 -0.0039838473820861 -0.17979335100984 -0.00703832442893018 0.999827285909462 -0.0172005912733011 0.0454021527607549 0.0038632578296254 0.0172280764758215 0.999844122160992 0.0191563312224599 6.06318376273957e-05 0.000242004632005553 9.07734058213575e-06 0.00070426792955118 -9.82190530152185e-05 0.000137546188283498 0.000242004632005553 0.00149497222036772 4.53710288806904e-05 0.00457617933359616 -0.000657431143516862 0.000944137115404371 9.07734058213575e-06 4.53710288806904e-05 1.09985177943795e-05 0.000156405323478848 -1.76742630113374e-05 3.62418173051177e-05 0.00070426792955118 0.00457617933359616 0.000156405323478848 0.0189417100327449 -0.00276442811327777 0.00549448621637887 -9.82190530152185e-05 -0.000657431143516862 -1.76742630113374e-05 -0.00276442811327777 0.000414761317018867 -0.000822469833624053 0.000137546188283498 0.000944137115404371 3.62418173051177e-05 0.00549448621637887 -0.000822469833624053 0.00219233752643552 2274 2274 0 0 0 2262 2262 0 0 0 0 0 0 0 0 0 0 0 0 0 137 124 0 0 3664 +1020 1021 0.999832641094651 -0.00497060619499578 -0.0176063305588689 0.138548041674626 0.00519212645736231 0.999907657825079 0.0125585686133522 -0.00640071802788596 0.0175422810530629 -0.0126478811197681 0.99976612238995 0.0430351127320932 3.38433773064593e-05 7.42518441357969e-06 3.7882630678997e-06 -1.62116862415926e-06 -1.37035103928512e-06 -8.13086407883916e-06 7.42518441357969e-06 2.68808512435314e-05 1.37987599316559e-06 1.93170574410307e-05 -5.79319047249585e-07 1.87089398545074e-05 3.7882630678997e-06 1.37987599316559e-06 9.86033885376818e-06 -2.55048936089982e-06 5.12694210951347e-06 2.44280435255723e-06 -1.62116862415926e-06 1.93170574410307e-05 -2.55048936089982e-06 0.000203973471058942 -3.00249369878122e-06 8.45193844095318e-05 -1.37035103928512e-06 -5.79319047249585e-07 5.12694210951347e-06 -3.00249369878122e-06 9.31671095342787e-06 -1.07606274746995e-05 -8.13086407883916e-06 1.87089398545074e-05 2.44280435255723e-06 8.45193844095318e-05 -1.07606274746995e-05 0.000298254069024083 2708 2705 0 0 151 2708 2705 0 0 146 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3765 +1021 1022 0.999865084399964 -0.0114999946740268 0.0117287305514954 0.152849169822908 0.0113922063230629 0.99989263676339 0.00921588744765665 -0.00324444263721943 -0.0118334539735865 -0.00908102796232154 0.999888745960371 0.0314954644163551 3.16027921117702e-05 6.97027843470435e-06 9.54721854237872e-06 1.44582010406068e-05 2.02428524714203e-06 2.42274653477614e-05 6.97027843470435e-06 4.94220767610863e-05 2.72243449485806e-07 3.04053151367895e-05 -2.98897862151254e-06 4.01241983853549e-05 9.54721854237872e-06 2.72243449485806e-07 1.06728900530596e-05 3.35491731801781e-08 5.70126451003133e-06 2.65939434592459e-06 1.44582010406068e-05 3.04053151367895e-05 3.35491731801781e-08 0.000291912328165892 -1.17285102021363e-05 0.00020840878013812 2.02428524714203e-06 -2.98897862151254e-06 5.70126451003133e-06 -1.17285102021363e-05 1.03106988312555e-05 -2.52754652282194e-05 2.42274653477614e-05 4.01241983853549e-05 2.65939434592459e-06 0.00020840878013812 -2.52754652282194e-05 0.000602517535219192 2465 2465 0 0 173 2465 2465 0 0 168 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3734 +1019 1020 0.99962474617346 -0.0122216560459455 0.0245152597608265 -0.153444631859056 0.0124995887791477 0.999858969638618 -0.0112161095551958 -0.00329200376548279 -0.0243747229317258 0.0115183313329907 0.999636534409035 -0.000783946256414992 3.16555481505542e-05 2.62881130345151e-07 1.95281252924435e-06 1.34615797140288e-05 -1.70484135716858e-07 -1.07382578639613e-05 2.62881130345151e-07 3.63388469344068e-05 1.55253263103302e-07 -0.000116395584217173 -2.99083202749137e-06 3.28205891605196e-05 1.95281252924435e-06 1.55253263103302e-07 9.87286121347919e-06 -8.55259615788416e-06 5.51813191331004e-06 2.62231703272427e-06 1.34615797140288e-05 -0.000116395584217173 -8.55259615788416e-06 0.00150783413717729 2.18309374298396e-05 -0.000497829372594568 -1.70484135716858e-07 -2.99083202749137e-06 5.51813191331004e-06 2.18309374298396e-05 9.6282541509118e-06 -6.84076224860683e-06 -1.07382578639613e-05 3.28205891605196e-05 2.62231703272427e-06 -0.000497829372594568 -6.84076224860683e-06 0.00031600810567573 2498 2498 0 0 0 2493 2493 0 0 0 0 0 0 0 0 0 0 0 0 0 99 96 0 0 3789 +1022 1023 0.999293555505437 -0.0128780970459601 -0.0353064376817879 0.118136527759226 0.0124234397076735 0.999837445873413 -0.0130667507498846 0.00335795464952201 0.03546897335888 0.0126188924159231 0.999291106476517 -0.0637403719516028 4.27001835524299e-05 5.88036493221714e-06 -7.42699527736738e-06 -1.80868076178209e-05 1.64305200862958e-06 -1.88130640089801e-05 5.88036493221714e-06 3.60193569869743e-05 -5.23548755656747e-08 1.68054767440317e-05 -9.87830689639837e-07 1.74709454621252e-05 -7.42699527736738e-06 -5.23548755656747e-08 1.04311455849113e-05 2.68718301498296e-06 5.81223987015383e-06 -9.78830372907979e-07 -1.80868076178209e-05 1.68054767440317e-05 2.68718301498296e-06 0.000189544318586962 -7.2581597072277e-06 0.000114977926999269 1.64305200862958e-06 -9.87830689639837e-07 5.81223987015383e-06 -7.2581597072277e-06 1.1045789179322e-05 -1.40650214172464e-05 -1.88130640089801e-05 1.74709454621252e-05 -9.78830372907979e-07 0.000114977926999269 -1.40650214172464e-05 0.000564722721711204 2330 2322 0 0 150 2330 2322 0 0 150 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3760 +1023 1024 0.99994668404295 -0.00707209821701598 0.00752426064919571 0.0465256736233974 0.00698834601169694 0.999913977029743 0.0110996198396169 -0.000309784116269384 -0.00760211099162298 -0.0110464459158634 0.999910087928459 -0.0706585493039943 2.45704349725537e-05 8.32212685976953e-06 2.48250109383355e-06 1.74903304313723e-05 2.13757833832113e-06 -1.0672543108678e-05 8.32212685976953e-06 3.27461158566823e-05 5.65312693011605e-06 8.25146776973951e-05 -2.7130343045668e-06 2.12660433021194e-05 2.48250109383355e-06 5.65312693011605e-06 1.02713463786787e-05 5.02474465688625e-06 4.83596590949282e-06 2.62345302965923e-07 1.74903304313723e-05 8.25146776973951e-05 5.02474465688625e-06 0.00127593182398978 -4.25235806620077e-05 0.000249722195024892 2.13757833832113e-06 -2.7130343045668e-06 4.83596590949282e-06 -4.25235806620077e-05 1.17779687549643e-05 -1.6291784920133e-05 -1.0672543108678e-05 2.12660433021194e-05 2.62345302965923e-07 0.000249722195024892 -1.6291784920133e-05 0.00018525998906954 2648 2640 0 0 83 2648 2640 0 0 73 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3832 +1017 1018 0.999550104106129 0.0179307391136805 -0.0240432521981435 0.0736900980007826 -0.0175424938602289 0.999713852809041 0.0162626384964901 -0.00021830490930597 0.0243279734172461 -0.0158335433981411 0.999578635532427 -0.0955618709494279 6.44661764391838e-05 1.07820255042509e-05 -1.19289861456556e-05 -1.92398749776794e-05 4.07566684493303e-06 -3.44421564695556e-05 1.07820255042509e-05 4.52981433760006e-05 -3.48878648684678e-06 2.58204717298055e-05 -3.08299877442862e-06 5.86484605635317e-05 -1.19289861456556e-05 -3.48878648684678e-06 1.25202338288029e-05 5.07280565248586e-06 5.81025004894206e-06 1.93130848345716e-05 -1.92398749776794e-05 2.58204717298055e-05 5.07280565248586e-06 0.000428193521312454 -9.43620940378411e-06 0.000211857952426816 4.07566684493303e-06 -3.08299877442862e-06 5.81025004894206e-06 -9.43620940378411e-06 1.3212987452754e-05 -4.02800556047438e-05 -3.44421564695556e-05 5.86484605635317e-05 1.93130848345716e-05 0.000211857952426816 -4.02800556047438e-05 0.00108012002684397 2346 2340 0 0 36 2345 2340 0 0 29 0 0 0 0 0 0 0 0 0 0 20 14 0 0 3903 +1016 1017 0.999519662583024 0.0306610176109665 -0.00451066613468561 0.186675191867583 -0.0307341414705555 0.999380456914167 -0.0171497780189527 -0.00316600644510657 0.00398204193680609 0.0172801717899873 0.999842757139803 0.057332889185063 3.6545296255655e-05 1.90358283834632e-05 8.35068171398127e-06 0.000103052574436595 2.0858580276828e-06 7.07244557707841e-05 1.90358283834632e-05 7.72550961079768e-05 2.55631388066228e-06 0.000243081084483188 -5.61532786518551e-06 0.000266860034183205 8.35068171398127e-06 2.55631388066228e-06 1.00460006731735e-05 1.49735854452326e-05 5.10008087960117e-06 1.3608407393245e-05 0.000103052574436595 0.000243081084483188 1.49735854452326e-05 0.00218091760793003 -3.94637451376543e-05 0.00148190930905736 2.0858580276828e-06 -5.61532786518551e-06 5.10008087960117e-06 -3.94637451376543e-05 1.02597866699067e-05 -3.41304003722882e-05 7.07244557707841e-05 0.000266860034183205 1.3608407393245e-05 0.00148190930905736 -3.41304003722882e-05 0.00167192394750633 2605 2597 0 0 91 2605 2597 0 0 82 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3852 +1008 1009 0.999308846215523 -0.00778612115645348 -0.0363484001399855 0.103734365823504 0.00803373039181472 0.999945476790385 0.00667102858941603 0.0131649900395449 0.0362944768717101 -0.00695843112965854 0.999316912288 -0.0650545707527257 4.62238290782885e-05 1.76350461765665e-05 -9.18388250809991e-06 -1.51885180972241e-05 1.31246716059993e-06 1.17423101185507e-05 1.76350461765665e-05 3.45587785863653e-05 -2.40990111228166e-06 -6.92941286474471e-06 8.82624574457978e-07 -1.98886956247554e-06 -9.18388250809991e-06 -2.40990111228166e-06 1.12082243120229e-05 1.20761613493215e-05 4.51377301388108e-06 -2.47425312759026e-06 -1.51885180972241e-05 -6.92941286474471e-06 1.20761613493215e-05 0.000643678259507486 -8.49667583296251e-05 -9.9370173322567e-05 1.31246716059993e-06 8.82624574457978e-07 4.51377301388108e-06 -8.49667583296251e-05 2.43430151532131e-05 5.76957868345862e-06 1.17423101185507e-05 -1.98886956247554e-06 -2.47425312759026e-06 -9.9370173322567e-05 5.76957868345862e-06 0.000485766809619352 2524 2510 0 0 134 2524 2510 0 0 129 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3768 +1024 1025 0.999771253065042 0.0213871635255483 -0.000175445395013995 -0.00691325284670036 -0.0213832098712035 0.999690643725316 0.012703353245023 0.000548228693066298 0.000447079813054293 -0.012696695806202 0.999919293760874 -0.13008425543732 2.85800203257392e-05 7.84433141717216e-06 -2.00276183428316e-06 2.82046230261014e-06 -3.99064312101817e-07 2.23989161122282e-06 7.84433141717216e-06 2.96367616072889e-05 4.88849417860905e-07 3.82705425854289e-05 -2.59615935787715e-06 3.95418506641608e-05 -2.00276183428316e-06 4.88849417860905e-07 9.76721177600752e-06 -1.84439372288251e-06 5.30283585029961e-06 3.70049974401655e-06 2.82046230261014e-06 3.82705425854289e-05 -1.84439372288251e-06 0.000786822491932053 -2.23330245080955e-05 0.000413738345660453 -3.99064312101817e-07 -2.59615935787715e-06 5.30283585029961e-06 -2.23330245080955e-05 1.08559445897019e-05 -2.28201410008448e-05 2.23989161122282e-06 3.95418506641608e-05 3.70049974401655e-06 0.000413738345660453 -2.28201410008448e-05 0.000465187973783037 2644 2644 0 0 0 2634 2634 0 0 0 0 0 0 0 0 0 0 0 0 0 88 81 0 0 3801 +1025 1026 0.999226438456917 0.0380135481413056 0.0100744650683072 0.0918265790826491 -0.0379800017738238 0.99927236801588 -0.00350056926731021 -0.00359729472162748 -0.0102002036236655 0.00311523316038149 0.999943123966754 -0.0183078344033752 1.83806103883247e-05 6.49969253367191e-06 -3.82124956672931e-06 -8.42042378756217e-07 -2.68452094684086e-06 -8.82519337189111e-06 6.49969253367191e-06 1.4228021452451e-05 -1.03710727718364e-06 7.6680930165415e-06 -8.34644945928188e-07 -5.34856533418646e-06 -3.82124956672931e-06 -1.03710727718364e-06 8.84700646311264e-06 -6.77335899487435e-07 4.84732266088588e-06 2.57615486259703e-06 -8.42042378756217e-07 7.6680930165415e-06 -6.77335899487435e-07 0.000184672906238275 2.25318079796287e-06 3.12472986608766e-05 -2.68452094684086e-06 -8.34644945928188e-07 4.84732266088588e-06 2.25318079796287e-06 9.26045366834906e-06 -1.92401141328604e-06 -8.82519337189111e-06 -5.34856533418646e-06 2.57615486259703e-06 3.12472986608766e-05 -1.92401141328604e-06 7.84172956210799e-05 2847 2847 0 0 5 2839 2839 0 0 0 0 0 0 0 0 0 0 0 0 0 57 53 0 0 3881 +1026 1027 0.99913169152702 0.0295798463823103 -0.0293410237441362 0.133852641079733 -0.0301305205343801 0.999374628552888 -0.0185068510856053 -0.00745737923082017 0.028775244893525 0.0193748417484219 0.99939811926406 0.0699614995668437 2.3841096899846e-05 2.47255941346046e-06 -3.90157960749489e-07 7.04174367208026e-06 -1.99103327655774e-07 -8.60491359229403e-06 2.47255941346046e-06 4.80720323882423e-05 2.49809946213959e-06 4.77529284325307e-05 7.32498262949551e-07 0.000148593334179998 -3.90157960749489e-07 2.49809946213959e-06 8.11948062137113e-06 3.612429725649e-06 5.51658862965368e-06 -3.94040909558232e-08 7.04174367208026e-06 4.77529284325307e-05 3.612429725649e-06 0.000557175817401189 2.74859368449506e-05 0.000199383759649063 -1.99103327655774e-07 7.32498262949551e-07 5.51658862965368e-06 2.74859368449506e-05 1.0330377141172e-05 -8.40641069451441e-06 -8.60491359229403e-06 0.000148593334179998 -3.94040909558232e-08 0.000199383759649063 -8.40641069451441e-06 0.0010676789244421 2916 2916 0 0 47 2916 2916 0 0 43 0 0 0 0 0 0 0 0 0 0 6 6 0 0 3894 +1028 1029 0.999504543534033 0.015614784994897 0.0273284822920672 0.173195615549183 -0.0161586167358314 0.999673506627789 0.0197934143513672 -0.00734582697145642 -0.0270104898143147 -0.0202251980475727 0.999430525251219 0.0544695340891242 2.80740871405058e-05 -6.14658605741075e-06 3.48027715576975e-06 -1.35780805681733e-06 2.92984381115355e-06 1.44576091733719e-05 -6.14658605741075e-06 6.1542206410204e-05 3.92613848851902e-06 1.9113101962466e-05 -1.82098428024587e-06 0.000129295704661325 3.48027715576975e-06 3.92613848851902e-06 9.348950541903e-06 6.01880779685542e-07 5.39619014140823e-06 3.8763127972582e-06 -1.35780805681733e-06 1.9113101962466e-05 6.01880779685542e-07 0.000478883560022634 3.35309713168574e-05 0.000112640934510375 2.92984381115355e-06 -1.82098428024587e-06 5.39619014140823e-06 3.35309713168574e-05 1.2632698820852e-05 -1.29757644432898e-05 1.44576091733719e-05 0.000129295704661325 3.8763127972582e-06 0.000112640934510375 -1.29757644432898e-05 0.000798076032220391 2947 2951 0 0 112 2947 2951 0 0 121 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3808 +1032 1033 0.999922362431772 -0.0117521167872159 -0.00414208400255603 0.180893396269977 0.0117707020997768 0.999920635354709 0.00449149907202896 -0.00509894979966185 0.00408897064588424 -0.00453990559982964 0.999981334613902 0.0790638123374913 2.59381703637735e-05 1.14093752323411e-06 3.69087524857929e-06 2.82386337431845e-06 3.40603831793401e-07 1.78724725476687e-05 1.14093752323411e-06 2.43387682906092e-05 5.54152546596977e-07 4.07841203594941e-06 -1.01449798578432e-07 2.71884454346458e-05 3.69087524857929e-06 5.54152546596977e-07 8.29128721078991e-06 -1.92537699955648e-06 4.78621202194693e-06 -1.45018877707892e-06 2.82386337431845e-06 4.07841203594941e-06 -1.92537699955648e-06 0.000174186676206486 1.39149522300487e-06 6.18431017027299e-05 3.40603831793401e-07 -1.01449798578432e-07 4.78621202194693e-06 1.39149522300487e-06 8.88379015431471e-06 -2.82046317711437e-06 1.78724725476687e-05 2.71884454346458e-05 -1.45018877707892e-06 6.18431017027299e-05 -2.82046317711437e-06 0.000265308828646663 3155 3158 0 0 195 3155 3158 0 0 197 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3700 +1030 1031 0.9719454165829 -0.0125837318378542 -0.234869659335826 0.0561850707978086 0.00612648934448119 0.999583459962388 -0.0282023527020899 -0.0149724649945897 0.235126717562692 0.0259722209803878 0.971617656501538 0.0613819234514 3.02750318525453e-05 -5.53568941154187e-06 -1.44088776746401e-05 -1.08154886088582e-05 -6.80871282274319e-06 6.091552313296e-07 -5.53568941154187e-06 5.35091580211716e-05 -1.69624933456448e-06 5.12671946351958e-05 -1.12188320803451e-06 1.34972775280995e-05 -1.44088776746401e-05 -1.69624933456448e-06 1.52060107567295e-05 1.45704699932485e-06 8.11400133056144e-06 4.40969780260569e-06 -1.08154886088582e-05 5.12671946351958e-05 1.45704699932485e-06 0.00154361637762134 9.28188301911971e-05 6.6117229426207e-05 -6.80871282274319e-06 -1.12188320803451e-06 8.11400133056144e-06 9.28188301911971e-05 1.94236596322552e-05 -1.31775584452084e-05 6.091552313296e-07 1.34972775280995e-05 4.40969780260569e-06 6.6117229426207e-05 -1.31775584452084e-05 0.000516957317691075 2021 2022 0 0 37 2027 2028 0 0 43 0 0 0 0 0 0 0 0 0 0 22 22 0 0 3729 +1027 1028 0.999054255842533 0.0143692253418949 -0.0410380219552037 0.0808900498890455 -0.0143129244667761 0.999896177901121 0.00166541644599207 -0.00994591319655201 0.041057692045831 -0.0010764672796078 0.999156197569762 -0.0996234704090652 2.76390360718103e-05 2.71103657612214e-07 1.85159420104903e-06 -1.1570724415454e-06 2.04053790444482e-06 5.21072558352021e-06 2.71103657612214e-07 1.93188689731712e-05 3.67360240647614e-06 -7.09157724389451e-06 1.41939527166998e-06 -4.00073784091227e-07 1.85159420104903e-06 3.67360240647614e-06 9.18920693677426e-06 -2.2173917373069e-06 5.40911591118805e-06 -4.21798076252455e-06 -1.1570724415454e-06 -7.09157724389451e-06 -2.2173917373069e-06 0.000338344772026168 2.57613277114048e-05 -4.72555917993122e-05 2.04053790444482e-06 1.41939527166998e-06 5.40911591118805e-06 2.57613277114048e-05 1.13907855944543e-05 -9.33929326271959e-06 5.21072558352021e-06 -4.00073784091227e-07 -4.21798076252455e-06 -4.72555917993122e-05 -9.33929326271959e-06 0.000160240602818692 2948 2952 0 0 41 2948 2952 0 0 41 0 0 0 0 0 0 0 0 0 0 2 7 0 0 3795 +1029 1030 0.999985214894558 0.0036834554967469 0.00400026847689443 -0.225984188690354 -0.00356004516210984 0.999530518643536 -0.0304313716192315 -0.0206468605632112 -0.00411048302848808 0.0304166805517551 0.999528853747347 -0.116062044257777 0.0126978291187605 -0.0011030572694098 0.000147574994351816 0.00077612326222453 0.00188273115059648 -0.00209395333234665 -0.0011030572694098 0.000167058077937621 -9.91057525320866e-06 -0.000146604203341899 -0.000183769036762143 0.00028203333734101 0.000147574994351816 -9.91057525320866e-06 1.72616394856493e-05 -8.80288023728012e-06 2.89391742275974e-05 -1.82352081732037e-05 0.00077612326222453 -0.000146604203341899 -8.80288023728012e-06 0.000683702684402288 0.000187805489241263 -0.000530229765860603 0.00188273115059648 -0.000183769036762143 2.89391742275974e-05 0.000187805489241263 0.000305472224876903 -0.000384287200502309 -0.00209395333234665 0.00028203333734101 -1.82352081732037e-05 -0.000530229765860603 -0.000384287200502309 0.00102408957353729 2805 2805 0 0 0 2808 2808 0 0 0 0 0 0 0 0 0 0 0 0 0 208 213 0 0 3742 +1037 1038 0.999320542944573 0.0330453080995372 0.0163236044294685 0.1904172025137 -0.0323394343807497 0.998604045997529 -0.0417626663576135 -0.00913840670715616 -0.0176808776053759 0.0412063942849993 0.998994204005775 0.0566900888551734 3.93413545751647e-05 -1.12002097327081e-06 8.30289710219178e-06 -2.40310249347116e-06 4.06732322203529e-06 2.45000471384154e-05 -1.12002097327081e-06 5.06493388938831e-05 -1.20819883102133e-06 2.02169745549496e-05 3.14387526602879e-06 2.90777075499111e-05 8.30289710219178e-06 -1.20819883102133e-06 1.00300646912685e-05 -4.51890346195571e-06 5.98269557621611e-06 6.61720882992762e-06 -2.40310249347116e-06 2.02169745549496e-05 -4.51890346195571e-06 0.000133841223578115 8.60413115630898e-06 0.000128611458646596 4.06732322203529e-06 3.14387526602879e-06 5.98269557621611e-06 8.60413115630898e-06 1.11826346657437e-05 6.46008771590201e-06 2.45000471384154e-05 2.90777075499111e-05 6.61720882992762e-06 0.000128611458646596 6.46008771590201e-06 0.000784670183946664 3300 3196 0 133 85 3300 3196 0 133 100 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3814 +1034 1035 0.998312346312155 0.00915144881969232 0.0573472770514869 0.190746632339104 -0.00929177073001567 0.999954452725867 0.00218070410945691 -0.00789644424677821 -0.0573247084372897 -0.00270988158647759 0.998351909070327 0.121056185486808 3.76612947298304e-05 1.02572570632291e-06 3.22991481493636e-06 -4.12859372555686e-06 1.06285547486275e-06 4.88057874091908e-06 1.02572570632291e-06 3.5082921280242e-05 5.89886969757085e-07 9.04732254815465e-06 -1.72633754517927e-06 6.69401008452605e-05 3.22991481493636e-06 5.89886969757085e-07 9.24328447081376e-06 3.6706816765193e-07 5.2039738519878e-06 6.03919589878799e-06 -4.12859372555686e-06 9.04732254815465e-06 3.6706816765193e-07 0.000172041596255976 3.66852322838724e-07 0.000111716199318175 1.06285547486275e-06 -1.72633754517927e-06 5.2039738519878e-06 3.66852322838724e-07 1.04216283642104e-05 -1.90416358817965e-05 4.88057874091908e-06 6.69401008452605e-05 6.03919589878799e-06 0.000111716199318175 -1.90416358817965e-05 0.000576154180644744 3138 3141 0 0 143 3138 3141 0 0 150 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3655 +1041 1042 0.988833895781976 0.00324707493772643 0.148986519715672 0.0861055450904295 -0.00688355849136429 0.999690679921031 0.023898976997407 -0.0273739813756129 -0.148862833424383 -0.0246576759524374 0.988550381033505 -0.116140703853023 4.52354848855146e-05 -1.18699731403734e-05 1.46561694705214e-05 -8.92865342242785e-06 4.7476099749e-06 5.34835413793804e-06 -1.18699731403734e-05 5.65423144538683e-05 7.26470607414126e-07 -1.89982266982433e-05 -4.62363492434733e-06 -1.05020468795956e-05 1.46561694705214e-05 7.26470607414126e-07 1.49549027510834e-05 -8.43507823077533e-06 5.99382085949835e-06 8.41509840154899e-07 -8.92865342242785e-06 -1.89982266982433e-05 -8.43507823077533e-06 0.00028229333131723 5.99007049357615e-05 -0.000233379589587538 4.7476099749e-06 -4.62363492434733e-06 5.99382085949835e-06 5.99007049357615e-05 2.74214009891928e-05 -6.38942653502088e-05 5.34835413793804e-06 -1.05020468795956e-05 8.41509840154899e-07 -0.000233379589587538 -6.38942653502088e-05 0.000512027648498009 2294 2283 0 114 27 2294 2287 0 63 52 0 0 0 0 0 0 0 0 1121 0 0 0 0 0 3731 +1038 1039 0.998780183668948 0.0340072875361208 -0.0358001271598007 0.113916317861438 -0.0334261320599557 0.999301511671573 0.0167087541851522 -0.0263107448608095 0.0363433405967682 -0.0154917127957189 0.999219279452174 -0.13790905773493 4.06233007319744e-05 -1.32078483218508e-05 -2.34313919798013e-06 2.61505829346655e-06 -9.19678873603032e-07 3.03594030500168e-05 -1.32078483218508e-05 5.80049612704308e-05 3.03215274807857e-06 6.79928090809511e-06 -6.48587556286435e-07 9.77767993072606e-06 -2.34313919798013e-06 3.03215274807857e-06 1.1389462488976e-05 -3.98071581715907e-06 6.30319782210818e-06 -1.70437088481445e-06 2.61505829346655e-06 6.79928090809511e-06 -3.98071581715907e-06 9.90208185648915e-05 6.69171500612313e-06 -1.79721902131855e-05 -9.19678873603032e-07 -6.48587556286435e-07 6.30319782210818e-06 6.69171500612313e-06 1.22972410904907e-05 -1.66476794353817e-05 3.03594030500168e-05 9.77767993072606e-06 -1.70437088481445e-06 -1.79721902131855e-05 -1.66476794353817e-05 0.00049746762779699 3310 3217 0 247 3 3311 3226 0 149 11 0 0 0 0 0 0 0 0 32 0 0 8 0 0 3837 +1039 1040 0.999193445309233 0.0366968268962699 0.0163034274559036 0.0808947251764713 -0.0367081121374321 0.999325952705553 0.000393385871166069 -0.0312605544974026 -0.0162780021615191 -0.000991536627222197 0.99986701290759 -0.0715015295140917 5.0371231353947e-05 -8.00413803410631e-05 -4.07131891967535e-06 -5.36808122642628e-05 -1.66412067529764e-05 6.34605951288691e-06 -8.00413803410631e-05 0.00053229458934178 2.20841133948053e-05 0.000426131163735041 9.78883552188329e-05 3.89516701325199e-05 -4.07131891967535e-06 2.20841133948053e-05 1.13226407637348e-05 1.2031920529246e-05 8.92920524496782e-06 4.93066024441407e-06 -5.36808122642628e-05 0.000426131163735041 1.2031920529246e-05 0.00119842958407705 0.000225686721307313 0.00101654719095937 -1.66412067529764e-05 9.78883552188329e-05 8.92920524496782e-06 0.000225686721307313 5.7564622951066e-05 0.000168735548082686 6.34605951288691e-06 3.89516701325199e-05 4.93066024441407e-06 0.00101654719095937 0.000168735548082686 0.00156897455529791 3179 3096 0 235 0 3200 3117 0 130 0 0 0 0 0 0 0 0 0 410 0 11 40 0 0 3884 +1033 1034 0.999927436049517 -0.00027878468446907 0.0120434594091462 0.155712866054313 0.000155766790907547 0.999947821272023 0.0102142288030289 -0.00857065968984061 -0.0120456785673077 -0.0102116116472122 0.99987530453323 0.0268075476796095 2.61615249914446e-05 3.1622175702079e-06 5.34234906832823e-06 -1.14802925177676e-05 2.98458699741361e-06 3.35872356723748e-06 3.1622175702079e-06 2.11817660334026e-05 1.82323502489584e-06 -9.61587288229619e-06 -3.42475301419336e-07 3.23924860650701e-06 5.34234906832823e-06 1.82323502489584e-06 8.43659397203656e-06 -4.10415204124189e-06 4.99699324416649e-06 -2.91017006808469e-07 -1.14802925177676e-05 -9.61587288229619e-06 -4.10415204124189e-06 0.00012164841877568 1.22328898151145e-06 -9.19455885011564e-06 2.98458699741361e-06 -3.42475301419336e-07 4.99699324416649e-06 1.22328898151145e-06 9.34003336906268e-06 -7.70753589047865e-06 3.35872356723748e-06 3.23924860650701e-06 -2.91017006808469e-07 -9.19455885011564e-06 -7.70753589047865e-06 0.000131207761123866 3267 3272 0 0 145 3267 3272 0 0 147 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3756 +1035 1036 0.999696266164778 0.0228139117894718 -0.00932206227529103 0.113691548172071 -0.0227415084747789 0.999710946642091 0.00780044590172694 -0.0103765698596565 0.00949732638660827 -0.00758607888414082 0.999926123370457 -0.0308811971564337 3.21827262972985e-05 2.41157657722643e-06 -8.08996364561662e-06 1.93870843082973e-06 -2.41261860047319e-06 1.30400816704325e-05 2.41157657722643e-06 3.91979844892119e-05 -9.46210270605721e-07 5.41122309290026e-06 -4.30908239163641e-06 4.65767115905132e-05 -8.08996364561662e-06 -9.46210270605721e-07 1.01693672409591e-05 -1.34893548060752e-06 6.1061244736257e-06 2.83078938556042e-06 1.93870843082973e-06 5.41122309290026e-06 -1.34893548060752e-06 0.000131683191782465 3.5397933258076e-06 -2.79050634238762e-05 -2.41261860047319e-06 -4.30908239163641e-06 6.1061244736257e-06 3.5397933258076e-06 1.26321472692162e-05 -3.36096113953225e-05 1.30400816704325e-05 4.65767115905132e-05 2.83078938556042e-06 -2.79050634238762e-05 -3.36096113953225e-05 0.000592756136748218 3173 3129 0 0 37 3173 3129 0 0 41 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3857 +1046 1047 0.99977218004308 -0.0178652754485836 0.0116798949076157 0.0867795789110064 0.0178825789506993 0.999839143320508 -0.00137871468568831 -0.00982044997648685 -0.0116533850008792 0.00158726722978932 0.999930837208635 -0.0397592463749678 2.38888249803126e-05 -3.53863020367927e-06 1.81210917758071e-06 -3.15875418472263e-06 9.8613127006538e-07 1.80305696116751e-06 -3.53863020367927e-06 1.56807464890468e-05 -1.80841295638224e-06 -4.25998605684085e-06 -8.93609896519817e-07 -9.08709398866326e-06 1.81210917758071e-06 -1.80841295638224e-06 9.32265290066442e-06 4.35117963151673e-06 4.88563407523688e-06 1.4483049647915e-07 -3.15875418472263e-06 -4.25998605684085e-06 4.35117963151673e-06 0.000139724056247856 1.72600253286497e-06 -1.1198018831129e-05 9.8613127006538e-07 -8.93609896519817e-07 4.88563407523688e-06 1.72600253286497e-06 8.81741782877784e-06 1.89659959141283e-06 1.80305696116751e-06 -9.08709398866326e-06 1.4483049647915e-07 -1.1198018831129e-05 1.89659959141283e-06 4.73634222443215e-05 3713 3675 0 43 93 3713 3675 0 0 125 0 0 0 0 0 0 0 0 3659 0 0 0 0 0 3676 +1036 1037 0.999026208827368 0.0399887883345348 -0.0186421802252596 0.130855993983499 -0.0399058496279646 0.999191914605442 0.00480009922625713 -0.0107332915578224 0.0188190659036404 -0.00405149289119622 0.999814696913317 -0.0615093119460241 2.59901521478439e-05 -3.05322810583369e-06 -4.1391139481572e-06 7.80577483636071e-06 -1.43908034224812e-06 6.38086999867042e-06 -3.05322810583369e-06 2.01431826055505e-05 1.68592840710481e-06 7.12362049509602e-06 -6.00056235879521e-07 1.46684215830888e-05 -4.1391139481572e-06 1.68592840710481e-06 9.086177282287e-06 -1.97166472841975e-06 4.73754883311546e-06 2.40457265366335e-06 7.80577483636071e-06 7.12362049509602e-06 -1.97166472841975e-06 0.000112698826802822 4.70996754303372e-06 5.11863086538676e-05 -1.43908034224812e-06 -6.00056235879521e-07 4.73754883311546e-06 4.70996754303372e-06 1.06846305937821e-05 -1.02585809110283e-05 6.38086999867042e-06 1.46684215830888e-05 2.40457265366335e-06 5.11863086538676e-05 -1.02585809110283e-05 0.000248846686379762 3647 3514 0 17 11 3647 3517 0 17 19 0 0 0 0 0 0 0 0 0 0 1 8 0 0 3891 +1047 1048 0.998587777524588 -0.0505035015115916 -0.0164877807352171 0.10529009650601 0.0502816255384456 0.998642405177143 -0.0136053193723173 0.00178025228629955 0.0171525132769361 0.0127570732176263 0.999771498079038 0.0377932330532602 3.53937148347338e-05 -9.9169696530434e-06 5.03011128606752e-06 -1.75888898844896e-05 1.43630611566084e-06 7.82980287847251e-06 -9.9169696530434e-06 2.47330573291359e-05 -1.74064931355626e-06 1.24293246551515e-05 4.3486361873567e-08 -6.59644049934193e-06 5.03011128606752e-06 -1.74064931355626e-06 1.05122857811925e-05 -1.89079309837732e-07 4.91147966916429e-06 1.9621751724717e-06 -1.75888898844896e-05 1.24293246551515e-05 -1.89079309837732e-07 0.000232215020957837 -1.81450317207815e-06 2.67070554000079e-06 1.43630611566084e-06 4.3486361873567e-08 4.91147966916429e-06 -1.81450317207815e-06 9.026427015641e-06 4.58931007100629e-06 7.82980287847251e-06 -6.59644049934193e-06 1.9621751724717e-06 2.67070554000079e-06 4.58931007100629e-06 8.96053048782266e-05 3690 3640 0 0 201 3643 3640 0 0 241 0 0 0 0 0 0 0 0 3745 0 0 0 0 0 3585 +1048 1049 0.998045200737455 -0.0510532316625316 0.036046425921922 0.139461881195488 0.0512870391613356 0.998668302914324 -0.00559109723469375 0.00913820434902296 -0.0357129794192022 0.00742888221982635 0.999334475943849 0.0883049912891924 3.66745019460119e-05 5.37181024250673e-07 1.02438842624537e-05 -8.60026572811616e-07 2.9527574396632e-06 1.80386323790101e-06 5.37181024250673e-07 4.52406787361182e-05 -4.86551911596824e-06 1.40775002887872e-05 8.53872146719116e-06 0.000104850086027265 1.02438842624537e-05 -4.86551911596824e-06 1.38546145348298e-05 -2.12581764066215e-06 3.16665555314328e-06 -1.41756052853677e-05 -8.60026572811616e-07 1.40775002887872e-05 -2.12581764066215e-06 0.000221801339007585 2.70409521420467e-06 0.000140779713437069 2.9527574396632e-06 8.53872146719116e-06 3.16665555314328e-06 2.70409521420467e-06 1.54919014501689e-05 7.49108145610346e-05 1.80386323790101e-06 0.000104850086027265 -1.41756052853677e-05 0.000140779713437069 7.49108145610346e-05 0.00112489748902416 3331 3265 0 34 258 3320 3265 0 0 285 0 0 0 0 0 0 0 0 3691 0 0 0 0 0 3546 +1043 1044 0.998839354243042 -0.0481618764705165 0.000614874118789489 0.160085870465194 0.0481348561202146 0.997658758519036 -0.0485802138379589 0.0116928344448564 0.00172627970777805 0.0485534262961358 0.998819095108457 0.0775203195750079 4.41020390657992e-05 -1.55513800320579e-05 6.01088690295681e-06 -1.75854386416992e-05 -1.88044112037947e-06 2.24750513207109e-05 -1.55513800320579e-05 6.79137477691117e-05 -1.92482402176498e-06 -8.26848378348347e-05 -8.11128083713048e-06 8.88822751871567e-05 6.01088690295681e-06 -1.92482402176498e-06 1.1196017628328e-05 5.93563544306235e-06 4.51214812892127e-06 -4.91394025893501e-06 -1.75854386416992e-05 -8.26848378348347e-05 5.93563544306235e-06 0.000514214055922928 5.97178008964158e-05 -0.000402922369431621 -1.88044112037947e-06 -8.11128083713048e-06 4.51214812892127e-06 5.97178008964158e-05 2.008501573191e-05 -3.20179885615494e-05 2.24750513207109e-05 8.88822751871567e-05 -4.91394025893501e-06 -0.000402922369431621 -3.20179885615494e-05 0.000810422912007503 3145 3128 0 77 269 3145 3128 0 11 311 0 0 0 0 0 0 0 0 2527 0 0 0 0 0 3534 +1045 1046 0.997947278336249 -0.0456361596845924 0.0449285053225226 -0.11545009410217 0.0452802687232678 0.998934605834139 0.00890789152054208 -0.0296933166206015 -0.0452871607149556 -0.00685523130430093 0.998950488702089 -0.00641290311000376 3.79818591025501e-05 -7.65070736736603e-06 6.63415118069052e-06 -0.000100214762400262 -4.39971032966251e-06 2.21722729756713e-05 -7.65070736736603e-06 9.18110026703819e-05 -3.17613076764799e-06 -0.000616147997404556 -2.41531623657537e-05 0.000228335965910102 6.63415118069052e-06 -3.17613076764799e-06 1.04237564029378e-05 1.78109813616125e-05 5.30042775406716e-06 -1.0379820298697e-05 -0.000100214762400262 -0.000616147997404556 1.78109813616125e-05 0.0126175990954718 0.000556606981010444 -0.00365234112499762 -4.39971032966251e-06 -2.41531623657537e-05 5.30042775406716e-06 0.000556606981010444 3.64032063208279e-05 -0.000119252704722972 2.21722729756713e-05 0.000228335965910102 -1.0379820298697e-05 -0.00365234112499762 -0.000119252704722972 0.00183999955258629 2835 2835 0 0 0 2798 2802 0 0 0 0 0 0 0 0 170 100 0 3416 0 9 35 0 0 3812 +1050 1051 0.994090179856504 -0.108556633780197 -0.000414216340020765 0.121020213594933 0.108554983138109 0.994035004158028 0.0104988639591671 0.0107746611890227 -0.000727975788648541 -0.0104817828092638 0.999944799616654 0.0920602211689799 3.99898917569997e-05 1.98722896193192e-05 5.89923982133768e-06 -2.5511162963437e-06 1.94153402253374e-06 -1.88394811120796e-05 1.98722896193192e-05 4.95408323749106e-05 9.49819520929571e-07 -6.33765912671168e-06 2.05527831200617e-06 -1.19943419211571e-05 5.89923982133768e-06 9.49819520929571e-07 1.29869133616015e-05 4.55898592266203e-06 4.49556806666932e-06 8.01895566769756e-07 -2.5511162963437e-06 -6.33765912671168e-06 4.55898592266203e-06 3.61773897989028e-05 1.35754077437674e-06 7.72332952539318e-06 1.94153402253374e-06 2.05527831200617e-06 4.49556806666932e-06 1.35754077437674e-06 1.12087245002498e-05 -1.0974520960905e-06 -1.88394811120796e-05 -1.19943419211571e-05 8.01895566769756e-07 7.72332952539318e-06 -1.0974520960905e-06 0.000118570075849918 3263 3211 0 0 383 3149 3147 0 0 392 0 0 0 0 0 4 0 0 3519 0 0 0 0 0 3406 +1042 1043 0.999088344114489 -0.0266062705370867 -0.0333854312938343 0.15752594491438 0.0263334703544553 0.999616353089058 -0.00858457780102788 -0.00541253000718065 0.0336010266756687 0.00769759735490406 0.999405682393943 0.0601122863486622 2.20496730503434e-05 -1.50171822341244e-05 1.47641178333935e-06 2.11069946506136e-06 1.13908431212016e-07 1.36789750912852e-05 -1.50171822341244e-05 2.14147830206398e-05 -1.14542037706514e-06 -1.30519746885511e-06 2.20495846481604e-07 -1.56948574669588e-05 1.47641178333935e-06 -1.14542037706514e-06 8.7421552939355e-06 -4.62392869625755e-06 4.51594050148728e-06 1.71918376803295e-06 2.11069946506136e-06 -1.30519746885511e-06 -4.62392869625755e-06 0.00010583939671383 1.64561239428053e-05 8.94761754212657e-06 1.13908431212016e-07 2.20495846481604e-07 4.51594050148728e-06 1.64561239428053e-05 1.31565232651714e-05 3.61713952171784e-07 1.36789750912852e-05 -1.56948574669588e-05 1.71918376803295e-06 8.94761754212657e-06 3.61713952171784e-07 6.09815133611749e-05 3507 3494 0 115 196 3507 3494 0 45 239 0 0 0 0 0 0 0 0 1719 0 0 0 0 0 3626 +1055 1056 0.962690616716041 -0.0254261329590549 -0.269407290639353 -0.0114258628380526 0.0742031913090796 0.98221844632688 0.172455240844569 0.0719491102710604 0.26023194055772 -0.186011922891945 0.947459182052506 0.296708057587361 0.00314919927574911 0.0046361097882585 0.000691826963484578 -0.000308873296451825 0.000286888255279047 0.00237418709074102 0.0046361097882585 0.00711722348907167 0.00104733794737349 -0.000493220173761673 0.000448484520986821 0.00379168736825201 0.000691826963484578 0.00104733794737349 0.000181353503149107 -6.34169166430238e-05 7.21555919444394e-05 0.000539042079430915 -0.000308873296451825 -0.000493220173761673 -6.34169166430238e-05 8.74422286995807e-05 -4.94246012096654e-05 -0.00042405239846466 0.000286888255279047 0.000448484520986821 7.21555919444394e-05 -4.94246012096654e-05 6.45531364639703e-05 0.000384158474160539 0.00237418709074102 0.00379168736825201 0.000539042079430915 -0.00042405239846466 0.000384158474160539 0.0036944477066247 789 781 0 0 42 789 781 0 0 32 0 0 0 0 0 0 0 0 1421 0 0 0 0 0 2082 +1052 1053 0.996747019489979 -0.0805064144222362 0.00375451391252017 0.0366704011748228 0.0805045855734766 0.996754035483514 0.000635963027175359 0.0201346491009507 -0.00379352599660647 -0.000331638665285575 0.99999274956187 -0.0446543357899779 3.1016804248826e-05 2.1644676697375e-05 4.24404029284364e-06 -6.46171320446413e-06 -5.065496806808e-07 7.67604237252844e-06 2.1644676697375e-05 5.01046861798146e-05 6.2841187651759e-07 8.97933173700229e-06 -2.51320157536286e-06 7.24532189503385e-05 4.24404029284364e-06 6.2841187651759e-07 1.30262151695813e-05 3.05194340101186e-06 -5.21251375230959e-07 3.60993081785068e-06 -6.46171320446413e-06 8.97933173700229e-06 3.05194340101186e-06 0.000121085194952483 -4.34363306855016e-05 9.1428058774834e-06 -5.065496806808e-07 -2.51320157536286e-06 -5.21251375230959e-07 -4.34363306855016e-05 3.68309954236707e-05 1.24050316548093e-05 7.67604237252844e-06 7.24532189503385e-05 3.60993081785068e-06 9.1428058774834e-06 1.24050316548093e-05 0.000468509022101143 3435 3404 0 0 292 3290 3261 0 0 279 0 0 0 0 0 71 0 0 2007 0 0 0 0 0 3507 +1054 1055 0.999020989733202 -0.0442262880707195 -0.00104762396879123 0.0567590886004339 0.0442355562915463 0.998952038261287 0.0117490771210801 0.0218653381692132 0.000526908029633394 -0.011783916882997 0.999930428415309 0.0273676104165999 7.34019204055996e-05 8.18011033122219e-05 -3.9687071633438e-06 7.62679888168902e-06 -8.94034645851869e-06 -0.000128607419055255 8.18011033122219e-05 0.00012413148187726 -9.19879290077467e-06 2.00853627053778e-05 -2.08807723595102e-05 -0.000237998298061149 -3.9687071633438e-06 -9.19879290077467e-06 1.19234956372165e-05 3.08612124715885e-06 4.86727127769012e-06 1.77206234095228e-05 7.62679888168902e-06 2.00853627053778e-05 3.08612124715885e-06 0.000335675436537499 -0.000179317890672083 -9.16866379174527e-05 -8.94034645851869e-06 -2.08807723595102e-05 4.86727127769012e-06 -0.000179317890672083 0.000119557069081092 0.000104814651985321 -0.000128607419055255 -0.000237998298061149 1.77206234095228e-05 -9.16866379174527e-05 0.000104814651985321 0.00116746408478443 2577 2536 0 0 188 2577 2536 0 0 155 0 0 0 0 0 0 0 0 1602 0 0 0 0 0 3711 +1044 1045 0.997038845016269 -0.0563392555997048 0.0523395625420766 0.14560700032756 0.056907934235161 0.998334819233487 -0.00943799380839428 0.00386074133590674 -0.0517206781636842 0.0123885828290337 0.998584745760607 -0.0136552138127233 4.69314844893871e-05 -1.17035608487264e-05 1.26618482123691e-05 -4.23519539480677e-06 -4.91380127176541e-07 6.43203813860772e-06 -1.17035608487264e-05 5.76467771939741e-05 -2.60710239998699e-06 3.78954152232092e-06 3.01514640183377e-07 -4.08940372430778e-06 1.26618482123691e-05 -2.60710239998699e-06 1.21961698504369e-05 -1.10365536050093e-06 2.92146820244489e-06 2.99722940023775e-06 -4.23519539480677e-06 3.78954152232092e-06 -1.10365536050093e-06 0.000120508803563693 6.52036373811929e-06 4.01361980592778e-05 -4.91380127176541e-07 3.01514640183377e-07 2.92146820244489e-06 6.52036373811929e-06 1.22835939991303e-05 1.57130193782128e-05 6.43203813860772e-06 -4.08940372430778e-06 2.99722940023775e-06 4.01361980592778e-05 1.57130193782128e-05 0.000212515190134492 3174 3139 0 28 270 3153 3139 0 0 310 0 0 0 0 0 0 0 0 3372 0 0 0 0 0 3528 +1049 1050 0.997088642426769 -0.0642057980069221 0.0411321607241513 0.120112796258591 0.0637717367273279 0.997894973901008 0.0117807749272386 0.00331216580493809 -0.0418019705076623 -0.00912340755420896 0.999084260058318 -0.0129473647236012 3.64732871894473e-05 1.81937689861254e-05 6.38878272900101e-06 -5.49525109695103e-07 8.33165306866675e-08 -2.17701042348921e-05 1.81937689861254e-05 0.000195745338499567 -7.09268147009486e-06 0.00011989551790657 -1.7887452279847e-05 -4.05969749136697e-05 6.38878272900101e-06 -7.09268147009486e-06 1.17115413381727e-05 -4.12946568691971e-06 5.11792669805526e-06 1.37788777906343e-06 -5.49525109695103e-07 0.00011989551790657 -4.12946568691971e-06 0.000192883274472303 -1.87969881603759e-05 4.97619738970006e-06 8.33165306866675e-08 -1.7887452279847e-05 5.11792669805526e-06 -1.87969881603759e-05 1.28609931549786e-05 6.79651404085768e-06 -2.17701042348921e-05 -4.05969749136697e-05 1.37788777906343e-06 4.97619738970006e-06 6.79651404085768e-06 0.000251253044631301 3246 3159 0 1 272 3187 3159 0 0 291 0 0 0 0 0 0 0 0 3707 0 0 0 0 0 3549 +1056 1057 0.998268471762495 -0.0516678775268968 -0.0281156311833542 0.0462389727320232 0.0526081230891441 0.998043114623672 0.0337983244750041 0.03225928552155 0.0263143244262564 -0.0352189123078181 0.999033124849143 0.0400249021039843 0.000429729549989202 0.000573254006799523 -3.47200065681359e-06 0.000256922215475668 -0.000180022159697086 -0.000481105748757483 0.000573254006799523 0.000850019469924796 -3.46700847203629e-06 0.000414382184043769 -0.000288433142773825 -0.000745356118369 -3.47200065681359e-06 -3.46700847203629e-06 1.21755304751606e-05 6.63216134340013e-06 1.02235537378914e-06 4.43355002119039e-06 0.000256922215475668 0.000414382184043769 6.63216134340013e-06 0.000371340888560887 -0.000244909869438844 -0.000502050047717762 -0.000180022159697086 -0.000288433142773825 1.02235537378914e-06 -0.000244909869438844 0.000189042921671219 0.000360228056695142 -0.000481105748757483 -0.000745356118369 4.43355002119039e-06 -0.000502050047717762 0.000360228056695142 0.0011821461681305 1987 1949 0 0 146 1987 1949 0 0 109 0 0 0 0 0 0 0 0 1292 0 0 0 0 0 3498 +1057 1058 0.997834015165378 -0.0652246009551775 0.00854573631574381 0.0631765772402915 0.0652438694857952 0.997867353815785 -0.00199541554680964 0.0146331706277045 -0.00839736110101831 0.00254865041184089 0.999961493612438 0.0502414772007172 3.24535818504134e-05 1.8018588285641e-05 1.15501268726914e-06 1.09832172290891e-05 -7.24557214239442e-06 2.43717917677126e-05 1.8018588285641e-05 2.86606714394156e-05 -5.3369156877447e-07 5.01751014411543e-06 -3.9799564832468e-06 1.17757491741387e-05 1.15501268726914e-06 -5.3369156877447e-07 1.06828893929472e-05 1.57450274987311e-06 2.37589472318777e-06 -3.58969817981785e-06 1.09832172290891e-05 5.01751014411543e-06 1.57450274987311e-06 4.78048787915644e-05 -2.13022403930628e-05 4.75406176078512e-05 -7.24557214239442e-06 -3.9799564832468e-06 2.37589472318777e-06 -2.13022403930628e-05 3.22739220051082e-05 -3.37784333780795e-05 2.43717917677126e-05 1.17757491741387e-05 -3.58969817981785e-06 4.75406176078512e-05 -3.37784333780795e-05 0.000194367115574834 1809 1796 0 0 138 1809 1796 0 0 97 0 0 0 0 0 0 0 0 1228 0 0 0 0 0 3561 +1053 1054 0.998499893780537 -0.0547100613860769 -0.00218433133639002 0.0314097272735536 0.0546919906605635 0.9984742169843 -0.00761736011842999 0.0324426619743208 0.00259774476041545 0.00748646784009103 0.999968601767795 0.0292888419868412 4.95675771801215e-05 4.13407529813064e-05 -2.8080218794245e-06 4.04965555505551e-07 -1.1196475425314e-06 -1.58432280615709e-05 4.13407529813064e-05 6.49280747456237e-05 -3.59930654427505e-06 -8.81862641584677e-06 6.68604791458782e-06 1.43977920073036e-05 -2.8080218794245e-06 -3.59930654427505e-06 1.27731933478109e-05 5.4834159525884e-07 5.20501100231232e-06 -9.27933635592285e-07 4.04965555505551e-07 -8.81862641584677e-06 5.4834159525884e-07 0.000112098260795927 -4.30343008848703e-05 8.15563915261624e-06 -1.1196475425314e-06 6.68604791458782e-06 5.20501100231232e-06 -4.30343008848703e-05 3.68518275965164e-05 1.43577604914924e-05 -1.58432280615709e-05 1.43977920073036e-05 -9.27933635592285e-07 8.15563915261624e-06 1.43577604914924e-05 0.000319272216482332 3037 2999 0 0 235 3018 2981 0 0 209 0 0 0 0 0 0 0 0 1740 0 0 0 0 0 3606 +1051 1052 0.994579946269228 -0.103974547231888 0.000154942002702054 0.0891977473411693 0.103972263644962 0.994545770802567 -0.0082751538517751 0.00954075568591829 0.000706308461505519 0.00824641174402269 0.999965748324264 0.00981600152656225 4.37436187916824e-05 1.5047016548235e-05 2.44415786665469e-06 -4.75770056746007e-08 -4.65829243908608e-06 1.13939099157874e-05 1.5047016548235e-05 2.44509816515994e-05 -9.01454428661629e-07 -7.71850041571564e-06 7.07940716470779e-07 -3.5610866688569e-06 2.44415786665469e-06 -9.01454428661629e-07 1.20381472182185e-05 1.5985762969508e-06 3.25934600238735e-06 5.69266419232359e-06 -4.75770056746007e-08 -7.71850041571564e-06 1.5985762969508e-06 6.30572976872492e-05 -8.11805383639375e-06 -1.1073994554174e-05 -4.65829243908608e-06 7.07940716470779e-07 3.25934600238735e-06 -8.11805383639375e-06 1.59253792729303e-05 4.72781594814742e-06 1.13939099157874e-05 -3.5610866688569e-06 5.69266419232359e-06 -1.1073994554174e-05 4.72781594814742e-06 0.000149835110836291 3465 3408 0 0 357 3338 3320 0 0 357 0 0 0 0 0 23 0 0 2912 0 0 0 0 0 3438 +1063 1064 0.997998628554687 -0.06245717026459 0.00989137429800275 0.0137370844744089 0.0623307609989476 0.997975877089563 0.0126105107196177 0.022876415600393 -0.0106589697558091 -0.0119687355162327 0.999871559618478 0.0510277380954422 2.28198869309018e-05 1.74910872928e-05 7.4070376268778e-07 2.37421508601349e-06 1.22876893566137e-06 3.96363475038807e-06 1.74910872928e-05 2.9558189287217e-05 1.49529417259582e-06 -5.20410058451065e-07 7.87205866882814e-06 3.97411168491114e-06 7.4070376268778e-07 1.49529417259582e-06 1.69209119258957e-05 -2.16510690275828e-06 -9.06104738126043e-07 -5.38278061963513e-07 2.37421508601349e-06 -5.20410058451065e-07 -2.16510690275828e-06 2.5285466923166e-05 -2.67525375204769e-06 -7.76695612699374e-07 1.22876893566137e-06 7.87205866882814e-06 -9.06104738126043e-07 -2.67525375204769e-06 5.5381640400998e-05 -4.83649946205611e-06 3.96363475038807e-06 3.97411168491114e-06 -5.38278061963513e-07 -7.76695612699374e-07 -4.83649946205611e-06 3.98998090832296e-05 0 101 0 0 41 0 101 0 0 150 0 0 0 0 0 0 0 0 1323 0 0 0 0 0 2804 +1064 1065 0.998225459374741 -0.0594324700991654 -0.00370320860855316 0.0103937085204698 0.0594552785635894 0.998210532189902 0.00638774420896934 0.0186436191152831 0.00331694241925339 -0.00659658419676737 0.999972741113438 0.0384171667553709 2.86040316625564e-05 2.03309401017456e-05 -1.46001720284968e-06 9.71679667105161e-07 2.2329027035471e-06 2.05250879095409e-06 2.03309401017456e-05 3.77951756463181e-05 7.13639421504167e-07 3.61956541492745e-06 -1.14662068162384e-06 -5.83442734369194e-06 -1.46001720284968e-06 7.13639421504167e-07 1.27401302434756e-05 1.43294885545574e-06 2.90689274010012e-06 1.70894855547584e-06 9.71679667105161e-07 3.61956541492745e-06 1.43294885545574e-06 2.58638093453032e-05 -1.16703734407623e-05 -3.35378895575928e-06 2.2329027035471e-06 -1.14662068162384e-06 2.90689274010012e-06 -1.16703734407623e-05 7.06432643068027e-05 4.73427082617583e-06 2.05250879095409e-06 -5.83442734369194e-06 1.70894855547584e-06 -3.35378895575928e-06 4.73427082617583e-06 4.51339433090568e-05 0 0 0 0 0 0 0 0 0 82 0 0 0 0 0 0 0 0 1257 0 0 0 0 0 3231 +1065 1066 0.999411586838791 -0.0340299575995567 0.00429442407559763 0.00757130469460469 0.0339014412586324 0.999057598504702 0.0271036372209705 0.00451458063692382 -0.00521271262935073 -0.0269421019185746 0.999623404473531 0.0176187374277952 5.3070243558772e-05 3.51356684504676e-05 -3.26738533008151e-07 5.59092515500097e-06 -1.25982477405987e-06 2.65128164030758e-05 3.51356684504676e-05 4.72737859287164e-05 -6.79280196964836e-07 -1.1262490949039e-06 9.17263857355879e-06 8.32155753643403e-06 -3.26738533008151e-07 -6.79280196964836e-07 1.41813713301537e-05 -3.84626862007437e-07 -2.04722575060948e-06 2.37911960193429e-06 5.59092515500097e-06 -1.1262490949039e-06 -3.84626862007437e-07 2.75103784954963e-05 -1.73445785670863e-05 -1.4774579434335e-06 -1.25982477405987e-06 9.17263857355879e-06 -2.04722575060948e-06 -1.73445785670863e-05 8.27145634652611e-05 3.04452379507114e-06 2.65128164030758e-05 8.32155753643403e-06 2.37911960193429e-06 -1.4774579434335e-06 3.04452379507114e-06 5.90336784716987e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1229 0 0 0 0 0 3138 +1067 1068 0.999437893050615 -0.00961058335383261 -0.0321175127017518 -0.0131998634638131 0.00904658154124413 0.999803122732239 -0.0176599868992271 0.0392154866814168 0.0322809122697264 0.0173595064003067 0.999328069374903 0.0240298537494447 4.36124172132625e-05 3.16284536902584e-05 3.49056327803307e-06 1.58018743896975e-06 1.17668367014483e-05 -4.75798511833676e-08 3.16284536902584e-05 4.5037881751766e-05 2.03936888960751e-06 3.59751088659451e-07 1.27322754001271e-05 -5.27584749956936e-06 3.49056327803307e-06 2.03936888960751e-06 1.70383379438492e-05 -3.91147778275452e-06 -2.31086319471978e-06 -4.6509555099673e-06 1.58018743896975e-06 3.59751088659451e-07 -3.91147778275452e-06 2.3822308802656e-05 -1.72319982502677e-05 -1.01987993890826e-06 1.17668367014483e-05 1.27322754001271e-05 -2.31086319471978e-06 -1.72319982502677e-05 9.08144134507169e-05 3.87608646419334e-06 -4.75798511833676e-08 -5.27584749956936e-06 -4.6509555099673e-06 -1.01987993890826e-06 3.87608646419334e-06 3.71454083028163e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1244 0 0 0 0 0 2384 +1066 1067 0.999457324722457 -0.0162776330555904 -0.0286372959745914 -0.00325844483863849 0.017219694170989 0.999308215374189 0.0329632040055444 0.0235304704131955 0.0280809221943725 -0.0334384411682285 0.999046211374105 0.0246631280515203 6.96446205607745e-05 2.7704322879155e-05 -5.52283784423068e-06 1.56844154510154e-06 1.09569464354857e-05 4.49509765896722e-05 2.7704322879155e-05 5.37177468128484e-05 -1.62727938048059e-06 4.2886981084919e-06 -2.73323346344369e-06 3.7647419087252e-06 -5.52283784423068e-06 -1.62727938048059e-06 1.69527655582337e-05 -4.60751470128896e-06 -3.83808568147027e-06 -3.98367933871402e-06 1.56844154510154e-06 4.2886981084919e-06 -4.60751470128896e-06 2.97770480569571e-05 -1.32510941462605e-05 -2.64614300163709e-06 1.09569464354857e-05 -2.73323346344369e-06 -3.83808568147027e-06 -1.32510941462605e-05 9.03872681731975e-05 1.11222395969036e-05 4.49509765896722e-05 3.7647419087252e-06 -3.98367933871402e-06 -2.64614300163709e-06 1.11222395969036e-05 5.7311421825589e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1200 0 0 0 0 0 2763 +1062 1063 0.996386307853639 -0.0781184597378288 0.0333441414641565 0.0213198142703615 0.0775428703218649 0.996822490160201 0.0182215908488305 0.0161909186279973 -0.034661632737638 -0.0155701431915369 0.999277810149388 0.0645706945102741 3.83383377482668e-05 3.06377363873523e-05 1.56376034184383e-06 -6.63850627737765e-07 7.33734540468146e-07 2.43349485020391e-05 3.06377363873523e-05 5.35676242293663e-05 1.8639492259351e-06 -2.31057746921016e-06 5.44422807402402e-06 1.58450526177771e-05 1.56376034184383e-06 1.8639492259351e-06 1.5073749673493e-05 1.09566680959748e-06 1.05553738636119e-06 2.19953344356606e-06 -6.63850627737765e-07 -2.31057746921016e-06 1.09566680959748e-06 3.25692964279147e-05 -2.31451674970346e-05 5.32423636497282e-06 7.33734540468146e-07 5.44422807402402e-06 1.05553738636119e-06 -2.31451674970346e-05 7.84059883357495e-05 -1.34835914724442e-05 2.43349485020391e-05 1.58450526177771e-05 2.19953344356606e-06 5.32423636497282e-06 -1.34835914724442e-05 9.93658411136794e-05 256 363 0 0 181 256 363 0 0 216 0 0 0 0 0 0 0 0 1214 0 0 0 0 0 3093 +1058 1059 0.997617743358212 -0.0682585323896854 0.00998052568126142 0.0601179095327014 0.0682431379235921 0.997666957037004 0.00187535673067094 0.00578727393458405 -0.0100852497841965 -0.0011897867590273 0.999948434742641 0.0584219261224425 1.85837547477249e-05 9.71183887418963e-06 -1.58683123093717e-09 4.72615543705441e-07 -2.33529457395457e-07 -9.28585301002587e-06 9.71183887418963e-06 3.51033487783008e-05 -7.62460519308401e-07 1.04190258732771e-05 -9.7350811053024e-06 3.73391433730874e-05 -1.58683123093717e-09 -7.62460519308401e-07 1.08870795677308e-05 8.66505176532193e-07 1.88836106309523e-06 1.87140104581569e-07 4.72615543705441e-07 1.04190258732771e-05 8.66505176532193e-07 3.90736448839377e-05 -1.78882114891045e-05 3.62680499950391e-05 -2.33529457395457e-07 -9.7350811053024e-06 1.88836106309523e-06 -1.78882114891045e-05 3.12674294008577e-05 -2.9412601827628e-05 -9.28585301002587e-06 3.73391433730874e-05 1.87140104581569e-07 3.62680499950391e-05 -2.9412601827628e-05 0.000158902233695939 1707 1671 0 0 151 1707 1671 0 0 135 0 0 0 0 0 0 0 0 1209 0 0 0 0 0 3488 +1071 1072 0.999361687084318 -0.0060974465869154 -0.0351999933679784 0.00985772849213499 0.00625549310131251 0.999970834881203 0.00438157426617459 0.0106439847374475 0.0351722503409355 -0.0045989707664091 0.999370683117053 0.0122258541340484 2.64432401954054e-05 -4.46379241513811e-06 -1.37171459622839e-05 8.78000467535689e-06 -7.08329045698885e-06 1.82268918788943e-05 -4.46379241513811e-06 7.40378949373077e-05 4.62768824336747e-06 -2.91179462039841e-06 3.84007608191077e-05 -1.68393854006786e-05 -1.37171459622839e-05 4.62768824336747e-06 2.41737626424724e-05 -1.38713793210046e-05 9.62687398981005e-08 -7.29084512044272e-06 8.78000467535689e-06 -2.91179462039841e-06 -1.38713793210046e-05 2.78268754109467e-05 -1.43892015381199e-05 3.37860132135994e-06 -7.08329045698885e-06 3.84007608191077e-05 9.62687398981005e-08 -1.43892015381199e-05 0.000110066739314539 -6.56395538425558e-06 1.82268918788943e-05 -1.68393854006786e-05 -7.29084512044272e-06 3.37860132135994e-06 -6.56395538425558e-06 4.71990622077592e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1190 0 0 0 0 0 2279 +1061 1062 0.99526516971983 -0.0888433791333842 0.0394220233717048 0.0293360823453617 0.0887339880999525 0.996045106436969 0.00451943567774571 0.019244667031735 -0.0396676354026173 -0.000999963564108543 0.999212429253377 0.0600574388183861 3.8454764842178e-05 2.90460168104557e-05 -3.09565826097245e-06 -5.44416146443595e-07 -4.91375865079141e-07 3.4795548023488e-05 2.90460168104557e-05 5.86611899164164e-05 -9.21739799818497e-07 -4.70624046169671e-06 7.17491093710189e-06 3.19959055084297e-05 -3.09565826097245e-06 -9.21739799818497e-07 1.39726184227123e-05 1.76030980025721e-06 1.96683176021434e-06 8.25783822704243e-08 -5.44416146443595e-07 -4.70624046169671e-06 1.76030980025721e-06 2.06519401428404e-05 -4.03197362329091e-07 7.65279466818794e-08 -4.91375865079141e-07 7.17491093710189e-06 1.96683176021434e-06 -4.03197362329091e-07 3.32661706629685e-05 -3.7853313754002e-06 3.4795548023488e-05 3.19959055084297e-05 8.25783822704243e-08 7.65279466818794e-08 -3.7853313754002e-06 0.000140904836314017 616 654 0 0 226 616 654 0 0 222 0 0 0 0 0 0 0 0 1206 0 0 0 0 0 2857 +1060 1061 0.996342434832355 -0.0853868207479135 -0.00329293104979522 0.0346077030302296 0.0854415224381114 0.996052280711342 0.0240748900971807 0.0182070780371338 0.00122425315712004 -0.0242681876599246 0.999704734545111 0.0701709677998821 2.78728203125883e-05 1.71491196967045e-05 -1.65700320974191e-06 -3.23016873224522e-06 3.02991047321146e-06 1.03698578965899e-05 1.71491196967045e-05 2.98084963824337e-05 1.03923104483988e-06 -1.81311245342936e-06 -1.64912255484492e-06 3.33467593570949e-06 -1.65700320974191e-06 1.03923104483988e-06 1.43027399125244e-05 8.48605341524485e-07 -6.79858227555097e-07 1.23461178786055e-06 -3.23016873224522e-06 -1.81311245342936e-06 8.48605341524485e-07 3.02546352318264e-05 -1.25851676067082e-05 7.21003573607734e-06 3.02991047321146e-06 -1.64912255484492e-06 -6.79858227555097e-07 -1.25851676067082e-05 4.38961530336695e-05 -7.78433143056266e-06 1.03698578965899e-05 3.33467593570949e-06 1.23461178786055e-06 7.21003573607734e-06 -7.78433143056266e-06 0.000120158853189063 1059 1029 0 0 190 1059 1029 0 0 183 0 0 0 0 0 0 0 0 1241 0 0 0 0 0 3107 +1059 1060 0.997768976807022 -0.0666061377575178 0.0045487728558721 0.0641654932546741 0.0665558266423917 0.997728111435663 0.0104373172306831 -0.00599272009195686 -0.00523362794012487 -0.010111283996238 0.999935183436673 0.0681755852398115 2.38769086248764e-05 1.44223009041847e-05 -2.32703851382563e-06 2.66395979002196e-06 -2.6200441065458e-06 -8.48775158360514e-06 1.44223009041847e-05 2.43098541725737e-05 -1.95825632486931e-06 -2.22732474736363e-06 8.08035605924034e-07 1.14417946917721e-05 -2.32703851382563e-06 -1.95825632486931e-06 1.09202209017252e-05 2.98636904704374e-06 3.42260952994069e-06 2.28217242893979e-06 2.66395979002196e-06 -2.22732474736363e-06 2.98636904704374e-06 2.64579275438018e-05 -8.819706848468e-06 -2.92652217947043e-07 -2.6200441065458e-06 8.08035605924034e-07 3.42260952994069e-06 -8.819706848468e-06 2.91673773332432e-05 -1.75096389884618e-06 -8.48775158360514e-06 1.14417946917721e-05 2.28217242893979e-06 -2.92652217947043e-07 -1.75096389884618e-06 0.000134744718874774 1434 1386 0 0 161 1434 1386 0 0 155 0 0 0 0 0 0 0 0 1243 0 0 0 0 0 3345 +1074 1075 0.999546152882537 -0.00915191104640428 0.0287007104775951 -0.0110908329081473 0.0095764231360486 0.999846256938449 -0.0146885876139139 0.00657444700708357 -0.0285618692952577 0.0149567713886044 0.999480122169516 0.00578524099116109 4.08834979427057e-05 3.16181752955719e-05 -2.45094493086326e-06 3.82865250015122e-06 -1.216481799487e-07 1.69079886101539e-05 3.16181752955719e-05 5.16818669363328e-05 -1.25771840814616e-06 2.04348449655249e-06 3.53809267114749e-06 4.79935173859375e-06 -2.45094493086326e-06 -1.25771840814616e-06 1.38043577508346e-05 -5.34956521668178e-06 -3.97316301518637e-06 -2.08216694711726e-06 3.82865250015122e-06 2.04348449655249e-06 -5.34956521668178e-06 2.11391573673221e-05 -6.11846279727139e-06 -1.32625486636251e-06 -1.216481799487e-07 3.53809267114749e-06 -3.97316301518637e-06 -6.11846279727139e-06 6.26934170474754e-05 5.73984739953174e-06 1.69079886101539e-05 4.79935173859375e-06 -2.08216694711726e-06 -1.32625486636251e-06 5.73984739953174e-06 5.04824429066563e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1038 0 0 0 0 0 2227 +1069 1070 0.999810814726719 -0.000607040611437227 -0.019441354304463 0.00708979737232776 0.000457463706599625 0.999970270918957 -0.00769727258352904 0.00257432177296767 0.0194454488879208 0.00768692265891037 0.999781368969028 0.00633572307452666 2.68815232205501e-05 5.57258317442637e-06 -6.53375960811417e-06 2.0200003916493e-06 5.86769782065928e-06 8.06065209996293e-06 5.57258317442637e-06 6.92025710420803e-05 4.93075412770795e-06 4.56844950756389e-06 2.66761961400937e-06 -2.75678394113138e-05 -6.53375960811417e-06 4.93075412770795e-06 2.2726915289179e-05 -7.38289450095433e-06 -1.72075454314017e-06 -6.0965964027132e-06 2.0200003916493e-06 4.56844950756389e-06 -7.38289450095433e-06 2.75097882483814e-05 -1.90559497301608e-05 -1.42115827795522e-06 5.86769782065928e-06 2.66761961400937e-06 -1.72075454314017e-06 -1.90559497301608e-05 9.82644719191925e-05 -6.792931114443e-06 8.06065209996293e-06 -2.75678394113138e-05 -6.0965964027132e-06 -1.42115827795522e-06 -6.792931114443e-06 5.02387839271812e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1210 0 0 0 0 0 2250 +1070 1071 0.999279820866131 -0.00956340118727811 -0.0367203072901603 0.00933086063960791 0.00916196079057395 0.999896583758113 -0.0110851370459388 0.0276573007571973 0.0368225214267656 0.010740723745932 0.999264098609166 0.00799087027601644 2.6153292134816e-05 1.11231007883861e-05 -8.54104870376844e-06 3.28671096535193e-06 3.8208850263101e-06 1.14267045508068e-05 1.11231007883861e-05 5.26384427680907e-05 1.86981086545837e-06 6.20306930716377e-06 -3.59497280100279e-06 -1.11016377086798e-05 -8.54104870376844e-06 1.86981086545837e-06 2.4054076193447e-05 -8.88280109519608e-06 -9.72727112158733e-06 -5.65447845152699e-06 3.28671096535193e-06 6.20306930716377e-06 -8.88280109519608e-06 2.94099864790533e-05 -5.27901878106411e-07 -5.07194491653661e-06 3.8208850263101e-06 -3.59497280100279e-06 -9.72727112158733e-06 -5.27901878106411e-07 6.50484477388249e-05 7.83915477351466e-06 1.14267045508068e-05 -1.11016377086798e-05 -5.65447845152699e-06 -5.07194491653661e-06 7.83915477351466e-06 4.69828618666295e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1205 0 0 0 0 0 2183 +1073 1074 0.999842686727723 -0.00554367620674657 0.0168484257781563 -0.0121443847438949 0.00563152850294899 0.999970771297623 -0.00517130903710825 0.0220804525575764 -0.016819265257667 0.00526537791156118 0.999844681993979 0.00432664573834655 2.73071703768327e-05 1.02295616414539e-05 -3.59239104946822e-06 -2.12323584544052e-06 1.26022270518459e-05 1.54176522428437e-05 1.02295616414539e-05 5.41274303608866e-05 5.90233981996462e-07 1.14879071340819e-05 -1.85935438160212e-05 -1.86191538966601e-07 -3.59239104946822e-06 5.90233981996462e-07 1.80966111747474e-05 -3.76260536070079e-06 -8.96178355272409e-06 -4.1821810127258e-06 -2.12323584544052e-06 1.14879071340819e-05 -3.76260536070079e-06 3.06269849448998e-05 -3.01062474693992e-05 -9.46062281278611e-06 1.26022270518459e-05 -1.85935438160212e-05 -8.96178355272409e-06 -3.01062474693992e-05 0.000115110515129515 2.26394550677953e-05 1.54176522428437e-05 -1.86191538966601e-07 -4.1821810127258e-06 -9.46062281278611e-06 2.26394550677953e-05 4.60554981216423e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1093 0 0 0 0 0 2100 +1068 1069 0.999835383721578 0.00185771326802302 -0.0180486664254655 -0.00251908317148655 -0.00179160627909083 0.999991630509017 0.0036781868981818 0.024449608572092 0.0180553483839176 -0.0036452453046462 0.999830343899106 0.0120334782768771 2.61832975861674e-05 1.69974018829518e-05 -3.56764442326384e-06 7.66770739349318e-07 3.54512773009881e-06 8.62966557895498e-06 1.69974018829518e-05 4.2621827297232e-05 -3.20555454501646e-06 1.93245602743716e-06 8.01750119298414e-07 1.81360209953613e-06 -3.56764442326384e-06 -3.20555454501646e-06 1.56933225487523e-05 -1.66445211568272e-06 -1.60404694145077e-06 -1.93574374847204e-06 7.66770739349318e-07 1.93245602743716e-06 -1.66445211568272e-06 2.61242153435677e-05 -1.35210631721701e-05 -2.38160689176258e-06 3.54512773009881e-06 8.01750119298414e-07 -1.60404694145077e-06 -1.35210631721701e-05 6.78070082299899e-05 4.78084914474006e-06 8.62966557895498e-06 1.81360209953613e-06 -1.93574374847204e-06 -2.38160689176258e-06 4.78084914474006e-06 3.81346310485648e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1220 0 0 0 0 0 2424 +1075 1076 0.999630437212975 0.00893179995067047 0.0256751231163221 -0.0127862746741292 -0.00866087580253882 0.999905843689293 -0.0106439178095415 0.0117581777359589 -0.0257677749860187 0.0104176151610855 0.999613672909002 0.00524626878223364 3.08197874217433e-05 -2.81262106284046e-06 -9.43381112387391e-06 2.7560652090312e-06 -7.3610402603e-07 1.0223019450506e-05 -2.81262106284046e-06 8.36085526771507e-05 6.86590982844222e-06 2.89237444134466e-06 1.4084684144541e-05 -2.47784241293782e-05 -9.43381112387391e-06 6.86590982844222e-06 1.93839741884142e-05 -9.20914239180924e-06 -3.4183694977697e-06 -5.4306242194958e-06 2.7560652090312e-06 2.89237444134466e-06 -9.20914239180924e-06 2.84038067325599e-05 -2.99518456501474e-06 -1.73795215751659e-08 -7.3610402603e-07 1.4084684144541e-05 -3.4183694977697e-06 -2.99518456501474e-06 6.32816810272056e-05 4.45797567070282e-06 1.0223019450506e-05 -2.47784241293782e-05 -5.4306242194958e-06 -1.73795215751659e-08 4.45797567070282e-06 4.94582261532656e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1113 0 0 0 0 0 2258 +1076 1077 0.99975488241992 0.00389048774954108 0.0217953936096979 -0.00856032254137278 -0.00371636696146248 0.999960903688405 -0.00802369685839277 0.00805604654928354 -0.0218257575845317 0.00794073042851239 0.999730254171656 0.00333311333687735 6.31155157878594e-05 3.17783361865395e-05 -6.65876001297556e-06 1.12827816116043e-05 -1.36341644532719e-05 1.35710654504174e-05 3.17783361865395e-05 5.2810344433601e-05 -6.25643887592102e-07 5.54108328470818e-06 -3.76307893542844e-06 -1.12634834007939e-05 -6.65876001297556e-06 -6.25643887592102e-07 1.519495981763e-05 -4.90133646092172e-06 -3.15571358261925e-06 -3.44841876641546e-06 1.12827816116043e-05 5.54108328470818e-06 -4.90133646092172e-06 2.99754917393662e-05 -2.28103541092765e-05 3.95916235476811e-06 -1.36341644532719e-05 -3.76307893542844e-06 -3.15571358261925e-06 -2.28103541092765e-05 0.000112996280581501 7.20577919374053e-06 1.35710654504174e-05 -1.12634834007939e-05 -3.44841876641546e-06 3.95916235476811e-06 7.20577919374053e-06 5.32908286601521e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 928 0 0 0 0 0 2236 +1072 1073 0.999572186377748 0.00839440511765543 0.0280174621036447 -0.00194516023645092 -0.00807289863976084 0.999900492102512 -0.0115686732474479 0.0128637161236077 -0.0281117862748107 0.0113375418797351 0.99954048823275 0.00989858106741578 6.2801461448012e-05 1.28410712192211e-05 -1.12130311054558e-05 1.52552750956282e-05 -5.72535868803001e-06 5.29184960279152e-06 1.28410712192211e-05 5.61675768155449e-05 -6.29488490338781e-06 8.23432395533815e-06 1.34924271592915e-05 6.15305170618231e-06 -1.12130311054558e-05 -6.29488490338781e-06 1.83005697145661e-05 -7.21159961780025e-06 1.11035192109683e-07 -4.27745182307779e-06 1.52552750956282e-05 8.23432395533815e-06 -7.21159961780025e-06 2.75018941105646e-05 -5.22028561312843e-06 3.21928482458578e-06 -5.72535868803001e-06 1.34924271592915e-05 1.11035192109683e-07 -5.22028561312843e-06 7.09441232863323e-05 2.89947174849918e-06 5.29184960279152e-06 6.15305170618231e-06 -4.27745182307779e-06 3.21928482458578e-06 2.89947174849918e-06 5.11929744008934e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1104 0 0 0 0 0 2112 +1078 1079 0.999967057777599 -0.0055653426363633 0.00590849565889897 -0.00549171963777473 0.00563475340974705 0.999914540029183 -0.011796702600275 0.00978093697749426 -0.00584233802708258 0.0118296069067348 0.99991295995542 0.00275514458695316 7.05824462865595e-05 3.54332719472233e-05 -6.17168081755442e-06 1.72100529285246e-05 -2.77581832016207e-05 1.7427450345808e-05 3.54332719472233e-05 6.21782353692658e-05 5.74151813843739e-08 3.67948388388099e-06 -1.11780381583996e-06 -2.03593185298035e-05 -6.17168081755442e-06 5.74151813843739e-08 1.32827177908518e-05 -3.85948887800644e-06 -1.07898509149035e-06 -1.6333513017244e-06 1.72100529285246e-05 3.67948388388099e-06 -3.85948887800644e-06 2.92303284915731e-05 -2.0383934573845e-05 5.46324763025231e-06 -2.77581832016207e-05 -1.11780381583996e-06 -1.07898509149035e-06 -2.0383934573845e-05 0.000108570489114988 -1.31192330482321e-05 1.7427450345808e-05 -2.03593185298035e-05 -1.6333513017244e-06 5.46324763025231e-06 -1.31192330482321e-05 6.96364056055071e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 903 0 0 0 0 0 2314 +1077 1078 0.999995178767177 -0.00309533080261344 0.000247728934326139 -0.00900264500540397 0.00309637658471957 0.999985793881087 -0.00433871963357496 0.0194287884938422 -0.000234295642533732 0.00433946577766905 0.999990557026573 -0.000586805936451082 7.59988229533336e-05 2.21182176185135e-05 -1.27032066068273e-05 1.59261246061947e-05 -1.37308382688368e-05 4.07308535067542e-05 2.21182176185135e-05 7.31059694383393e-05 -2.4503893713421e-07 4.91936364379452e-06 1.91023494910449e-05 -1.96055951913047e-05 -1.27032066068273e-05 -2.4503893713421e-07 1.7522854817064e-05 -7.56217078488044e-06 -3.21332041607425e-06 -6.11321500016582e-06 1.59261246061947e-05 4.91936364379452e-06 -7.56217078488044e-06 2.84923484787065e-05 -1.25659693950746e-05 1.02103606703428e-05 -1.37308382688368e-05 1.91023494910449e-05 -3.21332041607425e-06 -1.25659693950746e-05 9.56989635923982e-05 -1.60200482522052e-05 4.07308535067542e-05 -1.96055951913047e-05 -6.11321500016582e-06 1.02103606703428e-05 -1.60200482522052e-05 6.91709323796145e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 913 0 0 0 0 0 2329 +1081 1082 0.999938390392041 0.0110844064673344 0.000592750740224986 -0.0117700869442042 -0.0110793758615215 0.999907365464544 -0.00790619505664013 0.0116485511705972 -0.000680331310653353 0.0078991406508191 0.999968569869217 0.00132012224236866 9.39612410263113e-05 6.65370020756064e-05 -7.40608377129838e-06 2.08627647659432e-05 -2.23017155215952e-05 -2.37093541006893e-06 6.65370020756064e-05 8.47077308422171e-05 -6.75065150528917e-07 1.10021664630974e-05 -1.38616319618537e-05 -2.06132141470772e-05 -7.40608377129838e-06 -6.75065150528917e-07 1.45837500413914e-05 -3.67056201118514e-06 -2.2122247800572e-06 -3.98237385821537e-06 2.08627647659432e-05 1.10021664630974e-05 -3.67056201118514e-06 3.74365943574601e-05 -4.0800809465723e-05 6.14787912799809e-06 -2.23017155215952e-05 -1.38616319618537e-05 -2.2122247800572e-06 -4.0800809465723e-05 0.000150875941562357 3.64942232852521e-06 -2.37093541006893e-06 -2.06132141470772e-05 -3.98237385821537e-06 6.14787912799809e-06 3.64942232852521e-06 4.76349700296747e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 813 0 0 0 0 0 2396 +1082 1083 0.999999888637393 3.43777258422482e-05 -0.000470683943124014 -0.00565561611086168 -3.50115765731023e-05 0.99999909256346 -0.00134671691426542 0.00610314546069617 0.000470637218943339 0.00134673324367843 0.999998982404572 0.000102240782863587 3.84232330010713e-05 1.12803057293606e-05 -5.81291303776429e-06 3.03053257421431e-06 -1.30351534797674e-06 -5.28724823854184e-06 1.12803057293606e-05 4.63967266302511e-05 4.47428963651499e-06 -5.15734267191012e-06 8.13128178849958e-06 -1.82880574890556e-05 -5.81291303776429e-06 4.47428963651499e-06 1.37238634737006e-05 -2.14877077837054e-06 3.38445822360928e-06 9.21589981343069e-08 3.03053257421431e-06 -5.15734267191012e-06 -2.14877077837054e-06 2.24922863801572e-05 -1.16166623879939e-05 -8.14119862762746e-07 -1.30351534797674e-06 8.13128178849958e-06 3.38445822360928e-06 -1.16166623879939e-05 7.62793979990806e-05 -1.99674251257512e-06 -5.28724823854184e-06 -1.82880574890556e-05 9.21589981343069e-08 -8.14119862762746e-07 -1.99674251257512e-06 4.10844196292058e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 763 0 0 0 0 0 2372 +1083 1084 0.999985689437042 5.2338923307028e-05 0.00534959641111691 0.00420639570687742 -5.56988726734217e-05 0.999999801301858 0.000627928244612208 0.00054285481931469 -0.00534956248307381 -0.000628217225094887 0.999985493656962 -0.00171622763678382 2.54750346956588e-05 -1.18573545934761e-05 -1.1115066609498e-05 4.22994154107373e-06 1.72352069012152e-06 1.4881280409631e-05 -1.18573545934761e-05 7.15497761131166e-05 1.01819649147958e-05 -4.48473270136167e-06 4.53691821045533e-06 -3.7269149767283e-05 -1.1115066609498e-05 1.01819649147958e-05 1.88408223404565e-05 -8.33570623078049e-06 -4.2099285810371e-06 -6.54034942593537e-06 4.22994154107373e-06 -4.48473270136167e-06 -8.33570623078049e-06 2.33913566688948e-05 9.50088289478842e-06 6.55536610825187e-06 1.72352069012152e-06 4.53691821045533e-06 -4.2099285810371e-06 9.50088289478842e-06 3.72597334015823e-05 1.57715511326305e-08 1.4881280409631e-05 -3.7269149767283e-05 -6.54034942593537e-06 6.55536610825187e-06 1.57715511326305e-08 5.32505962725205e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 899 0 0 0 0 0 2603 +1085 1086 0.999998654648815 0.00163377131729818 0.000146600964433042 -0.00562707255681095 -0.00163390891915881 0.99999822011433 0.000943456313641417 0.0219213804387814 -0.000145059311635735 -0.000943694576984692 0.999999544199067 -0.00162647703718808 3.07316249863372e-05 -3.04968508364386e-05 -1.71919083269774e-05 1.14092576671221e-05 -7.88843026019256e-06 2.85510454604769e-05 -3.04968508364386e-05 0.000149915824597256 2.45195140700927e-05 3.47073293163822e-05 -0.000117792675600124 -8.08340576859997e-05 -1.71919083269774e-05 2.45195140700927e-05 2.59199839677866e-05 -1.13867159869024e-05 -2.05241155162417e-05 -1.71132694571796e-05 1.14092576671221e-05 3.47073293163822e-05 -1.13867159869024e-05 0.000298163007054992 -0.000743016248967374 -8.10800868330013e-06 -7.88843026019256e-06 -0.000117792675600124 -2.05241155162417e-05 -0.000743016248967374 0.00212982839441671 4.62174566288516e-05 2.85510454604769e-05 -8.08340576859997e-05 -1.71132694571796e-05 -8.10800868330013e-06 4.62174566288516e-05 7.5994250817097e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 917 0 0 0 0 0 2744 +1089 1090 0.999993870056626 -0.00118575298965502 0.00329451650772081 -0.00325380001537832 0.00117909861364777 0.999997262553089 0.00202104250002084 0.0101810316025598 -0.00329690394634339 -0.00201714555129786 0.999992530746202 -0.00370412529319962 2.77633992121368e-05 -1.55457738051842e-05 -1.43211507429512e-05 6.52331506147918e-06 1.99594846408314e-06 8.52453464526666e-06 -1.55457738051842e-05 9.66201307522994e-05 1.77969474724001e-05 -3.53132671430753e-06 1.87509955656005e-06 -5.43895204251528e-05 -1.43211507429512e-05 1.77969474724001e-05 2.25980427431472e-05 -1.34694931779042e-05 -8.6937671329174e-06 -9.65883002630583e-06 6.52331506147918e-06 -3.53132671430753e-06 -1.34694931779042e-05 2.76233972075028e-05 4.0307268855272e-06 2.16908555939453e-06 1.99594846408314e-06 1.87509955656005e-06 -8.6937671329174e-06 4.0307268855272e-06 5.22301386707741e-05 -1.64678963715865e-06 8.52453464526666e-06 -5.43895204251528e-05 -9.65883002630583e-06 2.16908555939453e-06 -1.64678963715865e-06 5.2883514759351e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 971 0 0 0 0 0 2447 +1086 1087 0.999968609261418 0.00152372992811048 -0.00777552177613736 -0.00258291682237501 -0.00152994776790036 0.999998514583088 -0.00079378299635261 0.00752034999730214 0.00777430071533785 0.000805654221103743 0.999969455118337 0.00514632193398197 2.84619202539101e-05 5.33149857297499e-06 -1.05721405237997e-05 5.78088996575648e-06 4.46121243314092e-06 -2.1146458886099e-06 5.33149857297499e-06 6.47621534480957e-05 5.7983583359312e-06 -2.63937327614645e-06 -1.25846518593408e-05 -3.92705731900806e-05 -1.05721405237997e-05 5.7983583359312e-06 1.9199738227645e-05 -7.19016083971912e-06 -9.5961729108675e-06 -4.54719203541094e-06 5.78088996575648e-06 -2.63937327614645e-06 -7.19016083971912e-06 2.54513543392515e-05 -5.25939187483398e-06 1.47859021293755e-06 4.46121243314092e-06 -1.25846518593408e-05 -9.5961729108675e-06 -5.25939187483398e-06 8.35644857012419e-05 5.59704141980693e-06 -2.1146458886099e-06 -3.92705731900806e-05 -4.54719203541094e-06 1.47859021293755e-06 5.59704141980693e-06 4.51910855860902e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 936 0 0 0 0 0 2558 +1079 1080 0.999980677456748 -0.000254001418442862 0.00621129587303441 -0.00308968892032342 0.000332736125871477 0.999919571692997 -0.012678305563638 0.00145476675793657 -0.00620757600142643 0.0126801273090559 0.999900335219272 -0.00264828341265171 0.000172597545270849 8.4737719402152e-05 -4.4264033069392e-06 2.49270229834613e-05 -3.60972639349255e-05 5.10782057231769e-05 8.4737719402152e-05 8.66766476549064e-05 -1.09386807505831e-06 5.68749953542028e-06 7.9182337019693e-06 -3.23268829242813e-07 -4.4264033069392e-06 -1.09386807505831e-06 1.28064812125813e-05 -3.4655026202115e-06 -4.45882258327018e-06 1.0771054836932e-06 2.49270229834613e-05 5.68749953542028e-06 -3.4655026202115e-06 2.69279180394236e-05 -1.81488855968529e-05 8.90451425288036e-06 -3.60972639349255e-05 7.9182337019693e-06 -4.45882258327018e-06 -1.81488855968529e-05 0.000117895567512558 -2.20131622399942e-05 5.10782057231769e-05 -3.23268829242813e-07 1.0771054836932e-06 8.90451425288036e-06 -2.20131622399942e-05 6.78434101501021e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 891 0 0 0 0 0 2295 +1080 1081 0.99999330359756 0.00342605670974678 0.00128642740161392 -0.0034014726936549 -0.00341324344206528 0.999945821336803 -0.00983382734600408 0.000620057820154524 -0.00132004895485827 0.0098293706048464 0.999950819262762 0.000296536506470016 3.60367295750281e-05 2.1663657358964e-05 -3.31421709268962e-06 3.88551595436711e-06 -5.18368026365323e-06 -9.78922870688398e-06 2.1663657358964e-05 4.55662798169252e-05 1.84938480258035e-06 6.71834298631807e-07 -1.04484573393051e-05 -2.02999482548343e-05 -3.31421709268962e-06 1.84938480258035e-06 1.29744234357859e-05 -7.18715888077636e-07 -8.23544762144859e-07 1.34278648254307e-07 3.88551595436711e-06 6.71834298631807e-07 -7.18715888077636e-07 2.39352335222694e-05 -1.56602412872974e-05 -3.07580635467799e-06 -5.18368026365323e-06 -1.04484573393051e-05 -8.23544762144859e-07 -1.56602412872974e-05 8.52998193789313e-05 5.4235310457402e-06 -9.78922870688398e-06 -2.02999482548343e-05 1.34278648254307e-07 -3.07580635467799e-06 5.4235310457402e-06 3.8547350510851e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 852 0 0 0 0 0 2387 +1094 1095 0.999985478393681 -0.000316306557508167 0.00537986541866478 -0.00615141405760936 0.000300771469109525 0.999995783912328 0.00288819910874037 0.0176234262428331 -0.005380756292998 -0.00288653905742436 0.999981357503221 -0.00469884304100398 3.29583088824572e-05 -2.73177744382195e-05 -1.43696150147096e-05 4.06307073572161e-06 -2.57595714009902e-06 1.03040455944134e-05 -2.73177744382195e-05 0.000166525029543643 3.26107924056138e-05 -8.25203788958142e-06 1.54439172438888e-05 -8.59901256277198e-05 -1.43696150147096e-05 3.26107924056138e-05 2.63721587335906e-05 -1.16857843568497e-05 -7.18073777121172e-06 -1.23486545215728e-05 4.06307073572161e-06 -8.25203788958142e-06 -1.16857843568497e-05 2.68885158091116e-05 5.41829487848705e-06 2.15144861659591e-06 -2.57595714009902e-06 1.54439172438888e-05 -7.18073777121172e-06 5.41829487848705e-06 5.89707223989361e-05 -8.47053726625652e-06 1.03040455944134e-05 -8.59901256277198e-05 -1.23486545215728e-05 2.15144861659591e-06 -8.47053726625652e-06 6.44259157777257e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 882 0 0 0 0 0 2599 +1095 1096 0.999999289028581 0.000188567442019305 0.00117744836476753 -0.00612583693393194 -0.000190929388977554 0.999997969356445 0.00200619763622296 0.0212846877163817 -0.00117706767023315 -0.00200642101937061 0.999997294389536 -0.00255787341779268 2.75527580145497e-05 -1.3410540322754e-05 -1.1189297120539e-05 2.02079793785171e-06 3.07017377753352e-06 7.12641422591968e-06 -1.3410540322754e-05 0.000116786078239188 2.15693397704878e-05 -6.51552595071643e-06 -1.61293177883928e-05 -6.00499755848361e-05 -1.1189297120539e-05 2.15693397704878e-05 2.10170437091641e-05 -9.62795180880226e-06 -1.0699156821787e-05 -8.28253737974405e-06 2.02079793785171e-06 -6.51552595071643e-06 -9.62795180880226e-06 2.63322793284179e-05 2.20212183272263e-06 4.1543026991059e-06 3.07017377753352e-06 -1.61293177883928e-05 -1.0699156821787e-05 2.20212183272263e-06 5.41375107357888e-05 2.47026236287389e-06 7.12641422591968e-06 -6.00499755848361e-05 -8.28253737974405e-06 4.1543026991059e-06 2.47026236287389e-06 5.36383882533912e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 987 0 0 0 0 0 2564 +1084 1085 0.999995122642893 0.000237913799218952 0.00311417524391677 -0.00179882830287285 -0.000235627840777834 0.999999702571191 -0.000734395703739477 0.00415170228181528 -0.00311434904054334 0.000733658335440844 0.99999488127465 -0.000181053656930014 3.27197208527809e-05 -1.49067507897806e-05 -1.26612275041747e-05 3.98707464014803e-06 1.20665852551839e-05 2.65406547690358e-05 -1.49067507897806e-05 9.48283660062685e-05 1.71384829134163e-05 -4.53382312908124e-06 -1.21400357517634e-05 -5.76513971837322e-05 -1.26612275041747e-05 1.71384829134163e-05 2.2047846318335e-05 -1.32429654571581e-05 -1.08954044791645e-05 -1.02946494067935e-05 3.98707464014803e-06 -4.53382312908124e-06 -1.32429654571581e-05 2.9501496493087e-05 -3.7709404248659e-07 1.59157940385497e-06 1.20665852551839e-05 -1.21400357517634e-05 -1.08954044791645e-05 -3.7709404248659e-07 6.48652436323759e-05 1.60497328127383e-05 2.65406547690358e-05 -5.76513971837322e-05 -1.02946494067935e-05 1.59157940385497e-06 1.60497328127383e-05 7.964699789638e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 935 0 0 0 0 0 2625 +1087 1088 0.999999792984509 0.000303584753438203 -0.000567333444613478 -0.00182093494878882 -0.000305366225387242 0.999995015285512 -0.00314263513590995 0.00705450696338936 0.000566376560505355 0.00314280772980831 0.999994900975583 0.00756699822725719 2.33813626876271e-05 -1.6977635552014e-06 -9.81179517160211e-06 5.30191723671397e-06 1.85631732447191e-06 8.83614653906846e-06 -1.6977635552014e-06 7.01192206411184e-05 1.22801083996832e-05 -6.31642706463355e-06 3.81393325305259e-06 -2.60714190877017e-05 -9.81179517160211e-06 1.22801083996832e-05 2.05793681844715e-05 -1.20748793514486e-05 -8.62180618634457e-06 -4.53986329207275e-06 5.30191723671397e-06 -6.31642706463355e-06 -1.20748793514486e-05 3.0005962631238e-05 -4.93493659254418e-06 9.07178925275479e-07 1.85631732447191e-06 3.81393325305259e-06 -8.62180618634457e-06 -4.93493659254418e-06 6.94778887658431e-05 3.11960066713549e-06 8.83614653906846e-06 -2.60714190877017e-05 -4.53986329207275e-06 9.07178925275479e-07 3.11960066713549e-06 4.70108193011118e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 863 0 0 0 0 0 2676 +1102 1103 0.999888854229576 -0.000884218787001459 0.0148827868560261 -0.0296592375469537 0.00111214621015489 0.999882122476857 -0.0153135326421966 -6.06839208200028 -0.0148674919967164 0.0153283824428117 0.999771973188594 -0.0705042115577288 0.000135850485363055 8.68752659501423e-05 -9.17660667137822e-07 -1.04571521865939e-05 3.83645741446696e-05 -0.000105702054945169 8.68752659501423e-05 0.000115818444535861 -2.43702249848937e-06 2.35935900821706e-06 2.83391464844613e-05 -0.00014515509206689 -9.17660667137822e-07 -2.43702249848937e-06 1.4745343968227e-05 6.09017180845116e-07 3.77605065071991e-07 -2.55662255814676e-06 -1.04571521865939e-05 2.35935900821706e-06 6.09017180845116e-07 2.85593098981581e-05 -8.88264527426381e-06 -4.84401128539421e-05 3.83645741446696e-05 2.83391464844613e-05 3.77605065071991e-07 -8.88264527426381e-06 8.03326230487318e-05 8.35028161149196e-05 -0.000105702054945169 -0.00014515509206689 -2.55662255814676e-06 -4.84401128539421e-05 8.35028161149196e-05 0.000755575202111586 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 564 465 +1090 1091 0.999965108369775 -0.00148473776393994 0.00822055939683272 -0.00329258867874058 0.00146295001691756 0.999995403304173 0.00265577630324429 0.0147873927143032 -0.00822446474079165 -0.00264365737137089 0.999962683931471 -0.00639798846621781 2.48537380629336e-05 -1.54622642093433e-05 -1.39948199935062e-05 7.01799814044016e-06 5.58392705348652e-06 1.17510112033235e-05 -1.54622642093433e-05 9.13266929426369e-05 1.34641806562575e-05 -6.58548247188258e-06 9.19126117063093e-06 -5.31075027730478e-05 -1.39948199935062e-05 1.34641806562575e-05 1.9915173785834e-05 -1.11064343758933e-05 -8.6679283515121e-06 -1.00140902962703e-05 7.01799814044016e-06 -6.58548247188258e-06 -1.11064343758933e-05 2.82426200774964e-05 -4.4952471644913e-06 6.18526565913323e-06 5.58392705348652e-06 9.19126117063093e-06 -8.6679283515121e-06 -4.4952471644913e-06 7.18519413852491e-05 -7.91346564995507e-06 1.17510112033235e-05 -5.31075027730478e-05 -1.00140902962703e-05 6.18526565913323e-06 -7.91346564995507e-06 5.74317731948247e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 950 0 0 0 0 0 2638 +1088 1089 0.999981913925569 0.00119378608929139 -0.00589463285781029 -0.000784748400188989 -0.00119580924769641 0.999999227319096 -0.000339707895976746 0.00411748449706419 0.0058942227645794 0.000346750608477599 0.999982568799085 0.00248560990269096 2.60742801085668e-05 -2.48586101473658e-05 -1.47301341740257e-05 5.54405588416687e-06 3.4167168111992e-08 1.61242513334568e-05 -2.48586101473658e-05 0.000122419623401394 2.23234746576934e-05 -5.26268142969832e-06 -3.32026710785788e-07 -6.70789330922653e-05 -1.47301341740257e-05 2.23234746576934e-05 2.14298404830681e-05 -1.08502308172938e-05 -1.01195175002121e-05 -1.32354052925776e-05 5.54405588416687e-06 -5.26268142969832e-06 -1.08502308172938e-05 2.758409066693e-05 -1.18505998550115e-06 7.46744468397565e-06 3.4167168111992e-08 -3.32026710785788e-07 -1.01195175002121e-05 -1.18505998550115e-06 6.38232226027017e-05 -4.12797497143121e-06 1.61242513334568e-05 -6.70789330922653e-05 -1.32354052925776e-05 7.46744468397565e-06 -4.12797497143121e-06 5.67831801292399e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 871 0 0 0 0 0 2595 +1099 1100 0.999980345388615 -0.000632127610538272 0.00623772804386647 -0.00757647912126835 0.000621115048323646 0.999998245510016 0.00176725577813617 0.0241972591721804 -0.00623883423100734 -0.00176334669665524 0.999978983557087 -0.00627189033380433 3.1854875693748e-05 -3.88017380596624e-05 -1.8118965317262e-05 4.5167891719887e-06 9.22201187489709e-06 1.87203804268978e-05 -3.88017380596624e-05 0.000150845943243501 2.85823928815969e-05 -2.50831525178887e-06 -8.75762813665983e-06 -7.98329231002275e-05 -1.8118965317262e-05 2.85823928815969e-05 2.40041945690549e-05 -1.16214127078572e-05 -8.13990594274072e-06 -1.43984492438381e-05 4.5167891719887e-06 -2.50831525178887e-06 -1.16214127078572e-05 3.12210698128034e-05 -1.99983467611683e-06 1.13477338697855e-06 9.22201187489709e-06 -8.75762813665983e-06 -8.13990594274072e-06 -1.99983467611683e-06 6.33442079832494e-05 2.21590059208516e-06 1.87203804268978e-05 -7.98329231002275e-05 -1.43984492438381e-05 1.13477338697855e-06 2.21590059208516e-06 6.43571310790199e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 893 0 0 0 0 0 2643 +1091 1092 0.999999796199587 0.000148785361516189 0.000620857229968226 -0.0056831345044656 -0.000147917067644384 0.999999011365683 -0.00139835195781589 0.0146627151177247 -0.000621064670469033 0.0013982598374503 0.999998829573366 0.00077342797697878 3.07767448998088e-05 -1.35704068559497e-05 -1.23571982510444e-05 7.50518038749608e-06 1.63060364913686e-06 1.94696005086212e-05 -1.35704068559497e-05 0.00010235686666804 1.75913848580581e-05 -1.29865550032008e-05 7.78600091424578e-06 -5.82563571881954e-05 -1.23571982510444e-05 1.75913848580581e-05 2.24869885859207e-05 -1.36557143266515e-05 -1.17518807217063e-05 -9.5487650548103e-06 7.50518038749608e-06 -1.29865550032008e-05 -1.36557143266515e-05 3.4255241011385e-05 -1.02450886261778e-05 7.97236010240251e-06 1.63060364913686e-06 7.78600091424578e-06 -1.17518807217063e-05 -1.02450886261778e-05 0.000103494918972775 1.0239242434939e-06 1.94696005086212e-05 -5.82563571881954e-05 -9.5487650548103e-06 7.97236010240251e-06 1.0239242434939e-06 7.40194761244461e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 850 0 0 0 0 0 2454 +1093 1094 0.999997793714491 -0.000302111016984353 0.00207877249440044 -0.00453212405068093 0.000306578103850407 0.999997644066926 -0.0021489230940834 0.0168549028092644 -0.00207811838361019 0.00214955565907518 0.999995530407237 0.000361615868396001 3.37783194899165e-05 -4.39207848635394e-05 -1.88886309984261e-05 8.01336317178932e-06 2.50112371719766e-08 2.9745021058025e-05 -4.39207848635394e-05 0.000171689423757572 3.59042710116709e-05 -1.36150453019361e-05 1.19213765269045e-05 -0.000108242042652404 -1.88886309984261e-05 3.59042710116709e-05 2.71685904002273e-05 -1.5021152417814e-05 -6.31875650169216e-06 -2.27201557894589e-05 8.01336317178932e-06 -1.36150453019361e-05 -1.5021152417814e-05 3.10597880532386e-05 5.25995001760466e-07 9.71991444099817e-06 2.50112371719766e-08 1.19213765269045e-05 -6.31875650169216e-06 5.25995001760466e-07 5.92839784082999e-05 -6.38160120604844e-06 2.9745021058025e-05 -0.000108242042652404 -2.27201557894589e-05 9.71991444099817e-06 -6.38160120604844e-06 9.73443623068941e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 892 0 0 0 0 0 2631 +1092 1093 0.999994922631227 0.00116692704550791 0.00296529813630128 0.000747860340038783 -0.00116857231973537 0.999999164220068 0.00055317076855979 0.0124463347936238 -0.00296465014803399 -0.000556633125229648 0.999995450494183 7.19470638633187e-05 3.23684028743535e-05 -2.7104415553288e-05 -1.39900929648482e-05 4.43870055461279e-06 -4.67453547570691e-06 1.59019648480699e-05 -2.7104415553288e-05 0.000160139074072181 3.01203913821213e-05 -1.12338357959342e-05 2.60675693723542e-05 -7.43302573989871e-05 -1.39900929648482e-05 3.01203913821213e-05 2.73914902547398e-05 -1.40735186270089e-05 -6.01033640344834e-06 -1.39327317820972e-05 4.43870055461279e-06 -1.12338357959342e-05 -1.40735186270089e-05 2.97119984944575e-05 7.59466046976691e-06 6.21021224771626e-06 -4.67453547570691e-06 2.60675693723542e-05 -6.01033640344834e-06 7.59466046976691e-06 6.05154357638955e-05 -1.34935141140585e-05 1.59019648480699e-05 -7.43302573989871e-05 -1.39327317820972e-05 6.21021224771626e-06 -1.34935141140585e-05 5.944487860864e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 866 0 0 0 0 0 2604 +1100 1101 0.999995479355467 -0.000430718705701135 0.00297586122430373 -0.00579584536529192 0.000424951900080284 0.999998031354361 0.00193822168108096 0.0234244323156531 -0.00297669019422135 -0.00193694832118807 0.99999369375346 -0.00477478459146909 2.46842514588998e-05 -1.54976201208115e-05 -1.45137025986115e-05 6.75528664914837e-06 1.93210528099249e-06 7.76323112423858e-06 -1.54976201208115e-05 0.000110748758766492 1.96495039661806e-05 -1.06354178112483e-05 -3.28262915069453e-07 -5.83511400000929e-05 -1.45137025986115e-05 1.96495039661806e-05 2.36049129811221e-05 -1.41967330620377e-05 -8.10203785762777e-06 -1.08571647551077e-05 6.75528664914837e-06 -1.06354178112483e-05 -1.41967330620377e-05 3.03726181894007e-05 2.76027105885386e-06 9.91903649415613e-06 1.93210528099249e-06 -3.28262915069453e-07 -8.10203785762777e-06 2.76027105885386e-06 6.77081442885756e-05 -4.24914291776245e-06 7.76323112423858e-06 -5.83511400000929e-05 -1.08571647551077e-05 9.91903649415613e-06 -4.24914291776245e-06 5.08906345071078e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 863 0 0 0 0 0 2575 +1101 1102 0.999993436533704 0.000215399139128757 -0.00361669638261435 -0.00853751921699859 -0.000215012855623108 0.999999971139448 0.000107194101392055 0.0230254952201353 0.00361671936775165 -0.000106415761610036 0.999993453986925 0.000732660626718696 2.31654863274399e-05 -1.69726923673302e-05 -1.06374161825336e-05 5.56902084544036e-06 -5.5998271385308e-06 9.2361408678744e-06 -1.69726923673302e-05 9.12003626543945e-05 2.18114456131378e-05 -2.23559626808776e-05 2.34061352662419e-05 -4.40069494059485e-05 -1.06374161825336e-05 2.18114456131378e-05 2.34700898346279e-05 -1.56750568410055e-05 -2.91898910604512e-06 -6.56293690315793e-06 5.56902084544036e-06 -2.23559626808776e-05 -1.56750568410055e-05 3.39789382075796e-05 -1.76210155629711e-05 6.76196049207956e-06 -5.5998271385308e-06 2.34061352662419e-05 -2.91898910604512e-06 -1.76210155629711e-05 0.000109032354746368 -1.00483168890354e-05 9.2361408678744e-06 -4.40069494059485e-05 -6.56293690315793e-06 6.76196049207956e-06 -1.00483168890354e-05 5.0426721123572e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 760 0 0 0 0 0 2487 +1096 1097 0.99993090912311 -0.000493872091489441 0.0117444910740265 -0.00294928807041501 0.000449613984138476 0.999992789597112 0.0037707560318706 0.0167446303737169 -0.0117462686626821 -0.00376521501960635 0.999923921270194 -0.00921358483025167 2.35440846454269e-05 -2.10202317667625e-05 -1.33935226528102e-05 4.9191453069492e-06 2.32233521102997e-06 1.14654525440179e-05 -2.10202317667625e-05 0.000102068191440761 1.73258333738518e-05 -1.52147248005885e-06 -5.58084384095845e-06 -5.24005940026175e-05 -1.33935226528102e-05 1.73258333738518e-05 2.05779867783405e-05 -1.10278468884339e-05 -7.38038209413156e-06 -8.93976624644104e-06 4.9191453069492e-06 -1.52147248005885e-06 -1.10278468884339e-05 2.85834978023387e-05 -4.72325272622392e-07 2.53120115668729e-06 2.32233521102997e-06 -5.58084384095845e-06 -7.38038209413156e-06 -4.72325272622392e-07 6.13906479798772e-05 7.39960498123227e-06 1.14654525440179e-05 -5.24005940026175e-05 -8.93976624644104e-06 2.53120115668729e-06 7.39960498123227e-06 4.80549095974441e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 998 0 0 0 0 0 2635 +1098 1099 0.999971711671495 -0.000616046561575787 0.00749642204086985 -0.00535187729893442 0.000597659309209341 0.999996808382876 0.00245479681696634 0.0107752472056246 -0.00749791038429935 -0.00245024706844908 0.999968888330618 -0.00603284249490817 4.02832264748449e-05 -2.65249885397527e-05 -1.01375110128118e-05 6.5679346625764e-07 7.08027044691589e-06 2.85985679796799e-05 -2.65249885397527e-05 0.000148973838817984 2.81775369254133e-05 -6.86025373311392e-06 -1.09063055859509e-05 -8.98728698345254e-05 -1.01375110128118e-05 2.81775369254133e-05 2.34817160573789e-05 -1.28089775536512e-05 -9.3437449855356e-06 -1.01311396938586e-05 6.5679346625764e-07 -6.86025373311392e-06 -1.28089775536512e-05 2.95265412721437e-05 3.3541154528917e-06 -7.58526415638618e-07 7.08027044691589e-06 -1.09063055859509e-05 -9.3437449855356e-06 3.3541154528917e-06 6.08231225610742e-05 1.0207035376397e-05 2.85985679796799e-05 -8.98728698345254e-05 -1.01311396938586e-05 -7.58526415638618e-07 1.0207035376397e-05 0.000102259115593299 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 877 0 0 0 0 0 2645 +1103 1104 0.99998120290042 -0.00101308657186126 -0.00604710686415719 -0.00397302722628433 0.000988536423698921 0.999991263767669 -0.00406142636007307 0.00248088711404777 0.0060511686117347 0.00405537223164412 0.999973468305282 0.0107490936633113 3.31710462862509e-05 2.12010689188035e-05 1.05324793662031e-05 -9.12175994914282e-06 -9.32600230790411e-06 1.24937527670753e-05 2.12010689188035e-05 5.31501276728542e-05 1.66472643053543e-05 -1.02352380210293e-05 -9.18242430401152e-06 -3.7448634295877e-06 1.05324793662031e-05 1.66472643053543e-05 1.93805629216767e-05 -9.53157040731963e-06 -5.08329401990975e-06 9.11176592755731e-06 -9.12175994914282e-06 -1.02352380210293e-05 -9.53157040731963e-06 2.4244422230992e-05 3.14425966028232e-07 -4.89520181719327e-06 -9.32600230790411e-06 -9.18242430401152e-06 -5.08329401990975e-06 3.14425966028232e-07 5.27003569731203e-05 -7.3241411179066e-06 1.24937527670753e-05 -3.7448634295877e-06 9.11176592755731e-06 -4.89520181719327e-06 -7.3241411179066e-06 5.65247058790775e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 715 0 0 0 0 0 2597 +1097 1098 0.999993385043535 0.000558309902006938 -0.00359418408353826 -0.00528504039025684 -0.000558636925714884 0.999999839913853 -8.99836288755382e-05 0.0107961995252732 0.00359413326940816 9.19908775846317e-05 0.999993536850974 0.000863842816487488 2.51645023865656e-05 -7.86484788015291e-06 -1.35818889248524e-05 6.4526415019035e-06 5.48756163105732e-06 3.0393450571928e-06 -7.86484788015291e-06 7.83902938657846e-05 1.28364621781714e-05 -8.81172169507089e-06 2.62007752319124e-06 -4.61108905404079e-05 -1.35818889248524e-05 1.28364621781714e-05 2.11079163568243e-05 -1.13262174158387e-05 -6.65704267536683e-06 -9.97824633197628e-06 6.4526415019035e-06 -8.81172169507089e-06 -1.13262174158387e-05 2.44802445185867e-05 2.0818391455801e-06 7.47607227154947e-06 5.48756163105732e-06 2.62007752319124e-06 -6.65704267536683e-06 2.0818391455801e-06 5.54364648098258e-05 3.37427310445806e-07 3.0393450571928e-06 -4.61108905404079e-05 -9.97824633197628e-06 7.47607227154947e-06 3.37427310445806e-07 4.10253123916683e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 999 0 0 0 0 0 2590 +1104 1105 0.999998900298536 -0.000197364812101872 0.00146984653968179 0.0025940654546358 0.000192396165628329 0.999994270089767 0.00337975906675747 -0.0043853721831743 -0.00147050516310622 -0.00337947255719317 0.999993208366837 -0.00545464946283394 3.15855327779982e-05 -1.62098675958238e-05 -3.81834676762414e-06 -1.28231484364885e-06 -6.6999372352567e-06 2.57959074322231e-05 -1.62098675958238e-05 0.000107412532013749 2.73124484477136e-05 -1.5515681457392e-05 -3.85200421167391e-06 -5.0005590380311e-05 -3.81834676762414e-06 2.73124484477136e-05 2.6093859441652e-05 -1.58372440466417e-05 -1.45465465099681e-05 -2.32605786061419e-06 -1.28231484364885e-06 -1.5515681457392e-05 -1.58372440466417e-05 2.84593479175031e-05 9.44915741766702e-06 1.87002739319858e-06 -6.6999372352567e-06 -3.85200421167391e-06 -1.45465465099681e-05 9.44915741766702e-06 5.4003648273757e-05 -1.78741925279136e-05 2.57959074322231e-05 -5.0005590380311e-05 -2.32605786061419e-06 1.87002739319858e-06 -1.78741925279136e-05 8.38151295305488e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 831 0 0 0 0 0 2622 +1105 1106 0.999998839004739 -2.37410814266963e-05 0.00152362250424351 -0.00032351327406876 2.28482072820389e-05 0.999999828020272 0.000586035311139194 0.000738989229211506 -0.00152363615532337 -0.000585999818712178 0.999998667567652 -0.00141002080736301 3.4336113102459e-05 -2.530077319244e-05 -1.33662688879505e-05 6.01422993018161e-06 -3.00496275139209e-06 3.32681867706457e-05 -2.530077319244e-05 0.000118447121870111 2.17527430084919e-05 -1.3659713131396e-05 1.5485841571851e-05 -6.32444090216937e-05 -1.33662688879505e-05 2.17527430084919e-05 2.33423482102778e-05 -1.61933685579438e-05 -5.00111276165082e-06 -1.2736084984887e-05 6.01422993018161e-06 -1.3659713131396e-05 -1.61933685579438e-05 3.18918289121997e-05 -2.52808524940478e-06 7.09686377445565e-06 -3.00496275139209e-06 1.5485841571851e-05 -5.00111276165082e-06 -2.52808524940478e-06 7.17145508429271e-05 -6.81042876339435e-06 3.32681867706457e-05 -6.32444090216937e-05 -1.2736084984887e-05 7.09686377445565e-06 -6.81042876339435e-06 8.8024762615109e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 870 0 0 0 0 0 2639 +1107 1108 0.999995194539396 6.64623052744319e-05 0.00309943234760269 0.00273870951956882 -7.19963632978061e-05 0.999998403527619 0.00178542956654684 -0.00471539108808322 -0.00309930873567965 -0.00178564413459271 0.999993602859731 -0.00340578762247742 2.96681575569988e-05 -2.63501948351435e-05 -1.73952605558202e-05 8.23945700854144e-06 2.99359342506574e-06 2.09316617486128e-05 -2.63501948351435e-05 0.000138881065680885 1.74841901755481e-05 -4.98177976621403e-06 2.31924903853193e-05 -9.15277811926813e-05 -1.73952605558202e-05 1.74841901755481e-05 2.40587075525338e-05 -1.52955993454013e-05 -9.14787129731547e-06 -1.51909531912684e-05 8.23945700854144e-06 -4.98177976621403e-06 -1.52955993454013e-05 2.88455392500781e-05 7.93605247865161e-06 6.1772465396093e-06 2.99359342506574e-06 2.31924903853193e-05 -9.14787129731547e-06 7.93605247865161e-06 5.58402141074128e-05 -1.43551288026994e-05 2.09316617486128e-05 -9.15277811926813e-05 -1.51909531912684e-05 6.1772465396093e-06 -1.43551288026994e-05 8.21755592696452e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 786 0 0 0 0 0 2577 +1111 1112 0.999946264741313 0.000687203125287729 -0.0103438571993142 -0.000150168865171281 -0.000737037534036264 0.999988137469503 -0.00481473737063144 -0.005920175539717 0.0103404257924241 0.00482210246047593 0.999934909342749 0.014272758472986 2.73465323202623e-05 -1.54280954016749e-05 -1.53431251622516e-05 8.20698902555298e-06 2.35411961261418e-06 2.14305518737744e-05 -1.54280954016749e-05 9.80497828279544e-05 1.56721840981737e-05 -1.00673117481959e-05 8.74674310457332e-06 -6.0473093871298e-05 -1.53431251622516e-05 1.56721840981737e-05 2.55805825802063e-05 -1.50334759653791e-05 -9.45614092716915e-06 -1.53872923344297e-05 8.20698902555298e-06 -1.00673117481959e-05 -1.50334759653791e-05 2.88487939349143e-05 9.31715286732851e-06 9.28441723513068e-06 2.35411961261418e-06 8.74674310457332e-06 -9.45614092716915e-06 9.31715286732851e-06 5.31307131507268e-05 -1.65238640592047e-06 2.14305518737744e-05 -6.0473093871298e-05 -1.53872923344297e-05 9.28441723513068e-06 -1.65238640592047e-06 7.51417562032716e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 913 0 0 0 0 0 2727 +1108 1109 0.999984670336824 -0.000458970758940345 0.00551801025688755 0.00157772429224278 0.000454904247752641 0.999999624072475 0.000738184959292802 -0.0012719030749528 -0.00551834698782662 -0.000735663476861014 0.99998450320281 -0.00324501761252521 3.13803521554125e-05 -2.17124808363173e-05 -1.56993129564716e-05 5.7541146026316e-06 1.64318008375853e-06 1.26088997983297e-05 -2.17124808363173e-05 0.000120631961529594 2.01903225233323e-05 -7.99753098696232e-06 1.57473142004968e-05 -7.17464331129959e-05 -1.56993129564716e-05 2.01903225233323e-05 2.39798001273389e-05 -1.43942170057303e-05 -6.82420508619669e-06 -1.13833050902722e-05 5.7541146026316e-06 -7.99753098696232e-06 -1.43942170057303e-05 2.81124090545134e-05 1.01766819064047e-05 6.89437143155444e-06 1.64318008375853e-06 1.57473142004968e-05 -6.82420508619669e-06 1.01766819064047e-05 4.58059921706382e-05 -8.48472399106425e-06 1.26088997983297e-05 -7.17464331129959e-05 -1.13833050902722e-05 6.89437143155444e-06 -8.48472399106425e-06 6.03295338411404e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 890 0 0 0 0 0 2532 +1106 1107 0.999996618056474 -0.000727528126711167 -0.00249691378299058 0.00040507552098723 0.000724240390819139 0.999998870003417 -0.00131737152890075 -0.00301053877938283 0.00249786938632714 0.0013155587078106 0.999996014968967 0.00594589704175096 3.49280668340636e-05 -3.31824954145687e-05 -1.58123962845699e-05 4.62031696202441e-06 7.93400549613808e-06 3.70430894295952e-05 -3.31824954145687e-05 0.00013470394968332 1.50271944956384e-05 -1.74254493071864e-07 7.63965455684943e-07 -8.00047066202174e-05 -1.58123962845699e-05 1.50271944956384e-05 2.29834251605341e-05 -1.52376605632691e-05 -8.65585119609141e-06 -1.18053777499592e-05 4.62031696202441e-06 -1.74254493071864e-07 -1.52376605632691e-05 3.57221768266998e-05 5.77403471130591e-06 1.33772355047422e-06 7.93400549613808e-06 7.63965455684943e-07 -8.65585119609141e-06 5.77403471130591e-06 6.29224106287407e-05 8.31102668069616e-06 3.70430894295952e-05 -8.00047066202174e-05 -1.18053777499592e-05 1.33772355047422e-06 8.31102668069616e-06 9.93467513128835e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 741 0 0 0 0 0 2552 +1113 1114 0.999999095078906 -0.000299755643441752 -0.0013114831007266 0.00204512521200479 0.000296841465856067 0.999997488012732 -0.00222167805274372 -0.00749355474671575 0.00131214576683197 0.00222128673973432 0.999996672073816 0.00387723013955515 5.09585901205204e-05 -9.66608670122924e-06 -9.62529200117909e-06 3.75302342574971e-06 3.3132165860814e-06 4.18885036488396e-05 -9.66608670122924e-06 0.000114354559703321 1.46459087134043e-05 -1.27505834759945e-06 7.05874736127835e-06 -6.83122033716704e-05 -9.62529200117909e-06 1.46459087134043e-05 1.75712897483387e-05 -6.53977626047571e-06 -7.45935301873117e-06 -6.43345053722522e-06 3.75302342574971e-06 -1.27505834759945e-06 -6.53977626047571e-06 2.18175062571204e-05 6.47440828760488e-06 -5.90631319038337e-07 3.3132165860814e-06 7.05874736127835e-06 -7.45935301873117e-06 6.47440828760488e-06 5.0205901454416e-05 -4.54425193604626e-06 4.18885036488396e-05 -6.83122033716704e-05 -6.43345053722522e-06 -5.90631319038337e-07 -4.54425193604626e-06 0.000118335531073813 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1089 0 0 0 0 0 2572 +1110 1111 0.999977699696854 -0.000612629726276996 0.00665017246448702 -0.000873789978939095 0.00059347676775094 0.999995671898636 0.00288166086167983 0.000792466617264595 -0.00665190907297141 -0.00287764987690984 0.999973735273517 -0.00652034583197688 4.19734072405882e-05 -2.70169353957906e-05 -1.78097066377414e-05 1.0569753698364e-05 -1.11651691868711e-06 2.5821806933538e-05 -2.70169353957906e-05 0.000154178624865629 2.55036435447434e-05 -1.96095951994725e-05 2.57995185370485e-05 -8.65677285888985e-05 -1.78097066377414e-05 2.55036435447434e-05 2.66615933307211e-05 -1.62029669833028e-05 -6.16409182399798e-06 -1.32555354133301e-05 1.0569753698364e-05 -1.96095951994725e-05 -1.62029669833028e-05 3.00201508995857e-05 3.85330892533882e-06 9.98408373458137e-06 -1.11651691868711e-06 2.57995185370485e-05 -6.16409182399798e-06 3.85330892533882e-06 6.19416985076026e-05 -1.66369140366311e-05 2.5821806933538e-05 -8.65677285888985e-05 -1.32555354133301e-05 9.98408373458137e-06 -1.66369140366311e-05 8.48609671232322e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 841 0 0 0 0 0 2581 +1109 1110 0.999971464933753 -0.000440665144852763 0.00754156034740177 0.00296061387106537 0.000430159507864317 0.999998935029532 0.00139459764805268 0.00111733514516242 -0.0075421668664373 -0.00139131377922884 0.999970589549976 -0.00412329251820107 3.71721092056633e-05 -4.23427934078081e-05 -1.75674932757407e-05 5.63454216732574e-06 1.45673095967971e-06 3.43567537002009e-05 -4.23427934078081e-05 0.000161153561413965 2.70085801619362e-05 -1.55367991337075e-05 5.38198802769049e-06 -0.000103128191665447 -1.75674932757407e-05 2.70085801619362e-05 2.47599183788776e-05 -1.27141995140196e-05 -8.90102342166333e-06 -1.90038221847291e-05 5.63454216732574e-06 -1.55367991337075e-05 -1.27141995140196e-05 2.83297062951602e-05 1.48784069534442e-05 1.56292050019927e-05 1.45673095967971e-06 5.38198802769049e-06 -8.90102342166333e-06 1.48784069534442e-05 4.00180008533149e-05 -1.56609426339075e-06 3.43567537002009e-05 -0.000103128191665447 -1.90038221847291e-05 1.56292050019927e-05 -1.56609426339075e-06 9.72907208344893e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 847 0 0 0 0 0 2547 +1114 1115 0.999998751731494 -0.000283105388976803 0.00155447315575946 0.00166922348493892 0.000282491533829498 0.999999882046737 0.000395101309475741 -0.0046720299850229 -0.00155458482771419 -0.000394661690777153 0.999998713753254 0.000636188613365133 2.55823092911369e-05 -1.39581428373388e-05 -1.58893522710532e-05 5.10397941699534e-06 5.18640665566191e-06 1.11314586527025e-05 -1.39581428373388e-05 9.85684024382756e-05 1.53346833196755e-05 -1.65690585766673e-06 -9.45767817846534e-07 -6.2218532547579e-05 -1.58893522710532e-05 1.53346833196755e-05 2.48724642344673e-05 -1.36761697028873e-05 -7.34270117315701e-06 -1.18261443529923e-05 5.10397941699534e-06 -1.65690585766673e-06 -1.36761697028873e-05 2.51848721124607e-05 8.19781079782566e-06 -5.98026872506683e-07 5.18640665566191e-06 -9.45767817846534e-07 -7.34270117315701e-06 8.19781079782566e-06 3.726662871256e-05 1.82581729958826e-06 1.11314586527025e-05 -6.2218532547579e-05 -1.18261443529923e-05 -5.98026872506683e-07 1.82581729958826e-06 6.32014663600338e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1116 0 0 0 0 0 2545 +1121 1122 0.999980906654852 -0.000635414911673693 0.00614675309650308 0.0023358928003009 0.000623981486440163 0.999998072145049 0.0018618145157226 0.00468289705805268 -0.00614792427116075 -0.00185794350732151 0.999979375323851 -0.002446958986721 2.51093624516795e-05 -3.70385594009223e-06 -1.02416052941487e-05 1.64527688260114e-06 3.17815706218825e-06 3.45790490431938e-06 -3.70385594009223e-06 0.000105305452043659 1.47522275876305e-05 3.06733433352581e-06 1.12330167020699e-05 -5.26407907675481e-05 -1.02416052941487e-05 1.47522275876305e-05 1.93949907347272e-05 -6.77254655318208e-06 -7.38519314772391e-06 -7.67663001453406e-06 1.64527688260114e-06 3.06733433352581e-06 -6.77254655318208e-06 2.0857910356276e-05 1.04385023230624e-05 -8.44446034179741e-07 3.17815706218825e-06 1.12330167020699e-05 -7.38519314772391e-06 1.04385023230624e-05 3.68719260846345e-05 -3.35263143542229e-06 3.45790490431938e-06 -5.26407907675481e-05 -7.67663001453406e-06 -8.44446034179741e-07 -3.35263143542229e-06 5.17234309522352e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1374 0 0 0 0 0 2546 +1115 1116 0.999977314036385 -8.17625178181551e-06 -0.00673582554157466 -0.000947603298114488 -3.71674652657082e-06 0.999998441286733 -0.00176561895384207 -0.00460513652370747 0.00673582947849914 0.00176560393443091 0.99997575532809 0.00657379688308637 5.17485777786462e-05 -5.27677059799007e-06 -1.60164533620451e-06 -5.42036874307514e-06 1.36015448485119e-06 4.36312455107756e-05 -5.27677059799007e-06 0.000117931124153855 1.92675002077693e-05 1.71004423506748e-06 7.67581639461801e-07 -5.83687089947695e-05 -1.60164533620451e-06 1.92675002077693e-05 2.15043648210902e-05 -7.70888233303671e-06 -7.99808705246475e-06 -1.97966043571518e-06 -5.42036874307514e-06 1.71004423506748e-06 -7.70888233303671e-06 2.14203566996009e-05 6.60677625623817e-06 -5.67876768174307e-06 1.36015448485119e-06 7.67581639461801e-07 -7.99808705246475e-06 6.60677625623817e-06 4.773376733635e-05 -1.59411542253291e-08 4.36312455107756e-05 -5.83687089947695e-05 -1.97966043571518e-06 -5.67876768174307e-06 -1.59411542253291e-08 0.00011966948587945 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1124 0 0 0 0 0 2691 +1116 1117 0.999990147862512 -0.000457002176683885 0.00441535127947129 0.00551280935392371 0.000455079754904749 0.999999801233141 0.000436389842756272 -0.00779125640693562 -0.00441554983295381 -0.000434376206405463 0.99999015707005 -0.00245523692337655 2.35348658506263e-05 -1.23288450060185e-05 -8.11931199323193e-06 -2.06909912818997e-06 9.96688249066444e-07 1.25978050320772e-05 -1.23288450060185e-05 9.45399891218803e-05 1.94706922945266e-05 2.04738639833289e-07 5.24488798874541e-06 -3.626418680864e-05 -8.11931199323193e-06 1.94706922945266e-05 1.93865787449295e-05 -5.91389020899556e-06 -2.04712802084585e-06 -6.09518446221e-06 -2.06909912818997e-06 2.04738639833289e-07 -5.91389020899556e-06 2.03005258883064e-05 3.79611503768275e-06 -2.56801032849405e-06 9.96688249066444e-07 5.24488798874541e-06 -2.04712802084585e-06 3.79611503768275e-06 3.75919931760354e-05 -1.11552292962966e-06 1.25978050320772e-05 -3.626418680864e-05 -6.09518446221e-06 -2.56801032849405e-06 -1.11552292962966e-06 4.57751739135271e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1173 0 0 0 0 0 2547 +1120 1121 0.999984004991784 -0.000803784982532442 0.00559854358682484 0.000898968519125073 0.000795567207258276 0.999998603211834 0.0014699140112433 -0.000134895802006105 -0.00559971726165326 -0.00146543648227053 0.999983247690933 -0.00671672186746579 2.4209279955019e-05 1.09629467876642e-07 -9.59480847669756e-06 3.32455546841476e-06 4.32771839026109e-06 7.71407359304993e-06 1.09629467876642e-07 6.80020823818279e-05 9.87579874866311e-06 4.70832011322106e-07 1.79613089419646e-06 -2.61816999123165e-05 -9.59480847669756e-06 9.87579874866311e-06 1.86725630878818e-05 -5.79874046249563e-06 -7.0715327856954e-06 -3.72430947680173e-06 3.32455546841476e-06 4.70832011322106e-07 -5.79874046249563e-06 1.81156142308868e-05 3.49109697750384e-06 1.80337909973774e-07 4.32771839026109e-06 1.79613089419646e-06 -7.0715327856954e-06 3.49109697750384e-06 4.34736585183876e-05 1.06669674887945e-06 7.71407359304993e-06 -2.61816999123165e-05 -3.72430947680173e-06 1.80337909973774e-07 1.06669674887945e-06 4.51259949243815e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1358 0 0 0 0 0 2596 +1117 1118 0.99999972565334 -0.000119786623344421 0.000730988652640829 0.00249201494778042 0.000119199685224639 0.999999670548866 0.000802928138293936 -0.00672729157912454 -0.000731084591866263 -0.000802840784395985 0.999999410480823 0.00154553052017202 2.09529663454581e-05 -1.09908016547519e-05 -1.11261186508122e-05 3.08015925227375e-06 -9.19182179847409e-07 1.10663841222067e-05 -1.09908016547519e-05 6.82578484066834e-05 1.00228998917402e-05 -2.91816061836967e-06 6.58394551278548e-06 -3.77764426481638e-05 -1.11261186508122e-05 1.00228998917402e-05 2.01331524493717e-05 -9.99432388901903e-06 -6.31368471781874e-06 -5.74841102736484e-06 3.08015925227375e-06 -2.91816061836967e-06 -9.99432388901903e-06 2.0094092289834e-05 6.3163565264349e-06 2.06221967279947e-06 -9.19182179847409e-07 6.58394551278548e-06 -6.31368471781874e-06 6.3163565264349e-06 4.54745977785734e-05 -5.01514021644238e-06 1.10663841222067e-05 -3.77764426481638e-05 -5.74841102736484e-06 2.06221967279947e-06 -5.01514021644238e-06 4.62060450708619e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1207 0 0 0 0 0 2662 +1122 1123 0.999999776069366 -0.00022792758002278 -0.000629213981952728 -0.000339068402140535 0.000225745237905086 0.999993967031341 -0.00346625734897582 -0.00127514175758848 0.000630000241573783 0.00346611453071456 0.999993794555624 0.0026444228307583 4.10568917213494e-05 -3.68340948485468e-05 -1.43620978792602e-05 -2.84472619088923e-07 -7.92929253863297e-07 3.67399227639049e-05 -3.68340948485468e-05 0.000138195231813258 2.32949372581184e-05 3.33518511212744e-06 4.34386238671435e-06 -8.60918735445578e-05 -1.43620978792602e-05 2.32949372581184e-05 2.36285685753766e-05 -8.41719719422868e-06 -6.82829001065889e-06 -1.18257669743204e-05 -2.84472619088923e-07 3.33518511212744e-06 -8.41719719422868e-06 1.98256689143498e-05 9.74202442268565e-06 -5.43333701793854e-06 -7.92929253863297e-07 4.34386238671435e-06 -6.82829001065889e-06 9.74202442268565e-06 3.04592366374194e-05 -3.86739764253042e-06 3.67399227639049e-05 -8.60918735445578e-05 -1.18257669743204e-05 -5.43333701793854e-06 -3.86739764253042e-06 9.96988299730759e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1241 0 0 0 0 0 2624 +1112 1113 0.999997539614423 -0.000654991806123472 0.00211937510481564 0.000354059752359391 0.000650600647836971 0.999997641892437 0.00207193831042109 -0.00206577112945189 -0.0021207272097173 -0.00207055434583775 0.999995607650755 -0.000830034129098023 2.09134771201295e-05 -1.15265239518581e-05 -1.28787480358697e-05 5.2066723132168e-06 4.35003506153242e-06 9.34054915974169e-06 -1.15265239518581e-05 9.24540271100906e-05 1.97097496161951e-05 -5.89737974554246e-06 -7.95267231022158e-06 -5.29068418523329e-05 -1.28787480358697e-05 1.97097496161951e-05 2.40481736137509e-05 -1.32047599250892e-05 -1.00268035634732e-05 -1.03823300740615e-05 5.2066723132168e-06 -5.89737974554246e-06 -1.32047599250892e-05 2.64541939207204e-05 1.75230494574389e-06 1.27441382890613e-06 4.35003506153242e-06 -7.95267231022158e-06 -1.00268035634732e-05 1.75230494574389e-06 5.28388620926216e-05 2.66696564492197e-06 9.34054915974169e-06 -5.29068418523329e-05 -1.03823300740615e-05 1.27441382890613e-06 2.66696564492197e-06 5.43337843651562e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 938 0 0 0 0 0 2727 +1119 1120 0.99999784107216 0.000175869434506169 -0.00207048809747438 0.00331490382431002 -0.000170809054384949 0.999996998900805 0.00244397496908937 -0.0108490547693449 0.00207091170422998 -0.00244361603460972 0.999994870019536 -0.000378380191805894 2.65239809492815e-05 7.62499566835454e-07 -1.23596024001394e-05 4.55217266121879e-06 3.73980204338986e-06 1.37649054328321e-05 7.62499566835454e-07 7.23657572109243e-05 7.78134762834855e-06 3.81154931079374e-06 1.47455498919969e-06 -3.17607533230602e-05 -1.23596024001394e-05 7.78134762834855e-06 1.90586006347997e-05 -7.77211795396182e-06 -5.3866507404435e-06 -7.33505412706933e-06 4.55217266121879e-06 3.81154931079374e-06 -7.77211795396182e-06 2.2789345170552e-05 -2.44984775858097e-06 1.01506837675723e-06 3.73980204338986e-06 1.47455498919969e-06 -5.3866507404435e-06 -2.44984775858097e-06 5.21781068466653e-05 9.55692090343722e-07 1.37649054328321e-05 -3.17607533230602e-05 -7.33505412706933e-06 1.01506837675723e-06 9.55692090343722e-07 5.02047143141629e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1247 0 0 0 0 0 2637 +1118 1119 0.999992886344503 6.76763224625807e-05 0.00377129689964473 0.00126518315078466 -6.80290185588514e-05 0.999999993324903 9.33929686225748e-05 0.00110529817365488 -0.0037712905539783 -9.36488618839471e-05 0.999992884273407 -0.00187416325459603 2.34840428936199e-05 -8.0358298602969e-06 -9.79865352076115e-06 2.2293425015465e-06 -9.25811404035307e-08 6.71071941052214e-06 -8.0358298602969e-06 7.25124983626049e-05 1.47840369405018e-05 -1.44414690943732e-06 6.46324335126486e-07 -3.85178706935468e-05 -9.79865352076115e-06 1.47840369405018e-05 2.0236589197428e-05 -7.29165112663747e-06 -3.41421782949192e-06 -7.99510414513045e-06 2.2293425015465e-06 -1.44414690943732e-06 -7.29165112663747e-06 2.14781953724553e-05 4.02528430468898e-06 -1.20486938232147e-06 -9.25811404035307e-08 6.46324335126486e-07 -3.41421782949192e-06 4.02528430468898e-06 4.02118971883067e-05 -3.4703848183838e-06 6.71071941052214e-06 -3.85178706935468e-05 -7.99510414513045e-06 -1.20486938232147e-06 -3.4703848183838e-06 4.86688491809572e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1255 0 0 0 0 0 2691 +1124 1125 0.999988985678449 -0.000113523944638998 0.00469208206450168 0.000708181724765722 0.000107920331429646 0.999999280754038 0.00119450601031639 0.00129254838651635 -0.00469221429477478 -0.0011939864825916 0.999988278691951 -0.00374091159355209 2.820009137282e-05 -2.21385952779423e-05 -1.57075776192831e-05 2.28714581130036e-06 2.08041200439449e-06 1.35062079050623e-05 -2.21385952779423e-05 0.000101206404940691 1.62302069387598e-05 4.05604565604397e-06 1.02664023279144e-05 -5.43142847272404e-05 -1.57075776192831e-05 1.62302069387598e-05 2.18951478034429e-05 -8.67822996252165e-06 -4.56733058195541e-06 -9.42853950625816e-06 2.28714581130036e-06 4.05604565604397e-06 -8.67822996252165e-06 2.0989093297263e-05 7.90719028916503e-06 -1.00759702235493e-06 2.08041200439449e-06 1.02664023279144e-05 -4.56733058195541e-06 7.90719028916503e-06 3.1647466206369e-05 -6.9674522440555e-06 1.35062079050623e-05 -5.43142847272404e-05 -9.42853950625816e-06 -1.00759702235493e-06 -6.9674522440555e-06 5.14456363004789e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1366 0 0 0 0 0 2610 +1127 1128 0.999985283526471 -0.000718604748006707 -0.00537739134713498 -0.000515893344563902 0.000713034858016734 0.999999207438579 -0.00103764324557833 -2.9106142665426e-05 0.00537813274058506 0.00103379370765327 0.999985003366948 0.00569119010959077 0.000118119664944202 -0.000308546028005905 -1.32238421424592e-05 -4.63724557199096e-05 -1.77224906552027e-05 0.000236865927974378 -0.000308546028005905 0.00103407767973871 2.13678478294078e-05 0.000156917958392115 6.31935198135204e-05 -0.00077964203074675 -1.32238421424592e-05 2.13678478294078e-05 2.6359999865814e-05 -7.94691573533348e-06 -6.23105574369489e-06 -8.53062850817819e-06 -4.63724557199096e-05 0.000156917958392115 -7.94691573533348e-06 4.7178929661241e-05 2.10970899416623e-05 -0.000123684224676784 -1.77224906552027e-05 6.31935198135204e-05 -6.23105574369489e-06 2.10970899416623e-05 3.78847872344021e-05 -5.24365278354702e-05 0.000236865927974378 -0.00077964203074675 -8.53062850817819e-06 -0.000123684224676784 -5.24365278354702e-05 0.000618021293119572 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1288 0 0 0 0 0 2715 +1123 1124 0.999987136882101 -0.000696395220586986 0.00502405255092062 0.00475309491673576 0.000681218855488696 0.999995202258408 0.00302182081468208 -0.0105835759767786 -0.00502613282838755 -0.00301835946531602 0.999982813599778 -0.0071993411845491 2.56612041869278e-05 -1.10633110322172e-05 -1.1559453457467e-05 4.17647069650281e-06 2.34540677719925e-06 1.3961053047539e-05 -1.10633110322172e-05 8.2022490004126e-05 1.5577945194556e-05 -7.8863195827e-07 -5.3677625478344e-07 -3.86645053056289e-05 -1.1559453457467e-05 1.5577945194556e-05 1.9166051664575e-05 -8.3012745233936e-06 -5.52461495812313e-06 -6.90401043784837e-06 4.17647069650281e-06 -7.8863195827e-07 -8.3012745233936e-06 2.09338810633481e-05 -7.67906224272069e-07 7.73750377607672e-07 2.34540677719925e-06 -5.3677625478344e-07 -5.52461495812313e-06 -7.67906224272069e-07 4.61948999516874e-05 4.5055375693191e-06 1.3961053047539e-05 -3.86645053056289e-05 -6.90401043784837e-06 7.73750377607672e-07 4.5055375693191e-06 5.53484616535204e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1350 0 0 0 0 0 2732 +1126 1127 0.999992733763546 -0.000708557316975956 0.00374571310138041 0.000229227891429521 0.000706711192853573 0.999999628180648 0.000494163794074383 0.00110284327233876 -0.00374606185202387 -0.000491513065989445 0.999992862692283 -0.00317955683987505 2.20309994947419e-05 -5.03685128367729e-06 -1.2023354899922e-05 4.15702400187435e-06 1.30139633775443e-06 5.20726007032706e-06 -5.03685128367729e-06 7.14008450261617e-05 1.14892993600375e-05 -1.38266078638833e-06 4.84680442012594e-06 -3.72965591414245e-05 -1.2023354899922e-05 1.14892993600375e-05 2.10559139150963e-05 -9.94577309669968e-06 -5.73938872140003e-06 -7.07186159833086e-06 4.15702400187435e-06 -1.38266078638833e-06 -9.94577309669968e-06 1.81562910046829e-05 8.96683848860528e-06 1.77873370959953e-06 1.30139633775443e-06 4.84680442012594e-06 -5.73938872140003e-06 8.96683848860528e-06 3.09566167933202e-05 5.14368338269083e-07 5.20726007032706e-06 -3.72965591414245e-05 -7.07186159833086e-06 1.77873370959953e-06 5.14368338269083e-07 4.24646101225575e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1288 0 0 0 0 0 2772 +1128 1129 0.999999441950844 -0.000377224482542007 -0.000986812894943888 -0.000468755452545855 0.000375642469492783 0.999998644883915 -0.00160284842377603 -0.00207449810276888 0.000987416191365112 0.00160247684047504 0.999998228537051 0.00528987514843838 3.23242043731154e-05 -4.60842470429566e-06 -1.0672871685554e-05 4.41561406358803e-06 3.81769828127546e-06 2.27825930059348e-05 -4.60842470429566e-06 8.00940229859231e-05 1.00509830000378e-05 2.39695328015345e-06 7.18397279614887e-06 -3.84338316561823e-05 -1.0672871685554e-05 1.00509830000378e-05 1.93156237085112e-05 -8.9142763891179e-06 -8.65606450268791e-06 -6.91317158551039e-06 4.41561406358803e-06 2.39695328015345e-06 -8.9142763891179e-06 1.98229047801606e-05 8.97174442040963e-06 1.00227005080844e-06 3.81769828127546e-06 7.18397279614887e-06 -8.65606450268791e-06 8.97174442040963e-06 3.3041759461798e-05 -3.8055200205535e-06 2.27825930059348e-05 -3.84338316561823e-05 -6.91317158551039e-06 1.00227005080844e-06 -3.8055200205535e-06 6.65239594385514e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1368 0 0 0 0 0 2584 +1132 1133 0.999985619753746 -0.000631587709399385 0.00532554060006475 -0.000473001289821938 0.00063249199622634 0.999999785844848 -0.000168119400694504 0.00498364510784926 -0.00532543327742561 0.000171485344901241 0.999985805075844 -0.00168923600918946 3.3730659885212e-05 3.67301194932195e-06 -1.39289462584821e-05 4.11618996561887e-06 7.38623059979443e-06 1.64895553842696e-05 3.67301194932195e-06 0.000103934763357982 1.05672494161163e-05 7.19242839117868e-06 8.04784137916203e-06 -4.76373288408273e-05 -1.39289462584821e-05 1.05672494161163e-05 2.13306009603767e-05 -8.01803256224492e-06 -7.21656394312926e-06 -8.78315800686127e-06 4.11618996561887e-06 7.19242839117868e-06 -8.01803256224492e-06 2.00924334660689e-05 8.13520518624574e-06 -1.32707745047538e-06 7.38623059979443e-06 8.04784137916203e-06 -7.21656394312926e-06 8.13520518624574e-06 3.2998625724285e-05 -3.35014990965238e-06 1.64895553842696e-05 -4.76373288408273e-05 -8.78315800686127e-06 -1.32707745047538e-06 -3.35014990965238e-06 7.91238476785946e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1261 0 0 0 0 0 2541 +1129 1130 0.999983988189091 0.000901002546368257 0.00558673069443562 0.000445172690410821 -0.000916920639081059 0.999995525884276 0.00284736158097158 0.00272012906152715 -0.00558414021872109 -0.00285243857823507 0.999980340292836 -0.00820589417911597 2.75991648511955e-05 3.97409550678381e-07 -9.02208403615863e-06 1.75416876290115e-06 3.10772022707606e-06 1.09584256666423e-05 3.97409550678381e-07 7.15979217565119e-05 1.15900450288218e-05 3.33674044908188e-06 -2.05142649985755e-06 -2.91832697042318e-05 -9.02208403615863e-06 1.15900450288218e-05 1.92256443159272e-05 -6.50895359580153e-06 -6.91017714766707e-06 -6.28280600937718e-06 1.75416876290115e-06 3.33674044908188e-06 -6.50895359580153e-06 1.86791469915278e-05 5.93353362540321e-06 -7.94322742619556e-07 3.10772022707606e-06 -2.05142649985755e-06 -6.91017714766707e-06 5.93353362540321e-06 3.30367756932695e-05 2.66226378930997e-06 1.09584256666423e-05 -2.91832697042318e-05 -6.28280600937718e-06 -7.94322742619556e-07 2.66226378930997e-06 4.97316034462971e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1285 0 0 0 0 0 2560 +1133 1134 0.999997654340089 0.000481464456973842 -0.00211175431730064 -0.00108318401616565 -0.000479678885008668 0.999999527125895 0.000845964628553456 0.00670595620316893 0.00211216062060721 -0.000844949680251806 0.999997412415428 0.00137763357651608 2.65973497397376e-05 -1.31042073209121e-05 -1.23531302566641e-05 3.57233756151519e-06 1.91755793227424e-07 1.4111262578658e-05 -1.31042073209121e-05 9.8579903345391e-05 1.24388519476896e-05 4.99975910714228e-06 3.29877671827481e-06 -5.48886899096503e-05 -1.23531302566641e-05 1.24388519476896e-05 2.0076964250814e-05 -7.52170060514343e-06 -4.73576915762657e-06 -7.62172657974771e-06 3.57233756151519e-06 4.99975910714228e-06 -7.52170060514343e-06 1.98896210051941e-05 5.78101853118066e-06 -3.64830767847122e-07 1.91755793227424e-07 3.29877671827481e-06 -4.73576915762657e-06 5.78101853118066e-06 3.49835931020976e-05 -6.82502293833971e-06 1.4111262578658e-05 -5.48886899096503e-05 -7.62172657974771e-06 -3.64830767847122e-07 -6.82502293833971e-06 6.47234560113696e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1271 0 0 0 0 0 2566 +1131 1132 0.999999410742185 4.48101586247632e-06 0.00108558518972955 -0.00127140018533969 -4.8133131360266e-06 0.99999995314065 0.000306097255553171 0.00411891536230858 -0.00108558376723308 -0.000306102300444425 0.999999363904431 -0.000887033946923399 2.75107727453708e-05 -2.71925029118092e-05 -1.35795494139335e-05 1.7563087757748e-06 -4.22456618718722e-07 1.94688154935711e-05 -2.71925029118092e-05 0.000118800894761529 1.90997354531114e-05 3.25615770249776e-06 4.00861856861886e-06 -6.642257755641e-05 -1.35795494139335e-05 1.90997354531114e-05 2.10129665066764e-05 -8.00975292712356e-06 -6.79027931124218e-06 -9.57783422900332e-06 1.7563087757748e-06 3.25615770249776e-06 -8.00975292712356e-06 1.89957031159379e-05 6.87368733326452e-06 -3.67362209000419e-06 -4.22456618718722e-07 4.00861856861886e-06 -6.79027931124218e-06 6.87368733326452e-06 3.59548288973501e-05 -3.84912369333663e-06 1.94688154935711e-05 -6.642257755641e-05 -9.57783422900332e-06 -3.67362209000419e-06 -3.84912369333663e-06 6.27739777187113e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1368 0 0 0 0 0 2424 +1130 1131 0.979499640527824 -0.0927023659249973 -0.178848331157355 -0.638600324576457 0.0902881556898986 0.995681217451783 -0.0216093071580623 0.862368951329901 0.180079158005528 0.0050184226249635 0.983639320221786 0.0494269802590756 0.00708946316992863 0.000501366884524685 -0.000472720422236235 0.00476343125697157 0.0112353179947863 0.00204761384672901 0.000501366884524685 0.0362393315638574 -0.0205545822075524 0.0384663262965408 0.0460031495953825 -0.0365112035452365 -0.000472720422236235 -0.0205545822075524 0.0133640556517433 -0.0224548066145778 -0.0252810341896614 0.0207227261004872 0.00476343125697157 0.0384663262965408 -0.0224548066145778 0.0439153078034091 0.0548926431940368 -0.0373332490377302 0.0112353179947863 0.0460031495953825 -0.0252810341896614 0.0548926431940368 0.0769434599465946 -0.0432632507249472 0.00204761384672901 -0.0365112035452365 0.0207227261004872 -0.0373332490377302 -0.0432632507249472 0.0387258781833483 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 464 0 0 0 0 0 819 +1125 1126 0.99999944361132 -0.000567579813664576 0.000889173889055663 0.000454518037670488 0.000568156146946227 0.999999628615688 -0.000648048670044933 -0.00335210363082958 -0.000888805739487041 0.00064855349908876 0.999999394701175 0.000533428723367497 4.91225027549764e-05 -2.15666785976323e-05 -1.27880093409396e-05 3.65657075464842e-06 1.80913052776146e-06 5.64539752988034e-05 -2.15666785976323e-05 0.000104514372278284 1.15835797899067e-05 5.5635928768291e-06 3.07779676544196e-07 -6.94375831572128e-05 -1.27880093409396e-05 1.15835797899067e-05 2.1512017306262e-05 -1.13512257174024e-05 -7.95396818102178e-06 -8.8708001022497e-06 3.65657075464842e-06 5.5635928768291e-06 -1.13512257174024e-05 2.4525757931523e-05 1.23384359465331e-05 -2.12355494055675e-07 1.80913052776146e-06 3.07779676544196e-07 -7.95396818102178e-06 1.23384359465331e-05 2.96827597064716e-05 -4.960959092165e-07 5.64539752988034e-05 -6.94375831572128e-05 -8.8708001022497e-06 -2.12355494055675e-07 -4.960959092165e-07 0.000128841490597985 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1264 0 0 0 0 0 2699 +1138 1139 0.999970698369128 -0.00104732390304186 0.00758323913646923 -0.00072366792136495 0.00101184032186173 0.999988529628246 0.00468153725846512 0.0098446240597792 -0.00758805523977101 -0.00467372705465985 0.999960288058029 -0.00545087238463717 2.26906234148272e-05 -6.81133017955326e-06 -1.05777368509715e-05 3.46811744897587e-06 3.71960889521629e-06 8.93606683545912e-06 -6.81133017955326e-06 8.33697234995194e-05 1.33988962454737e-05 -4.11018575223416e-06 7.85672935951726e-06 -2.92504395029531e-05 -1.05777368509715e-05 1.33988962454737e-05 2.07158315861766e-05 -9.83243187392483e-06 -5.57163388634967e-06 -4.58960088201039e-06 3.46811744897587e-06 -4.11018575223416e-06 -9.83243187392483e-06 2.5271482305397e-05 4.31860271204833e-06 1.83891689133431e-06 3.71960889521629e-06 7.85672935951726e-06 -5.57163388634967e-06 4.31860271204833e-06 5.04583666516202e-05 -3.61748124270706e-06 8.93606683545912e-06 -2.92504395029531e-05 -4.58960088201039e-06 1.83891689133431e-06 -3.61748124270706e-06 4.86148625842167e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1159 0 0 0 0 0 2668 +1141 1142 0.999998419944344 -5.81627071816406e-05 0.00177671773628439 -0.00258561414713248 5.58180497593114e-05 0.999999127667098 0.00131967775906528 0.00701475288442902 -0.00177679294242613 -0.00131957650098196 0.99999755085935 -0.00371067877241289 4.74500190075193e-05 -6.79796237579003e-06 -1.21887593709322e-05 6.00415840567237e-06 2.20124008192372e-06 4.87972113223451e-05 -6.79796237579003e-06 8.89221480780278e-05 5.53782867688173e-06 8.88922160320741e-06 8.1018602177491e-06 -3.47772149942409e-05 -1.21887593709322e-05 5.53782867688173e-06 1.95577785724809e-05 -1.21328667266777e-05 -7.76122902654246e-06 -4.53097360112285e-06 6.00415840567237e-06 8.88922160320741e-06 -1.21328667266777e-05 2.55939580052255e-05 1.07118374852491e-05 2.16072026922105e-06 2.20124008192372e-06 8.1018602177491e-06 -7.76122902654246e-06 1.07118374852491e-05 3.56166959502625e-05 1.48216972360748e-06 4.87972113223451e-05 -3.47772149942409e-05 -4.53097360112285e-06 2.16072026922105e-06 1.48216972360748e-06 0.000120110816919941 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1239 0 0 0 0 0 2602 +1139 1140 0.999998967645899 -0.000437859296143809 0.00136857092340328 -0.00132479989850578 0.000442760891741602 0.999993481960854 -0.00358329437805738 0.00516081315970119 -0.00136699302425017 0.00358389662851119 0.999992643480455 0.00488829002796728 2.81137199238572e-05 -9.7012498176145e-06 -8.94928390024247e-06 1.00685160581279e-06 -8.5709128712353e-07 1.36908145013207e-05 -9.7012498176145e-06 0.000103048273692917 1.59638178883553e-05 -9.64462361441554e-07 -1.44629097971042e-06 -3.97665932545218e-05 -8.94928390024247e-06 1.59638178883553e-05 1.93574512948421e-05 -9.47197536802623e-06 -8.02261343042424e-06 -4.65036406648382e-06 1.00685160581279e-06 -9.64462361441554e-07 -9.47197536802623e-06 2.62762129232251e-05 7.92513835262529e-06 -1.52670587463839e-06 -8.5709128712353e-07 -1.44629097971042e-06 -8.02261343042424e-06 7.92513835262529e-06 5.39633990876278e-05 -5.14852277312427e-06 1.36908145013207e-05 -3.97665932545218e-05 -4.65036406648382e-06 -1.52670587463839e-06 -5.14852277312427e-06 5.50181861562409e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1086 0 0 0 0 0 2659 +1137 1138 0.529584161014228 -0.847849935975302 0.0262888278462989 0.386413953943465 0.848160208968771 0.529738256042097 -0.00128062778665286 -0.079691102501542 -0.0128404176297675 0.022975337911627 0.999653568754166 -0.0333140016092273 0.000122718310433951 7.32001436171617e-05 -3.06275449521331e-05 3.46282256123617e-05 2.51018601982119e-05 5.35264906264129e-06 7.32001436171617e-05 0.000255246618667776 9.52133098867158e-05 4.1637451711101e-05 6.52000908186179e-05 -2.92577313677657e-05 -3.06275449521331e-05 9.52133098867158e-05 0.000251249904919651 -5.01367655105273e-05 -3.76000309717262e-05 -6.51017286686109e-05 3.46282256123617e-05 4.1637451711101e-05 -5.01367655105273e-05 0.000250570135895607 0.000154270870572587 -4.50052560880084e-05 2.51018601982119e-05 6.52000908186179e-05 -3.76000309717262e-05 0.000154270870572587 0.000218157690718363 -2.98444996183027e-05 5.35264906264129e-06 -2.92577313677657e-05 -6.51017286686109e-05 -4.50052560880084e-05 -2.98444996183027e-05 0.000113815761976666 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 249 +1144 1145 0.999968134885668 0.00102299970291513 -0.0079172397264674 0.00233920685607959 -0.00106126005189756 0.99998777308791 -0.00482984490278171 0.000738343062338753 0.0079122019931726 0.00483809324946467 0.999956994031908 -0.00059882198807452 2.79967357374679e-05 2.49071408897069e-06 -6.73165914841676e-06 3.05798005780407e-07 4.07445640627524e-06 1.1435486116688e-05 2.49071408897069e-06 7.96848401312593e-05 1.13984702028582e-05 4.79671643529722e-08 5.88208162252009e-07 -2.97349112329794e-05 -6.73165914841676e-06 1.13984702028582e-05 1.74586331055425e-05 -5.98435695082096e-06 -4.3113620340597e-06 -3.08917938047705e-06 3.05798005780407e-07 4.79671643529722e-08 -5.98435695082096e-06 2.15550639036159e-05 5.46699725555728e-06 -3.41655807467898e-06 4.07445640627524e-06 5.88208162252009e-07 -4.3113620340597e-06 5.46699725555728e-06 3.60909683054239e-05 -2.23032167488326e-06 1.1435486116688e-05 -2.97349112329794e-05 -3.08917938047705e-06 -3.41655807467898e-06 -2.23032167488326e-06 5.57531996411291e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1344 0 0 0 0 0 2637 +1134 1135 0.99999286732547 0.000510892762017115 -0.00374223018688393 -0.00308870300567152 -0.000509691042376084 0.999999818242775 0.000322070578961227 0.00389246158306406 0.00374239405023421 -0.000320160900531847 0.999992945967006 -0.00553681696591125 3.84725330344894e-05 -1.52322456463459e-05 -1.04820754079795e-05 2.65826539539112e-06 5.37908571507616e-06 3.03769907710118e-05 -1.52322456463459e-05 0.000114099821302009 1.25327993078157e-05 1.02523891415346e-05 5.16530251069073e-06 -3.4034563062122e-05 -1.04820754079795e-05 1.25327993078157e-05 2.20010103999239e-05 -9.04210523488215e-06 -7.13160692981929e-06 1.01133827416788e-06 2.65826539539112e-06 1.02523891415346e-05 -9.04210523488215e-06 2.31513939818488e-05 6.00779465317766e-06 -4.93443661486897e-06 5.37908571507616e-06 5.16530251069073e-06 -7.13160692981929e-06 6.00779465317766e-06 3.7142964391432e-05 2.08629742491289e-06 3.03769907710118e-05 -3.4034563062122e-05 1.01133827416788e-06 -4.93443661486897e-06 2.08629742491289e-06 9.75966774517066e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1347 0 0 0 0 0 2604 +1135 1136 0.999979325013075 0.000407770145859724 0.00641741925560745 0.000561509692191552 -0.000440260512215597 0.999987089855713 0.00506224185346351 0.00997261019612787 -0.00641527217469995 -0.00506496252796796 0.999966594660799 -0.00884591129673199 2.63572173690469e-05 3.1785170690552e-06 -9.34460100901622e-06 3.05225206735255e-06 4.46830921109473e-06 4.50566810905551e-06 3.1785170690552e-06 7.18544667960989e-05 1.03103068738167e-05 2.8726535971631e-06 7.70593469792222e-06 -3.12303759498323e-05 -9.34460100901622e-06 1.03103068738167e-05 1.9679593019329e-05 -7.430304652771e-06 -6.51399163879477e-06 -5.45011446908885e-06 3.05225206735255e-06 2.8726535971631e-06 -7.430304652771e-06 1.88620846977302e-05 9.00049587312339e-06 -1.62332481866464e-06 4.46830921109473e-06 7.70593469792222e-06 -6.51399163879477e-06 9.00049587312339e-06 3.46570763036176e-05 -8.24874256499917e-07 4.50566810905551e-06 -3.12303759498323e-05 -5.45011446908885e-06 -1.62332481866464e-06 -8.24874256499917e-07 4.94687115142476e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1306 0 0 0 0 0 2535 +1136 1137 0.999994006612617 0.00047978120655593 -0.00342878241336483 -0.00986273394824361 -0.00047941200032576 0.999999879195976 0.000108499615214414 0.0236111557040926 0.00342883405523041 -0.000106855165498716 0.999994115822186 0.000652105984576054 4.56854227519718e-05 1.01158521849717e-05 -1.02913532302762e-05 2.05189868182133e-06 1.07976125463273e-05 1.90799449020019e-05 1.01158521849717e-05 8.72494106076126e-05 9.95961633850822e-06 3.1158683233958e-06 9.32738412223205e-06 -3.75073401054151e-05 -1.02913532302762e-05 9.95961633850822e-06 1.97926641193145e-05 -8.77705961172533e-06 -3.45850510313995e-06 -3.9841085000882e-06 2.05189868182133e-06 3.1158683233958e-06 -8.77705961172533e-06 2.5108764995799e-05 -7.72697205736601e-06 -2.12585175382486e-06 1.07976125463273e-05 9.32738412223205e-06 -3.45850510313995e-06 -7.72697205736601e-06 6.44799461885811e-05 1.67429134824407e-06 1.90799449020019e-05 -3.75073401054151e-05 -3.9841085000882e-06 -2.12585175382486e-06 1.67429134824407e-06 7.78745879452659e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1363 0 0 0 0 0 2584 +1140 1141 0.99999984456659 -7.2174061742304e-05 0.000552863185240241 -0.00356046670632395 7.07461538857826e-05 0.999996663264554 0.00258233513317929 0.0139696875539176 -0.000553047718097395 -0.00258229561885415 0.999996512937699 -0.00534041919593117 2.2883836679311e-05 -4.33191633532017e-06 -8.50850673576568e-06 2.1834109874232e-06 1.17628823504349e-06 1.84918165217679e-05 -4.33191633532017e-06 9.42339753900801e-05 1.69640020850138e-05 -2.96511608809394e-06 -2.57279625574705e-06 -3.24596904009548e-05 -8.50850673576568e-06 1.69640020850138e-05 2.0568973883732e-05 -1.03327675244648e-05 -7.1407133486875e-06 -7.69120768520232e-06 2.1834109874232e-06 -2.96511608809394e-06 -1.03327675244648e-05 2.50622484482888e-05 1.066400217016e-06 3.98170822198522e-06 1.17628823504349e-06 -2.57279625574705e-06 -7.1407133486875e-06 1.066400217016e-06 6.26345631465527e-05 5.93978524917754e-06 1.84918165217679e-05 -3.24596904009548e-05 -7.69120768520232e-06 3.98170822198522e-06 5.93978524917754e-06 5.89352599692538e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1202 0 0 0 0 0 2414 +1147 1148 0.999837589784483 -0.0177155229760786 -0.00330972803102179 -0.030638650251533 0.017741324570059 0.999811113762924 0.00793613247374114 0.0101717288093485 0.0031685101317685 -0.00799356252399269 0.999963031067509 -0.0750804203019746 3.12159527773753e-05 4.90564614640712e-06 -8.01412072391137e-06 -3.42552414180921e-06 3.29826728507617e-06 -2.60491229481768e-06 4.90564614640712e-06 6.7279343643386e-05 7.02283393647463e-06 1.63889569297324e-06 -4.08171539448984e-06 -2.36487269944646e-05 -8.01412072391137e-06 7.02283393647463e-06 1.92398601625427e-05 -6.58408170903588e-06 -6.3288389486028e-06 5.96857439357049e-07 -3.42552414180921e-06 1.63889569297324e-06 -6.58408170903588e-06 2.60813082386549e-05 -2.97871783181464e-06 -3.9494691175174e-06 3.29826728507617e-06 -4.08171539448984e-06 -6.3288389486028e-06 -2.97871783181464e-06 6.24906098872426e-05 7.23599603792939e-06 -2.60491229481768e-06 -2.36487269944646e-05 5.96857439357049e-07 -3.9494691175174e-06 7.23599603792939e-06 4.79589565961392e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1728 0 0 0 0 0 3065 +1142 1143 0.999971676748876 -1.31354506260321e-05 0.00752632230912674 0.000838108223939325 -1.57619742698022e-06 0.999998089603067 0.0019546835375642 0.00787198555706371 -0.00752633360651278 -0.00195464003754135 0.999969766385348 -0.00519073462542061 2.32708138467668e-05 -1.12930997081928e-05 -1.09455548922689e-05 2.87121358438423e-06 -1.70325526007491e-06 1.13189730766772e-05 -1.12930997081928e-05 9.54362652251271e-05 7.69570825051272e-06 3.23528670747173e-06 2.17175643086118e-05 -3.9457074281139e-05 -1.09455548922689e-05 7.69570825051272e-06 1.86105682857257e-05 -9.54483154726446e-06 -4.51983134831374e-06 -8.07159348534695e-06 2.87121358438423e-06 3.23528670747173e-06 -9.54483154726446e-06 2.43513648723628e-05 9.40214386372394e-06 4.23929904064319e-06 -1.70325526007491e-06 2.17175643086118e-05 -4.51983134831374e-06 9.40214386372394e-06 4.07884702967087e-05 -7.3275987646824e-06 1.13189730766772e-05 -3.9457074281139e-05 -8.07159348534695e-06 4.23929904064319e-06 -7.3275987646824e-06 4.92622180905611e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1280 0 0 0 0 0 2642 +1146 1147 0.999756604022083 0.00991532094184711 -0.0197083516523517 -0.0114512478664842 -0.00940026477321282 0.999616261911844 0.0260569365733075 0.0045105827591502 0.0199591516960536 -0.0258653306959731 0.999466165976398 -0.0496224804266445 3.3242471984303e-05 1.35464090410008e-05 -3.49537248692608e-06 1.38914160649676e-06 -8.15416949796041e-08 -1.2354746984402e-05 1.35464090410008e-05 5.37306528566837e-05 1.6673843524334e-06 3.84269037062849e-06 1.65557360779142e-06 -2.20790166625867e-05 -3.49537248692608e-06 1.6673843524334e-06 1.39301700763225e-05 -2.18263280641599e-06 3.46389194912926e-07 -5.04029608660805e-06 1.38914160649676e-06 3.84269037062849e-06 -2.18263280641599e-06 2.63936511597705e-05 -1.22838241952365e-05 -2.91720619815155e-06 -8.15416949796041e-08 1.65557360779142e-06 3.46389194912926e-07 -1.22838241952365e-05 8.14151953248482e-05 6.02471907223544e-06 -1.2354746984402e-05 -2.20790166625867e-05 -5.04029608660805e-06 -2.91720619815155e-06 6.02471907223544e-06 3.99964172798157e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1552 0 0 0 0 0 2781 +1150 1151 0.997219588144396 0.0733868795638944 0.0129405922969028 -0.0357918242500978 -0.073542524196945 0.997219980762846 0.0119919598936653 -0.0277131565127265 -0.0120245646849258 -0.0129103011283228 0.999844354871754 -0.114906454788365 4.97522808019271e-05 2.5316385294212e-05 -1.97323867256095e-06 -3.09888339010139e-06 1.10114371322397e-05 6.29588833205519e-06 2.5316385294212e-05 5.43458834094703e-05 -2.26330693108929e-06 1.14345789120419e-05 1.53421342670236e-06 -3.20256416511101e-06 -1.97323867256095e-06 -2.26330693108929e-06 1.18110908070449e-05 2.49988164253945e-06 2.94497571287968e-06 -6.97445083796922e-07 -3.09888339010139e-06 1.14345789120419e-05 2.49988164253945e-06 3.19779960480236e-05 -1.01880443091198e-05 -2.95931617644147e-06 1.10114371322397e-05 1.53421342670236e-06 2.94497571287968e-06 -1.01880443091198e-05 5.78030910288208e-05 7.79959405579182e-06 6.29588833205519e-06 -3.20256416511101e-06 -6.97445083796922e-07 -2.95931617644147e-06 7.79959405579182e-06 8.34865351303399e-05 20 20 0 0 0 206 206 0 0 0 0 0 0 0 0 0 0 0 1881 0 133 216 0 0 3107 +1143 1144 0.999994182505906 -0.000612163273306529 0.00335562370832143 -0.00129506315935059 0.000620242267033894 0.999996910612173 -0.00240708654590011 0.0053351637251316 -0.00335413981151932 0.0024091538423445 0.999991472825588 0.00355513548678246 2.33020250111127e-05 -2.11200188874333e-06 -6.64551876443856e-06 -2.11932221263729e-07 9.17600402843902e-07 1.00182847096922e-05 -2.11200188874333e-06 7.12639381497267e-05 9.74828705240176e-06 1.52470408507195e-06 2.59273100945946e-07 -2.51395512593049e-05 -6.64551876443856e-06 9.74828705240176e-06 1.73381335609528e-05 -6.64955535843333e-06 -5.2405127861342e-06 -2.94005108981678e-06 -2.11932221263729e-07 1.52470408507195e-06 -6.64955535843333e-06 2.20408470864624e-05 5.31304831176409e-06 3.48015336662367e-06 9.17600402843902e-07 2.59273100945946e-07 -5.2405127861342e-06 5.31304831176409e-06 3.69922400976918e-05 7.29544587747002e-07 1.00182847096922e-05 -2.51395512593049e-05 -2.94005108981678e-06 3.48015336662367e-06 7.29544587747002e-07 5.15211201884705e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1327 0 0 0 0 0 2629 +1145 1146 0.999769821815518 0.00356560008659428 -0.0211563201665506 -0.00218201460206597 -0.00332103081690626 0.999927388223234 0.0115839991097329 0.0131888616692261 0.0211960878767823 -0.0115110719346033 0.999709068220168 -0.0186903160441848 2.21516378347454e-05 1.2611030882851e-05 -4.84422918528729e-06 1.92439989398164e-06 3.12320630041391e-06 -5.00084208149477e-06 1.2611030882851e-05 4.09690825271315e-05 -1.52480518598578e-06 -3.90589045636938e-07 8.50507273436772e-06 -9.88622278540557e-06 -4.84422918528729e-06 -1.52480518598578e-06 1.25982069767878e-05 -1.25581650067917e-06 7.0437012198444e-07 -1.34409908826579e-06 1.92439989398164e-06 -3.90589045636938e-07 -1.25581650067917e-06 2.03198702207831e-05 -7.06118290329933e-06 2.05720583848808e-06 3.12320630041391e-06 8.50507273436772e-06 7.0437012198444e-07 -7.06118290329933e-06 6.31208870956082e-05 1.56036931577169e-07 -5.00084208149477e-06 -9.88622278540557e-06 -1.34409908826579e-06 2.05720583848808e-06 1.56036931577169e-07 3.70769103804184e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1365 0 0 0 0 0 2533 +1151 1152 0.996747459973769 0.0776775141763165 0.0214640356696256 -0.0336209444804975 -0.0778183917008707 0.996950640357189 0.00580677229444224 -0.025095405783521 -0.0209475284682626 -0.00745818227035174 0.999752757719774 -0.10842851124103 4.20560644018e-05 2.1135555332309e-05 -9.67525636906776e-07 -3.58240131609313e-06 3.97271916115605e-06 -1.82032846633841e-05 2.1135555332309e-05 4.24094748210283e-05 -1.53455042014502e-06 -9.87974287369919e-07 4.62189237018649e-06 -7.56608416147001e-06 -9.67525636906776e-07 -1.53455042014502e-06 1.06954295899809e-05 2.0533362504046e-06 2.73414005391375e-06 1.38854726967673e-07 -3.58240131609313e-06 -9.87974287369919e-07 2.0533362504046e-06 2.54187712265265e-05 -8.37358800927272e-06 -1.44002584627021e-06 3.97271916115605e-06 4.62189237018649e-06 2.73414005391375e-06 -8.37358800927272e-06 4.69326259471013e-05 2.60179474619409e-06 -1.82032846633841e-05 -7.56608416147001e-06 1.38854726967673e-07 -1.44002584627021e-06 2.60179474619409e-06 8.76038636269039e-05 429 429 0 0 0 553 553 0 0 0 0 0 0 0 0 0 0 0 1964 0 180 207 0 0 2861 +1149 1150 0.998879506570258 0.0472988405190029 0.00159719739426683 -0.0393503573973903 -0.0472991144728838 0.998880761537513 0.00013416527107343 0.000492462694029748 -0.00158906388775129 -0.000209560962155911 0.999998715479257 -0.0873018493434869 4.32439728759945e-05 2.24712373206674e-05 -5.53694034904256e-06 6.89304466655875e-06 -4.09390894926266e-06 2.08592983495713e-05 2.24712373206674e-05 5.18071284740478e-05 -2.31503292316909e-06 6.29361846557469e-06 -1.14422616219169e-06 1.22243713140336e-05 -5.53694034904256e-06 -2.31503292316909e-06 1.34293788381718e-05 -2.36080701033373e-06 6.11028577851252e-07 -3.24615158023557e-06 6.89304466655875e-06 6.29361846557469e-06 -2.36080701033373e-06 3.3993909851965e-05 -2.7164057969981e-05 1.23189659798964e-05 -4.09390894926266e-06 -1.14422616219169e-06 6.11028577851252e-07 -2.7164057969981e-05 9.6893179604462e-05 -1.28616224942408e-05 2.08592983495713e-05 1.22243713140336e-05 -3.24615158023557e-06 1.23189659798964e-05 -1.28616224942408e-05 7.48200298057434e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1856 0 1 77 0 0 3093 +1148 1149 0.999861002701083 0.00888932904225584 -0.0141051446913431 -0.038656863355006 -0.00895289051113553 0.999950022454484 -0.00444953309599727 0.0116924733797777 0.0140648863870576 0.0045751964389808 0.999890617291944 -0.0794070337758482 4.42047649384712e-05 2.37090182061017e-05 -4.89633075731855e-06 -1.74165503879135e-06 4.96806946363595e-06 1.89832231655558e-05 2.37090182061017e-05 4.71798897594007e-05 -2.97108585782688e-06 9.568485315542e-07 4.95773389799245e-06 8.73007213924708e-06 -4.89633075731855e-06 -2.97108585782688e-06 1.08483524686351e-05 -1.7062175887859e-06 -2.50356190105483e-06 7.45189932656022e-08 -1.74165503879135e-06 9.568485315542e-07 -1.7062175887859e-06 2.31465274116664e-05 -1.45292980124605e-05 3.01561532118779e-08 4.96806946363595e-06 4.95773389799245e-06 -2.50356190105483e-06 -1.45292980124605e-05 7.89850699303611e-05 3.48160022186725e-06 1.89832231655558e-05 8.73007213924708e-06 7.45189932656022e-08 3.01561532118779e-08 3.48160022186725e-06 4.39626067327504e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1808 0 0 0 0 0 3135 +1154 1155 0.999009260107597 0.0413536478519779 0.016443054114315 -0.0358455304344796 -0.0414959669765585 0.999103274096881 0.00841025645108373 -0.0133776748106202 -0.0160805144181413 -0.00908424450503368 0.999829432232229 -0.0630244247532729 2.57146676789759e-05 1.80644656796447e-05 1.55461746753519e-06 -5.12346315130059e-06 5.64462731873915e-06 -1.15663318637409e-07 1.80644656796447e-05 3.22803377828957e-05 7.98704689921025e-07 1.86233992828451e-06 -2.26842202239897e-06 1.81274044581773e-05 1.55461746753519e-06 7.98704689921025e-07 1.07958392663638e-05 2.32908620231998e-06 1.39602383075844e-06 1.96367295252007e-06 -5.12346315130059e-06 1.86233992828451e-06 2.32908620231998e-06 4.20498860149082e-05 -3.15057878544476e-05 4.07030759482921e-06 5.64462731873915e-06 -2.26842202239897e-06 1.39602383075844e-06 -3.15057878544476e-05 5.84384973188728e-05 -1.05438790725717e-05 -1.15663318637409e-07 1.81274044581773e-05 1.96367295252007e-06 4.07030759482921e-06 -1.05438790725717e-05 0.000139805549801085 1497 1497 0 0 1 1486 1486 0 0 1 0 0 0 0 0 0 0 0 1916 0 130 98 0 0 3369 +1152 1153 0.997527556995675 0.068154643076066 0.0171381930615412 -0.0420965821407637 -0.0682721697218806 0.997646410142202 0.00636798020126139 -0.0084352408480734 -0.0166638493664381 -0.00752229735858499 0.999832851614079 -0.0913691033425844 2.03540824627076e-05 1.63227700153257e-05 6.40493342117494e-07 -1.87388948567822e-07 9.56384134206062e-08 -6.22682104699524e-06 1.63227700153257e-05 2.63478688523027e-05 -2.2950311861864e-07 3.21212288531811e-06 -7.34806242071845e-06 1.05818354763422e-05 6.40493342117494e-07 -2.2950311861864e-07 9.61094341523407e-06 3.49836282141923e-06 1.45716998354069e-06 1.84290628312974e-06 -1.87388948567822e-07 3.21212288531811e-06 3.49836282141923e-06 3.64625450226764e-05 -3.25735883106771e-05 8.73503886265399e-06 9.56384134206062e-08 -7.34806242071845e-06 1.45716998354069e-06 -3.25735883106771e-05 6.66345960281563e-05 -1.20475456633381e-05 -6.22682104699524e-06 1.05818354763422e-05 1.84290628312974e-06 8.73503886265399e-06 -1.20475456633381e-05 8.48110289171374e-05 845 845 0 0 0 903 903 0 0 0 0 0 0 0 0 0 0 0 1832 0 181 176 0 0 3208 +1158 1159 0.996847992541965 0.0777236583727323 -0.0159095158384119 -0.0133507822787973 -0.0774024775073393 0.996801375332226 0.0198965979883266 -0.040923443764213 0.0174050636534231 -0.0186024478212426 0.999675453681983 -0.0369900425552186 1.80796458587462e-05 1.16412271689746e-05 2.11193744254219e-06 -6.20237197547454e-07 1.3333430464971e-06 -5.09469028799577e-06 1.16412271689746e-05 2.00482966147258e-05 9.65186048234862e-07 1.30275331274919e-06 -2.11508565506233e-06 -5.87603352438356e-07 2.11193744254219e-06 9.65186048234862e-07 1.01476013282246e-05 1.95529748000894e-06 4.97204978007366e-06 2.39697305291959e-07 -6.20237197547454e-07 1.30275331274919e-06 1.95529748000894e-06 6.85865194691919e-05 -3.61341915283291e-05 -3.86808094389972e-06 1.3333430464971e-06 -2.11508565506233e-06 4.97204978007366e-06 -3.61341915283291e-05 3.88242684516188e-05 1.12905966797565e-06 -5.09469028799577e-06 -5.87603352438356e-07 2.39697305291959e-07 -3.86808094389972e-06 1.12905966797565e-06 7.29587355904704e-05 2973 2973 0 0 0 2914 2914 0 0 0 0 0 0 0 0 0 0 0 2216 0 280 235 0 0 3618 +1153 1154 0.99838279308924 0.0551998163853389 0.013593334188195 -0.0385049095823916 -0.0553650755203378 0.998392898101895 0.0120966702991351 -0.0130635157954052 -0.0129037543356334 -0.0128297034542328 0.999834432210315 -0.0842130025828049 3.00083141543938e-05 2.28138293452588e-05 1.33127712844924e-06 -5.36110232453147e-06 4.39627978208435e-06 2.00307534437337e-05 2.28138293452588e-05 4.93052251307915e-05 -8.90501179819492e-07 3.18676564244825e-06 -5.42387056328128e-06 4.46876956872613e-05 1.33127712844924e-06 -8.90501179819492e-07 1.16794681558201e-05 -3.15653253861268e-07 -7.63598532761205e-07 3.11187649532959e-06 -5.36110232453147e-06 3.18676564244825e-06 -3.15653253861268e-07 3.79362721602221e-05 -2.87726871579054e-05 -1.80286736963895e-06 4.39627978208435e-06 -5.42387056328128e-06 -7.63598532761205e-07 -2.87726871579054e-05 5.67182717519201e-05 1.46042407147979e-06 2.00307534437337e-05 4.46876956872613e-05 3.11187649532959e-06 -1.80286736963895e-06 1.46042407147979e-06 0.000156093147947901 1232 1232 0 0 0 1210 1210 0 0 0 0 0 0 0 0 0 0 0 1849 0 120 102 0 0 3391 +1155 1156 0.999103969710522 0.0420601850754602 0.00471153266931121 -0.0287310122999758 -0.0420327547863019 0.999099530876873 -0.00577710365904257 -0.0238464720783713 -0.00495027612871934 0.00557388850182181 0.999972212880547 -0.0724637010742783 2.28593749667347e-05 1.11719310288148e-05 7.21326549322277e-07 -5.26497714846654e-07 4.71366890067433e-07 -5.68772063188775e-06 1.11719310288148e-05 2.88824733950644e-05 1.89922076306741e-06 -3.15217988787477e-06 8.22418494142436e-07 1.04585148428846e-05 7.21326549322277e-07 1.89922076306741e-06 1.14825802979538e-05 4.86268419645903e-06 3.80372923468303e-06 1.05358981479867e-06 -5.26497714846654e-07 -3.15217988787477e-06 4.86268419645903e-06 3.79693771734655e-05 -2.14682031962052e-05 3.48340136674574e-06 4.71366890067433e-07 8.22418494142436e-07 3.80372923468303e-06 -2.14682031962052e-05 4.37282164433546e-05 -7.82903609084757e-06 -5.68772063188775e-06 1.04585148428846e-05 1.05358981479867e-06 3.48340136674574e-06 -7.82903609084757e-06 0.000120384889923635 1821 1821 0 0 5 1779 1779 0 0 0 0 0 0 0 0 0 0 0 2033 0 155 107 0 0 3432 +1167 1168 0.997547133874489 0.00682836697163061 -0.0696641163246358 2.2778419966081 -0.00562551223478672 0.999831944749687 0.0174480907309341 -0.0846883737318986 0.0697715508705942 -0.0170133965615155 0.99741790390315 -0.302596220199383 9.65248426327793e-05 4.972977676657e-05 1.88478200836629e-06 -5.65408335045743e-05 -5.75446346480698e-06 9.54889983257052e-05 4.972977676657e-05 0.00675224165256719 -0.000186396049573089 0.00361958691539771 -4.0682429009766e-05 -0.00326547555650023 1.88478200836629e-06 -0.000186396049573089 2.09757877165191e-05 -0.000103098555577369 4.35138463987929e-06 9.54952332618711e-05 -5.65408335045743e-05 0.00361958691539771 -0.000103098555577369 0.0037170047166551 -4.70324321217789e-05 -0.00175958388088187 -5.75446346480698e-06 -4.0682429009766e-05 4.35138463987929e-06 -4.70324321217789e-05 2.28396095184839e-05 3.59158019210007e-05 9.54889983257052e-05 -0.00326547555650023 9.54952332618711e-05 -0.00175958388088187 3.59158019210007e-05 0.00275574065438356 2986 2985 0 3827 3762 2986 2985 0 3827 3762 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1157 1158 0.996663357737367 0.0721747200144648 -0.038117727299914 -0.0155664519182674 -0.0714315088782325 0.997234529241005 0.0205142201618662 -0.0416951720670555 0.0394929219361645 -0.0177229647718473 0.99906266351848 -0.051844014007754 1.91984840563285e-05 1.20427958873454e-05 -3.82741289255377e-07 -4.70277131592386e-06 4.81961004604257e-06 -3.056984362805e-06 1.20427958873454e-05 1.72458610717376e-05 -9.07620993966932e-07 -7.13509863788869e-07 1.15944306717852e-07 -4.17066787732826e-06 -3.82741289255377e-07 -9.07620993966932e-07 8.60468638204382e-06 3.43082013303522e-06 4.52521617206435e-06 -4.31450803147347e-07 -4.70277131592386e-06 -7.13509863788869e-07 3.43082013303522e-06 5.86226066458287e-05 -3.59948373996969e-05 -2.20692947464397e-05 4.81961004604257e-06 1.15944306717852e-07 4.52521617206435e-06 -3.59948373996969e-05 4.14469139112697e-05 1.79509658470819e-05 -3.056984362805e-06 -4.17066787732826e-06 -4.31450803147347e-07 -2.20692947464397e-05 1.79509658470819e-05 8.02599609302849e-05 2471 2471 0 0 0 2439 2439 0 0 0 0 0 0 0 0 0 0 0 2154 0 236 191 0 0 3635 +1156 1157 0.998406147265019 0.0561847532238383 -0.00533278619471494 -0.0242015348973144 -0.0562183936806728 0.998398091366786 -0.00638305311926515 -0.0310087379515779 0.00496561329414998 0.00667268014630282 0.99996540841385 -0.109843750327382 3.24926948032713e-05 1.65704314358634e-05 -1.20353318208998e-07 1.23028717253368e-06 -2.03739972886457e-06 -7.37014946410785e-06 1.65704314358634e-05 3.39382211391507e-05 8.11911764884691e-07 -1.55733955685681e-06 3.15811109099757e-06 -7.14515397878449e-06 -1.20353318208998e-07 8.11911764884691e-07 1.11409419776283e-05 4.29325778750627e-06 5.42539765301399e-06 6.38470985714112e-07 1.23028717253368e-06 -1.55733955685681e-06 4.29325778750627e-06 2.821985763912e-05 -9.53356350180533e-06 -3.32340651557011e-06 -2.03739972886457e-06 3.15811109099757e-06 5.42539765301399e-06 -9.53356350180533e-06 2.56896244121168e-05 3.36564463224668e-06 -7.37014946410785e-06 -7.14515397878449e-06 6.38470985714112e-07 -3.32340651557011e-06 3.36564463224668e-06 0.000121612840984367 2109 2109 0 0 0 2056 2056 0 0 0 0 0 0 0 0 0 0 0 2078 0 161 125 0 0 3441 +1164 1165 0.997236204641636 0.0709127877852149 0.0221659351364812 0.178726972879815 -0.0704042562146779 0.997254775491411 -0.022938035365584 -0.0741728661169866 -0.0237316847021781 0.0213140631533238 0.999491129451929 0.0534717034913941 3.79396238827424e-05 2.16370538621364e-05 3.22995071246398e-06 1.49673650423571e-05 2.18672477450178e-06 -4.57540758355498e-06 2.16370538621364e-05 5.74902721402445e-05 -4.22248794154152e-06 1.44852616424839e-05 2.02560052027581e-06 3.8309331700889e-05 3.22995071246398e-06 -4.22248794154152e-06 1.16152017288696e-05 -1.98528004719825e-06 4.1923065702853e-06 -9.66153221673641e-06 1.49673650423571e-05 1.44852616424839e-05 -1.98528004719825e-06 0.000248713993682484 -1.12008591187734e-05 0.000121252318591248 2.18672477450178e-06 2.02560052027581e-06 4.1923065702853e-06 -1.12008591187734e-05 1.16175007367657e-05 4.99711843805489e-06 -4.57540758355498e-06 3.8309331700889e-05 -9.66153221673641e-06 0.000121252318591248 4.99711843805489e-06 0.000301619426255082 3295 3219 0 575 0 3313 3237 0 472 0 0 0 0 0 0 0 0 0 3281 0 57 79 0 0 3750 +1159 1160 0.995386227389503 0.0865600778454568 0.0413957877891077 0.0611426926147442 -0.0863670113320433 0.996242618057662 -0.00643314224820634 -0.0910862129092995 -0.0417971012973757 0.00282823071962141 0.999122116377239 0.121434967478197 3.49414055796592e-05 2.33957871836133e-05 3.1497021974824e-06 -5.653326473457e-07 -6.42664797785001e-07 2.93942590295508e-05 2.33957871836133e-05 3.95030479182486e-05 -3.62453158215213e-07 -4.22405910220089e-06 1.25693952261817e-07 3.19914659484758e-05 3.1497021974824e-06 -3.62453158215213e-07 9.45821468703304e-06 2.96983925305917e-06 3.37225963785076e-06 1.92885212581208e-06 -5.653326473457e-07 -4.22405910220089e-06 2.96983925305917e-06 9.20415617521572e-05 -4.1502668432616e-05 3.10039276583474e-05 -6.42664797785001e-07 1.25693952261817e-07 3.37225963785076e-06 -4.1502668432616e-05 3.60250880414204e-05 -2.09562666797478e-05 2.93942590295508e-05 3.19914659484758e-05 1.92885212581208e-06 3.10039276583474e-05 -2.09562666797478e-05 0.000309694392340579 3282 3270 0 1 0 3224 3212 0 1 0 0 0 0 0 0 0 0 0 2274 0 294 256 0 0 3770 +1160 1161 0.996006476589945 0.0862854245062332 0.0229330353128738 0.0728980807062924 -0.0860581101542431 0.996232416367394 -0.0107226048823968 -0.0877845468787875 -0.0237718376984733 0.00870621022965577 0.999679499457638 0.0658208197564679 2.29231719176441e-05 1.54520581842443e-05 1.04964450985527e-06 -2.54394322004172e-06 2.75072234826402e-06 -3.81771980327513e-06 1.54520581842443e-05 2.38867454463323e-05 -1.16038250339941e-06 -2.52135778213657e-08 1.87061094140536e-07 -1.32773614417222e-06 1.04964450985527e-06 -1.16038250339941e-06 9.0762981203216e-06 1.84909408191654e-06 4.82833476986971e-06 -5.61319248574991e-07 -2.54394322004172e-06 -2.52135778213657e-08 1.84909408191654e-06 5.96467701935001e-05 -1.94959113466246e-05 1.18970608298184e-05 2.75072234826402e-06 1.87061094140536e-07 4.82833476986971e-06 -1.94959113466246e-05 2.06796134184171e-05 -5.26724419372716e-06 -3.81771980327513e-06 -1.32773614417222e-06 -5.61319248574991e-07 1.18970608298184e-05 -5.26724419372716e-06 0.000115278035435445 3532 3379 0 307 0 3492 3339 0 209 0 0 0 0 0 0 0 0 0 2432 0 214 199 0 0 3712 +1168 1169 0.999954326676488 -0.00847004327838941 0.00442751937701538 0.114123396049732 0.00856105964887211 0.999743681393755 -0.0209590021458609 -0.0137013261894593 -0.00424886086617224 0.0209959491360586 0.9997705323229 0.0174990071412065 7.05161594064977e-05 4.49164179333921e-06 -1.28494907852421e-06 1.45088825698821e-05 2.44459764648351e-07 -1.45355454551827e-05 4.49164179333921e-06 3.40050720775006e-05 1.53222905685963e-08 -9.8992400455379e-06 1.02924571955383e-06 6.1999342359575e-06 -1.28494907852421e-06 1.53222905685963e-08 1.25216320983823e-05 2.21525641734016e-06 5.75040814164837e-06 4.31588789571179e-07 1.45088825698821e-05 -9.8992400455379e-06 2.21525641734016e-06 0.000152165935125336 -2.57186906462499e-06 -3.18217093440666e-05 2.44459764648351e-07 1.02924571955383e-06 5.75040814164837e-06 -2.57186906462499e-06 1.08867469221192e-05 8.10901072091252e-06 -1.45355454551827e-05 6.1999342359575e-06 4.31588789571179e-07 -3.18217093440666e-05 8.10901072091252e-06 0.000175326016826202 3404 3404 0 108 79 3404 3404 0 49 134 0 0 0 0 0 0 0 0 3726 0 0 0 0 0 3612 +1171 1172 0.999360336218132 -0.00184819766811465 0.0357141786880385 0.133507180418255 0.00142095174987587 0.999927172442662 0.0119846029115229 -0.00338297021241608 -0.0357337276267967 -0.0119261886703982 0.999290181445656 -0.00481048266280342 3.21131472798419e-05 -8.92012538858127e-07 3.45690438949577e-06 -2.06566853825925e-06 4.78805725022833e-07 -1.94192957079745e-06 -8.92012538858127e-07 2.42309861548046e-05 2.19195674960237e-06 -8.12117920255945e-07 -7.31558522929851e-07 -5.67647960645227e-06 3.45690438949577e-06 2.19195674960237e-06 9.45365987684597e-06 6.05368685157393e-07 4.19968053519796e-06 -1.91155123791374e-06 -2.06566853825925e-06 -8.12117920255945e-07 6.05368685157393e-07 9.15483406231559e-05 -1.22732427551128e-06 1.91698550769877e-05 4.78805725022833e-07 -7.31558522929851e-07 4.19968053519796e-06 -1.22732427551128e-06 9.3839663882596e-06 2.85207528525428e-07 -1.94192957079745e-06 -5.67647960645227e-06 -1.91155123791374e-06 1.91698550769877e-05 2.85207528525428e-07 8.38283154708557e-05 3429 3431 0 139 100 3429 3431 0 85 161 0 0 0 0 0 0 0 0 3686 0 0 0 0 0 3591 +1172 1173 0.999855082915974 0.0151127963221414 -0.00783687146860909 0.123512172491839 -0.0150678301689362 0.999869851758653 0.00576541742884216 -0.0053879321381238 0.007922983092884 -0.00564649727301539 0.999952670583691 -0.112320804085817 4.91760529608408e-05 -9.49626073911666e-06 2.54572710303406e-06 -1.3027658450762e-06 -1.2386697721402e-06 -4.688942570222e-05 -9.49626073911666e-06 6.17700727453627e-05 -1.6038491484336e-06 2.13872722537416e-05 3.581659607574e-06 0.000151583681175379 2.54572710303406e-06 -1.6038491484336e-06 1.26277162804434e-05 4.42447497031247e-06 4.86941371436541e-06 -3.40360661904709e-06 -1.3027658450762e-06 2.13872722537416e-05 4.42447497031247e-06 0.000162714065883341 8.18570096964777e-08 0.000151958560246275 -1.2386697721402e-06 3.581659607574e-06 4.86941371436541e-06 8.18570096964777e-08 1.13637969009518e-05 3.22684702693858e-05 -4.688942570222e-05 0.000151583681175379 -3.40360661904709e-06 0.000151958560246275 3.22684702693858e-05 0.00132973477384804 3330 3334 0 169 49 3330 3334 0 111 107 0 0 0 0 0 0 0 0 3667 0 0 0 0 0 3656 +1173 1174 0.999505676699964 0.0314147973311205 -0.00122994032028373 0.134874917497697 -0.0314169194779417 0.999504841956109 -0.00174587422504947 -0.00339434662575501 0.00117448502049508 0.00178365213474612 0.999997719582399 0.0160909587018216 5.45873784397305e-05 3.6751804141709e-06 -4.29308462914316e-06 -1.61274456327327e-05 7.17395034573343e-07 6.42354214507245e-06 3.6751804141709e-06 0.000108441345779376 4.64458306028605e-06 2.64294000652897e-05 1.540798313787e-06 -4.62025923229531e-05 -4.29308462914316e-06 4.64458306028605e-06 1.31529167113064e-05 1.19989296020904e-06 5.45634775255232e-06 -5.88738772987445e-06 -1.61274456327327e-05 2.64294000652897e-05 1.19989296020904e-06 0.000129275832869363 -2.74457212526673e-06 -1.88237959093342e-05 7.17395034573343e-07 1.540798313787e-06 5.45634775255232e-06 -2.74457212526673e-06 1.0298916122326e-05 7.0265025977747e-06 6.42354214507245e-06 -4.62025923229531e-05 -5.88738772987445e-06 -1.88237959093342e-05 7.0265025977747e-06 0.00023077493477672 3205 3216 0 218 18 3205 3216 0 166 76 0 0 0 0 0 0 0 0 3644 0 0 0 0 0 3698 +1163 1164 0.996458150246007 0.0837691779559543 -0.0073402747148969 0.0899387904773364 -0.0838947575060519 0.996295236581549 -0.0189069095284259 -0.0702278939587586 0.00572926446476793 0.019455754662798 0.999794303414054 -0.0263894612991459 5.50856701067067e-05 3.30483359315978e-05 3.20793021431024e-06 -1.34767020120309e-07 -8.00986221210535e-07 -1.93051020785643e-05 3.30483359315978e-05 6.33911596387418e-05 -3.7488389497231e-07 1.81578898040453e-05 -1.32462261116392e-06 3.55519621922764e-05 3.20793021431024e-06 -3.7488389497231e-07 1.2668816386491e-05 -1.53399448731363e-07 5.29986418415714e-06 -5.82312079819406e-06 -1.34767020120309e-07 1.81578898040453e-05 -1.53399448731363e-07 0.000317339159629148 -4.72455160652982e-05 0.000193602820481108 -8.00986221210535e-07 -1.32462261116392e-06 5.29986418415714e-06 -4.72455160652982e-05 1.88409833390737e-05 -2.14185142835563e-05 -1.93051020785643e-05 3.55519621922764e-05 -5.82312079819406e-06 0.000193602820481108 -2.14185142835563e-05 0.000336538860052232 3349 3257 0 450 0 3348 3256 0 326 0 0 0 0 0 0 0 0 0 3400 0 207 219 0 0 3748 +1175 1176 0.999847960150302 0.017344280994855 -0.0017979154740214 0.148559242273735 -0.0173678123777257 0.999750823041363 -0.0140232279211907 0.00610645954046082 0.00155424466939167 0.0140523216903491 0.999900053294637 -0.0233592174665082 3.93738281484303e-05 -1.02645709580239e-05 3.13225569281563e-06 2.50914365404287e-06 2.02782014105997e-06 1.02241640834372e-05 -1.02645709580239e-05 2.7730422360209e-05 -2.35322846404397e-06 -2.69346504854777e-06 -1.21833389838896e-06 -1.56682455210152e-05 3.13225569281563e-06 -2.35322846404397e-06 1.0568202860821e-05 7.39441778645229e-07 4.99756604271357e-06 2.67688586316666e-06 2.50914365404287e-06 -2.69346504854777e-06 7.39441778645229e-07 9.71445870452167e-05 5.14637215847757e-06 1.57605547420484e-05 2.02782014105997e-06 -1.21833389838896e-06 4.99756604271357e-06 5.14637215847757e-06 1.03587835531245e-05 5.04293052168975e-06 1.02241640834372e-05 -1.56682455210152e-05 2.67688586316666e-06 1.57605547420484e-05 5.04293052168975e-06 8.36647437742807e-05 3606 3632 0 190 88 3606 3632 0 146 155 0 0 0 0 0 0 0 0 3662 0 0 0 0 0 3639 +1165 1166 0.998430554665399 0.0533165897260174 0.0171396840849032 0.140584798747305 -0.0532955794640827 0.998577366469307 -0.00168059061358834 -0.059330518281707 -0.0172049039558607 0.000764483623354237 0.999851692424761 -0.0527278846057017 3.44412270723384e-05 1.00938623979469e-06 6.48480828798385e-06 5.50158372826129e-07 1.46439885924014e-06 -1.23512842875497e-05 1.00938623979469e-06 5.61727667789005e-05 -4.33124625151279e-06 -1.20014788912011e-05 -3.61335546469714e-07 -3.12887485940136e-05 6.48480828798385e-06 -4.33124625151279e-06 1.00783121318047e-05 1.91482666330257e-06 3.91791732202009e-06 -1.10215836949354e-06 5.50158372826129e-07 -1.20014788912011e-05 1.91482666330257e-06 0.000178689950239223 -9.5000911912628e-06 5.63131302093299e-06 1.46439885924014e-06 -3.61335546469714e-07 3.91791732202009e-06 -9.5000911912628e-06 1.0454441860965e-05 7.4151741687432e-06 -1.23512842875497e-05 -3.12887485940136e-05 -1.10215836949354e-06 5.63131302093299e-06 7.4151741687432e-06 0.000190212525395707 3174 3110 0 391 0 3193 3132 0 304 0 0 0 0 0 0 0 0 0 3462 0 14 46 0 0 3754 +1162 1163 0.99579720164853 0.0910521988844932 0.00987067714274834 0.141945970976722 -0.0908859683763132 0.995730297093675 -0.0161529007314862 -0.0978571649811104 -0.0112992894138293 0.0151879072962718 0.999820810710951 0.028651477437141 3.7333465680094e-05 2.66931603990056e-05 2.31471055698243e-06 -2.79138497934478e-05 9.64480728324936e-06 2.63979882466666e-06 2.66931603990056e-05 4.27987545752844e-05 -1.74683432978306e-06 1.85971209635031e-05 -2.99670446922685e-06 5.23636353218007e-05 2.31471055698243e-06 -1.74683432978306e-06 1.13211786618924e-05 4.9055404821718e-07 5.01555856357968e-06 5.28820312721108e-07 -2.79138497934478e-05 1.85971209635031e-05 4.9055404821718e-07 0.000361289189148587 -9.01067231511877e-05 0.000113620281531585 9.64480728324936e-06 -2.99670446922685e-06 5.01555856357968e-06 -9.01067231511877e-05 3.53521416355203e-05 -2.67740992778455e-05 2.63979882466666e-06 5.23636353218007e-05 5.28820312721108e-07 0.000113620281531585 -2.67740992778455e-05 0.000367343638450969 3395 3280 0 662 0 3361 3246 0 522 0 0 0 0 0 0 0 0 0 3189 0 230 228 0 0 3739 +1169 1170 0.99988194027734 -0.00434589836076496 -0.0147383402952576 0.138718975693294 0.00447533280483548 0.999951610662198 0.00876057819794985 -0.0145659929326527 0.0146995545343006 -0.00882550290432966 0.99985300599387 -0.00859665394289979 2.9150373034287e-05 -2.57688679054848e-06 3.05282457695997e-06 8.24177795685962e-07 2.38622145310342e-06 -6.18617840993532e-06 -2.57688679054848e-06 2.62860156538144e-05 1.01895481585493e-06 7.44914771533378e-06 -4.07490254170973e-07 -3.69802189141721e-06 3.05282457695997e-06 1.01895481585493e-06 9.44583606571367e-06 1.50663520077098e-06 4.40478202236185e-06 -2.29394039758497e-06 8.24177795685962e-07 7.44914771533378e-06 1.50663520077098e-06 0.000125766295489698 7.38340582954646e-07 3.74012443904957e-05 2.38622145310342e-06 -4.07490254170973e-07 4.40478202236185e-06 7.38340582954646e-07 9.38745385371775e-06 3.08242427113948e-06 -6.18617840993532e-06 -3.69802189141721e-06 -2.29394039758497e-06 3.74012443904957e-05 3.08242427113948e-06 9.71576037986121e-05 3321 3324 0 148 98 3321 3324 0 94 157 0 0 0 0 0 0 0 0 3670 0 0 0 0 0 3574 +1176 1177 0.999883081816623 0.0137382142050521 0.00671447446557929 0.139252210392107 -0.0137280258980732 0.999904547568474 -0.00156110756415609 0.00728148854731642 -0.00673528038277863 0.00146874856294021 0.999976239105622 -0.00221104698337108 4.2143462841384e-05 -9.82204310038006e-06 -2.23423904384287e-06 -8.94792142968041e-06 -2.1308890714517e-06 -6.44593450529253e-06 -9.82204310038006e-06 6.65211249517395e-05 -3.68928876935545e-06 2.92873088704321e-05 4.82928190748023e-06 4.7649417441212e-05 -2.23423904384287e-06 -3.68928876935545e-06 1.3592354393485e-05 -2.15281129242336e-07 5.53486530893218e-06 -8.60824415511373e-06 -8.94792142968041e-06 2.92873088704321e-05 -2.15281129242336e-07 8.15919540994959e-05 -8.42115874863329e-07 1.3246651494985e-05 -2.1308890714517e-06 4.82928190748023e-06 5.53486530893218e-06 -8.42115874863329e-07 1.16171000366339e-05 1.3962924350751e-05 -6.44593450529253e-06 4.7649417441212e-05 -8.60824415511373e-06 1.3246651494985e-05 1.3962924350751e-05 0.000366562915333224 3065 3096 0 163 80 3065 3096 0 119 153 0 0 0 0 0 0 0 0 3690 0 0 0 0 0 3652 +1166 1167 0.998560419729155 0.0421602303051377 0.0331602643377753 0.0855006903464645 -0.0421954592410413 0.999109309062845 0.00036299229039722 -0.0431566082535342 -0.0331154249522938 -0.00176168231614425 0.999449981292534 -0.0567452038129718 4.12645359782379e-05 8.98295330655127e-06 2.44342655134852e-06 9.32614444571219e-07 2.72339176845543e-06 6.22518118939361e-10 8.98295330655127e-06 3.89877717743476e-05 -5.43494417815427e-06 -1.22276294139016e-06 -7.04347179882595e-07 -1.66431740698383e-05 2.44342655134852e-06 -5.43494417815427e-06 1.04810465654332e-05 2.75082374082332e-07 5.18775693392643e-06 1.85504596808031e-06 9.32614444571219e-07 -1.22276294139016e-06 2.75082374082332e-07 0.000193979007619242 6.49029965148236e-07 5.94188702892188e-05 2.72339176845543e-06 -7.04347179882595e-07 5.18775693392643e-06 6.49029965148236e-07 9.39245642411512e-06 7.21229060341799e-06 6.22518118939361e-10 -1.66431740698383e-05 1.85504596808031e-06 5.94188702892188e-05 7.21229060341799e-06 0.0001585820318659 3557 3504 0 252 0 3592 3541 0 178 0 0 0 0 0 0 0 0 0 3606 0 3 43 0 0 3764 +1170 1171 0.999772123577336 0.000629367076414674 0.0213378727793545 0.150798085707716 -0.000702204294548892 0.999993952345635 0.00340619748171269 -0.00927688042014098 -0.0213355999867243 -0.00342040483551787 0.999766519245352 -0.021907314395254 3.19559327283198e-05 -9.51057620495303e-07 5.30525910295829e-06 6.54777052857416e-06 8.59983739990648e-07 -1.14684191891309e-05 -9.51057620495303e-07 3.73999095711599e-05 1.96460292478227e-06 -1.67836947336175e-05 1.96122108924335e-06 1.62807538028898e-05 5.30525910295829e-06 1.96460292478227e-06 9.63070187615289e-06 3.51870549690656e-06 4.73501771363415e-06 -3.83856524446899e-06 6.54777052857416e-06 -1.67836947336175e-05 3.51870549690656e-06 0.000308443311170733 -7.93744063432806e-06 -1.98684300832775e-05 8.59983739990648e-07 1.96122108924335e-06 4.73501771363415e-06 -7.93744063432806e-06 1.02391345953741e-05 9.58752205280577e-06 -1.14684191891309e-05 1.62807538028898e-05 -3.83856524446899e-06 -1.98684300832775e-05 9.58752205280577e-06 0.000212627826009266 3351 3355 0 169 116 3351 3355 0 113 170 0 0 0 0 0 0 0 0 3648 0 0 0 0 0 3571 +1178 1179 0.999567981257749 -0.0183997629043164 0.0229194146821496 0.145215399646852 0.0183941184085537 0.999830709409544 0.000457088153486347 0.0172849254234171 -0.0229239449545557 -3.53082553189761e-05 0.999737211221553 0.0103082446986938 4.63052016530899e-05 -1.15781238264334e-05 1.57810699768312e-06 1.73941993469066e-06 -7.12765679253901e-07 1.36865822043464e-05 -1.15781238264334e-05 4.52902528803227e-05 -3.41284096137878e-07 1.1036228427364e-05 -1.49177431937948e-07 -3.42194081665962e-05 1.57810699768312e-06 -3.41284096137878e-07 1.20422189827467e-05 -3.71556500532099e-06 5.31002438622024e-06 7.83548440679395e-07 1.73941993469066e-06 1.1036228427364e-05 -3.71556500532099e-06 8.0907663390023e-05 -9.82330171402718e-07 -1.88467037869467e-05 -7.12765679253901e-07 -1.49177431937948e-07 5.31002438622024e-06 -9.82330171402718e-07 9.78853109805444e-06 2.04172294574761e-06 1.36865822043464e-05 -3.42194081665962e-05 7.83548440679395e-07 -1.88467037869467e-05 2.04172294574761e-06 8.34342688606629e-05 3130 3154 0 77 182 3130 3154 0 37 255 0 0 0 0 0 0 0 0 3756 0 0 0 0 0 3539 +1179 1180 0.999367198766308 -0.0324425762763008 -0.0145835960770742 0.149567370406652 0.032733316946964 0.999260773271234 0.0201602818191014 0.0165745851548917 0.0139187640123846 -0.0206248938405121 0.999690392952956 -0.0200885780819715 3.28805551578148e-05 -8.28566515755869e-06 -3.28839238116848e-06 5.04017721103357e-07 -1.34389936888495e-06 2.2901337593928e-06 -8.28566515755869e-06 2.30382346619103e-05 3.10267126427875e-07 4.93032203825563e-06 -4.46300482272228e-07 -2.86735353948546e-06 -3.28839238116848e-06 3.10267126427875e-07 1.13765367651635e-05 -4.31696827962322e-06 5.3971199743892e-06 5.15586278517998e-07 5.04017721103357e-07 4.93032203825563e-06 -4.31696827962322e-06 5.20182127552578e-05 -1.13386652074495e-06 5.97659013815969e-06 -1.34389936888495e-06 -4.46300482272228e-07 5.3971199743892e-06 -1.13386652074495e-06 9.71617606397518e-06 2.31020110714814e-06 2.2901337593928e-06 -2.86735353948546e-06 5.15586278517998e-07 5.97659013815969e-06 2.31020110714814e-06 0.000113768014590346 3387 3402 0 50 217 3387 3402 0 5 288 0 0 0 0 0 0 0 0 3781 0 0 0 0 0 3495 +1174 1175 0.998583352823877 0.0311091177861143 -0.0431683941511986 0.13936837567604 -0.0310235538731611 0.999515138701059 0.00265077582643784 -0.00218784951282261 0.0432299267649465 -0.00130778361078122 0.99906429379391 -0.050894420375136 3.93215157629973e-05 -8.45992017825203e-06 -5.30888493029592e-06 -6.90362566448648e-06 -1.13960924557634e-06 1.46098372430057e-05 -8.45992017825203e-06 3.49762022565906e-05 1.81635030131784e-06 2.76088622378128e-06 -2.11043329538378e-07 -1.10294088447365e-05 -5.30888493029592e-06 1.81635030131784e-06 1.15968286618179e-05 -1.58063270199788e-06 5.12074593805497e-06 -3.96640538197203e-06 -6.90362566448648e-06 2.76088622378128e-06 -1.58063270199788e-06 7.02856188463501e-05 -1.76488546085368e-06 -1.39257864616182e-05 -1.13960924557634e-06 -2.11043329538378e-07 5.12074593805497e-06 -1.76488546085368e-06 9.84551630329806e-06 8.41208895122651e-07 1.46098372430057e-05 -1.10294088447365e-05 -3.96640538197203e-06 -1.39257864616182e-05 8.41208895122651e-07 0.000138442231083353 3377 3399 0 218 18 3377 3399 0 166 85 0 0 0 0 0 0 0 0 3644 0 0 0 0 0 3705 +1180 1181 0.998873768806159 -0.0312386768810941 -0.0357118895845575 0.138822197835687 0.0317916303088287 0.999381623864829 0.0150220545733103 0.0179283882443131 0.0352205370953908 -0.0161404754581563 0.999249217572222 -0.0902390002421679 3.71370929219937e-05 -1.26979026430457e-05 1.74541838285995e-06 2.34075676572858e-06 -4.29723330672861e-07 5.85627038832073e-06 -1.26979026430457e-05 4.64545588257498e-05 9.69444728937313e-07 6.74548355531627e-06 -1.02649917306232e-06 5.26155754304539e-05 1.74541838285995e-06 9.69444728937313e-07 1.09884859512836e-05 9.16021358144975e-07 5.05335409549222e-06 2.72015919687204e-06 2.34075676572858e-06 6.74548355531627e-06 9.16021358144975e-07 0.000101706893229283 -2.75258671823536e-07 5.50317181998623e-05 -4.29723330672861e-07 -1.02649917306232e-06 5.05335409549222e-06 -2.75258671823536e-07 9.55089341713848e-06 -2.70832670106039e-06 5.85627038832073e-06 5.26155754304539e-05 2.72015919687204e-06 5.50317181998623e-05 -2.70832670106039e-06 0.000491653443754695 3644 3648 0 31 199 3641 3648 0 1 267 0 0 0 0 0 0 0 0 3783 0 0 0 0 0 3515 +1181 1182 0.999641794793703 -0.0227550454949264 0.0140886481305754 0.14370341572749 0.0226625721112258 0.999720794084863 0.00668892365286825 0.0171252809289176 -0.0142369212587142 -0.00636724264138242 0.999878376751002 0.00557506419903639 3.85297596037918e-05 -3.14518805833629e-06 -1.88584178834282e-07 -3.90167691584811e-06 2.89163384520618e-06 -2.79933932592033e-06 -3.14518805833629e-06 4.26488136015341e-05 -1.73985338298183e-07 8.28351501527567e-07 -6.82471107870054e-07 -1.45449936843277e-05 -1.88584178834282e-07 -1.73985338298183e-07 1.03453729865303e-05 -1.28276744546209e-06 5.35977754706994e-06 1.7243647412651e-06 -3.90167691584811e-06 8.28351501527567e-07 -1.28276744546209e-06 8.50782421136411e-05 -1.02188708043845e-06 8.47699368143248e-06 2.89163384520618e-06 -6.82471107870054e-07 5.35977754706994e-06 -1.02188708043845e-06 9.30097962024973e-06 -2.84057682894824e-07 -2.79933932592033e-06 -1.45449936843277e-05 1.7243647412651e-06 8.47699368143248e-06 -2.84057682894824e-07 9.39860582930638e-05 3589 3585 0 68 193 3589 3585 0 13 254 0 0 0 0 0 0 0 0 3747 0 0 0 0 0 3542 +1177 1178 0.999864149712891 -0.00139842445578569 0.0164233531277578 0.132601415750881 0.00139629779277405 0.999999015241428 0.000140956194462759 0.0098460574479383 -0.0164235340713096 -0.000118005153801035 0.999865117705079 -0.0166408826854185 4.25113356947809e-05 -3.03769538692906e-06 -3.18394578149529e-06 -1.11677714806007e-05 -7.36274483237653e-07 -2.86837275956749e-07 -3.03769538692906e-06 3.03561554917823e-05 -4.53459156519709e-06 4.65509982867173e-06 7.97368391695797e-08 2.705880860333e-07 -3.18394578149529e-06 -4.53459156519709e-06 1.10299874613524e-05 -2.6168766690754e-06 5.08082763454841e-06 6.02297653323972e-07 -1.11677714806007e-05 4.65509982867173e-06 -2.6168766690754e-06 0.000115870245425441 4.55899652340487e-06 -2.1489260560167e-05 -7.36274483237653e-07 7.97368391695797e-08 5.08082763454841e-06 4.55899652340487e-06 1.03927160476301e-05 7.66881297454172e-06 -2.86837275956749e-07 2.705880860333e-07 6.02297653323972e-07 -2.1489260560167e-05 7.66881297454172e-06 0.000163908971884734 3635 3664 0 108 108 3635 3664 0 68 179 0 0 0 0 0 0 0 0 3735 0 0 0 0 0 3615 +1184 1185 0.999522868785304 0.0302843405769461 0.00607400123600734 0.145046098277881 -0.0301667069989141 0.99937173400003 -0.0186039530910674 0.00412957316855444 -0.00663359359903439 0.0184118439487332 0.999808481379494 0.0244478677673676 3.02813764998535e-05 8.3470063765564e-07 -6.96467741780514e-06 4.91921697062891e-07 -2.79185079050408e-06 2.66373472190933e-07 8.3470063765564e-07 3.15207565346909e-05 1.07258121576256e-06 1.45371693591683e-05 3.24920096054445e-07 -2.58141889570059e-05 -6.96467741780514e-06 1.07258121576256e-06 1.13910849915028e-05 -1.54061190919696e-06 5.34253165289488e-06 -8.95777610009389e-07 4.91921697062891e-07 1.45371693591683e-05 -1.54061190919696e-06 7.96495222292305e-05 -1.23022939573745e-06 -9.62724402003476e-06 -2.79185079050408e-06 3.24920096054445e-07 5.34253165289488e-06 -1.23022939573745e-06 9.43347471009987e-06 5.59635526011957e-07 2.66373472190933e-07 -2.58141889570059e-05 -8.95777610009389e-07 -9.62724402003476e-06 5.59635526011957e-07 5.18122247860272e-05 3419 3412 0 225 48 3419 3412 0 165 94 0 0 0 0 0 0 0 0 3626 0 0 0 0 0 3712 +1186 1187 0.999576142522375 0.0286084754692676 0.00539355461759887 0.139642070876919 -0.0286087160141314 0.999590686384992 -3.25638363506984e-05 0.004619686530626 -0.00539227856397402 -0.000121752638436432 0.999985454148301 -0.0107241343314018 4.50732671842118e-05 -4.25805740942956e-06 -2.97239192863894e-06 -2.26707999499407e-05 -2.44337866808725e-06 -6.97055993960004e-06 -4.25805740942956e-06 4.37294567410466e-05 -2.20038545833426e-06 1.5953098971313e-06 -5.6452318259489e-07 -2.76784060828938e-05 -2.97239192863894e-06 -2.20038545833426e-06 1.28447412144529e-05 3.35553612250621e-07 5.18563834534964e-06 3.52994981978929e-06 -2.26707999499407e-05 1.5953098971313e-06 3.35553612250621e-07 0.000109782584026962 -3.65632950788014e-07 4.79261106863694e-08 -2.44337866808725e-06 -5.6452318259489e-07 5.18563834534964e-06 -3.65632950788014e-07 9.99074921601535e-06 2.00003645851061e-06 -6.97055993960004e-06 -2.76784060828938e-05 3.52994981978929e-06 4.79261106863694e-08 2.00003645851061e-06 9.42986904437925e-05 3439 3446 0 207 50 3439 3446 0 148 106 0 0 0 0 0 0 0 0 3641 0 0 0 0 0 3723 +1189 1190 0.999905874592242 -0.0120401383502399 -0.00657852752747121 0.140139961453972 0.0118729500718308 0.999619734250227 -0.0248881488684253 0.0280493054730001 0.00687568269442578 0.0248076997323849 0.999668596596629 -0.0286569211622386 3.82643101690751e-05 -7.77155247556625e-06 -6.47813413961694e-06 -2.2592148978207e-05 -1.95237484301359e-06 3.73341243119843e-06 -7.77155247556625e-06 2.23568341568963e-05 -5.65355124561175e-07 8.98886134248142e-06 1.39779528567451e-06 -6.15581676210172e-06 -6.47813413961694e-06 -5.65355124561175e-07 1.12615735035545e-05 7.11074624500533e-07 4.75975561214565e-06 4.4297432748912e-07 -2.2592148978207e-05 8.98886134248142e-06 7.11074624500533e-07 6.35860689909998e-05 7.83263718915342e-08 -3.93186543099688e-06 -1.95237484301359e-06 1.39779528567451e-06 4.75975561214565e-06 7.83263718915342e-08 9.89391636604411e-06 -9.27338420161669e-07 3.73341243119843e-06 -6.15581676210172e-06 4.4297432748912e-07 -3.93186543099688e-06 -9.27338420161669e-07 7.53202891122965e-05 3561 3565 0 72 170 3561 3565 0 27 234 0 0 0 0 0 0 0 0 3729 0 0 0 0 0 3614 +1188 1189 0.999725537988232 -0.00458766146506734 0.0229739429881358 0.14240140635886 0.00434919066447275 0.999936259484935 0.0104192853805203 0.0191226029905824 -0.0230202787712105 -0.0103165076241234 0.999681767581933 -0.0259272215712583 3.87097755012477e-05 -2.07151368494796e-05 -8.00955831210736e-07 -1.84697208547945e-05 -2.35606889733264e-06 1.29813837486114e-06 -2.07151368494796e-05 6.35916859509719e-05 -2.12489690464497e-06 3.2490270129364e-05 1.15262930985722e-06 -1.03464940228039e-05 -8.00955831210736e-07 -2.12489690464497e-06 1.03775241842974e-05 -3.42036678482985e-06 4.42573328780115e-06 1.90104271152377e-06 -1.84697208547945e-05 3.2490270129364e-05 -3.42036678482985e-06 7.54708014854607e-05 1.07192852009063e-06 -1.72020554686619e-05 -2.35606889733264e-06 1.15262930985722e-06 4.42573328780115e-06 1.07192852009063e-06 9.33433337757247e-06 2.89761614885743e-06 1.29813837486114e-06 -1.03464940228039e-05 1.90104271152377e-06 -1.72020554686619e-05 2.89761614885743e-06 0.000231532277113961 3495 3510 0 105 149 3495 3510 0 58 211 0 0 0 0 0 0 0 0 3704 0 0 0 0 0 3631 +1193 1194 0.999783922739011 -0.0190886863907941 0.00822981679437648 0.137522136021209 0.0190670814437645 0.999814572537679 0.00269572745552267 0.0209972639313128 -0.00827974865632646 -0.00253822638303207 0.999962500881416 -0.0197524196948584 3.43311880145653e-05 -8.89783595630893e-06 -5.30665586259687e-06 -5.47049377787021e-06 -2.65117799231882e-06 -7.70114866673377e-06 -8.89783595630893e-06 7.02749633737293e-05 1.405306817401e-06 1.61774347395927e-05 5.86947085109621e-07 5.54832298877589e-06 -5.30665586259687e-06 1.405306817401e-06 1.11626265416835e-05 -2.39640474302253e-07 4.76649793514091e-06 -6.72342047833976e-06 -5.47049377787021e-06 1.61774347395927e-05 -2.39640474302253e-07 7.15956774087472e-05 -2.44517375423417e-06 -5.44826940281146e-05 -2.65117799231882e-06 5.86947085109621e-07 4.76649793514091e-06 -2.44517375423417e-06 9.27406149198381e-06 5.64813458188649e-06 -7.70114866673377e-06 5.54832298877589e-06 -6.72342047833976e-06 -5.44826940281146e-05 5.64813458188649e-06 0.000479121737297189 3260 3230 0 79 186 3260 3230 0 8 231 0 0 0 0 0 0 0 0 3702 0 0 0 0 0 3612 +1187 1188 0.999168561821207 0.0301251141513143 0.0274711223926413 0.136320972222362 -0.0309536091999092 0.999062982942556 0.0302494659691991 0.00749343376812043 -0.0265341128670338 -0.0310746457951289 0.999164804846061 0.0149435293090542 3.27398339539457e-05 -1.57538401482211e-05 -1.00638777615246e-06 2.28736082104259e-06 1.11780540963146e-06 2.60374032341715e-05 -1.57538401482211e-05 4.44427647371042e-05 1.15362083306396e-06 -7.43151509183354e-06 -3.33902801651817e-08 2.12901683226354e-05 -1.00638777615246e-06 1.15362083306396e-06 1.13785802641454e-05 -2.74704949357683e-06 4.68658180959936e-06 2.41989122809478e-06 2.28736082104259e-06 -7.43151509183354e-06 -2.74704949357683e-06 6.76227347965132e-05 -7.25479247145665e-07 -1.57210018572634e-05 1.11780540963146e-06 -3.33902801651817e-08 4.68658180959936e-06 -7.25479247145665e-07 1.03462203622635e-05 9.64146144028593e-06 2.60374032341715e-05 2.12901683226354e-05 2.41989122809478e-06 -1.57210018572634e-05 9.64146144028593e-06 0.000354022910877319 3372 3386 0 202 43 3372 3386 0 154 106 0 0 0 0 0 0 0 0 3633 0 0 0 0 0 3740 +1196 1197 -0.422009976501958 -0.0461047674942906 0.905418096874098 -0.449724233275403 -0.0646452304165518 0.997694156357174 0.0206727974676322 -0.0131244526113366 -0.904283458832023 -0.0498068347221968 -0.424017340798402 -0.253000563024344 0.000252251568796512 -0.000896105197978403 -3.57160347511831e-05 -0.0012311135869999 -7.70684348068578e-05 -0.000642838176812543 -0.000896105197978403 0.0180188289176544 -0.000185302229886741 0.0142777298580378 0.000811310696126618 -0.000375582583338635 -3.57160347511831e-05 -0.000185302229886741 0.000113335381530539 -0.000433612414703665 -1.65661277606571e-05 0.000256528498260022 -0.0012311135869999 0.0142777298580378 -0.000433612414703665 0.0199505560136017 0.00110416126904895 0.0017268742063903 -7.70684348068578e-05 0.000811310696126618 -1.65661277606571e-05 0.00110416126904895 7.44661500478296e-05 0.00014951178581808 -0.000642838176812543 -0.000375582583338635 0.000256528498260022 0.0017268742063903 0.00014951178581808 0.00496939378429705 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2251 0 0 0 0 0 2284 +1192 1193 0.97149020410524 -0.027162471006266 -0.235518541725259 0.0417894258255296 0.0251541717479988 0.99961711402559 -0.0115279222248795 0.025374397840637 0.235741491832115 0.00527498966676209 0.971801483592603 0.20329764629601 4.6621153542533e-05 -2.12325182007935e-05 -1.32492406497621e-05 -5.72755423329095e-05 -2.84096226859483e-06 3.48932268114749e-05 -2.12325182007935e-05 0.00113547099698767 -1.54536160897046e-05 -0.000777057403691106 -1.07689515656786e-05 -0.000141996802705119 -1.32492406497621e-05 -1.54536160897046e-05 1.76074448899974e-05 3.28687557800729e-06 5.57046515298362e-06 1.09668049627555e-05 -5.72755423329095e-05 -0.000777057403691106 3.28687557800729e-06 0.0010366838287812 6.51567318976196e-06 -0.000209440720760494 -2.84096226859483e-06 -1.07689515656786e-05 5.57046515298362e-06 6.51567318976196e-06 1.11269176344771e-05 3.40713069410729e-06 3.48932268114749e-05 -0.000141996802705119 1.09668049627555e-05 -0.000209440720760494 3.40713069410729e-06 0.000438155648895886 1603 1614 0 0 40 1564 1587 0 0 74 0 0 0 0 0 20 1 0 3449 0 0 0 0 0 3400 +1183 1184 0.999885036248065 0.0142479343773831 0.00518754789691475 0.13987039497983 -0.0141909391302887 0.999840295783854 -0.0108627884751472 0.0046937014058013 -0.00534149172099344 0.0107879234717871 0.999927541961597 -0.0397647939150821 3.33901896278076e-05 5.64889802724514e-06 -9.36771930511511e-06 2.0651393534883e-06 -1.77318889901365e-06 -9.75545004071086e-06 5.64889802724514e-06 9.61902054447537e-05 -1.34687355153338e-06 -1.62096523055643e-05 3.84327726901763e-07 -2.43302942381838e-05 -9.36771930511511e-06 -1.34687355153338e-06 1.17077360344117e-05 -5.63033943132119e-10 5.61827782013054e-06 -3.83518814178454e-07 2.0651393534883e-06 -1.62096523055643e-05 -5.63033943132119e-10 9.93604679180228e-05 -1.08988108737985e-06 -4.9825325868594e-05 -1.77318889901365e-06 3.84327726901763e-07 5.61827782013054e-06 -1.08988108737985e-06 9.70352337852499e-06 1.75690738324487e-06 -9.75545004071086e-06 -2.43302942381838e-05 -3.83518814178454e-07 -4.9825325868594e-05 1.75690738324487e-06 0.000493423505620578 3442 3433 0 180 84 3442 3433 0 118 137 0 0 0 0 0 0 0 0 3658 0 0 0 0 0 3654 +1182 1183 0.9998247370817 -0.0138479023967033 0.0125988379909067 0.134134326209465 0.0138942032327148 0.999897008501501 -0.00359492785422766 0.0151799479147487 -0.0125477582076541 0.00376934861222256 0.999914169204038 -0.0454193839731391 4.4685877717634e-05 -1.78311613363058e-06 -6.09782570030584e-06 1.33439231637781e-05 -2.17005284560659e-06 -2.09363848148032e-05 -1.78311613363058e-06 0.000122185524032637 6.49402727544679e-07 4.39746288147921e-05 -4.9411988185179e-08 -8.60431178655438e-05 -6.09782570030584e-06 6.49402727544679e-07 1.27686673795214e-05 6.65026697190803e-07 6.03721841377809e-06 -3.13070812496808e-06 1.33439231637781e-05 4.39746288147921e-05 6.65026697190803e-07 0.000126381688662644 5.6230964770926e-08 -0.000108081393422231 -2.17005284560659e-06 -4.9411988185179e-08 6.03721841377809e-06 5.6230964770926e-08 1.00905451582957e-05 -9.38802881050741e-06 -2.09363848148032e-05 -8.60431178655438e-05 -3.13070812496808e-06 -0.000108081393422231 -9.38802881050741e-06 0.00109906805725983 3284 3272 0 84 162 3284 3272 0 29 209 0 0 0 0 0 0 0 0 3739 0 0 0 0 0 3581 +1185 1186 0.999510641712365 0.0257419507339408 -0.0177715805753811 0.154015438779606 -0.0261892958363395 0.99933385999456 -0.0254156851564142 0.00626923380272805 0.0171054928994342 0.025868672961415 0.999518991251233 0.00596493968526529 4.72755652257701e-05 -1.46965489777377e-06 2.80947241956022e-06 4.31672016892214e-06 1.42508716427586e-06 2.45751202911891e-05 -1.46965489777377e-06 7.30861655874475e-05 -4.21754794605517e-06 9.42793990935781e-06 1.28527350858524e-05 0.000248642451291306 2.80947241956022e-06 -4.21754794605517e-06 1.01968440012685e-05 -2.03535355688864e-07 4.31569396184787e-06 -1.5016020702787e-05 4.31672016892214e-06 9.42793990935781e-06 -2.03535355688864e-07 0.00010904290693282 7.2177885769577e-06 8.50228793357281e-05 1.42508716427586e-06 1.28527350858524e-05 4.31569396184787e-06 7.2177885769577e-06 1.26805807080134e-05 7.01378418366943e-05 2.45751202911891e-05 0.000248642451291306 -1.5016020702787e-05 8.50228793357281e-05 7.01378418366943e-05 0.00145096035518397 3608 3607 0 232 70 3608 3607 0 164 119 0 0 0 0 0 0 0 0 3607 0 0 0 0 0 3698 +1197 1198 0.999079050729121 0.0235745074720135 0.0358509831336677 0.143793574939698 -0.023201101962643 0.999672522435821 -0.0107961453547844 0.00376595059043872 -0.0360937565503729 0.00995442033744636 0.999298829306743 0.0738824709822446 5.28718160199253e-05 -1.41375384264228e-05 4.08139465939411e-06 -8.28242939005519e-06 -9.55789497798913e-08 -7.33954085468977e-06 -1.41375384264228e-05 0.000297283325565231 -2.93191097932483e-06 0.000155385024650454 5.35334278290165e-06 -0.000378534682774407 4.08139465939411e-06 -2.93191097932483e-06 9.99735110380522e-06 -3.6579337145744e-06 4.48637349557164e-06 -3.71825677780027e-06 -8.28242939005519e-06 0.000155385024650454 -3.6579337145744e-06 0.000176871009669649 6.2440859412986e-06 -0.000293397959105975 -9.55789497798913e-08 5.35334278290165e-06 4.48637349557164e-06 6.2440859412986e-06 9.77797896782986e-06 -4.45016821781442e-06 -7.33954085468977e-06 -0.000378534682774407 -3.71825677780027e-06 -0.000293397959105975 -4.45016821781442e-06 0.00103492956672504 3472 3453 0 225 74 3472 3453 0 155 117 0 0 0 0 0 0 0 0 3588 0 0 0 0 0 3738 +1191 1192 0.999385852525804 -0.0122133156111551 -0.0328443707970657 0.142192199123064 0.0123573099845076 0.999914888862346 0.00418472476373791 0.030353528267979 0.0327904660110163 -0.00458802279677951 0.999451717385886 0.0247976730039948 3.82010695305806e-05 -3.90629437033559e-06 -4.39522862987281e-06 1.45814130936347e-07 -1.47886278043519e-06 -1.53494694695241e-06 -3.90629437033559e-06 6.40403617844205e-05 -2.68743404666393e-06 2.63808252165081e-05 7.2155858065432e-07 -5.02994898519707e-05 -4.39522862987281e-06 -2.68743404666393e-06 1.00479681350107e-05 -7.20383558386351e-06 4.95745547966614e-06 7.75315250963571e-07 1.45814130936347e-07 2.63808252165081e-05 -7.20383558386351e-06 7.43505212575668e-05 7.28698653807396e-07 -2.74804037668347e-05 -1.47886278043519e-06 7.2155858065432e-07 4.95745547966614e-06 7.28698653807396e-07 9.27273512409752e-06 -8.70161912269794e-07 -1.53494694695241e-06 -5.02994898519707e-05 7.75315250963571e-07 -2.74804037668347e-05 -8.70161912269794e-07 0.000119064259170087 3298 3288 0 75 181 3298 3288 0 15 236 0 0 0 0 0 0 0 0 3722 0 0 0 0 0 3616 +1190 1191 0.998953759277698 -0.0211816472064333 -0.0405305396778545 0.146744031802616 0.0217015777374806 0.999687202085508 0.0124313921244701 0.0267697211819489 0.0402545444473047 -0.0132979625533555 0.99910096378858 -0.00924242016949599 3.47942342491675e-05 -9.55703216855775e-06 -1.83947114665543e-06 -6.97495479346848e-06 -7.04894581052058e-07 4.80207935077095e-06 -9.55703216855775e-06 3.8066835752923e-05 -2.83035894315373e-06 1.6746704263719e-05 -1.43253966389209e-07 -2.35564936714533e-05 -1.83947114665543e-06 -2.83035894315373e-06 1.00620049452769e-05 -3.6053487549169e-06 4.32308964445747e-06 3.33464865960536e-06 -6.97495479346848e-06 1.6746704263719e-05 -3.6053487549169e-06 7.19075922376875e-05 -4.20788319246548e-07 -1.4182674690112e-05 -7.04894581052058e-07 -1.43253966389209e-07 4.32308964445747e-06 -4.20788319246548e-07 9.26496051640535e-06 2.68725589275034e-06 4.80207935077095e-06 -2.35564936714533e-05 3.33464865960536e-06 -1.4182674690112e-05 2.68725589275034e-06 0.000122960784280745 3310 3309 0 67 203 3310 3309 0 9 257 0 0 0 0 0 0 0 0 3734 0 0 0 0 0 3576 +1199 1200 0.999503051792151 -0.00927551297155912 0.0301266380017989 0.135286998675822 0.00989936842170256 0.999738270495224 -0.0206250578682867 0.00633378349354318 -0.0299274449799577 0.0209130429716294 0.999333274073589 0.0432449313120526 2.7872439064877e-05 -1.13703627742062e-05 -2.56108745479696e-06 4.71610510714701e-06 -2.35813125031743e-06 -9.5505788449921e-06 -1.13703627742062e-05 4.54254498640729e-05 -6.06344514058831e-07 -2.80219451776494e-06 3.76374881502407e-06 7.93551596913351e-05 -2.56108745479696e-06 -6.06344514058831e-07 8.50970283499079e-06 -1.9090076931274e-06 3.14660931038227e-06 -4.96880844539033e-06 4.71610510714701e-06 -2.80219451776494e-06 -1.9090076931274e-06 6.80734021732162e-05 3.07323475813455e-06 -3.62287559878381e-05 -2.35813125031743e-06 3.76374881502407e-06 3.14660931038227e-06 3.07323475813455e-06 9.99598077843617e-06 1.37873629554046e-05 -9.5505788449921e-06 7.93551596913351e-05 -4.96880844539033e-06 -3.62287559878381e-05 1.37873629554046e-05 0.000397983902848938 3590 3572 0 120 138 3590 3572 0 55 184 0 0 0 0 0 0 0 0 3678 0 0 0 0 0 3648 +1194 1195 0.999843976465181 0.0171687641084315 0.00415406611457578 0.145303424270436 -0.0171831802533438 0.999846371805702 0.00345992822975391 0.0110067165831208 -0.00409402524129086 -0.00353076846635234 0.999985386208899 -0.0394501284826795 3.61893316353862e-05 -4.72887222407521e-06 -2.29494788461453e-06 -3.24883814655426e-06 -1.20927639018923e-06 2.91918012779075e-06 -4.72887222407521e-06 3.53363323077935e-05 -1.73773214989835e-06 1.47493615417055e-05 -9.00827755896436e-07 1.75109510388401e-05 -2.29494788461453e-06 -1.73773214989835e-06 1.09698095600965e-05 1.68214996259677e-07 3.98064147778149e-06 -2.1347870724119e-06 -3.24883814655426e-06 1.47493615417055e-05 1.68214996259677e-07 5.84179473837132e-05 -2.64154092657223e-06 -1.8906515550352e-05 -1.20927639018923e-06 -9.00827755896436e-07 3.98064147778149e-06 -2.64154092657223e-06 9.71140967501183e-06 2.87565575922549e-06 2.91918012779075e-06 1.75109510388401e-05 -2.1347870724119e-06 -1.8906515550352e-05 2.87565575922549e-06 0.000299975330872332 3464 3435 0 194 93 3464 3435 0 114 133 0 0 0 0 0 0 0 0 3594 0 0 0 0 0 3697 +1195 1196 0.999281918661442 0.0157127859520318 -0.0344783322382634 0.146797497951401 -0.0153910525383738 0.999835683513227 0.00957713294249858 0.00778634968997102 0.0346231503197998 -0.00903959795914107 0.999359556481385 -0.0644273428130251 3.88010324035617e-05 -7.57553019399698e-06 -5.78226888914166e-06 1.68185991493614e-06 5.72880932455115e-07 1.22682413868394e-05 -7.57553019399698e-06 7.12239288248956e-05 2.85165256109767e-06 -5.67654402298975e-06 -2.60631812140008e-06 0.00010927144749478 -5.78226888914166e-06 2.85165256109767e-06 9.89470422404884e-06 -1.10638160519796e-06 3.81269076146768e-06 -1.13698735545985e-06 1.68185991493614e-06 -5.67654402298975e-06 -1.10638160519796e-06 8.54975837321751e-05 -8.55180268728188e-07 -3.26622532867025e-05 5.72880932455115e-07 -2.60631812140008e-06 3.81269076146768e-06 -8.55180268728188e-07 9.21461787931545e-06 -3.77233387129484e-06 1.22682413868394e-05 0.00010927144749478 -1.13698735545985e-06 -3.26622532867025e-05 -3.77233387129484e-06 0.000698414829053615 3763 3737 0 190 94 3763 3737 0 118 132 0 0 0 0 0 0 0 0 3605 0 0 0 0 0 3714 +1204 1205 0.999969932607071 8.28837811073542e-05 0.00775416095327463 0.139880959910396 3.79862273674123e-05 0.99987852528707 -0.0155863153696063 0.00519699904102419 -0.00775451087155018 0.0155861412810588 0.999848458398126 0.0262424104296595 5.77719836583375e-05 -4.27818066188034e-06 -1.61986415025459e-06 -9.6826227665256e-06 -3.07361777879247e-07 2.71915020888427e-05 -4.27818066188034e-06 5.61040309394428e-05 -4.42594523788115e-06 2.95885922757908e-05 -6.63096182276954e-07 -1.95121691185976e-05 -1.61986415025459e-06 -4.42594523788115e-06 1.07935492594438e-05 -4.65700967039704e-07 4.2736129830011e-06 1.75154867730047e-06 -9.6826227665256e-06 2.95885922757908e-05 -4.65700967039704e-07 7.59646782794658e-05 -2.04195682220334e-06 -7.35797878851613e-05 -3.07361777879247e-07 -6.63096182276954e-07 4.2736129830011e-06 -2.04195682220334e-06 9.02230838076259e-06 2.24420485179725e-06 2.71915020888427e-05 -1.95121691185976e-05 1.75154867730047e-06 -7.35797878851613e-05 2.24420485179725e-06 0.000274133149839201 3555 3526 0 151 117 3555 3526 0 81 157 0 0 0 0 0 0 0 0 3650 0 0 0 0 0 3670 +1200 1201 0.999931373461592 -0.00556201316130014 -0.0103107893397355 0.141013741297377 0.00569888956130201 0.999895396470619 0.0132935613976143 0.000885379890261351 0.0102357718313258 -0.0133514091562495 0.999858474409533 -0.014243074889606 3.93879056384975e-05 -2.29481688311032e-05 2.22318133477154e-06 -6.50601937920521e-06 -4.5938980489334e-07 1.06726423369619e-05 -2.29481688311032e-05 6.03948638657566e-05 -4.06573319744702e-06 2.33553991338093e-05 -1.78548338555442e-06 -4.20054911934181e-05 2.22318133477154e-06 -4.06573319744702e-06 1.08439043210661e-05 -3.36122471686517e-06 4.42139346375631e-06 1.88065302736618e-06 -6.50601937920521e-06 2.33553991338093e-05 -3.36122471686517e-06 5.23684143581854e-05 -8.09750519468891e-07 -2.79712169818379e-05 -4.5938980489334e-07 -1.78548338555442e-06 4.42139346375631e-06 -8.09750519468891e-07 9.63653545590991e-06 4.80663812866461e-06 1.06726423369619e-05 -4.20054911934181e-05 1.88065302736618e-06 -2.79712169818379e-05 4.80663812866461e-06 0.000171027006142302 3383 3364 0 134 134 3383 3364 0 64 179 0 0 0 0 0 0 0 0 3658 0 0 0 0 0 3651 +1201 1202 0.999251768739581 -0.0178636677525566 -0.0343044027093578 0.141717503606535 0.0191147986008955 0.999150949124527 0.03649664831191 0.00294198182733788 0.033623312526679 -0.0371250621276559 0.998744813561878 -0.00214938571004271 3.90077228386468e-05 -5.53798449682913e-06 -3.15715333328298e-07 -3.23240094503181e-06 -1.19692898128695e-06 1.25563968833857e-05 -5.53798449682913e-06 4.4244318761714e-05 -1.8139923987422e-06 1.95027198335638e-05 -4.25162678974503e-07 -1.9969537029583e-05 -3.15715333328298e-07 -1.8139923987422e-06 1.19939791959164e-05 -2.10393700209887e-06 3.77810636516968e-06 2.41968974499546e-06 -3.23240094503181e-06 1.95027198335638e-05 -2.10393700209887e-06 6.90559457132026e-05 -8.38128051741631e-07 -1.82436281771633e-05 -1.19692898128695e-06 -4.25162678974503e-07 3.77810636516968e-06 -8.38128051741631e-07 9.97597623660404e-06 -1.67836989506458e-06 1.25563968833857e-05 -1.9969537029583e-05 2.41968974499546e-06 -1.82436281771633e-05 -1.67836989506458e-06 0.000124917718367983 3573 3553 0 100 165 3573 3553 0 29 209 0 0 0 0 0 0 0 0 3687 0 0 0 0 0 3609 +1205 1206 0.999450929550605 0.0292858792719001 -0.0154976351648796 0.13695766471759 -0.0292530219842687 0.99956929357781 0.00234265685636772 -0.00371012363318231 0.0155595669997564 -0.00188801791053242 0.999877160086753 0.0534697998141058 2.64562192883505e-05 -8.80243357042338e-06 1.47317007547424e-06 6.20283455479323e-07 -4.37856715171766e-07 4.42211892348567e-06 -8.80243357042338e-06 3.26224904540337e-05 -2.47755727182214e-06 4.3071115537948e-06 8.97839381510336e-07 -1.46651157953811e-06 1.47317007547424e-06 -2.47755727182214e-06 8.85718074260151e-06 -5.93161906091015e-07 3.66674165799413e-06 4.42891372526311e-06 6.20283455479323e-07 4.3071115537948e-06 -5.93161906091015e-07 4.31387232400427e-05 -4.63094864393647e-09 -3.31581625448321e-05 -4.37856715171766e-07 8.97839381510336e-07 3.66674165799413e-06 -4.63094864393647e-09 8.82521667477196e-06 -1.37707979540071e-06 4.42211892348567e-06 -1.46651157953811e-06 4.42891372526311e-06 -3.31581625448321e-05 -1.37707979540071e-06 0.000259927968085924 3581 3561 0 231 40 3581 3561 0 158 78 0 0 0 0 0 0 0 0 3584 0 0 0 0 0 3748 +1203 1204 0.999778583512747 -0.0165099027071592 0.0130463428532649 0.134440176435519 0.0166105672790348 0.999832802946367 -0.00764560050488904 0.00995849806245703 -0.0129179334227056 0.00786061479859182 0.999885662328986 0.0164134740445824 3.55635343387248e-05 -5.67601417972288e-06 -1.43219509329275e-06 -8.01638047685982e-06 -6.30761717309117e-07 7.5127969563809e-06 -5.67601417972288e-06 3.77966937426717e-05 2.62179612918024e-07 1.11475175054018e-05 -5.59752548706627e-08 -1.6242664605668e-05 -1.43219509329275e-06 2.62179612918024e-07 8.0316961575428e-06 -8.90746832930161e-07 4.17611746450085e-06 7.47508627904563e-07 -8.01638047685982e-06 1.11475175054018e-05 -8.90746832930161e-07 4.40040122949846e-05 -3.86381565569334e-07 -1.84665468759885e-05 -6.30761717309117e-07 -5.59752548706627e-08 4.17611746450085e-06 -3.86381565569334e-07 8.28419684134257e-06 -1.9106054871913e-06 7.5127969563809e-06 -1.6242664605668e-05 7.47508627904563e-07 -1.84665468759885e-05 -1.9106054871913e-06 0.000131006363378318 3641 3614 0 92 160 3641 3614 0 22 204 0 0 0 0 0 0 0 0 3695 0 0 0 0 0 3629 +1206 1207 0.999529661980256 0.0281594601725823 -0.0121449423392237 0.1561871772182 -0.0284512890317548 0.999293277458179 -0.0245656218997496 0.000346691713607008 0.0114446045832027 0.0248996070185588 0.999624444777265 -0.043798298208183 4.64622579843512e-05 -2.76980430506253e-05 -8.05169910885571e-06 1.22601571071405e-06 -1.21477201455402e-07 4.04711172989141e-05 -2.76980430506253e-05 0.000109368124430997 1.43830114779262e-06 3.76939730910736e-05 2.20446204767448e-06 -1.33541378310327e-05 -8.05169910885571e-06 1.43830114779262e-06 1.23542381306819e-05 -1.85525856509553e-06 4.64277422496872e-06 -7.98648934497442e-06 1.22601571071405e-06 3.76939730910736e-05 -1.85525856509553e-06 6.8336540212505e-05 -7.65403693435185e-08 -1.11126493928514e-05 -1.21477201455402e-07 2.20446204767448e-06 4.64277422496872e-06 -7.65403693435185e-08 9.66762276250001e-06 1.06843792432023e-05 4.04711172989141e-05 -1.33541378310327e-05 -7.98648934497442e-06 -1.11126493928514e-05 1.06843792432023e-05 0.000344093463097904 3572 3565 0 244 67 3572 3565 0 175 109 0 0 0 0 0 0 0 0 3560 0 0 0 0 0 3742 +1198 1199 0.99925488451263 -0.000131631749145868 0.038596093723754 0.141750653795848 0.000633097207151402 0.999915546563133 -0.0129807137429752 0.00538719062570575 -0.0385911254769342 0.0129954766912716 0.99917057733902 0.0766685770759012 3.25984821077334e-05 -2.39078037686503e-05 -2.15810967827997e-06 4.21902962526471e-06 -2.03258428700206e-06 -2.51003029273291e-05 -2.39078037686503e-05 0.000108800238766115 -1.77546859989369e-06 -3.47326975695061e-05 4.55746478088778e-06 0.00024032315865943 -2.15810967827997e-06 -1.77546859989369e-06 9.37578830446842e-06 -1.26532032009245e-06 3.34501010006148e-06 -9.49959182803638e-06 4.21902962526471e-06 -3.47326975695061e-05 -1.26532032009245e-06 9.98771230577068e-05 3.74448165443299e-06 -0.000133912963536096 -2.03258428700206e-06 4.55746478088778e-06 3.34501010006148e-06 3.74448165443299e-06 1.09564111846128e-05 3.84134716277124e-05 -2.51003029273291e-05 0.00024032315865943 -9.49959182803638e-06 -0.000133912963536096 3.84134716277124e-05 0.00161969431827273 3554 3540 0 140 120 3554 3540 0 70 168 0 0 0 0 0 0 0 0 3666 0 0 0 0 0 3674 +1208 1209 0.999292834452193 0.0321318342018728 0.0195288566824724 0.133732570310512 -0.0321196173542043 0.999483590892451 -0.000938998270311886 0.00511936060407992 -0.019548943539759 0.000311074839079562 0.999808852750826 0.0620134524218299 5.00703979736495e-05 -2.89216391057426e-05 -2.00703951591802e-06 -1.36638213520834e-05 5.80434564238669e-07 2.33264828981676e-05 -2.89216391057426e-05 0.000115627800352676 -6.04415899360713e-06 4.27745127293317e-05 1.37047325525193e-06 -5.93170769334634e-05 -2.00703951591802e-06 -6.04415899360713e-06 1.11414438407114e-05 -4.51876939891658e-06 2.49690539420975e-06 -8.65849999462168e-07 -1.36638213520834e-05 4.27745127293317e-05 -4.51876939891658e-06 6.53553372617751e-05 2.56617223422266e-06 -4.2617929950572e-05 5.80434564238669e-07 1.37047325525193e-06 2.49690539420975e-06 2.56617223422266e-06 1.15125809124688e-05 1.92678784586128e-05 2.33264828981676e-05 -5.93170769334634e-05 -8.65849999462168e-07 -4.2617929950572e-05 1.92678784586128e-05 0.000456160205111113 3525 3532 0 217 40 3525 3532 0 156 88 0 0 0 0 0 0 0 0 3616 0 0 0 0 0 3763 +1207 1208 0.999564145657628 0.0158023742647723 -0.0249359917254446 0.144009235986194 -0.0164310410558815 0.999547109920294 -0.0252110281386609 0.0046596127348477 0.0245263043599177 0.0256097641063809 0.999371102432355 0.0218856261677484 4.20888524608661e-05 -1.83668644234712e-05 7.15816227886293e-07 -8.89458782531684e-06 -7.43332092094637e-07 1.07552528696501e-05 -1.83668644234712e-05 5.11504406554614e-05 -1.37492163380413e-06 1.63349096824352e-05 -4.28651656754087e-07 -3.76787281264534e-05 7.15816227886293e-07 -1.37492163380413e-06 9.83114102142035e-06 -3.29820859503118e-06 3.16080956464737e-06 2.26104907676387e-06 -8.89458782531684e-06 1.63349096824352e-05 -3.29820859503118e-06 3.8901666248212e-05 -3.41108096696809e-07 -2.03706322602878e-05 -7.43332092094637e-07 -4.28651656754087e-07 3.16080956464737e-06 -3.41108096696809e-07 9.29791396475908e-06 2.61875262571633e-06 1.07552528696501e-05 -3.76787281264534e-05 2.26104907676387e-06 -2.03706322602878e-05 2.61875262571633e-06 0.000104585904655694 3619 3615 0 186 77 3619 3615 0 132 129 0 0 0 0 0 0 0 0 3628 0 0 0 0 0 3706 +1202 1203 0.999649126118212 -0.0116815772504867 -0.0237732076934483 0.144941223898521 0.0121760949898726 0.999710254680848 0.0207641372744371 0.00629939174256304 0.0235237616441869 -0.0210463165160791 0.999501718457358 0.0274586274712813 5.13670706223437e-05 1.78489315250685e-05 4.25659321831815e-06 1.94844411593896e-05 2.51321709435433e-06 -0.000119557590436615 1.78489315250685e-05 0.000344866414624103 1.13387543437778e-05 0.000187513197753843 2.5405669707275e-05 -0.000875911442227294 4.25659321831815e-06 1.13387543437778e-05 1.17821439522159e-05 4.73771233522694e-06 5.79374070380942e-06 -3.70379008452554e-05 1.94844411593896e-05 0.000187513197753843 4.73771233522694e-06 0.000193589579563344 1.90337674909788e-05 -0.000694708540462802 2.51321709435433e-06 2.5405669707275e-05 5.79374070380942e-06 1.90337674909788e-05 1.17917634652032e-05 -0.000118782796740469 -0.000119557590436615 -0.000875911442227294 -3.70379008452554e-05 -0.000694708540462802 -0.000118782796740469 0.00530301799629627 3128 3102 0 120 157 3128 3102 0 49 203 0 0 0 0 0 0 0 0 3674 0 0 0 0 0 3625 +1209 1210 0.999212586896136 0.0171894473015595 0.0357593217189453 0.133638991634464 -0.0177804161956119 0.999709457635746 0.0162744312820313 0.00963522808120163 -0.0354691836421836 -0.0168974322046176 0.999227908835941 0.0725528878362634 5.53970099377854e-05 -5.76796233060937e-05 2.57017287205693e-06 -2.4767649043807e-05 -1.65496703900341e-06 1.67051269351213e-05 -5.76796233060937e-05 0.000146884072866283 -6.3072379264411e-06 7.59899129349492e-05 5.50482142744499e-06 -6.20053543733074e-05 2.57017287205693e-06 -6.3072379264411e-06 9.55002494865054e-06 -6.33301738432645e-06 2.21198172163154e-06 -7.13479208171591e-08 -2.4767649043807e-05 7.59899129349492e-05 -6.33301738432645e-06 9.07535803025833e-05 6.10087449852349e-06 -9.87912225413991e-05 -1.65496703900341e-06 5.50482142744499e-06 2.21198172163154e-06 6.10087449852349e-06 1.08400287331645e-05 1.25235082474026e-05 1.67051269351213e-05 -6.20053543733074e-05 -7.13479208171591e-08 -9.87912225413991e-05 1.25235082474026e-05 0.000692368285805036 3475 3485 0 158 69 3475 3485 0 107 127 0 0 0 0 0 0 0 0 3651 0 0 0 0 0 3734 +1214 1215 0.999538679642065 -0.0299411237045122 0.00509480232280848 0.139636295511528 0.029975692080552 0.999527158610883 -0.00684960462700368 0.0233531007911161 -0.00488730842993677 0.00699916499058522 0.999963562289019 0.0247357347305639 3.99052774722917e-05 -1.8671165032642e-05 -8.08992211838165e-06 -4.44274969272654e-07 -1.48212372890434e-07 2.4520006338472e-05 -1.8671165032642e-05 5.94021313909102e-05 1.66048494303943e-06 7.36712964354307e-06 -2.07703473189185e-07 -3.73289344282777e-05 -8.08992211838165e-06 1.66048494303943e-06 1.44877939369677e-05 2.3938433134781e-07 6.01831927351571e-06 3.45182905629835e-06 -4.44274969272654e-07 7.36712964354307e-06 2.3938433134781e-07 3.85204668642988e-05 1.14133355311281e-06 -6.1710677524915e-06 -1.48212372890434e-07 -2.07703473189185e-07 6.01831927351571e-06 1.14133355311281e-06 1.00478285509203e-05 -4.25738034975928e-06 2.4520006338472e-05 -3.73289344282777e-05 3.45182905629835e-06 -6.1710677524915e-06 -4.25738034975928e-06 0.000330254020715583 3561 3526 0 44 207 3561 3526 0 0 252 0 0 0 0 0 0 0 0 3716 0 0 0 0 0 3578 +1213 1214 0.999046047117442 -0.0250829464451602 -0.0357469094698088 0.137448196817908 0.0257601784974192 0.999494872281 0.0186121865391391 0.0244670877991735 0.0352620042367785 -0.0195152781588127 0.999187542444155 0.0548421864927249 3.26819240443147e-05 -1.24014378987986e-05 8.52079778485836e-07 -2.3753683670195e-06 8.21980115223277e-07 9.282855890534e-06 -1.24014378987986e-05 4.23028365993007e-05 -4.16038284524957e-07 7.25806677543996e-06 1.7052133858484e-07 3.07433721394336e-06 8.52079778485836e-07 -4.16038284524957e-07 9.17062755881453e-06 -1.27528219029894e-06 3.67123117617498e-06 -4.61427241552449e-06 -2.3753683670195e-06 7.25806677543996e-06 -1.27528219029894e-06 2.78816439917299e-05 -5.79646665108231e-08 -3.20839836269161e-05 8.21980115223277e-07 1.7052133858484e-07 3.67123117617498e-06 -5.79646665108231e-08 8.59083858650643e-06 -6.3915989848004e-06 9.282855890534e-06 3.07433721394336e-06 -4.61427241552449e-06 -3.20839836269161e-05 -6.3915989848004e-06 0.000565591031717501 3524 3503 0 42 202 3524 3503 0 0 253 0 0 0 0 0 0 0 0 3721 0 0 0 0 0 3584 +1216 1217 0.999646770027126 0.0237881631365486 -0.0118515175789016 0.137554795314791 -0.0236124244734829 0.999612311795975 0.0147539661241166 0.00469877963749932 0.0121978926384081 -0.0144689115173348 0.999820914971619 0.130636559126024 3.8446153050379e-05 -2.64611300815137e-08 -5.49463793960304e-06 -5.25233315625525e-06 -2.24279841448504e-06 -7.33316584799353e-06 -2.64611300815137e-08 7.20979764676414e-05 1.89851544116338e-06 8.89816715856143e-06 1.51925475625495e-06 -3.09156533024472e-05 -5.49463793960304e-06 1.89851544116338e-06 1.2117373592806e-05 -4.41638675431552e-06 3.95950391464966e-06 -1.31121191703979e-06 -5.25233315625525e-06 8.89816715856143e-06 -4.41638675431552e-06 3.72383476524122e-05 4.00790928384914e-07 -4.42270347825446e-05 -2.24279841448504e-06 1.51925475625495e-06 3.95950391464966e-06 4.00790928384914e-07 9.69531039072782e-06 -3.83554361014174e-06 -7.33316584799353e-06 -3.09156533024472e-05 -1.31121191703979e-06 -4.42270347825446e-05 -3.83554361014174e-06 0.000523048765091257 3571 3536 0 208 56 3571 3536 0 134 91 0 0 0 0 0 0 0 0 3584 0 0 0 0 0 3730 +1219 1220 0.999813587877834 0.0178759101300009 0.00729666580550106 0.137946439395203 -0.0180073995736636 0.99966906161596 0.0183711950743452 -0.000643950994331021 -0.0069658492265808 -0.0184991644375998 0.999804609841174 0.0767675248529494 3.84131548756213e-05 -1.8538599458248e-05 -1.15011536154222e-06 -5.11772331336134e-06 -6.12293974355789e-07 1.47550117053949e-05 -1.8538599458248e-05 4.09500385547464e-05 -9.23357359082185e-07 1.68842022647985e-05 2.41183976665099e-06 -7.96040032283424e-06 -1.15011536154222e-06 -9.23357359082185e-07 1.08470893668554e-05 -6.72738043929516e-06 2.49010460915109e-06 -3.11047818149293e-06 -5.11772331336134e-06 1.68842022647985e-05 -6.72738043929516e-06 3.103121009832e-05 1.36767109119813e-06 -4.21207082904787e-06 -6.12293974355789e-07 2.41183976665099e-06 2.49010460915109e-06 1.36767109119813e-06 9.30392244043304e-06 8.25341317479088e-07 1.47550117053949e-05 -7.96040032283424e-06 -3.11047818149293e-06 -4.21207082904787e-06 8.25341317479088e-07 0.000118510524034274 3606 3590 0 197 70 3606 3590 0 124 117 0 0 0 0 0 0 0 0 3619 0 0 0 0 0 3734 +1210 1211 0.999279818022598 -0.0097236784034984 0.0366782683755407 0.143631296972305 0.00931274800265181 0.999892129513921 0.0113579074109216 0.0191445887810416 -0.036784752511903 -0.0110081521801482 0.99926257938953 0.101298887963791 5.13966652388114e-05 -3.39969282596317e-05 3.03563455687883e-07 -9.41632114283125e-06 -5.21636461150102e-07 1.57477008387625e-05 -3.39969282596317e-05 0.000120019836586794 -2.96417155310507e-06 2.43871615987908e-05 4.08104801331733e-06 -7.3586250276133e-06 3.03563455687883e-07 -2.96417155310507e-06 1.12468271822562e-05 1.57153928247827e-07 3.54860731647401e-06 -1.62038840367255e-06 -9.41632114283125e-06 2.43871615987908e-05 1.57153928247827e-07 7.6298737492327e-05 7.53262162028994e-06 -1.91272926713431e-05 -5.21636461150102e-07 4.08104801331733e-06 3.54860731647401e-06 7.53262162028994e-06 1.08070468892758e-05 6.52847718858356e-06 1.57477008387625e-05 -7.3586250276133e-06 -1.62038840367255e-06 -1.91272926713431e-05 6.52847718858356e-06 0.000241615158783437 3561 3572 0 95 165 3561 3572 0 49 223 0 0 0 0 0 0 0 0 3697 0 0 0 0 0 3601 +1215 1216 -0.990379807108884 0.00188600178342668 -0.138362858702195 0.562536574263155 -0.000313443136094309 0.999873971667003 0.0158726978253431 0.0178636386706484 0.13837535699817 0.0157633682989115 -0.990254400038446 0.0812387125027878 5.18048608213683e-05 -0.000323160562472201 -4.86666024548012e-06 4.32427716034573e-05 3.41021759646536e-07 -3.97588686355441e-05 -0.000323160562472201 0.0406136202851496 1.96263229914707e-05 -0.00712508856271752 0.000104187499390075 -0.00214520296788596 -4.86666024548012e-06 1.96263229914707e-05 1.24071286058034e-05 1.06308028973289e-06 -3.9641708225941e-06 -2.88058218935848e-05 4.32427716034573e-05 -0.00712508856271752 1.06308028973289e-06 0.00316629333145718 -3.25524564627278e-05 -0.00235959423210011 3.41021759646536e-07 0.000104187499390075 -3.9641708225941e-06 -3.25524564627278e-05 1.06161070675685e-05 3.2513634114904e-06 -3.97588686355441e-05 -0.00214520296788596 -2.88058218935848e-05 -0.00235959423210011 3.2513634114904e-06 0.012536460607491 0 0 0 890 726 0 0 0 770 790 0 0 0 0 0 500 428 0 2835 0 338 369 0 0 3031 +1218 1219 0.999922609698392 0.0121895678441383 0.00248778008095422 0.1377316989668 -0.0121582714531439 0.999851295020095 -0.0122296476609119 0.00161232452031411 -0.00263648425553987 0.0121984540992509 0.999922120301556 0.0837317267486072 6.02567543563163e-05 -2.58206172272808e-05 -8.51498369243296e-06 -2.22283377301229e-05 -2.0533309426478e-06 1.23852572239792e-05 -2.58206172272808e-05 4.15600928190319e-05 7.48690866954582e-06 2.05985272390525e-05 1.91458015019063e-06 -2.32896069293753e-05 -8.51498369243296e-06 7.48690866954582e-06 1.22114887144886e-05 1.10286214414028e-06 5.7602966456197e-06 -7.00560613941751e-06 -2.22283377301229e-05 2.05985272390525e-05 1.10286214414028e-06 3.8761574445281e-05 -2.70884304852644e-06 -4.19462789283401e-05 -2.0533309426478e-06 1.91458015019063e-06 5.7602966456197e-06 -2.70884304852644e-06 9.7541875345263e-06 1.13257033443756e-05 1.23852572239792e-05 -2.32896069293753e-05 -7.00560613941751e-06 -4.19462789283401e-05 1.13257033443756e-05 0.000492850240239662 3575 3555 0 187 79 3575 3555 0 106 123 0 0 0 0 0 0 0 0 3623 0 0 0 0 0 3719 +1212 1213 0.999142479583983 -0.0390279520303001 -0.0138247767103706 0.140962300955795 0.0392868585843544 0.999047713099961 0.0189791910341675 0.0233964987846202 0.0130708925993579 -0.0195060480379568 0.999724294921653 -0.00419791472363834 4.16192302922235e-05 -1.75175544398185e-05 2.13368958496176e-06 -5.07676589807271e-08 1.28060713087274e-06 4.63632969540741e-06 -1.75175544398185e-05 5.89940066646328e-05 1.5063946383207e-06 2.65164973495652e-05 -2.54997022568531e-07 -1.31938813202437e-05 2.13368958496176e-06 1.5063946383207e-06 9.7467543268699e-06 1.03596842405283e-07 3.20220879157475e-06 -1.90939961052124e-06 -5.07676589807271e-08 2.65164973495652e-05 1.03596842405283e-07 6.17572007552339e-05 1.43866051102011e-06 -4.25563291080779e-05 1.28060713087274e-06 -2.54997022568531e-07 3.20220879157475e-06 1.43866051102011e-06 9.12351252866351e-06 7.18336133409419e-07 4.63632969540741e-06 -1.31938813202437e-05 -1.90939961052124e-06 -4.25563291080779e-05 7.18336133409419e-07 0.000319658234246866 3726 3716 0 10 232 3718 3716 0 0 285 0 0 0 0 0 0 0 0 3766 0 0 0 0 0 3544 +1221 1222 0.999598691001444 -0.0272426937673454 0.00776482997222092 0.139929562575352 0.0273462591779941 0.999534056948732 -0.0135591706449596 0.0147013865496383 -0.00739182367003127 0.0137660682806602 0.999877920701784 0.0515258989268082 4.50312595101082e-05 -1.66582335187317e-05 4.69834037493703e-06 -6.9501154017781e-06 1.62387005900035e-07 -3.26933543947678e-06 -1.66582335187317e-05 3.92889902912507e-05 -1.14632451270429e-06 9.20997621275316e-06 6.20632789325719e-07 -3.2049671669445e-06 4.69834037493703e-06 -1.14632451270429e-06 9.28253525414551e-06 -5.03524677642561e-06 1.34986594349914e-06 -2.348803938065e-06 -6.9501154017781e-06 9.20997621275316e-06 -5.03524677642561e-06 2.42902622670802e-05 -1.00440080720685e-06 -4.20602137385496e-05 1.62387005900035e-07 6.20632789325719e-07 1.34986594349914e-06 -1.00440080720685e-06 9.42160029096542e-06 9.21348471521451e-06 -3.26933543947678e-06 -3.2049671669445e-06 -2.348803938065e-06 -4.20602137385496e-05 9.21348471521451e-06 0.00039884041679091 3633 3616 0 62 194 3633 3616 0 2 244 0 0 0 0 0 0 0 0 3723 0 0 0 0 0 3587 +1223 1224 0.99896795611636 -0.045314443077205 -0.003102241335711 0.135640222054833 0.0453686179928599 0.998760434546262 0.0204763982765495 0.018838862963212 0.00217051932039321 -0.0205960101370308 0.999785523606096 0.0591279950272871 3.7461645936662e-05 -1.36582931434387e-05 -1.72516060767586e-07 -2.10283663205177e-06 1.07770832616207e-06 1.88101774814662e-05 -1.36582931434387e-05 3.6887409747616e-05 -6.26605129436833e-07 5.34321976125333e-06 1.01728333518749e-07 -5.59959517303847e-06 -1.72516060767586e-07 -6.26605129436833e-07 8.73545840004698e-06 -5.85952777305339e-06 2.14473049715708e-06 -2.78979029920618e-06 -2.10283663205177e-06 5.34321976125333e-06 -5.85952777305339e-06 1.84574869692209e-05 -1.65677421561015e-06 -2.91137869848542e-05 1.07770832616207e-06 1.01728333518749e-07 2.14473049715708e-06 -1.65677421561015e-06 9.74267090672823e-06 1.57752398549025e-05 1.88101774814662e-05 -5.59959517303847e-06 -2.78979029920618e-06 -2.91137869848542e-05 1.57752398549025e-05 0.000455134748070274 3455 3409 0 14 242 3441 3409 0 0 281 0 0 0 0 0 0 0 0 3755 0 0 0 0 0 3544 +1211 1212 0.999144751733167 -0.0259613459776965 -0.0321834367197668 0.137048672498551 0.0258670026077284 0.999659798743967 -0.00334439101528531 0.0201098108786785 0.0322593127664038 0.00250904168911 0.999476383637773 -0.00843283770652031 3.34076355721764e-05 -2.31888036278838e-05 -4.44484597367802e-08 7.17971641321746e-07 -7.98658802313797e-07 9.27359448572726e-06 -2.31888036278838e-05 5.29189537812404e-05 -2.64590148876524e-06 5.83974473276085e-06 1.79375333566179e-06 -4.77404793552004e-06 -4.44484597367802e-08 -2.64590148876524e-06 9.54579159277752e-06 -2.42063982624407e-06 3.39046582870245e-06 1.46262500964227e-06 7.17971641321746e-07 5.83974473276085e-06 -2.42063982624407e-06 5.43577470289768e-05 4.61278129065169e-06 -6.07553526816858e-06 -7.98658802313797e-07 1.79375333566179e-06 3.39046582870245e-06 4.61278129065169e-06 9.56828074827491e-06 2.36226478453966e-06 9.27359448572726e-06 -4.77404793552004e-06 1.46262500964227e-06 -6.07553526816858e-06 2.36226478453966e-06 0.000161784960876523 3667 3667 0 44 188 3667 3667 0 2 247 0 0 0 0 0 0 0 0 3745 0 0 0 0 0 3596 +1224 1225 0.999646322236535 -0.0261134893474861 -0.00503151200625312 0.140724970195343 0.0262001221181907 0.999494666367993 0.0179990417224627 0.0188000760127398 0.00455895162973202 -0.0181245020906448 0.999825343939632 0.0347998562263215 3.74820741962272e-05 -2.41771628119116e-05 2.18117417317362e-06 -3.76744797273846e-07 5.25956585650458e-07 3.47994505703604e-06 -2.41771628119116e-05 3.46581305904396e-05 -3.37146417186269e-06 -4.34903040523014e-06 -1.98190233789872e-06 -1.64410160473094e-05 2.18117417317362e-06 -3.37146417186269e-06 9.95045663107896e-06 -2.2511076972926e-06 2.84143862991025e-06 3.05033054178721e-07 -3.76744797273846e-07 -4.34903040523014e-06 -2.2511076972926e-06 2.17159494396998e-05 9.12929227817532e-08 -6.8347900407926e-06 5.25956585650458e-07 -1.98190233789872e-06 2.84143862991025e-06 9.12929227817532e-08 9.94617112306766e-06 1.0520561481567e-05 3.47994505703604e-06 -1.64410160473094e-05 3.05033054178721e-07 -6.8347900407926e-06 1.0520561481567e-05 0.000250685208882333 3775 3764 0 70 205 3775 3764 0 0 241 0 0 0 0 0 0 0 0 3694 0 0 0 0 0 3603 +1226 1227 0.999726309880878 0.00222199703184084 0.0232887969022134 0.145176193454616 -0.0024400150699044 0.999953429803688 0.00933726674673029 0.00406297874295299 -0.023266964959373 -0.00939153624448344 0.999685174136612 -0.0163578896948081 3.38636663628576e-05 -2.92590139242942e-06 -4.17295831823526e-06 2.2638369728088e-06 -2.51701150654399e-06 8.49096884590734e-07 -2.92590139242942e-06 4.08645912769371e-05 4.17793982560522e-06 4.60484710977369e-08 9.6231356011112e-07 1.909611450112e-05 -4.17295831823526e-06 4.17793982560522e-06 1.05191987505236e-05 -8.31990044831877e-06 1.71954023857602e-06 -7.80126187064751e-06 2.2638369728088e-06 4.60484710977369e-08 -8.31990044831877e-06 2.51300589119629e-05 -1.39983384314054e-06 -6.81601880240949e-05 -2.51701150654399e-06 9.6231356011112e-07 1.71954023857602e-06 -1.39983384314054e-06 9.61689216507662e-06 1.07490505756335e-05 8.49096884590734e-07 1.909611450112e-05 -7.80126187064751e-06 -6.81601880240949e-05 1.07490505756335e-05 0.000727772323773532 3758 3780 0 84 135 3758 3782 0 99 151 0 0 0 0 0 0 5 0 3680 0 0 0 0 0 3681 +1217 1218 0.999412412459363 0.0288386767483413 -0.0185245929931143 0.156110751948289 -0.029455173692688 0.998990498963691 -0.0339171891967793 0.00640653946223081 0.0175277655418323 0.0344429049831923 0.999252952825974 -0.0136499715052111 3.56424166013041e-05 -5.16904173083921e-06 7.54613173804166e-07 -1.74833279902931e-07 2.6992449224563e-07 -2.90245173396131e-05 -5.16904173083921e-06 2.53645118420079e-05 2.90377659401621e-06 1.60496938546517e-06 1.43861347385754e-06 1.41547147069235e-05 7.54613173804166e-07 2.90377659401621e-06 8.34014063838126e-06 -2.96639305498022e-06 3.24535118796994e-06 -2.62661913051951e-06 -1.74833279902931e-07 1.60496938546517e-06 -2.96639305498022e-06 1.86370993187751e-05 -2.84780723330715e-06 -1.32069950692815e-05 2.6992449224563e-07 1.43861347385754e-06 3.24535118796994e-06 -2.84780723330715e-06 9.06341446164189e-06 9.42980268263694e-06 -2.90245173396131e-05 1.41547147069235e-05 -2.62661913051951e-06 -1.32069950692815e-05 9.42980268263694e-06 0.000561383846886235 3556 3530 0 252 63 3556 3530 0 167 106 0 0 0 0 0 0 0 0 3551 0 0 0 0 0 3740 +1230 1231 0.999169296596083 0.0346654627598679 0.0214248087817216 0.134389851270606 -0.0348420274587715 0.999361422326439 0.00792342654657314 -0.00573255741908763 -0.0211364581292925 -0.00866332830504189 0.999739064396519 0.0547978372124569 5.18901545690149e-05 -2.21524672306149e-05 -8.94225238156887e-07 -8.4451740399273e-07 2.64748509343742e-06 3.48467029340028e-05 -2.21524672306149e-05 5.77039026883216e-05 -1.21133539781339e-06 2.63305454999764e-06 -2.95700767629466e-06 -2.97374184558879e-05 -8.94225238156887e-07 -1.21133539781339e-06 1.0341597116581e-05 -8.03157643493046e-06 2.62861967145055e-06 -2.14377255459389e-06 -8.4451740399273e-07 2.63305454999764e-06 -8.03157643493046e-06 1.7318191210161e-05 1.40753512742226e-07 -8.71180070460855e-06 2.64748509343742e-06 -2.95700767629466e-06 2.62861967145055e-06 1.40753512742226e-07 1.12368970823566e-05 3.7531786626691e-06 3.48467029340028e-05 -2.97374184558879e-05 -2.14377255459389e-06 -8.71180070460855e-06 3.7531786626691e-06 0.000131805503061411 3857 3932 0 176 22 3857 3932 0 192 52 0 0 0 0 0 0 0 0 3205 0 0 0 0 0 3809 +1220 1221 0.999748564642485 -0.00197705431608642 0.0223360415365535 0.146244314944742 0.00190976489715009 0.999993575247004 0.0030335231585012 0.00569760430863694 -0.0223418954730571 -0.00299010383545351 0.999745917213831 0.0363177178444408 5.24880674588084e-05 -2.03916553476946e-05 1.45386105004992e-06 5.43358249313625e-06 2.66884042616247e-06 3.05293033495071e-05 -2.03916553476946e-05 9.1602229172914e-05 4.58018957844141e-06 -1.64124183384206e-05 -3.1749461832938e-06 -7.66046260348942e-05 1.45386105004992e-06 4.58018957844141e-06 1.04584591831501e-05 -4.49572316704047e-06 2.95580451819485e-06 -4.60696010867795e-06 5.43358249313625e-06 -1.64124183384206e-05 -4.49572316704047e-06 3.15058715146282e-05 -3.69626284626214e-07 -2.74497125030934e-05 2.66884042616247e-06 -3.1749461832938e-06 2.95580451819485e-06 -3.69626284626214e-07 9.39326029241185e-06 1.26036746940983e-05 3.05293033495071e-05 -7.66046260348942e-05 -4.60696010867795e-06 -2.74497125030934e-05 1.26036746940983e-05 0.000565677181281368 3688 3676 0 157 133 3688 3676 0 88 180 0 0 0 0 0 0 0 0 3650 0 0 0 0 0 3662 +1227 1228 0.999473095745576 0.0296862007668543 -0.0131247996092918 0.143649584021474 -0.0293669221604149 0.999283305971759 0.0238842686506527 -0.00956979049432799 0.0138244263381227 -0.0234862489593897 0.999628571693626 -0.00971420394227733 5.88128335509061e-05 -1.67695282850544e-05 4.22119840380647e-06 -7.24276114518302e-06 1.06482801649918e-06 2.9776257621719e-05 -1.67695282850544e-05 2.79893180280424e-05 -2.08148482885496e-07 6.79089163803494e-06 2.04767173390179e-06 -6.16641640762106e-06 4.22119840380647e-06 -2.08148482885496e-07 1.03722888960147e-05 -4.98115336872278e-06 3.58314681058938e-06 -1.6131301015022e-06 -7.24276114518302e-06 6.79089163803494e-06 -4.98115336872278e-06 2.36088552076496e-05 2.15835547149458e-06 -6.01914890764153e-05 1.06482801649918e-06 2.04767173390179e-06 3.58314681058938e-06 2.15835547149458e-06 1.0725175337219e-05 -5.87885875437547e-06 2.9776257621719e-05 -6.16641640762106e-06 -1.6131301015022e-06 -6.01914890764153e-05 -5.87885875437547e-06 0.000523540858874933 3842 3903 0 190 50 3842 3903 0 191 69 0 0 0 0 0 0 0 0 3548 0 0 0 0 0 3766 +1231 1232 0.999822257504739 0.00682659951863159 0.01757415537487 0.133749831846412 -0.00714141779633348 0.999814032128447 0.0179137185116544 0.000416503020235758 -0.017448597364432 -0.0180360388685764 0.99968507428687 0.0579624081809746 6.72459190783204e-05 -1.71278330294657e-05 2.66425856803014e-06 -3.99723762254007e-06 2.59967100295539e-06 4.06738725620834e-05 -1.71278330294657e-05 4.57582787104873e-05 -2.97733004824355e-06 6.32994144889109e-06 -1.10650205228056e-06 -4.08821356365818e-05 2.66425856803014e-06 -2.97733004824355e-06 9.67346381933627e-06 -6.11064222059167e-06 2.78109773024073e-06 -4.74985393112336e-06 -3.99723762254007e-06 6.32994144889109e-06 -6.11064222059167e-06 1.8860569630996e-05 6.36658580241083e-08 -4.56810004458439e-05 2.59967100295539e-06 -1.10650205228056e-06 2.78109773024073e-06 6.36658580241083e-08 1.20386438707973e-05 1.03979393389653e-06 4.06738725620834e-05 -4.08821356365818e-05 -4.74985393112336e-06 -4.56810004458439e-05 1.03979393389653e-06 0.000526977477750656 3801 3864 0 77 91 3801 3864 0 110 131 0 0 0 0 0 0 0 0 3466 0 0 0 0 0 3731 +1234 1235 0.99951228656232 -0.029118405555944 -0.0112830611467751 0.139359198392703 0.0290806501551511 0.999570954927714 -0.00349597646599215 0.0212993176166477 0.0113800174655406 0.00316615267740332 0.99993023290613 -0.0215144211069709 5.83182204512544e-05 -9.12258969524126e-06 2.057147659151e-06 -4.23894963557339e-06 -9.09254442387274e-07 4.25622336053578e-05 -9.12258969524126e-06 4.06080711442294e-05 -4.17993412805532e-06 4.07094006850925e-06 -3.52641258291679e-06 -2.05833984583919e-05 2.057147659151e-06 -4.17993412805532e-06 1.15529796880144e-05 -5.31508821366979e-06 5.06035361698399e-06 1.14068779446921e-06 -4.23894963557339e-06 4.07094006850925e-06 -5.31508821366979e-06 1.81845060716747e-05 -4.23193397261842e-07 -2.00469447709332e-05 -9.09254442387274e-07 -3.52641258291679e-06 5.06035361698399e-06 -4.23193397261842e-07 1.46467201345192e-05 4.41120820508309e-06 4.25622336053578e-05 -2.05833984583919e-05 1.14068779446921e-06 -2.00469447709332e-05 4.41120820508309e-06 0.000187244447124304 3812 3838 0 4 210 3820 3853 0 17 245 0 0 0 0 0 17 33 0 3516 0 0 0 0 0 3613 +1228 1229 0.99938572047124 0.0349290803443872 -0.00285325506668807 0.138345768382414 -0.03501345977521 0.998635966614872 -0.0387332391848517 -0.00949680107304993 0.00149644670803476 0.0388093484804438 0.99924551293352 -0.00369005565030146 4.51123652896698e-05 -1.72447500383804e-05 1.69897136556665e-06 6.72645578426996e-08 3.06120604370962e-06 1.92155818437511e-05 -1.72447500383804e-05 3.26396500208425e-05 -1.88607163789731e-06 6.17534931447681e-07 -2.24235016798102e-06 -9.96536633370919e-06 1.69897136556665e-06 -1.88607163789731e-06 8.88806706366846e-06 -6.16266903804892e-06 1.97934499924607e-06 -4.86735474368026e-07 6.72645578426996e-08 6.17534931447681e-07 -6.16266903804892e-06 1.68155915259569e-05 6.10094431135365e-07 -1.64431915295423e-05 3.06120604370962e-06 -2.24235016798102e-06 1.97934499924607e-06 6.10094431135365e-07 9.78032811893543e-06 1.19933592664239e-06 1.92155818437511e-05 -9.96536633370919e-06 -4.86735474368026e-07 -1.64431915295423e-05 1.19933592664239e-06 0.000145119934594707 3884 3952 0 162 24 3884 3952 0 215 45 0 0 0 0 0 0 0 0 3542 0 0 0 0 0 3802 +1229 1230 0.999196327600583 0.0336785285078214 -0.0217360444206525 0.139225074288731 -0.0336419416994977 0.999431853766225 0.0020468112016415 -0.0130244403759605 0.0217926287582824 -0.00131392349679463 0.99976164906284 0.00705811731595985 5.67832385437658e-05 -2.57130858838631e-05 4.70723513878502e-06 1.62120622529098e-07 5.91398270367439e-06 8.712956390891e-06 -2.57130858838631e-05 3.33371255485302e-05 -2.7398354479446e-06 3.33569860544535e-06 -3.22856869226926e-06 -1.25816709162438e-05 4.70723513878502e-06 -2.7398354479446e-06 8.64818672984074e-06 -5.32706108698506e-06 2.31241911464989e-06 2.09549654215351e-06 1.62120622529098e-07 3.33569860544535e-06 -5.32706108698506e-06 1.47429255572598e-05 1.01730567565838e-06 -1.33151681635604e-05 5.91398270367439e-06 -3.22856869226926e-06 2.31241911464989e-06 1.01730567565838e-06 1.09521877845623e-05 3.06632443228304e-06 8.712956390891e-06 -1.25816709162438e-05 2.09549654215351e-06 -1.33151681635604e-05 3.06632443228304e-06 0.000229774323763576 3864 3899 0 153 23 3864 3899 0 192 53 0 0 0 0 0 0 0 0 3411 0 0 0 0 0 3795 +1235 1236 0.99988097069748 -0.00997605439965185 0.0117695699021008 0.127912726402753 0.00992112215593109 0.999939661149899 0.00471650236855823 0.0234826248798063 -0.0118159118239915 -0.00459917362584945 0.999919612683803 0.0629286971733124 0.000130123284371756 -1.12658077089302e-05 6.70697164133893e-06 -6.15610064138264e-06 5.21104261571327e-06 5.57616079332536e-05 -1.12658077089302e-05 4.31693711003437e-05 3.2067681247396e-06 -3.9164817299088e-06 2.2635174192942e-07 2.14907298932444e-06 6.70697164133893e-06 3.2067681247396e-06 1.49183651795322e-05 -8.41090401701647e-06 3.405849396846e-06 4.79443531851393e-06 -6.15610064138264e-06 -3.9164817299088e-06 -8.41090401701647e-06 1.82407561174437e-05 2.73515090408176e-07 -1.81311737935556e-05 5.21104261571327e-06 2.2635174192942e-07 3.405849396846e-06 2.73515090408176e-07 1.60083527101593e-05 1.00661527731624e-05 5.57616079332536e-05 2.14907298932444e-06 4.79443531851393e-06 -1.81311737935556e-05 1.00661527731624e-05 0.000247405096965569 3822 3855 0 54 152 3822 3855 0 66 181 0 0 0 0 0 0 0 0 3507 0 0 0 0 0 3668 +1232 1233 0.999787544620791 -0.0138623643516685 0.0152545231230685 0.13682826513036 0.0143004540829964 0.999477270378532 -0.0289945341348711 0.018268847263683 -0.0148446163355862 0.0292065206976059 0.999463164160936 -0.000589566988888071 3.79503318699135e-05 -7.43255240686346e-06 3.46177998152132e-06 -1.73238205116325e-06 -1.41968638901057e-07 9.77226531047731e-06 -7.43255240686346e-06 3.16142149391679e-05 6.6463657336422e-07 -6.7434970952565e-07 1.08284071447399e-06 -9.88713799638978e-06 3.46177998152132e-06 6.6463657336422e-07 9.99332816681379e-06 -6.85600730205957e-06 2.13235516947157e-06 -1.77070235080702e-07 -1.73238205116325e-06 -6.7434970952565e-07 -6.85600730205957e-06 1.63588709478508e-05 -5.57170490311698e-07 -1.43267500823213e-05 -1.41968638901057e-07 1.08284071447399e-06 2.13235516947157e-06 -5.57170490311698e-07 1.24910166782001e-05 3.29905236181907e-06 9.77226531047731e-06 -9.88713799638978e-06 -1.77070235080702e-07 -1.43267500823213e-05 3.29905236181907e-06 0.000162756614942686 3822 3869 0 51 166 3822 3872 0 72 207 0 0 0 0 0 0 8 0 3469 0 0 0 0 0 3656 +1233 1234 0.999638633651642 -0.0267521571288019 0.00263138747339662 0.129377903435289 0.0267662483141591 0.999626731369643 -0.00547411019503244 0.020538695583909 -0.00248396100292061 0.00554256440634445 0.999981554788656 0.053255895752494 7.29946391323608e-05 -1.2480942492014e-05 3.21007509116648e-06 -6.08069303908722e-06 -1.11892795157616e-06 2.74918269229342e-05 -1.2480942492014e-05 3.97281512271766e-05 -6.51461199087319e-06 4.1739091602121e-06 2.87014504308442e-06 -5.7795719047092e-06 3.21007509116648e-06 -6.51461199087319e-06 1.24387038179343e-05 -7.51339599490345e-06 1.11412899239593e-06 3.39885142424986e-07 -6.08069303908722e-06 4.1739091602121e-06 -7.51339599490345e-06 2.10497294079437e-05 -4.61570188972843e-07 -4.30218148219858e-05 -1.11892795157616e-06 2.87014504308442e-06 1.11412899239593e-06 -4.61570188972843e-07 1.31309059056153e-05 8.45920545479656e-06 2.74918269229342e-05 -5.7795719047092e-06 3.39885142424986e-07 -4.30218148219858e-05 8.45920545479656e-06 0.000364771504716554 3816 3848 0 11 189 3816 3860 0 24 223 0 0 0 0 0 10 31 0 3525 0 0 0 0 0 3636 +1245 1246 0.999769683609241 0.0210300740341913 0.00427968713740031 0.11731156358724 -0.0210581618435041 0.999756286165183 0.00662737451587813 0.0340656969983774 -0.00413926994171501 -0.00671597046727837 0.999968880608308 0.0649682569145623 8.36810246949257e-05 5.63588958784836e-05 5.39599818428149e-06 -1.97135538873966e-06 1.04728423881764e-06 -1.16731453800989e-06 5.63588958784836e-05 6.74967229321061e-05 4.85211774049335e-06 -3.78829641259636e-07 -1.36375587319446e-06 -6.97440192451895e-08 5.39599818428149e-06 4.85211774049335e-06 1.7040441576741e-05 -1.00090593369705e-05 -4.4390120349996e-06 -2.2890075870945e-06 -1.97135538873966e-06 -3.78829641259636e-07 -1.00090593369705e-05 1.96706757968146e-05 9.96039004190138e-08 -2.5717097405896e-05 1.04728423881764e-06 -1.36375587319446e-06 -4.4390120349996e-06 9.96039004190138e-08 1.60027290825158e-05 -4.58252573800271e-06 -1.16731453800989e-06 -6.97440192451895e-08 -2.2890075870945e-06 -2.5717097405896e-05 -4.58252573800271e-06 0.000249024790733912 3829 3849 0 114 78 3829 3849 0 105 120 0 0 0 0 0 0 0 0 3505 0 0 0 0 0 3787 +1244 1245 0.999198206467977 0.0292688794962928 -0.0273180688228292 0.126230004710802 -0.029525295573858 0.999523239410724 -0.00903054811008285 0.0361684009721523 0.0270407306198199 0.00982988153151859 0.999586000460502 0.0326497511664931 4.33261169681694e-05 2.19246858638195e-05 -4.3034535683042e-06 -3.1591175638848e-06 -2.1417024454415e-06 3.24535191917757e-05 2.19246858638195e-05 5.29636472140809e-05 -6.50805841682351e-06 3.65583403401517e-06 -3.92942604400577e-06 1.45234735086167e-05 -4.3034535683042e-06 -6.50805841682351e-06 1.76954270922927e-05 -5.91581900278348e-06 -1.31890329366283e-06 -3.41266445525146e-06 -3.1591175638848e-06 3.65583403401517e-06 -5.91581900278348e-06 1.8234758058887e-05 -7.65891587076981e-07 -1.33076761137443e-05 -2.1417024454415e-06 -3.92942604400577e-06 -1.31890329366283e-06 -7.65891587076981e-07 1.83226310844746e-05 5.85603443383654e-06 3.24535191917757e-05 1.45234735086167e-05 -3.41266445525146e-06 -1.33076761137443e-05 5.85603443383654e-06 0.000168259023988199 3840 3864 0 137 59 3840 3864 0 128 99 0 0 0 0 0 0 0 0 3457 0 0 0 0 0 3799 +1240 1241 0.999439606666821 0.0326798880361109 -0.00724551886469275 0.125380132492064 -0.0326780900818008 0.999465861428142 0.00036642640209712 0.0240682938762786 0.007253623527388 -0.000129451341034467 0.999973683747764 0.0114755068396529 5.62761196958397e-05 2.05829139354269e-05 3.37906443524713e-06 -1.04138369706343e-06 -3.77712811222898e-06 3.20651026673407e-05 2.05829139354269e-05 4.50406103015406e-05 1.67911410118574e-06 6.60168812863943e-06 -4.16590724649303e-06 1.04024853251891e-05 3.37906443524713e-06 1.67911410118574e-06 1.16128430723067e-05 -6.71983915114977e-06 -2.73644574491611e-06 1.90049510327527e-06 -1.04138369706343e-06 6.60168812863943e-06 -6.71983915114977e-06 1.78264598927385e-05 -3.20862160113435e-06 -2.03222496837725e-05 -3.77712811222898e-06 -4.16590724649303e-06 -2.73644574491611e-06 -3.20862160113435e-06 1.65758260776051e-05 8.16750660572614e-06 3.20651026673407e-05 1.04024853251891e-05 1.90049510327527e-06 -2.03222496837725e-05 8.16750660572614e-06 0.000205098764247243 3863 3906 0 151 50 3863 3906 0 168 84 0 0 0 0 0 0 0 0 3438 0 0 0 0 0 3830 +1236 1237 0.999357918500397 0.00175773808357712 0.0357863254244374 0.132681879764403 -0.00109389115861079 0.999827123392161 -0.0185614312888046 0.0222324416619051 -0.035812764940553 0.018510366992187 0.999187075667579 -0.0300087730441623 6.64428264198315e-05 -3.25838260628968e-05 -3.53185335450677e-06 -1.03591172387922e-05 5.25411719286157e-06 2.11374872650689e-05 -3.25838260628968e-05 5.48824225832357e-05 -1.89348580102529e-07 5.84821910502427e-06 -6.66312497092831e-06 -3.0464250889716e-05 -3.53185335450677e-06 -1.89348580102529e-07 1.5734455290127e-05 -5.87820800252677e-06 1.64513259340605e-06 -4.10181996009592e-06 -1.03591172387922e-05 5.84821910502427e-06 -5.87820800252677e-06 2.65865664915244e-05 -2.49419801176317e-06 -3.5593917174225e-05 5.25411719286157e-06 -6.66312497092831e-06 1.64513259340605e-06 -2.49419801176317e-06 1.81243392798941e-05 1.65226271240938e-05 2.11374872650689e-05 -3.0464250889716e-05 -4.10181996009592e-06 -3.5593917174225e-05 1.65226271240938e-05 0.000270717580100447 3832 3857 0 77 140 3832 3857 0 85 165 0 0 0 0 0 0 0 0 3573 0 0 0 0 0 3707 +1238 1239 0.999000295918515 0.0438500820386688 -0.00869362179542533 0.126898446283352 -0.0439079663510889 0.999013890951835 -0.0065830218126536 0.0151703357336134 0.00839638288976433 0.00695815999214161 0.999940540614237 0.0227726585415198 4.86058108094619e-05 1.62942498536766e-05 -1.10213126528775e-06 1.18090759861893e-06 -7.00002016007825e-06 1.82403622076343e-05 1.62942498536766e-05 4.77373099984276e-05 -1.91091834798698e-06 2.79381886818212e-06 -4.28403181710929e-06 3.09138878313093e-06 -1.10213126528775e-06 -1.91091834798698e-06 1.1951675221126e-05 -7.05304122961616e-06 4.1840735164175e-06 -3.78114847717919e-06 1.18090759861893e-06 2.79381886818212e-06 -7.05304122961616e-06 1.99001262016819e-05 -4.9431124568479e-06 -2.20430236239892e-05 -7.00002016007825e-06 -4.28403181710929e-06 4.1840735164175e-06 -4.9431124568479e-06 1.85648413558665e-05 5.3269039887634e-06 1.82403622076343e-05 3.09138878313093e-06 -3.78114847717919e-06 -2.20430236239892e-05 5.3269039887634e-06 0.000216474988313577 3870 3915 0 201 23 3870 3915 0 200 39 0 0 0 0 0 0 0 0 3523 0 0 0 0 0 3850 +1241 1242 0.998908683311238 0.0429680008343989 0.0183082852748135 0.118975630569123 -0.043024643137987 0.999070332997864 0.00271105263447895 0.0294945962137814 -0.0181747761542674 -0.00349580145791214 0.999828713772469 0.0443793644694846 4.12772638800753e-05 3.42231059564546e-05 1.84269064574367e-06 -4.12469085396612e-07 5.64013325240717e-08 2.70864555846782e-05 3.42231059564546e-05 6.68278162437764e-05 3.26847841826124e-07 -1.66642925596175e-07 1.05574585125845e-06 4.31851774553302e-05 1.84269064574367e-06 3.26847841826124e-07 1.09647324792228e-05 -6.6271443139731e-06 -5.43223221296712e-07 6.90177815072341e-07 -4.12469085396612e-07 -1.66642925596175e-07 -6.6271443139731e-06 1.41261389057423e-05 -3.05162352767843e-06 -7.58853116979455e-06 5.64013325240717e-08 1.05574585125845e-06 -5.43223221296712e-07 -3.05162352767843e-06 1.62720528224085e-05 -1.29234781508095e-06 2.70864555846782e-05 4.31851774553302e-05 6.90177815072341e-07 -7.58853116979455e-06 -1.29234781508095e-06 0.000102302903021998 3856 3894 0 174 22 3856 3894 0 190 58 0 0 0 0 0 0 0 0 3581 0 0 0 0 0 3849 +1237 1238 0.99975015810802 0.0223469867450958 -0.00048326639063282 0.128330636264274 -0.0223412943774764 0.999703937361662 0.00963868191868001 0.0193495775132943 0.000698518810587125 -0.00962547697545738 0.999953430047853 0.0421501242030874 3.99314120941849e-05 -9.3125236161377e-06 -2.06923838669828e-06 -5.18151864483127e-06 2.32390484486228e-07 2.97985076799907e-05 -9.3125236161377e-06 5.40575660702553e-05 6.33005756954858e-06 8.9342171796443e-06 -3.96777446275029e-06 -1.63857829723861e-05 -2.06923838669828e-06 6.33005756954858e-06 1.4608636960224e-05 -7.65048080960841e-06 1.72945377597805e-06 -2.03620917959648e-06 -5.18151864483127e-06 8.9342171796443e-06 -7.65048080960841e-06 2.40172927376133e-05 -3.17344197545697e-06 -1.47823398289751e-05 2.32390484486228e-07 -3.96777446275029e-06 1.72945377597805e-06 -3.17344197545697e-06 1.5330298500749e-05 2.33931334883732e-06 2.97985076799907e-05 -1.63857829723861e-05 -2.03620917959648e-06 -1.47823398289751e-05 2.33931334883732e-06 0.000111267288349043 3847 3864 0 138 75 3847 3864 0 144 95 0 0 0 0 0 0 0 0 3524 0 0 0 0 0 3778 +1239 1240 0.998457676120996 0.0419298385979201 -0.0363889767678727 0.124808209730661 -0.0424393278381083 0.999009940504053 -0.013343246484215 0.0192541243070246 0.0357934693444204 0.014866990591284 0.999248617783907 0.0511457268422622 6.58239677496492e-05 2.03294732986304e-05 4.89573325938689e-06 -7.9901096711418e-07 -2.68728024167753e-06 4.70621890358228e-05 2.03294732986304e-05 4.69758358535238e-05 -4.41012421143753e-08 3.96827574987766e-06 -1.48451355687662e-06 2.84367586082122e-05 4.89573325938689e-06 -4.41012421143753e-08 1.12078913407418e-05 -7.67060614263136e-06 1.23270389448658e-07 -8.49621356330569e-07 -7.9901096711418e-07 3.96827574987766e-06 -7.67060614263136e-06 1.67859599663827e-05 -1.86919933977202e-06 -2.28693585326153e-05 -2.68728024167753e-06 -1.48451355687662e-06 1.23270389448658e-07 -1.86919933977202e-06 1.48262794664321e-05 1.0135529457194e-05 4.70621890358228e-05 2.84367586082122e-05 -8.49621356330569e-07 -2.28693585326153e-05 1.0135529457194e-05 0.000276266187651984 3872 3918 0 181 19 3872 3919 0 204 42 0 0 0 0 0 0 0 0 3433 0 0 0 0 0 3858 +1243 1244 0.999947521297967 0.00928192164064228 -0.00433596364255098 0.119450317414619 -0.00934540138679824 0.999845955579015 -0.0148569372754396 0.0338638877412855 0.00419739478393168 0.0148966789232933 0.999880228244405 0.0408314966546626 8.30938428203497e-05 3.84235822145037e-05 7.34729330179133e-06 -8.8180578453018e-07 -2.43057347428053e-06 3.9175374931406e-05 3.84235822145037e-05 6.4590766262303e-05 -4.78591197181233e-07 4.51831194134713e-06 -3.8667814192135e-06 1.04301845116985e-05 7.34729330179133e-06 -4.78591197181233e-07 1.38935936756102e-05 -6.8140538745949e-06 -2.4213916346791e-06 -4.57377061556756e-07 -8.8180578453018e-07 4.51831194134713e-06 -6.8140538745949e-06 1.69546458436597e-05 -2.21709578462989e-06 -2.71540345527691e-05 -2.43057347428053e-06 -3.8667814192135e-06 -2.4213916346791e-06 -2.21709578462989e-06 1.69488650946839e-05 1.09637251574597e-06 3.9175374931406e-05 1.04301845116985e-05 -4.57377061556756e-07 -2.71540345527691e-05 1.09637251574597e-06 0.000235417577865824 3828 3859 0 84 111 3828 3859 0 85 151 0 0 0 0 0 0 0 0 3585 0 0 0 0 0 3760 +1246 1247 0.999190764868018 0.0376911074878506 0.0140426428710629 0.109748523722411 -0.0375747382140546 0.999258003242842 -0.00846061482835183 0.0377269337426898 -0.0143511132184993 0.00792611957188091 0.999865602057558 0.0637586472239599 4.06159864917776e-05 2.19810746422338e-05 3.27511484232073e-06 8.46578881778912e-07 -1.47784077566168e-06 2.07954717917172e-05 2.19810746422338e-05 4.86886087250904e-05 2.08748413844734e-06 1.46664814446351e-06 1.16334952606333e-06 2.99783285210013e-05 3.27511484232073e-06 2.08748413844734e-06 1.43230880508101e-05 -7.86245236579707e-06 -2.31421196476111e-06 -3.74870246755505e-07 8.46578881778912e-07 1.46664814446351e-06 -7.86245236579707e-06 1.46231838578805e-05 -4.39462706597193e-07 -4.77752717253103e-06 -1.47784077566168e-06 1.16334952606333e-06 -2.31421196476111e-06 -4.39462706597193e-07 1.63120377543815e-05 3.19675541227333e-06 2.07954717917172e-05 2.99783285210013e-05 -3.74870246755505e-07 -4.77752717253103e-06 3.19675541227333e-06 5.58258257137208e-05 3838 3847 0 147 31 3838 3847 0 125 74 0 0 0 0 0 0 0 0 3515 0 0 0 0 0 3795 +1248 1249 0.998569762079186 0.0534479398089698 -0.00132211621862509 0.107944950737488 -0.0534513329883413 0.998566858900577 -0.00268016924928613 0.0373946715566492 0.00117697191482027 0.00274700484384262 0.999995534340779 0.0970076449353928 4.71170388429791e-05 1.78597597454933e-05 1.7202046366257e-06 4.28606820038711e-07 -7.05313498129504e-07 1.04660487421901e-05 1.78597597454933e-05 5.999597566606e-05 1.97815364181213e-06 1.13155396903786e-05 -4.44434240001305e-06 1.24912969559904e-05 1.7202046366257e-06 1.97815364181213e-06 1.50947217482531e-05 -4.49427320403396e-06 -9.24580924777571e-06 -1.33709625421255e-06 4.28606820038711e-07 1.13155396903786e-05 -4.49427320403396e-06 2.33201771944007e-05 -1.16585246077807e-06 -2.43160420548081e-05 -7.05313498129504e-07 -4.44434240001305e-06 -9.24580924777571e-06 -1.16585246077807e-06 1.82253367858597e-05 -2.17223305248544e-06 1.04660487421901e-05 1.24912969559904e-05 -1.33709625421255e-06 -2.43160420548081e-05 -2.17223305248544e-06 0.000174447418291324 3838 3825 0 186 0 3838 3829 0 138 37 0 0 0 0 0 0 0 0 3330 0 0 0 0 0 3803 +1250 1251 0.999212056164247 0.0268618502042148 -0.0292182788614146 0.100406573491807 -0.0269141449130904 0.999636771341632 -0.00139792177018819 0.0333132206589588 0.0291701151799959 0.00218320527773371 0.999572077438691 0.0497360611991969 5.61300310908227e-05 5.51186090956847e-05 5.29026690907487e-06 4.33639118300772e-06 6.40508720001977e-07 5.86761029088997e-06 5.51186090956847e-05 8.68118215442484e-05 8.19948893852756e-06 9.56196753197022e-06 4.11023312043053e-06 4.71637763948969e-06 5.29026690907487e-06 8.19948893852756e-06 1.57807376454774e-05 -5.14374810524789e-06 -7.03682820163571e-06 4.49514384527882e-07 4.33639118300772e-06 9.56196753197022e-06 -5.14374810524789e-06 1.87124750323729e-05 1.17667712228392e-06 -2.25439245517192e-05 6.40508720001977e-07 4.11023312043053e-06 -7.03682820163571e-06 1.17667712228392e-06 1.4773312766271e-05 -4.17447143093788e-06 5.86761029088997e-06 4.71637763948969e-06 4.49514384527882e-07 -2.25439245517192e-05 -4.17447143093788e-06 0.000171593510828637 3823 3789 0 116 36 3823 3789 0 39 88 0 0 0 0 0 0 0 0 3647 0 0 0 0 0 3761 +1242 1243 0.998893323370334 0.0218974399729417 0.0416248801656025 0.116811344442466 -0.0233212486903275 0.999148554570802 0.0340335901515054 0.0333209845415974 -0.0408441903542383 -0.0349666701547082 0.998553495859185 0.0616378873026418 4.08092860156396e-05 8.8743308574918e-07 2.20345608867648e-06 2.30939067412689e-06 3.50907306878306e-06 1.04901628363072e-05 8.8743308574918e-07 5.84118761409744e-05 -3.86645245198255e-06 6.35583070316937e-06 -1.64216347976571e-06 -8.8811810146834e-06 2.20345608867648e-06 -3.86645245198255e-06 1.53237646522481e-05 -8.20589244056211e-06 -6.47844693363027e-06 -2.7603459906654e-06 2.30939067412689e-06 6.35583070316937e-06 -8.20589244056211e-06 1.95420147381172e-05 2.54307045945084e-06 -2.59565322044541e-05 3.50907306878306e-06 -1.64216347976571e-06 -6.47844693363027e-06 2.54307045945084e-06 1.7900917469827e-05 4.00170848090225e-06 1.04901628363072e-05 -8.8811810146834e-06 -2.7603459906654e-06 -2.59565322044541e-05 4.00170848090225e-06 0.0001795233763932 3840 3873 0 111 82 3840 3873 0 120 114 0 0 0 0 0 0 0 0 3629 0 0 0 0 0 3803 +1249 1250 0.999101252615355 0.0410049199709098 -0.0107370182363336 0.114586462505245 -0.0410342565920929 0.999154546396859 -0.00252630172819502 0.0350420420645332 0.0106243497853917 0.00296461678246767 0.999939165269053 0.023076053118485 5.64865236997846e-05 1.78037726060891e-05 9.41384373115479e-06 -2.76803370869113e-06 -4.82982378812924e-06 3.99430380121997e-05 1.78037726060891e-05 0.000103527528354233 4.30315735235836e-06 2.00016605067855e-05 -7.99640286268687e-06 -1.12817846988893e-05 9.41384373115479e-06 4.30315735235836e-06 2.23598834389487e-05 -7.06606968475665e-06 -8.92481584059228e-06 1.14713805680459e-05 -2.76803370869113e-06 2.00016605067855e-05 -7.06606968475665e-06 2.57684944196449e-05 -1.53849745533535e-06 -2.96160569162403e-05 -4.82982378812924e-06 -7.99640286268687e-06 -8.92481584059228e-06 -1.53849745533535e-06 2.25201300630018e-05 -4.57016398834093e-06 3.99430380121997e-05 -1.12817846988893e-05 1.14713805680459e-05 -2.96160569162403e-05 -4.57016398834093e-06 0.000233831991124502 3834 3810 0 161 25 3834 3810 0 102 74 0 0 0 0 0 0 0 0 3451 0 0 0 0 0 3759 +1253 1254 0.999535509074975 0.0300434788088074 0.00511424278804274 0.0877418775163067 -0.0300294136098206 0.999545079266151 -0.00280514403790563 0.0220588892690509 -0.00519619249841899 0.00265026336197345 0.999982987699107 0.0262875697410207 4.86865350267999e-05 3.93287191270945e-05 5.43758581393262e-06 7.34848527830276e-07 5.20145073544387e-07 2.11573352887281e-05 3.93287191270945e-05 6.11346110108613e-05 6.27498147921221e-06 1.7122129498136e-06 2.6032178470225e-06 9.07522671656086e-06 5.43758581393262e-06 6.27498147921221e-06 1.15919876519478e-05 -1.71867603915798e-06 -4.68735545942048e-06 2.8402692440831e-06 7.34848527830276e-07 1.7122129498136e-06 -1.71867603915798e-06 1.46563691491077e-05 -1.57456500722504e-06 -4.15267536671515e-06 5.20145073544387e-07 2.6032178470225e-06 -4.68735545942048e-06 -1.57456500722504e-06 1.29314959423887e-05 8.48547505531805e-07 2.11573352887281e-05 9.07522671656086e-06 2.8402692440831e-06 -4.15267536671515e-06 8.48547505531805e-07 0.000131536027644922 3813 3727 0 124 1 3813 3727 0 0 52 0 0 0 0 0 0 0 0 3633 0 0 0 0 0 3765 +1247 1248 0.998604753354438 0.0439967539217786 0.0292032912917233 0.112782034935317 -0.0439182637678878 0.999029597649138 -0.00332402295639167 0.0386262862417193 -0.0293211985692436 0.00203682727467163 0.999567965997869 0.0464975458199964 4.21791258367705e-05 1.75189065236768e-05 1.81073038905522e-06 -1.01139570834887e-06 -4.91616215261511e-06 1.95872398238288e-05 1.75189065236768e-05 3.97610486076446e-05 2.89886496545708e-06 -1.59721761057159e-07 -3.47514264900576e-06 2.37613860176066e-05 1.81073038905522e-06 2.89886496545708e-06 1.29368626705515e-05 -4.27526728444579e-06 -6.78149180149994e-06 5.81389948394614e-07 -1.01139570834887e-06 -1.59721761057159e-07 -4.27526728444579e-06 1.80484893804534e-05 -1.89516770892105e-06 -1.39868763759534e-05 -4.91616215261511e-06 -3.47514264900576e-06 -6.78149180149994e-06 -1.89516770892105e-06 1.64244243267922e-05 -2.62164970615233e-06 1.95872398238288e-05 2.37613860176066e-05 5.81389948394614e-07 -1.39868763759534e-05 -2.62164970615233e-06 0.000104178090356958 3838 3839 0 164 15 3838 3839 0 137 59 0 0 0 0 0 0 0 0 3509 0 0 0 0 0 3785 +1256 1257 0.998334263811583 0.0547054278101884 -0.0183306810536078 0.0566273004338522 -0.0551786361687248 0.998127730724928 -0.0263884684751578 0.0209917652914341 0.0168527686254908 0.0273559742288438 0.99948368414079 0.103227008004165 8.41254147543222e-05 -1.45243780242809e-05 8.06006535256482e-06 2.05885881656721e-06 1.47096597032893e-07 2.24160875797196e-06 -1.45243780242809e-05 0.000115725144562516 1.07903815315456e-06 -6.9222318610423e-06 -4.42896661766241e-06 2.73665700310289e-05 8.06006535256482e-06 1.07903815315456e-06 1.74488427486249e-05 -4.12401419851917e-06 -2.96572133800001e-06 5.58066251138063e-06 2.05885881656721e-06 -6.9222318610423e-06 -4.12401419851917e-06 1.65679239757862e-05 -3.34213195137907e-06 -1.87762946820022e-05 1.47096597032893e-07 -4.42896661766241e-06 -2.96572133800001e-06 -3.34213195137907e-06 1.79012066282824e-05 2.14818183483553e-05 2.24160875797196e-06 2.73665700310289e-05 5.58066251138063e-06 -1.87762946820022e-05 2.14818183483553e-05 0.000402938108591019 2136 2136 0 0 0 2160 2205 0 0 0 0 0 0 0 0 0 0 0 2491 0 0 4 0 0 3570 +1251 1252 0.999323398162727 0.0195063428913746 -0.0311808991452176 0.0949030374737642 -0.0196735648423037 0.999793626183095 -0.00506516436591148 0.0306996453174001 0.0310756613911238 0.00567517670757019 0.999500923280435 0.0858651779396251 5.08471954817905e-05 2.96747392251224e-05 -7.48450386048388e-07 -2.99360672376913e-06 -9.63398526482999e-07 3.39762578655437e-05 2.96747392251224e-05 6.52825267879397e-05 -1.08436763244856e-06 6.4684164140029e-07 -3.87734558086438e-06 5.38242566240056e-05 -7.48450386048388e-07 -1.08436763244856e-06 1.51576509217614e-05 -4.23214430398573e-06 -7.70678703228123e-06 -2.41120580008438e-06 -2.99360672376913e-06 6.4684164140029e-07 -4.23214430398573e-06 1.5493906168882e-05 -1.75881508631929e-06 -8.78497089037693e-06 -9.63398526482999e-07 -3.87734558086438e-06 -7.70678703228123e-06 -1.75881508631929e-06 1.65026779328596e-05 -3.24669347873927e-06 3.39762578655437e-05 5.38242566240056e-05 -2.41120580008438e-06 -8.78497089037693e-06 -3.24669347873927e-06 0.000256470847206258 3811 3763 0 89 46 3811 3763 0 2 95 0 0 0 0 0 0 0 0 3663 0 0 0 0 0 3753 +1257 1258 0.998221451295287 0.0530984337661584 -0.027101485300858 0.0471734328575794 -0.0545408682826539 0.996962624330609 -0.0555951380500109 0.0237740187464942 0.0240671531533319 0.0569743979293021 0.998085512428513 0.0766388849505436 6.16812002111749e-05 -1.17350941753622e-05 -3.05739686139796e-06 6.19013151121537e-06 2.23214822720148e-06 -4.15221463045615e-07 -1.17350941753622e-05 9.18387702783667e-05 -9.09765360879622e-06 -1.18356286373611e-06 -4.17010292809004e-06 4.20369599367875e-05 -3.05739686139796e-06 -9.09765360879622e-06 1.68239904931169e-05 -2.15270309552029e-06 -4.49991454493127e-06 -4.79193270227255e-06 6.19013151121537e-06 -1.18356286373611e-06 -2.15270309552029e-06 1.85877587190953e-05 -2.65441711717766e-06 1.63268743075521e-06 2.23214822720148e-06 -4.17010292809004e-06 -4.49991454493127e-06 -2.65441711717766e-06 1.5370817808632e-05 5.24519927090119e-06 -4.15221463045615e-07 4.20369599367875e-05 -4.79193270227255e-06 1.63268743075521e-06 5.24519927090119e-06 0.000125116010945421 1972 1972 0 0 0 2006 2050 0 0 0 0 0 0 0 0 0 0 0 2098 0 0 8 0 0 3509 +1258 1259 0.99953235504614 0.0304272326340195 0.00304215879799879 0.038505120874635 -0.0302834250714949 0.998759710771775 -0.0395215675931449 0.0340564215393789 -0.00424091757242883 0.0394109585434765 0.999214086652519 0.063029567463255 0.000123194399942636 4.02028631297741e-06 1.14567547859239e-05 1.95410749156804e-06 1.70806860577798e-06 -2.46700347360334e-05 4.02028631297741e-06 8.29328826528017e-05 -4.84647171445057e-06 -6.8599027309904e-06 4.0843087900486e-06 3.33186448327006e-05 1.14567547859239e-05 -4.84647171445057e-06 1.43877920155142e-05 1.24563516252866e-06 -5.51528958699005e-06 -3.26917252963755e-06 1.95410749156804e-06 -6.8599027309904e-06 1.24563516252866e-06 1.81553608871895e-05 -5.00544384585975e-06 -4.28875450670733e-06 1.70806860577798e-06 4.0843087900486e-06 -5.51528958699005e-06 -5.00544384585975e-06 1.59306941830751e-05 1.1417118850132e-05 -2.46700347360334e-05 3.33186448327006e-05 -3.26917252963755e-06 -4.28875450670733e-06 1.1417118850132e-05 9.8583757681081e-05 1852 1883 0 0 0 1852 1934 0 0 6 0 0 0 0 0 0 0 0 1748 0 0 0 0 0 3448 +1254 1255 0.998791481557825 0.042473323490808 0.0247304096037805 0.0780963275933652 -0.0422525299110464 0.999062898901935 -0.00938337645934416 0.0176595605537057 -0.0251057778935789 0.00832711410434701 0.999650118334936 0.081863957832319 9.54399021011153e-05 -3.36099955198166e-06 8.34003559717446e-06 5.61918766375336e-06 2.40681510527891e-06 -0.000173024354750713 -3.36099955198166e-06 0.000133063288848171 5.21527004012238e-07 -1.35009688185935e-06 -7.8639428067882e-06 -7.01983827971195e-06 8.34003559717446e-06 5.21527004012238e-07 1.53422654587675e-05 -4.03439560383404e-06 -5.42033787310433e-06 -2.60044818414537e-05 5.61918766375336e-06 -1.35009688185935e-06 -4.03439560383404e-06 1.92617725915842e-05 1.68261926939429e-06 -7.56283205952104e-05 2.40681510527891e-06 -7.8639428067882e-06 -5.42033787310433e-06 1.68261926939429e-06 1.59080237514798e-05 -3.44287693690656e-05 -0.000173024354750713 -7.01983827971195e-06 -2.60044818414537e-05 -7.56283205952104e-05 -3.44287693690656e-05 0.00173384905575264 3650 3516 0 119 0 3650 3555 0 1 4 0 0 0 0 0 0 0 0 3420 0 0 0 0 0 3770 +1252 1253 0.999682613588264 0.0244907116038774 -0.00590568662161579 0.0951294507807324 -0.0244914993617289 0.999700036374083 -6.10955894107168e-05 0.0239936982544946 0.00590241885598272 0.000205715318624695 0.999982559414341 0.0381985884996315 3.48128640449113e-05 2.40912358196814e-05 -4.45573542134715e-06 3.69489551035548e-07 -2.92413840783402e-06 2.49209347539998e-05 2.40912358196814e-05 7.15311395533543e-05 -1.18995679355677e-06 5.91634934388083e-06 -4.42992807054551e-06 1.03898241088446e-05 -4.45573542134715e-06 -1.18995679355677e-06 1.42665881892453e-05 -3.11307786736188e-06 -4.78618153380388e-06 -6.04154691816215e-06 3.69489551035548e-07 5.91634934388083e-06 -3.11307786736188e-06 1.54323080643202e-05 -1.30530786289407e-06 -4.70436011784136e-06 -2.92413840783402e-06 -4.42992807054551e-06 -4.78618153380388e-06 -1.30530786289407e-06 1.70014686925969e-05 -8.26088245442722e-06 2.49209347539998e-05 1.03898241088446e-05 -6.04154691816215e-06 -4.70436011784136e-06 -8.26088245442722e-06 0.000105325732254282 3814 3748 0 115 26 3814 3748 0 5 80 0 0 0 0 0 0 0 0 3642 0 0 0 0 0 3759 +1260 1261 0.999618724910091 0.025487700635803 -0.0106198834938384 0.0196489573776852 -0.0258432078187091 0.999059967696136 -0.0348038727246689 0.0282917488079577 0.00972282977131794 0.0350650547311084 0.99933773496148 0.0505942687615517 9.48736225304989e-05 3.64936720510002e-05 -9.55084064319571e-07 7.07802831544762e-06 -3.43852688255872e-07 3.0306102472875e-06 3.64936720510002e-05 0.000104464759445232 -1.29682129584608e-05 5.32012189348105e-06 -1.36614842188001e-05 -1.17258946076726e-05 -9.55084064319571e-07 -1.29682129584608e-05 1.32336419645051e-05 1.84245867349686e-06 -2.86862665387236e-06 9.61663806375641e-06 7.07802831544762e-06 5.32012189348105e-06 1.84245867349686e-06 2.0993272770855e-05 -9.44809662574304e-06 -1.61742021805329e-05 -3.43852688255872e-07 -1.36614842188001e-05 -2.86862665387236e-06 -9.44809662574304e-06 2.20862367369279e-05 2.96655977271124e-05 3.0306102472875e-06 -1.17258946076726e-05 9.61663806375641e-06 -1.61742021805329e-05 2.96655977271124e-05 0.000112663747321748 1642 1647 0 0 0 1645 1721 0 0 0 0 0 0 0 0 0 0 0 1240 0 0 0 0 0 3515 +1266 1267 0.999937499871334 0.0101700717116255 0.00464391994395235 -0.00224387195500891 -0.0103186774223216 0.999395992908218 0.0331839457456593 -0.00990892419068174 -0.00430363187546449 -0.0332297908566573 0.999438472219427 -0.00185216614967088 6.70231296561758e-05 4.65616186005323e-05 -9.83989132121178e-06 1.20631548243694e-05 -6.10175149116579e-07 8.38963819567857e-06 4.65616186005323e-05 0.000171336600951611 -2.2949716763582e-05 4.4366063473767e-05 -3.87112505030812e-06 -2.31699879403749e-05 -9.83989132121178e-06 -2.2949716763582e-05 1.34725019680688e-05 -2.9188673396902e-06 -6.34441272900704e-06 -1.0422634280703e-06 1.20631548243694e-05 4.4366063473767e-05 -2.9188673396902e-06 3.15417961455921e-05 -2.0375701931708e-06 -3.6711317136531e-06 -6.10175149116579e-07 -3.87112505030812e-06 -6.34441272900704e-06 -2.0375701931708e-06 2.00783484732018e-05 1.00615187231671e-05 8.38963819567857e-06 -2.31699879403749e-05 -1.0422634280703e-06 -3.6711317136531e-06 1.00615187231671e-05 0.000137485627147949 1510 1510 0 0 0 1555 1596 0 0 0 0 0 0 0 0 0 0 0 784 0 0 7 0 0 3426 +1264 1265 0.999829864126018 -0.00867072763181605 0.0162807028129357 8.11598606353572e-05 0.00861135340225315 0.999956026366696 0.00371347889568762 0.000839227386205957 -0.0163121854553513 -0.00357264821415094 0.999860564674099 0.017406359805122 8.10592144121314e-05 1.33986927152631e-05 -4.03952955411449e-06 5.06981909391928e-06 -5.12681431402349e-06 7.22399334882424e-06 1.33986927152631e-05 7.38153560431504e-05 -8.37495661778193e-06 7.28144471842671e-06 -8.26635143906737e-06 6.17629890716189e-06 -4.03952955411449e-06 -8.37495661778193e-06 1.12258465927607e-05 6.99871032333929e-07 -4.84384841639302e-06 1.18719232036621e-06 5.06981909391928e-06 7.28144471842671e-06 6.99871032333929e-07 2.38670303267753e-05 -5.24603105451078e-07 -6.26246031411901e-06 -5.12681431402349e-06 -8.26635143906737e-06 -4.84384841639302e-06 -5.24603105451078e-07 1.8618458303622e-05 4.58144421446617e-06 7.22399334882424e-06 6.17629890716189e-06 1.18719232036621e-06 -6.26246031411901e-06 4.58144421446617e-06 7.39524791057911e-05 1562 1585 0 0 0 1562 1646 0 0 1 0 0 0 0 0 0 0 0 734 0 0 0 0 0 3409 +1261 1262 0.99993096099474 0.00357737214851947 -0.0111926606598341 0.0101704239065605 -0.00368187930978734 0.999949691652355 -0.00933048386245633 0.0230173706452348 0.0111587189624688 0.00937104972083678 0.999893827572831 0.0398565479009968 7.69119822100255e-05 2.2214304052848e-05 -1.03779872427867e-06 5.14404786479815e-06 -1.88869463946866e-05 -3.54956410961287e-05 2.2214304052848e-05 9.38012811731425e-05 -1.32967546413768e-05 1.70595828176021e-05 -1.18165092562687e-05 -2.00903390286492e-05 -1.03779872427867e-06 -1.32967546413768e-05 1.42977645607757e-05 -2.14307054881593e-06 -6.36572807590495e-06 3.95896474968451e-06 5.14404786479815e-06 1.70595828176021e-05 -2.14307054881593e-06 2.57206644948606e-05 -9.590514829279e-07 -1.0404758753575e-05 -1.88869463946866e-05 -1.18165092562687e-05 -6.36572807590495e-06 -9.590514829279e-07 2.54992199979251e-05 2.49399499760834e-05 -3.54956410961287e-05 -2.00903390286492e-05 3.95896474968451e-06 -1.0404758753575e-05 2.49399499760834e-05 0.00011194107365359 1571 1607 0 0 0 1571 1652 0 0 9 0 0 0 0 0 0 0 0 999 0 0 0 0 0 3460 +1265 1266 0.999728073518931 -0.0208433929855675 -0.0104561937136121 -0.00159393934436184 0.0208147766929783 0.999779320522469 -0.00283819077078654 -0.00500165657385587 0.0105130437718499 0.00261977565435027 0.999941304620512 0.00505288176115778 8.26154770201697e-05 8.80720271190972e-06 -4.22509990719455e-06 3.00596542735775e-06 -3.70019090319797e-06 3.34438194246224e-05 8.80720271190972e-06 0.000173516287235768 -3.09610099840312e-05 5.02739532579155e-05 -2.86282222987996e-06 9.28994875742855e-06 -4.22509990719455e-06 -3.09610099840312e-05 1.48662092843271e-05 -5.89603958305857e-06 -6.26455528404993e-06 -4.5982428870817e-06 3.00596542735775e-06 5.02739532579155e-05 -5.89603958305857e-06 3.66573820255746e-05 -2.35984325300983e-06 -4.8393146059536e-07 -3.70019090319797e-06 -2.86282222987996e-06 -6.26455528404993e-06 -2.35984325300983e-06 1.96895168653697e-05 1.01578189545515e-05 3.34438194246224e-05 9.28994875742855e-06 -4.5982428870817e-06 -4.8393146059536e-07 1.01578189545515e-05 8.71103376075809e-05 1476 1515 0 0 0 1476 1560 0 0 7 0 0 0 0 0 0 0 0 650 0 0 0 0 0 3405 +1267 1268 0.999922728807712 0.00634847369051382 0.0106879977329745 -0.00345515093252664 -0.00639736540196334 0.999969201084957 0.00454649287109605 -0.00740959997831075 -0.0106588052638641 -0.00461451658508436 0.999932545778481 -0.00838539218854411 8.05852648453544e-05 1.37893097970086e-05 3.30581458507238e-07 1.1998046271356e-05 3.17826039418265e-06 -1.8620802413498e-06 1.37893097970086e-05 3.88396826267851e-05 -2.25264633722714e-06 3.84002377161223e-06 1.69386734866596e-06 1.11874466017884e-05 3.30581458507238e-07 -2.25264633722714e-06 1.15253499594557e-05 2.73461734930089e-06 -3.87340576216633e-06 -1.22622954042667e-06 1.1998046271356e-05 3.84002377161223e-06 2.73461734930089e-06 2.08897447327314e-05 -4.47787513764625e-06 -5.14119552356839e-06 3.17826039418265e-06 1.69386734866596e-06 -3.87340576216633e-06 -4.47787513764625e-06 1.94085944624227e-05 3.53606094761028e-06 -1.8620802413498e-06 1.11874466017884e-05 -1.22622954042667e-06 -5.14119552356839e-06 3.53606094761028e-06 6.1759672464089e-05 1486 1488 0 0 0 1513 1569 0 0 0 0 0 0 0 0 0 0 0 776 0 0 1 0 0 3474 +1255 1256 0.998302733563979 0.0579952913942247 -0.0053102104276153 0.0618515888993465 -0.0581201332944135 0.997929480856166 -0.027546349013661 0.0155747435131277 0.00370165699737285 0.0278082256579196 0.999606422709074 0.0924482426005417 8.66888256688837e-05 4.69491828859258e-05 2.30308316901921e-06 4.41787418225596e-06 -4.3135651858705e-06 4.93783545424157e-05 4.69491828859258e-05 6.80644294461389e-05 -1.87964941482729e-06 4.08269954906435e-06 -2.35381776790589e-06 5.69564553741832e-05 2.30308316901921e-06 -1.87964941482729e-06 1.38206229964203e-05 -1.99293755233416e-06 -4.77470034538134e-06 -1.90165981046047e-06 4.41787418225596e-06 4.08269954906435e-06 -1.99293755233416e-06 1.71978708268405e-05 4.18877814094724e-06 1.10232345993045e-07 -4.3135651858705e-06 -2.35381776790589e-06 -4.77470034538134e-06 4.18877814094724e-06 1.70032512629241e-05 -3.02428423255969e-06 4.93783545424157e-05 5.69564553741832e-05 -1.90165981046047e-06 1.10232345993045e-07 -3.02428423255969e-06 0.00016040856055384 2413 2413 0 0 0 2448 2483 0 0 0 0 0 0 0 0 0 0 0 3027 0 0 9 0 0 3668 +1270 1271 0.999953241697868 0.00676835433318608 0.00690679357925204 -0.00182318413668769 -0.00683220210704473 0.999933758027024 0.00926285983489059 -0.00209481868551252 -0.00684364174211724 -0.00930961532893691 0.999933245586991 0.00119240626982442 7.00155807118321e-05 2.57706039862822e-05 3.07621851983273e-06 9.21974530320913e-06 7.09826114746728e-06 2.21988309597431e-05 2.57706039862822e-05 4.56938584764035e-05 -1.24989718249457e-06 1.0564738235414e-05 1.39239772499096e-06 1.84467416105057e-05 3.07621851983273e-06 -1.24989718249457e-06 1.33992592931625e-05 4.37508020443986e-07 -1.15968559423007e-06 -3.49974059433198e-06 9.21974530320913e-06 1.0564738235414e-05 4.37508020443986e-07 2.36399475375672e-05 -3.41383263967864e-06 4.235370594328e-06 7.09826114746728e-06 1.39239772499096e-06 -1.15968559423007e-06 -3.41383263967864e-06 2.17343486825086e-05 -2.68599345517438e-06 2.21988309597431e-05 1.84467416105057e-05 -3.49974059433198e-06 4.235370594328e-06 -2.68599345517438e-06 4.16006602983197e-05 1405 1418 0 0 0 1426 1501 0 0 3 0 0 0 0 0 0 0 0 802 0 0 2 0 0 3340 +1269 1270 0.999716952094794 0.0019537154370856 -0.0237107294338822 0.00194069313480201 -0.00186635518636147 0.999991391145348 0.00370598887068395 -0.00541040460487501 0.0237177657593251 -0.00366068725544605 0.999711992003799 -0.000631275934555695 5.36317008843419e-05 2.34370880831988e-05 -2.42230134596245e-06 3.37870777759736e-06 -7.00656412713332e-07 1.18507224053514e-05 2.34370880831988e-05 4.71468379369184e-05 2.63779516206903e-07 5.26052017139401e-06 1.37511303440791e-06 1.12038003202704e-05 -2.42230134596245e-06 2.63779516206903e-07 1.15534319154414e-05 2.56185400256339e-06 -3.67401999997284e-06 -3.33546752766957e-06 3.37870777759736e-06 5.26052017139401e-06 2.56185400256339e-06 1.82117949945494e-05 -4.15526021054009e-06 3.75603246197757e-06 -7.00656412713332e-07 1.37511303440791e-06 -3.67401999997284e-06 -4.15526021054009e-06 1.89805709273723e-05 -3.35718591534963e-06 1.18507224053514e-05 1.12038003202704e-05 -3.33546752766957e-06 3.75603246197757e-06 -3.35718591534963e-06 6.03780321628802e-05 1437 1438 0 0 0 1446 1524 0 0 2 0 0 0 0 0 0 0 0 795 0 0 0 0 0 3402 +1259 1260 0.999854416048869 0.00887394625465627 0.0145739420008644 0.02499286240825 -0.00848829962047412 0.999617703883357 -0.0263133968259295 0.0375152833798869 -0.014801874108644 0.0261858580312971 0.999547500303031 0.0487882263858801 0.000129832921165799 2.04772751452138e-05 -2.08929880194974e-06 2.15361795941643e-05 -6.81060400027369e-06 -1.63054213378898e-05 2.04772751452138e-05 6.58238791511212e-05 -8.69151892041728e-06 2.17510381432747e-06 -2.17154053218214e-06 4.6047874781304e-05 -2.08929880194974e-06 -8.69151892041728e-06 1.41820624375248e-05 1.20647775686885e-06 -6.17111608360283e-06 -6.63298914763721e-06 2.15361795941643e-05 2.17510381432747e-06 1.20647775686885e-06 2.22030200969575e-05 -7.34760468028735e-06 -5.74744145371569e-06 -6.81060400027369e-06 -2.17154053218214e-06 -6.17111608360283e-06 -7.34760468028735e-06 1.64395161471918e-05 1.15802504049025e-05 -1.63054213378898e-05 4.6047874781304e-05 -6.63298914763721e-06 -5.74744145371569e-06 1.15802504049025e-05 0.00011422890807936 1707 1777 0 0 0 1707 1786 0 0 39 0 0 0 0 0 0 0 0 1591 0 0 0 0 0 3447 +1262 1263 0.998581137432911 0.0240684779356236 -0.0475017929457007 0.0120734469576015 -0.0238567273376629 0.999702785232215 0.00501973701382976 0.00326408522000948 0.047608492140901 -0.00387937737452851 0.998858539487577 0.0238918663155932 6.91572056972893e-05 1.10124669841537e-05 -4.20674732375964e-06 1.07949360607383e-05 -7.40898740250876e-06 -1.11330771835101e-05 1.10124669841537e-05 8.17395079577197e-05 -8.88527902650489e-06 1.06150205747276e-05 -1.30842281348538e-05 -1.43620235079277e-05 -4.20674732375964e-06 -8.88527902650489e-06 1.1770938373778e-05 2.02644042277404e-06 -5.18083131824051e-06 3.03145238749297e-06 1.07949360607383e-05 1.06150205747276e-05 2.02644042277404e-06 2.22697811734504e-05 -4.9075214456604e-06 -6.83462689557074e-06 -7.40898740250876e-06 -1.30842281348538e-05 -5.18083131824051e-06 -4.9075214456604e-06 1.91773055990149e-05 1.49156051637498e-05 -1.11330771835101e-05 -1.43620235079277e-05 3.03145238749297e-06 -6.83462689557074e-06 1.49156051637498e-05 9.5352619842399e-05 1562 1562 0 0 0 1603 1641 0 0 0 0 0 0 0 0 0 0 0 843 0 0 13 0 0 3434 +1263 1264 0.999943390029242 0.00438695569884291 -0.00969388242777995 0.0107020918080782 -0.00438481565745137 0.999990357366228 0.000242004572263164 0.00147923273774559 0.00969485061655931 -0.000199484984940583 0.999952983933376 0.0175448169486458 0.000156069002170807 0.000107379272912496 -2.14579446799406e-05 3.25282924903085e-05 -4.32015250511371e-05 -8.76408341821107e-05 0.000107379272912496 0.000121021394393209 -2.04789757628378e-05 2.82866050026618e-05 -3.37666646993444e-05 -4.93844232651963e-05 -2.14579446799406e-05 -2.04789757628378e-05 1.37175405220569e-05 -4.3798915910378e-07 -1.77057871915255e-06 7.50713481363181e-06 3.25282924903085e-05 2.82866050026618e-05 -4.3798915910378e-07 2.61142889694374e-05 -1.19905222794205e-05 -1.4571742230703e-05 -4.32015250511371e-05 -3.37666646993444e-05 -1.77057871915255e-06 -1.19905222794205e-05 3.23081990965602e-05 4.82173646277914e-05 -8.76408341821107e-05 -4.93844232651963e-05 7.50713481363181e-06 -1.4571742230703e-05 4.82173646277914e-05 0.000174987973763539 1598 1608 0 0 0 1598 1682 0 0 0 0 0 0 0 0 0 0 0 763 0 0 0 0 0 3389 +1268 1269 0.999758513030957 -0.00768431927005441 -0.020588027090668 -0.00303022035636792 0.00783736255011269 0.999942177407051 0.00736325951624147 -0.000102903591517442 0.0205302550005668 -0.00752283721751972 0.999760929197481 0.0039433185900721 5.96273180663044e-05 2.19772795820057e-05 -7.26721055500561e-06 4.31705551084469e-06 -2.60990907445809e-06 -7.64379832023065e-06 2.19772795820057e-05 4.10693972553114e-05 -5.79014244174968e-06 7.38387979269056e-06 1.19662410183369e-06 5.37326541200248e-06 -7.26721055500561e-06 -5.79014244174968e-06 1.2264458347936e-05 2.40364584880364e-06 -5.00545304692618e-06 -4.64881623268158e-06 4.31705551084469e-06 7.38387979269056e-06 2.40364584880364e-06 2.03220343887494e-05 -9.24008650311821e-06 3.04939665217094e-06 -2.60990907445809e-06 1.19662410183369e-06 -5.00545304692618e-06 -9.24008650311821e-06 1.86561304019961e-05 5.45112200056419e-06 -7.64379832023065e-06 5.37326541200248e-06 -4.64881623268158e-06 3.04939665217094e-06 5.45112200056419e-06 6.30063783055848e-05 1524 1539 0 0 0 1527 1613 0 0 0 0 0 0 0 0 0 0 0 757 0 0 0 0 0 3446 +1272 1273 0.999916636831891 -0.0101282381116531 -0.00800863156565849 -0.0046856293840282 0.0102318763363957 0.999863047321524 0.0130075096599325 0.00779719085655626 0.00787579160703922 -0.0130883686405216 0.999883326450087 0.00332734919459113 5.89458483258541e-05 2.54435048925243e-05 6.57970730468156e-06 7.26454345816298e-06 2.21973930825059e-06 9.44187963696416e-06 2.54435048925243e-05 4.37170827096548e-05 1.79947260793651e-06 1.05980753378318e-05 3.35178555362706e-06 1.82572893037673e-05 6.57970730468156e-06 1.79947260793651e-06 1.38428035796177e-05 2.68136939589418e-06 -1.81348462761297e-06 -2.34197213331701e-06 7.26454345816298e-06 1.05980753378318e-05 2.68136939589418e-06 2.18014764355984e-05 -6.71575473495215e-06 2.87596708073836e-06 2.21973930825059e-06 3.35178555362706e-06 -1.81348462761297e-06 -6.71575473495215e-06 2.2445932109066e-05 -8.80284525337844e-07 9.44187963696416e-06 1.82572893037673e-05 -2.34197213331701e-06 2.87596708073836e-06 -8.80284525337844e-07 4.70468181812342e-05 1248 1276 0 0 7 1252 1325 0 0 12 0 0 0 0 0 0 0 0 785 0 0 0 0 0 3353 +1274 1275 0.999977498955936 -0.0052716253549988 -0.00414868026574571 -0.0053376003353053 0.00528674843161322 0.999979389976625 0.00364278917842299 0.0026837866356489 0.00412939134155256 -0.00366464024075137 0.999984759153385 0.00418464836460532 5.46776254149272e-05 1.46203624053583e-05 1.13440045748255e-06 4.3896775135827e-06 -2.84994070131133e-06 1.78285831099899e-05 1.46203624053583e-05 3.80559834013373e-05 1.21187861262732e-06 4.08413327946093e-06 -3.36686007933139e-06 1.50896278277903e-05 1.13440045748255e-06 1.21187861262732e-06 1.1789770585282e-05 2.95749549281029e-06 -1.39343591188681e-06 3.60047654138716e-07 4.3896775135827e-06 4.08413327946093e-06 2.95749549281029e-06 2.18702188270023e-05 -6.87792667475582e-06 1.31123507147115e-06 -2.84994070131133e-06 -3.36686007933139e-06 -1.39343591188681e-06 -6.87792667475582e-06 2.83477234495699e-05 -1.12661688144515e-07 1.78285831099899e-05 1.50896278277903e-05 3.60047654138716e-07 1.31123507147115e-06 -1.12661688144515e-07 5.06453835373129e-05 1249 1258 0 0 0 1249 1325 0 0 0 0 0 0 0 0 0 0 0 781 0 5 25 0 0 3544 +1276 1277 0.999986405099315 0.000455272600560101 0.00519445313847263 -0.00358102702463926 -0.000504498109989154 0.999954944286021 0.00947918137806186 0.00311427540796735 -0.00518990348712058 -0.00948167310132323 0.99994157968203 0.00429844820093806 7.17128687987706e-05 3.13802982574996e-06 -3.39611832104909e-06 9.65708782340033e-06 -1.77292181758829e-06 1.62840921805726e-05 3.13802982574996e-06 4.15910466437059e-05 -2.36698566131989e-06 5.32100027636294e-06 -3.96829926999609e-06 2.11789765509874e-05 -3.39611832104909e-06 -2.36698566131989e-06 1.20067208605277e-05 1.05416198818882e-06 -3.51668981666896e-06 -1.17811285104517e-06 9.65708782340033e-06 5.32100027636294e-06 1.05416198818882e-06 2.35922999241221e-05 -6.95699178658394e-06 1.03187163765965e-06 -1.77292181758829e-06 -3.96829926999609e-06 -3.51668981666896e-06 -6.95699178658394e-06 2.191187572244e-05 -3.11439240524628e-06 1.62840921805726e-05 2.11789765509874e-05 -1.17811285104517e-06 1.03187163765965e-06 -3.11439240524628e-06 5.06502236023399e-05 1223 1225 0 0 0 1225 1300 0 0 0 0 0 0 0 0 0 0 0 780 0 0 0 0 0 3436 +1278 1279 0.99999959581618 0.000610548656908735 -0.000659998344139574 -0.00631909242668883 -0.000612461819323672 0.999995600376579 -0.00290243311814251 -0.00285558109289829 0.000658223363753352 0.0029028361688126 0.999995570132278 -0.00258553132311927 4.85979546102547e-05 3.0663002212678e-06 2.94781877086427e-06 -4.027121455658e-06 -2.77346798450604e-06 7.62291801405014e-06 3.0663002212678e-06 3.69566969560209e-05 3.04235796469786e-06 -4.57320745600057e-07 -6.71711425269158e-06 1.22455977996976e-05 2.94781877086427e-06 3.04235796469786e-06 1.0817036613251e-05 1.5714013518398e-06 -4.71668772470752e-06 1.85332057896881e-06 -4.027121455658e-06 -4.57320745600057e-07 1.5714013518398e-06 2.0566626459792e-05 -5.15433668545864e-06 1.78644444182018e-06 -2.77346798450604e-06 -6.71711425269158e-06 -4.71668772470752e-06 -5.15433668545864e-06 1.840931783497e-05 -5.5002401206358e-06 7.62291801405014e-06 1.22455977996976e-05 1.85332057896881e-06 1.78644444182018e-06 -5.5002401206358e-06 4.9182352657954e-05 1205 1205 0 0 0 1231 1286 0 0 0 0 0 0 0 0 0 0 0 789 0 0 10 0 0 3478 +1271 1272 0.999985078508664 0.000518976204643615 -0.00543814524631796 0.00290166442865253 -0.000571253352966474 0.999953602916941 -0.0096159078112857 -0.00225780488368956 0.00543290250490118 0.00961887088630648 0.999938978584816 -0.00869494633189284 4.1060768394685e-05 6.80510301317904e-06 -1.53596771127714e-06 -3.74070812609931e-07 2.73648306590477e-06 2.10676684170708e-06 6.80510301317904e-06 3.21911913666235e-05 -1.17517190311555e-06 3.22747925815531e-06 1.13831309501163e-07 6.46470166422897e-06 -1.53596771127714e-06 -1.17517190311555e-06 1.22478404136768e-05 1.86753168149133e-06 -4.38145909141591e-06 -2.56167250525484e-06 -3.74070812609931e-07 3.22747925815531e-06 1.86753168149133e-06 1.89198635161222e-05 -9.40202497058242e-07 5.07989778391207e-07 2.73648306590477e-06 1.13831309501163e-07 -4.38145909141591e-06 -9.40202497058242e-07 1.88566985760222e-05 -7.65131302106826e-06 2.10676684170708e-06 6.46470166422897e-06 -2.56167250525484e-06 5.07989778391207e-07 -7.65131302106826e-06 4.76416954235205e-05 1454 1455 0 0 0 1469 1549 0 0 0 0 0 0 0 0 0 0 0 803 0 0 3 0 0 3415 +1280 1281 0.999999905837963 0.000199785361740021 -0.000385240020480376 0.000154062324725889 -0.000199564676556982 0.99999981603445 0.000572804509137382 -0.000948874790876454 0.000385354387565548 -0.000572727574900859 0.999999761742532 0.000187355338600108 4.73882272850329e-05 -1.24163565541316e-06 3.90851397266496e-06 -1.31572314736323e-06 3.08209001294946e-06 1.17654942261377e-05 -1.24163565541316e-06 3.32070861949629e-05 9.66495966555056e-07 -1.68373328656998e-06 -3.32502057611431e-06 1.02162307846022e-05 3.90851397266496e-06 9.66495966555056e-07 1.11240533971363e-05 2.28356688004729e-06 -3.14240189941593e-06 1.0800567054761e-07 -1.31572314736323e-06 -1.68373328656998e-06 2.28356688004729e-06 1.76315464382812e-05 -3.80187660194043e-06 -1.05404952495921e-06 3.08209001294946e-06 -3.32502057611431e-06 -3.14240189941593e-06 -3.80187660194043e-06 1.61046713782079e-05 -1.43846078352929e-06 1.17654942261377e-05 1.02162307846022e-05 1.0800567054761e-07 -1.05404952495921e-06 -1.43846078352929e-06 3.79384003222441e-05 1234 1244 0 0 0 1235 1313 0 0 0 0 0 0 0 0 0 0 0 791 0 0 0 0 0 3499 +1282 1283 0.9999693844642 0.000125793121883044 -0.00782395746280764 -0.00483369391104463 -4.62398726352936e-05 0.999948311068134 0.0101672539980265 0.00300737358619044 0.00782483202142481 -0.0101665809433011 0.999917702931476 -0.00515256941195989 5.03753619539737e-05 2.12256746823152e-05 4.00882492683307e-06 -6.78330741182224e-07 -4.35636084327778e-06 1.96717864603305e-05 2.12256746823152e-05 3.5061940201881e-05 4.00286546138942e-06 -1.22406561741977e-06 -6.30861620584972e-06 1.68797155711576e-05 4.00882492683307e-06 4.00286546138942e-06 1.34057469945581e-05 1.03047145335865e-06 -2.71962468598513e-06 1.88157772635617e-06 -6.78330741182224e-07 -1.22406561741977e-06 1.03047145335865e-06 2.27494083921207e-05 -1.28366755625506e-05 -8.33655645581672e-07 -4.35636084327778e-06 -6.30861620584972e-06 -2.71962468598513e-06 -1.28366755625506e-05 2.25317146565898e-05 -5.78165405028761e-06 1.96717864603305e-05 1.68797155711576e-05 1.88157772635617e-06 -8.33655645581672e-07 -5.78165405028761e-06 4.68718007041869e-05 1346 1347 0 0 0 1352 1436 0 0 0 0 0 0 0 0 0 0 0 791 0 0 0 0 0 3492 +1285 1286 0.999983065952334 0.00118972635134505 0.00569669726940575 -4.83067500926754e-05 -0.00123355440034369 0.999969622450616 0.00769626659574715 0.00128078952636299 -0.00568736776652719 -0.00770316345278587 0.999954156509541 -0.000711747405770009 6.26409271463255e-05 2.38539782230653e-05 2.6269005317238e-06 1.0122084546173e-05 -6.1446736895818e-07 1.92728615597589e-05 2.38539782230653e-05 4.25881186047913e-05 1.24865554193769e-06 4.5066076488305e-06 -3.49459571880491e-06 1.81054774287488e-05 2.6269005317238e-06 1.24865554193769e-06 1.18603316198084e-05 2.51652314571971e-06 -5.22098518997464e-06 1.66202896461604e-06 1.0122084546173e-05 4.5066076488305e-06 2.51652314571971e-06 2.05460965909981e-05 -6.11666704899101e-06 -1.00656347730601e-06 -6.1446736895818e-07 -3.49459571880491e-06 -5.22098518997464e-06 -6.11666704899101e-06 1.54332063338047e-05 8.07537802472035e-07 1.92728615597589e-05 1.81054774287488e-05 1.66202896461604e-06 -1.00656347730601e-06 8.07537802472035e-07 3.74875573050342e-05 1267 1276 0 0 0 1270 1364 0 0 0 0 0 0 0 0 0 0 0 829 0 0 0 0 0 3383 +1273 1274 0.999954343574695 -0.00243435798633526 0.00924038242147175 0.00304875600225984 0.00243911946271169 0.999996898307342 -0.000504055494537315 0.00638915326331883 -0.00923912670912675 0.00052657087777239 0.999957179713593 -0.0027950851458528 5.12198999172253e-05 1.43761397421522e-05 3.03734525090583e-06 -4.79890086783563e-08 4.45057518422064e-06 2.32066045434188e-05 1.43761397421522e-05 3.67258558385665e-05 1.3881956761053e-07 2.8089341001171e-07 -1.88879342160991e-06 1.62938764334404e-05 3.03734525090583e-06 1.3881956761053e-07 1.30333381049507e-05 1.451528820706e-06 -1.36835755106161e-06 -2.21441485352356e-07 -4.79890086783563e-08 2.8089341001171e-07 1.451528820706e-06 1.78269642014023e-05 -5.94046285058462e-06 6.7182605951805e-07 4.45057518422064e-06 -1.88879342160991e-06 -1.36835755106161e-06 -5.94046285058462e-06 1.96908810209346e-05 -1.67054418109532e-06 2.32066045434188e-05 1.62938764334404e-05 -2.21441485352356e-07 6.7182605951805e-07 -1.67054418109532e-06 4.38378539538559e-05 1229 1258 0 0 0 1229 1309 0 0 6 0 0 0 0 0 0 0 0 784 0 0 0 0 0 3419 +1281 1282 0.99998370964337 0.00101486540475453 0.00561698282845665 -0.00198916709434016 -0.00100000344682821 0.999995993842251 -0.00264807336651186 -0.00207401566528052 -0.0056196477639863 0.0026424132262631 0.999980718419786 -0.00395536610748914 4.22803693473798e-05 1.68794548162754e-05 8.70251285212856e-06 -2.84685921949607e-06 3.40517381386141e-07 1.8088444809808e-05 1.68794548162754e-05 4.73170622435286e-05 9.46043984869692e-06 -2.02501748517117e-06 -8.10045807999887e-07 4.70422610472156e-06 8.70251285212856e-06 9.46043984869692e-06 1.33507213118743e-05 -2.04037103536902e-06 -1.24571608721804e-06 4.83575129897037e-07 -2.84685921949607e-06 -2.02501748517117e-06 -2.04037103536902e-06 2.33231081165868e-05 -2.95475573966017e-06 -4.80575724626143e-07 3.40517381386141e-07 -8.10045807999887e-07 -1.24571608721804e-06 -2.95475573966017e-06 2.27780925670394e-05 -8.28448834574325e-06 1.8088444809808e-05 4.70422610472156e-06 4.83575129897037e-07 -4.80575724626143e-07 -8.28448834574325e-06 4.98003585388485e-05 1322 1322 0 0 0 1330 1396 0 0 0 0 0 0 0 0 0 0 0 791 0 1 15 0 0 3419 +1286 1287 0.999990319741598 0.000849897228794371 0.00431718632879346 -0.00112312795998514 -0.00087951378660087 0.999976063291432 0.00686289295193229 -0.0014190125677845 -0.00431125023586111 -0.00686662354225063 0.999967130761073 -0.0013402895713288 4.71648227051314e-05 -8.45060836783586e-06 9.14761544654945e-08 6.31558925956175e-08 3.22961804182682e-06 6.52682623681539e-06 -8.45060836783586e-06 2.87518421251992e-05 2.07866933904433e-06 -1.85142007029653e-06 -2.78236083691292e-06 6.82952988016349e-06 9.14761544654945e-08 2.07866933904433e-06 1.33005637281532e-05 2.95483337694261e-06 -1.25500484382089e-06 7.14808866133351e-07 6.31558925956175e-08 -1.85142007029653e-06 2.95483337694261e-06 1.90416402839479e-05 -1.62771549403577e-06 1.0001413531722e-06 3.22961804182682e-06 -2.78236083691292e-06 -1.25500484382089e-06 -1.62771549403577e-06 2.48010236360071e-05 -2.50116132341632e-06 6.52682623681539e-06 6.82952988016349e-06 7.14808866133351e-07 1.0001413531722e-06 -2.50116132341632e-06 3.59659762156969e-05 1242 1246 0 0 0 1247 1319 0 0 0 0 0 0 0 0 0 0 0 785 0 0 0 0 0 3415 +1275 1276 0.99999719583411 -0.000692129303168838 -0.0022647915897775 -0.000114690958750693 0.000675013342979334 0.999971274533482 -0.00754946785344238 -0.00313226634405956 0.00226995174050721 0.00754791791893997 0.999968937644657 0.000399584130904747 5.16763732074205e-05 7.45043950372013e-07 2.11367480959914e-06 2.55045443729342e-06 7.29837094314065e-06 1.17192146922644e-05 7.45043950372013e-07 3.90878247952076e-05 -6.13287945230541e-07 3.92885758264813e-06 -1.86592580268348e-06 1.45000318551804e-05 2.11367480959914e-06 -6.13287945230541e-07 1.31215348887907e-05 2.59759248861708e-06 -1.32920711904685e-06 -1.67764618152905e-06 2.55045443729342e-06 3.92885758264813e-06 2.59759248861708e-06 1.94053161740069e-05 -4.07959571796251e-06 7.7859492798791e-06 7.29837094314065e-06 -1.86592580268348e-06 -1.32920711904685e-06 -4.07959571796251e-06 2.28300368780112e-05 1.88976266774651e-06 1.17192146922644e-05 1.45000318551804e-05 -1.67764618152905e-06 7.7859492798791e-06 1.88976266774651e-06 5.07574414330708e-05 1225 1227 0 0 0 1229 1302 0 0 0 0 0 0 0 0 0 0 0 793 0 0 0 0 0 3483 +1277 1278 0.999999800970644 -0.000150615234931344 -0.000612677503305277 -0.00329782512575741 0.000153125173086767 0.999991588615083 0.00409868903001454 0.000144706009188307 0.0006120550248278 -0.00409878203060384 0.999991412650385 0.00252474435593491 4.62179746910575e-05 8.49207998261351e-06 2.25725471239546e-06 -1.48855846098513e-06 -2.39709420424009e-06 1.48631190986949e-05 8.49207998261351e-06 5.27449733508465e-05 2.74940424573176e-06 2.23010702300691e-06 -5.35951491869945e-06 1.70881033552523e-05 2.25725471239546e-06 2.74940424573176e-06 1.16449501798251e-05 2.38096178580608e-06 -5.78435898916413e-06 2.57163414055509e-06 -1.48855846098513e-06 2.23010702300691e-06 2.38096178580608e-06 2.54285760291505e-05 -7.63869854570848e-07 3.57806255588598e-07 -2.39709420424009e-06 -5.35951491869945e-06 -5.78435898916413e-06 -7.63869854570848e-07 1.70348952248056e-05 -3.44363191221286e-06 1.48631190986949e-05 1.70881033552523e-05 2.57163414055509e-06 3.57806255588598e-07 -3.44363191221286e-06 3.84523202722918e-05 1200 1213 0 0 0 1203 1277 0 0 6 0 0 0 0 0 0 0 0 816 0 0 0 0 0 3433 +1287 1288 0.999996821270299 0.000782642707471492 0.00239685620985941 -0.00476436516223183 -0.000807187324124574 0.99994707442731 0.0102565487804991 -0.00311970159231423 -0.00238870214176497 -0.0102584508896532 0.999944527605118 0.00078063592675205 6.14871013285525e-05 3.07751767230057e-05 2.97150017143595e-06 -4.73941027511732e-07 -3.73516962439469e-06 1.55454965958545e-05 3.07751767230057e-05 5.90020694076482e-05 6.31022527867104e-06 -1.23235059652848e-06 -4.82747074898988e-06 7.25210053019276e-06 2.97150017143595e-06 6.31022527867104e-06 1.30337881804595e-05 5.09961100282938e-07 -4.0391185915567e-06 4.39122475980796e-06 -4.73941027511732e-07 -1.23235059652848e-06 5.09961100282938e-07 2.23348131362301e-05 -8.13588384147502e-06 -2.96546647283615e-06 -3.73516962439469e-06 -4.82747074898988e-06 -4.0391185915567e-06 -8.13588384147502e-06 1.69656727072327e-05 6.00187744353475e-07 1.55454965958545e-05 7.25210053019276e-06 4.39122475980796e-06 -2.96546647283615e-06 6.00187744353475e-07 4.68250779398136e-05 1250 1250 0 0 0 1277 1336 0 0 0 0 0 0 0 0 0 0 0 791 0 0 2 0 0 3452 +1279 1280 0.999980517435085 -0.000621433635583687 -0.00621116498710275 -0.00406849997846625 0.000651020966621223 0.999988446431116 0.00476268579518228 0.00270087024671361 0.00620813353283138 -0.00476663660448086 0.99996936865762 0.00319919375274235 7.38276005774282e-05 5.70296911031726e-06 8.25873889798477e-06 -4.78017839585564e-06 -3.19768907952451e-06 6.80857051360729e-06 5.70296911031726e-06 4.03170660786289e-05 1.75931788886074e-06 1.18817841979772e-06 -2.54128493816173e-06 1.9696023391067e-05 8.25873889798477e-06 1.75931788886074e-06 1.42009308865662e-05 2.15127052113204e-07 -3.19200687580809e-06 3.43795902975573e-08 -4.78017839585564e-06 1.18817841979772e-06 2.15127052113204e-07 2.26386365274709e-05 -4.63954471463415e-06 6.20448493064194e-07 -3.19768907952451e-06 -2.54128493816173e-06 -3.19200687580809e-06 -4.63954471463415e-06 2.09624074497142e-05 -1.54936152731359e-06 6.80857051360729e-06 1.9696023391067e-05 3.43795902975573e-08 6.20448493064194e-07 -1.54936152731359e-06 4.45192406024259e-05 1250 1250 0 0 0 1259 1326 0 0 0 0 0 0 0 0 0 0 0 788 0 0 1 0 0 3498 +1284 1285 0.999996054527381 0.0010979431569146 -0.0025856238115642 -0.00722951997653081 -0.00107604793085136 0.999963682943629 0.00845428380555264 0.00285711034818605 0.00259481223236941 -0.00845146819425498 0.99996091905376 0.00197622447780837 5.88294420825565e-05 1.03739522011141e-05 5.54170986228427e-06 3.5537900057631e-06 -5.80424474142594e-06 4.44224175951154e-06 1.03739522011141e-05 4.74763447864126e-05 8.34020889752312e-06 -2.80216672090966e-06 -4.12858000410164e-06 1.19164521311752e-05 5.54170986228427e-06 8.34020889752312e-06 1.52155904969032e-05 3.41212916944481e-08 -1.0113248107135e-06 2.007337651949e-06 3.5537900057631e-06 -2.80216672090966e-06 3.41212916944481e-08 2.55544708354765e-05 -1.29320673361983e-05 -2.18222920996348e-06 -5.80424474142594e-06 -4.12858000410164e-06 -1.0113248107135e-06 -1.29320673361983e-05 2.97855151979661e-05 -1.491142395831e-06 4.44224175951154e-06 1.19164521311752e-05 2.007337651949e-06 -2.18222920996348e-06 -1.491142395831e-06 5.3205872470866e-05 1345 1345 0 0 0 1360 1438 0 0 0 0 0 0 0 0 0 0 0 836 0 0 0 0 0 3497 +1283 1284 0.999994698722775 0.00139162072365983 0.00294379314949519 0.00130344261241511 -0.00138777496397503 0.999998181560174 -0.00130803554819235 8.46058843585371e-05 -0.00294560808576064 0.0013039432915013 0.999994811548989 -0.0021282460766309 5.86649118339512e-05 1.4618406395476e-05 2.73258011811163e-06 -4.42933195860369e-06 -3.58106506625126e-07 1.85673770398022e-05 1.4618406395476e-05 4.21040473928502e-05 1.35044658161389e-06 -3.22259541871435e-06 -5.20395315246748e-06 2.0299417174342e-05 2.73258011811163e-06 1.35044658161389e-06 1.16561200649376e-05 1.30829113455516e-06 -3.63804766977403e-06 1.61389935867708e-06 -4.42933195860369e-06 -3.22259541871435e-06 1.30829113455516e-06 2.00229789512019e-05 -2.20009074807135e-06 -3.92106611456107e-06 -3.58106506625126e-07 -5.20395315246748e-06 -3.63804766977403e-06 -2.20009074807135e-06 1.76679162197366e-05 -3.27116155994406e-06 1.85673770398022e-05 2.0299417174342e-05 1.61389935867708e-06 -3.92106611456107e-06 -3.27116155994406e-06 3.80425601319171e-05 1275 1290 0 0 0 1277 1370 0 0 0 0 0 0 0 0 0 0 0 794 0 0 0 0 0 3474 +1289 1290 0.999769757786058 0.000465067733226967 0.0214526252102134 -0.00587624906463737 -0.00122656897385498 0.999369016214451 0.0354973936946523 -0.0046236050715088 -0.0214225802591272 -0.0355155338206295 0.999139489717265 -0.00119701260927314 5.9563172864131e-05 3.71174231562988e-06 -3.87309085579814e-06 4.98870436662541e-06 1.07376800489483e-06 2.31801617448722e-05 3.71174231562988e-06 3.61226937039463e-05 -2.32486589048721e-07 -3.68602777451032e-06 -2.78008968464873e-07 1.45213787048186e-05 -3.87309085579814e-06 -2.32486589048721e-07 1.11497517415174e-05 1.85954941140937e-06 -5.65798594420576e-06 -8.073210237027e-07 4.98870436662541e-06 -3.68602777451032e-06 1.85954941140937e-06 2.25486976011544e-05 -2.05866643867356e-07 3.45083723313754e-07 1.07376800489483e-06 -2.78008968464873e-07 -5.65798594420576e-06 -2.05866643867356e-07 1.78137171953005e-05 2.2929678420465e-07 2.31801617448722e-05 1.45213787048186e-05 -8.073210237027e-07 3.45083723313754e-07 2.2929678420465e-07 4.1548489360888e-05 1377 1391 0 0 0 1393 1468 0 0 1 0 0 0 0 0 0 0 0 930 0 0 1 0 0 3348 +1292 1293 0.999970934435128 -0.000651368703535622 0.00759644678445476 -0.00404027527044773 0.000620266338623551 0.999991419120527 0.00409596813748622 0.00216536888199799 -0.00759904958571592 -0.00409113726562506 0.999962757827144 0.00071151379729662 5.32198385353117e-05 1.87505848368034e-06 -1.68813349708542e-06 -5.01434749906831e-06 -3.90728581933491e-06 1.86692744716366e-05 1.87505848368034e-06 4.757949312588e-05 8.51117663220243e-06 -1.62628958725321e-06 -7.84177743826449e-07 4.42934152369416e-07 -1.68813349708542e-06 8.51117663220243e-06 1.37730649897311e-05 -3.3228255059536e-07 -4.84446979174959e-06 3.10999413365681e-06 -5.01434749906831e-06 -1.62628958725321e-06 -3.3228255059536e-07 2.29230823340755e-05 -9.02676753746692e-07 -2.1440982041833e-06 -3.90728581933491e-06 -7.84177743826449e-07 -4.84446979174959e-06 -9.02676753746692e-07 2.62779749985551e-05 -1.10787543661243e-05 1.86692744716366e-05 4.42934152369416e-07 3.10999413365681e-06 -2.1440982041833e-06 -1.10787543661243e-05 3.97810224392618e-05 1405 1409 0 0 0 1407 1488 0 0 1 0 0 0 0 0 0 0 0 1111 0 0 0 0 0 3104 +1288 1289 0.999796169088173 -0.000191957954004968 0.0201886955684745 -0.00717787221383101 -0.000450364274809789 0.999493941386161 0.0318065764328314 -0.0121077655742737 -0.0201845844305158 -0.0318091855365941 0.999290127173718 0.00226220894674304 5.49262694567395e-05 -8.65964444872306e-06 -7.38295859569137e-07 -4.49146106824844e-06 9.66824413436846e-07 -1.0714792340687e-06 -8.65964444872306e-06 3.3063701667959e-05 1.45960924111072e-06 -1.40660971005319e-07 -9.16163857957948e-07 1.58526347527403e-05 -7.38295859569137e-07 1.45960924111072e-06 1.07699182206551e-05 1.67500711686457e-06 -4.73823447211017e-06 9.23847367243948e-07 -4.49146106824844e-06 -1.40660971005319e-07 1.67500711686457e-06 1.85064786915947e-05 -1.72584731924972e-06 6.87543453389646e-06 9.66824413436846e-07 -9.16163857957948e-07 -4.73823447211017e-06 -1.72584731924972e-06 1.78380650350731e-05 -2.31378874347452e-06 -1.0714792340687e-06 1.58526347527403e-05 9.23847367243948e-07 6.87543453389646e-06 -2.31378874347452e-06 4.27278059375025e-05 1352 1352 0 0 0 1397 1450 0 0 0 0 0 0 0 0 0 0 0 818 0 0 4 0 0 3449 +1290 1291 0.999915285843387 0.000250833182330903 0.0130137703780349 -0.0084995025256387 -0.000619426091951471 0.999598517951439 0.0283270051470785 -0.00512685304952815 -0.0130014402299971 -0.0283326665176549 0.999513993178657 0.0038692898509599 6.11439905716757e-05 -4.53097322286118e-06 -1.31241575673435e-06 -7.41958490960289e-08 -7.42152458965311e-07 3.07982428107437e-05 -4.53097322286118e-06 4.48489560102845e-05 2.36643659591425e-06 5.74174903416888e-06 1.13582728640486e-06 -9.44410321028085e-07 -1.31241575673435e-06 2.36643659591425e-06 1.49908284887913e-05 8.99469246853556e-07 9.09952549598449e-07 4.54846091080129e-06 -7.41958490960289e-08 5.74174903416888e-06 8.99469246853556e-07 2.2191549790318e-05 -6.85666356021331e-06 -3.81386843964276e-06 -7.42152458965311e-07 1.13582728640486e-06 9.09952549598449e-07 -6.85666356021331e-06 2.77805641990528e-05 -1.15490728802665e-06 3.07982428107437e-05 -9.44410321028085e-07 4.54846091080129e-06 -3.81386843964276e-06 -1.15490728802665e-06 5.44030892103905e-05 1283 1283 0 0 0 1317 1364 0 0 0 0 0 0 0 0 0 0 0 944 0 2 16 0 0 3235 +1298 1299 0.999999280108467 -0.000550511526831666 -0.0010661705340019 -0.00111755147772542 0.000546852762558946 0.999993971628724 -0.00342894419131638 0.000199359622056922 0.00106805178003226 0.00342835868454661 0.999993552790279 -0.00191761723428111 6.23326377213827e-05 1.12699893099152e-05 -7.576074576764e-06 1.05119973411179e-05 -3.74851266857245e-06 1.65660646951096e-05 1.12699893099152e-05 5.76201289768527e-05 -1.24217000238341e-05 7.19287802190908e-07 -7.59359525820292e-06 -5.70654699051249e-06 -7.576074576764e-06 -1.24217000238341e-05 1.78445101624613e-05 -1.33083343011417e-07 -2.06651547164548e-06 -1.34338703536832e-06 1.05119973411179e-05 7.19287802190908e-07 -1.33083343011417e-07 2.26494862827435e-05 -5.40938705792442e-06 -4.05320347191481e-07 -3.74851266857245e-06 -7.59359525820292e-06 -2.06651547164548e-06 -5.40938705792442e-06 2.5029412910797e-05 5.81790259011881e-06 1.65660646951096e-05 -5.70654699051249e-06 -1.34338703536832e-06 -4.05320347191481e-07 5.81790259011881e-06 4.67036139978629e-05 1399 1402 0 0 0 1400 1465 0 0 0 0 0 0 0 0 0 0 0 1005 0 10 25 0 0 3050 +1297 1298 0.999999886600431 7.18752320692579e-05 -0.000470779221495295 -0.00724556521840299 -7.21913109147309e-05 0.999999771996819 -0.000671412484576325 0.00172094343563239 0.000470730856227992 0.00067144639460759 0.999999663786044 -0.00482611573117878 4.55866398304651e-05 -1.38584021164539e-05 9.51301574977341e-06 3.85336895266597e-07 5.33213162913418e-06 1.4131074210821e-05 -1.38584021164539e-05 3.52727776977531e-05 -1.04462037330438e-05 -1.21545105583723e-06 -4.84604003612362e-06 -8.93461744580292e-06 9.51301574977341e-06 -1.04462037330438e-05 1.38570954079618e-05 2.20778079707996e-06 -1.80409621379795e-06 1.69317247264483e-06 3.85336895266597e-07 -1.21545105583723e-06 2.20778079707996e-06 1.96019328721861e-05 -8.9697066290989e-06 -5.76056537673616e-06 5.33213162913418e-06 -4.84604003612362e-06 -1.80409621379795e-06 -8.9697066290989e-06 2.29027776820898e-05 8.22096276839604e-06 1.4131074210821e-05 -8.93461744580292e-06 1.69317247264483e-06 -5.76056537673616e-06 8.22096276839604e-06 4.45830304223354e-05 1228 1228 0 0 0 1238 1301 0 0 0 0 0 0 0 0 0 0 0 1003 0 23 26 0 0 2790 +1291 1292 0.999709770756727 -0.000421814843362319 0.0240872648046687 -0.00501932467453717 -0.000317973855452076 0.999528569708597 0.0307007691909083 -0.0062079098350196 -0.0240888593785501 -0.0306995180503553 0.999238343162089 -0.00360798160207752 3.66507481112011e-05 3.92478594138965e-06 -4.4538707587087e-06 -1.1146381276219e-06 -1.04762527837057e-06 1.17713866126527e-05 3.92478594138965e-06 2.92165188701309e-05 3.5611392716542e-06 -3.04380337510421e-06 2.77242877686275e-06 3.71287832237264e-06 -4.4538707587087e-06 3.5611392716542e-06 1.02449114926239e-05 1.40429308234183e-06 -2.69442732803469e-06 -6.7364132191402e-07 -1.1146381276219e-06 -3.04380337510421e-06 1.40429308234183e-06 1.53315371359227e-05 -3.38217333071166e-06 2.48883265630336e-06 -1.04762527837057e-06 2.77242877686275e-06 -2.69442732803469e-06 -3.38217333071166e-06 1.99320440135112e-05 -1.06932120184551e-05 1.17713866126527e-05 3.71287832237264e-06 -6.7364132191402e-07 2.48883265630336e-06 -1.06932120184551e-05 3.82884383900893e-05 1372 1377 0 0 0 1386 1453 0 0 0 0 0 0 0 0 0 0 0 1046 0 0 1 0 0 3243 +1293 1294 0.999999495923905 0.000459970132451299 0.000892512976978649 -0.00312617018437885 -0.000463044379427284 0.999993950698655 0.00344734042382022 0.00225644514638052 -0.000890921904267348 -0.00344775195921588 0.999993659612194 0.00462482787805624 4.79754222600967e-05 2.47846240676331e-06 -4.66339235287723e-06 -2.85776359200265e-06 -6.22606050279439e-06 1.44578086156165e-05 2.47846240676331e-06 3.82490957589208e-05 -3.01887551684916e-06 -6.62036217381808e-07 -2.87713439246665e-06 4.70914336428948e-06 -4.66339235287723e-06 -3.01887551684916e-06 1.27714682511915e-05 3.55585956948989e-06 -3.1628408681233e-06 7.75781166583117e-07 -2.85776359200265e-06 -6.62036217381808e-07 3.55585956948989e-06 1.85587540710292e-05 -7.01147695346898e-06 -1.74848112803014e-06 -6.22606050279439e-06 -2.87713439246665e-06 -3.1628408681233e-06 -7.01147695346898e-06 2.43583480518166e-05 1.41821836190577e-06 1.44578086156165e-05 4.70914336428948e-06 7.75781166583117e-07 -1.74848112803014e-06 1.41821836190577e-06 3.19642183560802e-05 1404 1406 0 0 0 1411 1490 0 0 0 0 0 0 0 0 0 0 0 1091 0 0 2 0 0 2704 +1296 1297 0.999976365582447 0.000844133938397497 -0.0068231748046189 -0.0044805661415504 -0.000867801426401719 0.999993615214096 -0.00346647540400349 -0.00339023613550998 0.00682020507057345 0.00347231463670439 0.99997071348808 0.00289001729056825 6.6062617728874e-05 -2.74064080888993e-05 1.42062812777488e-05 3.37393694632885e-07 9.93800401437577e-06 2.80411265675705e-05 -2.74064080888993e-05 4.45594007199863e-05 -1.1195493069217e-05 -2.42656417052511e-06 -8.37493081179612e-06 -9.15854668993938e-06 1.42062812777488e-05 -1.1195493069217e-05 1.67987631798552e-05 4.99694250551403e-06 -1.12774903515982e-06 1.87156106505067e-07 3.37393694632885e-07 -2.42656417052511e-06 4.99694250551403e-06 2.06273139545724e-05 -1.54644367168304e-06 -7.19440160647061e-06 9.93800401437577e-06 -8.37493081179612e-06 -1.12774903515982e-06 -1.54644367168304e-06 2.79702490841459e-05 4.82709913550058e-06 2.80411265675705e-05 -9.15854668993938e-06 1.87156106505067e-07 -7.19440160647061e-06 4.82709913550058e-06 5.37550853717839e-05 1407 1407 0 0 0 1418 1473 0 0 0 0 0 0 0 0 0 0 0 1105 0 0 12 0 0 2877 +1299 1300 0.999992884964486 0.000291367824735224 0.00376100055758727 -0.000907034178075113 -0.000283641012917764 0.999997848615887 -0.00205482636093737 -0.00213151747188701 -0.00376159117651742 0.0020537449667671 0.999990816239545 -0.00152597202444714 4.67236701018092e-05 -1.5611665423776e-05 8.82384825679481e-06 5.35632399661366e-07 6.25696734305804e-06 1.23163266335625e-05 -1.5611665423776e-05 4.0497404290198e-05 -1.37328790442299e-05 5.06900478167993e-06 -1.07414525720252e-05 -2.4641348746514e-06 8.82384825679481e-06 -1.37328790442299e-05 2.2254458038398e-05 -2.59568985007272e-06 4.48160532539152e-06 2.24909994067274e-06 5.35632399661366e-07 5.06900478167993e-06 -2.59568985007272e-06 2.32450255292043e-05 -9.66494631138052e-06 -7.0784322812507e-06 6.25696734305804e-06 -1.07414525720252e-05 4.48160532539152e-06 -9.66494631138052e-06 3.55175500560866e-05 1.21734634361487e-05 1.23163266335625e-05 -2.4641348746514e-06 2.24909994067274e-06 -7.0784322812507e-06 1.21734634361487e-05 4.36975008689295e-05 1410 1410 0 0 0 1417 1484 0 0 0 0 0 0 0 0 0 0 0 997 0 0 6 0 0 3194 +1294 1295 0.999998513058959 -0.000128313337118279 0.00171971380158005 0.000154489671054146 0.000139790257960754 0.999977710291996 -0.00667528110716688 -0.00151275943712601 -0.0017188189420665 0.00667551158065338 0.999976241321053 0.00329197801329763 6.22341560778308e-05 6.36472917823232e-07 7.28074025492138e-06 -3.4364239533862e-06 3.1929217369916e-06 4.11460808154824e-05 6.36472917823232e-07 4.96436296510358e-05 -1.01765048432493e-05 -5.8282808962949e-07 -2.54060020549376e-06 3.22013348751651e-06 7.28074025492138e-06 -1.01765048432493e-05 1.75427634591533e-05 -8.62088389687161e-07 -1.33738767877802e-06 8.3405927123408e-07 -3.4364239533862e-06 -5.8282808962949e-07 -8.62088389687161e-07 2.1594804383125e-05 -3.8005894989833e-06 -6.24908224976756e-06 3.1929217369916e-06 -2.54060020549376e-06 -1.33738767877802e-06 -3.8005894989833e-06 2.58193803135514e-05 4.53273424451797e-06 4.11460808154824e-05 3.22013348751651e-06 8.3405927123408e-07 -6.24908224976756e-06 4.53273424451797e-06 5.35816416790626e-05 1401 1402 0 0 0 1404 1484 0 0 0 0 0 0 0 0 0 0 0 964 0 0 2 0 0 2825 +1295 1296 0.999998536800553 -1.54444237203476e-06 -0.00171067073608364 -0.00488449979759147 5.0962630347045e-06 0.999997844533458 0.00207627128932232 0.00146191901728133 0.00171066384210875 -0.00207627696935135 0.999996381345036 -0.00511584588877352 6.95521034215216e-05 -1.58206267953597e-05 1.51063611501661e-05 2.42215363351244e-06 1.2145722500536e-05 2.70356935821912e-05 -1.58206267953597e-05 3.87320673326568e-05 -1.69019560237904e-05 6.72312070453776e-06 -1.23764978501569e-05 -1.2147135085593e-05 1.51063611501661e-05 -1.69019560237904e-05 1.80317224500269e-05 3.66790661158252e-06 2.2449307428394e-07 3.86467400281737e-06 2.42215363351244e-06 6.72312070453776e-06 3.66790661158252e-06 2.79186833148122e-05 -1.71891614743198e-05 -1.09413478197335e-05 1.2145722500536e-05 -1.23764978501569e-05 2.2449307428394e-07 -1.71891614743198e-05 3.11975207147684e-05 1.81846575953482e-05 2.70356935821912e-05 -1.2147135085593e-05 3.86467400281737e-06 -1.09413478197335e-05 1.81846575953482e-05 4.99583387347044e-05 1402 1402 0 0 0 1408 1488 0 0 0 0 0 0 0 0 0 0 0 1076 0 0 0 0 0 3005 +1301 1302 0.999972208614309 -0.000286853043944542 -0.00744981304136954 -0.00795042493490503 0.00031325701471615 0.999993673352798 0.0035433211003436 0.0033800474595289 0.0074487494965874 -0.00354555633273381 0.999965972001662 0.0110981744542219 4.71623005264281e-05 8.27840737821667e-06 -2.21204224170091e-07 1.48924232970574e-05 -5.75969088612434e-06 -6.1146412561019e-06 8.27840737821667e-06 4.42726385500208e-05 -9.30122718891701e-06 9.97777423739281e-06 -7.93266289813231e-06 2.70269214078124e-06 -2.21204224170091e-07 -9.30122718891701e-06 2.01353198475494e-05 -1.47351523585565e-06 3.21704041637024e-06 -1.36759744061789e-06 1.48924232970574e-05 9.97777423739281e-06 -1.47351523585565e-06 3.16271872550796e-05 -1.43791686796973e-05 1.081005339646e-07 -5.75969088612434e-06 -7.93266289813231e-06 3.21704041637024e-06 -1.43791686796973e-05 4.23390139059331e-05 6.69648267617683e-06 -6.1146412561019e-06 2.70269214078124e-06 -1.36759744061789e-06 1.081005339646e-07 6.69648267617683e-06 3.97358399592148e-05 1370 1372 0 0 0 1373 1433 0 0 0 0 0 0 0 0 0 0 0 1001 0 31 49 0 0 2771 +1302 1303 0.999999070627063 -0.000650614905501405 0.00119810068654889 -0.00426216440165943 0.000652020958781857 0.999999098821611 -0.00117355214440365 0.00099325993347868 -0.00119733607632891 0.00117433224049441 0.999998593664066 0.000582019042047877 5.84171470817641e-05 1.96284476196104e-05 -3.62576728206252e-06 1.07473051560757e-05 -1.32838909817395e-05 -8.42925393023984e-06 1.96284476196104e-05 5.73272749751651e-05 -7.82418357115443e-06 8.01454441848314e-06 -1.10604948868822e-05 3.72000029276645e-06 -3.62576728206252e-06 -7.82418357115443e-06 2.1173923059466e-05 2.54541975536683e-06 2.6638848214285e-06 4.17911013735889e-07 1.07473051560757e-05 8.01454441848314e-06 2.54541975536683e-06 2.61513317828897e-05 -8.02582504304503e-06 -4.25383357809936e-06 -1.32838909817395e-05 -1.10604948868822e-05 2.6638848214285e-06 -8.02582504304503e-06 3.81981648835315e-05 4.68873610478946e-06 -8.42925393023984e-06 3.72000029276645e-06 4.17911013735889e-07 -4.25383357809936e-06 4.68873610478946e-06 4.21699770711603e-05 1406 1407 0 0 0 1406 1476 0 0 0 0 0 0 0 0 0 0 0 998 0 0 8 0 0 3002 +1300 1301 0.999995071410033 0.000797575699166097 -0.00303661466899714 -0.00138141611775983 -0.000790058518135948 0.999996622835564 0.002475908924866 -0.000142710776155699 0.0030385791386419 -0.00247349761884058 0.999992324393716 -0.00290938668210325 4.70782736872929e-05 3.46878564416172e-06 -5.99639648784741e-08 1.38086695598343e-05 -8.2701845563331e-06 7.12077155958152e-07 3.46878564416172e-06 3.98792327766184e-05 -1.22128947559526e-05 9.09670594918901e-06 -1.07054264103703e-05 7.54564640222652e-06 -5.99639648784741e-08 -1.22128947559526e-05 1.96892361192803e-05 -7.09922526917843e-08 3.29302489920348e-06 -7.77350199304321e-07 1.38086695598343e-05 9.09670594918901e-06 -7.09922526917843e-08 2.94690810081908e-05 -1.19711328135787e-05 -4.95915460951812e-06 -8.2701845563331e-06 -1.07054264103703e-05 3.29302489920348e-06 -1.19711328135787e-05 3.69130722060147e-05 7.77923625632138e-06 7.12077155958152e-07 7.54564640222652e-06 -7.77350199304321e-07 -4.95915460951812e-06 7.77923625632138e-06 3.35662202102279e-05 1411 1411 0 0 0 1417 1492 0 0 0 0 0 0 0 0 0 0 0 1094 0 0 0 0 0 3092 +1308 1309 0.999997450590776 0.00141189771535474 -0.00176220225567567 -0.00357000681591296 -0.0014057732748565 0.999992984969504 0.00347186020467006 -0.000360483295323536 0.00176709180526411 -0.00346937409664171 0.999992420386239 0.00612426531803316 3.40017194787212e-05 -8.22569073859262e-06 3.02900050793883e-06 4.13587059960648e-06 -2.26898935495338e-06 -6.59685579860031e-06 -8.22569073859262e-06 3.20818165351313e-05 -7.65250975765738e-06 2.83102431389471e-06 -3.81731938809751e-06 4.8877183937767e-06 3.02900050793883e-06 -7.65250975765738e-06 2.1225447106911e-05 1.94288555958741e-06 6.462350902766e-06 3.46215890354664e-06 4.13587059960648e-06 2.83102431389471e-06 1.94288555958741e-06 2.31540008944244e-05 -9.71690585544471e-06 -1.74546066693676e-06 -2.26898935495338e-06 -3.81731938809751e-06 6.462350902766e-06 -9.71690585544471e-06 4.39791662909817e-05 1.02314081854836e-05 -6.59685579860031e-06 4.8877183937767e-06 3.46215890354664e-06 -1.74546066693676e-06 1.02314081854836e-05 3.24429238594628e-05 1387 1387 0 0 0 1394 1451 0 0 0 0 0 0 0 0 0 0 0 1001 0 15 30 0 0 2771 +1309 1310 0.99999987020877 -0.000306511821562115 -0.000406980277685255 -0.0015749047609232 0.000305618091092616 0.99999754592139 -0.00219425358157607 0.000389017469144761 0.000407651843585919 0.00219412891624562 0.999997509806036 -0.00239102511185008 3.55803413856672e-05 -2.21054256041714e-05 7.09251136059947e-06 1.57081543582772e-06 1.26157153674258e-06 6.51360654959551e-08 -2.21054256041714e-05 2.90081172456957e-05 -1.11472743205513e-05 2.10406234564005e-07 -5.89833374037303e-06 3.92240913611236e-06 7.09251136059947e-06 -1.11472743205513e-05 1.81408459766749e-05 1.07609663096141e-06 1.82939042954261e-06 1.83731098321695e-06 1.57081543582772e-06 2.10406234564005e-07 1.07609663096141e-06 2.32134701249775e-05 -1.06198422131889e-05 -5.60448003542267e-06 1.26157153674258e-06 -5.89833374037303e-06 1.82939042954261e-06 -1.06198422131889e-05 3.36869508540942e-05 6.63244705754428e-06 6.51360654959551e-08 3.92240913611236e-06 1.83731098321695e-06 -5.60448003542267e-06 6.63244705754428e-06 3.33472149787517e-05 1407 1408 0 0 0 1415 1486 0 0 0 0 0 0 0 0 0 0 0 1102 0 0 6 0 0 2903 +1303 1304 0.999999315355986 -0.000410927804118715 -0.00109563949342252 -0.000104019268663623 0.000411423420839594 0.999999813137949 0.000452166823195568 0.000726229322109465 0.00109545348076933 -0.00045261728537065 0.999999297559386 -0.000303988281276593 2.81161488069887e-05 -1.79779734514554e-05 1.50915355607066e-06 -6.22865283418277e-07 -4.23841234838377e-06 -2.79092368477269e-06 -1.79779734514554e-05 2.71697618343143e-05 -4.26837645726796e-06 9.37791672838049e-07 1.83474207339232e-06 6.23325187834001e-06 1.50915355607066e-06 -4.26837645726796e-06 1.67927338201016e-05 1.14890792423913e-06 5.45983750444034e-07 7.27588865001841e-07 -6.22865283418277e-07 9.37791672838049e-07 1.14890792423913e-06 2.03567596149485e-05 -4.36070718999395e-06 -4.46924198337266e-06 -4.23841234838377e-06 1.83474207339232e-06 5.45983750444034e-07 -4.36070718999395e-06 3.08413582193221e-05 -8.78879775960734e-07 -2.79092368477269e-06 6.23325187834001e-06 7.27588865001841e-07 -4.46924198337266e-06 -8.78879775960734e-07 2.82699662543176e-05 1407 1412 0 0 0 1409 1488 0 0 0 0 0 0 0 0 0 0 0 1095 0 0 0 0 0 2961 +1304 1305 0.999998051543806 0.000598694501685084 -0.00188108306194117 -0.00245306670924718 -0.000593253881565623 0.999995643604362 0.00289150862531972 -0.00180527354849708 0.00188280599751468 -0.00289038703151378 0.999994050334493 -0.00203943521336391 3.55032363505187e-05 -1.47624811591415e-05 6.01287832124949e-06 1.61991227098874e-06 -4.64936404951198e-06 2.91579243024024e-06 -1.47624811591415e-05 2.61290971122293e-05 -7.76519640841417e-06 -5.38899591067548e-06 -1.29040799806187e-06 6.88699796633988e-06 6.01287832124949e-06 -7.76519640841417e-06 2.18619040888564e-05 3.09193027918171e-07 3.00818280384448e-06 3.85776344343767e-06 1.61991227098874e-06 -5.38899591067548e-06 3.09193027918171e-07 2.3853831317474e-05 -1.91978919355498e-06 -3.23702517673614e-06 -4.64936404951198e-06 -1.29040799806187e-06 3.00818280384448e-06 -1.91978919355498e-06 3.90000625449194e-05 7.15636210577441e-06 2.91579243024024e-06 6.88699796633988e-06 3.85776344343767e-06 -3.23702517673614e-06 7.15636210577441e-06 3.69320335547108e-05 1290 1290 0 0 0 1296 1357 0 0 0 0 0 0 0 0 0 0 0 1005 0 1 2 0 0 2987 +1310 1311 0.999975810469201 -0.00116075160111013 -0.0068579247725199 -0.0115286696052909 0.00118692880197627 0.999992021366002 0.00381423706079857 0.00013609023866858 0.00685344267387282 -0.00382228466462801 0.99996920975771 0.00181722593254129 6.67252856948482e-05 -1.33910657012485e-05 4.50987254148159e-06 1.02245434430188e-05 -9.1935649828624e-06 -8.04492887978567e-06 -1.33910657012485e-05 5.24235098958684e-05 -7.18606847934424e-06 5.51804571000545e-06 -1.01280636054151e-05 -7.66917933593622e-06 4.50987254148159e-06 -7.18606847934424e-06 1.86295262545875e-05 8.80694428480264e-07 9.80801766605981e-07 8.76346465026864e-08 1.02245434430188e-05 5.51804571000545e-06 8.80694428480264e-07 3.40592162196615e-05 -1.80543052042225e-05 -7.77332001861294e-06 -9.1935649828624e-06 -1.01280636054151e-05 9.80801766605981e-07 -1.80543052042225e-05 4.21248761942111e-05 9.1623185800025e-06 -8.04492887978567e-06 -7.66917933593622e-06 8.76346465026864e-08 -7.77332001861294e-06 9.1623185800025e-06 6.26846197588141e-05 1366 1366 0 0 0 1379 1436 0 0 0 0 0 0 0 0 0 0 0 1000 0 26 44 0 0 3011 +1305 1306 0.999987668284659 -0.00110431573854723 -0.00484187622315947 -0.00475736425309675 0.00111654597051801 0.999996191485491 0.00252395317083324 0.00463079932239584 0.00483907054159372 -0.00252932822354792 0.999985092836404 0.00363997685525232 3.54590574187486e-05 -1.37893310249731e-05 1.12573072531259e-07 2.06984942078759e-06 -5.66908524422533e-06 -2.63242989827015e-06 -1.37893310249731e-05 2.73915906575072e-05 -7.3910941144429e-06 -2.43018524844455e-06 -5.90010734246929e-06 4.37589513386584e-06 1.12573072531259e-07 -7.3910941144429e-06 2.07768275496519e-05 1.99951138043904e-06 2.85456220751487e-06 -1.23539242126674e-06 2.06984942078759e-06 -2.43018524844455e-06 1.99951138043904e-06 2.71715159938804e-05 -7.52992112808024e-06 2.96673455562477e-07 -5.66908524422533e-06 -5.90010734246929e-06 2.85456220751487e-06 -7.52992112808024e-06 3.74676805616579e-05 7.12310148136808e-06 -2.63242989827015e-06 4.37589513386584e-06 -1.23539242126674e-06 2.96673455562477e-07 7.12310148136808e-06 3.79677371496828e-05 1397 1400 0 0 0 1398 1462 0 0 0 0 0 0 0 0 0 0 0 1103 0 10 26 0 0 2983 +1312 1313 0.999998825912761 -0.000567268731954877 0.0014235094962491 0.000314003357807838 0.000563401634540963 0.999996154240662 0.00271552618914515 0.00496023164301243 -0.00142504445487207 -0.00271472099330353 0.999995299758069 -0.00270055301066839 3.68677130117927e-05 -1.84669288567007e-05 9.72034995676897e-06 4.52668551970449e-07 1.68152624113053e-06 -8.42310649966627e-08 -1.84669288567007e-05 4.47089377959696e-05 -8.44895176415184e-06 -8.57238108854009e-08 -1.25960348714682e-06 4.37192801782549e-06 9.72034995676897e-06 -8.44895176415184e-06 1.95820618533808e-05 9.3328207623768e-07 3.61492424985834e-06 -9.58620588756122e-07 4.52668551970449e-07 -8.57238108854009e-08 9.3328207623768e-07 2.63857658383124e-05 -1.06106911286893e-05 -6.22830013842207e-06 1.68152624113053e-06 -1.25960348714682e-06 3.61492424985834e-06 -1.06106911286893e-05 3.74335065970235e-05 3.43202871321827e-06 -8.42310649966627e-08 4.37192801782549e-06 -9.58620588756122e-07 -6.22830013842207e-06 3.43202871321827e-06 4.45883330919725e-05 1407 1417 0 0 0 1407 1488 0 0 0 0 0 0 0 0 0 0 0 1111 0 0 0 0 0 3062 +1306 1307 0.999991651049782 -0.000769995724856131 -0.00401309572716343 -0.00565116382439942 0.000779688771699224 0.999996781495877 0.00241434945824642 0.00267367430106593 0.00401122377223713 -0.00241745826664121 0.999989032929551 0.00326166959121279 3.56638875359124e-05 -1.20251290164624e-05 -2.76175401386959e-07 2.81400465867395e-06 -5.80169964132898e-06 -4.29752471572589e-06 -1.20251290164624e-05 3.24359926776777e-05 -8.50782747890998e-06 4.91933519866422e-06 -7.79426478944261e-06 7.66178307955344e-06 -2.76175401386959e-07 -8.50782747890998e-06 2.17139259525533e-05 7.38805917608582e-07 3.78904333709501e-06 -6.25176123478539e-08 2.81400465867395e-06 4.91933519866422e-06 7.38805917608582e-07 2.47923864812868e-05 -8.57744739866576e-06 -1.65905816787275e-06 -5.80169964132898e-06 -7.79426478944261e-06 3.78904333709501e-06 -8.57744739866576e-06 3.85217840854397e-05 4.05600978984325e-06 -4.29752471572589e-06 7.66178307955344e-06 -6.25176123478539e-08 -1.65905816787275e-06 4.05600978984325e-06 3.42884696447618e-05 1412 1412 0 0 0 1418 1487 0 0 0 0 0 0 0 0 0 0 0 1102 0 0 4 0 0 2903 +1307 1308 0.999996086808198 6.00900221470785e-05 0.0027969192839582 -0.00311621171081878 -6.10245205427402e-05 0.999999942349013 0.000334032899918053 0.00194799438290314 -0.00279689905066869 -0.000334202273441548 0.999996032824401 -0.00742332535542151 2.88321522224661e-05 -1.37058092858877e-05 3.26019956716271e-06 2.3867602584382e-06 -2.19530025284347e-06 -2.58699007303003e-06 -1.37058092858877e-05 2.81980171872912e-05 -9.71660049639451e-06 2.62894140144369e-06 -6.14330562464358e-06 5.65073999527018e-06 3.26019956716271e-06 -9.71660049639451e-06 1.94358954875596e-05 7.36897501926054e-07 3.96006446819818e-06 -1.59224305849803e-06 2.3867602584382e-06 2.62894140144369e-06 7.36897501926054e-07 2.45071760676939e-05 -1.51168391461768e-05 -1.74779866709461e-06 -2.19530025284347e-06 -6.14330562464358e-06 3.96006446819818e-06 -1.51168391461768e-05 3.9435376032817e-05 3.73098795021007e-06 -2.58699007303003e-06 5.65073999527018e-06 -1.59224305849803e-06 -1.74779866709461e-06 3.73098795021007e-06 3.60566701789094e-05 1249 1253 0 0 0 1251 1313 0 0 0 0 0 0 0 0 0 0 0 1106 0 26 27 0 0 3115 +1313 1314 0.999998922144886 6.37543189051849e-05 -0.00146684847635488 -0.00120033584389446 -5.71057588696411e-05 0.999989728157679 0.00453214276738866 0.00247134950745412 0.00146712235279394 -0.00453205411690001 0.999988653954375 0.00181625518200647 3.9906020275384e-05 -1.93965917977754e-05 -1.95540356504061e-06 -2.51793723864856e-06 -2.35758127902379e-06 4.61027315510789e-07 -1.93965917977754e-05 5.00031883218789e-05 -6.28920503508078e-06 8.54824795294462e-06 -6.76468890300367e-06 4.00680067359028e-07 -1.95540356504061e-06 -6.28920503508078e-06 2.12939660328254e-05 -2.03182898610282e-06 4.42651359305139e-06 -2.03018560042864e-07 -2.51793723864856e-06 8.54824795294462e-06 -2.03182898610282e-06 2.73908443554741e-05 -1.60979135201863e-05 -2.9545603803481e-06 -2.35758127902379e-06 -6.76468890300367e-06 4.42651359305139e-06 -1.60979135201863e-05 4.23310544426864e-05 6.97823654061597e-07 4.61027315510789e-07 4.00680067359028e-07 -2.03018560042864e-07 -2.9545603803481e-06 6.97823654061597e-07 4.22198720639953e-05 1393 1396 0 0 0 1405 1489 0 0 0 0 0 0 0 0 0 0 0 1109 0 0 0 0 0 2729 +1311 1312 0.999994937829215 -0.000345942496531083 0.00316301118143037 0.00526555369935411 0.00035486330017583 0.999995960191909 -0.00282022550529797 0.00212810242284996 -0.00316202276762013 0.00282133366542114 0.99999102080387 -0.00667430600462167 3.50477357234567e-05 -2.42676322356838e-05 4.00426833033666e-06 -2.63687397701257e-06 -1.11494200144764e-06 5.48614425850451e-06 -2.42676322356838e-05 4.31017896319206e-05 -6.32492619174317e-06 8.20107251535014e-06 5.41844942189143e-06 -6.24646566828609e-06 4.00426833033666e-06 -6.32492619174317e-06 1.8050818686552e-05 3.87988944080284e-07 -2.38356623728888e-08 2.2824788296154e-06 -2.63687397701257e-06 8.20107251535014e-06 3.87988944080284e-07 3.17512126567758e-05 -7.16599151996134e-06 -6.47270006715031e-06 -1.11494200144764e-06 5.41844942189143e-06 -2.38356623728888e-08 -7.16599151996134e-06 3.58380401817271e-05 3.44951544723216e-06 5.48614425850451e-06 -6.24646566828609e-06 2.2824788296154e-06 -6.47270006715031e-06 3.44951544723216e-06 4.31671033475616e-05 1400 1410 0 0 0 1404 1486 0 0 0 0 0 0 0 0 0 0 0 1101 0 0 0 0 0 2907 +1314 1315 0.999998183918475 0.000844687750592471 0.00170840930559844 -0.00314582094550669 -0.000851583647299113 0.99999147757048 0.0040397514404293 0.000837672414491546 -0.00170498241724337 -0.00404119895733888 0.999990380826708 -0.00787305734852512 3.2394066532016e-05 -1.09061107081749e-05 5.01063597095212e-06 5.54339524161988e-06 -4.70075245515583e-06 -8.06108436684639e-06 -1.09061107081749e-05 2.60390374576197e-05 -7.49788382752061e-06 2.07883982928609e-06 -4.34006895128179e-06 6.93978674945585e-06 5.01063597095212e-06 -7.49788382752061e-06 1.68993183461452e-05 2.83758802995446e-06 -1.68700007265486e-06 -8.83732253675347e-08 5.54339524161988e-06 2.07883982928609e-06 2.83758802995446e-06 2.5329053657773e-05 -1.77578359744511e-05 -7.53079154374998e-06 -4.70075245515583e-06 -4.34006895128179e-06 -1.68700007265486e-06 -1.77578359744511e-05 3.23004807331202e-05 9.9132566841596e-06 -8.06108436684639e-06 6.93978674945585e-06 -8.83732253675347e-08 -7.53079154374998e-06 9.9132566841596e-06 3.3307185529204e-05 1289 1289 0 0 0 1293 1355 0 0 0 0 0 0 0 0 0 0 0 1103 0 0 0 0 0 3067 +1317 1318 0.999999080791786 0.00120700539503247 -0.000617700218745578 -0.00505217193304541 -0.00120652633528658 0.999998971570781 0.000775339656138161 -0.00531163155591061 0.000618635422632566 -0.000774593671858351 0.999999508647308 -0.0018350271717548 2.79826199755921e-05 -1.67636240775577e-05 4.62451799597011e-06 -3.67405705098073e-07 2.4072112292993e-06 -1.31482867472978e-06 -1.67636240775577e-05 2.74927255200314e-05 -6.07741624054522e-06 7.70401528247563e-07 -4.99519792075324e-06 7.86264865136448e-07 4.62451799597011e-06 -6.07741624054522e-06 1.73785461205296e-05 2.89660426766653e-06 3.79726048986555e-06 -1.38835326590056e-06 -3.67405705098073e-07 7.70401528247563e-07 2.89660426766653e-06 2.20184376770358e-05 -2.06658810772139e-06 2.3635190840198e-07 2.4072112292993e-06 -4.99519792075324e-06 3.79726048986555e-06 -2.06658810772139e-06 4.14647477814054e-05 2.32079114968102e-06 -1.31482867472978e-06 7.86264865136448e-07 -1.38835326590056e-06 2.3635190840198e-07 2.32079114968102e-06 3.16532569948102e-05 1402 1402 0 0 0 1419 1478 0 0 0 0 0 0 0 0 0 0 0 1111 0 0 5 0 0 3117 +0 28 0.999962709671433 0.000281484244894508 0.00863134017314906 0.00541200037908999 -0.000233932023026647 0.999984793761389 -0.00550976603855923 -0.00409174534903908 -0.00863275983526376 0.00550754143070519 0.999947569848047 -0.00138975072943593 3.50961549708318e-05 -2.62829250205551e-06 4.09371942638621e-06 3.93594121275405e-07 -2.5251077802325e-06 6.05833535207915e-06 -2.62829250205551e-06 8.87762006019819e-05 -3.01285347235825e-07 2.3819834223696e-05 2.4077537303636e-06 -2.8807009704121e-05 4.09371942638621e-06 -3.01285347235825e-07 1.2678433837322e-05 2.52039000871903e-06 2.89322030498216e-06 -2.30756275331451e-07 3.93594121275405e-07 2.3819834223696e-05 2.52039000871903e-06 4.66898437442615e-05 1.7207050329785e-06 -9.31490144102855e-06 -2.5251077802325e-06 2.4077537303636e-06 2.89322030498216e-06 1.7207050329785e-06 2.20150738947926e-05 -2.64947964406422e-06 6.05833535207915e-06 -2.8807009704121e-05 -2.30756275331451e-07 -9.31490144102855e-06 -2.64947964406422e-06 4.44626323177983e-05 2693 2710 0 0 15 2693 2711 0 0 18 0 0 0 0 0 0 0 0 79 0 14 21 0 0 2768 +1315 1316 0.999997221087052 -0.000550857370753326 -0.00229224220583001 -0.00115090243924041 0.000557751842643822 0.999995319841997 0.00300818998475539 0.00362182584248348 0.00229057439414858 -0.00300946012757138 0.999992848183768 0.00500425931554319 3.89325232200818e-05 -1.06213938821946e-05 5.88504621557347e-06 2.61205938063566e-06 6.85982057493437e-07 -2.28609677066964e-06 -1.06213938821946e-05 3.23037401940065e-05 -8.91701497396992e-06 3.96191738796492e-06 -3.92037635882235e-06 5.5968189192347e-06 5.88504621557347e-06 -8.91701497396992e-06 1.77054655043216e-05 3.03338451413919e-06 1.9405345136148e-06 -3.81956488395771e-07 2.61205938063566e-06 3.96191738796492e-06 3.03338451413919e-06 2.03833898844061e-05 -1.16919728167938e-05 -4.31413951477955e-06 6.85982057493437e-07 -3.92037635882235e-06 1.9405345136148e-06 -1.16919728167938e-05 3.44330953551403e-05 8.26711565259313e-06 -2.28609677066964e-06 5.5968189192347e-06 -3.81956488395771e-07 -4.31413951477955e-06 8.26711565259313e-06 3.2942451611271e-05 1306 1310 0 0 0 1306 1371 0 0 0 0 0 0 0 0 0 0 0 1091 0 0 0 0 0 3091 +0 32 0.999978944406228 0.00103581800054148 0.00640607721429434 0.00204773334470571 -0.00103831988594612 0.999999385970145 0.000387235261627893 0.000906406895145506 -0.00640567217551723 -0.000393878665522038 0.99997940589973 -0.00239598224586395 3.42334818425928e-05 -3.75673212247456e-06 7.51319891877177e-06 2.42594154122579e-06 -7.59842971017324e-08 9.39200423541129e-06 -3.75673212247456e-06 4.73805658420735e-05 -1.62866612934601e-06 4.28919571300521e-06 -8.09952308371556e-07 1.88067773448948e-06 7.51319891877177e-06 -1.62866612934601e-06 1.7041987212693e-05 -1.87757699936471e-06 2.43154138947148e-06 5.16038505176103e-06 2.42594154122579e-06 4.28919571300521e-06 -1.87757699936471e-06 5.30088602051748e-05 4.45529587302476e-06 3.56247625905625e-06 -7.59842971017324e-08 -8.09952308371556e-07 2.43154138947148e-06 4.45529587302476e-06 2.01288292848515e-05 -2.76861487122776e-06 9.39200423541129e-06 1.88067773448948e-06 5.16038505176103e-06 3.56247625905625e-06 -2.76861487122776e-06 4.09376018299784e-05 2939 2939 0 0 7 2940 2952 0 0 10 0 0 0 0 0 0 0 0 56 0 9 12 0 0 3076 +1316 1317 0.99999966217069 0.000546508588960026 -0.000613992562996994 -1.83626228856416e-05 -0.000546583677086846 0.999999843164809 -0.000122133705083973 -0.000964425410192814 0.000613925719582523 0.000122469262136415 0.999999804048226 0.00203874907670554 5.22154953244771e-05 -1.92661101919338e-05 -4.01847936922774e-07 -3.47131017755602e-06 -4.31043794516213e-06 1.18908259560227e-05 -1.92661101919338e-05 4.09971372499144e-05 -3.29399385541463e-06 1.43286444197108e-06 -1.59552853322477e-06 4.60563267762721e-06 -4.01847936922774e-07 -3.29399385541463e-06 1.902394299714e-05 1.18643318981621e-06 -2.5446182888768e-07 -4.29116851521365e-07 -3.47131017755602e-06 1.43286444197108e-06 1.18643318981621e-06 2.21288681949118e-05 -6.3012832854079e-06 -5.03968060711841e-06 -4.31043794516213e-06 -1.59552853322477e-06 -2.5446182888768e-07 -6.3012832854079e-06 3.41667664591445e-05 -4.15225713901601e-06 1.18908259560227e-05 4.60563267762721e-06 -4.29116851521365e-07 -5.03968060711841e-06 -4.15225713901601e-06 4.91417818284709e-05 1397 1398 0 0 0 1402 1474 0 0 0 0 0 0 0 0 0 0 0 1008 0 0 1 0 0 3178 +0 26 0.999992573786588 -0.000179578461602398 0.00384969131892938 -0.000644768534550749 0.000184897522450996 0.999999028809395 -0.00138137365427293 0.000525798030915958 -0.00384943951518961 0.00138207519428444 0.999991635806808 -0.000499181790934055 2.75279426947067e-05 -3.17861150717876e-06 5.2049465404072e-06 3.09393717042198e-06 1.2851052017817e-06 -2.85517131583197e-07 -3.17861150717876e-06 2.73243924112469e-05 -2.01068345166249e-06 5.25055788443361e-07 1.44069159746725e-06 -1.60626830385047e-06 5.2049465404072e-06 -2.01068345166249e-06 1.28951984785767e-05 -2.16219016543161e-07 3.23882361468261e-06 1.28734207592444e-06 3.09393717042198e-06 5.25055788443361e-07 -2.16219016543161e-07 3.69667757857184e-05 2.88816166509101e-06 2.41912628507535e-06 1.2851052017817e-06 1.44069159746725e-06 3.23882361468261e-06 2.88816166509101e-06 1.96528836034937e-05 1.70878316235256e-07 -2.85517131583197e-07 -1.60626830385047e-06 1.28734207592444e-06 2.41912628507535e-06 1.70878316235256e-07 2.78898886835291e-05 3081 3098 0 0 11 3082 3100 0 0 13 0 0 0 0 0 0 0 0 64 0 18 25 0 0 3089 +0 44 0.999949064184902 -0.000342597815519345 -0.010087202906405 -0.0310880717689038 0.000553585330080967 0.999780978704442 0.0209209981614448 0.00229195148585305 0.0100778261058872 -0.0209255166609013 0.999730243702497 -0.0214227556496886 8.07832128632329e-05 -5.6523014168472e-06 4.76008435589807e-06 2.85213833786024e-05 -1.99637562662287e-05 4.68742950132877e-05 -5.6523014168472e-06 0.000128723500521101 -4.56106035270485e-06 4.57087048298261e-05 7.63657567338152e-06 -2.0934089610328e-05 4.76008435589807e-06 -4.56106035270485e-06 1.84495256097858e-05 8.19537392645081e-07 -2.00772739140684e-06 2.58501799091568e-06 2.85213833786024e-05 4.57087048298261e-05 8.19537392645081e-07 0.000128273833176474 -6.17628536986247e-06 -3.16385721927825e-06 -1.99637562662287e-05 7.63657567338152e-06 -2.00772739140684e-06 -6.17628536986247e-06 4.8577410638185e-05 -9.58055397992479e-06 4.68742950132877e-05 -2.0934089610328e-05 2.58501799091568e-06 -3.16385721927825e-06 -9.58055397992479e-06 9.29962544772174e-05 2537 2537 0 0 1 2539 2539 0 0 2 0 0 0 0 0 0 0 0 27 0 46 49 0 0 2348 +0 27 0.999999519396163 -0.000281107482726404 0.00093924758544639 -0.00163247932657306 0.000282360287127943 0.999999070395201 -0.00133397203930086 0.000203365015450325 -0.000938871722795332 0.00133423660440669 0.9999986691654 0.00408811971186972 2.79326772419218e-05 -7.46328691498083e-06 7.92632420707732e-06 -1.43179505778e-07 1.44207225936818e-06 5.11344324265039e-06 -7.46328691498083e-06 1.99777679804128e-05 -6.96208163413587e-06 1.1074708995313e-06 -3.15614485017025e-06 6.8951450815798e-06 7.92632420707732e-06 -6.96208163413587e-06 1.54772683280372e-05 -2.30651798503036e-06 3.81672425459648e-06 3.65119455241143e-06 -1.43179505778e-07 1.1074708995313e-06 -2.30651798503036e-06 3.8216273327635e-05 6.90742468190757e-06 1.52834753555163e-06 1.44207225936818e-06 -3.15614485017025e-06 3.81672425459648e-06 6.90742468190757e-06 1.67046449792226e-05 -6.73551363963749e-07 5.11344324265039e-06 6.8951450815798e-06 3.65119455241143e-06 1.52834753555163e-06 -6.73551363963749e-07 2.87013011786408e-05 3112 3112 0 0 8 3112 3126 0 0 11 0 0 0 0 0 0 0 0 69 0 10 13 0 0 3084 +0 47 0.999994535470778 0.000598200760931186 -0.00325133579204224 -0.00892392835383816 -0.000550918130802732 0.999894369149231 0.0145240157282275 0.00660210043927626 0.00325968062793679 -0.014522145141482 0.999889234756877 -0.0203652116778449 4.7287174875023e-05 -9.18977060503489e-07 1.67318029853535e-06 6.86731927343239e-06 -5.2791035403537e-06 4.00414007995336e-05 -9.18977060503489e-07 3.15832684494218e-05 -6.59297193096754e-06 -5.40855078384685e-08 -9.7535159849071e-07 2.07232382811525e-05 1.67318029853535e-06 -6.59297193096754e-06 1.80476298100336e-05 -4.91205532232438e-06 -3.57443906702876e-07 4.646304773194e-07 6.86731927343239e-06 -5.40855078384685e-08 -4.91205532232438e-06 6.93201706839543e-05 8.02488080738728e-06 -2.90444317967352e-06 -5.2791035403537e-06 -9.7535159849071e-07 -3.57443906702876e-07 8.02488080738728e-06 2.77506665998627e-05 -1.00407437935062e-05 4.00414007995336e-05 2.07232382811525e-05 4.646304773194e-07 -2.90444317967352e-06 -1.00407437935062e-05 8.9394967037121e-05 2917 2934 0 0 11 2918 2936 0 0 13 0 0 0 0 0 0 0 0 58 0 22 30 0 0 3035 +0 49 0.999995183908203 7.08873359868461e-05 0.0031027625408838 -0.00504019416302258 -0.000126782987831639 0.999837648963537 0.0180183140482386 0.00776881103003005 -0.00310098153388754 -0.0180186206478896 0.999832842640946 -0.0184496724702992 8.27480853016079e-05 -2.89040512345827e-06 6.50071218023079e-06 1.83837436071966e-06 -1.57256928274874e-05 4.26116129968575e-05 -2.89040512345827e-06 4.33285184270453e-05 -5.18893699536166e-06 3.97324687202589e-06 -3.57952340311155e-06 9.75392838136025e-06 6.50071218023079e-06 -5.18893699536166e-06 1.80138133680857e-05 -3.15144758809256e-06 -1.41727061117355e-06 1.44436090908458e-06 1.83837436071966e-06 3.97324687202589e-06 -3.15144758809256e-06 6.74569619978527e-05 3.92969910093208e-06 3.09940433904652e-06 -1.57256928274874e-05 -3.57952340311155e-06 -1.41727061117355e-06 3.92969910093208e-06 3.98683947382559e-05 -1.90501898312385e-05 4.26116129968575e-05 9.75392838136025e-06 1.44436090908458e-06 3.09940433904652e-06 -1.90501898312385e-05 8.46387312716197e-05 2932 2941 0 0 6 2937 2954 0 0 9 0 0 0 0 0 0 0 0 64 0 13 16 0 0 2618 +0 31 0.999999895081875 0.000396465756236771 -0.000229458370795877 -0.00443154414885877 -0.000396760862764473 0.99999909247843 -0.00128748713981116 0.000468277187908994 0.000228947717994926 0.00128757804483159 0.999999144862495 0.00288125583320986 2.51184021844812e-05 -6.51257341038111e-06 4.46755864496246e-06 5.06692671344083e-06 3.39368959180408e-06 -3.1721687429377e-06 -6.51257341038111e-06 1.60067589112323e-05 -7.44526146770461e-06 -2.20247367398103e-06 -1.55961470059379e-06 -1.36027901713682e-06 4.46755864496246e-06 -7.44526146770461e-06 1.22573493480534e-05 1.36450903176036e-07 2.59161979830723e-06 3.0662925379107e-06 5.06692671344083e-06 -2.20247367398103e-06 1.36450903176036e-07 3.75362613132068e-05 3.07086381266503e-06 -3.36369445654792e-06 3.39368959180408e-06 -1.55961470059379e-06 2.59161979830723e-06 3.07086381266503e-06 1.79310314373838e-05 3.22836079983161e-06 -3.1721687429377e-06 -1.36027901713682e-06 3.0662925379107e-06 -3.36369445654792e-06 3.22836079983161e-06 2.34873681441353e-05 3147 3158 0 0 12 3153 3170 0 0 13 0 0 0 0 0 0 0 0 67 0 13 19 0 0 2512 +0 35 0.999956951957931 0.000349789781626192 -0.00927210214098316 -0.022190121718454 -0.000324664052332186 0.999996272022598 0.0027111868544108 0.000635949884942395 0.00927301592025366 -0.00270805982487031 0.999953337705179 -0.00536921117876387 4.06137183656399e-05 2.03386609048396e-06 -5.16701854358678e-08 7.43034391671903e-06 -2.98252127416114e-06 -3.8836745054231e-06 2.03386609048396e-06 0.000105013131389348 -1.64627099765962e-06 4.09698084152637e-05 6.85733982639886e-07 -1.42491167454228e-05 -5.16701854358678e-08 -1.64627099765962e-06 1.65397037039074e-05 -1.43748257095256e-06 1.220946489575e-06 -6.99604782926685e-07 7.43034391671903e-06 4.09698084152637e-05 -1.43748257095256e-06 9.77482918063404e-05 -2.26081275518557e-06 -4.93480884861651e-06 -2.98252127416114e-06 6.85733982639886e-07 1.220946489575e-06 -2.26081275518557e-06 2.86527772099959e-05 2.23284592794102e-06 -3.8836745054231e-06 -1.42491167454228e-05 -6.99604782926685e-07 -4.93480884861651e-06 2.23284592794102e-06 4.35451496806817e-05 2509 2517 0 0 1 2519 2533 0 0 2 0 0 0 0 0 0 0 0 51 0 22 27 0 0 2620 +0 30 0.9999787230154 -0.000208561558453127 -0.00651997074887398 -0.00497641249788495 0.000187034941083002 0.999994530632302 -0.00330207865020776 -0.00202423606283983 0.006520623775426 0.00330078892958629 0.999973292772373 0.001014101122978 2.82191483531236e-05 -1.69561013510539e-06 4.03346806709239e-06 4.43648074982401e-06 -2.85141195869614e-06 -4.24699652567303e-07 -1.69561013510539e-06 3.8653436139919e-05 -1.36542628415973e-06 2.01990649386181e-06 3.9481185168163e-07 -6.96952447391638e-06 4.03346806709239e-06 -1.36542628415973e-06 1.40922145668706e-05 -3.56954493657971e-06 2.09353990936923e-06 1.89917269012421e-06 4.43648074982401e-06 2.01990649386181e-06 -3.56954493657971e-06 4.87980074074604e-05 -2.37322663177678e-06 -2.03843415385261e-06 -2.85141195869614e-06 3.9481185168163e-07 2.09353990936923e-06 -2.37322663177678e-06 2.65041337720816e-05 1.60670172042435e-06 -4.24699652567303e-07 -6.96952447391638e-06 1.89917269012421e-06 -2.03843415385261e-06 1.60670172042435e-06 3.31067100673971e-05 2985 2984 0 0 10 2986 2985 0 0 11 0 0 0 0 0 0 0 0 53 0 32 35 0 0 2777 +0 43 0.999994723006638 0.00010465263735323 -0.00324699964620736 -0.0048169499576446 -6.75244238839326e-05 0.999934643124821 0.0114326252142458 0.00340157019259615 0.00324798388683732 -0.011432345632578 0.999929373542956 -0.0159858789620871 3.88515128177847e-05 -1.33209479289383e-06 8.42356757173712e-06 2.60040990247601e-06 -2.27376634153089e-06 2.82309184070771e-05 -1.33209479289383e-06 2.58339446302971e-05 -7.07646523837528e-06 2.62802050299229e-06 -4.72368887909861e-06 6.48241350814828e-06 8.42356757173712e-06 -7.07646523837528e-06 1.81364302372815e-05 -8.42958644882584e-06 -3.98315060298396e-07 5.48336313455106e-06 2.60040990247601e-06 2.62802050299229e-06 -8.42958644882584e-06 5.46976689871565e-05 1.25950628212187e-05 -2.6065614011914e-06 -2.27376634153089e-06 -4.72368887909861e-06 -3.98315060298396e-07 1.25950628212187e-05 2.61728160938596e-05 -1.28961026658693e-05 2.82309184070771e-05 6.48241350814828e-06 5.48336313455106e-06 -2.6065614011914e-06 -1.28961026658693e-05 6.94268456339596e-05 3025 3042 0 0 16 3026 3045 0 0 19 0 0 0 0 0 0 0 0 18 0 19 26 0 0 3027 +0 29 0.999997107440504 0.000837413723188238 -0.00225473920483709 -0.00092363917303561 -0.00084736011806563 0.999989899273754 -0.00441399267075233 -0.00217059923281028 0.00225102009229708 0.00441589047909473 0.999987716334466 0.00877723929640911 2.90234336817962e-05 1.56243793882431e-06 3.60585709322912e-06 1.26664866288637e-06 -8.43564240984639e-08 -3.68982367193865e-06 1.56243793882431e-06 4.28513131320128e-05 -2.08951127578207e-06 7.83964544378375e-06 -1.11331767817807e-06 -4.49279840463127e-06 3.60585709322912e-06 -2.08951127578207e-06 1.43499882933659e-05 3.79094557831443e-07 2.94387714854544e-06 2.72923899142178e-06 1.26664866288637e-06 7.83964544378375e-06 3.79094557831443e-07 4.72250610989262e-05 -3.49585841319967e-06 -4.18426124917982e-06 -8.43564240984639e-08 -1.11331767817807e-06 2.94387714854544e-06 -3.49585841319967e-06 2.2796292084733e-05 2.47282355132669e-06 -3.68982367193865e-06 -4.49279840463127e-06 2.72923899142178e-06 -4.18426124917982e-06 2.47282355132669e-06 3.22665776193244e-05 2776 2775 0 0 11 2776 2775 0 0 11 0 0 0 0 0 0 0 0 69 0 30 33 0 0 2481 +0 33 0.999997783156171 0.000796978349749481 0.0019489762064813 -0.00359339023488753 -0.000794929263596825 0.999999130781672 -0.00105191414429898 -0.00174380032958049 -0.00194981286519426 0.00105036251414901 0.999997547481182 -0.00247017442846387 3.65852463394237e-05 -1.08276088666919e-05 1.79999129262985e-06 -6.09607060497373e-06 1.25576708124209e-06 9.01584247762413e-06 -1.08276088666919e-05 8.25399415863565e-05 -5.76492887555307e-06 8.55125905111606e-06 7.92208279086834e-06 -2.44184702445643e-05 1.79999129262985e-06 -5.76492887555307e-06 1.75737571741988e-05 -2.73275125794923e-07 4.9114853740094e-07 4.86885555599883e-07 -6.09607060497373e-06 8.55125905111606e-06 -2.73275125794923e-07 5.51869143808279e-05 1.57788085321857e-06 -1.1116562377266e-05 1.25576708124209e-06 7.92208279086834e-06 4.9114853740094e-07 1.57788085321857e-06 2.73833475362747e-05 -2.97003084655177e-06 9.01584247762413e-06 -2.44184702445643e-05 4.86885555599883e-07 -1.1116562377266e-05 -2.97003084655177e-06 4.75204017325429e-05 2589 2590 0 0 5 2594 2605 0 0 9 0 0 0 0 0 0 0 0 67 0 11 14 0 0 3075 +0 50 0.999978417449591 0.00122546106932236 -0.00645467893700132 -0.00394870866917699 -0.00118739238281127 0.999981899458247 0.00589837733671765 0.000474195124490544 0.00646179033561403 -0.00589058579808816 0.999961772401632 -0.0107142532518618 6.91397032155063e-05 1.12200119083024e-05 2.64041426788414e-06 1.29316232692972e-05 -9.35709160480223e-06 4.64151896050529e-05 1.12200119083024e-05 6.56701219501672e-05 -8.67540361835127e-06 2.3882321519697e-05 2.10496665223696e-06 2.91235998936307e-05 2.64041426788414e-06 -8.67540361835127e-06 2.42937093865078e-05 -1.16701825011246e-05 -1.13247294547954e-06 -3.0953428195467e-06 1.29316232692972e-05 2.3882321519697e-05 -1.16701825011246e-05 9.80722477241579e-05 1.29475476952242e-05 2.51101853686227e-05 -9.35709160480223e-06 2.10496665223696e-06 -1.13247294547954e-06 1.29475476952242e-05 3.63322272792515e-05 -1.12752816580761e-05 4.64151896050529e-05 2.91235998936307e-05 -3.0953428195467e-06 2.51101853686227e-05 -1.12752816580761e-05 9.89768002121313e-05 2825 2826 0 0 8 2827 2828 0 0 11 0 0 0 0 0 0 0 0 59 0 31 35 0 0 2715 +0 34 0.999991205193956 0.000616363293213494 0.00414844923198614 -0.00352506134653012 -0.000626878518906964 0.999996593146578 0.00253391368437828 0.00454919565516126 -0.00414687328744445 -0.0025364919728092 0.999988184755405 -0.00957022610080292 4.8750053243334e-05 -4.33479626399755e-06 5.29113163341348e-06 -7.64920085098978e-06 -1.44045017264724e-06 7.74542421287531e-07 -4.33479626399755e-06 3.71959806666423e-05 -3.99137340646342e-06 4.11740012822177e-07 3.66255469969903e-06 -5.39596136279162e-06 5.29113163341348e-06 -3.99137340646342e-06 1.89645178267125e-05 -2.80320710830475e-06 -1.24983181688392e-06 -1.2591966298813e-06 -7.64920085098978e-06 4.11740012822177e-07 -2.80320710830475e-06 6.41592732042231e-05 5.70237049287438e-06 8.15680824520362e-06 -1.44045017264724e-06 3.66255469969903e-06 -1.24983181688392e-06 5.70237049287438e-06 3.06715044879375e-05 1.71081305898461e-06 7.74542421287531e-07 -5.39596136279162e-06 -1.2591966298813e-06 8.15680824520362e-06 1.71081305898461e-06 3.19368271736928e-05 2891 2902 0 0 8 2897 2915 0 0 13 0 0 0 0 0 0 0 0 57 0 12 17 0 0 2694 +0 42 0.999954791991646 -9.33476567426822e-05 -0.00950816802330391 -0.00758499854677876 0.000198829579859448 0.999938445679671 0.0110934809019469 -0.000322480194156536 0.00950654720403634 -0.0110948698928229 0.99989325901434 -0.0156387331450848 6.40457561455284e-05 6.70373316713407e-06 4.80863011677416e-06 9.29932315558189e-06 -8.96709161963988e-06 2.62807541200622e-05 6.70373316713407e-06 4.94052759455e-05 3.64383526278989e-07 7.43668064631013e-06 2.40424572421003e-07 1.21903366517022e-05 4.80863011677416e-06 3.64383526278989e-07 1.55445692112588e-05 -4.56481073105766e-06 2.12341306067633e-06 1.32835193680591e-06 9.29932315558189e-06 7.43668064631013e-06 -4.56481073105766e-06 6.8181752352158e-05 6.50932145279114e-06 1.86378643714791e-06 -8.96709161963988e-06 2.40424572421003e-07 2.12341306067633e-06 6.50932145279114e-06 3.27352420056872e-05 -5.47613471066128e-06 2.62807541200622e-05 1.21903366517022e-05 1.32835193680591e-06 1.86378643714791e-06 -5.47613471066128e-06 8.63772816597185e-05 2955 2972 0 0 14 2958 2977 0 0 19 0 0 0 0 0 0 0 0 56 0 19 26 0 0 2618 +0 45 0.999990423034514 0.000547444720670154 -0.00434213582596737 -0.00545709472467385 -0.000539556275399904 0.999998202451295 0.00181768347188243 -0.00146049831263741 0.00434312310198728 -0.00181532323735702 0.999988920880259 -0.000596593343486548 6.92861036472352e-05 -1.14076217483384e-05 1.6616326386699e-06 9.35361194788159e-06 -5.3190032064803e-06 3.29754583553754e-05 -1.14076217483384e-05 0.000154278577439301 -5.05557782779111e-06 4.70300285310308e-05 7.54506276390883e-06 -8.5417531766225e-06 1.6616326386699e-06 -5.05557782779111e-06 1.88537067857961e-05 -2.79952411908667e-06 -1.11253964314128e-07 6.76473487806469e-08 9.35361194788159e-06 4.70300285310308e-05 -2.79952411908667e-06 9.67116824717337e-05 -1.85748564140004e-06 8.41196344047797e-06 -5.3190032064803e-06 7.54506276390883e-06 -1.11253964314128e-07 -1.85748564140004e-06 4.11865193079217e-05 -1.0115061162012e-05 3.29754583553754e-05 -8.5417531766225e-06 6.76473487806469e-08 8.41196344047797e-06 -1.0115061162012e-05 9.27236719019963e-05 2693 2702 0 0 6 2699 2711 0 0 9 0 0 0 0 0 0 0 0 28 0 18 26 0 0 2177 +0 52 0.999950271210874 0.0037933527662623 -0.0092231003513027 -0.00026486888414334 -0.00363140000228554 0.999840036540994 0.0175132596545112 0.00835971883102752 0.00928805896422446 -0.0174788959746782 0.999804090887902 -0.0246388766523782 5.50245984172981e-05 1.03529098527933e-05 6.91625958837256e-06 7.71332595250375e-06 -1.12844851211985e-05 3.89381506940891e-05 1.03529098527933e-05 5.67054444934246e-05 -1.45106146209488e-06 9.91669731685432e-06 -2.19818999693779e-06 2.2578084414836e-05 6.91625958837256e-06 -1.45106146209488e-06 1.94933720001512e-05 -4.63543292363131e-06 -4.15713561996016e-06 1.74092209872338e-06 7.71332595250375e-06 9.91669731685432e-06 -4.63543292363131e-06 8.79669803012992e-05 7.29801733307139e-06 6.36558350238917e-06 -1.12844851211985e-05 -2.19818999693779e-06 -4.15713561996016e-06 7.29801733307139e-06 3.55166522405528e-05 -1.70126915055698e-05 3.89381506940891e-05 2.2578084414836e-05 1.74092209872338e-06 6.36558350238917e-06 -1.70126915055698e-05 8.93512785027731e-05 2775 2775 0 0 5 2776 2776 0 0 7 0 0 0 0 0 0 0 0 61 0 34 36 0 0 3089 +0 48 0.999988472667411 0.000202436263539803 -0.00479724419411868 -0.0146843232379464 -0.000119642384621423 0.999851154974203 0.0172526398690603 0.00479645665996869 0.00480002270813415 -0.0172518670384075 0.999839653577358 -0.0187936987335523 7.96857148227228e-05 1.74730982507695e-06 5.19389479625082e-06 1.43033185984925e-05 -9.9819416258425e-06 5.7731494194232e-05 1.74730982507695e-06 3.11883588269742e-05 -3.31093489876961e-06 4.33919021097271e-06 -3.05435364216114e-06 6.83613826707406e-06 5.19389479625082e-06 -3.31093489876961e-06 1.52194054643907e-05 -9.82855661696534e-07 2.58817981166022e-06 -3.63702400311322e-07 1.43033185984925e-05 4.33919021097271e-06 -9.82855661696534e-07 5.64210057423823e-05 -3.8323524260559e-07 6.57177811950491e-06 -9.9819416258425e-06 -3.05435364216114e-06 2.58817981166022e-06 -3.8323524260559e-07 2.91028531536819e-05 -1.42757217617177e-05 5.7731494194232e-05 6.83613826707406e-06 -3.63702400311322e-07 6.57177811950491e-06 -1.42757217617177e-05 0.000106140691496065 3085 3084 0 0 3 3087 3087 0 0 6 0 0 0 0 0 0 0 0 45 0 36 40 0 0 2610 +0 46 0.99998022699924 0.00087129632325234 -0.00622787710745117 -0.0261536817955757 -0.000814715604378181 0.999958427313121 0.00908184364292084 0.00635775982856646 0.00623553117484069 -0.009076590118958 0.999939364993088 -0.0191389336873471 5.54038571792225e-05 4.28042161401654e-06 3.20973945199977e-06 7.69577892622888e-06 -7.81021460865601e-06 4.36877779987432e-05 4.28042161401654e-06 4.06281082884226e-05 -3.62080523399677e-06 5.37794456738099e-06 1.14338053844318e-07 1.49284256853066e-05 3.20973945199977e-06 -3.62080523399677e-06 1.60351675683225e-05 -7.81672884111018e-07 1.28406228879624e-06 2.8416461530714e-07 7.69577892622888e-06 5.37794456738099e-06 -7.81672884111018e-07 6.9474111074103e-05 -2.39511015405819e-06 1.20313596192247e-05 -7.81021460865601e-06 1.14338053844318e-07 1.28406228879624e-06 -2.39511015405819e-06 3.32042530674525e-05 -1.45737749361202e-05 4.36877779987432e-05 1.49284256853066e-05 2.8416461530714e-07 1.20313596192247e-05 -1.45737749361202e-05 9.73630569028454e-05 3080 3096 0 0 8 3084 3100 0 0 10 0 0 0 0 0 0 0 0 44 0 35 42 0 0 2582 +0 39 0.999951796618348 -0.000372129932082646 -0.00981152175007541 -0.0147824604359799 0.000478612840216464 0.999940992850545 0.0108527299246031 -0.00160629529214389 0.00980690417449536 -0.0108569027066122 0.9998929704194 -0.0162656111050694 4.80502952216584e-05 1.66634423172394e-06 8.40561546952034e-06 -4.87584495397574e-06 -6.05039333299072e-06 2.3315128404402e-05 1.66634423172394e-06 4.16754994286641e-05 7.44070640652245e-07 2.08205981217346e-06 -7.89822849946608e-06 6.61084475522835e-06 8.40561546952034e-06 7.44070640652245e-07 1.81440904253543e-05 -2.44153394903841e-06 1.90447604552228e-06 2.21509078306173e-06 -4.87584495397574e-06 2.08205981217346e-06 -2.44153394903841e-06 6.36836795369758e-05 7.20911130016917e-06 2.43289368675153e-06 -6.05039333299072e-06 -7.89822849946608e-06 1.90447604552228e-06 7.20911130016917e-06 3.39861437851474e-05 -7.17528292802545e-06 2.3315128404402e-05 6.61084475522835e-06 2.21509078306173e-06 2.43289368675153e-06 -7.17528292802545e-06 6.84105720856069e-05 2971 2987 0 0 2 2982 3004 0 0 5 0 0 0 0 0 0 0 0 61 0 19 23 0 0 3069 +0 37 0.999997788616424 0.00123532979079705 -0.00170197607814153 -0.0062685021856319 -0.00121339488237776 0.999916966008046 0.0128292151795347 0.00515430093200322 0.00171768306797737 -0.0128271216401558 0.999916253750936 -0.0266260972422324 4.10910731295414e-05 1.47713079318635e-06 6.99163193641197e-06 -4.65669939552289e-06 -7.35662325223379e-06 2.24954142895348e-05 1.47713079318635e-06 4.33739515568557e-05 -4.64557489209254e-06 1.22440361025597e-05 1.09568356111034e-06 -7.40790774075681e-06 6.99163193641197e-06 -4.64557489209254e-06 1.88365312326196e-05 -6.20043882012487e-06 1.8034171497442e-06 1.93536566228978e-06 -4.65669939552289e-06 1.22440361025597e-05 -6.20043882012487e-06 7.6092248874925e-05 1.54188131433109e-05 -1.95070125292852e-06 -7.35662325223379e-06 1.09568356111034e-06 1.8034171497442e-06 1.54188131433109e-05 3.56767959171787e-05 -1.76484775287978e-05 2.24954142895348e-05 -7.40790774075681e-06 1.93536566228978e-06 -1.95070125292852e-06 -1.76484775287978e-05 6.74579730395417e-05 2947 2958 0 0 5 2954 2973 0 0 7 0 0 0 0 0 0 0 0 67 0 13 15 0 0 3042 +1 42 0.999999961990619 4.731302855963e-05 -0.000271625176834112 -0.00189214781751258 -4.47357339205715e-05 0.999955057090676 0.00948060111473544 0.00336135031589812 0.000272061525159723 -0.00948058860303203 0.999955021199587 -0.0209007624573862 5.74329071274439e-05 1.14007633436785e-05 6.19671984243602e-06 2.85590391101244e-06 -9.84980736865178e-06 3.77258756268591e-05 1.14007633436785e-05 6.041979677314e-05 3.30596778482471e-06 1.28830131885128e-06 2.46647896892116e-06 1.51838368037029e-05 6.19671984243602e-06 3.30596778482471e-06 1.96250644824663e-05 -4.21771103601941e-06 -8.52392465621592e-07 2.53669759824135e-06 2.85590391101244e-06 1.28830131885128e-06 -4.21771103601941e-06 6.65543821335708e-05 1.03460473361661e-05 3.24146465373702e-06 -9.84980736865178e-06 2.46647896892116e-06 -8.52392465621592e-07 1.03460473361661e-05 3.20667636158577e-05 -1.42360688823208e-05 3.77258756268591e-05 1.51838368037029e-05 2.53669759824135e-06 3.24146465373702e-06 -1.42360688823208e-05 9.77396988807898e-05 2723 2732 0 0 11 2723 2732 0 0 13 0 0 0 0 0 0 0 0 64 0 12 19 0 0 2835 +0 36 0.999996416724044 -0.000229522836921497 -0.00266718172210738 -0.0106468978758399 0.000254257741965992 0.999956933875825 0.00927716264052947 -0.000967082438915169 0.00266493753624031 -0.00927780754949772 0.999953409112146 -0.0141489669637675 5.96502232442167e-05 2.40664908736825e-08 6.75394568017732e-06 1.98212400419398e-06 -1.20150958016317e-05 2.75692579357657e-05 2.40664908736825e-08 2.91037456135056e-05 -4.14699803836866e-06 4.35022490221476e-06 -1.40665303162875e-06 1.59113581407528e-05 6.75394568017732e-06 -4.14699803836866e-06 1.78590171608952e-05 -3.34745803837706e-06 -5.76507181639575e-06 2.28401520111148e-06 1.98212400419398e-06 4.35022490221476e-06 -3.34745803837706e-06 6.15790199085304e-05 1.13792908263117e-05 8.19174384496555e-06 -1.20150958016317e-05 -1.40665303162875e-06 -5.76507181639575e-06 1.13792908263117e-05 3.74046945679013e-05 -9.94411345682952e-06 2.75692579357657e-05 1.59113581407528e-05 2.28401520111148e-06 8.19174384496555e-06 -9.94411345682952e-06 6.55753925376502e-05 2802 2810 0 0 5 2811 2827 0 0 8 0 0 0 0 0 0 0 0 61 0 17 20 0 0 2574 +1 39 0.999998901367939 -0.000617867446146748 0.00134740592756786 -0.0112959432631434 0.000605839935084258 0.999960133815157 0.00890863279896378 0.00248151766151222 -0.00135285656583024 -0.00890780669933447 0.999959409555668 -0.0217863138252409 7.6024667478877e-05 1.39613304076547e-05 3.20153094772673e-06 1.95135058207789e-05 -7.75221892912481e-06 3.01818877215926e-05 1.39613304076547e-05 4.84539583597222e-05 4.58382674386389e-06 7.74771363192837e-07 -1.83883871067917e-06 7.37333644544143e-06 3.20153094772673e-06 4.58382674386389e-06 1.67133480065154e-05 6.20980575453784e-07 1.56774590178615e-06 -7.93366013645113e-07 1.95135058207789e-05 7.74771363192837e-07 6.20980575453784e-07 6.59592059831592e-05 6.88546169114475e-06 3.62837880488216e-06 -7.75221892912481e-06 -1.83883871067917e-06 1.56774590178615e-06 6.88546169114475e-06 3.15938872279661e-05 -9.65134992215621e-06 3.01818877215926e-05 7.37333644544143e-06 -7.93366013645113e-07 3.62837880488216e-06 -9.65134992215621e-06 8.55036557592431e-05 2768 2792 0 0 5 2770 2794 0 0 7 0 0 0 0 0 0 0 0 69 0 18 20 0 0 2676 +0 38 0.99998987415955 -0.00058403684595539 -0.00446211601483959 -0.0115256541740954 0.000638842766111622 0.999924259230252 0.0122909593910581 -0.0013655748291887 0.0044545996775814 -0.012293685525302 0.999914507264455 -0.0202869633597769 5.63889969401822e-05 -7.97843471726975e-06 5.7363212478154e-06 1.00570836138854e-05 -5.94091054399864e-06 1.17527717481316e-05 -7.97843471726975e-06 2.81725573628831e-05 -6.7423062982712e-06 4.10462974123738e-06 -2.00633672028607e-06 1.13833479044816e-05 5.7363212478154e-06 -6.7423062982712e-06 1.87906093322108e-05 -6.26024085656108e-06 1.38506120544571e-06 -1.00928520439874e-06 1.00570836138854e-05 4.10462974123738e-06 -6.26024085656108e-06 6.83996994752386e-05 3.01598172066592e-06 1.16311159274372e-06 -5.94091054399864e-06 -2.00633672028607e-06 1.38506120544571e-06 3.01598172066592e-06 3.48563317629655e-05 -6.40276620041762e-07 1.17527717481316e-05 1.13833479044816e-05 -1.00928520439874e-06 1.16311159274372e-06 -6.40276620041762e-07 6.58499594091124e-05 3024 3041 0 0 15 3026 3044 0 0 18 0 0 0 0 0 0 0 0 62 0 22 29 0 0 2619 +0 51 0.999987577522251 -6.30165393694547e-05 -0.00498405759358114 -0.00300155831318964 9.98607508762721e-05 0.999972670041921 0.00739250952390525 -5.56535022578503e-05 0.0049834555291286 -0.00739291540235388 0.999960254196557 -0.0151150921355596 6.35857383886432e-05 -4.17945347705888e-06 7.36348163629417e-06 -2.3067596094886e-06 -1.21532457629973e-05 4.91449267162862e-05 -4.17945347705888e-06 5.40817471301274e-05 -3.73667482007583e-06 8.41086209396269e-06 1.09454007446696e-06 1.1494921241104e-05 7.36348163629417e-06 -3.73667482007583e-06 2.1151674684692e-05 -8.72140809894966e-06 -3.59231721395727e-06 4.92373521732728e-06 -2.3067596094886e-06 8.41086209396269e-06 -8.72140809894966e-06 7.33630938923471e-05 6.60197467521861e-06 -4.52039170618627e-06 -1.21532457629973e-05 1.09454007446696e-06 -3.59231721395727e-06 6.60197467521861e-06 3.86216931945385e-05 -1.80407935201014e-05 4.91449267162862e-05 1.1494921241104e-05 4.92373521732728e-06 -4.52039170618627e-06 -1.80407935201014e-05 0.000112387208574469 2809 2826 0 0 16 2809 2827 0 0 18 0 0 0 0 0 0 0 0 70 0 17 24 0 0 2719 +1 41 0.999998707901459 0.00160691372988076 -4.49853038054084e-05 0.00255782100777958 -0.00160587976334741 0.999845418291854 0.0175088740635274 0.00571919924919127 7.311360002774e-05 -0.0175087791993477 0.999846706903288 -0.0248032684069278 5.76834021937133e-05 5.06267481952981e-06 6.31744858991278e-06 1.74908101282978e-06 -7.17002918107136e-06 2.85633901237133e-05 5.06267481952981e-06 5.330653641333e-05 -2.70732496654005e-06 1.88016034974409e-05 -3.93131971280981e-06 1.46768014473779e-05 6.31744858991278e-06 -2.70732496654005e-06 1.75017808395351e-05 -4.88021024376912e-06 -7.5715565935972e-07 4.91552315239931e-06 1.74908101282978e-06 1.88016034974409e-05 -4.88021024376912e-06 8.23035353253141e-05 8.0159918008985e-06 6.8796468519354e-07 -7.17002918107136e-06 -3.93131971280981e-06 -7.5715565935972e-07 8.0159918008985e-06 3.5689306128817e-05 -1.18397440423631e-05 2.85633901237133e-05 1.46768014473779e-05 4.91552315239931e-06 6.8796468519354e-07 -1.18397440423631e-05 7.18424687660131e-05 2846 2856 0 0 11 2847 2857 0 0 13 0 0 0 0 0 0 0 0 96 0 10 17 0 0 2606 +1 45 0.999998222657781 -6.89846519472074e-05 -0.00188412377420841 -0.00445616322978406 9.2782243180596e-05 0.999920190827243 0.0126334226346652 0.00927058554499448 0.00188310189158527 -0.01263357499398 0.999918420027423 -0.00968516315714128 7.91246727710162e-05 -6.03774564760284e-06 4.95016611803486e-06 1.27041078411539e-05 -1.595927971402e-05 3.24882871625394e-05 -6.03774564760284e-06 4.33481433085695e-05 -1.67879463536911e-06 1.56636172797351e-05 -6.00319873386081e-06 1.86175086559886e-05 4.95016611803486e-06 -1.67879463536911e-06 2.38039080642537e-05 2.08947501644652e-07 -1.03337804069536e-05 2.22139900096049e-06 1.27041078411539e-05 1.56636172797351e-05 2.08947501644652e-07 7.95374159978035e-05 -3.75781486596999e-06 1.72872149177058e-05 -1.595927971402e-05 -6.00319873386081e-06 -1.03337804069536e-05 -3.75781486596999e-06 5.09322758292827e-05 -8.45763079640159e-06 3.24882871625394e-05 1.86175086559886e-05 2.22139900096049e-06 1.72872149177058e-05 -8.45763079640159e-06 7.18752117616058e-05 2658 2677 0 0 13 2658 2678 0 0 16 0 0 0 0 0 0 0 0 28 0 12 14 0 0 2316 +0 41 0.999953531612406 0.00191579438790069 -0.00944798114625329 -0.00363905335157921 -0.00174510544009983 0.99983571679698 0.0180414529368598 0.0031676023638846 0.00948099271593452 -0.0180241268563357 0.99979259930657 -0.0234989399326739 5.39974633499941e-05 -5.84564644356768e-06 6.85219083724215e-06 3.91034441186326e-06 -5.19381580288062e-07 1.87972059786619e-05 -5.84564644356768e-06 5.50487875372151e-05 -1.0091572690365e-05 2.19131112504197e-05 1.10459910139005e-07 1.1366432590963e-05 6.85219083724215e-06 -1.0091572690365e-05 1.88509981207835e-05 -8.3417373926715e-06 1.3620430111291e-06 2.68126172964219e-07 3.91034441186326e-06 2.19131112504197e-05 -8.3417373926715e-06 8.37957556873972e-05 5.77707798120912e-06 6.4588629083543e-06 -5.19381580288062e-07 1.10459910139005e-07 1.3620430111291e-06 5.77707798120912e-06 3.02627320725083e-05 7.25676539660931e-07 1.87972059786619e-05 1.1366432590963e-05 2.68126172964219e-07 6.4588629083543e-06 7.25676539660931e-07 7.22140136414339e-05 2824 2841 0 0 15 2825 2843 0 0 17 0 0 0 0 0 0 0 0 93 0 19 26 0 0 2472 +0 4 0.999993077318945 0.000318214304607015 0.00370729737726905 0.00995869398156053 -0.0002956094787054 0.999981373453699 -0.00609633994209639 -0.00441351413945724 -0.00370916826569812 0.00609520182683427 0.999974544968754 -0.00836223073582371 2.86334873399715e-05 -4.97420267705946e-06 4.66758049394442e-06 -2.75133534184478e-06 3.36662941428542e-06 3.34984588009024e-07 -4.97420267705946e-06 2.51865721913972e-05 -3.16286276704961e-06 1.09112526501204e-06 -9.29423408804566e-07 -4.74056319270012e-06 4.66758049394442e-06 -3.16286276704961e-06 1.45610717080556e-05 2.89395874254045e-07 2.88720686701497e-06 2.60035410654708e-06 -2.75133534184478e-06 1.09112526501204e-06 2.89395874254045e-07 4.11696134264195e-05 3.1264654873519e-06 4.59645917165097e-06 3.36662941428542e-06 -9.29423408804566e-07 2.88720686701497e-06 3.1264654873519e-06 2.08553577330437e-05 -8.34979586894022e-07 3.34984588009024e-07 -4.74056319270012e-06 2.60035410654708e-06 4.59645917165097e-06 -8.34979586894022e-07 3.05704823831645e-05 3103 3104 0 0 14 3103 3105 0 0 16 0 0 0 0 0 0 0 0 77 0 24 28 0 0 2731 +1 43 0.999994770387373 0.000441099317703931 -0.00320384601633104 -0.00235276834876621 -0.000395460107478423 0.999898644271933 0.0142318233004219 0.00327389987130606 0.00320979893573294 -0.0142304818802091 0.999893589626541 -0.0198498981556365 6.02418609455477e-05 8.8623301449102e-06 8.02946142529215e-06 8.45482307350342e-06 -1.69361026702002e-06 2.42489741359773e-05 8.8623301449102e-06 0.000102374803287237 -6.9559654394241e-06 3.33637752232976e-05 -9.51640882379766e-07 -1.00385595312557e-05 8.02946142529215e-06 -6.9559654394241e-06 2.15551454502942e-05 -8.56375897704713e-06 -4.80823747874597e-07 3.37500896598515e-06 8.45482307350342e-06 3.33637752232976e-05 -8.56375897704713e-06 9.44938067945599e-05 7.66495733707694e-06 -4.42151968957374e-06 -1.69361026702002e-06 -9.51640882379766e-07 -4.80823747874597e-07 7.66495733707694e-06 3.24086238918182e-05 -8.79170344604399e-06 2.42489741359773e-05 -1.00385595312557e-05 3.37500896598515e-06 -4.42151968957374e-06 -8.79170344604399e-06 7.96764476106918e-05 2741 2749 0 0 10 2742 2750 0 0 12 0 0 0 0 0 0 0 0 18 0 15 22 0 0 2661 +1 40 0.999926161714043 -0.000289796053625553 -0.0121485446893411 -0.0152500094654884 0.000439197179311605 0.999924292601057 0.0122969985002113 0.00325042384378609 0.0121440613329849 -0.01230142611748 0.999850587182813 -0.0126803177253779 5.90820470318618e-05 -1.8346682503615e-05 1.95582168221441e-06 1.18174511371579e-07 -1.15135666143196e-05 2.86876195563953e-05 -1.8346682503615e-05 0.00011354184340477 -2.83691372667236e-06 3.09889482262194e-05 1.98259293810956e-06 -1.92406998518001e-05 1.95582168221441e-06 -2.83691372667236e-06 1.33793599315882e-05 -3.16748043619594e-07 -9.12438645703305e-08 -1.3616645821032e-06 1.18174511371579e-07 3.09889482262194e-05 -3.16748043619594e-07 7.83064132432963e-05 2.3352958808159e-06 -1.79783298247097e-05 -1.15135666143196e-05 1.98259293810956e-06 -9.12438645703305e-08 2.3352958808159e-06 3.48603741083872e-05 -6.30297323970225e-06 2.86876195563953e-05 -1.92406998518001e-05 -1.3616645821032e-06 -1.79783298247097e-05 -6.30297323970225e-06 8.32554555283736e-05 2871 2872 0 0 5 2881 2892 0 0 6 0 0 0 0 0 0 0 0 68 0 16 19 0 0 2633 +1 48 0.999998649000236 5.80514343568888e-05 -0.00164275005228673 -0.014096933300833 -3.65350034666375e-05 0.999914258608214 0.0130948118420761 0.00675362662498495 0.00164336937322095 -0.0130947341331096 0.999912909845196 -0.0179843825343167 4.81314016851801e-05 -1.88313703005838e-06 2.19509114665251e-06 1.1824657509175e-05 -1.99929941172029e-06 3.12693278829805e-05 -1.88313703005838e-06 5.88183341372819e-05 -3.20331587760767e-06 2.01634362774977e-05 -1.12399750916616e-06 2.43915135853826e-06 2.19509114665251e-06 -3.20331587760767e-06 1.87435778117716e-05 -6.33766686821176e-06 5.62776164821755e-07 1.7315588966641e-06 1.1824657509175e-05 2.01634362774977e-05 -6.33766686821176e-06 0.000100651443355506 9.09094212058953e-06 -2.91990048633338e-06 -1.99929941172029e-06 -1.12399750916616e-06 5.62776164821755e-07 9.09094212058953e-06 2.72411964308909e-05 -1.03002453688077e-05 3.12693278829805e-05 2.43915135853826e-06 1.7315588966641e-06 -2.91990048633338e-06 -1.03002453688077e-05 7.68036943749442e-05 2936 2935 0 0 5 2940 2951 0 0 6 0 0 0 0 0 0 0 0 47 0 17 21 0 0 2813 +1 47 0.99999168706543 0.000747039909390337 -0.00400845748499928 -0.0112127531934827 -0.000674659904195701 0.999837256732684 0.0180278918145041 0.00822345275701817 0.00402127269019888 -0.0180250376042762 0.999829449148861 -0.0252961302090234 7.19159052464259e-05 -1.21996435019817e-05 -2.12692837617874e-06 -6.46619365808632e-06 -7.73975539702837e-06 4.54821180737585e-05 -1.21996435019817e-05 5.50175633016637e-05 -3.70047817322418e-06 1.56169340225224e-05 -6.12037388260135e-06 1.83053666362885e-06 -2.12692837617874e-06 -3.70047817322418e-06 1.71230194289714e-05 -2.84766023761372e-06 -1.8977475000026e-07 -2.34378625875452e-06 -6.46619365808632e-06 1.56169340225224e-05 -2.84766023761372e-06 7.77261355652486e-05 8.11549938406334e-06 2.64477268435131e-06 -7.73975539702837e-06 -6.12037388260135e-06 -1.8977475000026e-07 8.11549938406334e-06 3.04422035212791e-05 -1.19750858859909e-05 4.54821180737585e-05 1.83053666362885e-06 -2.34378625875452e-06 2.64477268435131e-06 -1.19750858859909e-05 9.37417685222052e-05 2910 2918 0 0 4 2911 2919 0 0 5 0 0 0 0 0 0 0 0 62 0 22 29 0 0 2720 +1 37 0.999927259653828 -6.49487829690471e-05 -0.0120611435129993 -0.0145036908779954 0.000227006362845574 0.99990971445465 0.0134354533727875 0.00372410369940242 0.0120591819497345 -0.0134372140295788 0.999836995419667 -0.0198083480868618 6.11307586175454e-05 -5.77771249158956e-06 1.355889809658e-06 -3.609847769162e-06 -1.10428894463682e-05 3.63581092075671e-05 -5.77771249158956e-06 5.28925314342219e-05 -4.99078795436348e-06 1.18510570777074e-05 2.50380478329899e-06 -4.55911450296814e-06 1.355889809658e-06 -4.99078795436348e-06 1.83005107605952e-05 -1.78517275051859e-06 -2.63252996576211e-07 4.75287011938345e-06 -3.609847769162e-06 1.18510570777074e-05 -1.78517275051859e-06 6.07542785584269e-05 3.5864787789341e-06 4.03875303029288e-06 -1.10428894463682e-05 2.50380478329899e-06 -2.63252996576211e-07 3.5864787789341e-06 3.96022808576237e-05 -1.68319529281289e-05 3.63581092075671e-05 -4.55911450296814e-06 4.75287011938345e-06 4.03875303029288e-06 -1.68319529281289e-05 0.000102935057363847 2855 2874 0 0 6 2856 2875 0 0 7 0 0 0 0 0 0 0 0 61 0 18 20 0 0 2641 +1 38 0.999978615989596 -0.00101110131791155 -0.00646105545993429 -0.0148674080662484 0.00107849363323339 0.999944966187579 0.0104355856378485 0.000429474087505126 0.00645014844902846 -0.0104423306903541 0.999924673820353 -0.021216186701278 4.83242475892272e-05 3.54434525475721e-06 2.29904866258409e-06 -4.24199756630814e-07 -7.48901061257434e-06 2.79024041224317e-05 3.54434525475721e-06 0.000114563628018119 -2.19578319565682e-06 3.85056673193979e-05 7.61746444448567e-06 -2.04239614321886e-05 2.29904866258409e-06 -2.19578319565682e-06 1.67954745120759e-05 -5.446117035363e-06 -1.36790618557472e-06 8.68867049985856e-07 -4.24199756630814e-07 3.85056673193979e-05 -5.446117035363e-06 7.8153147848337e-05 1.50242515849345e-05 -1.65973080666993e-05 -7.48901061257434e-06 7.61746444448567e-06 -1.36790618557472e-06 1.50242515849345e-05 3.46392906228618e-05 -1.07294944578444e-05 2.79024041224317e-05 -2.04239614321886e-05 8.68867049985856e-07 -1.65973080666993e-05 -1.07294944578444e-05 8.91169263061305e-05 2735 2740 0 0 4 2736 2742 0 0 5 0 0 0 0 0 0 0 0 57 0 24 31 0 0 2825 +1 51 0.999999857304424 -0.000469657467823848 0.000254583963272528 -0.00320747438635193 0.00046578696814695 0.999887447310435 0.0149958578788115 0.00456625682753609 -0.000261598225801951 -0.0149957371570766 0.999887523391248 -0.0197218430531132 8.1259034906482e-05 3.65646468705936e-07 3.22214345980133e-06 7.03267313346592e-06 -1.03073922962073e-05 4.14077330908731e-05 3.65646468705936e-07 2.9469348791395e-05 -5.53334070279774e-06 2.18508295439277e-06 -2.06056787447711e-06 6.66407093982238e-06 3.22214345980133e-06 -5.53334070279774e-06 1.85963389051575e-05 -5.58061887803084e-06 4.42277497771704e-07 1.78510064679104e-06 7.03267313346592e-06 2.18508295439277e-06 -5.58061887803084e-06 5.90746147081916e-05 7.98999126588652e-06 -2.88607339224126e-07 -1.03073922962073e-05 -2.06056787447711e-06 4.42277497771704e-07 7.98999126588652e-06 3.52118985256016e-05 -1.20309077428201e-05 4.14077330908731e-05 6.66407093982238e-06 1.78510064679104e-06 -2.88607339224126e-07 -1.20309077428201e-05 8.03301912349539e-05 2911 2920 0 0 11 2911 2920 0 0 11 0 0 0 0 0 0 0 0 75 0 15 21 0 0 2623 +1 50 0.999995003572278 -0.000266449423296873 0.00314989447186397 -0.00357812862465194 0.000244438784108461 0.999975567312174 0.00698605957441038 0.00169736793341242 -0.00315167894302038 -0.00698525471269389 0.999970636137101 -0.0112370635741937 7.35393204744053e-05 -1.77598853067671e-05 4.86890661837168e-06 2.28549832244209e-06 -9.65488690389905e-06 2.92507659512428e-05 -1.77598853067671e-05 5.85505176661957e-05 -6.41244627041248e-06 1.37047254286375e-05 2.6740147704371e-06 3.28514433449969e-06 4.86890661837168e-06 -6.41244627041248e-06 2.03968774832066e-05 -7.08725712843354e-06 -2.84710088576452e-06 4.24053477712464e-06 2.28549832244209e-06 1.37047254286375e-05 -7.08725712843354e-06 7.90026194360093e-05 1.01768135942791e-05 -5.49630088436649e-07 -9.65488690389905e-06 2.6740147704371e-06 -2.84710088576452e-06 1.01768135942791e-05 4.22821018497036e-05 -1.51143758260207e-05 2.92507659512428e-05 3.28514433449969e-06 4.24053477712464e-06 -5.49630088436649e-07 -1.51143758260207e-05 6.73269715527665e-05 2901 2902 0 0 11 2901 2918 0 0 13 0 0 0 0 0 0 0 0 59 0 11 14 0 0 2644 +1 36 0.999989230472828 -0.000794099283130249 -0.00457256434512623 -0.0135166250513907 0.000829379240671792 0.99996986525929 0.00771885376154177 -0.000531478496143828 0.00456629701584668 -0.00772256302308093 0.999959754666115 -0.0137111118714973 4.64220706558067e-05 4.94848211424788e-06 -6.90841699306644e-08 3.82117259334239e-07 -8.55081995191947e-06 2.08518262648703e-05 4.94848211424788e-06 8.02050896962398e-05 3.67855259682595e-07 1.42957633153945e-05 -6.58642296357036e-06 4.92480690034113e-06 -6.90841699306644e-08 3.67855259682595e-07 1.57414902992532e-05 -5.9056747496649e-06 -3.7773510991496e-06 1.19601191085728e-06 3.82117259334239e-07 1.42957633153945e-05 -5.9056747496649e-06 7.05117035775223e-05 1.38386066440297e-05 -4.39130460711245e-06 -8.55081995191947e-06 -6.58642296357036e-06 -3.7773510991496e-06 1.38386066440297e-05 3.89697427397865e-05 -8.44136034519865e-06 2.08518262648703e-05 4.92480690034113e-06 1.19601191085728e-06 -4.39130460711245e-06 -8.44136034519865e-06 6.52907388744305e-05 2716 2733 0 0 5 2718 2735 0 0 7 0 0 0 0 0 0 0 0 61 0 16 18 0 0 2762 +1 35 0.999995636072301 0.000186374228226452 -0.00294840651893032 -0.0176377440174888 -0.000167738807098789 0.999980017747901 0.00631949116624395 0.00743206888012487 0.00294952539341686 -0.00631896902624908 0.999975685169594 -0.0107555227303294 3.5074427532395e-05 -5.58685896139018e-06 4.32186940883599e-06 -8.21258782099668e-06 -1.47597718664694e-07 9.1440197303208e-06 -5.58685896139018e-06 2.15924097226272e-05 -3.21336029858735e-06 9.24065779333547e-07 -1.7042655590482e-06 5.45566806433196e-06 4.32186940883599e-06 -3.21336029858735e-06 1.74014227687433e-05 -2.79478104932514e-06 -5.8317375098946e-07 1.53201586110228e-06 -8.21258782099668e-06 9.24065779333547e-07 -2.79478104932514e-06 6.93446509981276e-05 1.03008271306996e-05 -3.98092354329326e-06 -1.47597718664694e-07 -1.7042655590482e-06 -5.8317375098946e-07 1.03008271306996e-05 2.69462293841482e-05 -2.80707254428347e-06 9.1440197303208e-06 5.45566806433196e-06 1.53201586110228e-06 -3.98092354329326e-06 -2.80707254428347e-06 3.66833509900581e-05 2674 2691 0 0 3 2678 2695 0 0 7 0 0 0 0 0 0 0 0 65 0 20 22 0 0 2796 +1 52 0.999855981348858 0.00502266618006857 -0.016210779911996 -0.00208974602579686 -0.00481208507916573 0.999903876239044 0.0130031580520003 0.00445217016403151 0.0162745321930447 -0.012923277702581 0.999784040928499 -0.0147182727239707 8.7963498347771e-05 -4.45759479272916e-06 4.49658541673421e-06 4.15367902359053e-06 -1.98964413747291e-05 5.86532698377395e-05 -4.45759479272916e-06 4.6456546356332e-05 -9.47774981119757e-06 8.23611116646091e-06 1.85139608888343e-06 8.79209262158153e-06 4.49658541673421e-06 -9.47774981119757e-06 2.25268844160469e-05 -7.22863671793226e-06 -4.770918932731e-06 4.18821697659413e-06 4.15367902359053e-06 8.23611116646091e-06 -7.22863671793226e-06 7.43959758125125e-05 9.46253989329529e-06 -9.42119076006345e-07 -1.98964413747291e-05 1.85139608888343e-06 -4.770918932731e-06 9.46253989329529e-06 4.10204086988009e-05 -2.55584050674611e-05 5.86532698377395e-05 8.79209262158153e-06 4.18821697659413e-06 -9.42119076006345e-07 -2.55584050674611e-05 9.73013747492674e-05 2867 2867 0 0 7 2874 2887 0 0 10 0 0 0 0 0 0 0 0 62 0 18 19 0 0 2688 +1 34 0.999954931255518 0.000599953111380374 -0.00947499414439209 -0.00953132106649302 -0.000543713917279933 0.999982228047654 0.00593699958107506 0.00643107891503403 0.00947838767661861 -0.0059315803217755 0.999937486306988 -0.00464099212740919 5.17416656584418e-05 1.38279918548779e-06 -2.46873732588601e-07 -4.50409329342733e-06 -5.26832866865973e-06 7.62961832739261e-06 1.38279918548779e-06 5.10491745292117e-05 -9.00802158998649e-07 5.70964993017632e-06 -5.26377395450284e-07 -5.73393932663384e-06 -2.46873732588601e-07 -9.00802158998649e-07 1.56420723281318e-05 -1.65017814704967e-06 -2.32599007179393e-06 3.61077161957154e-07 -4.50409329342733e-06 5.70964993017632e-06 -1.65017814704967e-06 6.41976942493981e-05 7.86548158523354e-06 4.81823569593313e-06 -5.26832866865973e-06 -5.26377395450284e-07 -2.32599007179393e-06 7.86548158523354e-06 3.37827013842081e-05 -3.94428558519528e-06 7.62961832739261e-06 -5.73393932663384e-06 3.61077161957154e-07 4.81823569593313e-06 -3.94428558519528e-06 4.91108514620628e-05 2798 2819 0 0 8 2799 2821 0 0 10 0 0 0 0 0 0 0 0 52 0 15 17 0 0 2610 +1 49 0.99997703764636 0.00150172531364205 -0.00660825249910279 -0.00957535657352196 -0.00141523407040014 0.999913534827862 0.0130736368534791 0.00782014854335279 0.00662731412681715 -0.0130639844279238 0.999892699752494 -0.0131533857114893 4.82743841320534e-05 -8.49308000704387e-06 2.32151586523588e-06 2.95397851996225e-06 -2.5901719312601e-06 2.68484827438259e-05 -8.49308000704387e-06 3.91276171121252e-05 -6.89877522019497e-06 -8.93451728096241e-09 -1.14748106197877e-06 -1.521353312421e-06 2.32151586523588e-06 -6.89877522019497e-06 1.72329840964388e-05 2.81562145241137e-07 7.19949764808627e-07 3.22708886872824e-06 2.95397851996225e-06 -8.93451728096241e-09 2.81562145241137e-07 6.1611101394047e-05 8.2290723145232e-06 -1.05575861018132e-06 -2.5901719312601e-06 -1.14748106197877e-06 7.19949764808627e-07 8.2290723145232e-06 2.75950722663731e-05 -8.52917419177287e-06 2.68484827438259e-05 -1.521353312421e-06 3.22708886872824e-06 -1.05575861018132e-06 -8.52917419177287e-06 6.38711707319955e-05 3007 3025 0 0 8 3008 3027 0 0 11 0 0 0 0 0 0 0 0 62 0 15 18 0 0 2808 +1 31 0.999971157633694 9.4044471694128e-05 -0.00759440954703894 -0.0115364578827537 -7.76304167495299e-05 0.999997660727222 0.0021615997783847 0.00332672709213319 0.0075945950681526 -0.00216094787555398 0.999968825729097 0.00421594789281343 3.17222478153533e-05 7.52519339225318e-06 9.54711750388595e-07 8.80275475407043e-06 -5.41690374342641e-06 -5.04654317116845e-06 7.52519339225318e-06 8.59194440394571e-05 -5.43753264593742e-06 2.43582136651835e-05 -6.51801127441397e-06 -2.77385789371165e-05 9.54711750388595e-07 -5.43753264593742e-06 1.26643139073701e-05 2.5084118088775e-06 5.11540967286504e-06 3.03260476764087e-06 8.80275475407043e-06 2.43582136651835e-05 2.5084118088775e-06 5.54313683209044e-05 3.23940457786841e-06 -8.22645574316237e-06 -5.41690374342641e-06 -6.51801127441397e-06 5.11540967286504e-06 3.23940457786841e-06 2.93071383181001e-05 5.65758153776595e-06 -5.04654317116845e-06 -2.77385789371165e-05 3.03260476764087e-06 -8.22645574316237e-06 5.65758153776595e-06 4.27549270073571e-05 2910 2930 0 0 7 2910 2930 0 0 7 0 0 0 0 0 0 0 0 66 0 15 18 0 0 2631 +1 53 0.998947298093633 0.00955194721994396 -0.0448670919019447 0.00335869545644591 -0.00944889705887744 0.999952212221303 0.00250830980798898 -0.000425934748967061 0.0448889070461833 -0.00208172477275968 0.998989815987215 -0.0262468633005399 5.52612258363346e-05 1.64570858012372e-05 1.82484609936349e-06 2.07609791936686e-05 -7.97858196178753e-06 3.55155843572556e-05 1.64570858012372e-05 0.000100980625482015 -2.49618431857747e-06 3.27596781222426e-05 4.46888224433711e-06 3.38888426070083e-05 1.82484609936349e-06 -2.49618431857747e-06 1.59743009830371e-05 -2.51144522485649e-06 -4.04693592031929e-06 -3.10421303665067e-06 2.07609791936686e-05 3.27596781222426e-05 -2.51144522485649e-06 9.11136930415351e-05 2.67098199944749e-06 3.37092046814954e-05 -7.97858196178753e-06 4.46888224433711e-06 -4.04693592031929e-06 2.67098199944749e-06 3.33064245253886e-05 -6.35344313956047e-06 3.55155843572556e-05 3.38888426070083e-05 -3.10421303665067e-06 3.37092046814954e-05 -6.35344313956047e-06 8.31778617491497e-05 2529 2529 0 0 1 2535 2545 0 0 2 0 0 0 0 0 0 0 0 58 0 20 21 0 0 2701 +1 3 0.999999864343922 -0.000462805247506864 -0.000239005106946324 0.00137626996709597 0.000461628189295385 0.999987880444583 -0.00490161844352257 -0.00388093562368488 0.000241270705047624 0.00490150744709348 0.999987958434097 -0.0134640036595205 3.8419762182981e-05 1.30150215743688e-06 8.69192467042954e-07 5.77050247559874e-06 1.77527278551178e-06 -1.62163875197414e-06 1.30150215743688e-06 8.59762716659918e-05 -4.59308195317468e-06 3.39491399774574e-05 -1.69837771852326e-06 -3.13412574362554e-05 8.69192467042954e-07 -4.59308195317468e-06 1.64749085700469e-05 -1.78832402119286e-06 1.63830907703243e-06 4.52824004021097e-06 5.77050247559874e-06 3.39491399774574e-05 -1.78832402119286e-06 6.79898057905598e-05 3.08895591472672e-06 -2.16127420757513e-05 1.77527278551178e-06 -1.69837771852326e-06 1.63830907703243e-06 3.08895591472672e-06 2.64597782985107e-05 -2.25339185357862e-06 -1.62163875197414e-06 -3.13412574362554e-05 4.52824004021097e-06 -2.16127420757513e-05 -2.25339185357862e-06 4.99372397665049e-05 2849 2851 0 0 14 2856 2870 0 0 15 0 0 0 0 0 0 0 0 71 0 9 11 0 0 2563 +1 33 0.999999948163651 -1.91698757564341e-05 -0.000321411280033603 -0.00517075167071445 1.94301181576296e-05 0.999999672001697 0.000809703012503799 0.00346740676270373 0.000321395652705099 -0.0008097092155909 0.999999620537838 -0.00219166981409784 4.33984252716346e-05 -6.9205314243606e-06 1.33392997012597e-06 2.64320728367517e-06 -1.87014568011206e-06 3.89406174913044e-06 -6.9205314243606e-06 1.74815624853304e-05 -7.02616250152087e-06 1.91744944091816e-06 -1.94742024706323e-06 3.81196409320014e-06 1.33392997012597e-06 -7.02616250152087e-06 1.24471093825875e-05 -5.14246412742792e-07 1.19472638037392e-06 2.38338051458176e-06 2.64320728367517e-06 1.91744944091816e-06 -5.14246412742792e-07 5.07163768924467e-05 -2.35926740313275e-06 9.73326636747756e-06 -1.87014568011206e-06 -1.94742024706323e-06 1.19472638037392e-06 -2.35926740313275e-06 2.5594700124286e-05 -3.52679962043823e-06 3.89406174913044e-06 3.81196409320014e-06 2.38338051458176e-06 9.73326636747756e-06 -3.52679962043823e-06 3.00746848003777e-05 2783 2784 0 0 9 2790 2803 0 0 10 0 0 0 0 0 0 0 0 63 0 11 14 0 0 2679 +1 4 0.999994526270503 0.000771574979918367 -0.00321746811681723 0.00215869445452688 -0.000796170772564911 0.999970419878204 -0.00765019481508661 -0.00375647357043249 0.00321147024480764 0.00765271459406586 0.999965560616069 -0.000783796600389985 4.15461851049986e-05 -1.22258964382578e-05 2.54194321792547e-06 -5.90495710302817e-06 3.30582381449058e-06 -2.62624447650042e-06 -1.22258964382578e-05 3.93516959523824e-05 -5.90472529266207e-06 5.91902703208364e-06 -1.65624874782364e-06 -9.28875787588688e-06 2.54194321792547e-06 -5.90472529266207e-06 1.62735695231345e-05 -3.12166807805508e-06 3.80531987017613e-06 1.1006696857031e-06 -5.90495710302817e-06 5.91902703208364e-06 -3.12166807805508e-06 5.1723204634368e-05 3.95424119168171e-06 -2.93529503454179e-06 3.30582381449058e-06 -1.65624874782364e-06 3.80531987017613e-06 3.95424119168171e-06 2.25582786582306e-05 -6.24717447022419e-06 -2.62624447650042e-06 -9.28875787588688e-06 1.1006696857031e-06 -2.93529503454179e-06 -6.24717447022419e-06 3.56282609773842e-05 2969 2970 0 0 11 2971 2988 0 0 13 0 0 0 0 0 0 0 0 74 0 11 15 0 0 2573 +1 32 0.99999391967799 0.000718663604414257 -0.00341234958262001 -0.00479019218326177 -0.000725403919284204 0.999997787677033 -0.0019744442746557 0.0017954879357136 0.00341092307216152 0.00197690760115991 0.999992228689869 0.00544568726864236 3.47209387598715e-05 -4.32980240631071e-06 2.40258720036642e-06 2.81768684170692e-06 -2.04667336179342e-06 2.83850703146591e-06 -4.32980240631071e-06 3.60131828421168e-05 -2.51721070595971e-06 -2.73856185522279e-06 -3.91386913490889e-06 -3.76264467170366e-06 2.40258720036642e-06 -2.51721070595971e-06 1.32934557482831e-05 2.76255087214629e-07 2.13394487770392e-06 3.8083453747796e-06 2.81768684170692e-06 -2.73856185522279e-06 2.76255087214629e-07 4.29932201754243e-05 -9.43060675781987e-07 1.52926832244729e-06 -2.04667336179342e-06 -3.91386913490889e-06 2.13394487770392e-06 -9.43060675781987e-07 2.59084307185551e-05 -5.48979926232726e-06 2.83850703146591e-06 -3.76264467170366e-06 3.8083453747796e-06 1.52926832244729e-06 -5.48979926232726e-06 3.43533339312063e-05 2973 2974 0 0 8 2981 2994 0 0 9 0 0 0 0 0 0 0 0 54 0 14 17 0 0 2686 +2 5 0.999998421218819 -0.000935153774686229 0.001510975607414 -0.000507791951585971 0.000940667493606075 0.999992887055048 -0.00365253117386643 0.00215370361125819 -0.00150754918161328 0.00365394673295648 0.999992187953855 0.0163812322720048 4.50911870481293e-05 -4.57515020849313e-06 7.85642189731975e-06 -1.73535121302403e-06 -4.66623908207588e-06 3.13934972239172e-06 -4.57515020849313e-06 2.85735433213784e-05 -1.58501350093678e-06 2.64441382330499e-06 -1.92713551076633e-06 -4.79899648555276e-06 7.85642189731975e-06 -1.58501350093678e-06 1.36561571553062e-05 -9.74883586943389e-08 2.47990790516945e-06 1.41398202405156e-06 -1.73535121302403e-06 2.64441382330499e-06 -9.74883586943389e-08 3.87344232666969e-05 6.01341738511004e-06 -4.8886934156982e-06 -4.66623908207588e-06 -1.92713551076633e-06 2.47990790516945e-06 6.01341738511004e-06 2.43188526237316e-05 -3.72169689729299e-06 3.13934972239172e-06 -4.79899648555276e-06 1.41398202405156e-06 -4.8886934156982e-06 -3.72169689729299e-06 3.46369616014896e-05 2770 2770 0 0 9 2770 2781 0 0 12 0 0 0 0 0 0 0 0 63 0 8 9 0 0 2617 +1 28 0.999999586707168 0.000160588870102637 -0.000894872453400004 -0.00360416730836887 -0.000160013602462729 0.999999780548349 0.000642883272029121 0.0025133735721628 0.00089497549691703 -0.000642739814565059 0.999999392952011 -0.00287264459104856 4.98804375276355e-05 -7.54761676787898e-06 4.42878645471648e-06 2.74104262325673e-06 2.02191354642445e-07 3.31235011850352e-07 -7.54761676787898e-06 2.49817137148435e-05 -2.29045976325279e-06 1.23452321641349e-06 -2.10755866761495e-07 1.68340756372311e-05 4.42878645471648e-06 -2.29045976325279e-06 1.28055875960297e-05 8.98897233230031e-07 2.76242314764768e-06 2.84109143217856e-06 2.74104262325673e-06 1.23452321641349e-06 8.98897233230031e-07 3.79749045597556e-05 1.36294077975845e-06 2.23228257242945e-06 2.02191354642445e-07 -2.10755866761495e-07 2.76242314764768e-06 1.36294077975845e-06 2.17567393820866e-05 -4.14693507848164e-06 3.31235011850352e-07 1.68340756372311e-05 2.84109143217856e-06 2.23228257242945e-06 -4.14693507848164e-06 5.19085673662474e-05 2849 2856 0 0 9 2849 2856 0 0 10 0 0 0 0 0 0 0 0 76 0 19 26 0 0 2691 +1 30 0.999984157786696 0.00017088336341566 0.00562627536722663 -0.00229040827808937 -0.00013788685929209 0.999982793689732 -0.00586458111820097 0.000192838870578471 -0.00562718071913351 0.00586371242081606 0.999966975311585 -0.00265372808630183 3.61226892245736e-05 -1.05760108596928e-06 5.7558181805799e-06 3.91669612835285e-06 -1.20789115211618e-06 -2.7166532566707e-06 -1.05760108596928e-06 4.10216260399571e-05 -8.45238032210193e-07 3.86596535476171e-06 -1.03548239597298e-06 -8.99455580410925e-06 5.7558181805799e-06 -8.45238032210193e-07 1.41003220606419e-05 5.10500276492895e-07 9.24493457289336e-07 1.19811684898784e-06 3.91669612835285e-06 3.86596535476171e-06 5.10500276492895e-07 4.81974039318281e-05 1.76713654574227e-06 -8.54005780233008e-06 -1.20789115211618e-06 -1.03548239597298e-06 9.24493457289336e-07 1.76713654574227e-06 2.6670933526556e-05 -3.60741459520303e-06 -2.7166532566707e-06 -8.99455580410925e-06 1.19811684898784e-06 -8.54005780233008e-06 -3.60741459520303e-06 3.39442086418013e-05 2792 2793 0 0 12 2793 2808 0 0 13 0 0 0 0 0 0 0 0 64 0 11 13 0 0 2528 +2 4 0.999995661253703 0.000306825529881453 -0.00292973238769331 0.00182961327079712 -0.000313259681789364 0.99999753983164 -0.00219595060050952 0.00013793658061487 0.00292905140635179 0.00219685883987248 0.999993297212085 0.00920299925883675 3.520662151029e-05 -8.18450659195266e-06 2.64278756528078e-06 -7.22872816941329e-07 4.7084726037786e-06 -7.53001065575559e-06 -8.18450659195266e-06 2.63175980185581e-05 -6.25422656111849e-06 5.32415308359573e-06 -4.75088198061948e-06 3.66253201262903e-06 2.64278756528078e-06 -6.25422656111849e-06 1.77899657883343e-05 -6.62837546485283e-07 2.25670157741618e-06 2.99455047486587e-06 -7.22872816941329e-07 5.32415308359573e-06 -6.62837546485283e-07 4.45051218577356e-05 2.40831911550948e-06 1.36459277992907e-06 4.7084726037786e-06 -4.75088198061948e-06 2.25670157741618e-06 2.40831911550948e-06 2.1433190602719e-05 -3.91832423510255e-07 -7.53001065575559e-06 3.66253201262903e-06 2.99455047486587e-06 1.36459277992907e-06 -3.91832423510255e-07 2.73266448128473e-05 2985 2985 0 0 10 2988 2996 0 0 13 0 0 0 0 0 0 0 0 75 0 25 29 0 0 2706 +2 6 0.999996349810001 -0.00142374709077143 0.00229636906773371 0.00108951930270752 0.00143369039602688 0.999989579594705 -0.00433419356438496 0.000175068728924998 -0.00229017434315919 0.00433747002603311 0.999987970655273 0.0171071147599959 3.46362805052854e-05 2.0380789337831e-06 4.57363892955104e-06 -2.9911890845452e-06 4.44408534570319e-06 5.46128789881169e-06 2.0380789337831e-06 3.71049042655697e-05 -5.18721742824361e-06 8.19602544942041e-06 1.02683838595289e-06 -7.32400841102434e-06 4.57363892955104e-06 -5.18721742824361e-06 1.45986727477662e-05 -5.27707898419254e-07 3.37213862221467e-06 1.83575199709566e-06 -2.9911890845452e-06 8.19602544942041e-06 -5.27707898419254e-07 4.73943832408604e-05 3.99157192300855e-06 -1.34727930330704e-06 4.44408534570319e-06 1.02683838595289e-06 3.37213862221467e-06 3.99157192300855e-06 1.9910318428344e-05 -1.71689436968315e-06 5.46128789881169e-06 -7.32400841102434e-06 1.83575199709566e-06 -1.34727930330704e-06 -1.71689436968315e-06 3.97182635768616e-05 2789 2790 0 0 13 2792 2800 0 0 17 0 0 0 0 0 0 0 0 62 0 25 28 0 0 2669 +1 29 0.999973662495652 7.20269486354873e-07 0.00725770724910696 0.00144217182243132 3.95525204966434e-05 0.999984604377681 -0.00554882358809334 -0.000944179172405527 -0.00725759950883557 0.00554896450654269 0.999958267250326 0.00755962334313213 3.07311967731909e-05 -2.91326910263431e-06 3.29088371060739e-06 7.56458233707531e-06 1.84498532387501e-06 2.56558940410029e-06 -2.91326910263431e-06 5.8483853153343e-05 -3.72444770252125e-06 1.21154437714796e-05 1.44675727585244e-06 6.90884525488064e-06 3.29088371060739e-06 -3.72444770252125e-06 1.20627772806625e-05 7.61713638291749e-08 1.9590981787739e-06 -8.16867172235698e-07 7.56458233707531e-06 1.21154437714796e-05 7.61713638291749e-08 4.21986879877301e-05 3.95048534021373e-06 3.66304111137576e-06 1.84498532387501e-06 1.44675727585244e-06 1.9590981787739e-06 3.95048534021373e-06 2.42021864176764e-05 -2.03451586689709e-06 2.56558940410029e-06 6.90884525488064e-06 -8.16867172235698e-07 3.66304111137576e-06 -2.03451586689709e-06 3.76948748161867e-05 2904 2905 0 0 13 2905 2921 0 0 15 0 0 0 0 0 0 0 0 68 0 11 12 0 0 2621 +2 53 0.998641963334598 0.00869767737220411 -0.0513671049948207 -0.00478326240729045 -0.00855374031058986 0.999958851788365 0.00302130051379676 -0.00138353969126655 0.0513912696274268 -0.00257781660028933 0.99867526867729 -0.00647714253285724 6.22202786727013e-05 2.89005910739171e-05 2.88335496648971e-06 2.49370093803532e-05 -1.12432902017146e-05 3.6687081487577e-05 2.89005910739171e-05 0.000220769920061226 -5.50121827843105e-07 0.000100322324389556 1.74006447393362e-06 2.38575011469769e-05 2.88335496648971e-06 -5.50121827843105e-07 1.63070413418351e-05 1.85920807792205e-06 -2.96122322869013e-06 -8.80292579986826e-07 2.49370093803532e-05 0.000100322324389556 1.85920807792205e-06 0.000143153717289404 4.56605416499282e-06 1.94234620390848e-05 -1.12432902017146e-05 1.74006447393362e-06 -2.96122322869013e-06 4.56605416499282e-06 3.65814427115346e-05 -8.58912073223516e-06 3.6687081487577e-05 2.38575011469769e-05 -8.80292579986826e-07 1.94234620390848e-05 -8.58912073223516e-06 7.63838882600599e-05 2474 2472 0 0 0 2478 2476 0 0 0 0 0 0 0 0 0 0 0 54 0 46 60 0 0 2727 +1 27 0.999987982632267 -0.000665269157522216 -0.00485716048701357 -0.00572830708946694 0.000660120495699047 0.999999218685524 -0.00106154098948889 0.00159066452187817 0.00485786290252352 0.00105832192137207 0.999987640484987 0.00222652450916187 5.07960268422978e-05 -6.97817595761005e-06 5.16049831320998e-06 6.03769622779368e-06 -5.74078966909457e-06 -1.02989578235008e-07 -6.97817595761005e-06 9.93386864617894e-05 -5.12024739450078e-06 2.68731572403589e-05 5.75979032020687e-09 -1.0376434486664e-05 5.16049831320998e-06 -5.12024739450078e-06 1.30938467399915e-05 1.29304070855729e-06 3.35967487242258e-06 3.69718168786379e-06 6.03769622779368e-06 2.68731572403589e-05 1.29304070855729e-06 4.80950745389655e-05 6.2937135913956e-07 -2.43159364448245e-06 -5.74078966909457e-06 5.75979032020687e-09 3.35967487242258e-06 6.2937135913956e-07 2.79369059827087e-05 -4.78223329766374e-06 -1.02989578235008e-07 -1.0376434486664e-05 3.69718168786379e-06 -2.43159364448245e-06 -4.78223329766374e-06 4.2582129065991e-05 2852 2853 0 0 10 2860 2873 0 0 12 0 0 0 0 0 0 0 0 69 0 12 15 0 0 2691 +1 5 0.999999264121587 -0.000656597608940419 0.00102011561288135 0.00117921232539299 0.000657356997993187 0.999999506980908 -0.000744257830694278 0.00290191465068129 -0.00101962643203281 0.000744927863147896 0.999999202721891 0.00164902432993133 3.00533092497958e-05 -4.53870102030066e-06 1.88546082518067e-06 6.13987866406878e-06 1.40685134004871e-06 3.91681773058312e-06 -4.53870102030066e-06 1.63526386879195e-05 -6.20158112291562e-06 -1.44301188526812e-06 -2.47588381600792e-06 4.0567346422997e-06 1.88546082518067e-06 -6.20158112291562e-06 1.38013637540089e-05 -3.48569647896172e-06 2.84094170836953e-06 1.1449601783718e-07 6.13987866406878e-06 -1.44301188526812e-06 -3.48569647896172e-06 4.40631517911581e-05 5.78240075974577e-06 1.36458683911399e-06 1.40685134004871e-06 -2.47588381600792e-06 2.84094170836953e-06 5.78240075974577e-06 2.09128132559505e-05 -8.11902004006426e-08 3.91681773058312e-06 4.0567346422997e-06 1.1449601783718e-07 1.36458683911399e-06 -8.11902004006426e-08 3.26444746551367e-05 2795 2795 0 0 12 2801 2812 0 0 13 0 0 0 0 0 0 0 0 75 0 8 9 0 0 2598 +2 37 0.999981515087369 0.000973076765641496 -0.00600188346925601 -0.0112766491548675 -0.000884304794213009 0.999890443131476 0.0147756468342534 0.00546858688625364 0.00601560376032961 -0.0147700662133864 0.999872820740443 -0.00807127200673784 6.04809699819397e-05 5.21205361806389e-06 2.16113044920106e-06 2.85583164484995e-06 -1.56303946535572e-07 2.23373259778158e-05 5.21205361806389e-06 2.97348829081045e-05 -7.01765443686938e-06 4.37705464040309e-06 -2.86153415619827e-06 1.58538703162283e-05 2.16113044920106e-06 -7.01765443686938e-06 2.01777296990629e-05 -4.68742825029172e-06 -2.71004295353727e-06 -1.70063759691567e-06 2.85583164484995e-06 4.37705464040309e-06 -4.68742825029172e-06 7.0771232485091e-05 6.18766975088464e-07 1.32075902350349e-05 -1.56303946535572e-07 -2.86153415619827e-06 -2.71004295353727e-06 6.18766975088464e-07 3.5838239820944e-05 -1.21749027950162e-05 2.23373259778158e-05 1.58538703162283e-05 -1.70063759691567e-06 1.32075902350349e-05 -1.21749027950162e-05 6.72318893135787e-05 2821 2821 0 0 3 2826 2830 0 0 5 0 0 0 0 0 0 0 0 61 0 18 35 0 0 2654 +2 46 0.999905422610508 -0.000108615831189461 -0.0137526010885849 -0.0327780151131541 0.000287617157534216 0.999915266347762 0.0130145073305044 0.0071062933463967 0.0137500221989356 -0.0130172319364094 0.999820728211934 0.000392275473238377 0.000103319626595624 -9.16939241113254e-06 4.48970804556236e-06 -5.7247090075772e-07 -1.07904189536557e-05 3.43790816018805e-05 -9.16939241113254e-06 0.000113653212780687 -4.39450437252815e-06 2.5333104574242e-05 1.67806235746919e-06 1.43035864817432e-05 4.48970804556236e-06 -4.39450437252815e-06 1.80061738253049e-05 2.84798924630984e-06 -1.0928444383346e-06 1.71040812446855e-06 -5.7247090075772e-07 2.5333104574242e-05 2.84798924630984e-06 9.8568518460652e-05 -4.7761269104111e-06 3.78552510444312e-06 -1.07904189536557e-05 1.67806235746919e-06 -1.0928444383346e-06 -4.7761269104111e-06 3.33308131648761e-05 -2.86512129285007e-06 3.43790816018805e-05 1.43035864817432e-05 1.71040812446855e-06 3.78552510444312e-06 -2.86512129285007e-06 7.58900377452681e-05 2881 2880 0 0 1 2887 2886 0 0 1 0 0 0 0 0 0 0 0 44 0 51 75 0 0 2550 +2 38 0.999925097221611 -0.000870972813338026 -0.0122082493711961 -0.0156330185168781 0.00103579595833409 0.999908318827453 0.0135011505579668 0.00174831893731724 0.0121953709694942 -0.0135127845396355 0.999834325066359 -0.00249739576490911 3.91213972428407e-05 2.59476585492338e-06 4.01774721735655e-06 -2.0786340086855e-07 -4.49538292660974e-06 1.60562683947696e-05 2.59476585492338e-06 5.71779822683221e-05 -5.11236291691203e-06 1.57771462837932e-05 1.41147295422028e-07 9.33046162976071e-07 4.01774721735655e-06 -5.11236291691203e-06 1.71428973347895e-05 -4.61961025948307e-06 4.00582697184024e-07 4.88572802086079e-07 -2.0786340086855e-07 1.57771462837932e-05 -4.61961025948307e-06 6.45987797614357e-05 6.34474557881784e-06 4.40088000723011e-07 -4.49538292660974e-06 1.41147295422028e-07 4.00582697184024e-07 6.34474557881784e-06 3.22367671364679e-05 9.48657363541399e-08 1.60562683947696e-05 9.33046162976071e-07 4.88572802086079e-07 4.40088000723011e-07 9.48657363541399e-08 7.87173092292815e-05 2812 2813 0 0 7 2812 2813 0 0 7 0 0 0 0 0 0 0 0 59 0 33 57 0 0 2839 +2 39 0.999963791510433 -0.000514050975493361 -0.00849419917787768 -0.016921393197847 0.000570329318124962 0.999977895716646 0.00662440960219108 3.24971793555478e-06 0.00849060613547411 -0.00662901423315025 0.999941981205784 0.00378759947791977 7.24894254268932e-05 4.13172606850814e-05 9.00821991413024e-06 1.4682479103807e-05 -9.71112930672488e-06 1.35979789439088e-05 4.13172606850814e-05 0.000143541768063237 5.17949566150596e-06 5.22188758875823e-05 -1.6197880306547e-05 4.4600860353053e-06 9.00821991413024e-06 5.17949566150596e-06 1.74687085470626e-05 1.36000896814096e-06 7.06928999560394e-07 2.88655835121173e-07 1.4682479103807e-05 5.22188758875823e-05 1.36000896814096e-06 9.36685887612324e-05 -7.28484187010556e-06 -2.35152412624775e-06 -9.71112930672488e-06 -1.6197880306547e-05 7.06928999560394e-07 -7.28484187010556e-06 3.27720133330036e-05 -4.48444209777138e-06 1.35979789439088e-05 4.4600860353053e-06 2.88655835121173e-07 -2.35152412624775e-06 -4.48444209777138e-06 6.72404918974112e-05 2705 2705 0 0 2 2710 2712 0 0 4 0 0 0 0 0 0 0 0 64 0 28 52 0 0 2668 +2 42 0.999965190240988 0.000490635928049173 -0.00832932066202525 -0.00575301967170808 -0.000419315309998643 0.999963255904321 0.00856218522923298 0.00176079020575963 0.00833321552436598 -0.00855839456995306 0.999928653155519 0.00269735721774523 5.18908567862651e-05 1.98296517363937e-05 5.79593394178303e-06 7.48856447367529e-06 -3.16045789306527e-06 1.8941682836932e-05 1.98296517363937e-05 0.000158259730775279 -2.93018961647582e-06 4.220227643775e-05 3.72175918768208e-07 6.68983458729955e-06 5.79593394178303e-06 -2.93018961647582e-06 1.62861622644596e-05 -1.41121021432286e-06 7.00384752651047e-07 3.29737382281608e-06 7.48856447367529e-06 4.220227643775e-05 -1.41121021432286e-06 7.0369611750185e-05 5.02794977993378e-06 -1.43674012038753e-05 -3.16045789306527e-06 3.72175918768208e-07 7.00384752651047e-07 5.02794977993378e-06 2.57217460001811e-05 -5.91927953899376e-06 1.8941682836932e-05 6.68983458729955e-06 3.29737382281608e-06 -1.43674012038753e-05 -5.91927953899376e-06 7.7310950286459e-05 2684 2685 0 0 7 2686 2687 0 0 9 0 0 0 0 0 0 0 0 63 0 25 49 0 0 2840 +2 40 0.999941543816956 -0.000232405867112042 -0.0108099461828372 -0.014055713292566 0.000339845154209026 0.999950557576186 0.00993815417197802 0.000269495350142142 0.0108071020275588 -0.00994124693324612 0.999892183265365 0.00752354571734529 5.08305496744431e-05 6.81300731527799e-07 3.74022854907374e-06 1.11452572512631e-05 -9.69869012020712e-06 1.55006370825437e-05 6.81300731527799e-07 5.0531144316044e-05 -5.95547133047044e-06 1.40366433764006e-05 3.21965539423178e-06 8.81578836991358e-06 3.74022854907374e-06 -5.95547133047044e-06 1.56955331365574e-05 1.0850614888346e-06 2.72616991566894e-07 2.19611489481556e-06 1.11452572512631e-05 1.40366433764006e-05 1.0850614888346e-06 6.58397633784815e-05 8.42211065023074e-06 -3.50297210266391e-06 -9.69869012020712e-06 3.21965539423178e-06 2.72616991566894e-07 8.42211065023074e-06 3.42545173309728e-05 -4.11839045437772e-06 1.55006370825437e-05 8.81578836991358e-06 2.19611489481556e-06 -3.50297210266391e-06 -4.11839045437772e-06 6.70804551343964e-05 2949 2949 0 0 3 2956 2964 0 0 6 0 0 0 0 0 0 0 0 65 0 15 18 0 0 2631 +2 41 0.999981131554038 0.000729994561428536 -0.00609947898151438 -0.00703809372002101 -0.000622452620430812 0.999844655980218 0.0176146660636725 0.00684910357658866 0.00611139007435867 -0.0176105370656225 0.999826244852384 -0.00274538885435737 8.32193034521147e-05 1.19403911783964e-05 7.94038877393487e-06 3.5578608164942e-06 -1.46534687031117e-05 2.97339115850454e-05 1.19403911783964e-05 6.30813636313559e-05 -3.66515556830504e-06 1.66652537291297e-05 -7.57842496957085e-06 1.269733234932e-05 7.94038877393487e-06 -3.66515556830504e-06 1.86051296669284e-05 -4.30133151675079e-06 -4.11342614489412e-07 5.42144686856366e-06 3.5578608164942e-06 1.66652537291297e-05 -4.30133151675079e-06 8.25674771329081e-05 1.0029291706811e-05 -2.26927593240781e-07 -1.46534687031117e-05 -7.57842496957085e-06 -4.11342614489412e-07 1.0029291706811e-05 3.84888031310512e-05 -1.03460055563275e-05 2.97339115850454e-05 1.269733234932e-05 5.42144686856366e-06 -2.26927593240781e-07 -1.03460055563275e-05 6.7202908597052e-05 2749 2750 0 0 8 2751 2752 0 0 11 0 0 0 0 0 0 0 0 88 0 24 48 0 0 2584 +2 52 0.9998656432269 0.00405765059504115 -0.0158817809488061 -0.00500144088202102 -0.00375898180339569 0.99981637418923 0.0187906348722682 0.00902903833375897 0.0159551104746736 -0.0187284108976102 0.999697294722253 -0.00185804646967528 7.29930392807673e-05 -6.77358370625989e-06 2.42350263342048e-06 6.73459567191603e-07 -2.87545249871271e-06 3.25724826028235e-05 -6.77358370625989e-06 3.12678908235017e-05 -4.02194413877118e-06 1.91980847895114e-06 -2.03250671630494e-06 1.36403069110752e-05 2.42350263342048e-06 -4.02194413877118e-06 1.6122658705558e-05 2.45189416414888e-06 -5.2126647529518e-06 3.06633686665057e-06 6.73459567191603e-07 1.91980847895114e-06 2.45189416414888e-06 5.82901428560456e-05 -3.68665105432056e-06 2.76599858491795e-06 -2.87545249871271e-06 -2.03250671630494e-06 -5.2126647529518e-06 -3.68665105432056e-06 3.55005947891432e-05 -1.03848219402459e-05 3.25724826028235e-05 1.36403069110752e-05 3.06633686665057e-06 2.76599858491795e-06 -1.03848219402459e-05 6.68378272710556e-05 2918 2919 0 0 4 2922 2927 0 0 6 0 0 0 0 0 0 0 0 58 0 32 34 0 0 2850 +2 51 0.99998920802848 -0.000788093365407081 -0.00457850799061204 -0.00980354824675938 0.000849527617929909 0.999909431777544 0.013431550362323 0.00268977462302924 0.00456750800755416 -0.0134352949784009 0.999899310290513 0.00310473845915168 8.64388721430394e-05 1.65245715771628e-06 3.153669292897e-06 -2.02419202608518e-08 -1.10362028334549e-05 4.23036025581368e-05 1.65245715771628e-06 3.46617114157321e-05 -7.76321591894201e-06 -2.51942576639998e-06 -5.7677731189354e-06 2.03882089593627e-05 3.153669292897e-06 -7.76321591894201e-06 1.75583203177557e-05 1.32191788497682e-06 1.18124127818664e-06 -3.35951018480927e-07 -2.02419202608518e-08 -2.51942576639998e-06 1.32191788497682e-06 6.79133350214321e-05 9.15043871182013e-07 5.74671567279899e-06 -1.10362028334549e-05 -5.7677731189354e-06 1.18124127818664e-06 9.15043871182013e-07 3.15572029704379e-05 -1.20335292409087e-05 4.23036025581368e-05 2.03882089593627e-05 -3.35951018480927e-07 5.74671567279899e-06 -1.20335292409087e-05 7.89288190719549e-05 2844 2844 0 0 8 2845 2845 0 0 9 0 0 0 0 0 0 0 0 65 0 25 49 0 0 2725 +2 43 0.999934847371457 -0.000573870755040207 -0.011400512469965 -0.0104307686323302 0.000724630120982957 0.999912294074678 0.0132241850222453 0.00370544166539056 0.0113919236044262 -0.0132315845865611 0.999847563004441 0.00276671809320541 6.09924355376137e-05 5.48197494934209e-06 2.72110455053865e-06 -5.59742701540096e-07 2.41466668392215e-06 1.79608339639797e-05 5.48197494934209e-06 4.96015111811792e-05 -2.40101801897729e-06 1.16246620450467e-05 -1.93543206168428e-06 -4.62343141558164e-06 2.72110455053865e-06 -2.40101801897729e-06 1.88856090618909e-05 -1.70531259664029e-06 -1.17733306716666e-06 2.89555032539951e-06 -5.59742701540096e-07 1.16246620450467e-05 -1.70531259664029e-06 6.88151482619132e-05 -1.03158418468059e-06 -3.00609610711015e-06 2.41466668392215e-06 -1.93543206168428e-06 -1.17733306716666e-06 -1.03158418468059e-06 3.36434888446902e-05 -1.08716119227587e-05 1.79608339639797e-05 -4.62343141558164e-06 2.89555032539951e-06 -3.00609610711015e-06 -1.08716119227587e-05 6.49868291892742e-05 2810 2811 0 0 6 2812 2813 0 0 8 0 0 0 0 0 0 0 0 18 0 26 50 0 0 2652 +2 50 0.999995044763105 -0.000856854198612347 -0.00302923259541593 -0.010355981129478 0.000894718019123321 0.999921217717512 0.0125202970409587 0.00265218237866739 0.00301826587647046 -0.0125229453089081 0.999917029513894 0.00597006151697105 0.000101244431062001 -4.82231377971054e-06 1.37069075654045e-05 -1.94577071245951e-05 -1.98050629409365e-05 5.98144043699851e-05 -4.82231377971054e-06 8.16120397398345e-05 -5.09088656301424e-06 2.18511803922245e-05 5.86697483519064e-06 -2.67402784376888e-06 1.37069075654045e-05 -5.09088656301424e-06 2.3013488653829e-05 -8.04614555095273e-06 -4.35021100475125e-06 1.16646216997099e-05 -1.94577071245951e-05 2.18511803922245e-05 -8.04614555095273e-06 8.09065871820981e-05 9.4516670438909e-06 -2.99846015549665e-05 -1.98050629409365e-05 5.86697483519064e-06 -4.35021100475125e-06 9.4516670438909e-06 3.84190583105776e-05 -2.66100691561615e-05 5.98144043699851e-05 -2.67402784376888e-06 1.16646216997099e-05 -2.99846015549665e-05 -2.66100691561615e-05 0.000111883953898384 2777 2779 0 0 6 2781 2788 0 0 8 0 0 0 0 0 0 0 0 57 0 30 34 0 0 2703 +2 45 0.999992761711587 -0.000720943780059982 0.00373587533249373 0.0032277402164532 0.000685651026570553 0.999955210265425 0.00943966872824351 0.00529032622318203 -0.00374251347408463 -0.00943703889444187 0.999948466617056 0.00991234697958569 6.07585659874354e-05 6.76045493869046e-06 6.70278942495222e-06 9.34235152050493e-06 -5.4625486813819e-06 3.8593517784321e-05 6.76045493869046e-06 4.51949637068096e-05 -1.10366119177095e-06 1.70805047535247e-05 -2.27580722448478e-07 7.27878343425421e-06 6.70278942495222e-06 -1.10366119177095e-06 1.98480291514218e-05 -2.74158955391546e-06 -4.51531356886921e-06 -6.46639144486908e-07 9.34235152050493e-06 1.70805047535247e-05 -2.74158955391546e-06 9.42947164469309e-05 7.15309677371899e-07 4.69739893232358e-06 -5.4625486813819e-06 -2.27580722448478e-07 -4.51531356886921e-06 7.15309677371899e-07 3.56185574141187e-05 -8.16687869351697e-06 3.8593517784321e-05 7.27878343425421e-06 -6.46639144486908e-07 4.69739893232358e-06 -8.16687869351697e-06 9.13475534893562e-05 2615 2619 0 0 11 2616 2622 0 0 15 0 0 0 0 0 0 0 0 28 0 10 26 0 0 2319 +2 36 0.999960132732727 -0.000815910669667201 -0.00889197587300396 -0.0164195006695359 0.000895471469396737 0.999959572256928 0.00894717735319006 -0.000763041700269939 0.00888431629302209 -0.00895478316438002 0.999920437226125 0.00572666969446802 5.02045245876868e-05 2.1274676546572e-06 1.02027041544244e-05 -1.49976089084971e-06 -8.91824058885873e-06 2.94056966374581e-05 2.1274676546572e-06 4.5183056886822e-05 -4.96697470358313e-06 1.12227236861137e-05 7.36854206604772e-07 9.34856933999557e-06 1.02027041544244e-05 -4.96697470358313e-06 2.19592005861897e-05 -7.49767580997712e-06 -4.07915289236582e-06 3.29733809791557e-06 -1.49976089084971e-06 1.12227236861137e-05 -7.49767580997712e-06 7.36946854721273e-05 1.43517342527887e-05 4.14436933811996e-07 -8.91824058885873e-06 7.36854206604772e-07 -4.07915289236582e-06 1.43517342527887e-05 4.25773854378267e-05 -1.33445335036498e-05 2.94056966374581e-05 9.34856933999557e-06 3.29733809791557e-06 4.14436933811996e-07 -1.33445335036498e-05 7.60214679954317e-05 2708 2708 0 0 3 2714 2718 0 0 3 0 0 0 0 0 0 0 0 55 0 23 38 0 0 2796 +2 49 0.999991224673335 0.000512227444007443 -0.0041579080520182 -0.0104856205368186 -0.000445332680591365 0.999870712575638 0.016073574969139 0.00947153936553524 0.00416560381301792 -0.0160715822659295 0.999862166495134 0.00202954755404168 5.02940427703557e-05 -2.88850348341984e-06 6.14466185841351e-06 1.22888562910695e-05 -4.80832148641716e-06 3.13035753006264e-05 -2.88850348341984e-06 2.4199755437701e-05 -7.86688003646669e-06 1.79345037885896e-06 -4.81928184770009e-06 1.17656258710058e-05 6.14466185841351e-06 -7.86688003646669e-06 1.51907527361367e-05 -1.32098481813492e-06 -9.3841423024599e-07 2.58165317434855e-06 1.22888562910695e-05 1.79345037885896e-06 -1.32098481813492e-06 5.3300181496883e-05 6.33880541570425e-06 4.36409249542636e-06 -4.80832148641716e-06 -4.81928184770009e-06 -9.3841423024599e-07 6.33880541570425e-06 3.12662394142805e-05 -1.47707946136046e-05 3.13035753006264e-05 1.17656258710058e-05 2.58165317434855e-06 4.36409249542636e-06 -1.47707946136046e-05 7.23873596187072e-05 3028 3028 0 0 1 3034 3039 0 0 7 0 0 0 0 0 0 0 0 60 0 16 32 0 0 2841 +2 32 0.999997248634107 0.000420902687165637 -0.00230771860158441 -0.00699790197889589 -0.000412098216880283 0.999992640328372 0.00381437598445643 0.00455923280804725 0.00230930709863502 -0.00381341448299166 0.999990062435975 0.0152581583433921 3.64384941901553e-05 -7.87239291678048e-06 4.1541848839748e-06 2.87031716983403e-06 1.96582613158242e-06 -4.00325149611772e-06 -7.87239291678048e-06 1.96650884617326e-05 -1.32919350615778e-06 1.78071595156291e-06 -2.06485062624198e-06 9.16837699032862e-06 4.1541848839748e-06 -1.32919350615778e-06 1.51616419662003e-05 -9.82780406969925e-07 1.34862966823968e-06 4.3159000793275e-06 2.87031716983403e-06 1.78071595156291e-06 -9.82780406969925e-07 4.91621990014564e-05 -1.39195292864438e-06 5.90497453954954e-06 1.96582613158242e-06 -2.06485062624198e-06 1.34862966823968e-06 -1.39195292864438e-06 2.13780477885369e-05 -3.75757731094785e-06 -4.00325149611772e-06 9.16837699032862e-06 4.3159000793275e-06 5.90497453954954e-06 -3.75757731094785e-06 3.49266584794421e-05 3008 3008 0 0 4 3011 3023 0 0 8 0 0 0 0 0 0 0 0 46 0 12 15 0 0 2658 +2 47 0.999965161733633 -2.36917758753841e-05 -0.00834714069179366 -0.0173209719524482 0.000171792049772817 0.999842577091189 0.0177423652070602 0.00748280423978758 0.00834540631248572 -0.0177431810662244 0.999807748379222 -0.000745198480996665 6.59389836597798e-05 -6.6892475138575e-06 -2.02488035786689e-06 -6.41708669933469e-06 -8.96619008367717e-07 2.95775457442e-05 -6.6892475138575e-06 3.40306481692393e-05 -4.4733973951941e-06 4.82534749661395e-08 -4.69973424707384e-06 6.48764895500435e-06 -2.02488035786689e-06 -4.4733973951941e-06 1.83914767382119e-05 3.14870041463488e-07 7.55774656033375e-07 1.29206614187862e-06 -6.41708669933469e-06 4.82534749661395e-08 3.14870041463488e-07 7.3828489504036e-05 6.20101862624735e-06 -1.99288455879623e-06 -8.96619008367717e-07 -4.69973424707384e-06 7.55774656033375e-07 6.20101862624735e-06 3.36630165059723e-05 -6.40660405370015e-06 2.95775457442e-05 6.48764895500435e-06 1.29206614187862e-06 -1.99288455879623e-06 -6.40660405370015e-06 6.42242050301365e-05 2986 2986 0 0 1 2988 2988 0 0 3 0 0 0 0 0 0 0 0 52 0 35 60 0 0 2757 +2 48 0.999916420044333 -0.000396535738971266 -0.0129226810349949 -0.0214221045158042 0.000531842226847173 0.999945060100387 0.0104687117010399 0.00383888021643915 0.0129178198458657 -0.0104747095540386 0.999861695631045 0.00652350194982436 4.80789637482225e-05 2.3989548376377e-06 1.79809967020566e-06 7.15416592615619e-06 -3.98370326073257e-06 2.74511981318881e-05 2.3989548376377e-06 8.49098102177031e-05 -2.06026653126948e-06 2.11246706751371e-05 3.65203097551239e-07 -4.23874173613042e-06 1.79809967020566e-06 -2.06026653126948e-06 1.48010721099088e-05 6.89265749253249e-07 1.69423719864719e-06 1.34733464279958e-06 7.15416592615619e-06 2.11246706751371e-05 6.89265749253249e-07 7.79848484466235e-05 2.01245025756176e-06 -8.38962595662604e-06 -3.98370326073257e-06 3.65203097551239e-07 1.69423719864719e-06 2.01245025756176e-06 2.93990119353166e-05 -1.06288093110405e-05 2.74511981318881e-05 -4.23874173613042e-06 1.34733464279958e-06 -8.38962595662604e-06 -1.06288093110405e-05 7.29179103660028e-05 2909 2908 0 0 3 2916 2918 0 0 5 0 0 0 0 0 0 0 0 38 0 36 43 0 0 2835 +2 29 0.999999989191247 -0.000121607226770534 8.26388976930354e-05 -0.00412399764332734 0.000121943104899341 0.999991683074299 -0.00407662999421402 -0.000115422346745489 -8.21424627232974e-05 0.0040766400273945 0.999991687094799 0.0260722112077286 4.65814004962614e-05 2.86629339626648e-06 4.38707986557312e-06 1.52142719131535e-05 -5.29751892520718e-06 4.67814486262095e-06 2.86629339626648e-06 7.97597523576768e-05 -5.30256648986182e-06 2.59037584892105e-05 -3.48177710158628e-06 5.4600277423615e-06 4.38707986557312e-06 -5.30256648986182e-06 1.29532523814196e-05 6.84157441687388e-07 2.00202519235901e-06 1.88458015847659e-06 1.52142719131535e-05 2.59037584892105e-05 6.84157441687388e-07 6.31364270633192e-05 -5.52427010487937e-06 4.91673211056668e-07 -5.29751892520718e-06 -3.48177710158628e-06 2.00202519235901e-06 -5.52427010487937e-06 2.64439878579489e-05 -6.87341052687303e-06 4.67814486262095e-06 5.4600277423615e-06 1.88458015847659e-06 4.91673211056668e-07 -6.87341052687303e-06 4.21187699252434e-05 2772 2771 0 0 9 2778 2782 0 0 11 0 0 0 0 0 0 0 0 61 0 29 33 0 0 2615 +2 30 0.999996705523511 -0.000898288786707856 -0.00240458299483513 -0.0122547648379951 0.00088467306705575 0.999983604940091 -0.00565749101506219 0.000528493269538274 0.0024096256322926 0.00565534510677803 0.999981105209511 0.0179372490569573 6.78200293634218e-05 1.69727017549993e-05 5.7480227517831e-06 6.81099968821607e-06 -1.2337787404864e-05 2.01167866550707e-06 1.69727017549993e-05 8.45152442745646e-05 -6.10771495463998e-06 3.03010047736997e-05 -4.2957629951784e-06 -2.91223142420029e-05 5.7480227517831e-06 -6.10771495463998e-06 1.5285402010938e-05 -5.67182148782961e-07 1.78122682852226e-06 3.5576069676311e-06 6.81099968821607e-06 3.03010047736997e-05 -5.67182148782961e-07 6.2683881642107e-05 -3.58388465295013e-06 -1.63615984183841e-05 -1.2337787404864e-05 -4.2957629951784e-06 1.78122682852226e-06 -3.58388465295013e-06 3.36459316205029e-05 -6.15899015943221e-06 2.01167866550707e-06 -2.91223142420029e-05 3.5576069676311e-06 -1.63615984183841e-05 -6.15899015943221e-06 5.6504241407491e-05 2694 2693 0 0 8 2702 2705 0 0 11 0 0 0 0 0 0 0 0 49 0 31 35 0 0 2675 +2 34 0.999995165881562 0.000727191488925167 -0.00302314505878703 -0.0076028062518331 -0.000703671668309834 0.99996953663289 0.00777371548147371 0.00869186341398653 0.00302870594334473 -0.00777155060088531 0.999965214365763 0.00895255723252536 4.19517749790777e-05 -6.5907010104001e-06 3.33747837310962e-06 -1.8033101443935e-06 -2.79071498762675e-07 -3.88867638077533e-06 -6.5907010104001e-06 2.86134651363135e-05 -4.07549346656368e-06 4.23372702162645e-07 3.99673508996598e-06 9.53164445363228e-07 3.33747837310962e-06 -4.07549346656368e-06 1.97760776842953e-05 -1.15274718322237e-06 -2.24887121199321e-06 -1.18317407559354e-06 -1.8033101443935e-06 4.23372702162645e-07 -1.15274718322237e-06 6.71651343020059e-05 7.42723756638628e-06 9.5936449509314e-06 -2.79071498762675e-07 3.99673508996598e-06 -2.24887121199321e-06 7.42723756638628e-06 2.69256942115167e-05 2.42371864410068e-06 -3.88867638077533e-06 9.53164445363228e-07 -1.18317407559354e-06 9.5936449509314e-06 2.42371864410068e-06 3.66994143597968e-05 2794 2794 0 0 5 2800 2803 0 0 10 0 0 0 0 0 0 0 0 49 0 13 33 0 0 2695 +2 35 0.999999493165868 -0.000648782379165329 -0.000769902222373536 -0.0194199899901101 0.000652581610515935 0.999987561738679 0.00494474520804459 0.00606594176866718 0.000766684582568062 -0.00494524512591116 0.999987478294301 0.00672995450535561 4.67662262738679e-05 -7.5664366485478e-06 7.57889377437165e-06 -1.13366987462159e-05 -6.11870322784907e-06 1.44826157743438e-05 -7.5664366485478e-06 4.59965888547966e-05 -5.02906176227469e-06 7.30192552419418e-06 -7.03796699800411e-08 -3.48561164182095e-06 7.57889377437165e-06 -5.02906176227469e-06 1.70897542489984e-05 -4.21863561636187e-06 -4.19698502835431e-07 2.81960538789573e-06 -1.13366987462159e-05 7.30192552419418e-06 -4.21863561636187e-06 6.48942210038479e-05 1.24823493047088e-05 -2.62870813359965e-06 -6.11870322784907e-06 -7.03796699800411e-08 -4.19698502835431e-07 1.24823493047088e-05 2.79950499646063e-05 -2.48455387270433e-06 1.44826157743438e-05 -3.48561164182095e-06 2.81960538789573e-06 -2.62870813359965e-06 -2.48455387270433e-06 4.61078422537032e-05 2658 2658 0 0 1 2668 2672 0 0 3 0 0 0 0 0 0 0 0 61 0 22 37 0 0 2823 +2 33 0.999999619468166 -0.000725423427837813 0.000484586807639036 -0.0117479255306232 0.000725570924416441 0.999999690483392 -0.000304269542767771 0.00327431226502784 -0.00048436593339667 0.000304621029081503 0.999999836297822 0.0136421378483197 5.51089111326653e-05 -9.35858146267704e-06 2.1148555022848e-06 -2.6897763508626e-06 -5.20810127787684e-06 8.45159755152878e-07 -9.35858146267704e-06 3.48096429844022e-05 -5.97167720269338e-06 -1.04124019521187e-06 1.73695103375659e-06 -7.0258300286193e-07 2.1148555022848e-06 -5.97167720269338e-06 1.43809861672936e-05 2.27027091374759e-06 2.94209421547376e-07 1.41728655665968e-06 -2.6897763508626e-06 -1.04124019521187e-06 2.27027091374759e-06 5.44916782155978e-05 -1.25677742608291e-06 6.42474783007592e-06 -5.20810127787684e-06 1.73695103375659e-06 2.94209421547376e-07 -1.25677742608291e-06 2.92235393813947e-05 -2.79137724391254e-06 8.45159755152878e-07 -7.0258300286193e-07 1.41728655665968e-06 6.42474783007592e-06 -2.79137724391254e-06 3.59444693274916e-05 2757 2757 0 0 4 2761 2771 0 0 8 0 0 0 0 0 0 0 0 50 0 13 16 0 0 2633 +2 31 0.999924618252512 -0.000255977241707815 -0.0122756787274944 -0.0155566800081909 0.000306350916723845 0.999991540534134 0.00410182999222223 0.0040862294720523 0.0122745249066819 -0.0041052814545411 0.999916237843198 0.0197809883813119 3.44810599684777e-05 -6.201324893728e-06 2.8206436247563e-06 3.63806719132755e-06 -3.0799944105565e-06 -8.75136375818753e-06 -6.201324893728e-06 4.14642676340072e-05 -5.8116894016903e-06 9.17644753913343e-06 -7.69542480569039e-07 -1.23058590024508e-05 2.8206436247563e-06 -5.8116894016903e-06 1.30580555502018e-05 4.60465740994265e-07 5.39988198031197e-06 2.86357092822981e-06 3.63806719132755e-06 9.17644753913343e-06 4.60465740994265e-07 5.38309743901477e-05 1.30794333189045e-06 -1.86091320799611e-07 -3.0799944105565e-06 -7.69542480569039e-07 5.39988198031197e-06 1.30794333189045e-06 2.36965395937392e-05 1.95664847648693e-06 -8.75136375818753e-06 -1.23058590024508e-05 2.86357092822981e-06 -1.86091320799611e-07 1.95664847648693e-06 3.62170507800027e-05 2986 2986 0 0 2 2997 3001 0 0 6 0 0 0 0 0 0 0 0 54 0 19 38 0 0 2642 +3 6 0.999998675635282 5.75835444618714e-05 0.00162647220001016 0.00160487561921614 -5.67955307577246e-05 0.999999881000234 -0.000484534607914364 -0.00048832390623775 -0.00162649990768048 0.000484441589861962 0.999998559906161 0.0135696416675547 2.31614264011646e-05 8.14705144937261e-07 2.67422727431391e-06 3.99299723793772e-06 1.57473038993346e-06 3.13916020057759e-06 8.14705144937261e-07 6.97106497815782e-05 -3.19911609207572e-06 1.24938465267323e-05 4.68985368759471e-08 -1.03131228442006e-05 2.67422727431391e-06 -3.19911609207572e-06 1.48688432130996e-05 1.25899827046433e-06 3.23759655452833e-06 1.57399495997005e-06 3.99299723793772e-06 1.24938465267323e-05 1.25899827046433e-06 4.62495427528274e-05 2.56377029628485e-06 1.19557704698669e-06 1.57473038993346e-06 4.68985368759471e-08 3.23759655452833e-06 2.56377029628485e-06 1.87992385837259e-05 3.3206001642023e-07 3.13916020057759e-06 -1.03131228442006e-05 1.57399495997005e-06 1.19557704698669e-06 3.3206001642023e-07 3.28434280921325e-05 2691 2705 0 0 16 2691 2705 0 0 17 0 0 0 0 0 0 0 0 59 0 26 31 0 0 3073 +3 46 0.999974569678899 0.000448711952511839 -0.00711748924015909 -0.0276282300833013 -0.000402091133284202 0.999978465997729 0.00655025675444818 0.00514339822263359 0.00712027515062737 -0.00654722830000091 0.999953216647342 0.0036009470807061 2.99954792382931e-05 5.17301265751572e-07 1.05075582873414e-06 7.84754347126468e-06 -1.19708013584008e-06 2.71146054591856e-05 5.17301265751572e-07 4.10126472011344e-05 -6.40597335578934e-06 1.30141573843545e-05 1.21223658314357e-06 1.05626924197665e-05 1.05075582873414e-06 -6.40597335578934e-06 2.05840209907057e-05 -6.44235224422793e-06 -1.06675642384763e-06 -6.36787359508234e-07 7.84754347126468e-06 1.30141573843545e-05 -6.44235224422793e-06 7.88537095855059e-05 4.0800189422151e-06 7.64839872837412e-06 -1.19708013584008e-06 1.21223658314357e-06 -1.06675642384763e-06 4.0800189422151e-06 3.28272472762599e-05 -5.77642126774996e-06 2.71146054591856e-05 1.05626924197665e-05 -6.36787359508234e-07 7.64839872837412e-06 -5.77642126774996e-06 8.77708236939076e-05 3088 3104 0 0 10 3093 3109 0 0 12 0 0 0 0 0 0 0 0 47 0 24 26 0 0 2916 +3 39 0.999944099765546 0.000182095252893716 -0.0105718581806218 -0.0146654201035855 -7.64808618345587e-05 0.999950098883128 0.00998968939957506 0.00134344698804198 0.0105731497081087 -0.00998832242877065 0.99989421536496 0.00691137565528736 5.65893020693643e-05 -7.50109299695071e-07 5.1040752527644e-06 8.5919870408003e-06 -1.26604967811117e-05 2.31189386933212e-05 -7.50109299695071e-07 3.61662347065867e-05 -1.89642608141628e-06 8.77034650155918e-06 -9.8019430467577e-07 4.09946336332996e-06 5.1040752527644e-06 -1.89642608141628e-06 1.73611488196589e-05 -4.27899799446506e-06 -5.26425844281403e-07 1.28163469977391e-06 8.5919870408003e-06 8.77034650155918e-06 -4.27899799446506e-06 8.11334130591948e-05 7.3838097103655e-06 2.44183843585062e-05 -1.26604967811117e-05 -9.8019430467577e-07 -5.26425844281403e-07 7.3838097103655e-06 4.01048599573251e-05 -7.44155701497966e-06 2.31189386933212e-05 4.09946336332996e-06 1.28163469977391e-06 2.44183843585062e-05 -7.44155701497966e-06 6.60947139411069e-05 2977 2993 0 0 6 2980 2996 0 0 9 0 0 0 0 0 0 0 0 63 0 24 34 0 0 2684 +3 41 0.999953659362207 0.000890140472150458 -0.00958575912857036 -0.00370951128858538 -0.000777533138580621 0.999930726532862 0.0117446829536003 0.00412664117323002 0.00959554950742996 -0.0117366854521206 0.999885081218961 -0.00652611299180105 7.12738126244089e-05 1.00063339500045e-05 9.64432002482881e-07 1.49905530881901e-05 -1.18075512765896e-05 3.13313956990228e-05 1.00063339500045e-05 4.68452735908689e-05 -3.19604235220793e-06 8.76157693616909e-06 -7.68536097913827e-06 1.82007744343175e-05 9.64432002482881e-07 -3.19604235220793e-06 1.60304708208633e-05 -2.1355341317257e-06 4.30875963290441e-07 1.96302696792389e-06 1.49905530881901e-05 8.76157693616909e-06 -2.1355341317257e-06 7.62247463517771e-05 5.21183714092134e-06 3.98055755343955e-06 -1.18075512765896e-05 -7.68536097913827e-06 4.30875963290441e-07 5.21183714092134e-06 3.30609452825553e-05 -7.50803142362958e-06 3.13313956990228e-05 1.82007744343175e-05 1.96302696792389e-06 3.98055755343955e-06 -7.50803142362958e-06 7.51614828733144e-05 2812 2831 0 0 19 2814 2834 0 0 24 0 0 0 0 0 0 0 0 91 0 12 15 0 0 2591 +2 28 0.999997726881232 -0.000559875588578202 0.0020573700917266 -0.00783748098433512 0.000562997863441034 0.999998690356684 -0.00151733922433194 0.00385187977401906 -0.00205651787611431 0.00151849407020562 0.999996732449654 0.0156934500027386 6.54919289913937e-05 6.44035955663659e-06 7.162604355657e-06 6.1369790832725e-06 -3.25570360725981e-06 1.2036718029898e-05 6.44035955663659e-06 4.15225410152183e-05 -3.29150562163705e-06 6.41867245764912e-06 -1.79334053694653e-07 3.41871857241561e-06 7.162604355657e-06 -3.29150562163705e-06 1.50380325978103e-05 1.51341147439967e-06 2.95162913073103e-06 1.37708647098488e-06 6.1369790832725e-06 6.41867245764912e-06 1.51341147439967e-06 4.99699191815803e-05 1.24088043813507e-06 1.65179280321056e-06 -3.25570360725981e-06 -1.79334053694653e-07 2.95162913073103e-06 1.24088043813507e-06 2.51132312234963e-05 -2.64588052028964e-06 1.2036718029898e-05 3.41871857241561e-06 1.37708647098488e-06 1.65179280321056e-06 -2.64588052028964e-06 4.21132561928499e-05 2801 2801 0 0 3 2806 2806 0 0 9 0 0 0 0 0 0 0 0 68 0 28 52 0 0 2758 +3 51 0.999978661881895 -0.00020999738614677 -0.00652929414201394 -0.0037342054438802 0.000249817755335797 0.999981372724322 0.00609850764284619 0.000720907563819883 0.00652789184838758 -0.00610000864577633 0.999960087464763 0.0075019781282897 2.78471743991377e-05 -1.77701364952551e-06 7.07455791170048e-06 5.63709636024102e-06 -1.67639061826294e-06 2.04427058945955e-05 -1.77701364952551e-06 4.92114959426621e-05 -5.35962676114418e-06 4.85105516657056e-06 -7.90282047339123e-07 -2.4743764137651e-06 7.07455791170048e-06 -5.35962676114418e-06 1.9225330382092e-05 1.02571839822345e-06 -2.04479215746345e-06 4.92970655170098e-06 5.63709636024102e-06 4.85105516657056e-06 1.02571839822345e-06 5.67354533624612e-05 4.90200075353175e-06 -1.63560450129344e-06 -1.67639061826294e-06 -7.90282047339123e-07 -2.04479215746345e-06 4.90200075353175e-06 3.13660974733287e-05 -9.95971065628199e-06 2.04427058945955e-05 -2.4743764137651e-06 4.92970655170098e-06 -1.63560450129344e-06 -9.95971065628199e-06 6.47056509325403e-05 2759 2776 0 0 20 2759 2777 0 0 22 0 0 0 0 0 0 0 0 69 0 10 13 0 0 3094 +3 5 0.999999260077594 2.991746687075e-05 0.00121612055739032 0.000874376364184184 -2.42845001899784e-05 0.999989273484532 -0.00463166559023845 -0.00268364456622601 -0.0012162460803562 0.00463163263028539 0.999988534296594 0.0103588932152997 4.11773491273213e-05 -2.21265427431893e-06 1.06717430132932e-05 -5.49786936827833e-06 2.00599209659239e-07 7.79271660646672e-06 -2.21265427431893e-06 8.15942211518101e-05 -4.05599442905042e-06 2.28320311250472e-05 8.1380252532461e-07 -2.86526229649678e-05 1.06717430132932e-05 -4.05599442905042e-06 1.95816164408365e-05 -5.37699411004489e-06 1.47093104040362e-06 4.9265019729036e-06 -5.49786936827833e-06 2.28320311250472e-05 -5.37699411004489e-06 6.03912796780099e-05 4.32603055593396e-06 -1.81540413274073e-05 2.00599209659239e-07 8.1380252532461e-07 1.47093104040362e-06 4.32603055593396e-06 2.29615903496277e-05 1.8998458426539e-06 7.79271660646672e-06 -2.86526229649678e-05 4.9265019729036e-06 -1.81540413274073e-05 1.8998458426539e-06 4.36321308342405e-05 2584 2584 0 0 10 2586 2596 0 0 12 0 0 0 0 0 0 0 0 74 0 8 9 0 0 2635 +3 36 0.999991670402541 0.000911290371045785 -0.00397852678701425 -0.0112377001102361 -0.000864726151272129 0.999931296198048 0.0116899586130821 -0.00013392190334047 0.00398890639381984 -0.0116864209042763 0.999923755189479 0.00358929491447763 7.3031657126373e-05 -6.92724873536267e-06 5.65955815235981e-06 -1.03339079256555e-06 -7.67390603688922e-06 2.63721919289736e-05 -6.92724873536267e-06 3.17909160001329e-05 -4.99651722889095e-06 9.6405212213099e-06 -4.06678214557402e-06 1.83911932648828e-05 5.65955815235981e-06 -4.99651722889095e-06 1.98845702152843e-05 -5.57381238863361e-06 -5.03435118947288e-06 3.42802820420326e-06 -1.03339079256555e-06 9.6405212213099e-06 -5.57381238863361e-06 7.26951167867197e-05 7.15157673211568e-06 1.30934721272116e-05 -7.67390603688922e-06 -4.06678214557402e-06 -5.03435118947288e-06 7.15157673211568e-06 3.85577992479418e-05 -8.68028922179752e-06 2.63721919289736e-05 1.83911932648828e-05 3.42802820420326e-06 1.30934721272116e-05 -8.68028922179752e-06 7.1547882492094e-05 2789 2797 0 0 6 2791 2799 0 0 8 0 0 0 0 0 0 0 0 63 0 24 35 0 0 2354 +3 53 0.998522866847505 0.00981559006655379 -0.0534391109047058 -0.00279287396990907 -0.00978586900523475 0.999951782818326 0.000817805761048589 -0.00274539407444709 0.0534445614674914 -0.000293649613976979 0.998570774967629 -0.00695487518437323 5.80197071942527e-05 -7.81462528650679e-07 2.05907565119319e-06 7.9493414118927e-06 -9.97012797225822e-06 2.6599498512249e-05 -7.81462528650679e-07 3.73856462114288e-05 -4.47945493474482e-06 5.75960301570506e-06 1.24187610906224e-06 1.56548729643787e-05 2.05907565119319e-06 -4.47945493474482e-06 1.56852798367914e-05 4.13342583838436e-07 4.92614122937004e-08 1.60486615434177e-06 7.9493414118927e-06 5.75960301570506e-06 4.13342583838436e-07 7.30717868533909e-05 -9.60757664595547e-07 1.20200999959362e-05 -9.97012797225822e-06 1.24187610906224e-06 4.92614122937004e-08 -9.60757664595547e-07 3.39464040517646e-05 -7.16451615902927e-06 2.6599498512249e-05 1.56548729643787e-05 1.60486615434177e-06 1.20200999959362e-05 -7.16451615902927e-06 6.96136452121758e-05 2616 2619 0 0 0 2617 2620 0 0 0 0 0 0 0 0 0 0 0 56 0 37 50 0 0 2652 +3 37 0.999995793160558 -0.000145384143580544 -0.00289698543940875 -0.0112111409912353 0.000196328103065637 0.999845218169989 0.0175926449939236 0.00733351116068539 0.00289397934707517 -0.0175931397441467 0.999841040524683 -0.00995705071061321 6.54381704698429e-05 7.18814973630875e-06 6.88911002873661e-06 -1.26861655623145e-05 -1.18085163958107e-05 3.32397740162057e-05 7.18814973630875e-06 4.84866481360239e-05 -4.72186367070671e-06 1.20288441473843e-05 -5.68568024917153e-07 1.01931956534007e-05 6.88911002873661e-06 -4.72186367070671e-06 1.78405748108929e-05 -4.83744671025639e-06 1.84470144224291e-06 -3.87779190208731e-07 -1.26861655623145e-05 1.20288441473843e-05 -4.83744671025639e-06 7.92326185017224e-05 1.56271279913201e-05 1.89896442132619e-07 -1.18085163958107e-05 -5.68568024917153e-07 1.84470144224291e-06 1.56271279913201e-05 3.97621323716033e-05 -1.54652517983661e-05 3.32397740162057e-05 1.01931956534007e-05 -3.87779190208731e-07 1.89896442132619e-07 -1.54652517983661e-05 7.93708187047628e-05 2953 2964 0 0 5 2955 2966 0 0 7 0 0 0 0 0 0 0 0 65 0 16 26 0 0 2656 +3 45 0.999964125270816 -0.000628781155787959 -0.0084470589929044 -0.0127868374680003 0.000648190751015428 0.999997155829222 0.00229525210337618 0.000208894094380129 0.00844559175675566 -0.00230064506734104 0.999961688772201 0.0118921996851258 7.07562046294105e-05 -9.22242816565586e-06 1.24365693396408e-05 1.65364093660922e-06 -1.53118739220993e-05 2.9182360460947e-05 -9.22242816565586e-06 0.000115028157157725 -9.35338340180674e-07 4.40803194221136e-05 -1.35745121506897e-06 -9.58275130231097e-06 1.24365693396408e-05 -9.35338340180674e-07 2.15886437675769e-05 1.58495408722367e-06 -7.73525572409472e-06 5.15140004375945e-06 1.65364093660922e-06 4.40803194221136e-05 1.58495408722367e-06 0.000111150439091248 8.11489994914992e-08 5.41721020494721e-06 -1.53118739220993e-05 -1.35745121506897e-06 -7.73525572409472e-06 8.11489994914992e-08 4.51329049337611e-05 -7.99811125225824e-06 2.9182360460947e-05 -9.58275130231097e-06 5.15140004375945e-06 5.41721020494721e-06 -7.99811125225824e-06 7.14076554991732e-05 2744 2754 0 0 8 2747 2757 0 0 11 0 0 0 0 0 0 0 0 28 0 21 32 0 0 2326 +3 48 0.999966575799028 -0.000585616329158909 -0.00815501920798596 -0.0214015809687672 0.00071655959422602 0.99987072306355 0.0160631162207336 0.00502701518386285 0.00814455812893003 -0.0160684228811633 0.999837722812556 0.000213222514388564 6.24669024221374e-05 1.05386844024129e-06 1.33114610025565e-06 5.93744939882931e-06 -6.42044198256166e-06 2.74637692236083e-05 1.05386844024129e-06 4.40588588597937e-05 -1.77452216908271e-06 -1.37162819536285e-06 1.09721504521457e-06 1.55182806735922e-05 1.33114610025565e-06 -1.77452216908271e-06 1.79567923303547e-05 -4.17215806428061e-06 -9.26669867523627e-07 5.73647649946433e-07 5.93744939882931e-06 -1.37162819536285e-06 -4.17215806428061e-06 9.85047501102091e-05 4.38188732843289e-06 2.0264968381945e-06 -6.42044198256166e-06 1.09721504521457e-06 -9.26669867523627e-07 4.38188732843289e-06 3.40818189813886e-05 -4.85863176671905e-06 2.74637692236083e-05 1.55182806735922e-05 5.73647649946433e-07 2.0264968381945e-06 -4.85863176671905e-06 7.22986406536516e-05 3079 3087 0 0 4 3081 3089 0 0 5 0 0 0 0 0 0 0 0 40 0 37 47 0 0 2398 +3 38 0.999979408359333 0.000111941923223607 -0.00641641070418717 -0.0127821264564596 -2.17823005472126e-06 0.99985371302757 0.0171041673354172 0.00404141280956222 0.00641738674027805 -0.0171038011561309 0.999833124643026 -0.00462603950317497 5.96919141132062e-05 -3.74048524749763e-06 1.92871995034266e-06 6.18239077095124e-07 -6.29446512022093e-06 2.05024876919799e-05 -3.74048524749763e-06 3.22972802371586e-05 -4.72537624131334e-06 7.76094883704305e-07 1.39456111444831e-06 1.45305328087175e-05 1.92871995034266e-06 -4.72537624131334e-06 1.68337049292734e-05 -9.29506468472293e-07 -2.63442103289611e-07 1.19031798333404e-06 6.18239077095124e-07 7.76094883704305e-07 -9.29506468472293e-07 5.6750179184963e-05 8.11971034167488e-06 4.03252920144152e-06 -6.29446512022093e-06 1.39456111444831e-06 -2.63442103289611e-07 8.11971034167488e-06 3.59497776116592e-05 -4.36817233066561e-06 2.05024876919799e-05 1.45305328087175e-05 1.19031798333404e-06 4.03252920144152e-06 -4.36817233066561e-06 7.74956307790107e-05 3042 3060 0 0 15 3045 3063 0 0 18 0 0 0 0 0 0 0 0 66 0 17 19 0 0 2392 +3 43 0.999978200195936 -0.000517702386640979 -0.00658263755154704 -0.00714300421047583 0.000618855146194851 0.999881623707283 0.0153738606340886 0.00679002715710999 0.00657389923897523 -0.0153775991860634 0.999860146866585 0.00107640290298875 6.89657798386957e-05 8.03993990850988e-06 8.75888568756395e-06 -1.65266298270496e-06 -1.26330382711744e-05 4.991683825222e-05 8.03993990850988e-06 2.53289828743973e-05 -6.30128279830378e-06 -2.73634030055522e-06 -5.14591960086484e-06 1.22349184506459e-05 8.75888568756395e-06 -6.30128279830378e-06 1.81167098811893e-05 -1.68505257147757e-06 1.57541308280805e-06 4.06803505544807e-06 -1.65266298270496e-06 -2.73634030055522e-06 -1.68505257147757e-06 6.40111397497268e-05 6.9282833880181e-06 -8.69312747581346e-06 -1.26330382711744e-05 -5.14591960086484e-06 1.57541308280805e-06 6.9282833880181e-06 2.88577005971315e-05 -1.90287171024077e-05 4.991683825222e-05 1.22349184506459e-05 4.06803505544807e-06 -8.69312747581346e-06 -1.90287171024077e-05 8.62599078195959e-05 3054 3073 0 0 18 3054 3074 0 0 20 0 0 0 0 0 0 0 0 18 0 13 15 0 0 2642 +3 50 0.999971870123946 0.000241246092502934 -0.00749671669067786 -0.00646407596541928 -0.000204459279995232 0.99998793756367 0.00490743553801677 -0.000286927804445975 0.00749781016165785 -0.00490576471916644 0.999959857351934 0.0104385875025472 3.34021794129986e-05 4.92957211528034e-06 7.41255850733084e-06 3.35036969195002e-06 -5.23713824322026e-06 2.38928147297779e-05 4.92957211528034e-06 5.60566670539743e-05 -5.26868341823158e-06 2.06776931512317e-05 -1.03317202678273e-06 9.8055243848025e-06 7.41255850733084e-06 -5.26868341823158e-06 2.60520118936018e-05 -1.12359778672589e-05 -5.72449199188115e-06 4.12530362805012e-06 3.35036969195002e-06 2.06776931512317e-05 -1.12359778672589e-05 9.62382978901891e-05 1.59559621873282e-05 -8.84494056843043e-07 -5.23713824322026e-06 -1.03317202678273e-06 -5.72449199188115e-06 1.59559621873282e-05 3.75607977241875e-05 -1.73688074686415e-05 2.38928147297779e-05 9.8055243848025e-06 4.12530362805012e-06 -8.84494056843043e-07 -1.73688074686415e-05 7.51557623659173e-05 2811 2822 0 0 11 2812 2823 0 0 13 0 0 0 0 0 0 0 0 59 0 28 36 0 0 3078 +3 47 0.99998413204899 0.000215105586318113 -0.00562933209322511 -0.0151079048313705 -0.000120936971902674 0.999860150185652 0.0167232007993223 0.00867348986534039 0.00563214208609002 -0.016722254642014 0.99984431046799 -8.45681303093026e-05 6.74247893140187e-05 -5.7894743679639e-06 -2.78630348348365e-06 1.81333989833809e-07 -1.10614724723391e-05 3.92065661751452e-05 -5.7894743679639e-06 3.1433495425188e-05 -1.93113256650665e-06 9.84884008468487e-07 1.53290484537346e-08 1.21700529943505e-05 -2.78630348348365e-06 -1.93113256650665e-06 1.73827279912209e-05 -4.99565084750647e-06 -9.20690042445004e-07 2.37664933075257e-06 1.81333989833809e-07 9.84884008468487e-07 -4.99565084750647e-06 7.68911057271092e-05 6.87039206890889e-06 -1.38878530808205e-06 -1.10614724723391e-05 1.53290484537346e-08 -9.20690042445004e-07 6.87039206890889e-06 3.00529048945807e-05 -1.54141112388511e-05 3.92065661751452e-05 1.21700529943505e-05 2.37664933075257e-06 -1.38878530808205e-06 -1.54141112388511e-05 7.82652485902296e-05 2869 2888 0 0 12 2871 2890 0 0 14 0 0 0 0 0 0 0 0 56 0 18 21 0 0 2653 +3 40 0.999993570569853 0.000405106067648397 -0.00356296337771518 -0.00887437263529664 -0.000371188933021436 0.999954663647987 0.00951487611156194 0.00368655035453127 0.00356665637999899 -0.00951349240375605 0.999948384880215 0.00163091839971736 4.56699612363043e-05 -5.29288785459357e-06 1.81767907267061e-06 9.8651853872877e-06 -5.20380081315595e-06 2.93665714853293e-05 -5.29288785459357e-06 2.39352161497593e-05 -3.00906767963858e-06 1.31137009633912e-06 -2.64053201105118e-06 1.33129188428575e-05 1.81767907267061e-06 -3.00906767963858e-06 1.53369760002146e-05 -1.16869636499731e-06 -2.26060342133854e-06 1.92536815601117e-06 9.8651853872877e-06 1.31137009633912e-06 -1.16869636499731e-06 5.91384474723579e-05 6.58142115500454e-06 1.48172405907273e-05 -5.20380081315595e-06 -2.64053201105118e-06 -2.26060342133854e-06 6.58142115500454e-06 3.06876831104778e-05 -9.28921179246934e-06 2.93665714853293e-05 1.33129188428575e-05 1.92536815601117e-06 1.48172405907273e-05 -9.28921179246934e-06 7.44181674190832e-05 3114 3114 0 0 6 3118 3127 0 0 8 0 0 0 0 0 0 0 0 79 0 13 16 0 0 2626 +3 44 0.999951449705516 0.000441823272409116 -0.00984393336189129 -0.0331581560094428 -0.000180352799800689 0.999647559157905 0.0265466559572052 0.00608932029297203 0.00985219288813423 -0.0265435917282981 0.999599105658592 -0.00600349220043274 7.65766004599604e-05 1.87719894376004e-06 -2.242624462237e-06 7.14153486177967e-06 -1.11950886146252e-05 2.87645581616454e-05 1.87719894376004e-06 0.000123550851795171 -4.3545979492137e-06 5.2139042771521e-05 -3.81722671360169e-06 2.01788066204832e-06 -2.242624462237e-06 -4.3545979492137e-06 2.0727044187945e-05 -1.79794537662615e-06 -1.40012442190273e-06 -3.15409426118324e-07 7.14153486177967e-06 5.2139042771521e-05 -1.79794537662615e-06 0.000134960093550478 -4.69097013336417e-06 -1.76558301460894e-05 -1.11950886146252e-05 -3.81722671360169e-06 -1.40012442190273e-06 -4.69097013336417e-06 4.41294678390424e-05 -3.88206242573416e-06 2.87645581616454e-05 2.01788066204832e-06 -3.15409426118324e-07 -1.76558301460894e-05 -3.88206242573416e-06 7.07181370432088e-05 2533 2538 0 0 2 2535 2540 0 0 2 0 0 0 0 0 0 0 0 27 0 46 58 0 0 2117 +3 35 0.999925701342986 0.000623728096748957 -0.0121738554697997 -0.0245875322649647 -0.000525347824065182 0.999967195635312 0.00808280043752118 0.00227285929469048 0.0121784975839385 -0.00807580438782221 0.999893227089817 0.00714004875060385 4.06372411708422e-05 -1.26232739420472e-06 -1.05879476683178e-06 6.42288646238777e-06 -2.53701317967959e-06 -1.87668731903209e-06 -1.26232739420472e-06 0.000113655794587733 -4.63459644060312e-06 4.82790417544249e-05 -4.00740965341574e-06 -3.74731260396692e-05 -1.05879476683178e-06 -4.63459644060312e-06 1.68051287024314e-05 1.95818115904868e-06 2.32914589895343e-06 -2.36277338263469e-08 6.42288646238777e-06 4.82790417544249e-05 1.95818115904868e-06 8.82316676670534e-05 3.17340149559209e-06 -3.15959434650143e-05 -2.53701317967959e-06 -4.00740965341574e-06 2.32914589895343e-06 3.17340149559209e-06 2.72883141602045e-05 4.52543607006468e-06 -1.87668731903209e-06 -3.74731260396692e-05 -2.36277338263469e-08 -3.15959434650143e-05 4.52543607006468e-06 6.48557602186744e-05 2533 2541 0 0 4 2534 2542 0 0 4 0 0 0 0 0 0 0 0 57 0 31 42 0 0 2586 +3 42 0.999933391152983 -0.000571746025893605 -0.0115276347868238 -0.0107756321702935 0.000662933319832339 0.999968511117266 0.0079080524360827 0.000576683515003401 0.0115227503969309 -0.00791516774302682 0.999902283397178 0.00494924011180431 5.64355932615652e-05 1.50772254231146e-06 7.14242246962617e-06 3.08694494379717e-06 -8.59153696606881e-06 1.00188785381809e-05 1.50772254231146e-06 4.41115192686715e-05 2.59647263510197e-07 2.9788743600312e-06 -1.95687145411199e-06 6.54034722424319e-06 7.14242246962617e-06 2.59647263510197e-07 1.43381370625358e-05 1.16356961225562e-06 9.49782759412488e-07 2.36005867080636e-06 3.08694494379717e-06 2.9788743600312e-06 1.16356961225562e-06 5.9027966586343e-05 6.7798472611088e-06 -3.67745958574461e-06 -8.59153696606881e-06 -1.95687145411199e-06 9.49782759412488e-07 6.7798472611088e-06 2.70387096643645e-05 -3.1005504918427e-06 1.00188785381809e-05 6.54034722424319e-06 2.36005867080636e-06 -3.67745958574461e-06 -3.1005504918427e-06 6.61703324890079e-05 2969 2987 0 0 16 2971 2990 0 0 19 0 0 0 0 0 0 0 0 54 0 12 16 0 0 2614 +3 52 0.999946763932791 0.00385303057792315 -0.00957201419262201 -0.000195143004092175 -0.00364258441724265 0.999753386772608 0.0219065564492084 0.0106158575721645 0.00965406023916513 -0.0218705233605573 0.999714198823261 -0.00215822338614546 4.69368072568312e-05 -3.84034848681443e-06 4.67131750291765e-06 6.79758282147526e-06 -7.02044714090658e-06 2.56857417878689e-05 -3.84034848681443e-06 4.3751407353291e-05 -2.11770117529465e-06 6.97437020682944e-06 4.29164679696384e-06 2.55820090472096e-06 4.67131750291765e-06 -2.11770117529465e-06 2.15921660830474e-05 -2.94469872106237e-06 -4.27157141289118e-06 2.68248808887383e-06 6.79758282147526e-06 6.97437020682944e-06 -2.94469872106237e-06 6.75974446655583e-05 4.25716496793502e-06 8.50630483058884e-06 -7.02044714090658e-06 4.29164679696384e-06 -4.27157141289118e-06 4.25716496793502e-06 3.70578096577234e-05 -1.09623912791376e-05 2.56857417878689e-05 2.55820090472096e-06 2.68248808887383e-06 8.50630483058884e-06 -1.09623912791376e-05 6.05726321920948e-05 2746 2758 0 0 7 2747 2759 0 0 8 0 0 0 0 0 0 0 0 63 0 28 31 0 0 2726 +3 34 0.999999700515109 0.000349922344581304 0.000690307211058554 -0.007046565498904 -0.000352859146319576 0.999990868947735 0.0042588157481336 0.0060059017473218 -0.000688810653035604 -0.00425905805389582 0.999990692938878 0.00681749029326541 2.15759036857191e-05 -2.09484803662968e-06 2.70953091038691e-06 3.59358884023156e-06 7.8240831240766e-07 8.22724022549912e-07 -2.09484803662968e-06 4.83743253753437e-05 -3.12571078942178e-06 1.73739698577339e-05 5.86711812361488e-06 -5.93061856375383e-06 2.70953091038691e-06 -3.12571078942178e-06 1.70231479882339e-05 -4.32914607646365e-06 -1.65720720280751e-06 -9.14233729375267e-07 3.59358884023156e-06 1.73739698577339e-05 -4.32914607646365e-06 8.34290253901641e-05 1.19965429101974e-05 1.35560874809617e-05 7.8240831240766e-07 5.86711812361488e-06 -1.65720720280751e-06 1.19965429101974e-05 2.9461250908495e-05 -1.85735253869166e-07 8.22724022549912e-07 -5.93061856375383e-06 -9.14233729375267e-07 1.35560874809617e-05 -1.85735253869166e-07 3.13929683873512e-05 2914 2926 0 0 9 2916 2928 0 0 11 0 0 0 0 0 0 0 0 50 0 16 27 0 0 3081 +3 33 0.999997208372127 0.000410626762568301 -0.0023269365299196 -0.0104370354082809 -0.000398288274776867 0.999985873225442 0.00530044488699769 0.00235532381237302 0.00232908016233595 -0.00529950329859198 0.999983245184831 0.0127178382600946 5.63757279792755e-05 -1.87460193142459e-05 1.75230381744214e-06 -1.11310702259212e-05 -7.87694677644751e-06 1.20891814350832e-05 -1.87460193142459e-05 0.000157111328528562 -4.40140661607536e-06 1.76915468489042e-05 1.44368218011594e-05 -3.31065644606503e-05 1.75230381744214e-06 -4.40140661607536e-06 1.76592090872812e-05 9.7669064910427e-07 9.25671453097275e-07 8.91819417100154e-07 -1.11310702259212e-05 1.76915468489042e-05 9.7669064910427e-07 6.1557866518555e-05 2.85693749022687e-06 -2.24862369293213e-06 -7.87694677644751e-06 1.44368218011594e-05 9.25671453097275e-07 2.85693749022687e-06 3.2330822884e-05 -3.6602750443754e-06 1.20891814350832e-05 -3.31065644606503e-05 8.91819417100154e-07 -2.24862369293213e-06 -3.6602750443754e-06 4.63294403248375e-05 2530 2532 0 0 6 2534 2544 0 0 7 0 0 0 0 0 0 0 0 55 0 15 18 0 0 2666 +3 49 0.999999093118275 -0.000409681278238413 0.00128293564797822 -0.00966923327524624 0.000386488104342737 0.999837433560976 0.0180265658722493 0.00861153732318652 -0.00129011223224722 -0.0180260536849196 0.99983668516362 0.000455768155206935 6.99612695441143e-05 -3.57496891952949e-06 2.10093788804094e-06 8.54000826002651e-06 -4.46058531076181e-06 2.70896524951752e-05 -3.57496891952949e-06 3.48066095173085e-05 -6.35995518554845e-06 7.14582762763732e-06 1.09075400594931e-06 7.62606267650247e-07 2.10093788804094e-06 -6.35995518554845e-06 2.14933045534142e-05 -4.08416323221741e-06 -4.74799103631785e-06 -1.98601438668475e-07 8.54000826002651e-06 7.14582762763732e-06 -4.08416323221741e-06 7.70253417734573e-05 8.77332856274293e-06 7.61991344418206e-06 -4.46058531076181e-06 1.09075400594931e-06 -4.74799103631785e-06 8.77332856274293e-06 3.24150780088037e-05 -4.57284257948541e-06 2.70896524951752e-05 7.62606267650247e-07 -1.98601438668475e-07 7.61991344418206e-06 -4.57284257948541e-06 6.24105953346569e-05 2882 2891 0 0 6 2883 2892 0 0 7 0 0 0 0 0 0 0 0 65 0 17 28 0 0 2402 +3 32 0.999989454998637 0.00048935390706139 0.00456622648183162 -0.00830387161703635 -0.000511767776847744 0.999987821093024 0.00490874315572065 0.00497896899032401 -0.00456376875754206 -0.00491102824059257 0.999977526655648 0.0120533786168267 4.33252148900464e-05 -1.32637694688253e-05 3.80564192023345e-06 4.06509620360812e-06 -3.73166890434468e-06 6.95484731967075e-06 -1.32637694688253e-05 4.32112556654385e-05 -3.81937940561599e-06 5.20998095227459e-06 5.57669898814977e-07 -1.77455071160237e-06 3.80564192023345e-06 -3.81937940561599e-06 1.54137978247195e-05 -2.69910829554883e-07 1.83746945501135e-06 4.92591024479421e-06 4.06509620360812e-06 5.20998095227459e-06 -2.69910829554883e-07 5.86136442414539e-05 -9.53885102963306e-07 4.00844490559891e-06 -3.73166890434468e-06 5.57669898814977e-07 1.83746945501135e-06 -9.53885102963306e-07 2.66991417281661e-05 -4.77438732279932e-06 6.95484731967075e-06 -1.77455071160237e-06 4.92591024479421e-06 4.00844490559891e-06 -4.77438732279932e-06 3.7696538090975e-05 2890 2890 0 0 5 2894 2904 0 0 7 0 0 0 0 0 0 0 0 48 0 15 18 0 0 2686 +3 29 0.99997479523563 0.00101047404370503 -0.00702764794691284 -0.00834112920880337 -0.00100802974998603 0.999999430216387 0.000351344452429336 0.00177048515787172 0.00702799896712378 -0.000344251518672284 0.999975244054277 0.0137114298735486 3.98130173409778e-05 1.76619037405557e-07 5.96579802770902e-06 2.1922245592549e-06 -3.98055631410342e-06 1.52968439801431e-06 1.76619037405557e-07 5.52026194469485e-05 -6.19913895855635e-06 1.64963443368002e-05 -5.42394620114055e-07 3.23372588415401e-06 5.96579802770902e-06 -6.19913895855635e-06 1.79906818354743e-05 -1.99700850770711e-06 3.56007877052184e-06 4.46514271622718e-06 2.1922245592549e-06 1.64963443368002e-05 -1.99700850770711e-06 6.98744077651396e-05 -2.50432971272309e-07 -5.25102942444472e-06 -3.98055631410342e-06 -5.42394620114055e-07 3.56007877052184e-06 -2.50432971272309e-07 2.68143616933314e-05 -1.49197174374573e-06 1.52968439801431e-06 3.23372588415401e-06 4.46514271622718e-06 -5.25102942444472e-06 -1.49197174374573e-06 4.04979510223406e-05 2789 2797 0 0 9 2791 2799 0 0 11 0 0 0 0 0 0 0 0 66 0 32 40 0 0 2615 +3 30 0.999971815025574 0.000395897814809667 -0.00749749420669266 -0.0101539676189288 -0.000392172381956742 0.999999798922011 0.000498354051652232 0.00203251396822056 0.00749768999639165 -0.000495399695394286 0.999971769213441 0.0180581185048788 1.77595917835488e-05 3.20324091269876e-06 2.0168487810649e-06 4.78419122499848e-06 3.02384390791969e-06 2.51994196023018e-07 3.20324091269876e-06 4.61681670279955e-05 -1.38845611363759e-06 -1.01846679400168e-07 2.82115323636569e-06 -2.63059703227042e-06 2.0168487810649e-06 -1.38845611363759e-06 1.32079615258006e-05 1.43885342481722e-06 2.46724374756727e-06 8.80653055705644e-07 4.78419122499848e-06 -1.01846679400168e-07 1.43885342481722e-06 3.7784957775211e-05 -1.58759201378991e-06 1.23444678778922e-06 3.02384390791969e-06 2.82115323636569e-06 2.46724374756727e-06 -1.58759201378991e-06 2.25369600174466e-05 1.51799954373084e-06 2.51994196023018e-07 -2.63059703227042e-06 8.80653055705644e-07 1.23444678778922e-06 1.51799954373084e-06 2.95295606476336e-05 2988 2996 0 0 9 2989 2997 0 0 10 0 0 0 0 0 0 0 0 56 0 33 41 0 0 3139 +4 41 0.999958526612103 0.000334341142759395 -0.00910127857785495 -0.00567425878214875 -0.000228239505489664 0.999932035510792 0.0116564259518898 0.00219077788023801 0.00910455723687851 -0.0116538652490929 0.99989064125147 -0.0152915696162605 4.92387321327579e-05 1.1851273352491e-05 4.86954987373486e-06 1.6423060153819e-05 -9.97779055723189e-06 1.90545550639036e-05 1.1851273352491e-05 9.94169988517496e-05 -5.07935680173459e-06 3.99001553535765e-05 -6.75080347240968e-06 6.74270706270282e-06 4.86954987373486e-06 -5.07935680173459e-06 1.67360938453754e-05 -1.07800342036522e-06 2.05794426260993e-06 1.94015947240968e-06 1.6423060153819e-05 3.99001553535765e-05 -1.07800342036522e-06 8.93509926192905e-05 -2.89084223083503e-07 -1.71506427449771e-06 -9.97779055723189e-06 -6.75080347240968e-06 2.05794426260993e-06 -2.89084223083503e-07 3.44815070019909e-05 -4.00866722402731e-06 1.90545550639036e-05 6.74270706270282e-06 1.94015947240968e-06 -1.71506427449771e-06 -4.00866722402731e-06 6.21624029802356e-05 2752 2761 0 1 8 2753 2768 0 1 10 0 0 0 0 0 0 0 0 88 0 15 23 0 0 2607 +3 7 0.999994294164357 0.000408902394271564 -0.00335327266437769 -0.00170434257896731 -0.000421916436640064 0.99999237907355 -0.00388120874749828 1.27195709525049e-05 0.00335166007378383 0.0038826014028127 0.999986845804032 0.0203756834900183 3.49893742069232e-05 -4.17786941531671e-06 8.64651701625082e-06 -1.62537587148076e-06 -1.27411246901164e-06 7.76998632086063e-06 -4.17786941531671e-06 2.39131817897444e-05 -2.76935089127954e-06 6.49754061519822e-07 2.64030407864187e-07 -8.50165692344643e-06 8.64651701625082e-06 -2.76935089127954e-06 1.66890753589028e-05 -2.66073823388671e-06 2.5183228057308e-06 2.74410549516807e-06 -1.62537587148076e-06 6.49754061519822e-07 -2.66073823388671e-06 4.58282517688746e-05 6.39657341820952e-06 8.61091533776469e-07 -1.27411246901164e-06 2.64030407864187e-07 2.5183228057308e-06 6.39657341820952e-06 2.25242501561177e-05 -3.42521809747957e-06 7.76998632086063e-06 -8.50165692344643e-06 2.74410549516807e-06 8.61091533776469e-07 -3.42521809747957e-06 3.36493456757525e-05 3088 3095 0 0 12 3089 3096 0 0 14 0 0 0 0 0 0 0 0 60 0 11 22 0 0 2629 +4 46 0.99999413609686 -0.000194575774848965 -0.00341905135409627 -0.0274131422487913 0.00022523240852226 0.999959758453325 0.00896831892438705 0.00587965305150745 0.00341716874857781 -0.00896903641620489 0.999953938610929 -0.00565293090922522 3.37975946691503e-05 4.38618887202638e-06 4.22888397667071e-06 2.81084110677055e-06 -1.69776328590639e-06 3.42359084827651e-05 4.38618887202638e-06 4.58903682022137e-05 -5.32741636502373e-06 -2.97939731627633e-06 -5.54484618132085e-07 1.88751363809775e-05 4.22888397667071e-06 -5.32741636502373e-06 1.47193190933797e-05 1.44110623684507e-06 1.33575710605067e-06 -4.98151563279532e-07 2.81084110677055e-06 -2.97939731627633e-06 1.44110623684507e-06 6.72366686401195e-05 -4.60773221748649e-06 4.93663960452596e-06 -1.69776328590639e-06 -5.54484618132085e-07 1.33575710605067e-06 -4.60773221748649e-06 3.34518771678825e-05 -5.93622666779964e-06 3.42359084827651e-05 1.88751363809775e-05 -4.98151563279532e-07 4.93663960452596e-06 -5.93622666779964e-06 0.000100388936724085 3005 3012 0 0 0 3007 3015 0 0 0 0 0 0 0 0 0 0 0 45 0 31 46 0 0 2915 +4 53 0.998723441706677 0.00977993155981285 -0.0495564317143098 -0.0042371865441443 -0.00947104908613751 0.999934256186962 0.00646394098322913 -0.00232601952738755 0.049616390585951 -0.00598633798845938 0.998750408031311 -0.018249442473615 0.000173212917698747 -5.46775033302705e-06 7.32812899748525e-06 -4.10292214307859e-06 -6.02038100430834e-05 0.000112399131992236 -5.46775033302705e-06 7.06515252633105e-05 2.24080642468004e-07 3.67216383607375e-06 4.62055952267651e-06 5.51183697653102e-06 7.32812899748525e-06 2.24080642468004e-07 1.6019331680069e-05 1.48606204169417e-06 -2.29008420972637e-06 1.04876715511478e-06 -4.10292214307859e-06 3.67216383607375e-06 1.48606204169417e-06 7.11864826947791e-05 8.13505044173912e-06 9.12253831333321e-06 -6.02038100430834e-05 4.62055952267651e-06 -2.29008420972637e-06 8.13505044173912e-06 5.72805512002572e-05 -4.05725674296091e-05 0.000112399131992236 5.51183697653102e-06 1.04876715511478e-06 9.12253831333321e-06 -4.05725674296091e-05 0.000127390613660715 2609 2607 0 0 0 2613 2620 0 0 1 0 0 0 0 0 0 0 0 55 0 30 35 0 0 2614 +4 40 0.999983194981991 0.00039412408797046 -0.00578397958272548 -0.0105902488956938 -0.000336735821592529 0.999950743291303 0.00991955644958383 0.00132085571778907 0.00578760421906683 -0.00991744207814219 0.999934071816752 -0.00842547892334212 4.2679460875246e-05 -2.63529327379107e-06 1.09057876990876e-06 6.60528896029033e-06 -7.05323050651675e-06 1.93766213353554e-05 -2.63529327379107e-06 4.82241679759136e-05 -3.34834800057757e-06 6.93829745343164e-06 -1.33432343599843e-06 1.37266406265064e-05 1.09057876990876e-06 -3.34834800057757e-06 1.70677367911007e-05 7.66500407062122e-07 1.06998327384609e-06 3.69287506037445e-07 6.60528896029033e-06 6.93829745343164e-06 7.66500407062122e-07 6.02329156295464e-05 6.09826970138273e-07 3.58385295167977e-06 -7.05323050651675e-06 -1.33432343599843e-06 1.06998327384609e-06 6.09826970138273e-07 3.91990790009534e-05 -7.7123045102856e-06 1.93766213353554e-05 1.37266406265064e-05 3.69287506037445e-07 3.58385295167977e-06 -7.7123045102856e-06 7.3602947382288e-05 3079 3085 0 0 6 3080 3090 0 0 8 0 0 0 0 0 0 0 0 75 0 13 18 0 0 2653 +4 37 0.999981772873016 0.000137640129440208 -0.0060361392407818 -0.0152803730793075 -1.81618331910184e-05 0.99980417015851 0.019789416459357 0.00771323749538507 0.00603768100243408 -0.0197889461277962 0.999785949100738 -0.0154884128938307 5.41262648904988e-05 5.46047364748166e-06 5.99373650306972e-06 -6.4551348926673e-06 -1.23287841476226e-05 3.00334764404502e-05 5.46047364748166e-06 3.85796000819978e-05 -7.37210558659606e-06 1.32920171250003e-05 -1.02599337691545e-06 1.0575349356188e-05 5.99373650306972e-06 -7.37210558659606e-06 1.76485949156197e-05 -4.1983263324137e-06 -2.934257030387e-07 2.29989362056299e-06 -6.4551348926673e-06 1.32920171250003e-05 -4.1983263324137e-06 6.99367782132106e-05 1.44398227527567e-05 6.30226557164918e-06 -1.23287841476226e-05 -1.02599337691545e-06 -2.934257030387e-07 1.44398227527567e-05 4.60316603211494e-05 -1.19583040923325e-05 3.00334764404502e-05 1.0575349356188e-05 2.29989362056299e-06 6.30226557164918e-06 -1.19583040923325e-05 7.58195357358849e-05 3001 3012 0 0 5 3003 3014 0 0 7 0 0 0 0 0 0 0 0 60 0 19 29 0 0 2641 +4 49 0.999997636942597 -0.000108375635280789 -0.00217125860821636 -0.0111222860306054 0.000158025680918464 0.999738209767287 0.0228798373941788 0.0105776469238743 0.00216821057700732 -0.0228801264424297 0.999735864454643 -0.00775287721426204 7.07659885905753e-05 -1.34196323686761e-06 5.66653316686766e-06 9.28778922191658e-06 -7.93165623117898e-06 3.89767304851802e-05 -1.34196323686761e-06 2.75982811649443e-05 -1.07918856567616e-05 2.91037763520846e-06 7.05269757390167e-07 1.36220816710168e-05 5.66653316686766e-06 -1.07918856567616e-05 2.05535509147292e-05 -4.92912230162224e-06 -3.78887787146203e-06 -2.5206649047779e-06 9.28778922191658e-06 2.91037763520846e-06 -4.92912230162224e-06 6.91644224428653e-05 1.08306533468403e-05 7.35262514887426e-06 -7.93165623117898e-06 7.05269757390167e-07 -3.78887787146203e-06 1.08306533468403e-05 3.57642107863396e-05 -8.42012014653832e-06 3.89767304851802e-05 1.36220816710168e-05 -2.5206649047779e-06 7.35262514887426e-06 -8.42012014653832e-06 7.9499954384032e-05 2896 2905 0 0 6 2898 2909 0 0 10 0 0 0 0 0 0 0 0 60 0 16 27 0 0 2393 +4 6 0.999982997170585 -0.000952001923560716 0.00575317843210015 0.000774155739285122 0.000944574163502191 0.99999871712386 0.00129364998481839 0.00155606648957007 -0.00575440260875877 -0.0012881936854034 0.999982613552678 0.00297322117993535 1.69978691815088e-05 -4.06467206417665e-07 3.06621570740752e-06 -1.01313126738673e-06 5.64221918737767e-06 2.59311629620211e-06 -4.06467206417665e-07 4.53149616713249e-05 -7.28221081313687e-06 5.19797483801749e-06 3.29466835412169e-07 -4.8124569817864e-06 3.06621570740752e-06 -7.28221081313687e-06 1.72024493647192e-05 -3.25112120853956e-06 1.4888127561629e-06 2.2660104855474e-06 -1.01313126738673e-06 5.19797483801749e-06 -3.25112120853956e-06 4.67603228281327e-05 9.88532777180928e-07 -3.14424567110435e-06 5.64221918737767e-06 3.29466835412169e-07 1.4888127561629e-06 9.88532777180928e-07 1.84943166568331e-05 1.25985918414483e-06 2.59311629620211e-06 -4.8124569817864e-06 2.2660104855474e-06 -3.14424567110435e-06 1.25985918414483e-06 3.07908433535413e-05 2786 2790 0 0 14 2786 2804 0 0 17 0 0 0 0 0 0 0 0 64 0 7 10 0 0 3062 +4 38 0.999939147598307 -0.000266214173524882 -0.011028609630614 -0.0176709681738049 0.000419230741996552 0.999903656278238 0.0138745236673955 0.000240988557063299 0.0110238534984652 -0.0138783029015066 0.999842921344457 -0.00945551904460267 5.34242773912418e-05 -4.70769341969502e-06 -7.00158285494485e-08 -1.65391514653202e-06 -7.40401523967984e-06 2.18140591527975e-05 -4.70769341969502e-06 4.51862049747593e-05 -7.27023641546926e-06 5.44193241360908e-06 1.50620098615884e-06 2.11468882390656e-06 -7.00158285494485e-08 -7.27023641546926e-06 1.65589664278561e-05 -2.39576428053468e-06 -7.86535761164235e-07 1.66171052719723e-07 -1.65391514653202e-06 5.44193241360908e-06 -2.39576428053468e-06 6.03664765490575e-05 1.61293527217327e-05 -3.85047189412744e-06 -7.40401523967984e-06 1.50620098615884e-06 -7.86535761164235e-07 1.61293527217327e-05 4.09752258816764e-05 -9.3720240909859e-06 2.18140591527975e-05 2.11468882390656e-06 1.66171052719723e-07 -3.85047189412744e-06 -9.3720240909859e-06 7.40309565790329e-05 2980 2987 0 0 2 2984 2995 0 0 6 0 0 0 0 0 0 0 0 55 0 23 36 0 0 2530 +3 31 0.999996958489237 -6.84171478778653e-06 -0.0024663668553615 -0.0135714898872328 9.64706286237873e-06 0.999999353078138 0.00113743142181108 0.00498460139846665 0.00246635747783348 -0.00113745175549726 0.999996311635346 0.0120892928398149 2.23699491831847e-05 -4.74856712231099e-06 3.03911245570006e-06 4.59292348459945e-06 2.29867653703033e-06 1.05534736029329e-06 -4.74856712231099e-06 1.53582839767741e-05 -8.45635308950118e-06 1.69303912450585e-06 -2.70817373381348e-06 2.93213666446389e-07 3.03911245570006e-06 -8.45635308950118e-06 1.15470475205251e-05 -3.64614571321295e-07 2.15632934867273e-06 1.95567561223402e-06 4.59292348459945e-06 1.69303912450585e-06 -3.64614571321295e-07 4.28569101192061e-05 -2.99152041895223e-06 -1.21719467898602e-06 2.29867653703033e-06 -2.70817373381348e-06 2.15632934867273e-06 -2.99152041895223e-06 2.03780164540836e-05 2.22607930507502e-06 1.05534736029329e-06 2.93213666446389e-07 1.95567561223402e-06 -1.21719467898602e-06 2.22607930507502e-06 2.6049597473721e-05 3154 3165 0 0 9 3158 3169 0 0 12 0 0 0 0 0 0 0 0 62 0 22 34 0 0 2632 +4 45 0.999999559198131 -0.000830637519227534 -0.000437772605991723 -0.0074433227134271 0.00083234781148505 0.999991965616106 0.00392121159308911 0.00300547659994354 0.000434511983288498 -0.00392157424368224 0.9999922161971 -0.000355899388935998 6.93209396559827e-05 1.28623819799031e-06 5.42318347002018e-06 5.74530620736335e-06 -1.45687225570236e-05 4.11267571248641e-05 1.28623819799031e-06 7.95985394913138e-05 2.2953887459001e-06 1.32807032494133e-05 -2.11369082726932e-06 2.12489078619063e-05 5.42318347002018e-06 2.2953887459001e-06 2.09886900166053e-05 6.37911616416058e-07 -2.13913605658604e-06 6.21915337109626e-06 5.74530620736335e-06 1.32807032494133e-05 6.37911616416058e-07 7.7417057409854e-05 6.29015207216798e-07 8.58336917654403e-06 -1.45687225570236e-05 -2.11369082726932e-06 -2.13913605658604e-06 6.29015207216798e-07 4.49589440476741e-05 -1.4443104786707e-05 4.11267571248641e-05 2.12489078619063e-05 6.21915337109626e-06 8.58336917654403e-06 -1.4443104786707e-05 9.09848055682887e-05 2721 2730 0 1 7 2724 2733 0 1 10 0 0 0 0 0 0 0 0 27 0 16 27 0 0 2350 +4 39 0.999967410279645 -0.000433278795565759 -0.00806167774759478 -0.0172206884418036 0.000554825693424933 0.999886121328253 0.0150809994228543 0.00158157700473223 0.00805422541717497 -0.0150849807632469 0.99985377571338 -0.005843584482977 6.19602490126066e-05 1.55303750637822e-05 8.34879653930002e-06 9.30055668007458e-06 -1.49722634411648e-05 2.9496880409303e-05 1.55303750637822e-05 7.94647514966823e-05 1.00194930469344e-06 2.08742636228148e-05 -8.9480488027596e-06 6.90403555240612e-06 8.34879653930002e-06 1.00194930469344e-06 1.91747286303207e-05 -3.80601314116912e-06 1.80957787770266e-07 3.78446835087634e-06 9.30055668007458e-06 2.08742636228148e-05 -3.80601314116912e-06 7.41804570439321e-05 1.96614910149169e-06 -2.58919486071439e-06 -1.49722634411648e-05 -8.9480488027596e-06 1.80957787770266e-07 1.96614910149169e-06 4.30711011348687e-05 -1.07157100306513e-05 2.9496880409303e-05 6.90403555240612e-06 3.78446835087634e-06 -2.58919486071439e-06 -1.07157100306513e-05 7.75915456728006e-05 2899 2915 0 1 7 2901 2918 0 1 10 0 0 0 0 0 0 0 0 65 0 22 32 0 0 2674 +4 51 0.999999488536182 -0.000858644717034451 -0.00053446854387196 -0.00298902237056573 0.000862296800163601 0.999976023955871 0.0068708047297967 0.000188971252918498 0.000528556149247552 -0.00687126208614385 0.999976252910908 -0.00267631276862269 2.89620537911717e-05 5.2131860911438e-06 3.4794787355644e-06 4.49128743432764e-06 -2.84921622318874e-06 2.40385849699258e-05 5.2131860911438e-06 4.8237362209191e-05 -6.34893706630958e-06 4.32734696912321e-06 -6.02406850755865e-06 1.03456894279458e-05 3.4794787355644e-06 -6.34893706630958e-06 1.91774772823146e-05 -5.12592408520797e-06 -2.17165411065268e-06 3.67196035268274e-06 4.49128743432764e-06 4.32734696912321e-06 -5.12592408520797e-06 7.15183080124789e-05 7.09349090818048e-06 1.15134362329354e-06 -2.84921622318874e-06 -6.02406850755865e-06 -2.17165411065268e-06 7.09349090818048e-06 3.67226392495255e-05 -9.64219525245958e-06 2.40385849699258e-05 1.03456894279458e-05 3.67196035268274e-06 1.15134362329354e-06 -9.64219525245958e-06 6.67165975505285e-05 2767 2779 0 1 12 2767 2785 0 1 13 0 0 0 0 0 0 0 0 70 0 12 18 0 0 3094 +4 42 0.999903356311113 0.000477959649828533 -0.0138942287423526 -0.0103720580930571 -0.000327024316582305 0.999940937940796 0.0108634103842921 0.000874518594031788 0.0138986003924153 -0.0108578167535797 0.999844456264312 -0.00421343338116298 6.42641205242379e-05 1.34545137279266e-05 1.5204969214865e-06 2.04131402395375e-05 -1.59241130785114e-05 1.93915404698987e-05 1.34545137279266e-05 8.72626684114168e-05 -5.04218891058629e-06 3.35411323351524e-05 -9.55641319080576e-06 1.03325574063678e-05 1.5204969214865e-06 -5.04218891058629e-06 1.48927329406725e-05 4.76032753379648e-07 4.50402089820397e-06 -1.36847864188037e-06 2.04131402395375e-05 3.35411323351524e-05 4.76032753379648e-07 8.14292180136161e-05 -6.80905415011031e-07 -4.26739196073516e-06 -1.59241130785114e-05 -9.55641319080576e-06 4.50402089820397e-06 -6.80905415011031e-07 3.48996528530025e-05 -6.68635036526294e-06 1.93915404698987e-05 1.03325574063678e-05 -1.36847864188037e-06 -4.26739196073516e-06 -6.68635036526294e-06 8.11836091738703e-05 2881 2889 0 0 6 2882 2895 0 0 7 0 0 0 0 0 0 0 0 61 0 16 27 0 0 2575 +4 36 0.99996056891687 -0.000349895429395401 -0.00887345392941545 -0.0160524054420653 0.000444941984069579 0.999942529897532 0.0107116258688073 -0.00352510428665744 0.00886919602217599 -0.0107151516699941 0.999903256763678 -0.00262190830409409 6.65749640623569e-05 -1.58142767679873e-05 8.27682355757823e-06 3.35225305889845e-06 -9.76405445718326e-06 2.10023401537949e-05 -1.58142767679873e-05 4.52548569174625e-05 -8.51597232983959e-06 5.56367197775803e-06 -1.46682644776152e-07 -3.2153730949209e-06 8.27682355757823e-06 -8.51597232983959e-06 1.8810491490429e-05 -2.26658130209648e-06 -2.36366522335295e-06 4.8224656697315e-06 3.35225305889845e-06 5.56367197775803e-06 -2.26658130209648e-06 7.02904251699721e-05 5.46650463412758e-06 1.9407268527286e-06 -9.76405445718326e-06 -1.46682644776152e-07 -2.36366522335295e-06 5.46650463412758e-06 3.90761096013778e-05 -6.34156603309713e-06 2.10023401537949e-05 -3.2153730949209e-06 4.8224656697315e-06 1.9407268527286e-06 -6.34156603309713e-06 6.8898064782241e-05 2757 2765 0 0 6 2759 2767 0 0 8 0 0 0 0 0 0 0 0 53 0 22 33 0 0 2529 +4 52 0.999887747990256 0.00424058350363606 -0.0143704165048574 -0.00263510268576244 -0.00392613707313204 0.999753780045647 0.0218395222503281 0.00894265918717465 0.0144594905393435 -0.0217806504950676 0.999658204786693 -0.00720373204092118 8.1545674989941e-05 -2.96481721459118e-06 4.0321330127559e-06 1.74275186218386e-06 -1.92650837916444e-05 5.78407438852634e-05 -2.96481721459118e-06 3.43777952630333e-05 -5.1625713367194e-06 3.29031916790499e-06 -1.58905396083948e-06 1.63610659044375e-05 4.0321330127559e-06 -5.1625713367194e-06 1.96960258816529e-05 4.64065450344836e-07 -3.37464353800555e-06 2.13206535714956e-06 1.74275186218386e-06 3.29031916790499e-06 4.64065450344836e-07 6.26857193109167e-05 -1.48086792225236e-06 5.6410558553367e-06 -1.92650837916444e-05 -1.58905396083948e-06 -3.37464353800555e-06 -1.48086792225236e-06 3.52624728901981e-05 -2.49487381332952e-05 5.78407438852634e-05 1.63610659044375e-05 2.13206535714956e-06 5.6410558553367e-06 -2.49487381332952e-05 9.66906813952883e-05 2823 2825 0 1 4 2827 2842 0 1 7 0 0 0 0 0 0 0 0 60 0 19 21 0 0 2707 +4 47 0.999944706044757 0.000380298576394478 -0.010509054479716 -0.0189520605594357 -0.000155873202912279 0.999772093278873 0.0213480023497386 0.00877487269140109 0.0105147780104699 -0.0213451838542708 0.999716871203851 -0.0105882853781297 5.79216928758557e-05 -7.90096059436539e-06 -4.91109955986935e-06 8.52015391284413e-06 -1.19591962509426e-05 2.60419296378579e-05 -7.90096059436539e-06 4.45773453343167e-05 -4.92059499923289e-06 4.74592156268296e-06 -4.82862042379608e-07 2.79698610210458e-06 -4.91109955986935e-06 -4.92059499923289e-06 2.08226217046155e-05 -3.02777714408832e-06 1.09700602246516e-06 1.48744022391286e-07 8.52015391284413e-06 4.74592156268296e-06 -3.02777714408832e-06 8.08563171454139e-05 6.88179923769134e-07 2.85580126547552e-06 -1.19591962509426e-05 -4.82862042379608e-07 1.09700602246516e-06 6.88179923769134e-07 3.48075710371615e-05 -6.27516226430221e-06 2.60419296378579e-05 2.79698610210458e-06 1.48744022391286e-07 2.85580126547552e-06 -6.27516226430221e-06 5.68409514362485e-05 2782 2792 0 0 1 2783 2796 0 0 2 0 0 0 0 0 0 0 0 47 0 22 34 0 0 2645 +4 48 0.999987416896008 -0.00132277432754439 -0.00483904099267081 -0.0191189585944694 0.00137919685936783 0.999930891805858 0.011675162883831 0.00260814208178263 0.0048232629695538 -0.0116816899641817 0.99992013393766 -0.00615720910336967 6.08152519521404e-05 -1.28103469328973e-05 5.04646487421138e-06 -3.57724144456303e-06 -8.57631295975486e-06 1.73318042040564e-05 -1.28103469328973e-05 3.92908525248662e-05 -2.77904452201335e-06 3.38731482863793e-06 -1.00227204923286e-06 1.1551949555105e-05 5.04646487421138e-06 -2.77904452201335e-06 1.67437244052112e-05 2.25298904755497e-07 3.52451901800563e-07 2.89635502836754e-06 -3.57724144456303e-06 3.38731482863793e-06 2.25298904755497e-07 7.04598586352619e-05 5.60806751685594e-06 -5.73143900290672e-06 -8.57631295975486e-06 -1.00227204923286e-06 3.52451901800563e-07 5.60806751685594e-06 3.15672518284559e-05 -1.00500869431728e-06 1.73318042040564e-05 1.1551949555105e-05 2.89635502836754e-06 -5.73143900290672e-06 -1.00500869431728e-06 6.22594750480797e-05 3030 3029 0 1 4 3035 3047 0 1 6 0 0 0 0 0 0 0 0 34 0 18 22 0 0 2590 +4 50 0.999999916187399 -3.25738670838446e-05 -0.000408122700389991 -0.00350661452801738 3.47038513001325e-05 0.999986374789877 0.00522006036766793 -0.000771578458214748 0.000407947102079857 -0.0052200740935906 0.999986292108856 0.00119002713767257 3.61766754374988e-05 5.71805472808287e-06 5.05692180390971e-06 5.72142207623931e-06 -2.91299147623793e-06 3.12013831156809e-05 5.71805472808287e-06 8.62024492064077e-05 -6.62730948598359e-06 2.322741199756e-05 -2.06541181185298e-06 1.6011536837996e-05 5.05692180390971e-06 -6.62730948598359e-06 2.42656436369831e-05 -8.19801992578704e-06 -4.63069261610837e-06 8.70019799896142e-06 5.72142207623931e-06 2.322741199756e-05 -8.19801992578704e-06 7.19797873347933e-05 9.61127350470994e-06 -2.39857147034011e-06 -2.91299147623793e-06 -2.06541181185298e-06 -4.63069261610837e-06 9.61127350470994e-06 3.85161636879654e-05 -1.16273951127802e-05 3.12013831156809e-05 1.6011536837996e-05 8.70019799896142e-06 -2.39857147034011e-06 -1.16273951127802e-05 9.27262921728252e-05 2739 2740 0 0 10 2741 2757 0 0 12 0 0 0 0 0 0 0 0 59 0 13 16 0 0 3074 +4 43 0.999956719451993 -0.000367732720977797 -0.00929645069119914 -0.0101691458191768 0.000527819992922264 0.999851522222586 0.0172236731051131 0.00548223433269778 0.0092887366666865 -0.0172278345076404 0.999808442197461 -0.00634291262486647 5.58672432210834e-05 -4.17121099888521e-06 6.68157830493041e-06 7.46971237237905e-06 -8.26710050527722e-06 2.27778179751332e-05 -4.17121099888521e-06 4.44184216661951e-05 -6.23040421647043e-06 7.67117410153123e-06 -1.89505278984691e-07 -1.58154549713355e-06 6.68157830493041e-06 -6.23040421647043e-06 1.83103020967712e-05 -4.47040546665583e-06 2.1032352639243e-06 4.75651134431985e-06 7.46971237237905e-06 7.67117410153123e-06 -4.47040546665583e-06 7.28120471560484e-05 7.03819634042759e-06 4.53905751055044e-06 -8.26710050527722e-06 -1.89505278984691e-07 2.1032352639243e-06 7.03819634042759e-06 3.02554480243848e-05 -7.30014904309414e-06 2.27778179751332e-05 -1.58154549713355e-06 4.75651134431985e-06 4.53905751055044e-06 -7.30014904309414e-06 6.86183891270236e-05 3009 3020 0 0 5 3011 3028 0 0 7 0 0 0 0 0 0 0 0 18 0 15 22 0 0 2632 +4 7 0.999999993258968 1.99883770020396e-05 -0.000114378881447529 -0.0010965751335114 -2.00895002090097e-05 0.999999608915869 -0.000884174485737419 0.000661995351185858 0.000114361163502807 0.000884176777591733 0.999999602576396 0.0100861275688982 3.00889139713435e-05 -3.07527162170837e-06 7.53399520546515e-06 -1.52670664055277e-06 -1.21872094371074e-06 5.02269021974921e-06 -3.07527162170837e-06 2.50815796874605e-05 -1.57065126098578e-06 1.57809325447949e-06 -2.06074767027674e-06 -1.28275169241182e-06 7.53399520546515e-06 -1.57065126098578e-06 1.54577584672887e-05 -4.12495167212469e-06 2.60650535636576e-06 3.51077264862344e-06 -1.52670664055277e-06 1.57809325447949e-06 -4.12495167212469e-06 4.14455329139002e-05 3.6030547900721e-06 -2.92823724554938e-06 -1.21872094371074e-06 -2.06074767027674e-06 2.60650535636576e-06 3.6030547900721e-06 2.33697996022611e-05 4.39474183687047e-07 5.02269021974921e-06 -1.28275169241182e-06 3.51077264862344e-06 -2.92823724554938e-06 4.39474183687047e-07 2.93703179237766e-05 3019 3025 0 2 9 3021 3027 0 2 11 0 0 0 0 0 0 0 0 56 0 13 24 0 0 2649 +4 33 0.999993474469797 -0.000550288439629011 0.00357046221888572 -0.0105834737018726 0.000517653748118049 0.999958143934724 0.00913468188929846 0.00712916357577725 -0.00357533948322939 -0.00913277401750577 0.999951903536528 0.00123256914408434 4.84078420770139e-05 -1.23322307733432e-05 3.35534662345664e-06 -4.58658512285297e-07 -6.00966286776204e-06 5.81051093677598e-06 -1.23322307733432e-05 4.59168715349671e-05 -8.04125337361752e-06 9.75260692300356e-06 2.23832392639315e-06 -7.72353028813358e-06 3.35534662345664e-06 -8.04125337361752e-06 1.69335196651994e-05 -4.88188961092469e-07 1.89644943461738e-06 1.31312229016552e-06 -4.58658512285297e-07 9.75260692300356e-06 -4.88188961092469e-07 6.46059482567642e-05 -1.64143447103203e-06 4.17561365282042e-06 -6.00966286776204e-06 2.23832392639315e-06 1.89644943461738e-06 -1.64143447103203e-06 2.68680455928336e-05 -7.77565779869754e-07 5.81051093677598e-06 -7.72353028813358e-06 1.31312229016552e-06 4.17561365282042e-06 -7.77565779869754e-07 3.79557650541254e-05 2668 2675 0 0 7 2669 2679 0 0 9 0 0 0 0 0 0 0 0 60 0 11 16 0 0 2682 +4 31 0.999982459339855 0.00123851893499082 -0.00579198441498022 -0.0116330313141082 -0.00121560550199355 0.999991428598242 0.00395790769353345 0.00440897706800142 0.00579683671317621 -0.0039507975010974 0.999975393638876 0.00423181023162411 2.86606592081399e-05 -1.38451467853869e-06 5.60946662316805e-06 6.11672089387965e-06 -1.41610656325414e-06 5.17341409272696e-06 -1.38451467853869e-06 2.90865001667788e-05 -5.02629396120164e-06 2.73163132686847e-06 -8.31273372534308e-07 -8.64119794899109e-06 5.60946662316805e-06 -5.02629396120164e-06 1.57947240634395e-05 1.46712597043693e-06 5.10259082754384e-07 3.17962695730905e-06 6.11672089387965e-06 2.73163132686847e-06 1.46712597043693e-06 4.36063300671439e-05 3.19358957582254e-06 2.94551234498955e-06 -1.41610656325414e-06 -8.31273372534308e-07 5.10259082754384e-07 3.19358957582254e-06 2.39172120122029e-05 3.69644080071405e-06 5.17341409272696e-06 -8.64119794899109e-06 3.17962695730905e-06 2.94551234498955e-06 3.69644080071405e-06 2.87226394356135e-05 3111 3122 0 0 10 3112 3123 0 0 12 0 0 0 0 0 0 0 0 61 0 18 30 0 0 2657 +4 32 0.99999864080687 0.000473417558567616 0.00157932271162776 -0.00770425596898028 -0.000485689251230702 0.999969625856828 0.00777891185876416 0.00617061231711712 -0.00157559206759311 -0.00777966834578587 0.999968496638802 0.00580487379098135 3.89099005869921e-05 -5.27647835458971e-06 6.73404824319473e-06 2.86584894094205e-07 2.63086433672865e-07 4.70159811934042e-06 -5.27647835458971e-06 2.64950642017096e-05 -5.60994011505817e-06 -7.18154883783945e-07 -3.71877255891756e-06 4.40905448219651e-06 6.73404824319473e-06 -5.60994011505817e-06 1.64397946391116e-05 1.84463105478585e-06 2.60226928738727e-06 4.54520865063328e-06 2.86584894094205e-07 -7.18154883783945e-07 1.84463105478585e-06 5.56386201257212e-05 5.89020269562979e-06 1.72950361080645e-06 2.63086433672865e-07 -3.71877255891756e-06 2.60226928738727e-06 5.89020269562979e-06 2.49648735461863e-05 -5.59217722382273e-07 4.70159811934042e-06 4.40905448219651e-06 4.54520865063328e-06 1.72950361080645e-06 -5.59217722382273e-07 3.13020519982409e-05 2932 2940 0 0 8 2932 2943 0 0 10 0 0 0 0 0 0 0 0 54 0 10 15 0 0 2689 +4 35 0.999999687448873 0.000419899931853799 0.000669915071665012 -0.0202655046596315 -0.000428324169029124 0.999920211114055 0.0126248938225456 0.00810128261013692 -0.000664560427832017 -0.0126251768174372 0.999920078441155 -0.00662066282414279 4.82300253615498e-05 -7.8803650704299e-06 2.40665509921733e-06 -3.88156779338186e-06 -2.1220517684488e-06 3.60586044701464e-06 -7.8803650704299e-06 3.87083300993544e-05 -2.06101843094436e-06 3.97577517661648e-06 2.62232416166262e-06 -6.84006904745911e-06 2.40665509921733e-06 -2.06101843094436e-06 1.90332906311164e-05 -2.11735342568009e-06 3.22438780023917e-06 8.52354281798369e-07 -3.88156779338186e-06 3.97577517661648e-06 -2.11735342568009e-06 7.89760957366035e-05 6.12717519847251e-06 1.17735848337892e-07 -2.1220517684488e-06 2.62232416166262e-06 3.22438780023917e-06 6.12717519847251e-06 3.15749263153616e-05 3.49577377200407e-06 3.60586044701464e-06 -6.84006904745911e-06 8.52354281798369e-07 1.17735848337892e-07 3.49577377200407e-06 4.18508696282412e-05 2543 2551 0 0 3 2544 2552 0 0 3 0 0 0 0 0 0 0 0 64 0 29 40 0 0 2426 +4 8 0.999992179691499 0.000171758824141317 0.00395108273151721 0.000171901393673636 -0.000180626956836751 0.999997465389891 0.00224423432286749 0.00372984250107799 -0.00395068725001458 -0.00224493044431274 0.999989676125485 0.0107640848511761 2.60457739284479e-05 2.24819023291312e-06 1.90557742757772e-06 7.80322805053693e-06 1.3290639765775e-06 4.73841768091073e-06 2.24819023291312e-06 5.16022161049861e-05 -3.65047478935577e-06 9.15415151616574e-06 1.32209672803034e-06 -1.16356945779035e-06 1.90557742757772e-06 -3.65047478935577e-06 1.4877171956088e-05 -2.64262852627994e-07 1.64389719908524e-06 -1.60202963267472e-08 7.80322805053693e-06 9.15415151616574e-06 -2.64262852627994e-07 5.47722897431858e-05 -8.27331000861938e-08 3.36531884122034e-06 1.3290639765775e-06 1.32209672803034e-06 1.64389719908524e-06 -8.27331000861938e-08 2.11321730792616e-05 -7.71835218701799e-07 4.73841768091073e-06 -1.16356945779035e-06 -1.60202963267472e-08 3.36531884122034e-06 -7.71835218701799e-07 3.31472457647104e-05 2730 2743 0 0 10 2730 2750 0 0 12 0 0 0 0 0 0 0 0 75 0 11 16 0 0 3101 +5 41 0.999999299126259 0.000960784125108214 0.000691838750590847 0.00249655209451092 -0.000971712061539096 0.999871962136712 0.0159723232045555 0.00565867550385579 -0.000676404214459447 -0.0159729842780321 0.999872194958232 -0.0263241627346282 3.47749962122138e-05 9.79726973420052e-07 6.41381268622278e-06 2.73378634629054e-06 -1.52870312045943e-06 1.8346751520955e-05 9.79726973420052e-07 4.13941358310151e-05 -4.8136603982354e-06 8.36194273309535e-06 1.78443549277401e-06 6.73842871441381e-06 6.41381268622278e-06 -4.8136603982354e-06 1.88155340398066e-05 -4.89384205775245e-06 4.72219008402236e-07 -1.12926120306128e-06 2.73378634629054e-06 8.36194273309535e-06 -4.89384205775245e-06 6.47639312260913e-05 1.15415751424555e-05 2.39319895965067e-06 -1.52870312045943e-06 1.78443549277401e-06 4.72219008402236e-07 1.15415751424555e-05 2.95784246875803e-05 -4.2377742647335e-06 1.8346751520955e-05 6.73842871441381e-06 -1.12926120306128e-06 2.39319895965067e-06 -4.2377742647335e-06 6.4188308631815e-05 2873 2894 0 0 20 2873 2894 0 0 20 0 0 0 0 0 0 0 0 97 0 9 13 0 0 2823 +5 37 0.999931329087486 -7.58902792930356e-06 -0.0117190892026573 -0.0133548993930638 0.000132797313614313 0.999942922143333 0.0106833899266988 -0.000574842455068799 0.0117183392256189 -0.0106842125521279 0.99987425615821 -0.016822913393676 5.79214474577227e-05 7.91732321052463e-06 1.95419205964238e-06 -5.0310706949927e-06 -1.48385256972459e-05 2.02501263387115e-05 7.91732321052463e-06 5.02128921789923e-05 -1.76671120427836e-06 5.14544074472543e-06 -6.67360470777258e-06 5.80699840692021e-06 1.95419205964238e-06 -1.76671120427836e-06 1.60838052928337e-05 -3.43393530674201e-06 -7.51558870925164e-07 2.12559556159004e-06 -5.0310706949927e-06 5.14544074472543e-06 -3.43393530674201e-06 7.1240676731372e-05 8.23797070921527e-06 -1.90184188706185e-07 -1.48385256972459e-05 -6.67360470777258e-06 -7.51558870925164e-07 8.23797070921527e-06 4.3721526590497e-05 -1.2176046304078e-05 2.02501263387115e-05 5.80699840692021e-06 2.12559556159004e-06 -1.90184188706185e-07 -1.2176046304078e-05 6.57714696608638e-05 2847 2858 0 0 6 2847 2858 0 0 6 0 0 0 0 0 0 0 0 62 0 21 31 0 0 2745 +4 34 0.999995868009934 0.000332206451818286 -0.00285545126601571 -0.0122650364797852 -0.000312999877396389 0.999977343995176 0.00672410049221283 0.00729069172694635 0.00285762036246424 -0.00672317895240022 0.999973316079303 3.30566388641586e-05 2.06660679914586e-05 -6.95857163297758e-06 2.65817870681701e-06 1.19252177273511e-07 2.87578032831148e-06 1.0536103223844e-06 -6.95857163297758e-06 2.7010947044548e-05 -5.27517268536736e-06 2.11198892069788e-06 -5.42795138626726e-08 -2.24048430508531e-06 2.65817870681701e-06 -5.27517268536736e-06 1.81123035054643e-05 -3.38731459594824e-06 7.81386146878197e-07 2.03908025579141e-06 1.19252177273511e-07 2.11198892069788e-06 -3.38731459594824e-06 8.70322056948984e-05 6.30139058846554e-06 6.5454616678027e-06 2.87578032831148e-06 -5.42795138626726e-08 7.81386146878197e-07 6.30139058846554e-06 2.4628967399511e-05 4.02062801328559e-07 1.0536103223844e-06 -2.24048430508531e-06 2.03908025579141e-06 6.5454616678027e-06 4.02062801328559e-07 2.65238452849705e-05 2965 2976 0 0 8 2966 2979 0 0 11 0 0 0 0 0 0 0 0 50 0 21 32 0 0 3064 +5 38 0.999985182904927 -0.000670394730030427 -0.00540227188365643 -0.0138921269889189 0.000730378049114559 0.999938025990076 0.0111090380760644 -0.000895923463432867 0.0053944896426232 -0.0111128191731902 0.999923699454873 -0.018990366210402 7.93250171222257e-05 5.63038073463057e-06 9.29025618257663e-06 3.1453684602545e-06 -1.79095413498251e-05 3.03980587462202e-05 5.63038073463057e-06 0.000126291401868479 -5.14168706739048e-06 3.36349566720141e-05 -2.2411949065247e-06 -2.46742933560508e-06 9.29025618257663e-06 -5.14168706739048e-06 1.96711290065492e-05 -6.02015466482139e-06 6.7433030433982e-07 1.00092590205691e-06 3.1453684602545e-06 3.36349566720141e-05 -6.02015466482139e-06 9.4479112367947e-05 9.22192664143734e-06 -1.4397818430202e-05 -1.79095413498251e-05 -2.2411949065247e-06 6.7433030433982e-07 9.22192664143734e-06 4.059223232987e-05 -1.26814864073355e-05 3.03980587462202e-05 -2.46742933560508e-06 1.00092590205691e-06 -1.4397818430202e-05 -1.26814864073355e-05 8.62225325848171e-05 2782 2799 0 0 14 2783 2800 0 0 15 0 0 0 0 0 0 0 0 69 0 15 22 0 0 2627 +5 40 0.999951088881593 -0.000113827599669372 -0.00988973648755425 -0.011287145627067 0.000203149785815054 0.999959196600962 0.0090312714123198 -0.0011552954632461 0.00988830494474314 -0.0090328387805836 0.999910310602348 -0.00810397662841531 3.56220290506637e-05 -2.69866852864941e-06 2.76662454004015e-06 1.59970523181277e-06 -2.50222565631819e-06 1.61046967863119e-05 -2.69866852864941e-06 9.0686835226776e-05 -4.78977087541289e-06 2.0793877181611e-05 1.82359314617335e-06 -8.10310342018292e-06 2.76662454004015e-06 -4.78977087541289e-06 1.43177488875808e-05 -8.01034602507612e-07 1.61366753006357e-06 1.30087181126043e-06 1.59970523181277e-06 2.0793877181611e-05 -8.01034602507612e-07 6.53948301070648e-05 1.21785990795631e-05 -1.57919706936568e-05 -2.50222565631819e-06 1.82359314617335e-06 1.61366753006357e-06 1.21785990795631e-05 2.95155677931834e-05 -7.78263110527068e-06 1.61046967863119e-05 -8.10310342018292e-06 1.30087181126043e-06 -1.57919706936568e-05 -7.78263110527068e-06 7.23479632756808e-05 2892 2892 0 1 4 2893 2902 0 1 4 0 0 0 0 0 0 0 0 69 0 14 17 0 0 2856 +5 45 0.99999949319272 0.000412124500831446 -0.00091856828773165 -0.00336423456857406 -0.000404685593328128 0.999967242872703 0.00808389826359414 0.00271048252634435 0.000921869770609973 -0.00808352243526311 0.999966902862872 -0.00557883291286376 5.02079220273732e-05 -2.76411539827382e-06 9.89890978034801e-06 1.58081893785084e-06 -4.48986018038652e-06 3.64519568410091e-05 -2.76411539827382e-06 2.90440289207805e-05 -2.59375912906591e-06 4.16539744660893e-06 -3.01617284750361e-06 1.585999573333e-05 9.89890978034801e-06 -2.59375912906591e-06 2.44647219060339e-05 -7.83288538418533e-06 -5.65189237725848e-06 6.94798527542096e-06 1.58081893785084e-06 4.16539744660893e-06 -7.83288538418533e-06 8.01868977318191e-05 4.20206193391655e-06 4.40020287914407e-06 -4.48986018038652e-06 -3.01617284750361e-06 -5.65189237725848e-06 4.20206193391655e-06 3.87180129254872e-05 -1.57479097085965e-05 3.64519568410091e-05 1.585999573333e-05 6.94798527542096e-06 4.40020287914407e-06 -1.57479097085965e-05 8.71184329597688e-05 2663 2672 0 1 10 2664 2673 0 1 11 0 0 0 0 0 0 0 0 27 0 14 25 0 0 2550 +4 30 0.999995554274844 -0.000146232382323397 -0.00297826235213702 -0.0090557728942483 0.000150953250735731 0.999998732580093 0.00158494521146377 0.000987701786435548 0.00297802680711391 -0.00158538774361657 0.999994308934825 0.00959218415658129 2.02617199418211e-05 1.03798972410378e-07 4.01230282725299e-06 7.27302655744462e-06 1.12285568590901e-06 -1.33408798878763e-06 1.03798972410378e-07 8.48183552920002e-05 -2.62285234329622e-06 2.11584568931371e-05 2.3925708528198e-06 -1.76661391082848e-05 4.01230282725299e-06 -2.62285234329622e-06 1.55945880722582e-05 1.14933367711012e-06 5.35953003664479e-06 1.67901009346451e-06 7.27302655744462e-06 2.11584568931371e-05 1.14933367711012e-06 5.49903856878231e-05 2.87229697573281e-08 -7.11968159597997e-06 1.12285568590901e-06 2.3925708528198e-06 5.35953003664479e-06 2.87229697573281e-08 3.01638569868433e-05 2.21251444024834e-06 -1.33408798878763e-06 -1.76661391082848e-05 1.67901009346451e-06 -7.11968159597997e-06 2.21251444024834e-06 3.7201802615519e-05 2896 2895 0 0 8 2902 2915 0 0 13 0 0 0 0 0 0 0 0 50 0 17 19 0 0 3129 +5 36 0.999995398607205 -0.000455945621027674 -0.00299914621301627 -0.0131164969457911 0.000486053097992828 0.999949423298019 0.0100456258314348 -0.00199724475173859 0.00299441426698373 -0.0100470373518727 0.999945043751729 -0.0151893020968239 5.92596855468531e-05 5.40696725314645e-06 6.42673628802793e-06 6.42800142068392e-06 -7.46186390252016e-06 2.36349355049396e-05 5.40696725314645e-06 7.17135627051139e-05 -7.98978683558626e-06 2.20041837650226e-05 3.08356254973337e-06 3.32087951464668e-06 6.42673628802793e-06 -7.98978683558626e-06 1.78454415439499e-05 -3.49483179634685e-06 -3.32016144643898e-06 1.45979252107061e-06 6.42800142068392e-06 2.20041837650226e-05 -3.49483179634685e-06 6.66967568461898e-05 1.04462399129743e-05 4.76205585161096e-06 -7.46186390252016e-06 3.08356254973337e-06 -3.32016144643898e-06 1.04462399129743e-05 3.69361324373887e-05 -1.43938727912181e-06 2.36349355049396e-05 3.32087951464668e-06 1.45979252107061e-06 4.76205585161096e-06 -1.43938727912181e-06 6.4754915251388e-05 2743 2751 0 0 6 2744 2752 0 0 7 0 0 0 0 0 0 0 0 59 0 22 33 0 0 2595 +5 39 0.999999649911913 -0.000598744352706181 0.000584535073581005 -0.00974535112830388 0.000595346817798627 0.999983029625258 0.00579534499887107 -0.0011471194786543 -0.000587995083891815 -0.00579499496889388 0.999983036003657 -0.0193545868502384 6.25119690429444e-05 1.16380074104403e-05 8.61572681999775e-06 -1.08903900177697e-06 -7.90586505407801e-06 1.98621280414661e-05 1.16380074104403e-05 4.32901989780669e-05 2.00704634856086e-06 1.05274419110922e-06 2.16299426390166e-06 4.82792450277496e-06 8.61572681999775e-06 2.00704634856086e-06 1.86668463126555e-05 -7.22376725262586e-06 -1.55204840958685e-06 2.37430897822434e-06 -1.08903900177697e-06 1.05274419110922e-06 -7.22376725262586e-06 7.93659374050978e-05 1.81433367677927e-05 1.01203273557785e-06 -7.90586505407801e-06 2.16299426390166e-06 -1.55204840958685e-06 1.81433367677927e-05 3.50637361098446e-05 -1.02684839846367e-05 1.98621280414661e-05 4.82792450277496e-06 2.37430897822434e-06 1.01203273557785e-06 -1.02684839846367e-05 6.41525873097935e-05 2795 2811 0 1 8 2796 2812 0 1 9 0 0 0 0 0 0 0 0 72 0 19 29 0 0 2788 +5 51 0.999999978588089 -0.00020216085332593 4.42132478391358e-05 -0.00212103601452457 0.000201403694296439 0.999863803927259 0.0165025159494791 0.00382069061758287 -4.75433888747885e-05 -0.0165025066914173 0.999863823234207 -0.00990759243894053 5.56495010518781e-05 -2.08737575762869e-06 8.28628859265435e-06 -5.48910839356279e-06 -1.37734953474966e-05 3.07106634131268e-05 -2.08737575762869e-06 3.47186382639389e-05 -2.12255693155613e-06 -5.70376867355499e-06 -1.17082065662908e-06 9.27028004464972e-06 8.28628859265435e-06 -2.12255693155613e-06 1.89844635852277e-05 -7.23085514571353e-06 -2.17671488355507e-06 4.74511488021391e-06 -5.48910839356279e-06 -5.70376867355499e-06 -7.23085514571353e-06 6.18301033620765e-05 1.00415104425157e-05 -4.79795234894161e-06 -1.37734953474966e-05 -1.17082065662908e-06 -2.17671488355507e-06 1.00415104425157e-05 3.53311439190481e-05 -1.81656610287367e-05 3.07106634131268e-05 9.27028004464972e-06 4.74511488021391e-06 -4.79795234894161e-06 -1.81656610287367e-05 7.18918755313744e-05 2918 2938 0 1 21 2919 2939 0 1 23 0 0 0 0 0 0 0 0 72 0 9 14 0 0 2782 +5 46 0.999989709194593 -0.000521722251404668 -0.00450658527105226 -0.0253270952611315 0.00058202215722323 0.999910187682697 0.0133894667019354 0.00613720590140115 0.0044991949414731 -0.0133919518460202 0.999900201455442 -0.0120029349528414 8.78945218874694e-05 -9.27738961965241e-06 8.42656287647546e-06 7.07739328705974e-06 -2.49285059481061e-05 4.84840355530527e-05 -9.27738961965241e-06 6.02710834281833e-05 -2.68519570474682e-06 1.50844501083303e-05 2.60905112979278e-06 -4.93707704597875e-06 8.42656287647546e-06 -2.68519570474682e-06 1.67691803681394e-05 6.08632608670472e-07 3.5077185025286e-07 3.15560069351402e-06 7.07739328705974e-06 1.50844501083303e-05 6.08632608670472e-07 8.43521612647998e-05 1.1011336446997e-06 -8.38016686684994e-06 -2.49285059481061e-05 2.60905112979278e-06 3.5077185025286e-07 1.1011336446997e-06 4.18765615252689e-05 -2.47110706828103e-05 4.84840355530527e-05 -4.93707704597875e-06 3.15560069351402e-06 -8.38016686684994e-06 -2.47110706828103e-05 9.29101991902646e-05 2918 2935 0 0 11 2919 2936 0 0 11 0 0 0 0 0 0 0 0 50 0 22 29 0 0 2604 +5 42 0.999998859131689 -0.000632733539168318 0.00137163537013245 -0.00188329575658632 0.000624216927251161 0.999980580930223 0.00620065445592852 -0.000337196874527476 -0.00137553209628855 -0.00619979118378229 0.999979835047052 -0.0180233655573449 6.19801173809037e-05 6.40440173360939e-06 8.43926965974147e-06 -5.18073948643948e-07 -1.39222840847217e-05 2.19654985449763e-05 6.40440173360939e-06 5.15425010764494e-05 3.49342861790747e-07 9.88879396447671e-06 3.42200004162062e-06 8.02833014438579e-06 8.43926965974147e-06 3.49342861790747e-07 1.6317337886558e-05 -3.44073549329842e-06 -1.65089394621849e-06 -1.95286739145948e-07 -5.18073948643948e-07 9.88879396447671e-06 -3.44073549329842e-06 5.5420322708981e-05 1.42865141536428e-05 -4.71556988355162e-06 -1.39222840847217e-05 3.42200004162062e-06 -1.65089394621849e-06 1.42865141536428e-05 3.58283489191148e-05 -1.24140726420148e-05 2.19654985449763e-05 8.02833014438579e-06 -1.95286739145948e-07 -4.71556988355162e-06 -1.24140726420148e-05 7.95816734606399e-05 2779 2797 0 0 19 2779 2797 0 0 19 0 0 0 0 0 0 0 0 67 0 9 16 0 0 2647 +5 49 0.999979586239934 0.000255657535994359 -0.0063844923552281 -0.00991399048964849 -0.000153138765010855 0.999871133845894 0.0160527957143142 0.00482557732896047 0.0063877736284505 -0.0160514903031196 0.99985076186755 -0.012712604708802 5.28528484678987e-05 -6.75607312493188e-06 6.45767234610075e-06 -6.30262661975206e-06 -6.9915942973256e-06 2.30008088753038e-05 -6.75607312493188e-06 3.8272730283559e-05 -5.13079656088687e-06 2.28370915094772e-06 5.16203454905288e-07 5.78268612891769e-06 6.45767234610075e-06 -5.13079656088687e-06 1.6178832203829e-05 -5.39855466878329e-06 -1.43677785960295e-06 1.81549015082737e-06 -6.30262661975206e-06 2.28370915094772e-06 -5.39855466878329e-06 6.51604155522794e-05 9.16613267909357e-06 -1.26158516133366e-05 -6.9915942973256e-06 5.16203454905288e-07 -1.43677785960295e-06 9.16613267909357e-06 3.50076091286503e-05 -2.93136742086131e-06 2.30008088753038e-05 5.78268612891769e-06 1.81549015082737e-06 -1.26158516133366e-05 -2.93136742086131e-06 7.49889380437781e-05 3013 3022 0 0 5 3014 3024 0 0 7 0 0 0 0 0 0 0 0 64 0 18 29 0 0 2638 +5 53 0.999061467312035 0.00986382527388484 -0.0421768832808975 0.00619617077547609 -0.00963087207790345 0.999937245525965 0.00572287628427946 -0.000378713959255964 0.042230685944503 -0.00531130501029449 0.999093768974536 -0.0278955219264305 6.70601979235698e-05 1.22926792727551e-05 1.6988825425561e-06 3.87317672226344e-06 -8.47933751450272e-06 3.78697165873469e-05 1.22926792727551e-05 0.000100460022799854 -1.84373313284402e-06 3.72857483265108e-05 1.93033321935305e-06 2.87627620225841e-05 1.6988825425561e-06 -1.84373313284402e-06 1.52058955115697e-05 -3.60057828783059e-06 -5.13480392523127e-06 -1.55329260225197e-06 3.87317672226344e-06 3.72857483265108e-05 -3.60057828783059e-06 8.74542398708244e-05 8.74956614308833e-06 1.38796228218903e-05 -8.47933751450272e-06 1.93033321935305e-06 -5.13480392523127e-06 8.74956614308833e-06 3.59341800244561e-05 -4.51715982248252e-06 3.78697165873469e-05 2.87627620225841e-05 -1.55329260225197e-06 1.38796228218903e-05 -4.51715982248252e-06 8.73123977145908e-05 2503 2503 0 0 0 2504 2517 0 0 0 0 0 0 0 0 0 0 0 57 0 34 37 0 0 2612 +5 50 0.999993269197956 -0.000587218795489365 0.00362170303452556 -0.00219499376169502 0.000547441204724021 0.999939630187697 0.0109743468242325 0.00271830075267185 -0.00362792873571656 -0.0109722902886041 0.999933221259756 -0.00993651872661496 4.7139600913805e-05 -2.14920336161826e-06 7.02120819193748e-06 -1.24011626501582e-06 -8.8389349401061e-06 1.89104043946644e-05 -2.14920336161826e-06 4.5415148992102e-05 -3.71317477330861e-06 1.01817024006185e-05 -1.48626514332861e-06 4.68801424606465e-06 7.02120819193748e-06 -3.71317477330861e-06 1.67564096223614e-05 -4.70136466466847e-06 -2.11040225621129e-06 -5.08946120299031e-07 -1.24011626501582e-06 1.01817024006185e-05 -4.70136466466847e-06 6.22802805990871e-05 1.37391379125772e-05 -3.44604923026266e-06 -8.8389349401061e-06 -1.48626514332861e-06 -2.11040225621129e-06 1.37391379125772e-05 3.58569609779498e-05 -8.49796275469227e-06 1.89104043946644e-05 4.68801424606465e-06 -5.08946120299031e-07 -3.44604923026266e-06 -8.49796275469227e-06 5.72453255722368e-05 2865 2867 0 0 12 2866 2881 0 0 13 0 0 0 0 0 0 0 0 62 0 32 36 0 0 2763 +5 48 0.999994343634626 0.000855615154761773 -0.00325278672225985 -0.0117958701766171 -0.000806767612085082 0.999887334595123 0.0149889039719685 0.0053499042693968 0.0032652449791185 -0.0149861949462745 0.999882369149621 -0.0177725921312865 6.41335226798978e-05 -3.92173619277644e-06 2.70921999739403e-06 1.1926886623645e-07 -8.78330371875758e-06 3.37456147967796e-05 -3.92173619277644e-06 5.54773874203579e-05 -6.49777062033151e-06 2.35891848659667e-05 2.22270074219633e-06 1.77738997074983e-06 2.70921999739403e-06 -6.49777062033151e-06 1.91942479089005e-05 -1.01356506248974e-05 -2.16382180211725e-07 3.24825908376702e-06 1.1926886623645e-07 2.35891848659667e-05 -1.01356506248974e-05 0.000109769928198661 1.42268026578777e-05 -9.96780543222032e-06 -8.78330371875758e-06 2.22270074219633e-06 -2.16382180211725e-07 1.42268026578777e-05 2.98603951469957e-05 -9.14183406384162e-06 3.37456147967796e-05 1.77738997074983e-06 3.24825908376702e-06 -9.96780543222032e-06 -9.14183406384162e-06 7.50737756396862e-05 2894 2896 0 1 5 2897 2911 0 1 6 0 0 0 0 0 0 0 0 48 0 37 41 0 0 2644 +5 35 0.999994675461932 -0.00010190486465687 -0.0032616963658953 -0.0186030147689971 0.000126636395193114 0.999971239824907 0.00758310531792808 0.00387109342346089 0.00326082980361562 -0.00758347799086514 0.999965928344838 -0.0114812122448744 3.49163304437958e-05 -3.34688818569941e-06 2.83640016456601e-06 7.27621305877494e-06 -3.27351009948735e-06 5.06549923838092e-06 -3.34688818569941e-06 3.04576047854391e-05 -3.67509348320721e-06 9.70838222094719e-07 2.18607924649172e-06 1.05060407559075e-05 2.83640016456601e-06 -3.67509348320721e-06 1.70150998249258e-05 -2.71535080336089e-06 -2.39154854123402e-06 -7.10202308464926e-07 7.27621305877494e-06 9.70838222094719e-07 -2.71535080336089e-06 5.83203005164546e-05 2.22858906068015e-06 9.27277908492663e-06 -3.27351009948735e-06 2.18607924649172e-06 -2.39154854123402e-06 2.22858906068015e-06 2.61967370014373e-05 -1.32612656563728e-06 5.06549923838092e-06 1.05060407559075e-05 -7.10202308464926e-07 9.27277908492663e-06 -1.32612656563728e-06 4.13948055527598e-05 2685 2693 0 1 3 2686 2694 0 1 4 0 0 0 0 0 0 0 0 63 0 25 36 0 0 2626 +5 43 0.99999970052114 0.000644108505421949 -0.00042904762295204 -0.00154804153073926 -0.000637806895379585 0.999894243414846 0.0145291151904155 0.00197469830353594 0.00043836057501097 -0.0145288371897203 0.999894354784505 -0.0210152733608495 7.57666124894889e-05 2.76936733321299e-05 1.24462233535104e-05 1.34817897507119e-05 -1.34490223354697e-05 3.67662712765622e-05 2.76936733321299e-05 6.57241902218333e-05 -5.15014262885374e-06 2.13525096779629e-05 -7.64479974668029e-06 2.29632087606885e-05 1.24462233535104e-05 -5.15014262885374e-06 2.2889386355828e-05 -8.88653911239737e-06 8.13016645912155e-07 4.23436874967644e-06 1.34817897507119e-05 2.13525096779629e-05 -8.88653911239737e-06 7.9643399554867e-05 4.66179306140651e-06 8.54604927264883e-06 -1.34490223354697e-05 -7.64479974668029e-06 8.13016645912155e-07 4.66179306140651e-06 3.04697845070742e-05 -1.47354370774009e-05 3.67662712765622e-05 2.29632087606885e-05 4.23436874967644e-06 8.54604927264883e-06 -1.47354370774009e-05 8.02867660043482e-05 2765 2783 0 0 17 2765 2783 0 0 17 0 0 0 0 0 0 0 0 18 0 11 17 0 0 2563 +5 47 0.999989187065646 -0.000380152544065463 -0.00463478541373161 -0.0124926716943564 0.000463763733876983 0.999836937852409 0.0180522195066618 0.00403712854415981 0.00462716705849693 -0.0180541737545865 0.999826302982199 -0.0211460950723385 6.81622389404653e-05 -1.87143149562924e-05 2.21068219239597e-06 -3.94831643265242e-06 -1.2148119965179e-05 4.66763457687362e-05 -1.87143149562924e-05 5.45939172069455e-05 -6.28539166512945e-06 1.04499362780189e-05 9.70198739463536e-06 1.31721258043649e-06 2.21068219239597e-06 -6.28539166512945e-06 1.63344425897286e-05 -4.34842208327031e-06 -1.054867955378e-06 1.02337295035249e-06 -3.94831643265242e-06 1.04499362780189e-05 -4.34842208327031e-06 7.34551702141754e-05 1.50472368985489e-05 -4.31656457003585e-06 -1.2148119965179e-05 9.70198739463536e-06 -1.054867955378e-06 1.50472368985489e-05 3.64303324253732e-05 -1.18650433489556e-05 4.66763457687362e-05 1.31721258043649e-06 1.02337295035249e-06 -4.31656457003585e-06 -1.18650433489556e-05 8.99200163285557e-05 2935 2953 0 0 12 2937 2955 0 0 14 0 0 0 0 0 0 0 0 57 0 15 22 0 0 2514 +5 34 0.999954225337802 0.00075422285967601 -0.00953825859131243 -0.0107404105995469 -0.000723875138976394 0.999994666717195 0.00318473577382723 0.0025531576602425 0.00954060972160455 -0.00317768548535961 0.999949438262303 0.00469612043307297 4.77496892048406e-05 1.10577821743771e-06 1.1399674595875e-06 7.88473881136527e-06 -5.61212197188259e-06 3.99125661615325e-06 1.10577821743771e-06 5.06798492276119e-05 -4.37246360458119e-06 1.13499226902497e-05 3.69149458767957e-06 -8.82145323953442e-06 1.1399674595875e-06 -4.37246360458119e-06 1.75109588845399e-05 -5.30481353329406e-06 -5.74780707301501e-06 -4.76735281576759e-07 7.88473881136527e-06 1.13499226902497e-05 -5.30481353329406e-06 8.19988850756346e-05 9.04081226658217e-06 1.32917637097537e-05 -5.61212197188259e-06 3.69149458767957e-06 -5.74780707301501e-06 9.04081226658217e-06 3.25701343401352e-05 -1.41141174803605e-06 3.99125661615325e-06 -8.82145323953442e-06 -4.76735281576759e-07 1.32917637097537e-05 -1.41141174803605e-06 4.26940518762721e-05 2818 2829 0 0 5 2819 2830 0 0 6 0 0 0 0 0 0 0 0 48 0 20 31 0 0 2770 +5 52 0.999830193504886 0.00433385479000874 -0.0179109424275031 -0.00327354050038208 -0.00406089167279603 0.999875490095419 0.0152483922191025 0.00336327802231103 0.0179747966554291 -0.0151730685461079 0.999723304057723 -0.016664528364508 6.66059770850396e-05 -1.29817818701309e-05 8.04007401970179e-06 -4.49036881784367e-06 -1.47035631468154e-05 3.89060440856598e-05 -1.29817818701309e-05 5.1857156253994e-05 -8.70344868935213e-06 1.64168571790645e-05 1.39138133552557e-06 -7.15613484775418e-07 8.04007401970179e-06 -8.70344868935213e-06 1.8755538355051e-05 -3.96372205707837e-06 -3.47732917798239e-06 5.33024670836882e-06 -4.49036881784367e-06 1.64168571790645e-05 -3.96372205707837e-06 6.50791766845581e-05 8.75173283845307e-06 -7.62918084255615e-06 -1.47035631468154e-05 1.39138133552557e-06 -3.47732917798239e-06 8.75173283845307e-06 3.78207383410091e-05 -2.33531554705915e-05 3.89060440856598e-05 -7.15613484775418e-07 5.33024670836882e-06 -7.62918084255615e-06 -2.33531554705915e-05 8.67357606906952e-05 2784 2783 0 1 3 2786 2799 0 1 3 0 0 0 0 0 0 0 0 59 0 38 40 0 0 2588 +5 31 0.999965768383171 -4.36008838094273e-05 -0.0082740655555439 -0.01466158965627 6.94769115590135e-05 0.99999510818509 0.003127103907545 0.00276481292913367 0.00827388873585252 -0.00312757171824308 0.999960879764971 0.00376932962351452 2.26354850676567e-05 -6.00275215866924e-07 2.27808470433564e-06 2.5693659792692e-06 -1.39494451160493e-06 2.80505230207621e-06 -6.00275215866924e-07 7.23682073789552e-05 -4.74970371889875e-06 1.67674737710512e-05 -2.42532388850896e-06 -2.97139649556846e-05 2.27808470433564e-06 -4.74970371889875e-06 1.27428304207859e-05 4.31865909395183e-07 4.45421670133246e-06 2.57434997207788e-06 2.5693659792692e-06 1.67674737710512e-05 4.31865909395183e-07 4.87514437039148e-05 -1.60038825200235e-06 -9.41744393893157e-06 -1.39494451160493e-06 -2.42532388850896e-06 4.45421670133246e-06 -1.60038825200235e-06 2.29504984175287e-05 3.6650099885333e-06 2.80505230207621e-06 -2.97139649556846e-05 2.57434997207788e-06 -9.41744393893157e-06 3.6650099885333e-06 5.04789624211295e-05 2934 2945 0 0 8 2935 2946 0 0 9 0 0 0 0 0 0 0 0 57 0 21 33 0 0 2867 +5 32 0.999992175771361 0.000328132453238822 -0.00394217264372701 -0.00718835830440164 -0.000335670190211363 0.999998116616074 -0.00191156737480911 -0.000810257357252894 0.00394153797181019 0.00191287568811008 0.999990402546454 0.0062407479668225 4.55318919049704e-05 -9.59062504504168e-06 5.11354197779172e-06 -5.84665475455728e-06 -6.82353747308965e-06 8.59701957033819e-06 -9.59062504504168e-06 3.82523567832943e-05 -7.42262165619747e-07 -5.82137467448822e-06 2.26870300719273e-07 -2.15811996522377e-06 5.11354197779172e-06 -7.42262165619747e-07 1.3860179496063e-05 -6.9238519645181e-07 3.17686015538012e-06 2.55891305281637e-06 -5.84665475455728e-06 -5.82137467448822e-06 -6.9238519645181e-07 5.03011930615191e-05 1.00864188613395e-06 -3.71808531204006e-06 -6.82353747308965e-06 2.26870300719273e-07 3.17686015538012e-06 1.00864188613395e-06 2.34137392179163e-05 -4.01510483897349e-06 8.59701957033819e-06 -2.15811996522377e-06 2.55891305281637e-06 -3.71808531204006e-06 -4.01510483897349e-06 4.29657475794752e-05 2987 2987 0 2 5 2991 3001 0 2 5 0 0 0 0 0 0 0 0 45 0 13 16 0 0 2746 +5 7 0.999997803694503 0.000705418856944433 0.0019735730049978 0.00115361430598367 -0.000703519712500209 0.999999289022242 -0.000962816195046244 -0.000918232957647375 -0.00197425079053104 0.000961425632894668 0.999997588994378 0.00564164449644203 2.44636017470446e-05 -8.80104621601749e-07 3.58807933292745e-06 4.11737636209239e-06 3.29284601172197e-06 3.08692891354703e-06 -8.80104621601749e-07 4.64525773859199e-05 -3.80135611357916e-06 8.88710832833576e-06 1.17187772558836e-06 -1.2539856010282e-05 3.58807933292745e-06 -3.80135611357916e-06 1.47606321321458e-05 -1.91697838313049e-06 1.86182189185707e-06 2.186371112611e-06 4.11737636209239e-06 8.88710832833576e-06 -1.91697838313049e-06 4.50396290836541e-05 6.50868513046102e-06 -1.88432616695693e-06 3.29284601172197e-06 1.17187772558836e-06 1.86182189185707e-06 6.50868513046102e-06 2.17350497886933e-05 -1.22075747827781e-06 3.08692891354703e-06 -1.2539856010282e-05 2.186371112611e-06 -1.88432616695693e-06 -1.22075747827781e-06 3.64715636018507e-05 2898 2904 0 2 13 2898 2904 0 2 13 0 0 0 0 0 0 0 0 60 0 12 23 0 0 2866 +6 36 0.999990582150659 -0.000598364866730391 -0.00429855434677736 -0.0176451925847986 0.000649022554340037 0.999930248263536 0.0117931071964946 -0.00213848094672243 0.00429119793413142 -0.0117957859895099 0.9999212194234 -0.0138030321712388 6.75678313518171e-05 1.22313175758578e-05 4.27212925405118e-06 1.3342330504612e-05 -7.1582657818897e-06 2.25927318198678e-05 1.22313175758578e-05 7.46422386354167e-05 -5.23426017789544e-06 2.29405200142582e-05 -7.9227852521989e-06 -8.90122254826079e-06 4.27212925405118e-06 -5.23426017789544e-06 1.75232556002945e-05 -1.71642726817984e-06 -1.67095079832652e-06 2.0441709742727e-06 1.3342330504612e-05 2.29405200142582e-05 -1.71642726817984e-06 8.25153417009556e-05 6.28476540054796e-06 -1.73011228118761e-06 -7.1582657818897e-06 -7.9227852521989e-06 -1.67095079832652e-06 6.28476540054796e-06 3.91167532341168e-05 -3.55746600742249e-06 2.25927318198678e-05 -8.90122254826079e-06 2.0441709742727e-06 -1.73011228118761e-06 -3.55746600742249e-06 8.1166282194328e-05 2765 2773 0 1 3 2766 2774 0 1 4 0 0 0 0 0 0 0 0 55 0 19 30 0 0 2514 +5 9 0.999999641946394 -0.000574863644670676 -0.000620998288084825 -0.00719508905929298 0.000576133358112227 0.999997740171462 0.00204639251440348 0.000213523408243737 0.000619820488075915 -0.00204674955951435 0.999997713316787 0.0105856871324331 3.5952766278742e-05 1.54171025086395e-06 5.91902267147149e-06 -2.08272698031825e-08 -6.54954762484151e-06 1.95590223649922e-06 1.54171025086395e-06 5.4119402057404e-05 -4.75525490076634e-06 1.01820993353476e-05 2.24000490573607e-06 -7.94503887373792e-06 5.91902267147149e-06 -4.75525490076634e-06 1.59666659437725e-05 -2.07933732061442e-06 1.78315348547996e-06 2.69974134348631e-07 -2.08272698031825e-08 1.01820993353476e-05 -2.07933732061442e-06 3.94703318259857e-05 3.08060326269769e-06 -6.91815033173592e-07 -6.54954762484151e-06 2.24000490573607e-06 1.78315348547996e-06 3.08060326269769e-06 2.66223555315433e-05 -2.8237578183575e-07 1.95590223649922e-06 -7.94503887373792e-06 2.69974134348631e-07 -6.91815033173592e-07 -2.8237578183575e-07 3.87747715289648e-05 2902 2913 0 0 9 2903 2914 0 0 10 0 0 0 0 0 0 0 0 50 0 17 28 0 0 2776 +6 41 0.999999920972279 -0.000191295330527449 -0.000348513317635679 -0.0020829626708175 0.000194798663663745 0.999949175785072 0.0100800744161707 0.0021056865499577 0.000346567333552735 -0.0100801415094939 0.999949134025442 -0.0251180985244356 5.79683861602359e-05 2.49436854910479e-06 7.02245616250737e-06 -4.48206999434476e-06 -1.03380061297384e-05 4.13218843958621e-05 2.49436854910479e-06 4.92631981597413e-05 -4.05498749076729e-06 7.2418103507224e-06 -3.84377527552059e-06 5.53362709824852e-06 7.02245616250737e-06 -4.05498749076729e-06 1.78178134237216e-05 -3.71605839159078e-06 -1.24498963246593e-07 4.93002168532937e-06 -4.48206999434476e-06 7.2418103507224e-06 -3.71605839159078e-06 6.95589846872299e-05 8.41873502264687e-06 -1.01920813575726e-05 -1.03380061297384e-05 -3.84377527552059e-06 -1.24498963246593e-07 8.41873502264687e-06 3.26652365757803e-05 -1.56924086746396e-05 4.13218843958621e-05 5.53362709824852e-06 4.93002168532937e-06 -1.01920813575726e-05 -1.56924086746396e-05 8.46898057145812e-05 2905 2907 0 2 9 2907 2925 0 2 11 0 0 0 0 0 0 0 0 90 0 10 12 0 0 2617 +5 33 0.999998411017931 0.0006454149627244 -0.00166174641247407 -0.00836868258635945 -0.000639767096795243 0.999994025375751 0.00339704443069052 0.00336099323368485 0.00166392898746827 -0.00339597590216992 0.999992849318432 -0.00489182047498156 5.80160439690568e-05 -9.29221174799521e-06 -2.06088525165096e-06 8.68724470262859e-06 -1.39417173174073e-06 5.72636446279204e-06 -9.29221174799521e-06 1.94547957231735e-05 -5.50247748647805e-06 -4.06905995581695e-06 -9.61410040185615e-08 7.78310702217004e-06 -2.06088525165096e-06 -5.50247748647805e-06 1.21679478607893e-05 1.02458069437871e-06 -3.38582177862453e-07 -7.86932467659082e-07 8.68724470262859e-06 -4.06905995581695e-06 1.02458069437871e-06 4.83480720466689e-05 -2.72317596561726e-06 5.22756448028292e-06 -1.39417173174073e-06 -9.61410040185615e-08 -3.38582177862453e-07 -2.72317596561726e-06 2.39292283523048e-05 4.25237311848882e-06 5.72636446279204e-06 7.78310702217004e-06 -7.86932467659082e-07 5.22756448028292e-06 4.25237311848882e-06 4.08794956735823e-05 2790 2790 0 1 5 2792 2802 0 1 6 0 0 0 0 0 0 0 0 64 0 13 16 0 0 2790 +6 49 0.999962008702909 0.000272470661517037 -0.00871245720695198 -0.0155132023682373 -0.000105274339155624 0.999815941708304 0.0191851928124521 0.00697072018920515 0.00871608100913893 -0.0191835467439174 0.999777986087995 -0.0127995820940604 7.94556649962917e-05 -8.04301659233651e-06 -3.66743347083103e-06 4.38488074177056e-06 -8.64502558095371e-06 4.50980029679916e-05 -8.04301659233651e-06 4.91469354642395e-05 -8.29087694456429e-06 1.33035345032783e-05 5.54375772332979e-06 5.13133869396903e-06 -3.66743347083103e-06 -8.29087694456429e-06 1.74796821541502e-05 -3.89486998316919e-07 -1.69494218176333e-06 -2.0227924453298e-06 4.38488074177056e-06 1.33035345032783e-05 -3.89486998316919e-07 7.87484241196715e-05 6.37517496751725e-06 -4.06197553176973e-06 -8.64502558095371e-06 5.54375772332979e-06 -1.69494218176333e-06 6.37517496751725e-06 3.50157053571866e-05 -4.71046439575794e-06 4.50980029679916e-05 5.13133869396903e-06 -2.0227924453298e-06 -4.06197553176973e-06 -4.71046439575794e-06 8.50504475586223e-05 2974 2986 0 0 4 2975 2987 0 0 5 0 0 0 0 0 0 0 0 58 0 16 24 0 0 2419 +6 46 0.999990209634277 -0.00108739403755009 -0.00428931344176635 -0.0304318245329535 0.00112423792201249 0.999962416102841 0.00859665463209412 0.00447446609442524 0.00427980428166125 -0.00860139267653191 0.999953848594691 -0.0144632485181377 2.91192301253938e-05 -2.22985333369339e-06 2.34864311630446e-06 4.68322470643268e-06 -3.92678678420258e-06 2.05223369919273e-05 -2.22985333369339e-06 6.64931475059112e-05 -4.67316426123174e-07 9.580614502461e-06 -1.32165668316811e-06 -1.09693623424658e-06 2.34864311630446e-06 -4.67316426123174e-07 1.79280749597271e-05 9.29367873025614e-07 1.92612082585518e-07 -8.22477155752317e-07 4.68322470643268e-06 9.580614502461e-06 9.29367873025614e-07 8.3899841381625e-05 -8.82175005931348e-06 -8.66409067277949e-07 -3.92678678420258e-06 -1.32165668316811e-06 1.92612082585518e-07 -8.82175005931348e-06 3.35211273509455e-05 -1.15512686265301e-05 2.05223369919273e-05 -1.09693623424658e-06 -8.22477155752317e-07 -8.66409067277949e-07 -1.15512686265301e-05 6.46646919974316e-05 2954 2956 0 0 0 2956 2972 0 0 0 0 0 0 0 0 0 0 0 42 0 24 27 0 0 2917 +5 8 0.999999922000487 -0.000297589184751586 0.000259691540931189 -0.00373572043082166 0.000297045081968523 0.999997766145146 0.00209271807407061 0.00149010561341262 -0.000260313731083557 -0.00209264077074456 0.999997776543211 0.00870397776930829 4.78028178533557e-05 -2.71508150392986e-06 1.05745306196757e-05 -7.31187146247847e-06 -3.21910765957612e-06 6.89200463038445e-06 -2.71508150392986e-06 2.18471302237606e-05 -2.97678297771602e-06 -2.12902964276732e-07 8.50027504845673e-07 -9.84594408018768e-07 1.05745306196757e-05 -2.97678297771602e-06 1.65708692380801e-05 -3.55525723739259e-06 2.92497219375424e-06 3.04297507682454e-06 -7.31187146247847e-06 -2.12902964276732e-07 -3.55525723739259e-06 4.32278847985671e-05 2.50511926136798e-06 -2.36911489619263e-06 -3.21910765957612e-06 8.50027504845673e-07 2.92497219375424e-06 2.50511926136798e-06 1.98475662112727e-05 -3.81279464750143e-06 6.89200463038445e-06 -9.84594408018768e-07 3.04297507682454e-06 -2.36911489619263e-06 -3.81279464750143e-06 3.08098860082749e-05 2682 2701 0 0 21 2682 2701 0 0 21 0 0 0 0 0 0 0 0 74 0 9 15 0 0 2769 +6 48 0.99999359900787 0.000160502706844962 -0.00357437857098681 -0.018031517519818 -8.44617930567872e-05 0.999773894534005 0.0212638819248346 0.00614389398814059 0.00357698329506134 -0.0212634439164706 0.999767508545521 -0.0187814984432494 8.1235216446687e-05 -1.02319596473754e-06 8.95081675349907e-06 4.55187822379046e-06 -1.02759882803003e-05 3.75480950672155e-05 -1.02319596473754e-06 5.30647045717009e-05 -6.35749933755279e-06 1.90365808557757e-05 2.93790018689754e-06 -3.20478166666474e-07 8.95081675349907e-06 -6.35749933755279e-06 2.18753726313798e-05 -7.69781799202002e-06 2.21681042610174e-07 1.63217479307206e-06 4.55187822379046e-06 1.90365808557757e-05 -7.69781799202002e-06 0.000104871568458247 1.22135530846938e-05 -8.08988182409003e-06 -1.02759882803003e-05 2.93790018689754e-06 2.21681042610174e-07 1.22135530846938e-05 3.5788257680569e-05 -9.62599113028985e-06 3.75480950672155e-05 -3.20478166666474e-07 1.63217479307206e-06 -8.08988182409003e-06 -9.62599113028985e-06 6.23720421980955e-05 2989 2989 0 1 2 2992 3007 0 1 5 0 0 0 0 0 0 0 0 43 0 19 23 0 0 2433 +6 40 0.999933478720333 -0.000419691666482143 -0.011526577686257 -0.0180728809384018 0.000532093332598708 0.999952324235525 0.0097501862883568 -0.000174440684316923 0.0115219360759222 -0.00975567090862245 0.999886029442449 -0.0136409558618972 4.91578266718911e-05 1.01915904009455e-05 7.46025530692629e-07 1.652491209579e-05 -1.03383972683904e-05 3.01301035689977e-05 1.01915904009455e-05 6.77065515661094e-05 -2.28203096501907e-06 2.21717651590173e-05 -9.63369833653739e-06 6.09336538609499e-06 7.46025530692629e-07 -2.28203096501907e-06 1.30355160182898e-05 -5.29832064383009e-07 -3.19079877550231e-07 1.96154069671429e-07 1.652491209579e-05 2.21717651590173e-05 -5.29832064383009e-07 7.31660461118532e-05 -1.22406579728193e-06 1.4407722277363e-05 -1.03383972683904e-05 -9.63369833653739e-06 -3.19079877550231e-07 -1.22406579728193e-06 3.84198817364689e-05 -1.18045893341186e-05 3.01301035689977e-05 6.09336538609499e-06 1.96154069671429e-07 1.4407722277363e-05 -1.18045893341186e-05 8.53530471665555e-05 2954 2954 0 1 2 2956 2956 0 1 4 0 0 0 0 0 0 0 0 58 0 22 35 0 0 2645 +6 35 0.999996108552009 0.000563618079343377 -0.00273225465499239 -0.0205083197968681 -0.000529627282689552 0.999922661876693 0.0124253676150939 0.00614085822998893 0.00273904650937534 -0.0124238721858135 0.999919069237171 -0.0108978092163038 5.36119013293933e-05 -1.03255152272184e-05 4.1257786201887e-06 9.90035941218928e-06 -1.4410511319835e-05 1.37846695503252e-06 -1.03255152272184e-05 2.23490917038658e-05 -2.77216468896056e-06 -2.38185704690569e-06 -1.90275324630147e-06 9.54334394294878e-06 4.1257786201887e-06 -2.77216468896056e-06 1.62166818279225e-05 2.3541486334617e-06 -8.62744196347017e-07 4.98082800589089e-08 9.90035941218928e-06 -2.38185704690569e-06 2.3541486334617e-06 5.94340666985226e-05 1.95260319878904e-07 4.44921770830968e-06 -1.4410511319835e-05 -1.90275324630147e-06 -8.62744196347017e-07 1.95260319878904e-07 3.35807996217821e-05 -3.04129128495959e-06 1.37846695503252e-06 9.54334394294878e-06 4.98082800589089e-08 4.44921770830968e-06 -3.04129128495959e-06 3.84830910998403e-05 2727 2736 0 1 2 2728 2737 0 1 3 0 0 0 0 0 0 0 0 66 0 20 30 0 0 2397 +6 37 0.999887880937535 -3.32167408929926e-05 -0.0149741260477667 -0.0209090974174247 0.000310359361981884 0.999828698259749 0.0185061560914968 0.00501726267143903 0.0149709462397241 -0.0185087285588325 0.9997166087126 -0.0188164724067823 6.48623089561e-05 3.4636144538711e-06 -1.8019728250879e-06 1.20044444381553e-05 -1.90262264256647e-05 4.35105650715436e-05 3.4636144538711e-06 4.84450490440184e-05 -3.74705586363876e-06 1.2681550092673e-05 -4.99071924686822e-06 1.42089064625266e-05 -1.8019728250879e-06 -3.74705586363876e-06 1.38662520550625e-05 3.38746461491148e-06 1.04092423828938e-06 -1.27217291406824e-07 1.20044444381553e-05 1.2681550092673e-05 3.38746461491148e-06 7.22727421244699e-05 2.24792915443728e-06 1.90214900289672e-05 -1.90262264256647e-05 -4.99071924686822e-06 1.04092423828938e-06 2.24792915443728e-06 4.61446800854157e-05 -1.46830971923602e-05 4.35105650715436e-05 1.42089064625266e-05 -1.27217291406824e-07 1.90214900289672e-05 -1.46830971923602e-05 9.70895926264326e-05 2893 2904 0 1 3 2894 2905 0 1 4 0 0 0 0 0 0 0 0 53 0 20 30 0 0 2648 +6 39 0.999999985742761 0.000153013328333107 -7.14240835082792e-05 -0.0121368522723291 -0.000151954331612681 0.999893423295384 0.0145985944706957 0.00102726877981703 7.36502508937751e-05 -0.0145985834093611 0.999893432290702 -0.0177738261770385 7.00175990152647e-05 1.36584108544326e-05 1.25899967745043e-05 5.78085313103518e-07 -1.64473383424495e-05 2.9766773564837e-05 1.36584108544326e-05 4.55019674337255e-05 3.64963656545286e-06 -2.62138801894495e-06 -2.7040322999702e-06 1.05525655864078e-05 1.25899967745043e-05 3.64963656545286e-06 2.31762103485898e-05 -6.70211925484527e-06 6.41454066764017e-08 2.82756092992891e-06 5.78085313103518e-07 -2.62138801894495e-06 -6.70211925484527e-06 6.73904653419481e-05 7.3804369834956e-06 3.0403628690456e-06 -1.64473383424495e-05 -2.7040322999702e-06 6.41454066764017e-08 7.3804369834956e-06 4.29327978682619e-05 -1.40364668243098e-05 2.9766773564837e-05 1.05525655864078e-05 2.82756092992891e-06 3.0403628690456e-06 -1.40364668243098e-05 6.95577860445368e-05 2787 2805 0 1 5 2788 2806 0 1 6 0 0 0 0 0 0 0 0 69 0 15 23 0 0 2704 +6 45 0.999993210004861 -0.000509548456210739 -0.00364969924035666 -0.0128021126266508 0.000540233903065525 0.999964475774406 0.00841161913947723 0.00484128525092934 0.00364528346007074 -0.0084135337158898 0.999957961295827 -0.00985606523383245 5.06315189670264e-05 8.40891715368735e-07 7.31050449392173e-06 9.6801511465279e-06 -1.36897318074556e-05 3.06741438304376e-05 8.40891715368735e-07 2.56293082989339e-05 -5.34835134747853e-06 8.8641308135053e-06 -4.5657492033606e-06 1.17588081014583e-05 7.31050449392173e-06 -5.34835134747853e-06 2.50119614982288e-05 -6.10754259854598e-06 -9.68125460832821e-06 5.98399928438425e-07 9.6801511465279e-06 8.8641308135053e-06 -6.10754259854598e-06 9.86210050639944e-05 -7.47119097789682e-06 7.23378053817279e-06 -1.36897318074556e-05 -4.5657492033606e-06 -9.68125460832821e-06 -7.47119097789682e-06 5.01134326755654e-05 -1.31808741953006e-05 3.06741438304376e-05 1.17588081014583e-05 5.98399928438425e-07 7.23378053817279e-06 -1.31808741953006e-05 6.85183735033335e-05 2667 2681 0 1 6 2668 2683 0 1 8 0 0 0 0 0 0 0 0 27 0 15 21 0 0 2349 +6 38 0.999979178117612 0.000180333753369013 -0.00645064422852617 -0.0167558820473953 -7.10132598072272e-05 0.999856447144399 0.0169434371039936 -0.000146599826914287 0.00645277369373463 -0.0169426262284644 0.999835641057139 -0.0199221701827463 8.14007570225102e-05 1.37625835435773e-06 1.23765767265207e-05 -8.37887262851104e-06 -1.41879388062292e-05 3.16526270210254e-05 1.37625835435773e-06 8.04535154866689e-05 -9.59821795826037e-06 3.79714884225696e-05 -4.90527789067754e-06 -6.44448248003582e-06 1.23765767265207e-05 -9.59821795826037e-06 2.21185958615447e-05 -1.08627502816737e-05 1.69231847978037e-06 5.97086216892121e-06 -8.37887262851104e-06 3.79714884225696e-05 -1.08627502816737e-05 0.000101319124729583 1.31252164813747e-05 -1.48060886181129e-05 -1.41879388062292e-05 -4.90527789067754e-06 1.69231847978037e-06 1.31252164813747e-05 4.31023010076311e-05 -1.48530241599105e-05 3.16526270210254e-05 -6.44448248003582e-06 5.97086216892121e-06 -1.48060886181129e-05 -1.48530241599105e-05 7.70122334589965e-05 2774 2775 0 1 1 2778 2795 0 1 2 0 0 0 0 0 0 0 0 60 0 20 22 0 0 2404 +6 51 0.999999446431251 0.000395606627106819 0.00097500389140331 -0.000850674131756927 -0.000403773857626564 0.999964715933632 0.00839070047388986 0.00203743836632928 -0.000971650072587758 -0.00839108951014273 0.999964322120029 -0.0146168380721417 2.8721447742672e-05 -3.33556638991638e-07 3.31699271053958e-06 7.56657157598906e-06 -3.44367016855368e-06 2.32357459720367e-05 -3.33556638991638e-07 3.13852688880873e-05 -6.42457544015839e-06 5.04142714096811e-07 -3.20262237411928e-07 4.32533756298633e-06 3.31699271053958e-06 -6.42457544015839e-06 1.89984314811103e-05 -6.10276737940172e-06 -1.02799281057416e-06 2.5828622677082e-06 7.56657157598906e-06 5.04142714096811e-07 -6.10276737940172e-06 6.10524610513775e-05 8.47993967281822e-06 7.32091517308455e-06 -3.44367016855368e-06 -3.20262237411928e-07 -1.02799281057416e-06 8.47993967281822e-06 3.2234437807346e-05 -9.80332858124346e-06 2.32357459720367e-05 4.32533756298633e-06 2.5828622677082e-06 7.32091517308455e-06 -9.80332858124346e-06 6.19624550294881e-05 2865 2867 0 1 9 2866 2884 0 1 9 0 0 0 0 0 0 0 0 74 0 10 12 0 0 3097 +6 50 0.999996791059923 -0.000469428434969837 0.00248947922268176 -0.00389529128936032 0.000454686644194812 0.999982379786575 0.00591889993447505 -7.94388587161058e-05 -0.00249221385745953 -0.00591774900812629 0.99997938434588 -0.0108047108565472 2.64657483298578e-05 1.98113083135726e-08 6.79623923851526e-07 5.32252405061833e-06 2.15255174173184e-06 1.60289919764416e-05 1.98113083135726e-08 4.19416706828968e-05 -2.64259940950724e-06 3.44419250689658e-06 -1.23000556624352e-06 8.10546363126622e-06 6.79623923851526e-07 -2.64259940950724e-06 1.89489578838875e-05 -2.52930562689342e-06 -2.26922710988902e-06 2.5593932546261e-06 5.32252405061833e-06 3.44419250689658e-06 -2.52930562689342e-06 6.51723616024162e-05 8.90295801159326e-06 1.72732545004406e-06 2.15255174173184e-06 -1.23000556624352e-06 -2.26922710988902e-06 8.90295801159326e-06 2.85275706301919e-05 -5.61950365791791e-06 1.60289919764416e-05 8.10546363126622e-06 2.5593932546261e-06 1.72732545004406e-06 -5.61950365791791e-06 6.36730904335992e-05 2951 2951 0 0 7 2953 2970 0 0 11 0 0 0 0 0 0 0 0 59 0 13 16 0 0 3088 +6 47 0.999995468878929 0.0012359531964024 -0.00274493010976602 -0.0150955859823464 -0.00117685158994938 0.999769670941945 0.0214294210133977 0.0089752016876888 0.00277078363399798 -0.0214260935387326 0.999766595398007 -0.0211084883440182 5.67404993010043e-05 -5.06764404212197e-06 -5.59235493150801e-07 -3.97081951160811e-07 -1.21022890343782e-05 4.02376267526421e-05 -5.06764404212197e-06 5.5494438871442e-05 -5.28602647650292e-06 1.16261669896549e-05 9.16722448188509e-08 5.91435992805565e-06 -5.59235493150801e-07 -5.28602647650292e-06 1.54459521944069e-05 9.08779575800333e-08 1.93696002375272e-06 2.1062952364696e-06 -3.97081951160811e-07 1.16261669896549e-05 9.08779575800333e-08 9.10878119418076e-05 5.45396273099019e-06 -2.09399424043449e-06 -1.21022890343782e-05 9.16722448188509e-08 1.93696002375272e-06 5.45396273099019e-06 3.47714514791039e-05 -1.26373582281695e-05 4.02376267526421e-05 5.91435992805565e-06 2.1062952364696e-06 -2.09399424043449e-06 -1.26373582281695e-05 7.4104498086629e-05 2923 2928 0 0 1 2923 2941 0 0 1 0 0 0 0 0 0 0 0 55 0 18 21 0 0 2680 +6 52 0.999813150528662 0.0045733236224402 -0.0187816064540886 -0.00814358867172966 -0.00416571230022876 0.999756179306544 0.0216847591504511 0.00718335730513935 0.0188761985310485 -0.0216024685956439 0.99958842654344 -0.0146742248289215 7.41740929046657e-05 -8.7840860107731e-06 -5.86949340693214e-07 9.78496925046233e-06 -1.9147507845009e-05 5.26509554325026e-05 -8.7840860107731e-06 4.44522101365925e-05 -2.28469983305117e-06 1.11841868752993e-05 2.30865156855189e-06 -4.52861086232111e-06 -5.86949340693214e-07 -2.28469983305117e-06 1.90459266234563e-05 -7.67972139221943e-08 -3.11310806798677e-06 1.52891350947475e-06 9.78496925046233e-06 1.11841868752993e-05 -7.67972139221943e-08 8.00458778735126e-05 -3.10261512344994e-06 -2.70072231183152e-06 -1.9147507845009e-05 2.30865156855189e-06 -3.11310806798677e-06 -3.10261512344994e-06 4.41975726456791e-05 -2.11732284730472e-05 5.26509554325026e-05 -4.52861086232111e-06 1.52891350947475e-06 -2.70072231183152e-06 -2.11732284730472e-05 9.10640885444591e-05 2791 2790 0 1 0 2799 2812 0 1 4 0 0 0 0 0 0 0 0 57 0 22 24 0 0 2725 +6 33 0.99999930659046 0.000595339796863353 -0.00101606551195243 -0.0108144447292518 -0.000584320729472062 0.999941389820122 0.0108108969973492 0.00578895794227959 0.00102244211739232 -0.010810295792829 0.999941044320608 -0.00459750240437838 5.56239283647232e-05 -9.40652057581613e-06 2.54157144269345e-06 -1.70337404504894e-06 -6.13597138314626e-06 1.1166888932502e-05 -9.40652057581613e-06 2.21581221078074e-05 -9.80112631877766e-06 1.55184386652065e-06 -6.99961840076665e-07 2.47037996815262e-06 2.54157144269345e-06 -9.80112631877766e-06 1.55882185937096e-05 1.13676378752162e-06 7.60519109634434e-07 4.20055977031827e-07 -1.70337404504894e-06 1.55184386652065e-06 1.13676378752162e-06 5.97157736384146e-05 -1.09903933135354e-06 1.78879481606621e-06 -6.13597138314626e-06 -6.99961840076665e-07 7.60519109634434e-07 -1.09903933135354e-06 3.2569863616619e-05 1.67830001746219e-06 1.1166888932502e-05 2.47037996815262e-06 4.20055977031827e-07 1.78879481606621e-06 1.67830001746219e-06 3.5986984483244e-05 2763 2764 0 1 5 2764 2766 0 1 7 0 0 0 0 0 0 0 0 59 0 15 28 0 0 2689 +6 42 0.999998419905665 -0.000824575271908017 -0.00157488469217739 -0.00789845333887904 0.000837639862655597 0.999965095416054 0.00831302045121518 -8.15047555524554e-05 0.00156797501038351 -0.00831432650205591 0.999964206073989 -0.0137634716338167 7.11102546829044e-05 -9.31822510352482e-06 4.81913236780467e-06 4.8473196597596e-06 -1.87319085662209e-05 2.03711883277982e-05 -9.31822510352482e-06 6.23019703788517e-05 6.41505355550061e-07 8.05665401204684e-06 -2.57433244799392e-06 8.05253188289218e-06 4.81913236780467e-06 6.41505355550061e-07 1.69975448942621e-05 -2.81452586159393e-06 1.77112269665436e-07 -4.46125846841705e-08 4.8473196597596e-06 8.05665401204684e-06 -2.81452586159393e-06 5.82659709112859e-05 4.41017492401967e-06 -1.29312469760935e-06 -1.87319085662209e-05 -2.57433244799392e-06 1.77112269665436e-07 4.41017492401967e-06 3.93741987401922e-05 -1.20476427981079e-05 2.03711883277982e-05 8.05253188289218e-06 -4.46125846841705e-08 -1.29312469760935e-06 -1.20476427981079e-05 7.08701992636589e-05 2757 2758 0 0 7 2758 2775 0 0 7 0 0 0 0 0 0 0 0 60 0 13 15 0 0 2639 +6 53 0.998778899696837 0.00990813963057655 -0.0483997757167986 -0.0012701742303822 -0.00956582634330756 0.999927606126326 0.00729914192526782 -0.00118070866039439 0.0484685927869284 -0.00682724509128811 0.998801373766435 -0.0270413106191133 7.03295445573754e-05 -9.39964840937735e-06 -6.58535375808348e-07 -1.05024077724786e-05 -8.55412641174181e-06 3.91518833679985e-05 -9.39964840937735e-06 0.00014017319384031 -1.83326454037887e-06 5.82176180565027e-05 1.17124820570928e-05 -9.81859176865141e-06 -6.58535375808348e-07 -1.83326454037887e-06 1.47985582524546e-05 1.70958605817219e-06 -3.26709115415422e-06 -3.04465293079863e-06 -1.05024077724786e-05 5.82176180565027e-05 1.70958605817219e-06 0.000107789410480716 1.45836345122483e-05 -2.128600664958e-07 -8.55412641174181e-06 1.17124820570928e-05 -3.26709115415422e-06 1.45836345122483e-05 3.73880694532581e-05 -7.25649669494521e-06 3.91518833679985e-05 -9.81859176865141e-06 -3.04465293079863e-06 -2.128600664958e-07 -7.25649669494521e-06 7.10585532852193e-05 2562 2560 0 2 0 2574 2582 0 2 0 0 0 0 0 0 0 0 0 51 0 31 36 0 0 2617 +6 43 0.999964898203231 -0.000184569308936911 -0.00837665181157406 -0.013631378216738 0.000345137846903088 0.999816156342996 0.0191711865930078 0.00397208767363702 0.0083715734046106 -0.0191734047494827 0.999781124701324 -0.0159636634209785 7.47737129459236e-05 5.31457160772751e-06 8.45097930394559e-06 7.47624287260407e-06 -1.61847842678271e-05 4.4115858035319e-05 5.31457160772751e-06 9.92629070766915e-05 -8.35971006051733e-06 3.65728291170144e-05 -8.76450106221401e-06 -1.38543304507959e-05 8.45097930394559e-06 -8.35971006051733e-06 2.16705933694764e-05 -8.68204203895919e-06 -8.16903596136341e-07 7.36725710680902e-06 7.47624287260407e-06 3.65728291170144e-05 -8.68204203895919e-06 9.84530785978475e-05 2.87876463940208e-06 -1.56279814535941e-05 -1.61847842678271e-05 -8.76450106221401e-06 -8.16903596136341e-07 2.87876463940208e-06 3.68581643473189e-05 -1.28189462972929e-05 4.4115858035319e-05 -1.38543304507959e-05 7.36725710680902e-06 -1.56279814535941e-05 -1.28189462972929e-05 9.03563206338455e-05 2783 2784 0 1 2 2784 2801 0 1 3 0 0 0 0 0 0 0 0 17 0 17 19 0 0 2659 +6 34 0.999946170947493 0.000505768127190294 -0.0103633684701929 -0.0130378642201353 -0.000471448733295082 0.999994398278554 0.00331378146598194 0.00318067786028689 0.0103649864225354 -0.00330871729132747 0.999940807971325 -0.000655903648012149 2.25317102210771e-05 -2.10312502377716e-06 -1.42823122886649e-06 4.08543541272676e-06 3.48304117289024e-06 1.06958271544031e-07 -2.10312502377716e-06 4.7063417487635e-05 -6.41135402103097e-06 1.0059880790198e-05 5.0764731883287e-06 -1.62777622657957e-06 -1.42823122886649e-06 -6.41135402103097e-06 1.76625694658328e-05 3.80454672960249e-07 -3.728640752931e-06 -1.46951968905396e-07 4.08543541272676e-06 1.0059880790198e-05 3.80454672960249e-07 0.000102115068839533 5.80282399358762e-06 1.04983444852463e-05 3.48304117289024e-06 5.0764731883287e-06 -3.728640752931e-06 5.80282399358762e-06 2.79645359052484e-05 3.13387162701591e-06 1.06958271544031e-07 -1.62777622657957e-06 -1.46951968905396e-07 1.04983444852463e-05 3.13387162701591e-06 3.19921951948607e-05 2812 2826 0 0 6 2812 2827 0 0 7 0 0 0 0 0 0 0 0 49 0 17 25 0 0 3066 +6 10 0.999999285419735 0.000536097703755546 -0.00106853136153247 -0.00818820047136249 -0.00053169321823802 0.99999137952909 0.00411802984802928 -6.7758942954795e-05 0.00107072981663447 -0.00411745877448802 0.999990949994499 0.00310382370253431 1.71775073920416e-05 -3.47478012638522e-06 3.4572304552291e-06 3.55644527338618e-06 4.11839879500902e-06 -1.09209006811791e-06 -3.47478012638522e-06 4.72178079633767e-05 -6.48704614994058e-06 1.5175688931487e-05 -9.53209089208274e-08 -5.27810874127301e-06 3.4572304552291e-06 -6.48704614994058e-06 1.39506124362841e-05 -1.82395498291981e-06 4.31798614437198e-06 2.45777173761131e-06 3.55644527338618e-06 1.5175688931487e-05 -1.82395498291981e-06 5.950217463392e-05 5.17122767913483e-06 -2.50280065912135e-06 4.11839879500902e-06 -9.53209089208274e-08 4.31798614437198e-06 5.17122767913483e-06 2.03572130125167e-05 1.2797602711388e-06 -1.09209006811791e-06 -5.27810874127301e-06 2.45777173761131e-06 -2.50280065912135e-06 1.2797602711388e-06 2.67651324332646e-05 2914 2914 0 2 6 2918 2933 0 2 10 0 0 0 0 0 0 0 0 58 0 16 19 0 0 3135 +7 34 0.999963964296566 0.000497406751675955 -0.00847482712626459 -0.0113852973163412 -0.000462606123524865 0.99999145587636 0.00410781813772794 0.00234828574850145 0.00847679797277015 -0.00410374960268735 0.999955650584228 -0.00385706496831053 3.84908160714054e-05 -3.44512709913123e-07 5.51340027815139e-07 5.52750664149727e-07 -7.46510062435491e-06 5.40469903942332e-07 -3.44512709913123e-07 0.000158469070383917 -3.04305673029742e-06 4.30750924844261e-05 -4.58672352934955e-06 -4.76412831066534e-05 5.51340027815139e-07 -3.04305673029742e-06 1.66624121562729e-05 -2.36887015301537e-07 -6.88200313354466e-07 3.45423468768466e-06 5.52750664149727e-07 4.30750924844261e-05 -2.36887015301537e-07 7.63450807418779e-05 4.43240345927146e-06 -7.21458943311108e-06 -7.46510062435491e-06 -4.58672352934955e-06 -6.88200313354466e-07 4.43240345927146e-06 3.19186803891113e-05 3.43613594081905e-07 5.40469903942332e-07 -4.76412831066534e-05 3.45423468768466e-06 -7.21458943311108e-06 3.43613594081905e-07 5.60865998208591e-05 2897 2898 0 0 5 2898 2918 0 0 6 0 0 0 0 0 0 0 0 45 0 16 18 0 0 2764 +6 32 0.999985402005161 0.000304728701604305 -0.00539471194729589 -0.0110055832840763 -0.000296108457658773 0.999998678345507 0.00159863286000539 0.000566549890094381 0.00539519196666638 -0.00159701210333692 0.999984170602708 0.00637451345911568 3.61259190204321e-05 -3.02410182469856e-06 1.51125450981007e-06 9.92863469549231e-06 -5.89879298874187e-06 5.85431252751308e-06 -3.02410182469856e-06 4.58240121505654e-05 -2.30050982741205e-07 6.85014700217196e-06 -3.81613639124559e-06 4.1118935177851e-06 1.51125450981007e-06 -2.30050982741205e-07 1.33484346218241e-05 1.18882200799361e-06 3.35952360801254e-06 2.11744176228719e-06 9.92863469549231e-06 6.85014700217196e-06 1.18882200799361e-06 5.6011235354046e-05 -2.94635724639498e-06 6.52711612845712e-06 -5.89879298874187e-06 -3.81613639124559e-06 3.35952360801254e-06 -2.94635724639498e-06 2.26400815419447e-05 -3.82113804554476e-06 5.85431252751308e-06 4.1118935177851e-06 2.11744176228719e-06 6.52711612845712e-06 -3.82113804554476e-06 3.87073121156141e-05 2947 2947 0 2 4 2948 2948 0 2 5 0 0 0 0 0 0 0 0 44 0 15 29 0 0 2691 +6 9 0.999999343720408 -0.000938258874850692 -0.00065744128069589 -0.00668873503302155 0.000939584253992325 0.999997521284608 0.0020185653492457 -0.000188038733204132 0.000655545714232672 -0.00201918174597773 0.999997746579908 0.00559970915098621 1.99235326458757e-05 2.12625955274019e-06 3.51424549067665e-06 4.25525776237511e-06 1.94567475999323e-06 4.75878010476118e-06 2.12625955274019e-06 4.23938312243863e-05 -3.4916463419473e-06 8.12484391020289e-06 -2.72583646314968e-06 -6.73570456050168e-06 3.51424549067665e-06 -3.4916463419473e-06 1.45807364202568e-05 -1.2676607422997e-06 1.92448505214501e-06 1.11039032718402e-06 4.25525776237511e-06 8.12484391020289e-06 -1.2676607422997e-06 4.86899220227963e-05 2.15114172330668e-06 -9.36310864376803e-07 1.94567475999323e-06 -2.72583646314968e-06 1.92448505214501e-06 2.15114172330668e-06 2.269547857468e-05 -2.57429524079663e-06 4.75878010476118e-06 -6.73570456050168e-06 1.11039032718402e-06 -9.36310864376803e-07 -2.57429524079663e-06 3.75047185637599e-05 2963 2979 0 0 8 2963 2980 0 0 9 0 0 0 0 0 0 0 0 51 0 13 18 0 0 3075 +7 49 0.999982973470939 -8.16983651429266e-05 -0.00583490304939875 -0.0146394672606872 0.000175453068418003 0.999870866560875 0.016069207168546 0.00391521324241535 0.00583283674034621 -0.0160699573173671 0.999853856564737 -0.0204305961923824 8.03868192531443e-05 -8.36758895083374e-06 2.07838056105114e-06 -1.48509567184495e-07 -1.9277573358972e-05 4.80554974085836e-05 -8.36758895083374e-06 0.000154028952828349 -8.47961057111523e-06 6.36774911408922e-05 6.00378802126387e-06 -2.18033092272252e-05 2.07838056105114e-06 -8.47961057111523e-06 2.50655146337227e-05 -1.19547105845193e-05 -4.05833505296148e-06 8.47679447375737e-07 -1.48509567184495e-07 6.36774911408922e-05 -1.19547105845193e-05 0.000133751159519932 1.99499883690281e-05 -1.42164114746167e-05 -1.9277573358972e-05 6.00378802126387e-06 -4.05833505296148e-06 1.99499883690281e-05 3.88802865400632e-05 -2.46395604613285e-05 4.80554974085836e-05 -2.18033092272252e-05 8.47679447375737e-07 -1.42164114746167e-05 -2.46395604613285e-05 9.53708049545813e-05 2703 2703 0 0 3 2707 2722 0 0 5 0 0 0 0 0 0 0 0 51 0 19 22 0 0 2605 +7 44 0.999920593738263 -0.000343741553992682 -0.0125971449091717 -0.0359130824313973 0.000598653822057519 0.999795020838844 0.0202375373861527 0.00361654361992912 0.0125876062744251 -0.020243471727909 0.999715836635932 -0.0239159223405339 5.71604010783242e-05 6.70908848394373e-06 -2.56354170701785e-07 1.23765442748453e-05 -9.16451178454099e-06 3.67675500449098e-05 6.70908848394373e-06 5.39989290968321e-05 -4.33679517542498e-06 1.47971992569692e-05 -5.19230096720745e-06 5.73088810581751e-06 -2.56354170701785e-07 -4.33679517542498e-06 1.72912630358522e-05 -3.12508927654559e-06 -1.24465918950529e-06 -3.8419460934862e-06 1.23765442748453e-05 1.47971992569692e-05 -3.12508927654559e-06 9.99698645882578e-05 -2.61828334891522e-06 4.74644741708631e-06 -9.16451178454099e-06 -5.19230096720745e-06 -1.24465918950529e-06 -2.61828334891522e-06 3.56585907712519e-05 1.34229931597579e-06 3.67675500449098e-05 5.73088810581751e-06 -3.8419460934862e-06 4.74644741708631e-06 1.34229931597579e-06 8.41166092743991e-05 2596 2596 0 0 1 2596 2596 0 0 1 0 0 0 0 0 0 0 0 27 0 49 66 0 0 2314 +7 50 0.999997701116022 -0.000458548237619705 -0.00209463509576043 -0.00456595651911828 0.000479302159571009 0.999950696593115 0.00991839968863064 0.00246837863689272 0.0020899837584168 -0.00991938085050542 0.999948617605641 -0.012625575661125 6.7839214669823e-05 -6.75127239904304e-06 3.56996010491394e-06 1.50886192428048e-06 -1.23331313257475e-05 2.03623772825262e-05 -6.75127239904304e-06 2.66312418918666e-05 -4.83552768293838e-06 -3.23922079870163e-06 -2.74840439419769e-06 1.22164828203714e-05 3.56996010491394e-06 -4.83552768293838e-06 2.08800206970535e-05 -9.88653786058095e-06 -6.25565925867527e-06 2.92868689337533e-06 1.50886192428048e-06 -3.23922079870163e-06 -9.88653786058095e-06 6.78384618308178e-05 1.21485813047672e-05 -1.2719757184102e-06 -1.23331313257475e-05 -2.74840439419769e-06 -6.25565925867527e-06 1.21485813047672e-05 3.87915318671762e-05 -1.14649763421809e-05 2.03623772825262e-05 1.22164828203714e-05 2.92868689337533e-06 -1.2719757184102e-06 -1.14649763421809e-05 6.71529301453038e-05 2842 2854 0 0 15 2842 2854 0 0 15 0 0 0 0 0 0 0 0 56 0 28 36 0 0 2760 +7 45 0.999956849139812 3.74963013140198e-05 -0.00928969603417223 -0.0122317012483241 -2.5172266374776e-07 0.9999919631086 0.00400920417865305 -0.00245597790413352 0.00928977170422197 -0.00400902883961704 0.999948812604649 -0.00555441318798304 4.28480539627865e-05 -2.12662033810609e-06 1.83388429142007e-06 1.31068179902633e-05 -1.17607619057516e-06 3.03732167666001e-05 -2.12662033810609e-06 6.72248042956738e-05 -6.00361258777666e-06 1.29955004000388e-05 -6.26978232694378e-07 9.56512754075743e-06 1.83388429142007e-06 -6.00361258777666e-06 2.00086880723121e-05 -4.7876988617662e-06 -1.78393270879033e-06 7.09656438381404e-07 1.31068179902633e-05 1.29955004000388e-05 -4.7876988617662e-06 7.98676553428288e-05 -8.57758692058829e-07 3.01726983574149e-05 -1.17607619057516e-06 -6.26978232694378e-07 -1.78393270879033e-06 -8.57758692058829e-07 2.8952017666802e-05 -3.65628972895272e-06 3.03732167666001e-05 9.56512754075743e-06 7.09656438381404e-07 3.01726983574149e-05 -3.65628972895272e-06 7.41413921563284e-05 2786 2787 0 0 3 2792 2807 0 0 4 0 0 0 0 0 0 0 0 27 0 18 20 0 0 2554 +6 8 0.999999144681497 -0.000636026310631942 -0.00114285029901617 -0.00421315638728003 0.000637665494631516 0.999998767791011 0.00143450311141098 0.000957617801953224 0.00114193650906422 -0.00143523064065514 0.999998318045594 0.00533355745906269 1.75411240601964e-05 -4.45651911907345e-06 5.22883837143817e-06 -2.37883597610782e-06 4.03039688763873e-06 1.16471601137525e-06 -4.45651911907345e-06 1.75082584336496e-05 -4.30673893427092e-06 -2.25151973501342e-06 -1.54744092050486e-06 1.66524161977052e-06 5.22883837143817e-06 -4.30673893427092e-06 1.38619888585976e-05 -1.41977857876381e-06 2.36909245637635e-06 2.89938575558524e-06 -2.37883597610782e-06 -2.25151973501342e-06 -1.41977857876381e-06 3.48595297570535e-05 3.17247168146805e-06 -6.12965370111656e-06 4.03039688763873e-06 -1.54744092050486e-06 2.36909245637635e-06 3.17247168146805e-06 1.62416217955502e-05 5.47048469709396e-07 1.16471601137525e-06 1.66524161977052e-06 2.89938575558524e-06 -6.12965370111656e-06 5.47048469709396e-07 2.27172001001486e-05 2670 2672 0 2 8 2671 2689 0 2 9 0 0 0 0 0 0 0 0 71 0 12 14 0 0 3091 +7 40 0.999998427835524 -0.000403038621646891 0.00172681393047254 -0.00706879709058902 0.000389517620919421 0.999969322265898 0.00782322204099454 -0.000554870438222557 -0.00172991401636217 -0.00782253711714879 0.999967907140298 -0.018582341149014 3.24701825652616e-05 -5.14695486347431e-06 1.3577888757161e-06 5.60871190660283e-06 -1.46184294454269e-06 1.28436621569496e-05 -5.14695486347431e-06 3.28834368174228e-05 -1.76316566063393e-06 -4.84814677103035e-06 1.67624580270664e-06 6.32291786404218e-06 1.3577888757161e-06 -1.76316566063393e-06 1.49121004030265e-05 -1.71463090982684e-06 1.37862011816652e-06 8.59029343512893e-07 5.60871190660283e-06 -4.84814677103035e-06 -1.71463090982684e-06 4.7699826980806e-05 8.08731754611291e-06 3.21636367955503e-06 -1.46184294454269e-06 1.67624580270664e-06 1.37862011816652e-06 8.08731754611291e-06 3.1335388019397e-05 -5.53914702818385e-06 1.28436621569496e-05 6.32291786404218e-06 8.59029343512893e-07 3.21636367955503e-06 -5.53914702818385e-06 5.83240852411327e-05 3081 3084 0 0 8 3084 3096 0 0 25 0 0 0 0 0 0 0 0 69 0 14 17 0 0 2833 +7 33 0.999972013291487 0.000184343688587447 -0.00747921460944732 -0.0101240978873776 -0.00019193426216133 0.999999467295834 -0.00101418405038194 -0.00213898501025671 0.00747902366680978 0.00101559118424615 0.999971515984099 -0.00605974487686855 4.03560570970873e-05 -1.07689161362014e-05 -1.29905184364468e-06 4.7572415008472e-06 -4.90497129677412e-06 -3.07921976656821e-07 -1.07689161362014e-05 4.39327631437288e-05 -5.60764573831091e-06 -1.01160952666607e-06 3.4632816705147e-06 -6.75806583907496e-06 -1.29905184364468e-06 -5.60764573831091e-06 1.42218625064198e-05 -6.26239373215117e-07 -2.46063516748482e-06 1.27617439223332e-06 4.7572415008472e-06 -1.01160952666607e-06 -6.26239373215117e-07 5.12692755718016e-05 3.27005008304135e-06 3.54827387991012e-06 -4.90497129677412e-06 3.4632816705147e-06 -2.46063516748482e-06 3.27005008304135e-06 2.79104731919246e-05 -7.43136864167473e-07 -3.07921976656821e-07 -6.75806583907496e-06 1.27617439223332e-06 3.54827387991012e-06 -7.43136864167473e-07 3.61667440297791e-05 2558 2561 0 0 5 2561 2573 0 0 20 0 0 0 0 0 0 0 0 54 0 15 18 0 0 2723 +7 37 0.999937724382009 3.01474106442805e-05 -0.0111600380314291 -0.0148899075695321 0.000107940443112721 0.999923450476827 0.01237261231014 6.19790801097731e-05 0.0111595567380633 -0.0123730464175125 0.99986117637188 -0.0278115878530511 5.00568846818121e-05 6.65181011982858e-06 2.83057913226422e-06 -6.93219712514827e-07 -5.26617581372666e-06 2.15397511353732e-05 6.65181011982858e-06 0.000129015783746385 -5.01455947977461e-06 3.09677696024101e-05 -5.73449747823198e-06 -6.01613913099979e-06 2.83057913226422e-06 -5.01455947977461e-06 1.48887652783457e-05 -1.75631757471774e-06 4.6461552110101e-07 1.54058697782509e-06 -6.93219712514827e-07 3.09677696024101e-05 -1.75631757471774e-06 7.01339624491093e-05 5.61683613027265e-06 -2.19249747723376e-06 -5.26617581372666e-06 -5.73449747823198e-06 4.6461552110101e-07 5.61683613027265e-06 2.96796408041873e-05 -6.74289510183747e-06 2.15397511353732e-05 -6.01613913099979e-06 1.54058697782509e-06 -2.19249747723376e-06 -6.74289510183747e-06 7.45263634506226e-05 2912 2912 0 0 4 2919 2935 0 0 6 0 0 0 0 0 0 0 0 53 0 16 18 0 0 2705 +7 35 0.999960618758586 0.000190581796446132 -0.0088726890244686 -0.0237320248611744 -0.000136940171872585 0.999981713906422 0.00604591599040783 0.00148150446539937 0.00887367901917743 -0.00604446286717066 0.999942359483441 -0.0124270884523828 5.3772277637409e-05 -1.15937251402199e-06 4.14107773947679e-06 -8.58816255617058e-07 -1.18808911536341e-05 1.42721601589808e-05 -1.15937251402199e-06 4.02240754868031e-05 -2.92384925488074e-06 4.97858681767277e-06 2.29307591359341e-06 -1.79723815147052e-06 4.14107773947679e-06 -2.92384925488074e-06 1.64061983805179e-05 -1.00733765912113e-07 -5.81405049175983e-07 -1.59075005493881e-07 -8.58816255617058e-07 4.97858681767277e-06 -1.00733765912113e-07 6.56516219871884e-05 4.17053275376076e-06 4.44203284301215e-06 -1.18808911536341e-05 2.29307591359341e-06 -5.81405049175983e-07 4.17053275376076e-06 3.10391451470874e-05 -3.95065184327654e-06 1.42721601589808e-05 -1.79723815147052e-06 -1.59075005493881e-07 4.44203284301215e-06 -3.95065184327654e-06 5.14673190802683e-05 2559 2559 0 0 0 2568 2581 0 0 1 0 0 0 0 0 0 0 0 50 0 25 28 0 0 2601 +7 36 0.9999988790683 -0.000591757114583451 0.00137538564095427 -0.00922073096755871 0.000587722687754934 0.999995529375328 0.00293186142233891 -0.0042603026118305 -0.00137711444197693 -0.0029310497905769 0.999994756237721 -0.0177370607412864 4.89929311961719e-05 -4.90632247041619e-06 2.44477707431254e-06 4.90549183660326e-06 -4.64534774897406e-06 1.08091155779722e-05 -4.90632247041619e-06 5.75104300301722e-05 -3.93100445434633e-06 1.27036144905002e-05 4.5522155625098e-06 3.45066310714547e-06 2.44477707431254e-06 -3.93100445434633e-06 1.6531746979759e-05 -1.86593374095036e-06 -5.35419938416751e-07 -3.74724421940658e-06 4.90549183660326e-06 1.27036144905002e-05 -1.86593374095036e-06 6.0643197270689e-05 6.97504631755278e-06 1.38737024977067e-05 -4.64534774897406e-06 4.5522155625098e-06 -5.35419938416751e-07 6.97504631755278e-06 3.16710928851377e-05 -2.56165846247128e-06 1.08091155779722e-05 3.45066310714547e-06 -3.74724421940658e-06 1.38737024977067e-05 -2.56165846247128e-06 6.5218942421954e-05 2720 2722 0 0 6 2724 2740 0 0 7 0 0 0 0 0 0 0 0 59 0 17 19 0 0 2571 +7 48 0.9999937802708 -0.000401937580339478 -0.00350397858109484 -0.0173364947538863 0.000461853995830728 0.999853411860944 0.0171155333225939 0.00584512305549542 0.00349658556334544 -0.0171170451951205 0.999847378679959 -0.0243388524488644 6.68877614994079e-05 -9.98606982337729e-06 5.71801418870132e-07 -5.09366934630004e-06 -8.7820851112004e-06 2.61732864201315e-05 -9.98606982337729e-06 2.20618093206507e-05 -3.7404904486678e-06 -1.92527553696962e-07 -9.62314233795263e-07 7.70168073460842e-06 5.71801418870132e-07 -3.7404904486678e-06 1.66787073601106e-05 -1.69662937411309e-06 1.57232397006841e-07 1.94847887664831e-07 -5.09366934630004e-06 -1.92527553696962e-07 -1.69662937411309e-06 5.55533576649953e-05 6.60861564738454e-06 -5.1478744108988e-06 -8.7820851112004e-06 -9.62314233795263e-07 1.57232397006841e-07 6.60861564738454e-06 2.79847890534881e-05 -8.25206332766221e-06 2.61732864201315e-05 7.70168073460842e-06 1.94847887664831e-07 -5.1478744108988e-06 -8.25206332766221e-06 6.54398824124714e-05 3141 3147 0 0 6 3141 3147 0 0 6 0 0 0 0 0 0 0 0 43 0 35 46 0 0 2623 +7 51 0.999998699370119 0.000292412281071326 -0.00158611258369071 -0.00207547060933974 -0.000261202088749189 0.999807047066977 0.0196418025822615 0.00527457433598433 0.00159155004291301 -0.0196413627396263 0.999805823066755 -0.0185251309433892 8.37031074250433e-05 1.24072995017991e-06 1.17236763004781e-05 6.4785145723231e-06 -1.97659162847985e-05 5.15677677780326e-05 1.24072995017991e-06 2.61902507831795e-05 -6.32419578439338e-06 2.28649232548845e-06 -2.64755836650369e-06 1.16139547859311e-05 1.17236763004781e-05 -6.32419578439338e-06 2.00132781508426e-05 -3.69178783024525e-06 -6.24071941711631e-06 8.90645142416045e-06 6.4785145723231e-06 2.28649232548845e-06 -3.69178783024525e-06 5.35453435509499e-05 9.27786313217441e-06 -1.88676729852113e-06 -1.97659162847985e-05 -2.64755836650369e-06 -6.24071941711631e-06 9.27786313217441e-06 3.81070315943922e-05 -2.30825568524402e-05 5.15677677780326e-05 1.16139547859311e-05 8.90645142416045e-06 -1.88676729852113e-06 -2.30825568524402e-05 8.3905513135716e-05 2806 2812 0 0 12 2806 2822 0 0 13 0 0 0 0 0 0 0 0 74 0 22 30 0 0 2780 +7 47 0.999996383463556 0.000603795396488237 0.00262078059508358 -0.00884762846780559 -0.000635461023450182 0.999926607956923 0.0120985490472665 0.00336658144146174 -0.00261328320242232 -0.0121001706963422 0.999923375374345 -0.0267381916676349 6.89541756650648e-05 -9.05586473885219e-06 4.16300830097427e-07 -8.46308703583874e-07 -1.19499330266664e-05 2.90166036490333e-05 -9.05586473885219e-06 4.86560530288987e-05 -1.83392825985468e-06 4.08124299821289e-06 7.49399452985287e-08 1.42614409610562e-05 4.16300830097427e-07 -1.83392825985468e-06 1.76326485306277e-05 -3.42695809674355e-06 1.71634468729805e-06 4.2447748479385e-06 -8.46308703583874e-07 4.08124299821289e-06 -3.42695809674355e-06 7.36976104906888e-05 7.8301367434782e-06 4.53276902977814e-06 -1.19499330266664e-05 7.49399452985287e-08 1.71634468729805e-06 7.8301367434782e-06 3.15548360632988e-05 -1.36046941744432e-05 2.90166036490333e-05 1.42614409610562e-05 4.2447748479385e-06 4.53276902977814e-06 -1.36046941744432e-05 9.11638093054335e-05 2899 2902 0 0 9 2899 2914 0 0 10 0 0 0 0 0 0 0 0 56 0 27 38 0 0 2638 +7 38 0.99999902423132 -0.000806311825026316 -0.00114078816974953 -0.0106507902282317 0.000813688077522455 0.999978671548396 0.00648030554976602 -0.00398559256016078 0.0011355386915097 -0.00648122747221954 0.999978351886846 -0.0248482331014484 5.65534457036667e-05 -4.19372554491908e-06 8.18100761316784e-06 -7.19659194886566e-06 -9.7485731249919e-06 1.5064170601737e-05 -4.19372554491908e-06 6.64637670158723e-05 -2.44442471911598e-06 1.71143828015435e-05 2.73550430493049e-06 -2.40169908493018e-06 8.18100761316784e-06 -2.44442471911598e-06 1.88999908269463e-05 -5.47178300396713e-06 -1.06368171063697e-06 4.22376864151852e-06 -7.19659194886566e-06 1.71143828015435e-05 -5.47178300396713e-06 7.94932658739818e-05 9.8992531260371e-06 -6.15680970486969e-06 -9.7485731249919e-06 2.73550430493049e-06 -1.06368171063697e-06 9.8992531260371e-06 3.61008899154811e-05 -6.83425250061113e-06 1.5064170601737e-05 -2.40169908493018e-06 4.22376864151852e-06 -6.15680970486969e-06 -6.83425250061113e-06 7.34751039506684e-05 2942 2944 0 0 8 2943 2956 0 0 9 0 0 0 0 0 0 0 0 60 0 29 41 0 0 2620 +7 9 0.999999144924723 0.000213325252550038 0.00129021012208939 -0.00502844360630512 -0.000214858465782362 0.999999270863082 0.00118832198665072 0.00161952322238514 -0.00128995568226165 -0.00118859818311334 0.999998461623165 0.00671869445368146 3.19672073545111e-05 -4.62521788435417e-06 4.75052308938204e-06 1.67944284140736e-06 -4.4571346951208e-07 2.90114227021519e-06 -4.62521788435417e-06 1.98832300815543e-05 -4.230767319249e-06 -3.65642897109619e-06 1.46657901231222e-06 7.20195458238706e-06 4.75052308938204e-06 -4.230767319249e-06 1.20342514025802e-05 9.65322507858624e-07 1.57293425125348e-06 -7.77722021754313e-08 1.67944284140736e-06 -3.65642897109619e-06 9.65322507858624e-07 3.39013438890497e-05 5.17331066886992e-06 3.26139741066832e-06 -4.4571346951208e-07 1.46657901231222e-06 1.57293425125348e-06 5.17331066886992e-06 2.03421461335645e-05 2.16682989859192e-06 2.90114227021519e-06 7.20195458238706e-06 -7.77722021754313e-08 3.26139741066832e-06 2.16682989859192e-06 3.7613626605914e-05 3147 3149 0 0 9 3147 3167 0 0 10 0 0 0 0 0 0 0 0 54 0 16 18 0 0 2775 +7 10 0.999979597706531 0.000811978301302375 0.00633599731075273 -0.00114954922646434 -0.000824546685969982 0.999997697308811 0.00198128741912771 0.000564439208565461 -0.00633437395851457 -0.00198647132190524 0.99997796457634 0.000735100715908384 3.12412563907229e-05 -5.20552525989883e-06 3.32863360354339e-06 4.86843168103849e-06 -2.72806260562228e-06 9.8924162003996e-07 -5.20552525989883e-06 3.60059166714653e-05 -4.41345191952363e-06 5.79968697913982e-06 1.54692470495526e-06 -1.06660372299717e-05 3.32863360354339e-06 -4.41345191952363e-06 1.32881528658116e-05 -1.59821677685621e-06 3.51578302529313e-06 2.35319837840793e-06 4.86843168103849e-06 5.79968697913982e-06 -1.59821677685621e-06 4.89165413266654e-05 5.25542332069632e-07 -3.29003752400529e-06 -2.72806260562228e-06 1.54692470495526e-06 3.51578302529313e-06 5.25542332069632e-07 2.3605349004882e-05 -3.38982475523694e-06 9.8924162003996e-07 -1.06660372299717e-05 2.35319837840793e-06 -3.29003752400529e-06 -3.38982475523694e-06 3.28501161420823e-05 2908 2921 0 0 13 2909 2922 0 0 14 0 0 0 0 0 0 0 0 69 0 30 35 0 0 2806 +7 41 0.999992431158324 0.00158448631672527 -0.00355345313411906 0.00141931559020935 -0.00153352490327491 0.999896594743796 0.0142985356289537 0.00493179607414562 0.0035757415224406 -0.0142929780967276 0.999891456534004 -0.0302677417238437 3.95393970216763e-05 -6.7465865780701e-07 7.94525670552722e-06 -5.47464106111971e-06 -9.40438363037059e-07 2.90568091321486e-05 -6.7465865780701e-07 2.79284752554696e-05 -8.30097261381954e-06 2.962448987465e-06 -7.16672942589149e-06 1.13144374349017e-05 7.94525670552722e-06 -8.30097261381954e-06 2.12614396486499e-05 -1.30326213654221e-05 1.0520566327038e-06 5.35343279750457e-06 -5.47464106111971e-06 2.962448987465e-06 -1.30326213654221e-05 8.77966416347267e-05 1.24177443604466e-05 -2.78327003020831e-06 -9.40438363037059e-07 -7.16672942589149e-06 1.0520566327038e-06 1.24177443604466e-05 2.68994202562175e-05 -1.01163313223161e-05 2.90568091321486e-05 1.13144374349017e-05 5.35343279750457e-06 -2.78327003020831e-06 -1.01163313223161e-05 7.98269330215312e-05 2828 2835 0 0 12 2829 2846 0 0 14 0 0 0 0 0 0 0 0 92 0 19 27 0 0 2827 +8 35 0.99999211257507 0.000770511425987912 -0.00389629308325593 -0.0194278676873656 -0.000728189860890607 0.999940852501761 0.0108517849949891 0.00721368231071463 0.00390442405159865 -0.0108488621612313 0.999933526621961 -0.0165340078368931 4.00995626306072e-05 -4.47616711206274e-06 6.91564749772198e-06 -1.25640430937582e-06 -2.3008863895279e-06 7.08416513024402e-06 -4.47616711206274e-06 2.93852100998192e-05 -7.52148331378753e-06 2.49652671430268e-06 -3.80419349587656e-06 4.72530097070914e-06 6.91564749772198e-06 -7.52148331378753e-06 1.79682666778385e-05 -1.45489586440966e-06 2.8282028631402e-06 2.12539978803143e-06 -1.25640430937582e-06 2.49652671430268e-06 -1.45489586440966e-06 6.7392815638344e-05 2.54108445590754e-06 3.15559957571446e-06 -2.3008863895279e-06 -3.80419349587656e-06 2.8282028631402e-06 2.54108445590754e-06 3.07463007106969e-05 -4.45472407783496e-06 7.08416513024402e-06 4.72530097070914e-06 2.12539978803143e-06 3.15559957571446e-06 -4.45472407783496e-06 4.31147948838586e-05 2746 2755 0 0 5 2748 2760 0 0 6 0 0 0 0 0 0 0 0 73 0 24 26 0 0 2477 +7 43 0.99999859042732 0.000105825784891703 0.00167569217843243 0.000487508962519114 -0.000119848046505891 0.999964962470593 0.00837015338152791 0.000563550543123522 -0.00167474768826719 -0.0083703424116225 0.999963565630315 -0.0216079498369807 5.14641438810647e-05 3.79502123944711e-07 9.47109335895016e-06 -8.05310375719929e-07 -4.20707436720024e-06 1.80423053067796e-05 3.79502123944711e-07 4.69887627380316e-05 -3.6722973795719e-06 1.06967493402944e-05 2.99981684028134e-06 -3.96973906090058e-06 9.47109335895016e-06 -3.6722973795719e-06 1.87814145474085e-05 -5.84932306212294e-06 1.89945281789288e-06 -1.42996228326421e-06 -8.05310375719929e-07 1.06967493402944e-05 -5.84932306212294e-06 6.3277743343507e-05 1.10135480390189e-05 6.76588709109967e-06 -4.20707436720024e-06 2.99981684028134e-06 1.89945281789288e-06 1.10135480390189e-05 2.74634989780482e-05 -4.4929737695389e-06 1.80423053067796e-05 -3.96973906090058e-06 -1.42996228326421e-06 6.76588709109967e-06 -4.4929737695389e-06 6.22439964956602e-05 2939 2946 0 0 13 2940 2956 0 0 15 0 0 0 0 0 0 0 0 17 0 21 31 0 0 2711 +8 10 0.999993768411759 -0.000416712878720961 -0.00350563660780617 -0.00747585328042601 0.000423457711666621 0.999998060462969 0.00192347442590271 -0.000305779086232776 0.00350482827192898 -0.00192494692845797 0.999992005347096 -0.00189281684144865 1.98951306903139e-05 -1.05594218657286e-05 5.81313139557559e-06 -4.48941195918871e-06 1.66890557700738e-06 9.48315449904972e-07 -1.05594218657286e-05 6.47933762741656e-05 -9.91751748485863e-06 2.57355257283019e-05 -1.84674319016897e-06 -1.85672266136014e-05 5.81313139557559e-06 -9.91751748485863e-06 1.9487961492904e-05 -5.81317338636416e-06 8.48116550114024e-07 3.97748378228496e-06 -4.48941195918871e-06 2.57355257283019e-05 -5.81317338636416e-06 6.7071697391168e-05 4.09556418075024e-06 -1.67741598489973e-05 1.66890557700738e-06 -1.84674319016897e-06 8.48116550114024e-07 4.09556418075024e-06 2.15189715161448e-05 -1.72385481111341e-06 9.48315449904972e-07 -1.85672266136014e-05 3.97748378228496e-06 -1.67741598489973e-05 -1.72385481111341e-06 3.80391005137392e-05 2651 2656 0 0 9 2652 2658 0 0 10 0 0 0 0 0 0 0 0 67 0 31 35 0 0 3140 +8 34 0.999980499413517 0.00105881203101832 -0.00615464944385395 -0.0079771360051835 -0.00104235653004087 0.999995875546132 0.00267626298946766 0.00260538127249724 0.00615745771873766 -0.00266979546173187 0.999977478699713 -0.00863903010379612 2.34809558691817e-05 -4.58369011444817e-06 6.96248540189419e-07 4.91686857997891e-07 -2.12587613583628e-07 2.15291593120825e-06 -4.58369011444817e-06 2.82785314315425e-05 -6.01673404503591e-06 3.00247690672115e-06 2.49232084866949e-06 -5.93198342987963e-06 6.96248540189419e-07 -6.01673404503591e-06 1.77029276191931e-05 -1.5713969130677e-06 -3.71704149577968e-07 -1.76301660642959e-06 4.91686857997891e-07 3.00247690672115e-06 -1.5713969130677e-06 7.1847163737635e-05 1.05721473913957e-05 7.23657601989132e-06 -2.12587613583628e-07 2.49232084866949e-06 -3.71704149577968e-07 1.05721473913957e-05 2.57271738236161e-05 2.20352829221324e-06 2.15291593120825e-06 -5.93198342987963e-06 -1.76301660642959e-06 7.23657601989132e-06 2.20352829221324e-06 3.15349215217154e-05 3096 3105 0 0 8 3099 3117 0 0 9 0 0 0 0 0 0 0 0 55 0 17 19 0 0 3064 +8 49 0.999950544284173 -0.000117345059048666 -0.00994460737900684 -0.0188522120775896 0.000327352279295146 0.999776921733804 0.021118702823889 0.00585404467331817 0.00993991077780483 -0.0211209137732157 0.999727515463646 -0.0189731816476456 8.98391052278677e-05 -7.88940438413082e-06 3.9829400526629e-06 9.27270315418875e-06 -2.45509457848057e-05 5.60328112211305e-05 -7.88940438413082e-06 6.00065306925563e-05 -6.83792141723037e-06 1.43705761561618e-05 1.17810295204472e-06 8.42143138019836e-06 3.9829400526629e-06 -6.83792141723037e-06 1.93962495681802e-05 -4.24301833677052e-06 -5.51528959933819e-06 4.74206966783248e-06 9.27270315418875e-06 1.43705761561618e-05 -4.24301833677052e-06 9.1840072727636e-05 4.01643111318765e-06 -1.20268939239043e-06 -2.45509457848057e-05 1.17810295204472e-06 -5.51528959933819e-06 4.01643111318765e-06 4.17537428811218e-05 -2.32129757379427e-05 5.60328112211305e-05 8.42143138019836e-06 4.74206966783248e-06 -1.20268939239043e-06 -2.32129757379427e-05 0.000101785543928383 2811 2819 0 0 4 2813 2828 0 0 5 0 0 0 0 0 0 0 0 50 0 23 26 0 0 2389 +8 12 0.999998006102617 6.18642824350994e-05 0.0019959868737333 -0.00655797533000899 -5.94895314356916e-05 0.999999290417907 -0.0011898002681751 -0.000518733700477089 -0.00199605906355659 0.00118967915551159 0.999997300202216 -0.00013408185362913 4.83058580397722e-05 -2.67191699027397e-06 8.67111570702957e-06 2.82663250261994e-06 -3.82742057903906e-06 1.56175385408412e-05 -2.67191699027397e-06 4.65269049937055e-05 -8.18682290411294e-06 1.38032878002617e-05 -8.23648798050754e-07 -4.62709926582361e-06 8.67111570702957e-06 -8.18682290411294e-06 1.77717938801901e-05 -3.55026237525247e-07 -1.88958795055079e-08 6.23552462877492e-06 2.82663250261994e-06 1.38032878002617e-05 -3.55026237525247e-07 4.91629346960105e-05 5.3054780312773e-06 -1.99109589069645e-06 -3.82742057903906e-06 -8.23648798050754e-07 -1.88958795055079e-08 5.3054780312773e-06 2.42766698756597e-05 -7.67376031286477e-06 1.56175385408412e-05 -4.62709926582361e-06 6.23552462877492e-06 -1.99109589069645e-06 -7.67376031286477e-06 4.45701600141572e-05 2658 2666 0 0 12 2665 2679 0 0 13 0 0 0 0 0 0 0 0 63 0 15 18 0 0 2658 +7 42 0.99998479944809 -0.000240617119421862 -0.005508445893733 -0.00687359658796818 0.000300986174382439 0.999939879403921 0.0109611580133608 0.001590402885299 0.0055054772804157 -0.0109626493637658 0.999924752188304 -0.0236417916424181 4.46109483206538e-05 -2.77560898945209e-06 7.08451851795937e-06 -2.0039791273309e-07 -3.41271579548448e-06 1.75438391689158e-05 -2.77560898945209e-06 3.458939419576e-05 -1.58162814545346e-06 2.25642120964636e-06 -8.33369673630861e-07 9.10695510532271e-06 7.08451851795937e-06 -1.58162814545346e-06 1.55075413955618e-05 -2.79020698836796e-06 1.06177271887967e-06 4.24057376729132e-06 -2.0039791273309e-07 2.25642120964636e-06 -2.79020698836796e-06 5.36716303693211e-05 8.88911836504019e-06 -9.09137951249741e-06 -3.41271579548448e-06 -8.33369673630861e-07 1.06177271887967e-06 8.88911836504019e-06 2.73930273361309e-05 -9.63149308210715e-06 1.75438391689158e-05 9.10695510532271e-06 4.24057376729132e-06 -9.09137951249741e-06 -9.63149308210715e-06 7.4081436519094e-05 2986 2990 0 0 9 2987 3002 0 0 10 0 0 0 0 0 0 0 0 56 0 26 36 0 0 2617 +8 11 0.999996064835471 0.000912011853703244 -0.00265302618759916 -0.00883192238093886 -0.000909771455305591 0.999999228677462 0.000845553298042072 0.00175202405830547 0.00265379529589102 -0.00084313632315507 0.999996123238319 0.00141453796419963 3.13009546345968e-05 2.37358042299077e-06 4.08260245045427e-06 1.00188828797181e-05 -1.93897870055989e-06 3.70259596773231e-06 2.37358042299077e-06 5.44106884557005e-05 -5.82664133369131e-06 1.69016276846002e-05 -2.18176779218949e-06 -4.36733704484885e-06 4.08260245045427e-06 -5.82664133369131e-06 1.51342002501891e-05 -1.13012517317119e-06 3.50487050278581e-06 9.79456211906059e-07 1.00188828797181e-05 1.69016276846002e-05 -1.13012517317119e-06 6.07504074646449e-05 -1.67710472098964e-06 2.32201038958175e-06 -1.93897870055989e-06 -2.18176779218949e-06 3.50487050278581e-06 -1.67710472098964e-06 2.81803728588496e-05 -3.44513722077909e-06 3.70259596773231e-06 -4.36733704484885e-06 9.79456211906059e-07 2.32201038958175e-06 -3.44513722077909e-06 3.60529923504337e-05 2952 2956 0 0 6 2953 2958 0 0 7 0 0 0 0 0 0 0 0 77 0 31 35 0 0 2645 +7 52 0.999862913722317 0.0038185551914077 -0.0161112506953558 -0.00492858224165506 -0.00356651696764813 0.999871272882465 0.0156434529793934 0.0026395431922209 0.0161689121290799 -0.0155838474276793 0.999747823193386 -0.0259603548767386 7.88247322990022e-05 2.02455839498619e-05 1.40595497915257e-06 1.21589941484791e-05 -8.18989598998151e-06 3.1718812786435e-05 2.02455839498619e-05 0.000115546743648142 -9.96917609481225e-06 6.09057689429137e-05 -4.23487277017482e-06 2.97703941045361e-05 1.40595497915257e-06 -9.96917609481225e-06 1.94311758699011e-05 -6.70081806535966e-06 -4.65665123315465e-06 8.07416655005899e-08 1.21589941484791e-05 6.09057689429137e-05 -6.70081806535966e-06 0.000109057439874728 3.35742504886345e-06 1.28490692415858e-05 -8.18989598998151e-06 -4.23487277017482e-06 -4.65665123315465e-06 3.35742504886345e-06 3.21492652124891e-05 -8.93204523927608e-06 3.1718812786435e-05 2.97703941045361e-05 8.07416655005899e-08 1.28490692415858e-05 -8.93204523927608e-06 6.97138033303487e-05 2687 2695 0 0 6 2687 2695 0 0 7 0 0 0 0 0 0 0 0 57 0 34 41 0 0 2559 +7 39 0.999988753711457 -0.000888153411584698 -0.00465871593076133 -0.0138904953626544 0.000921980864522621 0.999973191797382 0.00726399599689145 -0.00115113650605628 0.00465213949613434 -0.00726820955083791 0.999962764670782 -0.0233114255911829 4.28714049069849e-05 -1.51481601106218e-06 3.96734974675481e-06 -3.02139715003104e-07 -9.18015402978247e-06 1.81670189622324e-05 -1.51481601106218e-06 2.71463516452222e-05 1.02646042998996e-06 -2.84874159440859e-06 -1.2990617830404e-06 4.02873126191199e-06 3.96734974675481e-06 1.02646042998996e-06 1.41326267875483e-05 -3.87529894766376e-06 -1.75856615023996e-07 1.11819897064327e-06 -3.02139715003104e-07 -2.84874159440859e-06 -3.87529894766376e-06 6.63345315664127e-05 8.904704529692e-06 4.38613333401336e-06 -9.18015402978247e-06 -1.2990617830404e-06 -1.75856615023996e-07 8.904704529692e-06 3.05267722223528e-05 -9.26067244385877e-06 1.81670189622324e-05 4.02873126191199e-06 1.11819897064327e-06 4.38613333401336e-06 -9.26067244385877e-06 6.89485835441297e-05 3008 3008 0 0 3 3015 3037 0 0 3 0 0 0 0 0 0 0 0 60 0 17 20 0 0 2792 +7 46 0.999995697671635 -0.000241098513325479 -0.00292344141847734 -0.0233163371856487 0.000287931307502406 0.999871471057408 0.0160299239255089 0.00848817364036962 0.00291920088081593 -0.0160306967098226 0.999867238701826 -0.0188050370067188 7.49576509475236e-05 -3.03382292352044e-06 1.09204914901982e-05 -8.14715626913122e-06 -1.89250864568959e-05 4.81516094781593e-05 -3.03382292352044e-06 2.41744769214141e-05 -3.54000858623242e-06 7.32598019553359e-06 5.44361722185742e-07 1.6022249040653e-05 1.09204914901982e-05 -3.54000858623242e-06 1.64466039632783e-05 -1.5240385067705e-06 -2.23496669148818e-06 3.97608344474226e-06 -8.14715626913122e-06 7.32598019553359e-06 -1.5240385067705e-06 7.58434038461252e-05 7.42568284721261e-06 4.11691511087886e-07 -1.89250864568959e-05 5.44361722185742e-07 -2.23496669148818e-06 7.42568284721261e-06 4.18549096446916e-05 -1.38641438652598e-05 4.81516094781593e-05 1.6022249040653e-05 3.97608344474226e-06 4.11691511087886e-07 -1.38641438652598e-05 0.000103606738760301 3133 3132 0 0 1 3134 3147 0 0 2 0 0 0 0 0 0 0 0 46 0 38 48 0 0 2599 +7 11 0.999995803581264 -5.89056016483254e-05 -0.00289643746559288 -0.00861273234501324 6.7935717711837e-05 0.999995137767674 0.00311766350794152 0.00066181083938529 0.00289623973459633 -0.00311784719647799 0.999990945371136 -0.000133518492222058 2.74187163020232e-05 -3.12029775881417e-06 6.42534347610673e-06 -3.12525246510791e-06 -8.24036233683122e-07 6.77784411547213e-06 -3.12029775881417e-06 3.18362379667701e-05 -2.57467736260171e-06 2.30837556353316e-06 1.13284525803242e-06 -1.70739111536865e-06 6.42534347610673e-06 -2.57467736260171e-06 1.65864305928876e-05 -2.82908702517327e-06 2.65909555217925e-06 1.62344020409147e-06 -3.12525246510791e-06 2.30837556353316e-06 -2.82908702517327e-06 5.06272652901513e-05 3.36110373086852e-06 -8.18618391006171e-06 -8.24036233683122e-07 1.13284525803242e-06 2.65909555217925e-06 3.36110373086852e-06 2.10726630863144e-05 -4.79310967245879e-06 6.77784411547213e-06 -1.70739111536865e-06 1.62344020409147e-06 -8.18618391006171e-06 -4.79310967245879e-06 3.94664551880795e-05 3055 3063 0 0 11 3055 3063 0 0 11 0 0 0 0 0 0 0 0 70 0 31 41 0 0 2882 +8 48 0.999999691037643 -0.00033694819493245 -0.000710204571497449 -0.016380066343944 0.000346681660763331 0.999905405745735 0.0137498862643661 0.00525595184478216 0.000705504390868328 -0.0137501282310692 0.999905213626363 -0.0227191885465151 9.41331790428248e-05 -1.14036098890243e-06 5.26615291340104e-06 1.34637658799311e-05 -1.53750826749918e-05 4.5142182688189e-05 -1.14036098890243e-06 6.32856661721628e-05 -2.11604281865048e-06 1.56205456618815e-05 -4.9831116111954e-08 8.01400959995666e-06 5.26615291340104e-06 -2.11604281865048e-06 2.16757794237228e-05 -2.40784007050555e-06 -1.24574834462292e-06 1.80086332572242e-06 1.34637658799311e-05 1.56205456618815e-05 -2.40784007050555e-06 9.71434028762468e-05 -4.0992199970212e-07 5.75089696408147e-06 -1.53750826749918e-05 -4.9831116111954e-08 -1.24574834462292e-06 -4.0992199970212e-07 3.39239301517909e-05 -1.09966888056955e-05 4.5142182688189e-05 8.01400959995666e-06 1.80086332572242e-06 5.75089696408147e-06 -1.09966888056955e-05 8.77471416576286e-05 2863 2867 0 0 3 2863 2868 0 0 3 0 0 0 0 0 0 0 0 45 0 37 41 0 0 2416 +8 50 0.999997619453826 -3.79909951067006e-05 0.00218166068956876 -0.00445542875193629 2.74152594578461e-05 0.999988250972841 0.00484738740789364 0.0012069580861852 -0.00218181921424935 -0.00484731605767024 0.999985871496169 -0.0157304985308999 2.5661034484183e-05 3.94343408765921e-06 4.86931833640958e-06 6.09229650462993e-06 1.87678765458855e-06 1.48763336284263e-05 3.94343408765921e-06 4.63432918437709e-05 -3.43933843486451e-06 7.47636917754358e-06 -1.79112871899267e-06 6.18710082497283e-06 4.86931833640958e-06 -3.43933843486451e-06 2.02498852674061e-05 -6.08003508396266e-06 -1.88858884347336e-06 -1.25199846707282e-06 6.09229650462993e-06 7.47636917754358e-06 -6.08003508396266e-06 6.04526711243096e-05 7.13292550697047e-06 7.88155515191247e-06 1.87678765458855e-06 -1.79112871899267e-06 -1.88858884347336e-06 7.13292550697047e-06 2.90255087809146e-05 -6.98762818006574e-06 1.48763336284263e-05 6.18710082497283e-06 -1.25199846707282e-06 7.88155515191247e-06 -6.98762818006574e-06 5.27398695693029e-05 2849 2855 0 0 9 2850 2859 0 0 11 0 0 0 0 0 0 0 0 60 0 28 32 0 0 3082 +8 36 0.999968807174651 0.000390183016757224 -0.0078887536987653 -0.0158216966738934 -0.000286929172580966 0.999914338213617 0.0130856374118705 -0.00205246641555101 0.00789318372751269 -0.0130829657202966 0.999883260015191 -0.0210908803059568 7.1702297374956e-05 7.54922235887855e-06 5.28979436355266e-06 1.13628167881623e-05 -9.74252047396067e-06 3.47540072140791e-05 7.54922235887855e-06 8.2534325393286e-05 -1.01356314738799e-05 2.80113724611698e-05 -2.41660840675404e-06 7.00032612960499e-06 5.28979436355266e-06 -1.01356314738799e-05 1.73646797256846e-05 -5.30552342513301e-06 2.10482786344227e-06 5.08676745439563e-07 1.13628167881623e-05 2.80113724611698e-05 -5.30552342513301e-06 8.59432602678927e-05 5.52399097400471e-06 1.17851774651862e-05 -9.74252047396067e-06 -2.41660840675404e-06 2.10482786344227e-06 5.52399097400471e-06 3.48832737439119e-05 -9.34332270866579e-06 3.47540072140791e-05 7.00032612960499e-06 5.08676745439563e-07 1.17851774651862e-05 -9.34332270866579e-06 8.73705915890212e-05 2815 2824 0 0 3 2818 2832 0 0 4 0 0 0 0 0 0 0 0 59 0 21 23 0 0 2370 +8 44 0.999984502835437 -0.000317186169430336 -0.00555819052370848 -0.0310769083759324 0.00046802202801242 0.999631062068638 0.0271573323967654 0.00970464943122482 0.00554752596615967 -0.0271595128907172 0.999615719071681 -0.0299811633889401 6.81601086038356e-05 -1.90634350533374e-06 5.70617201138393e-06 8.73694044407379e-07 -4.46675353545065e-06 3.73131295911941e-05 -1.90634350533374e-06 3.3565222605368e-05 -5.66068708103218e-06 1.27380934305884e-05 -2.89382023097025e-06 7.39570823748475e-06 5.70617201138393e-06 -5.66068708103218e-06 1.88818087274552e-05 -4.63482252562541e-06 6.60065154643256e-07 -1.98839165503998e-06 8.73694044407379e-07 1.27380934305884e-05 -4.63482252562541e-06 0.000100635938338195 -9.78593104314617e-08 -4.50461128126952e-06 -4.46675353545065e-06 -2.89382023097025e-06 6.60065154643256e-07 -9.78593104314617e-08 3.30903146716958e-05 -3.11348127608047e-06 3.73131295911941e-05 7.39570823748475e-06 -1.98839165503998e-06 -4.50461128126952e-06 -3.11348127608047e-06 6.51199543449642e-05 2754 2754 0 0 1 2757 2761 0 0 1 0 0 0 0 0 0 0 0 27 0 46 49 0 0 2119 +8 45 0.999999268339799 -0.000215415087907439 -0.00119034289488159 -0.00647398194210359 0.000219238023925203 0.999994816103155 0.0032124292219195 0.0015333564553382 0.00118964471854358 -0.00321268783993696 0.999994131673925 -0.0119134135403707 5.55573448758783e-05 -5.96150771137934e-06 4.32722414162355e-06 1.4309032067452e-05 -1.12322406237137e-05 3.66566996731315e-05 -5.96150771137934e-06 2.28592817595965e-05 -5.63065051622015e-06 2.54246014814033e-06 -4.52515868764872e-06 1.6279187154154e-05 4.32722414162355e-06 -5.63065051622015e-06 1.80072203309169e-05 -1.39126130528189e-06 -4.59203572209727e-06 5.66821054619034e-06 1.4309032067452e-05 2.54246014814033e-06 -1.39126130528189e-06 7.21303321986459e-05 -8.91884597612424e-06 1.51394554085079e-05 -1.12322406237137e-05 -4.52515868764872e-06 -4.59203572209727e-06 -8.91884597612424e-06 4.55272577047971e-05 -1.73139882525506e-05 3.66566996731315e-05 1.6279187154154e-05 5.66821054619034e-06 1.51394554085079e-05 -1.73139882525506e-05 8.57840965075858e-05 2951 2960 0 0 14 2955 2972 0 0 16 0 0 0 0 0 0 0 0 28 0 14 16 0 0 2324 +8 51 0.999999907611069 -0.000385381517870955 0.000190417802782389 -0.00118519409633557 0.000384238716713498 0.999982132010088 0.00596556964311669 -1.95869674433537e-06 -0.000192713420683039 -0.0059654959260719 0.999982187701308 -0.0173911858634047 2.6611690921418e-05 -2.66584427156501e-06 3.24799109054872e-06 -1.09288884828896e-06 -2.36967622226791e-06 1.81955370333563e-05 -2.66584427156501e-06 4.2828658252643e-05 -6.86405018944586e-06 1.37777978464314e-05 -2.83518748424489e-09 2.94772442568717e-07 3.24799109054872e-06 -6.86405018944586e-06 2.34183753592512e-05 -1.58974077344398e-05 -6.78288426818478e-06 3.49283397918118e-06 -1.09288884828896e-06 1.37777978464314e-05 -1.58974077344398e-05 8.41221099430313e-05 1.56232452720377e-05 -1.01166810804083e-05 -2.36967622226791e-06 -2.83518748424489e-09 -6.78288426818478e-06 1.56232452720377e-05 3.4926762605152e-05 -1.16096165557169e-05 1.81955370333563e-05 2.94772442568717e-07 3.49283397918118e-06 -1.01166810804083e-05 -1.16096165557169e-05 6.37465472667136e-05 2593 2594 0 0 9 2594 2617 0 0 11 0 0 0 0 0 0 0 0 74 0 10 12 0 0 3093 +8 43 0.999992412766021 -7.19853876612763e-05 -0.00389476937635925 -0.00698567366849068 0.000119702774637702 0.999924924297093 0.0122528135829325 0.00225976852907968 0.00389359495027495 -0.0122531868326699 0.999917346249582 -0.0203750243767697 4.2172386285906e-05 -5.08284842996902e-06 6.4930922774335e-06 3.92729964179757e-06 -9.6004949570204e-06 2.54086426038887e-05 -5.08284842996902e-06 3.66614125342957e-05 -4.18515397208532e-06 3.9610076482334e-06 -3.63498426595801e-06 5.40765705501435e-07 6.4930922774335e-06 -4.18515397208532e-06 1.59563863581399e-05 -3.56059674610479e-06 4.32378752340388e-07 3.17886841791729e-06 3.92729964179757e-06 3.9610076482334e-06 -3.56059674610479e-06 6.65401357375513e-05 9.40345276662677e-06 2.21153948115858e-06 -9.6004949570204e-06 -3.63498426595801e-06 4.32378752340388e-07 9.40345276662677e-06 3.19194737523668e-05 -1.6232026036804e-05 2.54086426038887e-05 5.40765705501435e-07 3.17886841791729e-06 2.21153948115858e-06 -1.6232026036804e-05 6.75570262907445e-05 3059 3060 0 0 8 3059 3081 0 0 8 0 0 0 0 0 0 0 0 18 0 13 15 0 0 2634 +8 42 0.999999821663564 0.000338461162863469 -0.000492053738283579 -0.0035481611994659 -0.000334835554485418 0.99997293363773 0.00734982156948331 -0.000583651735643221 0.000494528049334089 -0.00734965550165603 0.999972868634952 -0.019372334690523 4.82074134698968e-05 -4.20103824648079e-06 4.88541649709634e-06 4.07242135099476e-06 -6.77750013904401e-06 1.50278083731323e-05 -4.20103824648079e-06 2.99201181771149e-05 2.23850613848741e-06 -4.35769946974298e-06 2.41256646491976e-06 4.63508893879591e-06 4.88541649709634e-06 2.23850613848741e-06 1.5142077584317e-05 -1.8405786062559e-06 1.66644321918143e-06 -3.0441790652717e-06 4.07242135099476e-06 -4.35769946974298e-06 -1.8405786062559e-06 5.00126289144456e-05 7.89210232462094e-06 9.90677379613518e-06 -6.77750013904401e-06 2.41256646491976e-06 1.66644321918143e-06 7.89210232462094e-06 2.98594269214461e-05 -4.74518164211408e-07 1.50278083731323e-05 4.63508893879591e-06 -3.0441790652717e-06 9.90677379613518e-06 -4.74518164211408e-07 7.04015268666589e-05 3042 3042 0 0 9 3042 3061 0 0 10 0 0 0 0 0 0 0 0 65 0 13 16 0 0 2622 +8 37 0.999960786977265 0.000389214740876051 -0.00884720406087116 -0.0134567265996724 -0.000276372474545775 0.999918649017394 0.012752214140484 0.00330656618535285 0.00885144768184977 -0.0127492689639419 0.999879546752918 -0.0258897499926176 4.95099108067244e-05 5.0425691072471e-07 2.93347842891137e-06 7.09960456960847e-07 -7.44652362214392e-06 2.68583214555418e-05 5.0425691072471e-07 3.44160743022696e-05 -1.91053429442677e-06 4.94103650807958e-06 -1.97297906089724e-06 1.58953792510506e-06 2.93347842891137e-06 -1.91053429442677e-06 1.44863476354071e-05 -6.83317417710812e-07 2.17253939930785e-06 1.77665020733592e-06 7.09960456960847e-07 4.94103650807958e-06 -6.83317417710812e-07 5.79694906797156e-05 4.59282219453072e-06 4.75006046434942e-06 -7.44652362214392e-06 -1.97297906089724e-06 2.17253939930785e-06 4.59282219453072e-06 3.16609081771103e-05 -1.17596765052602e-05 2.68583214555418e-05 1.58953792510506e-06 1.77665020733592e-06 4.75006046434942e-06 -1.17596765052602e-05 6.98429054997346e-05 3111 3119 0 0 9 3115 3130 0 0 10 0 0 0 0 0 0 0 0 66 0 19 21 0 0 2609 +8 46 0.999999965102083 -0.000215613798493975 -0.000152664738180377 -0.0239318643827957 0.000216781166075174 0.999970420815623 0.00768833530439375 0.0047327090079427 0.000151002511302863 -0.00768836813092683 0.999970432659749 -0.0224121889134974 2.60692762104241e-05 2.39145849705281e-07 5.36999947219884e-06 5.08736501669576e-07 -2.13703407512662e-06 2.01682768556771e-05 2.39145849705281e-07 5.16214160093602e-05 -2.33767070952253e-06 6.94991469107093e-06 -4.23898789737714e-07 6.75619978667348e-06 5.36999947219884e-06 -2.33767070952253e-06 1.73331261913337e-05 -3.2095120966195e-06 5.45974162676723e-07 5.74071161891119e-06 5.08736501669576e-07 6.94991469107093e-06 -3.2095120966195e-06 8.28292239505634e-05 2.5611503419646e-06 -7.58343324171531e-06 -2.13703407512662e-06 -4.23898789737714e-07 5.45974162676723e-07 2.5611503419646e-06 3.18424121798577e-05 -1.02374529665946e-05 2.01682768556771e-05 6.75619978667348e-06 5.74071161891119e-06 -7.58343324171531e-06 -1.02374529665946e-05 6.69389453064277e-05 2875 2877 0 0 1 2883 2903 0 0 1 0 0 0 0 0 0 0 0 47 0 24 26 0 0 2917 +8 41 0.999991736215086 0.000199335636916646 -0.00406051312530603 -0.0033661397740289 -0.000156652996637744 0.999944764096734 0.0105092442813856 0.00248083996288345 0.00406238370609817 -0.0105085213437023 0.999936531994803 -0.0302822575307602 4.33299796744818e-05 7.6868191030435e-06 1.52880025201314e-06 7.3253687308375e-06 -3.03479434044819e-06 2.13622406823734e-05 7.6868191030435e-06 5.79347644268945e-05 -6.54357833041624e-06 1.6332262743184e-05 -1.40528939470372e-06 1.39038550986538e-05 1.52880025201314e-06 -6.54357833041624e-06 1.56001580314838e-05 -4.4090104187708e-06 1.08499163431227e-07 1.69182796098414e-06 7.3253687308375e-06 1.6332262743184e-05 -4.4090104187708e-06 8.60378804201314e-05 1.20796889716562e-05 9.96153170229257e-06 -3.03479434044819e-06 -1.40528939470372e-06 1.08499163431227e-07 1.20796889716562e-05 2.85395229742756e-05 -5.53392153232496e-06 2.13622406823734e-05 1.39038550986538e-05 1.69182796098414e-06 9.96153170229257e-06 -5.53392153232496e-06 6.11064916489348e-05 2899 2902 0 0 10 2900 2923 0 0 11 0 0 0 0 0 0 0 0 94 0 13 15 0 0 2603 +8 39 0.999999752965804 -0.000684755365823443 -0.000158677092583207 -0.0113565114575974 0.000686177259549106 0.999957983133316 0.00914117764397543 -0.000793128298249157 0.000152410955027304 -0.0091412842664045 0.999958205973061 -0.0217685234242272 6.0687164371253e-05 1.17882759181138e-05 1.16124079843465e-05 -5.47627933614735e-06 -1.25437788165121e-05 4.71183748517569e-05 1.17882759181138e-05 3.73127215728037e-05 3.928098050915e-06 3.38673948186108e-06 -6.69329445981686e-06 1.99494717590763e-05 1.16124079843465e-05 3.928098050915e-06 1.75131338896766e-05 -9.78049333087238e-07 9.11602255744491e-07 4.88144748160646e-06 -5.47627933614735e-06 3.38673948186108e-06 -9.78049333087238e-07 6.30471793949301e-05 1.33408223494022e-05 -3.61677085139911e-06 -1.25437788165121e-05 -6.69329445981686e-06 9.11602255744491e-07 1.33408223494022e-05 3.73940060530705e-05 -2.07732252235335e-05 4.71183748517569e-05 1.99494717590763e-05 4.88144748160646e-06 -3.61677085139911e-06 -2.07732252235335e-05 9.72213010124744e-05 3053 3061 0 0 8 3059 3077 0 0 9 0 0 0 0 0 0 0 0 75 0 18 20 0 0 2662 +8 47 0.999923462401992 6.84154679287824e-05 -0.0123719302187085 -0.0161891553426048 0.000142100263680497 0.999855242798222 0.0170139136128024 0.00591046773099059 0.0123713033075705 -0.0170143694632681 0.999778706557726 -0.0232492115872227 5.22593671259209e-05 -7.67085682087309e-06 4.29439522222611e-07 -3.71496287615393e-06 -5.27937157666168e-06 2.67953975012429e-05 -7.67085682087309e-06 0.000132019450410321 -8.97629935092443e-06 5.35551931483849e-05 7.20628946993675e-06 1.09435884684236e-05 4.29439522222611e-07 -8.97629935092443e-06 1.74107636142178e-05 -2.42824838913198e-06 -3.23843939118798e-06 3.34740695551088e-06 -3.71496287615393e-06 5.35551931483849e-05 -2.42824838913198e-06 9.79714908535478e-05 1.08497266008417e-05 -4.89789516765841e-06 -5.27937157666168e-06 7.20628946993675e-06 -3.23843939118798e-06 1.08497266008417e-05 3.2563601543787e-05 -6.2499324900485e-06 2.67953975012429e-05 1.09435884684236e-05 3.34740695551088e-06 -4.89789516765841e-06 -6.2499324900485e-06 8.20083383143703e-05 2740 2741 0 0 2 2745 2767 0 0 5 0 0 0 0 0 0 0 0 57 0 19 22 0 0 2637 +8 40 0.999978457293183 0.000332163195076178 -0.00655550281492405 -0.013328576447272 -0.000270170440248197 0.99995526192017 0.00945521898730907 0.00117275814441918 0.00655835021006476 -0.00945324419321699 0.999933809917809 -0.023563988395522 3.94808874502194e-05 7.66600653604199e-06 1.30629610889702e-06 1.3335439660551e-05 -4.5881489250377e-06 1.38624525247817e-05 7.66600653604199e-06 8.31243589901834e-05 -6.96610018240986e-06 2.44460791360418e-05 5.90508730563615e-07 9.98820673821811e-07 1.30629610889702e-06 -6.96610018240986e-06 1.59340658691903e-05 -4.43456061909479e-06 -1.92690791035675e-06 6.34815090727317e-07 1.3335439660551e-05 2.44460791360418e-05 -4.43456061909479e-06 8.37903305881256e-05 9.85348810703243e-06 -9.71339865946996e-07 -4.5881489250377e-06 5.90508730563615e-07 -1.92690791035675e-06 9.85348810703243e-06 3.39431484555932e-05 -4.25481525275001e-06 1.38624525247817e-05 9.98820673821811e-07 6.34815090727317e-07 -9.71339865946996e-07 -4.25481525275001e-06 5.83142785265058e-05 2768 2778 0 0 3 2770 2780 0 0 5 0 0 0 0 0 0 0 0 75 0 16 19 0 0 2625 +8 38 0.999989958632209 -7.1471996491566e-05 -0.00448079529836631 -0.0147345841476457 0.000122458840528136 0.999935241272206 0.0113797304769692 -0.00250308580710219 0.00447969179570656 -0.011380164921907 0.999925209307059 -0.0264673083452651 6.70833064212264e-05 -7.13108220258549e-06 5.76102546841448e-06 -6.06137212493808e-06 -1.03720153037292e-05 3.67950006630856e-05 -7.13108220258549e-06 4.56830823455633e-05 -6.49545069182206e-06 5.85981929664788e-06 -1.48881289818799e-06 1.20867060417253e-05 5.76102546841448e-06 -6.49545069182206e-06 1.57897701825545e-05 -3.79509052284266e-06 -2.17399099695885e-07 2.17732603837512e-06 -6.06137212493808e-06 5.85981929664788e-06 -3.79509052284266e-06 5.885604682832e-05 1.14273875884047e-05 -7.27147501495798e-06 -1.03720153037292e-05 -1.48881289818799e-06 -2.17399099695885e-07 1.14273875884047e-05 3.81412460128418e-05 -1.12648112841696e-05 3.67950006630856e-05 1.20867060417253e-05 2.17732603837512e-06 -7.27147501495798e-06 -1.12648112841696e-05 0.00010196702700055 3041 3041 0 0 2 3047 3066 0 0 4 0 0 0 0 0 0 0 0 61 0 19 21 0 0 2610 +8 52 0.999784781631436 0.00413782529075725 -0.0203290142418408 -0.0100198592691938 -0.00370316142484327 0.999764718019783 0.0213727676796007 0.00634603112356347 0.0204126679697523 -0.0212928862460635 0.999564873323222 -0.0224313331510528 7.90642910236447e-05 -1.74713724511855e-06 4.308266674716e-06 1.08051524496551e-05 -1.59246151411889e-05 5.72875940566408e-05 -1.74713724511855e-06 4.88884113052062e-05 -6.02838726190476e-06 1.74639151708835e-05 -1.03539770977775e-06 1.05993159731819e-05 4.308266674716e-06 -6.02838726190476e-06 1.9223997532674e-05 -1.81988906791102e-06 -3.15863146564044e-06 6.13849169156486e-07 1.08051524496551e-05 1.74639151708835e-05 -1.81988906791102e-06 8.31206657698939e-05 2.40379303322629e-06 1.37579053110394e-05 -1.59246151411889e-05 -1.03539770977775e-06 -3.15863146564044e-06 2.40379303322629e-06 3.76436622792632e-05 -1.97290287780418e-05 5.72875940566408e-05 1.05993159731819e-05 6.13849169156486e-07 1.37579053110394e-05 -1.97290287780418e-05 9.36405711335459e-05 2919 2920 0 0 1 2920 2924 0 0 2 0 0 0 0 0 0 0 0 60 0 39 41 0 0 2692 +9 11 0.99999982511842 -0.000435267476793209 0.000400381509027176 -0.00617631886595532 0.000435290667669989 0.999999903588475 -5.78366301634678e-05 -0.000992716401287088 -0.000400356296021706 5.80109023832937e-05 0.999999918174782 -0.00213107545751125 3.15913428018771e-05 -2.31202871389881e-06 5.39788512781636e-06 2.48714706319808e-06 -2.81213092000888e-06 9.26215968619852e-06 -2.31202871389881e-06 4.22187764344556e-05 -5.09439617885595e-06 1.02115848414837e-05 -4.03316780555075e-07 7.90040495916846e-07 5.39788512781636e-06 -5.09439617885595e-06 1.64414565354266e-05 -1.83545632397517e-06 1.8639935632997e-06 2.00408530543315e-06 2.48714706319808e-06 1.02115848414837e-05 -1.83545632397517e-06 4.59654502349128e-05 4.27044340373236e-06 1.69802179258066e-06 -2.81213092000888e-06 -4.03316780555075e-07 1.8639935632997e-06 4.27044340373236e-06 2.53655917033925e-05 -3.99444492102179e-06 9.26215968619852e-06 7.90040495916846e-07 2.00408530543315e-06 1.69802179258066e-06 -3.99444492102179e-06 3.61237664179736e-05 3051 3065 0 1 9 3054 3068 0 1 14 0 0 0 0 0 0 0 0 74 0 34 38 0 0 2664 +9 36 0.999999862714842 0.000163911921351968 0.000497697880462409 -0.00852923482687026 -0.000168005117624373 0.999966074523019 0.00823538568037064 -3.81312132314839e-05 -0.000496331117934478 -0.00823546816556536 0.99996596478056 -0.0250044052903969 7.12025449364864e-05 1.01412355433593e-05 7.74304974745552e-06 9.55137985975293e-06 -1.43939753295797e-05 3.5416966869065e-05 1.01412355433593e-05 5.22722008488192e-05 -1.14690207771233e-06 1.13940432703755e-05 2.15262821443307e-08 1.37857595601506e-05 7.74304974745552e-06 -1.14690207771233e-06 1.69792003107707e-05 -1.60859404756589e-06 -9.44024958287236e-07 4.19510426804494e-06 9.55137985975293e-06 1.13940432703755e-05 -1.60859404756589e-06 6.56378384977418e-05 7.07906193840483e-06 6.78296189784317e-06 -1.43939753295797e-05 2.15262821443307e-08 -9.44024958287236e-07 7.07906193840483e-06 3.50046650666963e-05 -1.24352418273172e-05 3.5416966869065e-05 1.37857595601506e-05 4.19510426804494e-06 6.78296189784317e-06 -1.24352418273172e-05 7.93258798656398e-05 2678 2678 0 1 5 2682 2696 0 1 7 0 0 0 0 0 0 0 0 58 0 14 16 0 0 2609 +9 45 0.999951449713113 -0.000300775196464224 -0.00984925128755464 -0.0164000773101243 0.000330219698842655 0.999995481314453 0.00298802704557215 9.43592906716521e-05 0.00984830805746353 -0.00299113439279586 0.999947030568844 -0.0119806101200038 6.28200935530408e-05 -7.15849450220449e-06 3.63415100304955e-06 8.0198669167951e-06 -1.58470130332375e-05 2.35385887657134e-05 -7.15849450220449e-06 6.29474838232834e-05 -3.00519341426342e-06 2.51449387235587e-05 -1.4256431308156e-06 1.0003946157168e-05 3.63415100304955e-06 -3.00519341426342e-06 2.10250867119082e-05 -4.27433386435772e-06 -6.39721253117161e-06 8.32322393080138e-06 8.0198669167951e-06 2.51449387235587e-05 -4.27433386435772e-06 8.99269785608195e-05 -9.12974543709353e-06 1.12026593996776e-05 -1.58470130332375e-05 -1.4256431308156e-06 -6.39721253117161e-06 -9.12974543709353e-06 5.57645763718328e-05 -1.6733262987364e-05 2.35385887657134e-05 1.0003946157168e-05 8.32322393080138e-06 1.12026593996776e-05 -1.6733262987364e-05 7.35233982740363e-05 2800 2800 0 1 2 2807 2821 0 1 3 0 0 0 0 0 0 0 0 27 0 18 20 0 0 2351 +9 47 0.999996506100684 0.000560029512702787 0.00258343828445019 -0.0100820612724354 -0.000602044264091697 0.999867109852823 0.0162911073063203 0.0061536263534092 -0.0025739714700702 -0.0162926057310324 0.999863953580368 -0.0284533310829639 5.89805782611377e-05 -9.80582684200661e-06 1.42461758881744e-06 -8.27233350312711e-07 -1.23800891028256e-05 3.45619786640337e-05 -9.80582684200661e-06 5.33983586156253e-05 -3.27237617018502e-06 6.2847870615722e-06 2.52371235577592e-06 9.24691668051969e-07 1.42461758881744e-06 -3.27237617018502e-06 1.86758685680135e-05 -2.70849831830276e-06 -1.56951138710269e-06 1.91773717258331e-06 -8.27233350312711e-07 6.2847870615722e-06 -2.70849831830276e-06 7.37142064200214e-05 7.91200820493381e-06 -1.34624135687526e-05 -1.23800891028256e-05 2.52371235577592e-06 -1.56951138710269e-06 7.91200820493381e-06 3.77592163272779e-05 -1.37417603536167e-05 3.45619786640337e-05 9.24691668051969e-07 1.91773717258331e-06 -1.34624135687526e-05 -1.37417603536167e-05 7.30074370536239e-05 2852 2852 0 0 5 2858 2870 0 0 8 0 0 0 0 0 0 0 0 53 0 25 33 0 0 2683 +9 49 0.999929055263159 -0.000388557325200941 -0.0119051864215306 -0.0174850914331607 0.000600548971230683 0.999841239897521 0.0178082660896736 0.00457261338917991 0.011896376820676 -0.01781415233438 0.999770539771576 -0.0235626584915636 9.75199163350541e-05 1.51237394970138e-05 -2.22025244599638e-06 3.79238938712541e-05 -1.67726465589119e-05 4.91291034568357e-05 1.51237394970138e-05 0.000133488550977248 -2.8541290869323e-06 5.5836949065792e-05 -9.36738337176318e-07 7.11484067974345e-06 -2.22025244599638e-06 -2.8541290869323e-06 1.87694334502492e-05 -1.43768231783434e-06 -3.16782263466778e-06 -1.48493499317003e-06 3.79238938712541e-05 5.5836949065792e-05 -1.43768231783434e-06 0.000116137530398846 -3.80625877897126e-06 2.16553659267768e-05 -1.67726465589119e-05 -9.36738337176318e-07 -3.16782263466778e-06 -3.80625877897126e-06 3.56303071541872e-05 -1.67161625650906e-05 4.91291034568357e-05 7.11484067974345e-06 -1.48493499317003e-06 2.16553659267768e-05 -1.67161625650906e-05 8.35630281011248e-05 2684 2684 0 0 0 2692 2704 0 0 3 0 0 0 0 0 0 0 0 54 0 16 19 0 0 2425 +9 12 0.999999497326483 0.000146096198338015 -0.000991969093572486 -0.00639783251855354 -0.0001436500385583 0.999996950117282 0.00246558731351825 0.00177422515207901 0.000992326281116266 -0.00246544357773426 0.999996468432022 -0.00416260475297535 3.53889674868764e-05 -5.38590699306977e-06 3.80812029205839e-06 5.98287454247171e-06 1.37820890057294e-06 5.36758614566729e-06 -5.38590699306977e-06 3.31404635891622e-05 -2.96939127750646e-06 9.40686889317697e-06 1.44123137921653e-07 3.56408380192084e-06 3.80812029205839e-06 -2.96939127750646e-06 1.47955324710093e-05 9.51247342514829e-07 -2.97797476917261e-07 4.09068011945058e-06 5.98287454247171e-06 9.40686889317697e-06 9.51247342514829e-07 5.16463731776629e-05 2.56860098336915e-06 3.76195427520916e-06 1.37820890057294e-06 1.44123137921653e-07 -2.97797476917261e-07 2.56860098336915e-06 2.23110567961889e-05 -3.95570891286012e-06 5.36758614566729e-06 3.56408380192084e-06 4.09068011945058e-06 3.76195427520916e-06 -3.95570891286012e-06 3.4667155522442e-05 2900 2900 0 1 6 2903 2916 0 1 8 0 0 0 0 0 0 0 0 59 0 13 16 0 0 2693 +9 13 0.999997963920184 -0.000166681453590167 0.00201106259972631 -0.00143088088040036 0.0001691952938734 0.999999204560391 -0.00124990061148923 -0.00183885827707207 -0.0020108526647967 0.00125023832891939 0.999997196683912 -0.0078278904442615 3.94090531157477e-05 -4.43022588326245e-06 6.32427293667171e-06 1.58986771469821e-06 -4.40124884831508e-06 4.85339846107075e-06 -4.43022588326245e-06 5.14174258583495e-05 -3.57152459953735e-06 7.2546715196776e-06 1.42884044920907e-06 -9.93173803119764e-06 6.32427293667171e-06 -3.57152459953735e-06 1.52699793424192e-05 -4.76959691274131e-07 2.53723855407024e-06 2.01505058124468e-06 1.58986771469821e-06 7.2546715196776e-06 -4.76959691274131e-07 4.46703017234126e-05 4.97220163174555e-06 -3.06541549890533e-06 -4.40124884831508e-06 1.42884044920907e-06 2.53723855407024e-06 4.97220163174555e-06 2.5311806859057e-05 -3.39539979940739e-06 4.85339846107075e-06 -9.93173803119764e-06 2.01505058124468e-06 -3.06541549890533e-06 -3.39539979940739e-06 3.91271333580652e-05 2916 2920 0 0 11 2916 2921 0 0 12 0 0 0 0 0 0 0 0 64 0 10 12 0 0 2655 +9 35 0.999959990453618 0.000305471151923051 -0.00894003240347736 -0.0224792262909639 -0.000262586040223811 0.999988456227812 0.00479775569286804 0.00273285713388339 0.00894139477773809 -0.00479521620913082 0.999948527355752 -0.0136247238267673 4.1875984465283e-05 -2.29665679598978e-06 5.80576158830993e-06 5.4531787816726e-07 -4.81527589974944e-06 6.60498927326138e-06 -2.29665679598978e-06 6.09884544927871e-05 -5.06380232158323e-06 2.35059484482464e-05 -2.97033426378359e-06 4.74149356731561e-06 5.80576158830993e-06 -5.06380232158323e-06 1.45256921439268e-05 -6.96804926949978e-07 5.18895244028596e-07 2.73929789629981e-06 5.4531787816726e-07 2.35059484482464e-05 -6.96804926949978e-07 8.28598886376224e-05 -7.3128553640792e-07 9.09606106698164e-06 -4.81527589974944e-06 -2.97033426378359e-06 5.18895244028596e-07 -7.3128553640792e-07 3.00798142323202e-05 -1.85642549411155e-06 6.60498927326138e-06 4.74149356731561e-06 2.73929789629981e-06 9.09606106698164e-06 -1.85642549411155e-06 4.24848966354672e-05 2542 2542 0 2 0 2551 2561 0 2 1 0 0 0 0 0 0 0 0 52 0 21 23 0 0 2636 +9 43 0.999999656347747 -2.42256111992337e-05 0.000828684202455448 -0.00424283799531485 1.47498502654126e-05 0.999934643270701 0.0114328023484151 0.00296094690407484 -0.000828907008990964 -0.0114327861965389 0.999934299998232 -0.0228037446061086 6.11396408932204e-05 5.2835790699615e-06 7.43630223863447e-06 -1.5236369935551e-07 -9.7663054433486e-06 3.40366366657837e-05 5.2835790699615e-06 5.7620635861468e-05 -1.22846548345463e-06 7.60718469771383e-06 -1.07043340868547e-05 6.58962546116405e-06 7.43630223863447e-06 -1.22846548345463e-06 2.13478898956449e-05 -4.20009376142931e-06 -1.86817604614049e-06 4.04065658045718e-06 -1.5236369935551e-07 7.60718469771383e-06 -4.20009376142931e-06 7.64683096824238e-05 6.4335945185e-06 3.7697466483974e-06 -9.7663054433486e-06 -1.07043340868547e-05 -1.86817604614049e-06 6.4335945185e-06 3.23052593131361e-05 -1.55992230056585e-05 3.40366366657837e-05 6.58962546116405e-06 4.04065658045718e-06 3.7697466483974e-06 -1.55992230056585e-05 7.57546940312513e-05 2945 2945 0 1 8 2951 2963 0 1 11 0 0 0 0 0 0 0 0 17 0 22 29 0 0 2670 +9 51 0.99999925241398 0.000473253213560019 -0.00112747633071418 -0.00010328163070185 -0.000465221377052658 0.999974591424515 0.00711337293021264 0.00246153153970373 0.00113081410974519 -0.00711284308626331 0.999974064025002 -0.0221168707872976 3.69184592326522e-05 1.34798492766063e-07 6.22547964063949e-06 2.55180659441308e-06 -2.37332750492564e-06 3.08636379627707e-05 1.34798492766063e-07 3.42298657001059e-05 -7.90524224849775e-06 4.08246318751563e-06 -1.5300273791381e-06 1.07987281575258e-05 6.22547964063949e-06 -7.90524224849775e-06 2.14555930322086e-05 -3.07663096355649e-06 -3.46025740748767e-06 2.57741428358969e-06 2.55180659441308e-06 4.08246318751563e-06 -3.07663096355649e-06 5.84167668129628e-05 6.99008404730787e-06 2.98036098936229e-06 -2.37332750492564e-06 -1.5300273791381e-06 -3.46025740748767e-06 6.99008404730787e-06 2.89735059819949e-05 -1.13727784188517e-05 3.08636379627707e-05 1.07987281575258e-05 2.57741428358969e-06 2.98036098936229e-06 -1.13727784188517e-05 8.15632595919333e-05 2798 2798 0 1 10 2801 2815 0 1 12 0 0 0 0 0 0 0 0 70 0 19 26 0 0 3103 +9 50 0.99999810116185 -9.60029111995929e-05 -0.00194639567802874 -0.00481272173905432 0.000107124965799932 0.999983664196877 0.00571488089373977 0.00166962151374855 0.00194581523688918 -0.00571507854967635 0.999981775674054 -0.0185797573085816 2.86326142850091e-05 1.61908378339398e-06 2.03211233620859e-06 9.7266037596066e-06 1.36716931333712e-06 2.46445434307996e-05 1.61908378339398e-06 2.52035689095622e-05 -4.6000095618229e-06 3.80113186888686e-06 -1.91613417931637e-06 1.51696102542833e-05 2.03211233620859e-06 -4.6000095618229e-06 1.80616193867411e-05 -5.04306794247807e-06 -2.36203177174965e-06 -9.81497158599529e-07 9.7266037596066e-06 3.80113186888686e-06 -5.04306794247807e-06 7.62852766073496e-05 7.03999930077515e-06 9.20603156395672e-06 1.36716931333712e-06 -1.91613417931637e-06 -2.36203177174965e-06 7.03999930077515e-06 2.62483997976722e-05 -6.14003592409496e-06 2.46445434307996e-05 1.51696102542833e-05 -9.81497158599529e-07 9.20603156395672e-06 -6.14003592409496e-06 7.50788507242382e-05 2810 2824 0 0 10 2810 2825 0 0 14 0 0 0 0 0 0 0 0 58 0 33 37 0 0 3087 +9 40 0.999999351446112 4.78533380327569e-05 0.00113790044073966 -0.00738891717379648 -5.52788939425158e-05 0.99997870046013 0.00652652819755594 0.0016831505136226 -0.00113756388782383 -0.00652658686662849 0.999978054565336 -0.0256932334552169 4.54067972574771e-05 -1.44096474045382e-07 2.29496684615245e-06 8.70060328406229e-06 -9.07228776806347e-06 3.49041919111148e-05 -1.44096474045382e-07 2.91986531944449e-05 -6.08922428858885e-07 -2.12251823539708e-06 -7.0962951591385e-07 2.09411396263546e-06 2.29496684615245e-06 -6.08922428858885e-07 1.34805087623139e-05 1.26012437098309e-06 2.54781880217519e-07 2.76710031905937e-07 8.70060328406229e-06 -2.12251823539708e-06 1.26012437098309e-06 5.76463462943493e-05 -2.37094175442217e-07 2.68210763636171e-06 -9.07228776806347e-06 -7.0962951591385e-07 2.54781880217519e-07 -2.37094175442217e-07 3.27064644099827e-05 -1.64294516317399e-05 3.49041919111148e-05 2.09411396263546e-06 2.76710031905937e-07 2.68210763636171e-06 -1.64294516317399e-05 8.6399067191099e-05 3071 3076 0 1 6 3073 3078 0 1 8 0 0 0 0 0 0 0 0 75 0 12 15 0 0 2632 +9 38 0.999999680416341 -0.000736121167408748 -0.000311918007396842 -0.0100838706089305 0.000738545101475798 0.999968966201248 0.00784354419511891 -0.00279243354884227 0.000306134528486641 -0.00784377205396678 0.999969190286189 -0.0279586566209187 6.51081735073639e-05 -5.55244304308412e-06 5.87240973369743e-06 3.94299728605307e-06 -1.04444637254717e-05 3.23249885157877e-05 -5.55244304308412e-06 6.09694505607596e-05 -3.34149726417867e-06 1.40487493313787e-05 4.00958664188237e-06 3.65771093207262e-06 5.87240973369743e-06 -3.34149726417867e-06 1.62287614780661e-05 -1.95391404594893e-06 -1.71846002970171e-08 1.67684769217645e-06 3.94299728605307e-06 1.40487493313787e-05 -1.95391404594893e-06 7.22817227287076e-05 1.16741832645976e-05 -2.10585195949331e-07 -1.04444637254717e-05 4.00958664188237e-06 -1.71846002970171e-08 1.16741832645976e-05 4.02518648829248e-05 -8.56663867307292e-06 3.23249885157877e-05 3.65771093207262e-06 1.67684769217645e-06 -2.10585195949331e-07 -8.56663867307292e-06 7.77281190311594e-05 2938 2938 0 1 6 2948 2957 0 1 9 0 0 0 0 0 0 0 0 62 0 24 31 0 0 2653 +9 44 0.999893445753405 -0.000685869617399349 -0.0145817256266554 -0.0387951529141343 0.00104398819688937 0.99969766511481 0.0245660019669729 0.00525005125164805 0.0145604679879421 -0.024578607504586 0.999591859123066 -0.0294642513825009 6.2151368807295e-05 4.64320967652805e-06 1.46607740233389e-06 1.22933260021959e-05 -6.80534124715369e-06 3.24941671891905e-05 4.64320967652805e-06 7.11051401155776e-05 -4.86574289915335e-06 3.74953897471904e-05 -6.73490209166061e-06 1.52008530931793e-05 1.46607740233389e-06 -4.86574289915335e-06 1.92118128571311e-05 -9.56034794121657e-07 -5.14046873696149e-07 -4.84004872570676e-06 1.22933260021959e-05 3.74953897471904e-05 -9.56034794121657e-07 0.000102920302097742 -1.33894218663069e-05 5.32798280428837e-06 -6.80534124715369e-06 -6.73490209166061e-06 -5.14046873696149e-07 -1.33894218663069e-05 4.00757190416118e-05 1.87444145428113e-06 3.24941671891905e-05 1.52008530931793e-05 -4.84004872570676e-06 5.32798280428837e-06 1.87444145428113e-06 8.53476348235565e-05 2594 2598 0 0 0 2601 2605 0 0 2 0 0 0 0 0 0 0 0 27 0 48 51 0 0 2135 +9 48 0.999994572494738 -0.00027818607620546 -0.00328292454563422 -0.0160597863717414 0.000347020001415967 0.99977972307593 0.020985349731058 0.00811168456426772 0.00327636356101387 -0.0209863750734424 0.999774393302355 -0.028965348164727 8.44723979614085e-05 2.75208079828672e-07 7.32574758095508e-06 -1.75932428330328e-06 -1.52789722029435e-05 5.99479600192428e-05 2.75208079828672e-07 3.02198633903924e-05 -3.73131651268096e-06 9.12834213561412e-06 -1.53979627825394e-06 2.28850203850464e-05 7.32574758095508e-06 -3.73131651268096e-06 1.69145972512298e-05 -3.26647884043865e-06 -3.55812441767973e-06 2.1411998888063e-06 -1.75932428330328e-06 9.12834213561412e-06 -3.26647884043865e-06 8.21562585353829e-05 1.2232311131103e-05 8.92316406370684e-06 -1.52789722029435e-05 -1.53979627825394e-06 -3.55812441767973e-06 1.2232311131103e-05 3.51414629966143e-05 -2.06032319749784e-05 5.99479600192428e-05 2.28850203850464e-05 2.1411998888063e-06 8.92316406370684e-06 -2.06032319749784e-05 0.000114230408738697 3121 3133 0 1 5 3119 3133 0 1 9 0 0 0 0 0 0 0 0 39 0 33 37 0 0 2433 +9 42 0.999986518157603 -0.000432673431445984 -0.00517458179333934 -0.00706895648959588 0.000487118737915352 0.999944491429111 0.0105250546749999 0.0024616049271544 0.00516974064817665 -0.010527433413624 0.999931221098407 -0.0231073252689 4.89934967660088e-05 -2.86186066292897e-06 4.57852369699532e-06 3.05601784491676e-06 -1.04969907074998e-05 2.27568303140317e-05 -2.86186066292897e-06 3.33617478417169e-05 -3.69177580397152e-07 1.49086065153532e-06 1.6304723613776e-06 1.8194636218135e-05 4.57852369699532e-06 -3.69177580397152e-07 1.57505401691472e-05 -3.58438668077612e-06 1.48424726361647e-06 8.32003012263755e-07 3.05601784491676e-06 1.49086065153532e-06 -3.58438668077612e-06 6.68909035067016e-05 1.00319735452825e-05 2.00284473240991e-06 -1.04969907074998e-05 1.6304723613776e-06 1.48424726361647e-06 1.00319735452825e-05 2.86376267690465e-05 -1.35890574294086e-05 2.27568303140317e-05 1.8194636218135e-05 8.32003012263755e-07 2.00284473240991e-06 -1.35890574294086e-05 8.76972846225144e-05 2999 2999 0 0 8 3006 3017 0 0 11 0 0 0 0 0 0 0 0 59 0 21 28 0 0 2619 +9 41 0.999988183524828 0.00154335315081446 -0.00460986678410732 -0.00256295257614506 -0.00147868562940945 0.999900920226392 0.0139986863392095 0.00585022850185451 0.00463101495621887 -0.0139917043803128 0.999891387056119 -0.0365845216926258 5.82678905114734e-05 -1.4693996389554e-06 1.09098753272227e-05 -1.55106631075372e-06 -1.32450474541241e-05 3.28296153420077e-05 -1.4693996389554e-06 3.19676008456665e-05 -6.08896126616163e-06 6.98816659986593e-07 -3.01124755994458e-06 1.7694295583458e-05 1.09098753272227e-05 -6.08896126616163e-06 2.30519398574541e-05 -1.22385847356179e-05 -2.08664537101573e-06 7.17806206898149e-06 -1.55106631075372e-06 6.98816659986593e-07 -1.22385847356179e-05 9.07283181616238e-05 8.59992457949913e-06 -6.69716096433068e-06 -1.32450474541241e-05 -3.01124755994458e-06 -2.08664537101573e-06 8.59992457949913e-06 3.62751536157333e-05 -1.34095477598808e-05 3.28296153420077e-05 1.7694295583458e-05 7.17806206898149e-06 -6.69716096433068e-06 -1.34095477598808e-05 7.85294922393696e-05 2807 2807 0 1 9 2811 2825 0 1 12 0 0 0 0 0 0 0 0 90 0 21 28 0 0 2622 +9 52 0.99977921019053 0.00428388778841087 -0.0205713192629116 -0.0112514333220619 -0.00377543463132619 0.999687973295047 0.0246921473870851 0.00721494579493465 0.0206706788506066 -0.0246090299414108 0.999483425916207 -0.0329138535722164 7.73318399548771e-05 -4.45519327565222e-07 4.06365565459011e-06 -2.02555074945192e-06 -2.07572575380275e-05 5.96503899044311e-05 -4.45519327565222e-07 0.000120822476795953 -8.48601796446998e-06 6.23377909249212e-05 6.93919583677294e-06 -1.70758222246372e-06 4.06365565459011e-06 -8.48601796446998e-06 2.17916919993122e-05 -4.97479508093166e-06 -6.0719130225203e-06 3.00269239900371e-06 -2.02555074945192e-06 6.23377909249212e-05 -4.97479508093166e-06 0.000145229330496409 1.02045616344769e-05 -9.30680557430203e-06 -2.07572575380275e-05 6.93919583677294e-06 -6.0719130225203e-06 1.02045616344769e-05 4.82168502765973e-05 -2.57110472068551e-05 5.96503899044311e-05 -1.70758222246372e-06 3.00269239900371e-06 -9.30680557430203e-06 -2.57110472068551e-05 0.000101279904858674 2722 2735 0 1 0 2725 2738 0 1 5 0 0 0 0 0 0 0 0 54 0 39 41 0 0 2731 +10 13 0.999999392076795 -0.000922431060676148 -0.000604124969543153 -0.00326423502740944 0.000923288658058386 0.999998564385598 0.00142083243074932 0.00246277811478405 0.000602813482286507 -0.00142138934872475 0.999998808133402 -0.00665738940945593 3.2795857372158e-05 -2.68434150544441e-06 6.62196564314446e-06 -8.09914080872949e-06 -9.62339433999142e-07 2.16393969703443e-06 -2.68434150544441e-06 2.62811203573271e-05 -1.58098597949452e-06 4.51761860121764e-07 1.49769527682602e-06 2.88646975180216e-06 6.62196564314446e-06 -1.58098597949452e-06 1.72176265715958e-05 -4.01686554064156e-06 -4.93659658550987e-07 2.51961058399054e-06 -8.09914080872949e-06 4.51761860121764e-07 -4.01686554064156e-06 4.74922902291187e-05 6.24994183545919e-06 -2.46475817837998e-06 -9.62339433999142e-07 1.49769527682602e-06 -4.93659658550987e-07 6.24994183545919e-06 2.45779860624443e-05 -1.55396143578703e-06 2.16393969703443e-06 2.88646975180216e-06 2.51961058399054e-06 -2.46475817837998e-06 -1.55396143578703e-06 2.71018104062976e-05 2839 2840 0 0 11 2849 2858 0 0 14 0 0 0 0 0 0 0 0 58 0 9 11 0 0 2618 +10 12 0.999991893547638 0.000830961777930246 -0.00393984029279352 -0.00392582444599875 -0.000820209899318187 0.999995937593734 0.00272984463859451 -0.000264374203446779 0.00394209268411598 -0.00272659101322911 0.99998851273738 -0.000496226206204116 3.31970053454006e-05 -7.81887498761e-06 4.77397812396521e-06 5.05005421136123e-07 -2.87491387829991e-06 7.76568919463974e-06 -7.81887498761e-06 2.9457632536386e-05 -5.00011068518632e-06 1.40543014316225e-06 -9.10129748979255e-07 -7.4646171379199e-06 4.77397812396521e-06 -5.00011068518632e-06 1.52209126196328e-05 -5.59828794539696e-07 3.96115696395417e-06 2.48726874148901e-06 5.05005421136123e-07 1.40543014316225e-06 -5.59828794539696e-07 4.48641586769401e-05 5.567399132294e-06 1.9611567487626e-06 -2.87491387829991e-06 -9.10129748979255e-07 3.96115696395417e-06 5.567399132294e-06 2.45603815273283e-05 1.79476159797929e-07 7.76568919463974e-06 -7.4646171379199e-06 2.48726874148901e-06 1.9611567487626e-06 1.79476159797929e-07 3.29746511436778e-05 2952 2969 0 0 9 2952 2969 0 0 11 0 0 0 0 0 0 0 0 72 0 13 16 0 0 2652 +10 14 0.999996865179453 0.000117114564229682 -0.00250118280941035 -0.00047957372666039 -0.000122687930065192 0.999997509910781 -0.00222825490228493 -0.00167507060932663 0.00250091562014012 0.00222855478204728 0.999994389466583 -0.00197625929144533 2.95820567786745e-05 -9.68881376427344e-07 5.23434258359103e-06 3.84371831489441e-06 1.87191305489988e-06 6.54859106486572e-06 -9.68881376427344e-07 3.25996497254417e-05 -4.6732478838122e-06 6.09270938287475e-06 5.868090435925e-07 -6.57048569989417e-06 5.23434258359103e-06 -4.6732478838122e-06 1.42219289667951e-05 2.01236408753016e-07 2.39836029974718e-06 1.17145761861202e-06 3.84371831489441e-06 6.09270938287475e-06 2.01236408753016e-07 4.36862717232328e-05 3.81951850620968e-06 9.84813585867703e-07 1.87191305489988e-06 5.868090435925e-07 2.39836029974718e-06 3.81951850620968e-06 2.4890473120742e-05 3.4025452288101e-07 6.54859106486572e-06 -6.57048569989417e-06 1.17145761861202e-06 9.84813585867703e-07 3.4025452288101e-07 3.27542768560828e-05 2972 2977 0 0 10 2972 2993 0 0 13 0 0 0 0 0 0 0 0 70 0 12 16 0 0 2601 +9 46 0.999991941328438 9.8055963423774e-06 -0.00401462103210698 -0.0283318532200033 1.97963980566061e-05 0.999972815623995 0.00737344025016475 0.00640157446028297 0.00401458419811807 -0.00737346030506749 0.999964756977388 -0.0252363247038326 3.58653802821404e-05 -1.69783639961492e-06 -4.88625463483226e-07 4.09123475450477e-07 2.43159245760207e-06 3.04312111790455e-05 -1.69783639961492e-06 2.19398951405587e-05 -4.2259842229813e-06 -4.19634698251628e-06 -3.30032522196865e-06 1.44596446452727e-05 -4.88625463483226e-07 -4.2259842229813e-06 1.55660409352529e-05 -2.05747216245694e-06 -1.89788722286341e-06 -8.99621366312928e-07 4.09123475450477e-07 -4.19634698251628e-06 -2.05747216245694e-06 7.07249877660786e-05 4.30710620357272e-06 -7.05969291940469e-06 2.43159245760207e-06 -3.30032522196865e-06 -1.89788722286341e-06 4.30710620357272e-06 2.95294923931812e-05 -5.95130320492663e-06 3.04312111790455e-05 1.44596446452727e-05 -8.99621366312928e-07 -7.05969291940469e-06 -5.95130320492663e-06 8.41974679713494e-05 3125 3124 0 0 0 3133 3139 0 0 3 0 0 0 0 0 0 0 0 44 0 40 47 0 0 2927 +10 36 0.999988821478537 -0.000342233252464793 -0.00471590864710602 -0.0131478791027188 0.000406296048584412 0.999907567153137 0.0135901461881933 0.00406092607409942 0.00471082174231276 -0.0135919103255013 0.999896528712954 -0.0278352460548617 6.95911121287148e-05 -4.40657178087957e-07 5.02476220177128e-06 8.92090343876672e-06 -1.68428627218718e-05 4.2697235931944e-05 -4.40657178087957e-07 3.06306076255354e-05 -6.48733037599718e-06 6.54220400608791e-06 1.1306160339799e-06 1.99788033451835e-05 5.02476220177128e-06 -6.48733037599718e-06 1.5501582983522e-05 -2.76247808183088e-07 -2.06247558964444e-06 -1.84891457950552e-06 8.92090343876672e-06 6.54220400608791e-06 -2.76247808183088e-07 7.30866965590575e-05 2.51924677609864e-06 1.98604541602542e-05 -1.68428627218718e-05 1.1306160339799e-06 -2.06247558964444e-06 2.51924677609864e-06 3.25954586305618e-05 -1.5601278596204e-05 4.2697235931944e-05 1.99788033451835e-05 -1.84891457950552e-06 1.98604541602542e-05 -1.5601278596204e-05 9.17260979680025e-05 2846 2863 0 0 3 2847 2864 0 0 4 0 0 0 0 0 0 0 0 63 0 17 19 0 0 2338 +9 39 0.999985111907096 0.000102122609888173 -0.0054557799741331 -0.0139036706855943 -2.66235592370716e-05 0.999904268741654 0.0138366413339771 0.00320184380465474 0.00545667071937603 -0.0138362900804941 0.999889384792872 -0.0263430990148103 5.55884521208974e-05 7.44380943171132e-06 6.86050766844566e-06 4.29179036902022e-06 -5.92885534759408e-06 3.76294989026745e-05 7.44380943171132e-06 3.67093407693987e-05 -1.32646397833635e-07 6.89752943437787e-06 -2.6082747556194e-06 1.77981441355206e-05 6.86050766844566e-06 -1.32646397833635e-07 1.38086680700756e-05 1.36196603619277e-07 7.2471845345827e-07 1.22149813693442e-06 4.29179036902022e-06 6.89752943437787e-06 1.36196603619277e-07 6.34376603074443e-05 6.15132570712013e-07 1.27515546366638e-05 -5.92885534759408e-06 -2.6082747556194e-06 7.2471845345827e-07 6.15132570712013e-07 3.18881186845958e-05 -9.67487393987504e-06 3.76294989026745e-05 1.77981441355206e-05 1.22149813693442e-06 1.27515546366638e-05 -9.67487393987504e-06 9.4019150051488e-05 3026 3026 0 1 1 3033 3054 0 1 5 0 0 0 0 0 0 0 0 70 0 15 17 0 0 2724 +10 45 0.999973577613446 -0.0002510129154909 -0.00726505798195676 -0.0072447955084395 0.000264069604965213 0.999998351809602 0.0017962865368207 -0.00186934475204868 0.0072645951166373 -0.0017981575556348 0.999971995751479 -0.0156651070391543 6.13764659926289e-05 2.8699933602385e-06 7.97515592010215e-06 -3.89729596940297e-06 -1.27085351707997e-05 4.31933079751155e-05 2.8699933602385e-06 0.000172757839182653 -5.27755881991243e-06 7.3535604517465e-05 3.71960301821213e-06 -2.73973035917143e-05 7.97515592010215e-06 -5.27755881991243e-06 2.50519513706379e-05 -5.85887068652457e-06 -6.88067225987003e-06 7.79710615057918e-06 -3.89729596940297e-06 7.3535604517465e-05 -5.85887068652457e-06 0.0001231803543094 1.3550705397198e-05 -2.67051704051801e-05 -1.27085351707997e-05 3.71960301821213e-06 -6.88067225987003e-06 1.3550705397198e-05 4.55010596426628e-05 -2.03943446989407e-05 4.31933079751155e-05 -2.73973035917143e-05 7.79710615057918e-06 -2.67051704051801e-05 -2.03943446989407e-05 0.000108432209609649 2596 2615 0 0 8 2596 2616 0 0 9 0 0 0 0 0 0 0 0 28 0 15 17 0 0 2306 +9 37 0.999882242111311 0.00055882420557478 -0.0153358933865744 -0.0162493429565507 -0.000320918506730785 0.999879644499203 0.0155110775724951 0.0044484542055189 0.0153427155930477 -0.0155043294487438 0.999762080120353 -0.0300892471648123 6.56088383248889e-05 1.12959441326615e-05 1.01194161121694e-06 2.79591571539402e-06 -1.47916914528553e-05 3.83693273299526e-05 1.12959441326615e-05 0.000111239347810003 -6.14151306909967e-06 4.50121409832718e-05 5.04321510960261e-07 -1.60032280202282e-05 1.01194161121694e-06 -6.14151306909967e-06 1.68277719326614e-05 -1.05552304563366e-06 1.49366115432486e-06 4.12203046994743e-07 2.79591571539402e-06 4.50121409832718e-05 -1.05552304563366e-06 8.51613015820791e-05 6.14400968503171e-06 -9.53221139047605e-06 -1.47916914528553e-05 5.04321510960261e-07 1.49366115432486e-06 6.14400968503171e-06 3.4929672409682e-05 -1.85742681650524e-05 3.83693273299526e-05 -1.60032280202282e-05 4.12203046994743e-07 -9.53221139047605e-06 -1.85742681650524e-05 8.56076741989834e-05 2924 2924 0 1 3 2932 2946 0 1 4 0 0 0 0 0 0 0 0 53 0 17 19 0 0 2668 +10 47 0.999989168336544 0.0013909315405418 -0.0044416797538715 -0.0103174356454114 -0.00130550702648098 0.999815236682477 0.0191778035490858 0.0099810923618028 0.00446753410621953 -0.0191717971774439 0.999806222891214 -0.0295464603908596 6.60335339678037e-05 -8.06324624068172e-06 -4.14138763288239e-07 -1.99851512692341e-06 -8.90423652847506e-06 4.53508682543072e-05 -8.06324624068172e-06 2.63525926634615e-05 -4.32045238334929e-06 5.49188327279555e-06 -4.02528567377013e-06 1.25031108197414e-05 -4.14138763288239e-07 -4.32045238334929e-06 1.66479795095855e-05 -1.9815136575573e-06 3.63002624628392e-07 1.92178673955928e-06 -1.99851512692341e-06 5.49188327279555e-06 -1.9815136575573e-06 5.97590908411434e-05 6.90547990343226e-06 3.47845582175835e-06 -8.90423652847506e-06 -4.02528567377013e-06 3.63002624628392e-07 6.90547990343226e-06 3.20421368982346e-05 -1.50558198419406e-05 4.53508682543072e-05 1.25031108197414e-05 1.92178673955928e-06 3.47845582175835e-06 -1.50558198419406e-05 9.37521721382612e-05 3047 3059 0 0 2 3050 3070 0 0 5 0 0 0 0 0 0 0 0 60 0 18 22 0 0 2668 +10 49 0.999999694995844 4.42401206208228e-06 0.000781017699872674 -0.00666735138271236 -2.20192607966944e-05 0.999746166047333 0.0225300463561621 0.0112539710453564 -0.000780719777865974 -0.0225300566818367 0.99974586121801 -0.0285719482438461 6.92723148375872e-05 -9.29852933681447e-06 6.63565479693514e-06 -5.14352437273208e-06 -1.16779242644092e-05 2.70689802250047e-05 -9.29852933681447e-06 3.06246556811916e-05 -3.19589069675108e-06 -1.54662486896939e-06 2.00624870682232e-06 1.68927166044456e-06 6.63565479693514e-06 -3.19589069675108e-06 2.03189045728291e-05 -7.08172276643908e-06 -4.81014098437168e-07 4.16519189319336e-06 -5.14352437273208e-06 -1.54662486896939e-06 -7.08172276643908e-06 7.2437990864665e-05 1.11836950335554e-05 -7.88180668685434e-06 -1.16779242644092e-05 2.00624870682232e-06 -4.81014098437168e-07 1.11836950335554e-05 3.82581877305606e-05 -7.13529327744677e-06 2.70689802250047e-05 1.68927166044456e-06 4.16519189319336e-06 -7.88180668685434e-06 -7.13529327744677e-06 6.58663442179864e-05 3004 3021 0 0 8 3004 3023 0 0 10 0 0 0 0 0 0 0 0 65 0 11 14 0 0 2379 +10 44 0.999892603650606 -0.000489869858262446 -0.0146472247314891 -0.0373258936357982 0.000865108079213028 0.999671301848426 0.0256230335574165 0.00521216871665217 0.0146298582639771 -0.0256329531696053 0.999564364590385 -0.0324674666533745 6.23963952045459e-05 2.5353895474465e-05 1.93880108198183e-07 3.05578405111665e-05 -7.61765515008076e-06 2.28695006774773e-05 2.5353895474465e-05 0.000109724747301377 -5.41044906323704e-07 4.55191660707839e-05 -2.19528376389193e-06 1.25373300918829e-05 1.93880108198183e-07 -5.41044906323704e-07 1.57521024115724e-05 1.90999505401162e-06 -9.48005565331587e-07 -1.96888518726165e-06 3.05578405111665e-05 4.55191660707839e-05 1.90999505401162e-06 0.000111683679807874 -9.20456644596838e-06 -2.91490801197704e-06 -7.61765515008076e-06 -2.19528376389193e-06 -9.48005565331587e-07 -9.20456644596838e-06 3.81493488156613e-05 3.26041216179198e-06 2.28695006774773e-05 1.25373300918829e-05 -1.96888518726165e-06 -2.91490801197704e-06 3.26041216179198e-06 5.99022729513756e-05 2484 2484 0 0 0 2497 2509 0 0 0 0 0 0 0 0 0 0 0 27 0 33 37 0 0 2105 +10 50 0.999977271779788 -0.000431988683366007 -0.00672824714395248 -0.00730031435128391 0.000468460265729335 0.999985201779136 0.00542003392250131 0.000296646367889503 0.00672580618454723 -0.00542306265122171 0.999962676264794 -0.0175606297506 3.19190811226045e-05 -3.69851516085649e-07 1.55680244802231e-06 7.68204822041612e-06 -4.23759689138751e-07 2.27822940330754e-05 -3.69851516085649e-07 4.60240935956266e-05 -1.1730594355223e-06 7.74143904986287e-06 -5.20928277149704e-07 5.07511828596264e-06 1.55680244802231e-06 -1.1730594355223e-06 2.10216669048597e-05 -1.10462484303449e-05 -2.16424616395494e-06 1.05769281100589e-06 7.68204822041612e-06 7.74143904986287e-06 -1.10462484303449e-05 9.16058533384172e-05 1.05130450782347e-05 8.50894554562491e-06 -4.23759689138751e-07 -5.20928277149704e-07 -2.16424616395494e-06 1.05130450782347e-05 3.12371370853635e-05 -7.93993691350993e-06 2.27822940330754e-05 5.07511828596264e-06 1.05769281100589e-06 8.50894554562491e-06 -7.93993691350993e-06 7.16716037715201e-05 2847 2848 0 0 10 2850 2864 0 0 12 0 0 0 0 0 0 0 0 57 0 14 18 0 0 3081 +10 48 0.999940063948989 -0.000465209282012189 -0.0109385597779872 -0.0212925558261661 0.000678044334375079 0.999810373870263 0.0194616689234673 0.0054119766355317 0.0109274317922049 -0.0194679192963696 0.99975076461721 -0.0277112929523971 9.86804206364557e-05 -1.34826681530807e-05 3.34514784078084e-06 7.44145215483844e-06 -1.80736317368595e-05 6.13622699034906e-05 -1.34826681530807e-05 5.23198008093367e-05 -2.06813534924451e-06 2.88326249536422e-06 -4.50029817863613e-06 2.58808048350957e-06 3.34514784078084e-06 -2.06813534924451e-06 1.96903760057827e-05 -5.45954114025699e-06 -1.39672332099408e-06 1.56120213781859e-06 7.44145215483844e-06 2.88326249536422e-06 -5.45954114025699e-06 7.38790735488353e-05 1.22076377953448e-05 -2.9732432781853e-06 -1.80736317368595e-05 -4.50029817863613e-06 -1.39672332099408e-06 1.22076377953448e-05 4.07584444807202e-05 -1.73754282023322e-05 6.13622699034906e-05 2.58808048350957e-06 1.56120213781859e-06 -2.9732432781853e-06 -1.73754282023322e-05 0.000105499001255026 2988 2987 0 0 1 2996 3008 0 0 2 0 0 0 0 0 0 0 0 39 0 21 25 0 0 2393 +10 40 0.999979072783352 0.000112894177256864 -0.00646848129410081 -0.00960322638027326 -3.94674567475756e-05 0.999935580612499 0.0113504655175417 0.00554810852746652 0.00646934599996386 -0.011349972689385 0.999914659199615 -0.029203269631337 5.47257971007206e-05 6.9954822318004e-06 1.48435326036674e-06 1.96524866410811e-05 -1.12813309033907e-05 4.6952550165427e-05 6.9954822318004e-06 4.31202384749557e-05 -5.95324347078748e-06 1.37374818231319e-05 -6.15640800514462e-06 2.13586207901782e-05 1.48435326036674e-06 -5.95324347078748e-06 1.55635471801131e-05 -1.58339296078471e-07 3.8305921428176e-07 6.40117157389743e-07 1.96524866410811e-05 1.37374818231319e-05 -1.58339296078471e-07 8.22414643962124e-05 5.87192135799796e-07 2.37429105448782e-05 -1.12813309033907e-05 -6.15640800514462e-06 3.8305921428176e-07 5.87192135799796e-07 3.34124708965395e-05 -1.4127745354222e-05 4.6952550165427e-05 2.13586207901782e-05 6.40117157389743e-07 2.37429105448782e-05 -1.4127745354222e-05 9.9139976569044e-05 2986 2986 0 0 7 2997 3004 0 0 8 0 0 0 0 0 0 0 0 78 0 13 16 0 0 2607 +10 51 0.999976512929663 5.38045095757947e-05 -0.00685351691509706 -0.00284352914556355 -4.90393678679595e-06 0.99997454609783 0.00713492343262006 0.000243700407951513 0.00685372635740414 -0.00713472224495783 0.999951059889185 -0.0205116028715012 3.43014344595584e-05 3.88037248231747e-06 4.3186862494093e-06 8.08655826082542e-06 -3.17285838013408e-06 3.58027424722295e-05 3.88037248231747e-06 4.71735075872854e-05 -7.06476843906359e-06 1.91319267469353e-05 -1.29613360534216e-06 1.4511723411339e-05 4.3186862494093e-06 -7.06476843906359e-06 2.01121405445279e-05 -6.727137531212e-06 -2.47483340733374e-06 3.2801214506022e-06 8.08655826082542e-06 1.91319267469353e-05 -6.727137531212e-06 8.40335565920683e-05 6.23105069481615e-06 1.17348250324293e-05 -3.17285838013408e-06 -1.29613360534216e-06 -2.47483340733374e-06 6.23105069481615e-06 3.26092899181884e-05 -9.4071742558066e-06 3.58027424722295e-05 1.4511723411339e-05 3.2801214506022e-06 1.17348250324293e-05 -9.4071742558066e-06 9.70655156972538e-05 2941 2946 0 0 9 2941 2961 0 0 10 0 0 0 0 0 0 0 0 72 0 12 17 0 0 3100 +10 52 0.999949077373907 0.0046343182855514 -0.00896469481360102 -0.000150621906681694 -0.00440114277268221 0.999655948924088 0.0258575660682877 0.0116329610323644 0.00908144269195529 -0.0258167944313309 0.999625440114408 -0.0338505350423581 7.39732774089635e-05 3.39775483736263e-06 5.63662163634207e-06 2.41556560184923e-05 -1.47377909483796e-05 5.07933449134829e-05 3.39775483736263e-06 4.8840761250636e-05 -3.26228598932992e-06 1.12195578934985e-05 4.80990279892526e-07 1.72175555451014e-05 5.63662163634207e-06 -3.26228598932992e-06 2.08185438625849e-05 1.23097326374906e-06 -6.83050116431768e-06 1.17123712256367e-06 2.41556560184923e-05 1.12195578934985e-05 1.23097326374906e-06 8.05429160942145e-05 -7.20873479715718e-06 3.15127933324823e-05 -1.47377909483796e-05 4.80990279892526e-07 -6.83050116431768e-06 -7.20873479715718e-06 4.02828392173651e-05 -1.84581056224773e-05 5.07933449134829e-05 1.72175555451014e-05 1.17123712256367e-06 3.15127933324823e-05 -1.84581056224773e-05 9.84900180015538e-05 2950 2950 0 0 4 2952 2966 0 0 7 0 0 0 0 0 0 0 0 62 0 15 16 0 0 2749 +10 43 0.999995794497143 0.00119476434951178 -0.00264263621723078 -0.00174113244555285 -0.00115507853868326 0.999887300144352 0.0149683934879034 0.0048250755906436 0.00266022209541938 -0.0149652780859018 0.999884475162113 -0.0244250776975493 5.47908509386264e-05 6.69224477592066e-08 9.28675737407079e-06 8.65609846684013e-07 -8.22285173244559e-06 2.52203560108163e-05 6.69224477592066e-08 3.57501359119558e-05 -5.70866631658541e-06 1.17795820347593e-06 1.64715561894601e-07 1.7189217604157e-05 9.28675737407079e-06 -5.70866631658541e-06 2.1550814281092e-05 -8.83859741497338e-06 -5.57827118846782e-07 2.04014650320722e-06 8.65609846684013e-07 1.17795820347593e-06 -8.83859741497338e-06 7.27895735113444e-05 1.13733381468644e-05 -2.66219674732745e-06 -8.22285173244559e-06 1.64715561894601e-07 -5.57827118846782e-07 1.13733381468644e-05 3.1162823740785e-05 -1.17941321192117e-05 2.52203560108163e-05 1.7189217604157e-05 2.04014650320722e-06 -2.66219674732745e-06 -1.17941321192117e-05 7.57046072895857e-05 2899 2909 0 0 8 2901 2924 0 0 12 0 0 0 0 0 0 0 0 18 0 11 13 0 0 2649 +10 46 0.999931437812196 -0.000615034568460035 -0.011693648161072 -0.0317491030859249 0.000719019140592245 0.999960222226347 0.00889027426520238 0.00571183461836243 0.0116877151877861 -0.00889807268539974 0.99989210498742 -0.024370413395425 2.87955355750814e-05 4.38037455865362e-06 3.31833859432896e-06 4.23153639238522e-06 -1.94057646363232e-06 2.26175089296549e-05 4.38037455865362e-06 4.90022355166323e-05 -6.24295795095053e-06 2.15491961261157e-05 2.08799737255244e-07 1.2352445896316e-05 3.31833859432896e-06 -6.24295795095053e-06 1.74147500398755e-05 -4.08668469961738e-06 1.68563561751021e-06 7.70276305395668e-07 4.23153639238522e-06 2.15491961261157e-05 -4.08668469961738e-06 8.65620060146452e-05 1.3928237467654e-06 9.10417463648005e-06 -1.94057646363232e-06 2.08799737255244e-07 1.68563561751021e-06 1.3928237467654e-06 3.18501817512928e-05 -5.93828921756528e-06 2.26175089296549e-05 1.2352445896316e-05 7.70276305395668e-07 9.10417463648005e-06 -5.93828921756528e-06 7.55185018009475e-05 2961 2966 0 0 1 2968 2977 0 0 1 0 0 0 0 0 0 0 0 45 0 27 38 0 0 2918 +10 41 0.99995383296152 0.00103292068646775 -0.0095532727596123 -0.00428231966017383 -0.00088265392435615 0.999876040248705 0.0157202117867699 0.00457392869637524 0.00956832627024717 -0.0157110537974557 0.999830790644577 -0.0377307614737318 5.5608557399751e-05 4.30893765196458e-06 4.2820274566826e-06 7.60496061057721e-06 -1.12653482020543e-05 3.0689753140272e-05 4.30893765196458e-06 4.54470912673116e-05 -3.8505725652116e-06 1.38889906004217e-05 -1.22438887538648e-06 6.85904210208672e-06 4.2820274566826e-06 -3.8505725652116e-06 1.50512083347247e-05 -1.39279642824084e-06 3.33298990514948e-07 3.1012355758716e-06 7.60496061057721e-06 1.38889906004217e-05 -1.39279642824084e-06 7.34239889397611e-05 7.64933187320557e-06 -1.02830381327501e-06 -1.12653482020543e-05 -1.22438887538648e-06 3.33298990514948e-07 7.64933187320557e-06 3.89653540594097e-05 -8.00000572663015e-06 3.0689753140272e-05 6.85904210208672e-06 3.1012355758716e-06 -1.02830381327501e-06 -8.00000572663015e-06 8.06838275883775e-05 2782 2790 0 0 7 2783 2804 0 0 10 0 0 0 0 0 0 0 0 88 0 16 20 0 0 2588 +10 42 0.999938176539313 3.85169414386791e-05 -0.0111194251505489 -0.00832182779222286 0.000106247877855949 0.999915253898405 0.0130182077366967 0.00236653813643643 0.0111189842441605 -0.0130185843213677 0.999853431584673 -0.0268492947488245 9.267704641559e-05 1.86874064837464e-05 3.03374216951758e-06 2.30057062191533e-05 -2.59185457972122e-05 5.39486715389745e-05 1.86874064837464e-05 6.00383234272841e-05 -7.48180364859254e-07 1.67230271884148e-05 -9.26557611890406e-06 3.13228625792866e-05 3.03374216951758e-06 -7.48180364859254e-07 1.62745626542801e-05 -3.84596178208792e-07 2.89990253239823e-07 -2.925347181823e-06 2.30057062191533e-05 1.67230271884148e-05 -3.84596178208792e-07 7.15831175609665e-05 9.69855459232269e-08 2.86738036251066e-05 -2.59185457972122e-05 -9.26557611890406e-06 2.89990253239823e-07 9.69855459232269e-08 4.4047882330335e-05 -2.09147797098948e-05 5.39486715389745e-05 3.13228625792866e-05 -2.925347181823e-06 2.86738036251066e-05 -2.09147797098948e-05 0.000145939045332502 2832 2839 0 0 8 2834 2855 0 0 11 0 0 0 0 0 0 0 0 56 0 15 20 0 0 2525 +10 37 0.999999035564139 0.001061489775826 -0.000895606078512049 -0.00611558541685204 -0.0010422291160941 0.999773886824539 0.0212388554828828 0.0112864950564206 0.000917948398123001 -0.0212379015726374 0.999774028922301 -0.041060635856459 0.000101330743146414 2.37909280332267e-05 1.33243298024588e-05 1.78650494625102e-06 -3.40787771072188e-05 7.46671675766287e-05 2.37909280332267e-05 5.8340563507589e-05 1.80541276154809e-06 6.20566074898912e-06 -8.23431091862365e-06 1.55171975965624e-05 1.33243298024588e-05 1.80541276154809e-06 2.24110235844693e-05 -2.91012117924677e-06 -4.00572922277935e-06 1.07390117021962e-05 1.78650494625102e-06 6.20566074898912e-06 -2.91012117924677e-06 7.66183610963695e-05 1.12618260098204e-05 1.02591584352903e-05 -3.40787771072188e-05 -8.23431091862365e-06 -4.00572922277935e-06 1.12618260098204e-05 5.48285573793683e-05 -3.96501228486559e-05 7.46671675766287e-05 1.55171975965624e-05 1.07390117021962e-05 1.02591584352903e-05 -3.96501228486559e-05 0.000135493854601876 2805 2824 0 0 6 2807 2827 0 0 9 0 0 0 0 0 0 0 0 69 0 14 16 0 0 2662 +10 39 0.999944288816366 -0.000397192704786204 -0.0105480567636004 -0.014892459764478 0.000542997160557843 0.999904301911247 0.0138236092777773 0.00211519957763065 0.0105415566979691 -0.0138285667130144 0.999848811733578 -0.0245464128756271 5.56102416444462e-05 7.85582727756433e-06 5.55318831235372e-06 4.3501852429846e-06 -1.25776393077526e-05 2.27921679236419e-05 7.85582727756433e-06 5.4026640204221e-05 -5.47245419363475e-07 1.08616254023639e-05 1.6084319252013e-06 1.22176418517069e-05 5.55318831235372e-06 -5.47245419363475e-07 1.53760992978834e-05 -1.24847629225247e-06 9.11433074434626e-07 2.50700635967304e-06 4.3501852429846e-06 1.08616254023639e-05 -1.24847629225247e-06 6.5373250545018e-05 1.44705771011403e-05 4.95104435832741e-06 -1.25776393077526e-05 1.6084319252013e-06 9.11433074434626e-07 1.44705771011403e-05 4.20963310419163e-05 -6.40946525539739e-06 2.27921679236419e-05 1.22176418517069e-05 2.50700635967304e-06 4.95104435832741e-06 -6.40946525539739e-06 7.5403256011587e-05 2860 2884 0 0 4 2861 2886 0 0 6 0 0 0 0 0 0 0 0 68 0 16 18 0 0 2663 +11 14 0.999998026149745 -0.000325516021126905 -0.00196003467695568 0.00149577362720566 0.000321611149607402 0.999997963787188 -0.00199223185067581 -0.00277489244663783 0.00196067918929316 0.00199159754930274 0.999996094630533 -0.00228545086691406 3.07906478158228e-05 -6.88017705154679e-06 1.96593752195894e-06 1.18546189082951e-05 -1.33728766572737e-06 2.18055548209985e-06 -6.88017705154679e-06 6.66588070078e-05 -3.49682153619206e-06 1.16333176548721e-05 -3.37492746573181e-06 -1.42605918694738e-05 1.96593752195894e-06 -3.49682153619206e-06 1.44191225479958e-05 5.45365224595106e-07 2.37791556055344e-06 2.45091676250505e-06 1.18546189082951e-05 1.16333176548721e-05 5.45365224595106e-07 4.58962979296271e-05 1.75924995950326e-06 -6.76543902956163e-06 -1.33728766572737e-06 -3.37492746573181e-06 2.37791556055344e-06 1.75924995950326e-06 2.5988862200241e-05 5.46410709150293e-06 2.18055548209985e-06 -1.42605918694738e-05 2.45091676250505e-06 -6.76543902956163e-06 5.46410709150293e-06 3.92517085708902e-05 2768 2770 0 0 10 2768 2782 0 0 13 0 0 0 0 0 0 0 0 58 0 11 19 0 0 2838 +10 38 0.999987096362067 -0.000634406631687795 -0.00504030133901556 -0.0108174282426947 0.000695458625917775 0.9999263050776 0.0121202620086001 0.000759674500913882 0.00503224071980346 -0.0121236109341709 0.999913843594164 -0.0306955751756059 7.18938955402555e-05 4.78225626493023e-06 1.002365714095e-05 -5.79105485225222e-06 -1.59368455411059e-05 3.85621140967459e-05 4.78225626493023e-06 2.88322920950047e-05 -2.79363345844155e-06 1.60996775728742e-06 -1.51270734343855e-06 1.51984546345346e-05 1.002365714095e-05 -2.79363345844155e-06 1.71736229532227e-05 -6.63771545340022e-07 -1.5089882293504e-06 4.03830440423093e-06 -5.79105485225222e-06 1.60996775728742e-06 -6.63771545340022e-07 5.51575932943614e-05 6.10972621795684e-06 -3.1503283244628e-06 -1.59368455411059e-05 -1.51270734343855e-06 -1.5089882293504e-06 6.10972621795684e-06 4.00346441446234e-05 -1.41119436753703e-05 3.85621140967459e-05 1.51984546345346e-05 4.03830440423093e-06 -3.1503283244628e-06 -1.41119436753703e-05 8.55939345226543e-05 2898 2905 0 0 9 2898 2917 0 0 9 0 0 0 0 0 0 0 0 74 0 15 19 0 0 2562 +11 49 0.999994830357748 -0.00035058886907609 -0.00319630180412419 -0.0104287074420734 0.000407622119456159 0.999840407994459 0.0178603579382315 0.00882447939027601 0.0031895300572181 -0.0178615684898863 0.999835382085019 -0.028156910830129 5.6778539210131e-05 -7.66662512578734e-07 2.28703821653928e-06 1.23072441509335e-05 -8.01443730842611e-06 3.03278081228706e-05 -7.66662512578734e-07 2.56564023708632e-05 -7.29670151658011e-06 4.77466995172462e-06 -9.08360072008736e-07 1.57135666537203e-05 2.28703821653928e-06 -7.29670151658011e-06 2.13496597508536e-05 -1.05699198481042e-05 -3.74296193595775e-06 -1.54551828945312e-06 1.23072441509335e-05 4.77466995172462e-06 -1.05699198481042e-05 7.39972628767943e-05 7.18193283571882e-06 8.08984611929086e-06 -8.01443730842611e-06 -9.08360072008736e-07 -3.74296193595775e-06 7.18193283571882e-06 2.93445278906648e-05 -9.3939310069298e-06 3.03278081228706e-05 1.57135666537203e-05 -1.54551828945312e-06 8.08984611929086e-06 -9.3939310069298e-06 7.3576728259647e-05 2881 2898 0 0 7 2882 2901 0 0 10 0 0 0 0 0 0 0 0 55 0 13 16 0 0 2640 +11 15 0.999996864253962 -0.000230464098092625 0.00249366568396293 0.0025631968071539 0.000237256181103773 0.999996262354968 -0.00272378148870986 -0.00209212566103654 -0.00249302862968158 0.00272436458521998 0.999993181299682 -0.00479990178038222 2.89590601665259e-05 -4.10712746881966e-06 1.35601425061472e-06 7.24329785080159e-06 1.15378736773032e-06 2.39003990286979e-06 -4.10712746881966e-06 2.46484102560938e-05 -4.03105070501821e-06 2.57134410321404e-06 3.88401142753185e-07 -6.95559438384004e-06 1.35601425061472e-06 -4.03105070501821e-06 1.30598316977933e-05 -2.61926353429473e-06 1.63821226395053e-06 -1.779979370476e-07 7.24329785080159e-06 2.57134410321404e-06 -2.61926353429473e-06 4.26924279623411e-05 5.92960122116129e-06 3.7285602217082e-06 1.15378736773032e-06 3.88401142753185e-07 1.63821226395053e-06 5.92960122116129e-06 2.01367960688927e-05 -4.04031333010453e-07 2.39003990286979e-06 -6.95559438384004e-06 -1.779979370476e-07 3.7285602217082e-06 -4.04031333010453e-07 2.73933949786533e-05 2927 2929 0 0 12 2929 2947 0 0 15 0 0 0 0 0 0 0 0 72 0 9 12 0 0 2704 +11 50 0.999996022731575 0.0012313507501666 -0.00253737982206843 -0.00256540329676812 -0.00119809635081451 0.999913919611831 0.0130659072260206 0.00289827703031397 0.00255325011809278 -0.0130628152338949 0.999911417962611 -0.0204767737274951 6.10694379593192e-05 -5.65709401469318e-07 2.30201483125005e-06 -5.4515349188661e-07 -1.07726996903996e-05 2.81161474865652e-05 -5.65709401469318e-07 6.55678750150566e-05 -9.07517181313764e-06 2.37502884639909e-05 3.61719560128347e-07 6.35111435315402e-06 2.30201483125005e-06 -9.07517181313764e-06 2.59116280769006e-05 -1.09107885367584e-05 -6.37061063532705e-06 2.76089424607477e-06 -5.4515349188661e-07 2.37502884639909e-05 -1.09107885367584e-05 0.000106970263106279 1.06776786329763e-05 2.89778789215366e-06 -1.07726996903996e-05 3.61719560128347e-07 -6.37061063532705e-06 1.06776786329763e-05 3.71106014968883e-05 -7.9537907734824e-06 2.81161474865652e-05 6.35111435315402e-06 2.76089424607477e-06 2.89778789215366e-06 -7.9537907734824e-06 7.01091028299912e-05 2720 2722 0 0 9 2720 2736 0 0 11 0 0 0 0 0 0 0 0 59 0 14 17 0 0 2766 +11 43 0.999952925102631 -0.000449513280042382 -0.00969254953580633 -0.0109548263075242 0.000566122053338367 0.999927460089179 0.0120313783675671 0.00185557913271269 0.00968643817477394 -0.0120362991577105 0.999880643086 -0.0261106148670169 6.54650595645681e-05 7.41226436423891e-06 3.91414848885721e-06 1.19169868853876e-05 -1.19726071361582e-05 4.11093195359263e-05 7.41226436423891e-06 4.36485151537795e-05 -3.69964795520332e-06 6.82841824941548e-06 -7.42566097582483e-06 3.58023315941059e-06 3.91414848885721e-06 -3.69964795520332e-06 1.66575583523731e-05 -2.89837831455306e-06 1.25468195591375e-06 1.48277388646806e-06 1.19169868853876e-05 6.82841824941548e-06 -2.89837831455306e-06 7.7213330002541e-05 5.11610168922947e-06 2.03301423064604e-05 -1.19726071361582e-05 -7.42566097582483e-06 1.25468195591375e-06 5.11610168922947e-06 3.8480796507367e-05 -9.76337979875826e-06 4.11093195359263e-05 3.58023315941059e-06 1.48277388646806e-06 2.03301423064604e-05 -9.76337979875826e-06 8.35419495052938e-05 3012 3013 0 0 3 3015 3025 0 0 6 0 0 0 0 0 0 0 0 18 0 17 24 0 0 2694 +11 13 0.99998714765166 0.000659960314063628 -0.00502682642247748 -0.00262276596041465 -0.000655395036441583 0.999999371382274 0.000909776017758097 -0.00123696529592382 0.00502742367859169 -0.00090646976791346 0.999986951576727 -0.000346907734873622 2.85807560957009e-05 -2.48703881244133e-06 6.41484537768773e-06 1.30035119618726e-06 -5.17904218189942e-06 3.81541762741329e-06 -2.48703881244133e-06 4.01189825991235e-05 -8.66179942817213e-06 1.02176893755312e-05 -1.19888989282334e-06 -1.29666572976734e-05 6.41484537768773e-06 -8.66179942817213e-06 1.64717578269538e-05 -1.92523940297159e-06 4.10879397048332e-06 5.66521543533614e-06 1.30035119618726e-06 1.02176893755312e-05 -1.92523940297159e-06 4.7461329407856e-05 6.76380735581424e-06 -8.16567335914045e-06 -5.17904218189942e-06 -1.19888989282334e-06 4.10879397048332e-06 6.76380735581424e-06 2.72511868069376e-05 -7.39171986469748e-07 3.81541762741329e-06 -1.29666572976734e-05 5.66521543533614e-06 -8.16567335914045e-06 -7.39171986469748e-07 3.63167085836996e-05 2973 2978 0 0 13 2973 2980 0 0 15 0 0 0 0 0 0 0 0 58 0 12 20 0 0 2869 +11 42 0.999955281149719 7.12186366878471e-05 -0.00945677686596443 -0.00701853836009928 1.74231699965782e-05 0.999956072785208 0.00937295025147073 -0.00206912460273375 0.00945702898483446 -0.0093726958709427 0.999911354658447 -0.0289110716735738 6.61264096752954e-05 1.39139434331785e-05 3.74099353129329e-06 2.55865160081099e-05 -1.52237146401762e-05 2.95686148588765e-05 1.39139434331785e-05 9.51769232015206e-05 -2.37495703793703e-06 3.67789798230634e-05 -8.02736671219112e-06 -1.03995430712331e-05 3.74099353129329e-06 -2.37495703793703e-06 1.61161461386152e-05 -2.12541354968297e-06 2.26637514986327e-06 5.97250758183504e-07 2.55865160081099e-05 3.67789798230634e-05 -2.12541354968297e-06 8.98794928423256e-05 1.20502206203697e-06 -6.79533859034584e-06 -1.52237146401762e-05 -8.02736671219112e-06 2.26637514986327e-06 1.20502206203697e-06 4.06886812872385e-05 1.32321788019362e-07 2.95686148588765e-05 -1.03995430712331e-05 5.97250758183504e-07 -6.79533859034584e-06 1.32321788019362e-07 9.5332492333508e-05 2894 2896 0 0 7 2895 2905 0 0 8 0 0 0 0 0 0 0 0 44 0 16 23 0 0 2646 +11 47 0.999947510969228 -0.000165039414883522 -0.0102444164517898 -0.0183650326683861 0.000315211235173489 0.999892501236568 0.0146590113158203 0.00491033218345549 0.0102408958750388 -0.0146614710336876 0.999840069870579 -0.0298068166272754 9.86854610079572e-05 -4.17905651366788e-06 -3.80941283942496e-06 7.69598530543178e-06 -2.86608277175182e-05 5.27152087328853e-05 -4.17905651366788e-06 6.19157800060953e-05 -1.47396484291617e-06 2.15312826626703e-05 -1.52272542447724e-06 1.9433444969864e-05 -3.80941283942496e-06 -1.47396484291617e-06 1.9304153772588e-05 -2.76889268835038e-07 3.33715725916092e-06 2.07628281706923e-06 7.69598530543178e-06 2.15312826626703e-05 -2.76889268835038e-07 7.73655505849344e-05 -3.29795940593747e-06 4.33955588240265e-06 -2.86608277175182e-05 -1.52272542447724e-06 3.33715725916092e-06 -3.29795940593747e-06 4.49643803546241e-05 -1.33985459306891e-05 5.27152087328853e-05 1.9433444969864e-05 2.07628281706923e-06 4.33955588240265e-06 -1.33985459306891e-05 9.19179479439689e-05 2761 2765 0 0 1 2765 2773 0 0 2 0 0 0 0 0 0 0 0 54 0 23 31 0 0 2568 +11 44 0.999998510197076 0.000318665501561386 -0.0016964833998432 -0.0238113722060452 -0.000279226134855648 0.999730864916358 0.0231974086129407 0.00880113743075659 0.00170341903049205 -0.023196900350871 0.999729464494129 -0.0360731788401642 6.01317577122881e-05 3.57094706404819e-06 5.39874373147176e-06 3.59145369667555e-06 -9.62098088834345e-06 3.04005313080554e-05 3.57094706404819e-06 4.60376417985322e-05 -3.19141114559932e-06 1.15469503449243e-05 3.73280843748393e-07 5.0360468713689e-06 5.39874373147176e-06 -3.19141114559932e-06 1.96823488565134e-05 -6.34718914298985e-06 -1.97980042347685e-06 4.94018663600844e-07 3.59145369667555e-06 1.15469503449243e-05 -6.34718914298985e-06 0.000108034630237809 8.65444647627325e-06 -5.59054251945832e-06 -9.62098088834345e-06 3.73280843748393e-07 -1.97980042347685e-06 8.65444647627325e-06 3.58682919557684e-05 -1.53949692662977e-06 3.04005313080554e-05 5.0360468713689e-06 4.94018663600844e-07 -5.59054251945832e-06 -1.53949692662977e-06 6.7049677412013e-05 2554 2555 0 0 1 2558 2568 0 0 3 0 0 0 0 0 0 0 0 27 0 27 30 0 0 2366 +11 48 0.999979195598298 -0.000845403871688485 -0.00639481531198399 -0.0196320115064191 0.000918431963391669 0.999934304054973 0.0114255878109627 0.00235182100302442 0.00638473596237709 -0.0114312233112267 0.999914277465974 -0.0292170364026076 6.01089765576066e-05 -1.16786494773131e-05 3.06161344575803e-06 1.83411751321957e-06 -7.29320688053212e-06 2.31294197906683e-05 -1.16786494773131e-05 5.98047341802584e-05 -4.93006666838171e-07 1.28792075908123e-05 2.13897956717546e-06 8.46927691699294e-06 3.06161344575803e-06 -4.93006666838171e-07 1.84595787226629e-05 -3.02774165936739e-06 3.29301798983429e-06 -1.97815080520124e-07 1.83411751321957e-06 1.28792075908123e-05 -3.02774165936739e-06 9.57282783965114e-05 1.05683905523504e-05 4.85169293097363e-07 -7.29320688053212e-06 2.13897956717546e-06 3.29301798983429e-06 1.05683905523504e-05 3.40496380088145e-05 -3.40003901190069e-06 2.31294197906683e-05 8.46927691699294e-06 -1.97815080520124e-07 4.85169293097363e-07 -3.40003901190069e-06 6.85236754835476e-05 3010 3010 0 0 2 3015 3026 0 0 3 0 0 0 0 0 0 0 0 40 0 20 24 0 0 2654 +11 51 0.999996715292473 -0.000546237587131354 -0.00250420222068947 -0.00533825274506784 0.000590930705308709 0.999839940600645 0.0178813864283663 0.0047928780758305 0.00249403391420897 -0.0178828075032262 0.999836979207429 -0.025245779934989 6.50858743586341e-05 -3.3903420547597e-06 8.64892291109072e-06 8.41995148031421e-06 -1.4957810146938e-05 3.80313835730378e-05 -3.3903420547597e-06 4.72956917685211e-05 -7.78767979038352e-06 1.84011395038146e-05 1.86471918505938e-06 1.86664527760826e-06 8.64892291109072e-06 -7.78767979038352e-06 2.06303879779417e-05 -5.18178908100874e-06 -2.41647724285595e-06 3.16863607135004e-06 8.41995148031421e-06 1.84011395038146e-05 -5.18178908100874e-06 8.84466026943476e-05 3.98485752799817e-07 2.48330490699532e-06 -1.4957810146938e-05 1.86471918505938e-06 -2.41647724285595e-06 3.98485752799817e-07 4.41798460104864e-05 -1.49594003384258e-05 3.80313835730378e-05 1.86664527760826e-06 3.16863607135004e-06 2.48330490699532e-06 -1.49594003384258e-05 8.49186988132875e-05 2669 2674 0 0 7 2670 2683 0 0 8 0 0 0 0 0 0 0 0 64 0 13 18 0 0 2787 +11 38 0.999934283849689 -0.000629051560328638 -0.0114469330452885 -0.0136666133940501 0.000762288081883996 0.999931975647695 0.0116388570820708 -0.00146656653663753 0.0114388329338743 -0.0116468180818239 0.999866743486191 -0.0308171302806069 5.94774580605224e-05 -6.30393734423297e-06 2.54096571668522e-06 6.36565178081291e-06 -8.03692462439018e-06 1.99196403126747e-05 -6.30393734423297e-06 4.49920411679303e-05 -6.13130319527756e-06 8.93962079047404e-06 -5.47677424586883e-07 1.17956597114612e-05 2.54096571668522e-06 -6.13130319527756e-06 1.50690478789593e-05 -3.98304362122814e-06 -4.02167464701977e-07 -5.77456637356365e-07 6.36565178081291e-06 8.93962079047404e-06 -3.98304362122814e-06 5.94228853165699e-05 5.02007151041866e-06 5.46441804849506e-06 -8.03692462439018e-06 -5.47677424586883e-07 -4.02167464701977e-07 5.02007151041866e-06 3.51062599533358e-05 -1.03795269153347e-06 1.99196403126747e-05 1.17956597114612e-05 -5.77456637356365e-07 5.46441804849506e-06 -1.03795269153347e-06 7.74398300946525e-05 3004 3005 0 0 5 3007 3014 0 0 7 0 0 0 0 0 0 0 0 70 0 20 27 0 0 2635 +11 46 0.999986367092969 -6.47940797631098e-05 -0.00522124792873179 -0.0264311730844144 0.000125442694114452 0.999932521323087 0.011616241413815 0.00596641254734792 0.00522014294215701 -0.0116167380180825 0.999918897463931 -0.0243553667427355 8.97880627996885e-05 -1.27343686962841e-05 3.47710448898154e-06 7.72425626211854e-06 -2.26858163621737e-05 5.84003739543698e-05 -1.27343686962841e-05 4.3433547007513e-05 -5.5078380530127e-06 7.23528903442587e-06 3.87504721618897e-06 5.48850586854357e-06 3.47710448898154e-06 -5.5078380530127e-06 1.90782056366409e-05 -8.52796655817039e-07 2.36720635214486e-06 1.18999690720251e-06 7.72425626211854e-06 7.23528903442587e-06 -8.52796655817039e-07 7.90104086738054e-05 -6.95028231801695e-06 3.43377957818998e-06 -2.26858163621737e-05 3.87504721618897e-06 2.36720635214486e-06 -6.95028231801695e-06 4.12034533139408e-05 -9.34988104247752e-06 5.84003739543698e-05 5.48850586854357e-06 1.18999690720251e-06 3.43377957818998e-06 -9.34988104247752e-06 0.00010236903858199 3003 3008 0 0 1 3009 3015 0 0 1 0 0 0 0 0 0 0 0 47 0 29 36 0 0 2610 +11 45 0.999999792357334 -0.0005784678478093 0.000284007461956052 -0.00290893985712227 0.000576004969048176 0.999962881802908 0.00859669905829129 0.00479673665438108 -0.000288969834113617 -0.00859653368354044 0.999963007368304 -0.0199054058913459 4.04814388964268e-05 -4.13635565049325e-06 3.99435354213711e-06 7.84308249553158e-07 -5.01635745598447e-06 3.00783527778837e-05 -4.13635565049325e-06 5.49223259501609e-05 -3.28384739552742e-06 1.02875246830543e-05 4.26630297114265e-06 6.23721465748305e-06 3.99435354213711e-06 -3.28384739552742e-06 2.26722151424194e-05 -7.57225681041757e-06 -4.56849554911032e-06 7.19311341218093e-06 7.84308249553158e-07 1.02875246830543e-05 -7.57225681041757e-06 7.25070561090666e-05 1.56873517886447e-05 1.52895508637131e-06 -5.01635745598447e-06 4.26630297114265e-06 -4.56849554911032e-06 1.56873517886447e-05 4.47252455906006e-05 -1.36067762333685e-05 3.00783527778837e-05 6.23721465748305e-06 7.19311341218093e-06 1.52895508637131e-06 -1.36067762333685e-05 9.41315116032927e-05 2755 2773 0 0 12 2757 2776 0 0 15 0 0 0 0 0 0 0 0 28 0 12 14 0 0 2537 +11 39 0.99996618686143 -0.000872767657476951 -0.00817700497912682 -0.0155784222523577 0.000922854769166656 0.999980824795979 0.00612359203635422 -0.00298510837605827 0.00817150371031116 -0.00613093116653064 0.999947817743578 -0.0254503256322758 5.86622257054762e-05 1.64523134381688e-06 5.45802120957745e-06 -2.65557504771796e-06 -1.07456400239869e-05 2.26884973120238e-05 1.64523134381688e-06 6.64794223627785e-05 -2.47650331117453e-08 4.22765353604228e-06 -5.5045416425677e-06 -2.5177999994223e-06 5.45802120957745e-06 -2.47650331117453e-08 1.75606513584169e-05 -3.64634903211473e-06 -1.63883679996651e-06 4.13722101188677e-06 -2.65557504771796e-06 4.22765353604228e-06 -3.64634903211473e-06 6.64168535853272e-05 9.5576442598125e-06 -1.06156133310365e-06 -1.07456400239869e-05 -5.5045416425677e-06 -1.63883679996651e-06 9.5576442598125e-06 4.1692857250753e-05 -5.15652977894235e-06 2.26884973120238e-05 -2.5177999994223e-06 4.13722101188677e-06 -1.06156133310365e-06 -5.15652977894235e-06 8.97399405102709e-05 2908 2932 0 0 4 2909 2933 0 0 5 0 0 0 0 0 0 0 0 57 0 17 19 0 0 2815 +12 16 0.999990854410478 -0.000245085755476694 0.00426978083442766 0.0049112045978728 0.000265612786971675 0.999988408098212 -0.00480761053446874 -0.00358407368330568 -0.00426855306268769 0.0048087006744234 0.999979327712616 -0.00409172216911496 4.33180784487443e-05 -1.3293990249924e-06 5.49061735500939e-06 1.60849643024564e-06 1.86155629252656e-06 8.16854478044771e-06 -1.3293990249924e-06 3.80708777188391e-05 -5.04766926555027e-06 5.23826257452725e-06 -1.65581613418361e-06 -5.32989933793236e-06 5.49061735500939e-06 -5.04766926555027e-06 1.46935118390641e-05 2.32224380270647e-08 3.66300104576761e-06 4.108688466752e-06 1.60849643024564e-06 5.23826257452725e-06 2.32224380270647e-08 4.41292815179729e-05 -1.04362967546718e-06 7.04004808603802e-06 1.86155629252656e-06 -1.65581613418361e-06 3.66300104576761e-06 -1.04362967546718e-06 2.48751487474691e-05 -5.2733548356835e-06 8.16854478044771e-06 -5.32989933793236e-06 4.108688466752e-06 7.04004808603802e-06 -5.2733548356835e-06 3.67441126437405e-05 3001 3003 0 0 12 3001 3016 0 0 15 0 0 0 0 0 0 0 0 81 0 8 10 0 0 2717 +11 40 0.999975909368959 0.00150200065081266 -0.00677677473199454 -0.00826437673184269 -0.00141948754677279 0.999925004732007 0.0121642906411077 0.00339960227691747 0.006794537278417 -0.0121543780483307 0.999903047978868 -0.0281591503051496 4.0987632251784e-05 -6.16791146162237e-07 3.57953553049953e-06 8.64415762779111e-06 -3.20017044508853e-06 3.36928663896876e-05 -6.16791146162237e-07 3.64302516748023e-05 -6.08792830796163e-06 4.3830283398833e-06 -3.76002156165344e-06 7.63953669580154e-06 3.57953553049953e-06 -6.08792830796163e-06 1.61776376601869e-05 -4.39463323575257e-06 1.97709466630801e-06 3.53521519683371e-06 8.64415762779111e-06 4.3830283398833e-06 -4.39463323575257e-06 7.37111347693819e-05 8.20391402315537e-06 9.56110465426425e-06 -3.20017044508853e-06 -3.76002156165344e-06 1.97709466630801e-06 8.20391402315537e-06 3.22500728762075e-05 -5.03822256313235e-06 3.36928663896876e-05 7.63953669580154e-06 3.53521519683371e-06 9.56110465426425e-06 -5.03822256313235e-06 8.63874944183864e-05 3077 3082 0 0 6 3078 3084 0 0 8 0 0 0 0 0 0 0 0 74 0 13 22 0 0 2849 +12 14 0.999999944078841 -0.000222195564567649 0.000249942884439977 0.002168537202016 0.000221691506486826 0.999997945480632 0.00201491622418738 -0.00144605583532704 -0.000250390076375469 -0.00201486070129634 0.999997938818458 0.000621901816678112 2.20444540884015e-05 -3.69864387796124e-06 1.93011828340967e-06 4.75339997320504e-07 5.52729453567999e-06 2.45740676721037e-06 -3.69864387796124e-06 1.71585155847289e-05 -6.64320410567534e-06 5.20622766741598e-07 1.01664531191467e-06 2.68359793172442e-06 1.93011828340967e-06 -6.64320410567534e-06 1.22963085055724e-05 -1.41856427507653e-06 1.40021690835827e-07 5.62848399090138e-07 4.75339997320504e-07 5.20622766741598e-07 -1.41856427507653e-06 3.39141455197752e-05 5.49526488486566e-06 9.75915008594576e-07 5.52729453567999e-06 1.01664531191467e-06 1.40021690835827e-07 5.49526488486566e-06 1.93944908037622e-05 -1.2926604364165e-06 2.45740676721037e-06 2.68359793172442e-06 5.62848399090138e-07 9.75915008594576e-07 -1.2926604364165e-06 2.75226659379677e-05 3010 3010 0 0 11 3015 3033 0 0 15 0 0 0 0 0 0 0 0 73 0 28 37 0 0 2599 +12 49 0.99998917673764 0.000867630000623947 -0.00457095457842723 -0.00996259177307598 -0.000792079745553704 0.99986348111921 0.0165042944063714 0.00547599943752801 0.00458465017779014 -0.0165004952155236 0.99985334656658 -0.0284808016720475 6.46179523993489e-05 -1.09500288071658e-05 2.24760829401274e-06 -1.8639285371536e-06 -9.11246882205693e-06 5.21317310928129e-05 -1.09500288071658e-05 7.58198973655211e-05 -8.21787131112999e-06 2.12522553991186e-05 5.65195802575837e-06 -8.4879728119914e-06 2.24760829401274e-06 -8.21787131112999e-06 1.83923583076149e-05 -4.70560326815359e-06 -3.0453854458176e-06 2.59515754526949e-06 -1.8639285371536e-06 2.12522553991186e-05 -4.70560326815359e-06 8.69172145236928e-05 1.9037528647056e-05 -1.92747369177337e-05 -9.11246882205693e-06 5.65195802575837e-06 -3.0453854458176e-06 1.9037528647056e-05 4.16527551186953e-05 -2.4581992919673e-05 5.21317310928129e-05 -8.4879728119914e-06 2.59515754526949e-06 -1.92747369177337e-05 -2.4581992919673e-05 0.000104356014981073 2931 2932 0 0 1 2938 2953 0 0 6 0 0 0 0 0 0 0 0 57 0 14 17 0 0 2843 +11 52 0.999846680156102 0.00368566441472568 -0.0171181791860072 -0.00916270271533795 -0.00337801461412871 0.999832885060517 0.0179663844117293 0.00582016344618669 0.0171815365462161 -0.0179058043490183 0.999692041066911 -0.0353912185526969 8.64334377709411e-05 4.55975577688603e-06 3.43522003037243e-07 2.03869603285327e-05 -1.66875753816064e-05 5.75644090686493e-05 4.55975577688603e-06 3.64397767082408e-05 -4.34117408496352e-06 4.89248333518687e-06 -3.72160788577884e-06 2.02101107218911e-05 3.43522003037243e-07 -4.34117408496352e-06 1.80140818053582e-05 -2.429508459033e-06 -4.98517656656517e-06 -1.72861580753512e-06 2.03869603285327e-05 4.89248333518687e-06 -2.429508459033e-06 7.23566827058553e-05 -1.76389073564937e-06 2.74144921886073e-05 -1.66875753816064e-05 -3.72160788577884e-06 -4.98517656656517e-06 -1.76389073564937e-06 3.42511908041996e-05 -1.81336238803589e-05 5.75644090686493e-05 2.02101107218911e-05 -1.72861580753512e-06 2.74144921886073e-05 -1.81336238803589e-05 0.000104780222955168 2809 2809 0 0 1 2814 2825 0 0 3 0 0 0 0 0 0 0 0 56 0 21 23 0 0 2571 +11 37 0.999970014422071 -0.000376203843791906 -0.00773490319212802 -0.0138767777966066 0.000494722021648504 0.999882422720287 0.0153263167502967 0.00713140957849253 0.00772822792397921 -0.0153296838087759 0.999852626784307 -0.0389624882110887 7.14846515450118e-05 2.59198314607434e-06 4.77251420000551e-06 3.68432926448467e-06 -1.70772061125858e-05 4.87296354617796e-05 2.59198314607434e-06 3.00832799342199e-05 -4.23149962214108e-06 6.87729241086682e-06 -3.7969506503326e-06 1.29301828683554e-05 4.77251420000551e-06 -4.23149962214108e-06 1.42841009504013e-05 -1.88599993367813e-06 1.13055226393769e-06 3.12517803171495e-06 3.68432926448467e-06 6.87729241086682e-06 -1.88599993367813e-06 6.47521422179625e-05 4.67734690248906e-06 1.9143284397479e-05 -1.70772061125858e-05 -3.7969506503326e-06 1.13055226393769e-06 4.67734690248906e-06 3.74203757968067e-05 -2.37447935849014e-05 4.87296354617796e-05 1.29301828683554e-05 3.12517803171495e-06 1.9143284397479e-05 -2.37447935849014e-05 0.000103237019211637 3022 3041 0 0 6 3023 3043 0 0 8 0 0 0 0 0 0 0 0 61 0 14 16 0 0 2616 +12 50 0.999994175590474 -0.00073572355127471 -0.00333279102016522 -0.00654477160101912 0.000786481800650446 0.999883336596138 0.0152543319667604 0.00345215932713482 0.00332117923413353 -0.0152568642987667 0.999878091499291 -0.0268321604856235 8.32986389099443e-05 -3.67896184902766e-06 -5.68797700477203e-07 1.49109479252045e-05 -3.83192113969984e-06 4.4513357711598e-05 -3.67896184902766e-06 3.13903154401946e-05 -3.43186279373259e-06 7.79123832621976e-06 -2.91104645237949e-06 1.97887266639444e-05 -5.68797700477203e-07 -3.43186279373259e-06 2.35444277893846e-05 -9.51899549302174e-06 -7.02259726239035e-06 -1.64389177768525e-06 1.49109479252045e-05 7.79123832621976e-06 -9.51899549302174e-06 9.10018601631987e-05 1.00742277549747e-05 2.83259634022153e-05 -3.83192113969984e-06 -2.91104645237949e-06 -7.02259726239035e-06 1.00742277549747e-05 3.95526997640136e-05 -1.28600018848104e-05 4.4513357711598e-05 1.97887266639444e-05 -1.64389177768525e-06 2.83259634022153e-05 -1.28600018848104e-05 0.000100528043812371 2971 2972 0 0 11 2971 2973 0 0 13 0 0 0 0 0 0 0 0 56 0 29 47 0 0 2733 +11 41 0.999987032501931 0.000217540912909058 -0.00508797640842253 -0.00391662028308066 -0.00016352635037036 0.999943655200394 0.0106141266059703 0.00140636172758385 0.00508999873420299 -0.0106131569490912 0.999930724006648 -0.0315548063550054 4.7374327928778e-05 -7.91714106279465e-06 1.97700097826114e-07 1.37939754756905e-06 -2.31278835418143e-06 3.20612157368485e-05 -7.91714106279465e-06 4.79712915792732e-05 -5.1716566895645e-06 1.41475135101224e-05 7.79830301582506e-07 -1.6617870989977e-07 1.97700097826114e-07 -5.1716566895645e-06 2.13303638791758e-05 -1.21138848611532e-05 -1.33402431306063e-06 1.36916416114515e-06 1.37939754756905e-06 1.41475135101224e-05 -1.21138848611532e-05 8.09614463931619e-05 8.94760955829961e-06 -5.08640200531815e-06 -2.31278835418143e-06 7.79830301582506e-07 -1.33402431306063e-06 8.94760955829961e-06 3.4187225630749e-05 -8.04598335808018e-06 3.20612157368485e-05 -1.6617870989977e-07 1.36916416114515e-06 -5.08640200531815e-06 -8.04598335808018e-06 7.88482741819162e-05 2701 2705 0 0 7 2704 2718 0 0 11 0 0 0 0 0 0 0 0 82 0 14 20 0 0 2819 +12 15 0.999981239111756 -2.18079801624328e-05 -0.00612543459097244 -0.000777543962231722 7.40472447010601e-06 0.999997235432611 -0.00235139794703411 -0.00319961447328814 0.00612546893603551 0.0023513084755646 0.999978474757715 0.00276371699327257 2.69824906713203e-05 -6.89607866794375e-06 4.44774400674561e-06 1.23925445093518e-06 2.46007901401209e-06 5.01019182392623e-07 -6.89607866794375e-06 3.6722384430085e-05 -4.0960689456582e-06 6.48476646187103e-06 -1.92953865360233e-06 -8.95155412473407e-06 4.44774400674561e-06 -4.0960689456582e-06 1.38422018342942e-05 -1.2458006931554e-06 3.33243743085334e-06 2.42078029934778e-06 1.23925445093518e-06 6.48476646187103e-06 -1.2458006931554e-06 4.32309222442583e-05 3.73011764668483e-06 -6.15653764928231e-06 2.46007901401209e-06 -1.92953865360233e-06 3.33243743085334e-06 3.73011764668483e-06 2.02091027702138e-05 -3.40953023531063e-06 5.01019182392623e-07 -8.95155412473407e-06 2.42078029934778e-06 -6.15653764928231e-06 -3.40953023531063e-06 3.3357015163894e-05 2837 2839 0 0 14 2837 2839 0 0 14 0 0 0 0 0 0 0 0 65 0 32 50 0 0 2894 +12 48 0.999980379843007 -0.000748717659362116 -0.00621927253800327 -0.0179656112852629 0.000871843967604475 0.999803214472231 0.01981848175545 0.00786900409939091 0.00620321022790249 -0.0198235151489718 0.999784250941175 -0.0351032398063779 4.95259497303328e-05 -2.58183396044599e-06 4.95977101748604e-06 -4.29165906839126e-06 -4.44555335832318e-06 3.30819923341094e-05 -2.58183396044599e-06 3.13681013296193e-05 -2.72113593185673e-06 -6.73547221511668e-06 2.86942489998733e-07 1.56101495545833e-05 4.95977101748604e-06 -2.72113593185673e-06 1.78928968901892e-05 -2.13852338738018e-06 3.53713008069898e-07 1.79958046900266e-06 -4.29165906839126e-06 -6.73547221511668e-06 -2.13852338738018e-06 8.58194271764801e-05 1.09858070130381e-05 -1.46243337183336e-05 -4.44555335832318e-06 2.86942489998733e-07 3.53713008069898e-07 1.09858070130381e-05 2.93142564838605e-05 -1.31062241511091e-05 3.30819923341094e-05 1.56101495545833e-05 1.79958046900266e-06 -1.46243337183336e-05 -1.31062241511091e-05 8.94351589885103e-05 3084 3083 0 0 4 3085 3084 0 0 5 0 0 0 0 0 0 0 0 40 0 35 53 0 0 2840 +12 52 0.999861375058251 0.0035104054059837 -0.0162759860072623 -0.00702983473396996 -0.00313801783988837 0.999734004305927 0.0228489272936961 0.00502738120572213 0.0163518656629603 -0.0227946855280284 0.999606431952605 -0.0379102406730222 7.85685114503386e-05 -5.93322469344418e-06 1.48318258860994e-06 1.36304877260712e-05 -1.3085242423571e-05 5.02662350856036e-05 -5.93322469344418e-06 9.9964912031781e-05 -1.92402315735827e-06 2.39750445035498e-05 -2.47557220106493e-06 1.07544379631357e-05 1.48318258860994e-06 -1.92402315735827e-06 1.97880231193133e-05 -2.28186689754703e-06 -3.594080964101e-06 -1.30803361744946e-06 1.36304877260712e-05 2.39750445035498e-05 -2.28186689754703e-06 8.50509781459532e-05 2.54167830355193e-07 2.10668432128504e-05 -1.3085242423571e-05 -2.47557220106493e-06 -3.594080964101e-06 2.54167830355193e-07 4.48480910733584e-05 -1.51267792947141e-05 5.02662350856036e-05 1.07544379631357e-05 -1.30803361744946e-06 2.10668432128504e-05 -1.51267792947141e-05 9.83463000257776e-05 2802 2801 0 0 4 2803 2802 0 0 5 0 0 0 0 0 0 0 0 59 0 39 55 0 0 2893 +12 51 0.999996566802522 -1.8804489681517e-05 -0.00262031096642343 -0.00232856083800361 5.56458997021291e-05 0.999901143685897 0.0140605746386188 0.00354078806787502 0.00261978753020877 -0.0140606721754507 0.999897711874205 -0.0277033510398203 6.14090376495611e-05 -4.98782130732942e-06 1.42360958683383e-06 -1.05513133763371e-06 -1.47602145003707e-06 3.01196359837525e-05 -4.98782130732942e-06 1.84957771853324e-05 -6.43855231512186e-06 2.52994497277131e-07 -3.32430458713517e-06 6.28589758658079e-06 1.42360958683383e-06 -6.43855231512186e-06 1.46127590899198e-05 -1.71476399795283e-06 -4.60404444201526e-07 1.77241597968717e-06 -1.05513133763371e-06 2.52994497277131e-07 -1.71476399795283e-06 4.87344920636574e-05 5.80703278080569e-06 2.2592790344882e-06 -1.47602145003707e-06 -3.32430458713517e-06 -4.60404444201526e-07 5.80703278080569e-06 2.88553326675995e-05 -1.06344506163363e-05 3.01196359837525e-05 6.28589758658079e-06 1.77241597968717e-06 2.2592790344882e-06 -1.06344506163363e-05 6.99665773035088e-05 2967 2967 0 0 11 2972 2990 0 0 14 0 0 0 0 0 0 0 0 72 0 29 36 0 0 2744 +12 40 0.999997988148749 -0.000241892564717942 -0.0019912775903898 -0.00899300819735862 0.000266860865075742 0.999921233466714 0.0125481332350523 0.00337032735342355 0.00198808544422654 -0.0125486393841351 0.999919286325588 -0.0294320377681165 4.95304582949816e-05 -3.98124806979332e-06 -1.94213708068369e-06 1.40938330485216e-05 -1.24266655296521e-06 1.6712105290592e-05 -3.98124806979332e-06 7.17677244672286e-05 -3.69087814280445e-06 9.10248218034912e-06 2.01128830185773e-06 8.24595807888131e-06 -1.94213708068369e-06 -3.69087814280445e-06 1.74553274313119e-05 -3.8543393127406e-06 7.96472913934268e-07 4.48992406410916e-07 1.40938330485216e-05 9.10248218034912e-06 -3.8543393127406e-06 7.3975681120518e-05 7.74879994056245e-06 -2.52869812722673e-06 -1.24266655296521e-06 2.01128830185773e-06 7.96472913934268e-07 7.74879994056245e-06 2.74672462317256e-05 -7.09648407852204e-06 1.6712105290592e-05 8.24595807888131e-06 4.48992406410916e-07 -2.52869812722673e-06 -7.09648407852204e-06 7.33945070828444e-05 2957 2957 0 0 4 2961 2961 0 0 8 0 0 0 0 0 0 0 0 74 0 17 31 0 0 2628 +12 38 0.999998837806493 -0.000769500422583491 -0.00131615149691038 -0.00905357630155288 0.000782157511527686 0.999953195285084 0.00964341582524194 -0.00407196852357336 0.00130866928226211 -0.0096444340555063 0.999952635016509 -0.0315060057005905 4.54651084753598e-05 1.97324377598076e-06 7.54154130726776e-06 -6.59862860310023e-06 -3.03917326820654e-06 2.00215391066178e-05 1.97324377598076e-06 4.70035737310112e-05 -1.77253598001735e-06 3.38350457460356e-06 1.96243566036233e-06 1.36531752527396e-06 7.54154130726776e-06 -1.77253598001735e-06 2.19924989868003e-05 -8.60830089233669e-06 -4.69065538066253e-06 3.77428994296453e-06 -6.59862860310023e-06 3.38350457460356e-06 -8.60830089233669e-06 7.61869727963497e-05 1.30590488003672e-05 -7.4697581822081e-06 -3.03917326820654e-06 1.96243566036233e-06 -4.69065538066253e-06 1.30590488003672e-05 3.49462142911406e-05 -5.74055654444526e-06 2.00215391066178e-05 1.36531752527396e-06 3.77428994296453e-06 -7.4697581822081e-06 -5.74055654444526e-06 6.40617418534949e-05 2771 2772 0 0 9 2779 2794 0 0 9 0 0 0 0 0 0 0 0 56 0 36 46 0 0 2833 +12 43 0.999997986998564 -0.000480445438028573 0.00194811986297511 0.000625780665517018 0.000462211506963284 0.99995618629444 0.00934943057094076 -0.000160193282141033 -0.00195252639989102 -0.00934851130710598 0.999954395448612 -0.0287850981574453 6.41817384686267e-05 6.26663592605104e-07 7.07213424103465e-06 2.58431423823382e-06 -7.97449323690984e-06 2.2381800504171e-05 6.26663592605104e-07 4.48186024466003e-05 -5.07114635372479e-06 5.06788638990456e-06 3.29876621966872e-06 2.91047513420725e-06 7.07213424103465e-06 -5.07114635372479e-06 2.03224167596792e-05 -5.92836850882441e-06 -2.87392084215667e-06 3.48880964747919e-08 2.58431423823382e-06 5.06788638990456e-06 -5.92836850882441e-06 7.79383279739628e-05 1.16334567390499e-05 5.62768369955644e-06 -7.97449323690984e-06 3.29876621966872e-06 -2.87392084215667e-06 1.16334567390499e-05 3.73443345932918e-05 -1.27594633598528e-05 2.2381800504171e-05 2.91047513420725e-06 3.48880964747919e-08 5.62768369955644e-06 -1.27594633598528e-05 6.72348975204418e-05 2797 2798 0 0 13 2802 2821 0 0 15 0 0 0 0 0 0 0 0 18 0 26 33 0 0 2664 +12 46 0.999979110747739 -0.000734284670751455 -0.00642175164454278 -0.0278027744301096 0.000841214088428431 0.999860786856517 0.0166643111325933 0.00921023202254142 0.00640862130409638 -0.0166693650955501 0.999840518202924 -0.0328694764496839 5.90018106179523e-05 6.37066453562971e-07 3.07872381336417e-06 -2.28748700294002e-06 -9.76151068993195e-07 2.84296065866965e-05 6.37066453562971e-07 3.50810206315663e-05 -5.02798150667795e-06 1.10475165286345e-05 6.35776450167902e-07 8.57932520266389e-06 3.07872381336417e-06 -5.02798150667795e-06 1.42189915933781e-05 -2.32488776738737e-06 5.69811175548263e-07 -1.05528744315873e-06 -2.28748700294002e-06 1.10475165286345e-05 -2.32488776738737e-06 7.75998158778335e-05 5.12975932095942e-07 -2.90612108737756e-06 -9.76151068993195e-07 6.35776450167902e-07 5.69811175548263e-07 5.12975932095942e-07 3.15234026188859e-05 -3.12547306546275e-06 2.84296065866965e-05 8.57932520266389e-06 -1.05528744315873e-06 -2.90612108737756e-06 -3.12547306546275e-06 7.5606334201531e-05 3042 3041 0 0 1 3053 3065 0 0 2 0 0 0 0 0 0 0 0 46 0 43 52 0 0 2573 +12 44 0.999931514209689 -0.000222442961214842 -0.011701171285294 -0.032343708320415 0.000482431787500002 0.999752968577386 0.0222209153788615 0.00555494940056859 0.0116933378420873 -0.0222250385788894 0.999684607018772 -0.0320341480564543 4.53543400423132e-05 6.33992840393555e-06 -3.92983464115037e-07 8.25670622258028e-06 1.2422813526665e-06 2.9201059044529e-05 6.33992840393555e-06 4.06430655580867e-05 -3.6994041564604e-06 6.34798698922594e-06 5.47003879313661e-06 1.11210881903607e-05 -3.92983464115037e-07 -3.6994041564604e-06 1.74826412869081e-05 -1.08373967027868e-06 -2.72321286677765e-06 -3.61208345222821e-06 8.25670622258028e-06 6.34798698922594e-06 -1.08373967027868e-06 7.82292891780626e-05 -4.56712961815641e-07 1.02434948174947e-06 1.2422813526665e-06 5.47003879313661e-06 -2.72321286677765e-06 -4.56712961815641e-07 3.39965283115203e-05 5.24061829006953e-07 2.9201059044529e-05 1.11210881903607e-05 -3.61208345222821e-06 1.02434948174947e-06 5.24061829006953e-07 6.45450508529979e-05 2574 2574 0 0 2 2580 2581 0 0 3 0 0 0 0 0 0 0 0 27 0 47 63 0 0 2547 +12 45 0.999961334352866 -0.000760814862878226 -0.00876076252270347 -0.00463756049187898 0.000782873574784047 0.999996531578217 0.00251474461979515 -0.00434636946065395 0.00875881888160081 -0.00252150595504104 0.999958461687043 -0.00756989990450306 0.000100117888043141 5.95537852501675e-06 1.98662692829859e-06 2.40483975299941e-05 -1.58274866798786e-05 7.82760560967568e-05 5.95537852501675e-06 5.89124418397902e-05 1.15586355132994e-06 2.01030671515338e-05 -9.57776820896932e-06 2.5405559972311e-05 1.98662692829859e-06 1.15586355132994e-06 2.06709222715659e-05 -7.52448107616518e-07 -8.75573499541592e-06 5.6992936594809e-06 2.40483975299941e-05 2.01030671515338e-05 -7.52448107616518e-07 0.000100163347476092 -9.27657723980698e-06 2.88217345900386e-05 -1.58274866798786e-05 -9.57776820896932e-06 -8.75573499541592e-06 -9.27657723980698e-06 5.21388829746576e-05 -3.46151664054228e-05 7.82760560967568e-05 2.5405559972311e-05 5.6992936594809e-06 2.88217345900386e-05 -3.46151664054228e-05 0.000142141606651444 2627 2628 0 0 7 2632 2650 0 0 10 0 0 0 0 0 0 0 0 28 0 14 16 0 0 2316 +12 47 0.999999876060247 1.11786428411015e-05 -0.000497749463656578 -0.0105581098055668 -3.39024271281053e-06 0.999877617598429 0.015644481908859 0.00547952584439182 0.000497863431957528 -0.0156444782823943 0.999877493711742 -0.0334988343799568 7.8572484174298e-05 -1.49996518827846e-05 -3.2872938163487e-06 -8.36339516551951e-07 -7.94540388135469e-06 2.84777876614253e-05 -1.49996518827846e-05 3.72907151861205e-05 -6.64296675708761e-07 3.06963174006712e-06 1.04063138296198e-06 -6.47850741492216e-07 -3.2872938163487e-06 -6.64296675708761e-07 1.86615788318397e-05 2.67117658612255e-06 5.24987455378196e-08 4.65102543544834e-08 -8.36339516551951e-07 3.06963174006712e-06 2.67117658612255e-06 7.03566339292919e-05 4.29430534013972e-06 2.21759718470935e-06 -7.94540388135469e-06 1.04063138296198e-06 5.24987455378196e-08 4.29430534013972e-06 3.16356940848317e-05 -1.03567588272797e-05 2.84777876614253e-05 -6.47850741492216e-07 4.65102543544834e-08 2.21759718470935e-06 -1.03567588272797e-05 6.36738522696821e-05 2980 2981 0 0 6 2989 3007 0 0 9 0 0 0 0 0 0 0 0 56 0 34 42 0 0 2686 +12 41 0.999996456329288 0.000439424733445413 -0.00262568748510283 -0.000179583504708661 -0.000398407703071002 0.999878208269441 0.0156015992511685 0.00341099262968744 0.00263222342667238 -0.0156004978701183 0.999874840100518 -0.0301279009738948 5.04229475681828e-05 -4.628504889615e-06 7.49125409889113e-06 -2.54504657930668e-06 6.71153593542165e-07 3.18604120440026e-05 -4.628504889615e-06 2.30396554094283e-05 -7.52004631119332e-06 4.03655886507934e-06 -1.46027259544609e-07 6.51970352313985e-06 7.49125409889113e-06 -7.52004631119332e-06 1.955136024716e-05 -4.01646389020704e-06 -1.11506197318543e-06 9.12608944072546e-07 -2.54504657930668e-06 4.03655886507934e-06 -4.01646389020704e-06 7.88319341490699e-05 1.09004676232949e-05 -1.8416641875721e-07 6.71153593542165e-07 -1.46027259544609e-07 -1.11506197318543e-06 1.09004676232949e-05 3.34709354532059e-05 -3.71644938144583e-06 3.18604120440026e-05 6.51970352313985e-06 9.12608944072546e-07 -1.8416641875721e-07 -3.71644938144583e-06 7.66440370331821e-05 2950 2951 0 0 12 2954 2973 0 0 15 0 0 0 0 0 0 0 0 91 0 29 36 0 0 2583 +13 15 0.999995165283137 0.000179805275550367 0.00310436473619482 0.00707129406423185 -0.000162687038951769 0.999984786647622 -0.00551362006654299 -0.00419330935377254 -0.00310530888637552 0.00551308836984432 0.999979981256298 -0.00383859158936366 4.22825638162154e-05 -1.39402226317006e-05 6.65052528486202e-06 9.8292377672812e-07 -2.9710836863817e-06 4.4504560116018e-06 -1.39402226317006e-05 4.77473260225679e-05 -4.00060394393985e-06 6.0091618729231e-06 1.97003983788293e-06 -1.53005328774316e-05 6.65052528486202e-06 -4.00060394393985e-06 1.74657167152581e-05 -2.64356561152323e-06 4.03708828234425e-06 2.5055278430358e-06 9.8292377672812e-07 6.0091618729231e-06 -2.64356561152323e-06 4.91122923033298e-05 4.62204255963775e-06 -1.2464598705508e-05 -2.9710836863817e-06 1.97003983788293e-06 4.03708828234425e-06 4.62204255963775e-06 2.61134505735004e-05 -3.25078561010954e-06 4.4504560116018e-06 -1.53005328774316e-05 2.5055278430358e-06 -1.2464598705508e-05 -3.25078561010954e-06 3.96963752041842e-05 2681 2683 0 0 14 2686 2702 0 0 16 0 0 0 0 0 0 0 0 72 0 29 33 0 0 2680 +12 42 0.999989302722454 8.56713990557222e-05 -0.00462461901912739 -0.00543597129202582 -2.94367451769974e-05 0.999926081732734 0.0121585444893567 0.00164533722589192 0.00462531881481961 -0.0121582782923002 0.999915387767799 -0.0281422103295205 4.33395328175065e-05 -2.59483245359815e-07 4.86185158845887e-06 5.88882370350579e-06 -1.93448041842966e-06 2.1627041614832e-05 -2.59483245359815e-07 4.06824080488976e-05 5.33489839130061e-08 1.16772755769732e-06 2.16868281017222e-06 2.17374471260725e-05 4.86185158845887e-06 5.33489839130061e-08 1.81452333062664e-05 -4.67458729965308e-06 6.91914848182757e-07 -1.33347376735731e-06 5.88882370350579e-06 1.16772755769732e-06 -4.67458729965308e-06 5.21656987128778e-05 1.15575763970825e-05 3.08980931166073e-06 -1.93448041842966e-06 2.16868281017222e-06 6.91914848182757e-07 1.15575763970825e-05 2.77569575572869e-05 -7.74976595407071e-06 2.1627041614832e-05 2.17374471260725e-05 -1.33347376735731e-06 3.08980931166073e-06 -7.74976595407071e-06 7.62426464754969e-05 2802 2803 0 0 8 2810 2828 0 0 11 0 0 0 0 0 0 0 0 65 0 33 41 0 0 2836 +13 50 0.999977431411323 -0.000540093610059477 -0.00669663847797242 -0.00872181574168582 0.000619718934162445 0.999929072147142 0.0118939742474298 -0.000332526706615608 0.00668973964029456 -0.0118978558508773 0.999906839865443 -0.0152989492019439 6.61705855122508e-05 -2.54469018972379e-06 5.23730932638935e-06 3.71902053882019e-06 -1.03699183054982e-05 2.59596717003802e-05 -2.54469018972379e-06 4.95916944000891e-05 -3.77125001418093e-06 5.9269084169024e-06 2.34320804754645e-06 3.41067398492045e-06 5.23730932638935e-06 -3.77125001418093e-06 1.90899405354423e-05 -1.85274681367132e-06 -1.50050499754396e-06 1.53363770557483e-06 3.71902053882019e-06 5.9269084169024e-06 -1.85274681367132e-06 7.13043260647884e-05 9.46842364431947e-06 8.28809379199955e-06 -1.03699183054982e-05 2.34320804754645e-06 -1.50050499754396e-06 9.46842364431947e-06 3.82118490281571e-05 -8.35355755450073e-06 2.59596717003802e-05 3.41067398492045e-06 1.53363770557483e-06 8.28809379199955e-06 -8.35355755450073e-06 7.04841309235186e-05 2961 2962 0 0 6 2968 2980 0 0 9 0 0 0 0 0 0 0 0 56 0 37 44 0 0 2758 +13 16 0.999999941837117 -0.000339608709812561 -3.14910693605722e-05 0.00395197664238104 0.000339581057208283 0.999999560407827 -0.000873995914375138 -0.00196823217401969 3.17878721422069e-05 0.00087398516977039 0.999999617569654 -0.000218850711240873 2.93300282002862e-05 -4.93185406157297e-06 2.48607175725295e-06 -3.82215418375623e-07 -4.55504511158036e-07 2.64926186726485e-07 -4.93185406157297e-06 2.05560826416766e-05 -3.34861113198675e-06 8.74116020460177e-07 -7.73697187783002e-07 1.89058476338631e-06 2.48607175725295e-06 -3.34861113198675e-06 1.32475273729473e-05 3.35324677919191e-07 -1.09162901900863e-06 2.22540227426938e-06 -3.82215418375623e-07 8.74116020460177e-07 3.35324677919191e-07 3.52705720264968e-05 2.59120343025065e-06 3.15172995418617e-06 -4.55504511158036e-07 -7.73697187783002e-07 -1.09162901900863e-06 2.59120343025065e-06 1.91919284374629e-05 -3.25646776272685e-07 2.64926186726485e-07 1.89058476338631e-06 2.22540227426938e-06 3.15172995418617e-06 -3.25646776272685e-07 2.31338843540355e-05 2759 2760 0 1 11 2761 2764 0 1 14 0 0 0 0 0 0 0 0 81 0 10 25 0 0 2788 +12 39 0.999994847393684 -0.0011095855725171 -0.00301230907096287 -0.0126193109314067 0.001139379305728 0.999950275048775 0.00990703006342554 -0.00168931397018213 0.00300116658641637 -0.00991041117901778 0.999946386937511 -0.0264880663953708 4.3707284575239e-05 -5.75075360642235e-06 5.67029965723441e-06 2.21149385476427e-06 -5.40606562725586e-06 1.23038763128085e-05 -5.75075360642235e-06 2.53811868801682e-05 2.36406251310797e-06 -2.61452805803266e-06 -1.02959522403516e-06 1.39763802993702e-05 5.67029965723441e-06 2.36406251310797e-06 1.97314794916596e-05 -4.70522254329038e-06 -3.58308022618288e-06 -5.06118610729044e-07 2.21149385476427e-06 -2.61452805803266e-06 -4.70522254329038e-06 5.88863124670516e-05 1.05271808283977e-05 4.40617902001799e-06 -5.40606562725586e-06 -1.02959522403516e-06 -3.58308022618288e-06 1.05271808283977e-05 3.99548736985011e-05 -6.5671296423765e-06 1.23038763128085e-05 1.39763802993702e-05 -5.06118610729044e-07 4.40617902001799e-06 -6.5671296423765e-06 6.09006607413249e-05 2850 2850 0 0 5 2856 2877 0 0 7 0 0 0 0 0 0 0 0 60 0 16 18 0 0 2699 +13 45 0.999993213396871 -0.000237495985230062 -0.00367651409041408 -0.00582252928055575 0.000249487923705429 0.999994649670972 0.00326165375314951 -0.00319599504358232 0.00367571979018244 -0.00326254886346683 0.999987922356534 -0.0141485985036486 4.19940817206888e-05 -1.26506389972294e-05 8.49285905115026e-06 -3.68065046918916e-06 -4.22133846754925e-06 2.53325571220987e-05 -1.26506389972294e-05 6.29551975341012e-05 -6.07452443398145e-06 2.71951973024907e-05 -3.30692174211659e-07 -1.45244209712965e-06 8.49285905115026e-06 -6.07452443398145e-06 2.32068577058668e-05 -1.2543151881942e-05 -5.75967183200782e-06 7.4794786044595e-06 -3.68065046918916e-06 2.71951973024907e-05 -1.2543151881942e-05 0.000113449626611247 8.77742936237599e-06 -7.67585492013316e-06 -4.22133846754925e-06 -3.30692174211659e-07 -5.75967183200782e-06 8.77742936237599e-06 4.42178304799363e-05 -1.39197312890367e-05 2.53325571220987e-05 -1.45244209712965e-06 7.4794786044595e-06 -7.67585492013316e-06 -1.39197312890367e-05 7.00384663721424e-05 2841 2841 0 1 6 2844 2848 0 1 7 0 0 0 0 0 0 0 0 27 0 20 37 0 0 2553 +13 48 0.999957322478928 -0.000409823951749333 -0.00922958639925852 -0.0211796641212641 0.000539167073997304 0.999901627893644 0.0140158422688984 0.002258355840539 0.00922293443753789 -0.0140202203965878 0.999859175534431 -0.0287849285265442 7.82677538875126e-05 -5.85213727228138e-06 4.2949107180969e-06 -3.00548156656182e-07 -1.43491477365218e-05 3.9667356254231e-05 -5.85213727228138e-06 5.08050456398992e-05 -8.91922171789891e-07 9.04405460540245e-06 -2.19828226003722e-06 7.43575173192534e-06 4.2949107180969e-06 -8.91922171789891e-07 2.19993249475825e-05 -5.73045976158538e-06 -6.89568749148463e-06 -1.41686588342903e-07 -3.00548156656182e-07 9.04405460540245e-06 -5.73045976158538e-06 0.00010074312970209 8.79104182664198e-06 -5.35234952387627e-08 -1.43491477365218e-05 -2.19828226003722e-06 -6.89568749148463e-06 8.79104182664198e-06 3.85495710038448e-05 -1.43218444407701e-05 3.9667356254231e-05 7.43575173192534e-06 -1.41686588342903e-07 -5.35234952387627e-08 -1.43218444407701e-05 7.43251488024669e-05 2753 2752 0 1 3 2759 2763 0 1 4 0 0 0 0 0 0 0 0 40 0 46 59 0 0 2631 +13 43 0.99999861880532 -0.0003676810844885 -0.00162086337261292 -0.00531121828784116 0.00037893019297877 0.999975808900199 0.00694536005558932 -0.00138269679418431 0.0016182704846279 -0.00694596465676554 0.999974567064396 -0.0206013455167742 3.91622313248608e-05 -3.44174365865384e-06 7.55508229345347e-06 -1.83440067421608e-06 -2.83794726181409e-06 2.16501211114659e-05 -3.44174365865384e-06 1.75689367461737e-05 -5.43642651333608e-06 -3.04642086992327e-06 -3.17582667807818e-06 7.22452851564822e-06 7.55508229345347e-06 -5.43642651333608e-06 1.53288272784231e-05 -4.86571402905093e-06 -2.44341595493128e-07 1.61715743032707e-06 -1.83440067421608e-06 -3.04642086992327e-06 -4.86571402905093e-06 5.21904506720653e-05 1.74357835918679e-05 -3.00446628830016e-06 -2.83794726181409e-06 -3.17582667807818e-06 -2.44341595493128e-07 1.74357835918679e-05 3.18043912798433e-05 -8.50640263214648e-06 2.16501211114659e-05 7.22452851564822e-06 1.61715743032707e-06 -3.00446628830016e-06 -8.50640263214648e-06 5.58368105735781e-05 3144 3145 0 0 5 3147 3148 0 0 8 0 0 0 0 0 0 0 0 18 0 24 48 0 0 2791 +13 49 0.999994365665458 -0.00120072079137489 0.00313478977261857 -0.00870772694884671 0.00114221520630858 0.999826373637594 0.0185988688667053 0.00654233215756657 -0.00315657753901775 -0.0185951834699092 0.999822111762868 -0.0284540774104122 7.14822967730778e-05 -1.0859189814705e-06 -7.77341398533787e-08 7.71442157977381e-06 -1.05882676647643e-05 3.97345199295789e-05 -1.0859189814705e-06 3.74659272729804e-05 -4.89212973983126e-06 6.39276745186726e-06 1.88655161049763e-06 3.12933668652863e-06 -7.77341398533787e-08 -4.89212973983126e-06 2.24855544971917e-05 -6.87122246333007e-06 -5.05249303156458e-06 -1.28906927433086e-06 7.71442157977381e-06 6.39276745186726e-06 -6.87122246333007e-06 7.99492092238844e-05 3.10667027392984e-06 5.7666599075084e-06 -1.05882676647643e-05 1.88655161049763e-06 -5.05249303156458e-06 3.10667027392984e-06 3.31613193345528e-05 -1.15454156127186e-05 3.97345199295789e-05 3.12933668652863e-06 -1.28906927433086e-06 5.7666599075084e-06 -1.15454156127186e-05 7.78987205151401e-05 2744 2744 0 0 2 2748 2757 0 0 6 0 0 0 0 0 0 0 0 63 0 16 28 0 0 2625 +13 42 0.999989026516544 -0.000794316902820118 -0.00461691532871318 -0.0069682990854045 0.000799975597043151 0.999998931020967 0.00122392645518656 -0.00512949048408578 0.00461593820785633 -0.00122760644404644 0.99998859298338 -0.0175460578518849 4.96976551820682e-05 5.97988950478653e-07 4.95077782711656e-06 2.52583203331769e-06 -8.01188475950641e-06 1.7396026377459e-05 5.97988950478653e-07 3.19529325278817e-05 1.24388934852184e-06 -6.55073862567639e-07 -2.25766324228566e-07 5.92505171845197e-06 4.95077782711656e-06 1.24388934852184e-06 1.36365466981101e-05 -2.01041137094498e-07 7.16177664051498e-07 1.14741504839151e-06 2.52583203331769e-06 -6.55073862567639e-07 -2.01041137094498e-07 4.35973985773574e-05 6.173555352e-06 2.62010184930162e-06 -8.01188475950641e-06 -2.25766324228566e-07 7.16177664051498e-07 6.173555352e-06 3.34523062157236e-05 -1.14482939074748e-05 1.7396026377459e-05 5.92505171845197e-06 1.14741504839151e-06 2.62010184930162e-06 -1.14482939074748e-05 7.78518709357743e-05 3060 3061 0 0 8 3061 3062 0 0 9 0 0 0 0 0 0 0 0 51 0 28 52 0 0 2640 +13 44 0.999976761653596 2.83261936711349e-05 -0.00681728321364582 -0.0304654120007066 0.000118460391172306 0.999768192008337 0.0215301698905471 0.00349503977191223 0.00681631278067756 -0.0215304771430372 0.999744955693235 -0.030338039188147 6.08864484806057e-05 -9.70510755292403e-06 4.95309551959486e-06 5.08743346541295e-06 -1.02672414715364e-05 3.27399086208487e-05 -9.70510755292403e-06 0.00013492765062228 -6.35740747651966e-06 6.99740144174635e-05 2.04682790973279e-05 -2.5925333263484e-05 4.95309551959486e-06 -6.35740747651966e-06 1.89718689051625e-05 -6.89136233743335e-06 3.53028098284474e-07 -1.39532205691089e-07 5.08743346541295e-06 6.99740144174635e-05 -6.89136233743335e-06 0.000156378046853553 1.1676188882402e-05 -1.6323062575999e-05 -1.02672414715364e-05 2.04682790973279e-05 3.53028098284474e-07 1.1676188882402e-05 4.11792242330064e-05 -4.86752023205937e-06 3.27399086208487e-05 -2.5925333263484e-05 -1.39532205691089e-07 -1.6323062575999e-05 -4.86752023205937e-06 9.18661325794654e-05 2668 2668 0 0 2 2674 2677 0 0 2 0 0 0 0 0 0 0 0 27 0 54 68 0 0 2336 +13 52 0.999945498482665 0.00293885731559046 -0.0100181426389358 -0.00411811943052029 -0.00272746740755402 0.999774715229167 0.0210494586623479 0.00613928600139032 0.0100777470595463 -0.0210209872773798 0.999728241627738 -0.0360854384980568 6.75176774244474e-05 -4.04572114692273e-06 1.35537896085126e-05 -1.60807011517175e-05 -1.73305847234808e-05 1.8442365880891e-05 -4.04572114692273e-06 3.94926565619012e-05 -6.36556862785822e-06 7.44912489060005e-06 1.96673896056327e-06 5.14649301823943e-06 1.35537896085126e-05 -6.36556862785822e-06 2.32151688876058e-05 -1.41196771021258e-05 -6.37291965053752e-06 -1.52760903685929e-07 -1.60807011517175e-05 7.44912489060005e-06 -1.41196771021258e-05 0.000102714166831334 2.3947643338564e-05 1.03499842387583e-05 -1.73305847234808e-05 1.96673896056327e-06 -6.37291965053752e-06 2.3947643338564e-05 4.2976464418151e-05 -7.1105742501144e-06 1.8442365880891e-05 5.14649301823943e-06 -1.52760903685929e-07 1.03499842387583e-05 -7.1105742501144e-06 6.82086868874415e-05 2846 2845 0 0 3 2852 2865 0 0 7 0 0 0 0 0 0 0 0 59 0 38 40 0 0 2610 +13 17 0.999999071873915 -9.07737661101568e-05 -0.00135941584224727 0.00517302347134442 8.6250020096675e-05 0.999994460462532 -0.00332740216725686 -0.00449397898512822 0.00135971035253837 0.0033272818293644 0.999993540170828 -0.000194269994448207 4.35475418918022e-05 -1.03689481386663e-05 1.11178706389584e-06 6.39239706034963e-06 -3.07078361062764e-06 4.79701954086579e-06 -1.03689481386663e-05 3.45261697328532e-05 -2.53001100785437e-06 6.16401457041344e-07 -1.36410114755379e-06 -1.08943819788772e-05 1.11178706389584e-06 -2.53001100785437e-06 1.3560479475844e-05 -1.99170679796031e-06 3.80171541515241e-06 6.37457818339667e-07 6.39239706034963e-06 6.16401457041344e-07 -1.99170679796031e-06 4.43030619733675e-05 -3.52177775491453e-06 1.77517526896574e-06 -3.07078361062764e-06 -1.36410114755379e-06 3.80171541515241e-06 -3.52177775491453e-06 2.45067591553862e-05 2.3446705722713e-06 4.79701954086579e-06 -1.08943819788772e-05 6.37457818339667e-07 1.77517526896574e-06 2.3446705722713e-06 4.27056714188166e-05 2813 2813 0 1 11 2814 2819 0 1 13 0 0 0 0 0 0 0 0 74 0 11 32 0 0 2772 +13 47 0.999989528915056 -0.000775199806515572 -0.00451011369086865 -0.0131909714001627 0.000837398962372082 0.99990434839609 0.0138055359029529 0.00355959171218217 0.00449898024249949 -0.0138091681085386 0.999894527464236 -0.0281174596924329 6.05050212023742e-05 -6.52987916178212e-06 3.08118310208528e-06 -3.94025791369867e-06 -4.76121096359159e-06 3.06878467634712e-05 -6.52987916178212e-06 3.01223973168013e-05 -6.82821595794868e-06 8.66251439299787e-06 7.0982992984991e-07 1.44727034157398e-05 3.08118310208528e-06 -6.82821595794868e-06 2.25700348029891e-05 -7.37399009800974e-06 -6.99994146789747e-06 -1.68594781562796e-06 -3.94025791369867e-06 8.66251439299787e-06 -7.37399009800974e-06 8.03344295855497e-05 1.28926255965365e-05 1.02076942309852e-05 -4.76121096359159e-06 7.0982992984991e-07 -6.99994146789747e-06 1.28926255965365e-05 3.69042953410322e-05 -5.32212341430711e-06 3.06878467634712e-05 1.44727034157398e-05 -1.68594781562796e-06 1.02076942309852e-05 -5.32212341430711e-06 6.72550320572229e-05 2775 2776 0 0 5 2776 2777 0 0 6 0 0 0 0 0 0 0 0 56 0 29 54 0 0 2557 +14 17 0.999976679471839 5.6371968039378e-05 -0.00682915329130715 -0.00154273771205675 -6.80256942425585e-05 0.999998542045857 -0.0017062469531382 -0.00252610001006531 0.0068290471502161 0.00170667172045181 0.999975225386439 0.00565052388770529 4.11181205417192e-05 6.5003977915397e-06 2.79156982052383e-06 5.21075651763368e-07 -2.99549565840791e-06 1.7311426094279e-06 6.5003977915397e-06 5.19901328145968e-05 -7.63991110653197e-07 8.76457848298778e-06 -1.45045118396854e-07 -5.73553908726572e-06 2.79156982052383e-06 -7.63991110653197e-07 1.52365373018669e-05 -1.25456384359354e-06 2.4320268780418e-06 -1.12263985810151e-06 5.21075651763368e-07 8.76457848298778e-06 -1.25456384359354e-06 4.30747053034828e-05 2.32914895521317e-06 -6.13709907259614e-06 -2.99549565840791e-06 -1.45045118396854e-07 2.4320268780418e-06 2.32914895521317e-06 2.43905663252385e-05 -4.44962834567835e-06 1.7311426094279e-06 -5.73553908726572e-06 -1.12263985810151e-06 -6.13709907259614e-06 -4.44962834567835e-06 4.10789580603535e-05 2614 2622 0 2 8 2616 2631 0 2 15 0 0 0 0 0 0 0 0 67 0 10 19 0 0 2653 +14 16 0.999992291845206 -1.82319141236893e-06 0.00392635286855774 0.00385801023030908 1.88548502369343e-05 0.999990591747655 -0.00433774834093356 -0.0018993088943716 -0.00392630801989363 0.0043377889356932 0.999982883699757 -0.000128000422730824 3.17999395115654e-05 -7.8634587518048e-06 2.23280923677933e-06 4.89807359718333e-07 -6.35139025149051e-07 1.26735867035065e-06 -7.8634587518048e-06 2.77844549961763e-05 -3.16817344475536e-06 5.7526787685372e-07 1.78809411807274e-06 -1.22088605401011e-05 2.23280923677933e-06 -3.16817344475536e-06 1.37989463886744e-05 -1.55637612046611e-07 4.2113339138929e-06 3.06342149738332e-06 4.89807359718333e-07 5.7526787685372e-07 -1.55637612046611e-07 3.5565560866319e-05 6.17465385421347e-06 4.50038488322652e-07 -6.35139025149051e-07 1.78809411807274e-06 4.2113339138929e-06 6.17465385421347e-06 2.4100475134824e-05 -2.26420344233011e-06 1.26735867035065e-06 -1.22088605401011e-05 3.06342149738332e-06 4.50038488322652e-07 -2.26420344233011e-06 3.19868788049208e-05 3007 3016 0 1 11 3009 3023 0 1 22 0 0 0 0 0 0 0 0 60 0 8 12 0 0 2649 +13 51 0.999978322956336 0.000588897791226181 -0.00655795828173108 -0.00333816827656178 -0.000462807295875606 0.999815324565246 0.0192120424187354 0.00203041864061433 0.00656806111727964 -0.0192085908875142 0.999793924070994 -0.0184648716412502 6.86909065714767e-05 -1.43869480850046e-05 9.06983049323986e-06 -6.44749857807472e-07 -1.2815099946328e-05 4.23810842220268e-05 -1.43869480850046e-05 5.60322077432075e-05 -1.02340420023271e-05 1.96668722689636e-05 5.86096711015125e-06 -7.3748731929817e-06 9.06983049323986e-06 -1.02340420023271e-05 2.29271339081668e-05 -1.56895071137921e-05 -3.02742419584485e-06 7.71061568291026e-06 -6.44749857807472e-07 1.96668722689636e-05 -1.56895071137921e-05 0.000100328789219279 7.92205436529085e-06 -6.26196919557184e-06 -1.2815099946328e-05 5.86096711015125e-06 -3.02742419584485e-06 7.92205436529085e-06 4.31242432530479e-05 -1.77345449133602e-05 4.23810842220268e-05 -7.3748731929817e-06 7.71061568291026e-06 -6.26196919557184e-06 -1.77345449133602e-05 8.60911264958754e-05 2647 2648 0 1 9 2647 2648 0 1 9 0 0 0 0 0 0 0 0 74 0 21 44 0 0 2777 +13 40 0.999995756456487 -0.000546484664281671 -0.00286154215931466 -0.0105202294930101 0.000568439178387542 0.999970369203074 0.00767708230825283 0.00052129629387629 0.00285726196179215 -0.00767867634289397 0.999966436428595 -0.0228728040879391 4.0510375582971e-05 -8.65263982966613e-07 3.8367726455636e-07 1.78841891887545e-05 -3.03910615134719e-07 2.63082626251682e-05 -8.65263982966613e-07 3.35680900963201e-05 -6.92883406569228e-06 4.35017913227549e-06 -6.57455341321255e-08 1.72093820834213e-05 3.8367726455636e-07 -6.92883406569228e-06 1.74774566702322e-05 -9.01813080798009e-06 -2.46196959745378e-06 -1.93951693587442e-06 1.78841891887545e-05 4.35017913227549e-06 -9.01813080798009e-06 7.82107472183875e-05 6.90913981117145e-06 1.87600143519969e-05 -3.03910615134719e-07 -6.57455341321255e-08 -2.46196959745378e-06 6.90913981117145e-06 2.8571424685973e-05 -6.82642701297314e-06 2.63082626251682e-05 1.72093820834213e-05 -1.93951693587442e-06 1.87600143519969e-05 -6.82642701297314e-06 7.7206244767045e-05 2916 2916 0 0 4 2920 2931 0 0 5 0 0 0 0 0 0 0 0 75 0 15 18 0 0 2860 +14 49 0.999992896736919 0.000204888827485925 -0.00376357493265692 -0.0108159795217863 -0.000143288203360913 0.999866146712435 0.016360566216282 0.00430955457024925 0.00376642326300825 -0.0163599107269857 0.999859073758302 -0.0244062736736834 6.26455662173627e-05 -9.43319066083559e-06 3.04932039385605e-06 7.65933482146885e-06 -1.14977800547918e-05 3.10698417336308e-05 -9.43319066083559e-06 4.95773128404527e-05 -6.81921656430397e-06 1.2493483636647e-05 2.2556788753176e-06 -6.65789591635851e-06 3.04932039385605e-06 -6.81921656430397e-06 1.55028305909963e-05 -4.56194545319022e-06 1.40237138320944e-06 1.34206150369565e-06 7.65933482146885e-06 1.2493483636647e-05 -4.56194545319022e-06 7.19966094700277e-05 3.93767323544594e-06 -6.45791360730631e-06 -1.14977800547918e-05 2.2556788753176e-06 1.40237138320944e-06 3.93767323544594e-06 3.67318338801815e-05 -1.23923277010336e-05 3.10698417336308e-05 -6.65789591635851e-06 1.34206150369565e-06 -6.45791360730631e-06 -1.23923277010336e-05 7.0577326335528e-05 2942 2951 0 0 2 2947 2958 0 0 13 0 0 0 0 0 0 0 0 58 0 17 26 0 0 2603 +14 44 0.999943108555819 -0.000523612641471558 -0.0106538951340222 -0.0347412711170694 0.000765863346481835 0.999740963126415 0.0227468701232254 0.00454233633759647 0.0106392248335848 -0.0227537354487139 0.999684487434946 -0.0318551152458671 6.40699226829069e-05 7.96161070766342e-07 7.01568965658997e-06 -2.47190550829843e-06 -1.3956445757104e-05 3.71340570884831e-05 7.96161070766342e-07 4.20362072621435e-05 -4.78922449742839e-06 7.08603660702543e-06 -7.04115384383772e-07 8.54174484289689e-06 7.01568965658997e-06 -4.78922449742839e-06 1.79523088614203e-05 -1.73441549574576e-06 -1.30872232097898e-06 2.66652015667135e-06 -2.47190550829843e-06 7.08603660702543e-06 -1.73441549574576e-06 7.61442192626891e-05 2.95569632416151e-06 -8.14922598463226e-06 -1.3956445757104e-05 -7.04115384383772e-07 -1.30872232097898e-06 2.95569632416151e-06 4.03741000416485e-05 -6.11312464046512e-06 3.71340570884831e-05 8.54174484289689e-06 2.66652015667135e-06 -8.14922598463226e-06 -6.11312464046512e-06 7.50007676575323e-05 2522 2522 0 0 1 2531 2542 0 0 1 0 0 0 0 0 0 0 0 27 0 47 50 0 0 2325 +13 46 0.999970583820958 -0.000865631800384863 -0.0076211662071848 -0.0290797684279156 0.000980773158734751 0.999885245310079 0.0151173508001013 0.00507809672258855 0.00760720558302972 -0.0151243807406578 0.999856681495118 -0.0216277451274026 7.68598494851871e-05 6.4676241373302e-06 1.38594188521762e-06 4.09681846377052e-06 -1.32805610047347e-05 3.91128825822927e-05 6.4676241373302e-06 6.31077755597278e-05 -4.5493637742017e-06 1.48239343017288e-05 -7.97284854058809e-08 1.06502882442719e-05 1.38594188521762e-06 -4.5493637742017e-06 1.9295778042356e-05 -3.91967990949004e-06 -2.38309805168311e-06 -1.09886382206649e-06 4.09681846377052e-06 1.48239343017288e-05 -3.91967990949004e-06 8.99050571702864e-05 -2.51023095912347e-07 1.21881881336876e-06 -1.32805610047347e-05 -7.97284854058809e-08 -2.38309805168311e-06 -2.51023095912347e-07 3.76455047508456e-05 -6.45495152444158e-06 3.91128825822927e-05 1.06502882442719e-05 -1.09886382206649e-06 1.21881881336876e-06 -6.45495152444158e-06 7.35694911331789e-05 2772 2771 0 0 1 2774 2773 0 0 1 0 0 0 0 0 0 0 0 45 0 43 67 0 0 2613 +13 41 0.999951585771943 -0.000337932547018032 -0.00983422156399224 -0.00638730741015272 0.000408509081643218 0.999974172305959 0.00717550286340395 -0.0031714828180682 0.00983154273276779 -0.00717917283579168 0.999925897376844 -0.0217005117036246 3.99961657650877e-05 3.12187167716418e-06 3.60014999772595e-06 6.88227156428462e-06 -7.83615528402113e-06 2.14706842663505e-05 3.12187167716418e-06 4.76527578404072e-05 -4.61607327641046e-06 1.078502960818e-05 -5.96674276268204e-07 2.57407018994147e-06 3.60014999772595e-06 -4.61607327641046e-06 1.66389652982545e-05 -5.89536310119873e-06 -2.91502044499668e-06 4.47247675590799e-06 6.88227156428462e-06 1.078502960818e-05 -5.89536310119873e-06 6.91053737617421e-05 1.05402993612673e-05 4.64360311424416e-07 -7.83615528402113e-06 -5.96674276268204e-07 -2.91502044499668e-06 1.05402993612673e-05 3.70717357398087e-05 -1.17007439074409e-05 2.14706842663505e-05 2.57407018994147e-06 4.47247675590799e-06 4.64360311424416e-07 -1.17007439074409e-05 5.93153954176047e-05 2981 2982 0 1 9 2981 2982 0 1 9 0 0 0 0 0 0 0 0 87 0 28 52 0 0 2831 +14 48 0.999983738909265 -0.000848287678811503 -0.00563935502172336 -0.0196473452778526 0.000943040741084489 0.999858076634826 0.0168207390523451 0.00642078930062713 0.00562428583979466 -0.0168257836703201 0.999842617821761 -0.0283131518195347 5.48446448637168e-05 1.75657967616188e-06 1.82668848313018e-06 1.13475978797413e-05 -7.93427380279794e-06 2.87075395301353e-05 1.75657967616188e-06 3.02726727579465e-05 -4.68019669132747e-06 3.87972090579401e-06 -1.20471564914808e-06 1.09532770499907e-05 1.82668848313018e-06 -4.68019669132747e-06 1.90946002380763e-05 -1.03465970086888e-05 1.29898538926306e-06 -1.12159539247187e-06 1.13475978797413e-05 3.87972090579401e-06 -1.03465970086888e-05 9.03457290925353e-05 3.76607467843092e-06 1.14277159764296e-05 -7.93427380279794e-06 -1.20471564914808e-06 1.29898538926306e-06 3.76607467843092e-06 2.99473108620062e-05 -1.14335827002203e-05 2.87075395301353e-05 1.09532770499907e-05 -1.12159539247187e-06 1.14277159764296e-05 -1.14335827002203e-05 7.62704776742837e-05 2998 2998 0 1 3 2995 3009 0 1 4 0 0 0 0 0 0 0 0 36 0 37 41 0 0 2618 +13 39 0.999985694592818 -8.01659898731835e-05 -0.00534828786935366 -0.0140320383377681 9.84210381987064e-05 0.999994170599135 0.00341307501355438 -0.00601862348143386 0.00534798307950276 -0.00341355257217126 0.999979873165364 -0.0202620636291652 4.70956179269817e-05 -4.68764464704089e-07 4.90652359383726e-06 -6.90947961562859e-07 -3.17572678397894e-06 2.09546982022364e-05 -4.68764464704089e-07 3.34876199068736e-05 1.65338376037496e-06 -4.43563868242444e-08 -4.03758955962158e-07 5.07536859677376e-06 4.90652359383726e-06 1.65338376037496e-06 1.56961147211507e-05 -1.9887163895177e-06 5.1344888782103e-07 8.21501916154328e-07 -6.90947961562859e-07 -4.43563868242444e-08 -1.9887163895177e-06 5.33640600018122e-05 4.38039432843651e-06 5.06765577480672e-06 -3.17572678397894e-06 -4.03758955962158e-07 5.1344888782103e-07 4.38039432843651e-06 3.38885698683178e-05 -4.41288606964611e-06 2.09546982022364e-05 5.07536859677376e-06 8.21501916154328e-07 5.06765577480672e-06 -4.41288606964611e-06 6.91086181330175e-05 3085 3085 0 1 2 3092 3097 0 1 3 0 0 0 0 0 0 0 0 63 0 28 49 0 0 2864 +14 43 0.99999649215001 -0.0017695451605043 0.00197088751595477 -0.00702959104592491 0.00176072844229749 0.9999884760975 0.00446626326510577 -0.00384533190492856 -0.0019787680581855 -0.00446277740041831 0.999988083976427 -0.0235622124407106 7.24795937794045e-05 3.48132321180717e-06 1.40403787636539e-05 -1.29186005116294e-05 -7.56308588935044e-06 2.4368086639172e-05 3.48132321180717e-06 4.7914980509911e-05 -4.21576243572094e-06 2.18914655964802e-06 3.20908767116887e-07 -2.041215820858e-06 1.40403787636539e-05 -4.21576243572094e-06 2.32276234426508e-05 -1.20868042780131e-05 -3.32667597847364e-06 6.84848485901733e-06 -1.29186005116294e-05 2.18914655964802e-06 -1.20868042780131e-05 8.06688376486343e-05 2.80800979830768e-05 -1.02278644347797e-05 -7.56308588935044e-06 3.20908767116887e-07 -3.32667597847364e-06 2.80800979830768e-05 3.64696744107939e-05 -1.27594193945751e-05 2.4368086639172e-05 -2.041215820858e-06 6.84848485901733e-06 -1.02278644347797e-05 -1.27594193945751e-05 6.41447271712932e-05 2839 2840 0 1 8 2841 2860 0 1 10 0 0 0 0 0 0 0 0 17 0 12 14 0 0 2762 +14 47 0.999999391212021 -0.000696138800359986 -0.0008561345443076 -0.0116155902393406 0.000705338803700601 0.999941504676203 0.0107930404920622 0.00307297622490911 0.000848571010179836 -0.0107936377863042 0.999941386937544 -0.0300773354907958 8.15463322316991e-05 -6.10243007001745e-06 1.88469536299465e-06 -6.29228431185043e-06 -1.71444796943639e-05 4.1650735665425e-05 -6.10243007001745e-06 4.09250658469452e-05 -1.0659381088195e-06 -1.04144944657422e-06 6.10561233745725e-07 3.51709374424161e-06 1.88469536299465e-06 -1.0659381088195e-06 1.65707285685707e-05 -1.96555204031483e-06 1.02110712213375e-06 1.1528647894633e-06 -6.29228431185043e-06 -1.04144944657422e-06 -1.96555204031483e-06 7.18323169601226e-05 7.75658856101522e-06 -1.30132873202956e-05 -1.71444796943639e-05 6.10561233745725e-07 1.02110712213375e-06 7.75658856101522e-06 3.32856009266687e-05 -1.5681856219183e-05 4.1650735665425e-05 3.51709374424161e-06 1.1528647894633e-06 -1.30132873202956e-05 -1.5681856219183e-05 7.97284937264003e-05 3009 3009 0 0 4 3014 3032 0 0 8 0 0 0 0 0 0 0 0 51 0 14 17 0 0 2676 +14 18 0.999966675972019 0.000466328969300868 0.00815042837918299 0.00735290291166252 -0.000432893329364231 0.999991486500122 -0.00410359971751413 -0.00307566718062885 -0.00815227261793867 0.00409993470296551 0.999958364626545 -0.00707414127711294 3.58013744846374e-05 -2.24692042846197e-06 5.93790121096006e-06 6.00342861817843e-06 2.87562106625112e-07 -2.10352098738253e-06 -2.24692042846197e-06 4.48368112507605e-05 -2.61325621349794e-06 1.16243193856624e-05 6.96241849299259e-07 -1.1097659013757e-05 5.93790121096006e-06 -2.61325621349794e-06 1.48558440150116e-05 -1.15349429752576e-06 1.79404681093995e-07 1.50957855294157e-06 6.00342861817843e-06 1.16243193856624e-05 -1.15349429752576e-06 5.00460252444481e-05 3.61442998552657e-06 -3.79245406632239e-06 2.87562106625112e-07 6.96241849299259e-07 1.79404681093995e-07 3.61442998552657e-06 2.40133494168672e-05 -5.90742925609564e-06 -2.10352098738253e-06 -1.1097659013757e-05 1.50957855294157e-06 -3.79245406632239e-06 -5.90742925609564e-06 3.29270789983885e-05 2813 2823 0 4 14 2813 2832 0 4 25 0 0 0 0 0 0 0 0 61 0 9 13 0 0 2636 +14 51 0.999997241082966 -0.00100486636272274 -0.00212322162047239 -0.00381261704733483 0.00103859602954592 0.999872328552734 0.0159451532705361 0.00303796517231183 0.00210692779752521 -0.015947314448726 0.999870613638149 -0.0181114573279964 5.51101310735276e-05 -4.56927772035718e-06 8.63678420164771e-06 -4.43222030958991e-06 -4.73996195914034e-06 3.27318942813808e-05 -4.56927772035718e-06 2.06968175650079e-05 -6.51743752375915e-06 -2.86367845565874e-07 -3.58806763652944e-06 8.70429230318839e-06 8.63678420164771e-06 -6.51743752375915e-06 1.72703687649349e-05 -5.39081531538485e-06 -2.87756587366544e-06 4.74223547387889e-06 -4.43222030958991e-06 -2.86367845565874e-07 -5.39081531538485e-06 6.14233416209996e-05 1.39622432816258e-05 2.93986047878889e-09 -4.73996195914034e-06 -3.58806763652944e-06 -2.87756587366544e-06 1.39622432816258e-05 3.98641600716865e-05 -1.33022674917796e-05 3.27318942813808e-05 8.70429230318839e-06 4.74223547387889e-06 2.93986047878889e-09 -1.33022674917796e-05 7.15564062614429e-05 2995 2997 0 1 10 2993 3015 0 1 13 0 0 0 0 0 0 0 0 65 0 9 11 0 0 2646 +14 40 0.999999913506496 6.38578408278661e-05 0.000410985616974418 -0.00631123809338698 -6.69534367334838e-05 0.999971597742587 0.00753652608141316 -0.000165408420605649 -0.00041049267777223 -0.00753655294645211 0.999971515527041 -0.0240227134359315 3.86316367092694e-05 5.67236816684318e-06 4.6830264199634e-06 6.84634440724854e-06 -8.06792395697865e-06 1.48087208833234e-05 5.67236816684318e-06 4.79525798642306e-05 -3.49477855646218e-06 9.17684788032091e-06 -6.95806679557007e-06 -2.32051955942129e-07 4.6830264199634e-06 -3.49477855646218e-06 1.70687291387096e-05 -3.74975945404632e-06 -2.46931186510013e-07 -5.97384704658687e-08 6.84634440724854e-06 9.17684788032091e-06 -3.74975945404632e-06 7.41458745099408e-05 4.98978011369094e-06 4.26217898548022e-06 -8.06792395697865e-06 -6.95806679557007e-06 -2.46931186510013e-07 4.98978011369094e-06 3.71120804158965e-05 -6.77850519969836e-06 1.48087208833234e-05 -2.32051955942129e-07 -5.97384704658687e-08 4.26217898548022e-06 -6.77850519969836e-06 5.32076792043498e-05 2900 2910 0 1 6 2905 2916 0 1 11 0 0 0 0 0 0 0 0 74 0 14 17 0 0 2826 +14 50 0.999999406136941 -0.000891920244175973 -0.000626261960811862 -0.00745222901137924 0.000899983061983568 0.999915163108293 0.0129944840838132 0.00405589564080037 0.000614618787276737 -0.0129950399920262 0.999915372008727 -0.0190297769460625 6.43814112826601e-05 -5.35823373256014e-06 7.79799987122698e-06 -6.48991934382103e-07 -1.19634020325622e-05 3.12029009622189e-05 -5.35823373256014e-06 2.91579081377006e-05 -5.38058995493832e-06 1.38713024486698e-06 -1.61649875797764e-06 7.73424478519012e-06 7.79799987122698e-06 -5.38058995493832e-06 2.20770287029083e-05 -2.76823500742657e-06 -1.27015131294114e-07 -2.07013112176773e-07 -6.48991934382103e-07 1.38713024486698e-06 -2.76823500742657e-06 6.68473380192758e-05 4.67082168465906e-06 1.05392197970842e-05 -1.19634020325622e-05 -1.61649875797764e-06 -1.27015131294114e-07 4.67082168465906e-06 3.59597124671085e-05 -1.13561915607185e-05 3.12029009622189e-05 7.73424478519012e-06 -2.07013112176773e-07 1.05392197970842e-05 -1.13561915607185e-05 7.54490829643658e-05 2899 2903 0 0 9 2897 2911 0 0 10 0 0 0 0 0 0 0 0 55 0 28 32 0 0 2667 +14 41 0.999996330423769 0.00056149568553735 -0.00265025689173163 0.00102123205244091 -0.000531900883821284 0.999937647466463 0.0111542933745669 0.00158788385275929 0.00265635472910494 -0.011152842769054 0.99993427677909 -0.0271778077195732 3.08579334441469e-05 1.10769364754094e-06 3.74791061036312e-06 9.13243372628597e-07 6.63444063431221e-07 1.79989346909132e-05 1.10769364754094e-06 2.27402058666642e-05 -3.6466645832833e-06 1.89187181598718e-07 -2.90658667174123e-07 5.90724490228036e-06 3.74791061036312e-06 -3.6466645832833e-06 1.59671449564611e-05 -1.22116653750812e-06 -2.4963955527027e-06 1.47977462703522e-06 9.13243372628597e-07 1.89187181598718e-07 -1.22116653750812e-06 5.48508972196127e-05 7.94103839624837e-06 -7.74426077124311e-07 6.63444063431221e-07 -2.90658667174123e-07 -2.4963955527027e-06 7.94103839624837e-06 3.34977577728558e-05 -2.72622447548322e-06 1.79989346909132e-05 5.90724490228036e-06 1.47977462703522e-06 -7.74426077124311e-07 -2.72622447548322e-06 5.28811056697493e-05 2926 2927 0 1 10 2927 2950 0 1 15 0 0 0 0 0 0 0 0 88 0 9 11 0 0 2828 +14 45 0.999961932406506 9.79768251946508e-05 -0.00872491480696845 -0.00931405217436571 -9.1627232343627e-05 0.999999730700329 0.000728150891405465 -0.00259938158346163 0.00872498379926436 -0.000727323732657132 0.999961672094431 -0.00626822226568155 4.5528615609246e-05 5.2038655571238e-06 -4.78836740161765e-07 8.63466689310843e-06 -6.83711870146769e-06 3.44633678016347e-05 5.2038655571238e-06 5.37313142621336e-05 1.12764848705392e-06 1.19100687363646e-05 -2.19841773699344e-06 1.80340609313311e-05 -4.78836740161765e-07 1.12764848705392e-06 1.9470535864881e-05 -7.37433830302657e-06 -1.90286988448069e-06 -8.67261182948932e-07 8.63466689310843e-06 1.19100687363646e-05 -7.37433830302657e-06 9.4477615310031e-05 -3.99320952832969e-07 1.84988962505395e-05 -6.83711870146769e-06 -2.19841773699344e-06 -1.90286988448069e-06 -3.99320952832969e-07 3.68397176229626e-05 -1.38340964396138e-05 3.44633678016347e-05 1.80340609313311e-05 -8.67261182948932e-07 1.84988962505395e-05 -1.38340964396138e-05 8.51967963076059e-05 2635 2644 0 1 3 2642 2656 0 1 13 0 0 0 0 0 0 0 0 27 0 17 23 0 0 2528 +15 49 0.999974596450453 2.64426040960464e-05 -0.00712781555194984 -0.0136516502318995 7.70505666708772e-05 0.99989459146347 0.0145189540019068 0.00561801641423666 0.00712744813829641 -0.0145191343711669 0.999869188554257 -0.0198838330552431 5.62807701995892e-05 -5.34980868163781e-06 4.25973664668086e-06 4.21184435627048e-06 -1.09617583281033e-05 3.72498171726262e-05 -5.34980868163781e-06 5.07157851404153e-05 -7.27883015756165e-06 2.09011353877408e-06 1.14656440200328e-06 2.05198074861748e-06 4.25973664668086e-06 -7.27883015756165e-06 2.01800863621405e-05 -3.27007189117011e-06 -2.92095374050179e-06 3.69744230971042e-06 4.21184435627048e-06 2.09011353877408e-06 -3.27007189117011e-06 5.5528987959609e-05 5.85934204799882e-06 -2.93626868028992e-06 -1.09617583281033e-05 1.14656440200328e-06 -2.92095374050179e-06 5.85934204799882e-06 3.70451619961529e-05 -1.6559366704036e-05 3.72498171726262e-05 2.05198074861748e-06 3.69744230971042e-06 -2.93626868028992e-06 -1.6559366704036e-05 7.86652593199101e-05 2767 2779 0 0 0 2771 2784 0 0 5 0 0 0 0 0 0 0 0 58 0 14 22 0 0 2825 +14 42 0.999995333526535 0.000801261184806547 -0.00294803420401495 -0.00353346452263446 -0.000770924010119665 0.999946888640686 0.0102774303199619 -5.92332332691487e-05 0.00295611253590601 -0.0102751096502555 0.99994284012655 -0.0255384566544438 5.93456771977066e-05 4.49448688194918e-06 7.41672939831472e-06 5.51497522685003e-07 -1.02700217446249e-05 2.84438979761026e-05 4.49448688194918e-06 2.75390424657266e-05 -7.49720033451752e-07 -2.82769708647007e-06 3.85909762936178e-07 1.04725272440567e-05 7.41672939831472e-06 -7.49720033451752e-07 1.67737398779361e-05 -2.24535960685444e-06 -1.88704072561742e-06 1.49326696638e-06 5.51497522685003e-07 -2.82769708647007e-06 -2.24535960685444e-06 4.76853831838702e-05 1.27886600516e-05 -3.47945948817303e-06 -1.02700217446249e-05 3.85909762936178e-07 -1.88704072561742e-06 1.27886600516e-05 3.18921664051906e-05 -1.30827230021287e-05 2.84438979761026e-05 1.04725272440567e-05 1.49326696638e-06 -3.47945948817303e-06 -1.30827230021287e-05 7.18989151889948e-05 2846 2846 0 0 8 2849 2869 0 0 12 0 0 0 0 0 0 0 0 54 0 14 16 0 0 2630 +14 46 0.999987805326103 -0.000581765732485717 -0.00490415616752316 -0.0238182643842822 0.000665851031280675 0.99985250782255 0.0171615629638327 0.00933971363077834 0.00489344883360321 -0.0171646191216105 0.999840702316586 -0.0227815947239483 4.73418576366492e-05 -5.87870144714634e-07 1.57075187315798e-06 5.09735809861076e-06 -6.37044357457371e-06 2.54116818509889e-05 -5.87870144714634e-07 2.92691529558017e-05 -6.67971394660573e-06 7.22588366039169e-06 1.42788649107019e-06 3.32585129257916e-06 1.57075187315798e-06 -6.67971394660573e-06 1.59316012528657e-05 -2.42314514960376e-06 -1.37746933607299e-06 -4.21441474152123e-07 5.09735809861076e-06 7.22588366039169e-06 -2.42314514960376e-06 8.36383544003561e-05 9.82269025061263e-07 -4.53158217052477e-06 -6.37044357457371e-06 1.42788649107019e-06 -1.37746933607299e-06 9.82269025061263e-07 3.05078147108553e-05 -5.41101170575357e-06 2.54116818509889e-05 3.32585129257916e-06 -4.21441474152123e-07 -4.53158217052477e-06 -5.41101170575357e-06 5.79754392893458e-05 3004 3003 0 0 0 3007 3022 0 0 5 0 0 0 0 0 0 0 0 48 0 23 25 0 0 2540 +15 44 0.999992352415378 0.000474098157940633 -0.00388205379862214 -0.0267596859285347 -0.000393390762270305 0.999784321170754 0.0207643055468293 0.0065567683431411 0.00389106084081445 -0.0207626195859425 0.99977686174139 -0.0302380169155276 4.16304480513388e-05 8.3411610230053e-07 6.01552328609724e-06 8.26418427642067e-06 4.93813092978529e-07 2.87188785694876e-05 8.3411610230053e-07 2.91368910255962e-05 -7.94691993640607e-06 -2.28030711619408e-06 1.52296688252153e-07 1.14484657172107e-05 6.01552328609724e-06 -7.94691993640607e-06 2.04308142533199e-05 -8.80303265029631e-07 -4.66187584520357e-07 -1.05703693796645e-06 8.26418427642067e-06 -2.28030711619408e-06 -8.80303265029631e-07 8.33817405488015e-05 5.82752150522286e-07 3.79558205616414e-06 4.93813092978529e-07 1.52296688252153e-07 -4.66187584520357e-07 5.82752150522286e-07 3.36101960674134e-05 2.00098333908698e-06 2.87188785694876e-05 1.14484657172107e-05 -1.05703693796645e-06 3.79558205616414e-06 2.00098333908698e-06 6.53854764004973e-05 2591 2591 0 0 1 2601 2605 0 0 3 0 0 0 0 0 0 0 0 27 0 27 30 0 0 2545 +15 17 0.999998185951981 -0.000341664132911074 -0.00187386188600948 -0.0015331600386475 0.000343369807812332 0.999999526998814 0.000909999628153052 0.000246415858373313 0.00187355008543669 -0.000910641404965695 0.999997830268801 -0.00491871830660265 6.32897279051047e-05 3.70878574899441e-06 5.55665600035092e-06 -1.06526224703709e-05 -7.40216710981641e-06 1.49594792586408e-05 3.70878574899441e-06 3.06689220522397e-05 -4.37579282351855e-06 3.27702973129676e-06 -3.17642892295146e-06 6.58498174883611e-06 5.55665600035092e-06 -4.37579282351855e-06 1.62168187616378e-05 -8.54319786765331e-07 -2.73641993167011e-07 2.76410699848094e-06 -1.06526224703709e-05 3.27702973129676e-06 -8.54319786765331e-07 4.8742722093937e-05 4.29477124018658e-06 -3.67274513532667e-06 -7.40216710981641e-06 -3.17642892295146e-06 -2.73641993167011e-07 4.29477124018658e-06 2.77537885778413e-05 -6.79701317146828e-06 1.49594792586408e-05 6.58498174883611e-06 2.76410699848094e-06 -3.67274513532667e-06 -6.79701317146828e-06 3.98486126212337e-05 2769 2790 0 0 9 2769 2791 0 0 12 0 0 0 0 0 0 0 0 75 0 10 13 0 0 2711 +14 52 0.999890704809949 0.00365574412325508 -0.0143252912560059 -0.00788896872427696 -0.00333107589385987 0.999738525060366 0.0226226754278581 0.00447061969374436 0.0144042482640872 -0.0225724842458724 0.999641436009391 -0.0360552369477221 7.74775748463466e-05 3.42137276914571e-06 4.2889650478959e-06 6.07235618301628e-06 -1.82927104068726e-05 3.83456936160728e-05 3.42137276914571e-06 8.60009404258891e-05 -7.73262943810177e-06 3.93137668612304e-05 5.73400854295952e-06 5.64690858282695e-06 4.2889650478959e-06 -7.73262943810177e-06 1.8614531417068e-05 -9.01008338811381e-06 -4.34777402523533e-06 7.13860936448969e-08 6.07235618301628e-06 3.93137668612304e-05 -9.01008338811381e-06 0.000107219622380539 1.13144191609554e-05 1.37586320262622e-05 -1.82927104068726e-05 5.73400854295952e-06 -4.34777402523533e-06 1.13144191609554e-05 4.60013707526156e-05 -1.31385918083874e-05 3.83456936160728e-05 5.64690858282695e-06 7.13860936448969e-08 1.37586320262622e-05 -1.31385918083874e-05 7.75222960415844e-05 2805 2805 0 1 2 2806 2819 0 1 3 0 0 0 0 0 0 0 0 47 0 38 40 0 0 2523 +15 48 0.999998250275653 -0.0011352627420421 -0.00148681678034886 -0.014834879102053 0.00115602967050816 0.999900740729712 0.0140418048545708 0.00354381811244398 0.00147072806211777 -0.0140434990895957 0.999900303576456 -0.0254163108288103 4.2775218897735e-05 -2.48985417142949e-06 5.35427269008133e-06 8.24430855840888e-06 -3.132403754844e-06 3.08319971696976e-05 -2.48985417142949e-06 3.42106512373685e-05 -4.41093291065212e-06 2.94185651841305e-07 -1.06357881318995e-06 3.01962434064583e-06 5.35427269008133e-06 -4.41093291065212e-06 1.75666990659489e-05 -3.19621619369232e-06 2.09391660213273e-06 -1.3423494182503e-06 8.24430855840888e-06 2.94185651841305e-07 -3.19621619369232e-06 6.88726238152755e-05 3.7710972241995e-06 -2.75983006374e-07 -3.132403754844e-06 -1.06357881318995e-06 2.09391660213273e-06 3.7710972241995e-06 2.98288932740209e-05 -1.107081742728e-05 3.08319971696976e-05 3.01962434064583e-06 -1.3423494182503e-06 -2.75983006374e-07 -1.107081742728e-05 6.7553167746653e-05 3046 3046 0 0 5 3050 3059 0 0 6 0 0 0 0 0 0 0 0 43 0 16 19 0 0 2838 +15 51 0.999998320986253 -0.000946889248136982 0.00156889305780683 -0.00520661058995442 0.000926880653303181 0.999918854358646 0.0127053370812244 0.00135674788641924 -0.00158079629604961 -0.0127038615721664 0.999918053134468 -0.0244557757095497 8.56447946879244e-05 3.44446307672729e-06 2.50174940058338e-06 -1.99424966732924e-06 -1.2604034587922e-05 3.57841842079999e-05 3.44446307672729e-06 3.96417806564297e-05 -8.18863455550967e-06 8.84178711575119e-06 -2.03282311527318e-06 7.24778932913265e-06 2.50174940058338e-06 -8.18863455550967e-06 2.13809651175646e-05 -4.39502499911993e-06 -3.17426519627646e-06 1.85811639450482e-06 -1.99424966732924e-06 8.84178711575119e-06 -4.39502499911993e-06 8.71958457361432e-05 5.35231612879432e-06 -4.61061217071565e-06 -1.2604034587922e-05 -2.03282311527318e-06 -3.17426519627646e-06 5.35231612879432e-06 3.88103006940974e-05 -1.74732433633214e-05 3.57841842079999e-05 7.24778932913265e-06 1.85811639450482e-06 -4.61061217071565e-06 -1.74732433633214e-05 8.04491015276031e-05 2742 2751 0 0 7 2744 2753 0 0 9 0 0 0 0 0 0 0 0 69 0 12 14 0 0 2717 +15 46 0.999998506746004 -0.000851314109983428 -0.00150391823186409 -0.0248254318871189 0.00087746207941465 0.999846962317096 0.0174723211272671 0.00819611901943542 0.00148881364219281 -0.0174736146678728 0.999846216287474 -0.0311672161966823 7.01750353125006e-05 -2.63250040379687e-06 4.15029612757253e-06 9.52447526269942e-06 -1.09888656864794e-05 4.47544895135028e-05 -2.63250040379687e-06 3.47105954892069e-05 -3.84888382919727e-06 6.24683224056417e-07 1.2058869615519e-06 1.2280927150642e-05 4.15029612757253e-06 -3.84888382919727e-06 1.61974990031316e-05 -2.88793931790787e-06 9.04427428958506e-07 3.46574551266501e-08 9.52447526269942e-06 6.24683224056417e-07 -2.88793931790787e-06 7.57996920406183e-05 1.36062049198003e-06 9.22940178388271e-06 -1.09888656864794e-05 1.2058869615519e-06 9.04427428958506e-07 1.36062049198003e-06 3.87388091873642e-05 -6.95438817570785e-06 4.47544895135028e-05 1.2280927150642e-05 3.46574551266501e-08 9.22940178388271e-06 -6.95438817570785e-06 9.34003243357163e-05 3046 3057 0 0 1 3046 3057 0 0 1 0 0 0 0 0 1 0 0 50 0 21 23 0 0 2528 +15 18 0.999998841305854 0.00146613070929858 -0.000409692192006871 0.00212284561576399 -0.00146555311383802 0.999997936827989 0.00140658943415823 0.000303323041701895 0.000411753590706201 -0.00140598737868358 0.99999892682866 -0.00192881927281941 2.83035106715027e-05 -1.39769622948901e-05 6.37374198570073e-06 -4.5173421231525e-06 2.30560849256163e-06 9.97928895497001e-06 -1.39769622948901e-05 4.95206511143825e-05 -7.59143743351356e-06 1.77381905289247e-05 -2.91804368631177e-06 -2.28057778643849e-05 6.37374198570073e-06 -7.59143743351356e-06 1.60153615474849e-05 -3.82669097621436e-06 4.15036086192624e-06 5.55908136935946e-06 -4.5173421231525e-06 1.77381905289247e-05 -3.82669097621436e-06 5.13861058539838e-05 3.66930814509596e-06 -1.43841329117462e-05 2.30560849256163e-06 -2.91804368631177e-06 4.15036086192624e-06 3.66930814509596e-06 2.17446827018165e-05 -1.2601266565923e-06 9.97928895497001e-06 -2.28057778643849e-05 5.55908136935946e-06 -1.43841329117462e-05 -1.2601266565923e-06 4.47749369334292e-05 2881 2900 0 0 9 2881 2902 0 0 13 0 0 0 0 0 0 0 0 75 0 10 12 0 0 2824 +15 19 0.999998626751003 0.000726089799107059 -0.00148972806615239 0.00295426541409243 -0.00072615585385314 0.999999735389595 -4.37997280722877e-05 -0.000763152763565453 0.00148969586941909 4.4881442680241e-05 0.99999888939532 0.000135434484408033 4.21746795622462e-05 -4.31042868227631e-06 5.86872396696836e-06 1.50337934676656e-06 6.11539542292479e-07 -1.19485486250091e-07 -4.31042868227631e-06 5.72787947216806e-05 -8.41862575806991e-06 1.86784766259408e-05 -9.81904214191867e-07 -2.4633804508052e-05 5.86872396696836e-06 -8.41862575806991e-06 1.891184409957e-05 -7.23108709685961e-06 3.87582801050519e-07 4.60991313805665e-06 1.50337934676656e-06 1.86784766259408e-05 -7.23108709685961e-06 5.71686888401655e-05 5.09518599936824e-06 -1.24209431154807e-05 6.11539542292479e-07 -9.81904214191867e-07 3.87582801050519e-07 5.09518599936824e-06 2.89148717112209e-05 -7.01350640639659e-06 -1.19485486250091e-07 -2.4633804508052e-05 4.60991313805665e-06 -1.24209431154807e-05 -7.01350640639659e-06 4.71855573133149e-05 2913 2921 0 0 9 2914 2923 0 0 12 0 0 0 0 0 0 0 0 76 0 9 11 0 0 2602 +15 50 0.999998102703132 0.000472041517393273 0.00188991188745815 -0.0029660198960677 -0.00049116094405098 0.999948580545181 0.0101289203079246 0.000866490301278785 -0.00188503343830753 -0.0101298293412626 0.999946915194228 -0.0204317780596101 9.3921584839503e-05 4.7245826450633e-06 1.59327186306516e-06 1.35791297211847e-05 -1.50707077725597e-05 3.7006142613093e-05 4.7245826450633e-06 3.77589879990661e-05 -2.64506103084821e-06 7.56084892647364e-06 -2.35361359931367e-06 3.63253278663017e-07 1.59327186306516e-06 -2.64506103084821e-06 2.25305606741748e-05 -6.47333930205319e-06 2.28029408836662e-07 2.05922344778187e-06 1.35791297211847e-05 7.56084892647364e-06 -6.47333930205319e-06 8.39247328143789e-05 6.56266854091389e-06 -3.76722674520215e-06 -1.50707077725597e-05 -2.35361359931367e-06 2.28029408836662e-07 6.56266854091389e-06 3.93768054045035e-05 -1.97637500416112e-05 3.7006142613093e-05 3.63253278663017e-07 2.05922344778187e-06 -3.76722674520215e-06 -1.97637500416112e-05 8.18989226546226e-05 2750 2750 0 0 8 2754 2771 0 0 12 0 0 0 0 0 0 0 0 60 0 13 15 0 0 2706 +15 45 0.9999943151487 -4.98803127771893e-05 -0.00337152520923544 0.000439539098262802 7.6735305179395e-05 0.999968271355488 0.00796557556044754 0.00354586147654907 0.0033710209099102 -0.00796578899235081 0.999962590512142 -0.011536694988859 5.58954783548256e-05 -7.96019871635248e-07 6.27169331524537e-06 1.67515567505407e-05 -5.72344279275238e-06 2.88974650823138e-05 -7.96019871635248e-07 3.2904854122586e-05 -7.41234710690945e-06 1.11574143811672e-05 -2.67281843892917e-06 8.80026936926078e-06 6.27169331524537e-06 -7.41234710690945e-06 1.96507398982045e-05 -4.9822213248978e-06 -2.64860283477012e-06 8.33353757895283e-07 1.67515567505407e-05 1.11574143811672e-05 -4.9822213248978e-06 9.51878546507638e-05 -3.66537264781298e-06 1.43325047819632e-05 -5.72344279275238e-06 -2.67281843892917e-06 -2.64860283477012e-06 -3.66537264781298e-06 3.83199025478576e-05 -3.16340816552805e-06 2.88974650823138e-05 8.80026936926078e-06 8.33353757895283e-07 1.43325047819632e-05 -3.16340816552805e-06 6.63843862424503e-05 2819 2837 0 0 10 2819 2839 0 0 13 0 0 0 0 0 0 0 0 28 0 9 11 0 0 2300 +15 42 0.999997648985804 -0.000300353141733085 -0.00214751271356194 -0.0036582371983593 0.000316739271664221 0.999970810290347 0.00763401883028724 -0.0017942343214524 0.00214515712674962 -0.00763468108421338 0.999968554478412 -0.023159015536349 5.47440823184757e-05 7.482003585189e-06 3.72924280127799e-06 6.75597950282228e-06 -1.13480925971115e-05 2.55636294757657e-05 7.482003585189e-06 7.12285607012789e-05 5.97329080236337e-07 1.51689500459781e-05 -5.0182942866673e-06 1.10936490445414e-05 3.72924280127799e-06 5.97329080236337e-07 1.7091362016316e-05 -4.97493713330573e-06 2.66782785483991e-06 1.13101454408936e-06 6.75597950282228e-06 1.51689500459781e-05 -4.97493713330573e-06 6.63122936740668e-05 7.73395410059019e-06 -3.41872176747421e-06 -1.13480925971115e-05 -5.0182942866673e-06 2.66782785483991e-06 7.73395410059019e-06 3.42342841024698e-05 -4.38169503791235e-06 2.55636294757657e-05 1.10936490445414e-05 1.13101454408936e-06 -3.41872176747421e-06 -4.38169503791235e-06 7.65803164933515e-05 2888 2894 0 0 7 2889 2896 0 0 9 0 0 0 0 0 0 0 0 58 0 14 16 0 0 2823 +15 47 0.999988842298582 8.25574933198472e-05 -0.00472318352405691 -0.014483306157817 5.87251005357507e-06 0.999824775433776 0.0187194656524398 0.00521503645502955 0.00472390133843326 -0.0187192845231741 0.999813619202642 -0.0299634270199868 6.58229915031886e-05 6.20219475159343e-06 1.37123018647262e-06 -3.24417961354742e-06 -9.36826576177657e-06 3.6864259129813e-05 6.20219475159343e-06 6.95973820234657e-05 -3.83901632031469e-06 1.32598636039642e-05 -5.32415845224763e-06 2.11151082436912e-05 1.37123018647262e-06 -3.83901632031469e-06 2.27942260660242e-05 -2.14877755861845e-06 -4.48179791453275e-06 2.51371268709688e-06 -3.24417961354742e-06 1.32598636039642e-05 -2.14877755861845e-06 8.23922038840145e-05 7.83443485535046e-06 8.36670667692267e-07 -9.36826576177657e-06 -5.32415845224763e-06 -4.48179791453275e-06 7.83443485535046e-06 3.63190540007212e-05 -1.49972456058799e-05 3.6864259129813e-05 2.11151082436912e-05 2.51371268709688e-06 8.36670667692267e-07 -1.49972456058799e-05 7.71519086875384e-05 2746 2755 0 0 2 2749 2758 0 0 4 0 0 0 0 0 0 0 0 57 0 17 20 0 0 2722 +16 18 0.999999766589752 0.000537495130181116 0.000421804962714907 0.000832111489987593 -0.000537820627420697 0.999999557426025 0.000771943473580032 -0.000304505880617261 -0.000421389860177184 -0.000772170148810211 0.999999613091849 -0.000863963759043614 3.84616691032366e-05 -4.57580659774146e-06 3.25026848814529e-06 -3.87274784398844e-06 3.31107226670785e-07 -2.86272901984441e-06 -4.57580659774146e-06 2.47247654571313e-05 -3.43633291236412e-06 6.0853449587045e-07 -7.59364710716546e-07 -3.51142196464842e-07 3.25026848814529e-06 -3.43633291236412e-06 1.54290651348829e-05 7.32118911468134e-07 -6.12309963363849e-07 1.25223666190696e-06 -3.87274784398844e-06 6.0853449587045e-07 7.32118911468134e-07 4.15183274489754e-05 2.76023263407281e-06 -4.27628456885124e-06 3.31107226670785e-07 -7.59364710716546e-07 -6.12309963363849e-07 2.76023263407281e-06 2.08507179709323e-05 -4.97787068403523e-07 -2.86272901984441e-06 -3.51142196464842e-07 1.25223666190696e-06 -4.27628456885124e-06 -4.97787068403523e-07 2.73776859117951e-05 2807 2808 0 0 9 2808 2828 0 0 12 0 0 0 0 0 0 0 0 77 0 10 12 0 0 2638 +15 43 0.999977550725519 -0.00083041837363569 -0.00664894354890571 -0.00833705722969637 0.000892184706710164 0.999956429720094 0.00929207554277589 -0.00199919363046903 0.00664093754231427 -0.00929779902817165 0.999934722310307 -0.0188716175517809 5.98199102831632e-05 -6.31542155839429e-06 1.23685176060174e-05 -1.092757406328e-05 -1.19440694124652e-05 2.79809911322473e-05 -6.31542155839429e-06 7.62706640484367e-05 -3.77360716702932e-06 1.91771845028379e-05 -2.09166023254538e-06 -1.7866797652928e-05 1.23685176060174e-05 -3.77360716702932e-06 2.2215046023693e-05 -6.12817022623259e-06 -7.54359637128318e-08 5.71027270429546e-06 -1.092757406328e-05 1.91771845028379e-05 -6.12817022623259e-06 8.82423731976973e-05 1.85462044800836e-05 -9.62101386933341e-06 -1.19440694124652e-05 -2.09166023254538e-06 -7.54359637128318e-08 1.85462044800836e-05 3.92843107340249e-05 -1.61514899256057e-05 2.79809911322473e-05 -1.7866797652928e-05 5.71027270429546e-06 -9.62101386933341e-06 -1.61514899256057e-05 8.63202098708457e-05 2944 2950 0 0 5 2946 2952 0 0 7 0 0 0 0 0 0 0 0 18 0 13 15 0 0 2602 +15 52 0.999780028373961 0.00344692446557241 -0.020688488980349 -0.0146080055536799 -0.00305833727523171 0.999818866663463 0.0187851121077047 0.00466528547809143 0.0207494924678247 -0.0187177075390322 0.999609476739197 -0.0272249092717029 7.78959705730963e-05 6.07758184714092e-06 3.17469632193616e-06 2.84507498851697e-05 -1.18434058009044e-05 4.53848650476214e-05 6.07758184714092e-06 4.95625188174232e-05 -5.56252268508711e-07 1.54273199018506e-05 -1.50907768979472e-06 1.98882765656779e-05 3.17469632193616e-06 -5.56252268508711e-07 1.69524681678376e-05 -2.87910410143897e-07 -5.20094732838842e-06 2.48815958994328e-06 2.84507498851697e-05 1.54273199018506e-05 -2.87910410143897e-07 9.1958554578136e-05 -5.05561046265767e-06 4.85588369238801e-05 -1.18434058009044e-05 -1.50907768979472e-06 -5.20094732838842e-06 -5.05561046265767e-06 3.84698041322775e-05 -1.28060077545476e-05 4.53848650476214e-05 1.98882765656779e-05 2.48815958994328e-06 4.85588369238801e-05 -1.28060077545476e-05 9.83273447965703e-05 2781 2780 0 0 1 2788 2793 0 0 2 0 0 0 0 0 0 0 0 53 0 23 25 0 0 2780 +16 20 0.999989928889451 -0.000157283560803524 -0.00448524041181226 -0.00272473176388185 0.000143230146542956 0.999995080611234 -0.00313340684508512 -0.00349887726336087 0.00448571118055701 0.00313273286655693 0.999985032077976 0.00661533444293697 4.52034987666139e-05 -8.25829767058819e-06 6.82547751152634e-06 -8.82876702089539e-07 6.76293637379321e-09 7.21985632292107e-06 -8.25829767058819e-06 3.44570561616131e-05 -4.02041097916507e-06 5.7054869924877e-06 -6.13905728167809e-07 -1.11732854695194e-05 6.82547751152634e-06 -4.02041097916507e-06 1.87785966921197e-05 -3.46809487675602e-06 3.03285478091496e-06 1.69736585798207e-06 -8.82876702089539e-07 5.7054869924877e-06 -3.46809487675602e-06 5.13565296687311e-05 4.45315572881823e-06 -9.87312120495324e-06 6.76293637379321e-09 -6.13905728167809e-07 3.03285478091496e-06 4.45315572881823e-06 2.36019385806306e-05 -5.66849796773111e-07 7.21985632292107e-06 -1.11732854695194e-05 1.69736585798207e-06 -9.87312120495324e-06 -5.66849796773111e-07 4.37373298986433e-05 2989 2996 0 0 12 2989 2996 0 0 12 0 0 0 0 0 0 0 0 71 0 34 38 0 0 2632 +15 41 0.999999804250163 -9.43185785473235e-05 -0.000618549626612612 -0.00313089768161515 0.000100331934628205 0.999952668205225 0.00972888908118958 0.000595768654962396 0.000617602734559644 -0.00972894923704183 0.999952481927819 -0.0253174953374969 7.17348999584955e-05 7.90035934365122e-06 7.92845099390602e-06 4.09831841147879e-06 -2.00472029354586e-05 3.8954091504127e-05 7.90035934365122e-06 4.29177824158232e-05 -1.4677290564341e-06 1.39377857874655e-05 -7.29102915262541e-06 2.82618596374773e-06 7.92845099390602e-06 -1.4677290564341e-06 1.75000621553076e-05 -4.02902929577687e-06 1.7070029196425e-07 8.94537680747464e-06 4.09831841147879e-06 1.39377857874655e-05 -4.02902929577687e-06 8.8931495921319e-05 2.90218008976275e-06 -7.91350922900615e-06 -2.00472029354586e-05 -7.29102915262541e-06 1.7070029196425e-07 2.90218008976275e-06 4.71486506439037e-05 -1.68060911034582e-05 3.8954091504127e-05 2.82618596374773e-06 8.94537680747464e-06 -7.91350922900615e-06 -1.68060911034582e-05 9.21207852464999e-05 2725 2733 0 0 9 2725 2733 0 0 10 0 0 0 0 0 0 0 0 93 0 11 13 0 0 2569 +16 49 0.999998781932265 -0.00114464903625367 0.00106109027428515 -0.0108797672756275 0.00112208077557645 0.999778195390013 0.0210309523660269 0.00845191780821158 -0.00108492797892797 -0.0210297361199044 0.999778261981129 -0.0225286613912145 7.17696834297553e-05 -3.85131663652414e-06 1.34646111781507e-06 5.39852466628989e-06 -7.96004871082474e-06 2.83421278788496e-05 -3.85131663652414e-06 3.11902425149491e-05 -5.44065530341971e-06 -1.40735777700119e-06 2.82211833783337e-07 1.25196459068053e-06 1.34646111781507e-06 -5.44065530341971e-06 1.57503980774176e-05 -1.57007924998327e-08 1.38672399187244e-06 2.0351564070049e-07 5.39852466628989e-06 -1.40735777700119e-06 -1.57007924998327e-08 5.87352608468846e-05 4.47742916205424e-06 3.63244209534963e-06 -7.96004871082474e-06 2.82211833783337e-07 1.38672399187244e-06 4.47742916205424e-06 3.48938140617084e-05 -7.19513086554353e-06 2.83421278788496e-05 1.25196459068053e-06 2.0351564070049e-07 3.63244209534963e-06 -7.19513086554353e-06 6.02364264150036e-05 2983 2985 0 0 3 2985 2999 0 0 5 0 0 0 0 0 0 0 0 62 0 10 13 0 0 2396 +16 45 0.999961020039158 -0.000995936733335869 -0.00877305603935015 -0.0107566064973341 0.00100329233196322 0.999999148865964 0.000834069447906383 -0.00327464281557943 0.00877221789190223 -0.000842838875764128 0.999961168153987 -0.00891475432350436 7.56638887614184e-05 -7.23963247603944e-06 5.22597213826206e-06 4.13074948190933e-06 -1.31460429873932e-05 4.12219808676691e-05 -7.23963247603944e-06 0.000131709412651832 -2.08057206506362e-06 4.00191532558312e-05 4.693906690633e-07 -1.80048683150937e-05 5.22597213826206e-06 -2.08057206506362e-06 2.13242807176847e-05 -3.90810791370977e-06 -5.02410110367425e-06 3.59674345242001e-06 4.13074948190933e-06 4.00191532558312e-05 -3.90810791370977e-06 8.82810624380691e-05 -1.93797892242494e-06 -8.89527905234155e-06 -1.31460429873932e-05 4.693906690633e-07 -5.02410110367425e-06 -1.93797892242494e-06 4.44117868797228e-05 -1.49660720357988e-05 4.12219808676691e-05 -1.80048683150937e-05 3.59674345242001e-06 -8.89527905234155e-06 -1.49660720357988e-05 9.70531173278958e-05 2553 2553 0 0 4 2560 2577 0 0 6 0 0 0 0 0 0 0 0 28 0 14 16 0 0 2342 +16 19 0.999999305745162 0.000765289786537605 0.000896013803442921 0.00147407199406719 -0.000765172896241713 0.999999698701973 -0.000130791445538104 0.00116141542669038 -0.000896113626833167 0.000130105749258457 0.999999590026347 -0.0047785856963895 4.15280325559307e-05 -1.04051358135973e-05 8.22679000026416e-06 -1.15060351971046e-06 3.7768356504716e-06 3.12271053577371e-06 -1.04051358135973e-05 2.79325347980632e-05 -7.19054814547961e-06 6.02218104431274e-06 5.80934975995588e-08 -7.63518647028257e-08 8.22679000026416e-06 -7.19054814547961e-06 1.88448206814628e-05 -2.47024448328946e-06 -1.84950861020511e-07 4.73355550140251e-06 -1.15060351971046e-06 6.02218104431274e-06 -2.47024448328946e-06 3.88292636070279e-05 6.79287141111854e-06 -2.16543264622727e-06 3.7768356504716e-06 5.80934975995588e-08 -1.84950861020511e-07 6.79287141111854e-06 2.01688515263951e-05 -2.5155643137687e-06 3.12271053577371e-06 -7.63518647028257e-08 4.73355550140251e-06 -2.16543264622727e-06 -2.5155643137687e-06 3.29893789161104e-05 2823 2828 0 0 11 2823 2835 0 0 12 0 0 0 0 0 0 0 0 77 0 30 37 0 0 2614 +16 50 0.999994093371062 0.000155541760234388 -0.00343351565443973 -0.00373767269098885 -0.000134270300098641 0.999980804246346 0.00619460332204162 0.000101633487337087 0.00343441326502372 -0.00619410571364106 0.999974918615429 -0.0137809195087563 2.7110639393519e-05 4.34741909271442e-07 3.11831913809784e-06 1.29588156997475e-05 -1.62335080679731e-06 1.43823990768226e-05 4.34741909271442e-07 5.0168382433901e-05 -2.79415637874747e-06 1.01943553261277e-05 -7.00970555983046e-07 1.23477516583135e-06 3.11831913809784e-06 -2.79415637874747e-06 1.86620647621969e-05 -2.80597453566028e-06 -1.80331764147521e-06 -6.08940242925621e-07 1.29588156997475e-05 1.01943553261277e-05 -2.80597453566028e-06 7.21550188284385e-05 5.78610789967526e-06 1.99294210171796e-06 -1.62335080679731e-06 -7.00970555983046e-07 -1.80331764147521e-06 5.78610789967526e-06 2.93011934022371e-05 -9.40184693909163e-06 1.43823990768226e-05 1.23477516583135e-06 -6.08940242925621e-07 1.99294210171796e-06 -9.40184693909163e-06 5.8443143202853e-05 2851 2861 0 0 11 2851 2862 0 0 12 0 0 0 0 0 0 0 0 63 0 34 38 0 0 3072 +16 44 0.999946115717925 -2.05392775336351e-05 -0.0103810037458517 -0.034187670266259 0.000292471759068548 0.999656826044633 0.0261943620392125 0.00433212747864172 0.0103769032424638 -0.026195986725246 0.999602966261399 -0.0289096976423576 6.37812783778011e-05 -1.92779337351864e-06 3.9280457988193e-06 2.90759420137436e-05 -6.45233787163171e-06 1.99237661740696e-05 -1.92779337351864e-06 0.000119469392455986 -4.33615808023037e-06 4.09483533891571e-05 -1.75316540224632e-06 -1.49215022001645e-05 3.9280457988193e-06 -4.33615808023037e-06 1.89122476101433e-05 7.96214778446884e-07 -1.365445791573e-06 -3.09806373530057e-06 2.90759420137436e-05 4.09483533891571e-05 7.96214778446884e-07 0.00012308442268638 -8.34380582806051e-06 -5.31589641552066e-06 -6.45233787163171e-06 -1.75316540224632e-06 -1.365445791573e-06 -8.34380582806051e-06 3.91743799584257e-05 5.74009886595159e-06 1.99237661740696e-05 -1.49215022001645e-05 -3.09806373530057e-06 -5.31589641552066e-06 5.74009886595159e-06 6.67382070962047e-05 2466 2466 0 0 1 2468 2468 0 0 1 0 0 0 0 0 0 0 0 27 0 48 51 0 0 2090 +16 42 0.999972510305276 3.35486641534556e-05 -0.00741468193866075 -0.00900567117005407 3.59891891112254e-05 0.999956024309309 0.00937806762075902 -0.00191342865758135 0.00741467049454226 -0.00937807666893352 0.999928534616074 -0.0166687120934195 6.29161524969497e-05 1.03653865729044e-05 4.15720521417619e-06 1.11872753421865e-05 -6.55124968126515e-06 1.97466028048096e-05 1.03653865729044e-05 5.4010800255791e-05 -3.14813482043252e-06 6.27134084052539e-06 -1.4002316653344e-07 9.1884248363047e-06 4.15720521417619e-06 -3.14813482043252e-06 1.67695702120349e-05 -2.92271613151536e-06 -2.14977655385599e-06 -2.34192995091999e-06 1.11872753421865e-05 6.27134084052539e-06 -2.92271613151536e-06 6.33821197412301e-05 4.28452364339236e-06 5.77433990207367e-06 -6.55124968126515e-06 -1.4002316653344e-07 -2.14977655385599e-06 4.28452364339236e-06 3.49209420316999e-05 -3.99539437934395e-06 1.97466028048096e-05 9.1884248363047e-06 -2.34192995091999e-06 5.77433990207367e-06 -3.99539437934395e-06 6.75797630749651e-05 2763 2763 0 0 6 2764 2773 0 0 8 0 0 0 0 0 0 0 0 52 0 40 47 0 0 2587 +16 47 0.999992482336916 0.000448054950645684 -0.00385156025719253 -0.0123295367105289 -0.000380044492987524 0.999844321525341 0.0176405294624315 0.00801829355965594 0.00385886457872428 -0.0176389330826092 0.999836975313411 -0.0220287137042667 4.16328963244364e-05 -3.00644258186706e-06 2.62131141510849e-06 4.65924019515297e-06 -5.28195817374218e-07 2.43846387010571e-05 -3.00644258186706e-06 2.35720789606283e-05 -5.37822908854701e-06 4.93737067933901e-06 -2.05475057489436e-06 1.2014203507756e-05 2.62131141510849e-06 -5.37822908854701e-06 1.69568344963517e-05 -1.64820906374556e-06 -2.54093607051741e-06 2.8650997983437e-06 4.65924019515297e-06 4.93737067933901e-06 -1.64820906374556e-06 6.81786544473753e-05 7.57560105409761e-06 7.52354028261074e-06 -5.28195817374218e-07 -2.05475057489436e-06 -2.54093607051741e-06 7.57560105409761e-06 2.80080003604859e-05 -7.57552086406168e-06 2.43846387010571e-05 1.2014203507756e-05 2.8650997983437e-06 7.52354028261074e-06 -7.57552086406168e-06 6.25126216932849e-05 3021 3024 0 0 4 3024 3036 0 0 7 0 0 0 0 0 0 0 0 57 0 35 43 0 0 2670 +17 19 0.999998303303335 -0.000516865010923329 -0.00176811792936361 -0.00343752361017829 0.000512329592845922 0.999996580160228 -0.00256460254968956 -0.00207504050210518 0.00176943743600845 0.00256369233919811 0.999995148274605 -0.000796682486339488 3.04770641395289e-05 -3.57321892161965e-06 4.94398838172197e-06 4.63347176015599e-06 3.6594217704925e-06 4.58365641337107e-06 -3.57321892161965e-06 6.10566645835583e-05 -2.91952500554079e-06 2.09276042834875e-05 -6.38122076569661e-06 -5.61052905033355e-06 4.94398838172197e-06 -2.91952500554079e-06 1.52265972073691e-05 -1.43965127261408e-06 2.76418988908628e-06 3.9660200690121e-06 4.63347176015599e-06 2.09276042834875e-05 -1.43965127261408e-06 5.37524365262935e-05 4.97917706198192e-06 4.86628412053995e-07 3.6594217704925e-06 -6.38122076569661e-06 2.76418988908628e-06 4.97917706198192e-06 2.16603793121824e-05 7.33064575896959e-07 4.58365641337107e-06 -5.61052905033355e-06 3.9660200690121e-06 4.86628412053995e-07 7.33064575896959e-07 3.49823826897429e-05 3037 3038 0 0 9 3040 3048 0 0 9 0 0 0 0 0 0 0 0 68 0 22 39 0 0 2607 +16 48 0.99994310523261 -0.000394860948098123 -0.0106597552785174 -0.0225632594809238 0.000586292381190939 0.999838513000844 0.017961185414792 0.00432228572134124 0.0106509416959239 -0.0179664132506309 0.999781858925184 -0.0218186140071263 8.67100347954402e-05 -5.97541575278289e-07 9.10039436421485e-07 5.92021475861827e-06 -9.12932925362707e-06 4.44422440903588e-05 -5.97541575278289e-07 5.67076434256149e-05 -4.70905517772178e-07 4.28127707065696e-06 -7.80621085706205e-06 1.27812685009535e-05 9.10039436421485e-07 -4.70905517772178e-07 1.79853938729733e-05 1.66005731016111e-07 1.38968801995359e-06 1.31798706488972e-06 5.92021475861827e-06 4.28127707065696e-06 1.66005731016111e-07 7.5711766946712e-05 -5.97638647900546e-07 -4.98879957626255e-06 -9.12932925362707e-06 -7.80621085706205e-06 1.38968801995359e-06 -5.97638647900546e-07 3.23039020677343e-05 -1.07775314781312e-05 4.44422440903588e-05 1.27812685009535e-05 1.31798706488972e-06 -4.98879957626255e-06 -1.07775314781312e-05 9.44317024937394e-05 2983 2984 0 0 2 2983 2984 0 0 2 0 0 0 0 0 0 0 0 37 0 41 45 0 0 2386 +16 43 0.999996037728997 -0.000362139317530002 -0.00279166284171654 -0.00652825708066034 0.00040533055505573 0.999879994792394 0.0154865012544359 0.00423161866827424 0.00278571955664245 -0.0154875714389702 0.999876179783014 -0.0197540759427537 4.0845734199661e-05 1.51009064141889e-06 7.72386876226952e-06 1.08490602057264e-06 -2.0588337234954e-06 1.58714795280555e-05 1.51009064141889e-06 2.29277783824349e-05 -4.48679859529753e-06 -2.89871637838156e-06 -2.31457012047507e-06 6.11619825976621e-06 7.72386876226952e-06 -4.48679859529753e-06 2.14675013504075e-05 -9.34839295366634e-06 -5.29203198767608e-07 2.46441907124852e-06 1.08490602057264e-06 -2.89871637838156e-06 -9.34839295366634e-06 6.35998557960227e-05 1.10003332165033e-05 -4.2146983089274e-06 -2.0588337234954e-06 -2.31457012047507e-06 -5.29203198767608e-07 1.10003332165033e-05 3.13851029072628e-05 -1.07525612484618e-05 1.58714795280555e-05 6.11619825976621e-06 2.46441907124852e-06 -4.2146983089274e-06 -1.07525612484618e-05 4.94655224887931e-05 2839 2841 0 0 7 2840 2851 0 0 9 0 0 0 0 0 0 0 0 18 0 34 41 0 0 2649 +17 44 0.999984030437346 -0.00130188724670575 -0.0054994508705136 -0.0339785276033718 0.00145724218902764 0.999597271389481 0.0283402800957862 0.00818169252372059 0.00546034023508113 -0.0283478415457326 0.999583205423248 -0.0273985957621811 5.60492009080649e-05 -1.32236556899392e-06 3.38338254235071e-06 1.49011900047861e-05 -2.95829351435241e-06 2.85440140371517e-05 -1.32236556899392e-06 2.7552281163839e-05 -5.18796782422194e-06 8.13426073498356e-06 -2.19298707959006e-06 6.97521792133131e-06 3.38338254235071e-06 -5.18796782422194e-06 1.66560452737018e-05 -4.84253482025978e-06 1.47323471659204e-07 2.85834969729915e-06 1.49011900047861e-05 8.13426073498356e-06 -4.84253482025978e-06 0.000111679173540301 -7.39752606806255e-06 -6.00385114459296e-06 -2.95829351435241e-06 -2.19298707959006e-06 1.47323471659204e-07 -7.39752606806255e-06 3.47750140624894e-05 -3.98620242867745e-06 2.85440140371517e-05 6.97521792133131e-06 2.85834969729915e-06 -6.00385114459296e-06 -3.98620242867745e-06 6.80869544933764e-05 2760 2760 0 0 0 2760 2760 0 0 0 0 0 0 0 0 0 0 0 27 0 52 69 0 0 2122 +16 46 0.999951960018335 -0.000640030932888147 -0.00978100280621373 -0.0295227549156303 0.00072025315989908 0.999966115776233 0.00820052039681752 0.00396912572708281 0.00977542279780624 -0.00820717124214617 0.999918538406668 -0.0184148269437722 2.88045666924781e-05 4.00696395297178e-06 8.11317735412557e-07 -7.83949035396407e-07 -4.31388905376177e-06 2.64091081222578e-05 4.00696395297178e-06 4.52408238979848e-05 -4.81513048257299e-06 1.128385232716e-05 6.62093010563598e-07 1.14066699056972e-05 8.11317735412557e-07 -4.81513048257299e-06 1.49873990743665e-05 -1.48365871857507e-06 -1.98161065412143e-07 -5.9175825689466e-07 -7.83949035396407e-07 1.128385232716e-05 -1.48365871857507e-06 7.50320146977386e-05 1.29101656434915e-06 -2.8466545039917e-06 -4.31388905376177e-06 6.62093010563598e-07 -1.98161065412143e-07 1.29101656434915e-06 2.85761808855169e-05 -9.36408493363211e-06 2.64091081222578e-05 1.14066699056972e-05 -5.9175825689466e-07 -2.8466545039917e-06 -9.36408493363211e-06 7.59451234992348e-05 2971 2970 0 0 0 2976 2982 0 0 2 0 0 0 0 0 0 0 0 46 0 46 53 0 0 2923 +16 52 0.999947033707994 0.00363606038825683 -0.00962854316280433 -0.00327060145936179 -0.00339930956384258 0.999694254498653 0.0244916764814313 0.00969137731420794 0.00971465249374392 -0.0244576488492839 0.999653664495705 -0.0275327752772393 7.33346693185815e-05 2.3179026994122e-06 1.13591920411407e-05 7.37690986562389e-06 -2.00713684492396e-05 4.24834234020292e-05 2.3179026994122e-06 4.39841072080333e-05 -4.29029520756293e-06 4.88959242600921e-06 -2.42946385698054e-06 7.15562221097761e-06 1.13591920411407e-05 -4.29029520756293e-06 1.99835508257364e-05 -2.94695455610911e-06 -5.20613814863827e-06 4.42120090580543e-06 7.37690986562389e-06 4.88959242600921e-06 -2.94695455610911e-06 6.68280225427295e-05 4.35171067776664e-06 1.26005274224601e-05 -2.00713684492396e-05 -2.42946385698054e-06 -5.20613814863827e-06 4.35171067776664e-06 4.2354919568918e-05 -1.7033087737577e-05 4.24834234020292e-05 7.15562221097761e-06 4.42120090580543e-06 1.26005274224601e-05 -1.7033087737577e-05 7.25441181488776e-05 2884 2893 0 0 3 2884 2893 0 0 3 0 0 0 0 0 0 0 0 62 0 35 37 0 0 2748 +16 51 0.99998600776073 8.03945617889789e-06 -0.00529001116487017 -0.00235027337813368 2.59618177048999e-05 0.999979344046221 0.00642734835476132 -0.000371736490770789 0.00528995356702951 -0.00642739576007078 0.999965351887255 -0.0148879463477433 2.37931668897875e-05 -1.28373431453943e-06 1.65935855902805e-06 7.17660168991518e-06 7.69124967758302e-07 1.42970625986611e-05 -1.28373431453943e-06 3.40058493619279e-05 -3.4767222614473e-06 3.31858316241037e-06 -1.96182819043038e-06 1.62631494491329e-06 1.65935855902805e-06 -3.4767222614473e-06 1.51294527478286e-05 -1.29072521161837e-06 3.48540450521848e-07 3.24943594375896e-06 7.17660168991518e-06 3.31858316241037e-06 -1.29072521161837e-06 5.99377641535249e-05 -4.24869915519015e-06 6.68781076849471e-06 7.69124967758302e-07 -1.96182819043038e-06 3.48540450521848e-07 -4.24869915519015e-06 2.96625061973105e-05 -6.49750050171563e-06 1.42970625986611e-05 1.62631494491329e-06 3.24943594375896e-06 6.68781076849471e-06 -6.49750050171563e-06 5.51092388075154e-05 2915 2916 0 0 11 2915 2926 0 0 12 0 0 0 0 0 0 0 0 71 0 33 40 0 0 3098 +17 47 0.999941858026674 0.000226081125115237 -0.0107809764625903 -0.0178547128805323 -2.06577695897663e-05 0.999818521597748 0.0190505496863174 0.00684532685394348 0.0107833269179142 -0.019049219338838 0.999760394846266 -0.0218709890017398 6.16094616439908e-05 4.1745123103858e-07 -5.34916812651446e-07 1.22840857752701e-05 -1.25596008344521e-05 3.38717573133504e-05 4.1745123103858e-07 0.000142824328513254 -1.73642239157552e-05 7.52364114431844e-05 1.5207934150309e-05 -2.62006340713503e-06 -5.34916812651446e-07 -1.73642239157552e-05 2.00707296784939e-05 -1.30817894731849e-05 -5.97805482700154e-06 6.46445563254918e-06 1.22840857752701e-05 7.52364114431844e-05 -1.30817894731849e-05 0.000130322594877502 1.75399991912604e-05 -3.53262433811304e-06 -1.25596008344521e-05 1.5207934150309e-05 -5.97805482700154e-06 1.75399991912604e-05 3.82344429796154e-05 -1.8452561390953e-05 3.38717573133504e-05 -2.62006340713503e-06 6.46445563254918e-06 -3.53262433811304e-06 -1.8452561390953e-05 8.49910616662655e-05 2714 2714 0 0 2 2719 2731 0 0 4 0 0 0 0 0 0 0 0 46 0 31 40 0 0 2661 +17 20 0.99999041868612 0.000344772901662581 0.00436390508653228 0.00216419685070684 -0.000346671769751667 0.999999845565674 0.000434381528752173 -0.00118940253941016 -0.00436375464961544 -0.000435890209505779 0.999990383776306 -0.0028638096960429 3.37214965856879e-05 -5.59230328448428e-06 3.98395532301821e-06 1.48296423609413e-06 2.86276770180943e-06 5.46432256290907e-06 -5.59230328448428e-06 3.70040519072804e-05 -2.76833404365637e-06 8.17757578044746e-06 3.18781062627077e-06 -6.95911078271001e-06 3.98395532301821e-06 -2.76833404365637e-06 1.48958148403819e-05 -1.49136213503211e-06 3.87528164589466e-06 2.50853064885904e-06 1.48296423609413e-06 8.17757578044746e-06 -1.49136213503211e-06 4.34179961060366e-05 2.35216855259728e-06 -2.72827435086783e-06 2.86276770180943e-06 3.18781062627077e-06 3.87528164589466e-06 2.35216855259728e-06 2.31178713126684e-05 -5.20539989811633e-07 5.46432256290907e-06 -6.95911078271001e-06 2.50853064885904e-06 -2.72827435086783e-06 -5.20539989811633e-07 3.4249674654909e-05 2906 2907 0 0 9 2907 2908 0 0 11 0 0 0 0 0 0 0 0 77 0 31 46 0 0 2642 +17 48 0.999999964043377 -0.000120566209493212 -0.000239535038450396 -0.0151287718502141 0.000125236148165811 0.999808041719182 0.0195924482789242 0.00545608579841036 0.000237126870492538 -0.0195924775728915 0.999808020868708 -0.0238202349024183 6.90187180741746e-05 1.93704275182978e-06 2.10839689314906e-06 2.1680338780971e-05 -6.59572274396635e-06 3.48604587250633e-05 1.93704275182978e-06 4.91768208069281e-05 -4.97510841976877e-06 9.26906513071082e-06 5.92435467326955e-06 1.13073163718635e-05 2.10839689314906e-06 -4.97510841976877e-06 1.89996995912403e-05 -5.55297598006405e-06 -2.31363856795127e-06 1.10034149556834e-06 2.1680338780971e-05 9.26906513071082e-06 -5.55297598006405e-06 0.00010275887476144 7.58956457230772e-06 -7.18308007746821e-07 -6.59572274396635e-06 5.92435467326955e-06 -2.31363856795127e-06 7.58956457230772e-06 3.93971136909747e-05 -9.45534254558782e-06 3.48604587250633e-05 1.13073163718635e-05 1.10034149556834e-06 -7.18308007746821e-07 -9.45534254558782e-06 6.95535529072196e-05 2805 2804 0 0 4 2805 2804 0 0 4 0 0 0 0 0 0 0 0 38 0 33 51 0 0 2400 +17 49 0.999949204516358 -0.000116392694759324 -0.0100784343944912 -0.0183193366509851 0.000335967832642991 0.99976256386506 0.0217876804542899 0.00671722771647667 0.0100735054831416 -0.0217899597682837 0.999711819546302 -0.0160204310532747 9.96426136800037e-05 -3.78064606658669e-06 4.35365276288822e-06 1.41189358630099e-05 -2.20018337722176e-05 5.77831644095147e-05 -3.78064606658669e-06 6.22788275766256e-05 -1.29270227115004e-05 1.77872597340355e-05 4.80684919019616e-06 8.84255880852064e-06 4.35365276288822e-06 -1.29270227115004e-05 2.03600530064311e-05 -3.44863245919105e-06 -3.40777713699294e-06 3.19691139061099e-06 1.41189358630099e-05 1.77872597340355e-05 -3.44863245919105e-06 8.17630230104006e-05 7.34950184354872e-07 -1.08783949357561e-06 -2.20018337722176e-05 4.80684919019616e-06 -3.40777713699294e-06 7.34950184354872e-07 4.48407741130296e-05 -1.96341754292249e-05 5.77831644095147e-05 8.84255880852064e-06 3.19691139061099e-06 -1.08783949357561e-06 -1.96341754292249e-05 9.55926873978337e-05 2783 2783 0 0 0 2789 2806 0 0 3 0 0 0 0 0 0 0 0 48 0 20 23 0 0 2408 +17 21 0.999994948243098 -3.07671992945839e-05 0.0031784495691616 0.000314365832758349 3.31585759775365e-05 0.999999716455933 -0.000752322113569058 -0.00177618712799652 -0.00317842552108668 0.000752423705882158 0.99999466572066 -0.0010800049806426 4.01496098590546e-05 -6.41906132080526e-06 1.42742822012277e-06 4.46598475728513e-06 2.26744745328908e-06 5.80188694313898e-06 -6.41906132080526e-06 6.2118467807869e-05 -7.47809974338886e-06 1.57459389628144e-05 3.83404360770408e-07 -1.47994553400185e-05 1.42742822012277e-06 -7.47809974338886e-06 1.70326600365861e-05 -3.87131274113238e-06 1.10767466605336e-07 6.44292477523985e-06 4.46598475728513e-06 1.57459389628144e-05 -3.87131274113238e-06 6.18225630711536e-05 7.15789823892957e-06 -5.77066740455224e-06 2.26744745328908e-06 3.83404360770408e-07 1.10767466605336e-07 7.15789823892957e-06 2.32640367004096e-05 -3.14477558500643e-06 5.80188694313898e-06 -1.47994553400185e-05 6.44292477523985e-06 -5.77066740455224e-06 -3.14477558500643e-06 4.57581142418347e-05 2622 2625 0 0 7 2624 2628 0 0 11 0 0 0 0 0 0 0 0 74 0 32 47 0 0 2680 +17 45 0.999997224923333 -0.000444876007637094 -0.00231348891748849 -0.010567238843383 0.000454761120022624 0.999990762815686 0.00427404675055458 0.00162187547400379 0.00231156612651011 -0.00427508697455844 0.999988190076964 -0.0127936552700633 4.48590400204815e-05 -7.00695606547317e-06 4.99108422707993e-06 4.62271561512668e-06 -4.92559930191239e-06 2.0613946104172e-05 -7.00695606547317e-06 1.73733284489827e-05 -5.34661682754922e-06 2.56067042939553e-06 -1.37467897207275e-06 7.44721985521737e-06 4.99108422707993e-06 -5.34661682754922e-06 1.73193194718105e-05 6.05819855248575e-07 -4.03242259043189e-06 7.91071175904635e-07 4.62271561512668e-06 2.56067042939553e-06 6.05819855248575e-07 6.22328262063831e-05 -8.50611301338454e-06 4.57387508437988e-06 -4.92559930191239e-06 -1.37467897207275e-06 -4.03242259043189e-06 -8.50611301338454e-06 4.47616868102707e-05 -7.39017437871465e-06 2.0613946104172e-05 7.44721985521737e-06 7.91071175904635e-07 4.57387508437988e-06 -7.39017437871465e-06 5.86154341861285e-05 2942 2942 0 0 4 2947 2965 0 0 7 0 0 0 0 0 0 0 0 28 0 17 19 0 0 2313 +17 50 0.999999316766151 -0.000900469756802911 0.000745400194038928 -0.00465337221387504 0.000896241255730415 0.99998361539334 0.00565382140464691 0.000239966257010926 -0.000750479076135194 -0.00565314948335882 0.999983739208831 -0.0140073678814572 2.89809277155683e-05 -5.59597868097226e-07 6.24449521728592e-06 -1.91259506926939e-06 -6.04459915519294e-07 1.97688918923764e-05 -5.59597868097226e-07 5.40269039973526e-05 -4.87752417486832e-06 1.42384647675747e-05 -4.97198327512475e-06 3.03388960604977e-06 6.24449521728592e-06 -4.87752417486832e-06 2.02883540332762e-05 -9.56286325332546e-06 -1.83128615569632e-06 3.45175746120257e-06 -1.91259506926939e-06 1.42384647675747e-05 -9.56286325332546e-06 9.69797824108694e-05 1.8014779814746e-05 -1.82553114500042e-05 -6.04459915519294e-07 -4.97198327512475e-06 -1.83128615569632e-06 1.8014779814746e-05 3.49991404591588e-05 -1.39721902298722e-05 1.97688918923764e-05 3.03388960604977e-06 3.45175746120257e-06 -1.82553114500042e-05 -1.39721902298722e-05 6.49356454664374e-05 2867 2870 0 0 8 2869 2873 0 0 12 0 0 0 0 0 0 0 0 56 0 33 48 0 0 3080 +17 43 0.99999737673413 0.000315931277044289 -0.00226863665814491 -0.00646357346945458 -0.000290152343428649 0.999935493089329 0.0113545352973253 0.000930281688797538 0.00227207756823939 -0.0113538472611176 0.999932961660878 -0.0164259434532988 4.8599060316419e-05 -6.76462604829449e-06 3.26618364149125e-06 1.06559134080768e-06 -6.56054491030694e-06 3.10063743642176e-05 -6.76462604829449e-06 3.0611727840114e-05 -5.91858496776745e-06 1.42598014273678e-06 -2.39407214308099e-07 -1.74345771140374e-07 3.26618364149125e-06 -5.91858496776745e-06 1.72970121686622e-05 -6.47913945744963e-06 9.11359600779561e-08 2.84276144223078e-07 1.06559134080768e-06 1.42598014273678e-06 -6.47913945744963e-06 6.54167541581582e-05 1.91190154825827e-05 1.78210082906688e-06 -6.56054491030694e-06 -2.39407214308099e-07 9.11359600779561e-08 1.91190154825827e-05 3.36553334672611e-05 -9.01646443467545e-06 3.10063743642176e-05 -1.74345771140374e-07 2.84276144223078e-07 1.78210082906688e-06 -9.01646443467545e-06 6.95958751735626e-05 3030 3030 0 0 6 3033 3043 0 0 7 0 0 0 0 0 0 0 0 18 0 25 39 0 0 2643 +18 20 0.99999206517515 0.000280217675475429 -0.00397379727618314 -0.000349437249042486 -0.000283141576553216 0.999999689617813 -0.000735251742975256 -0.00273989474307965 0.00397359001225295 0.000736371056107137 0.9999918341367 0.000445557826466591 2.76301643566836e-05 3.59357814257527e-06 5.56879842009209e-06 8.02830213488697e-06 2.0915338172981e-06 3.4360078345731e-06 3.59357814257527e-06 5.76088659183179e-05 -2.83354827841832e-06 1.82954094858685e-05 -1.79710251158863e-06 -1.98615693942322e-06 5.56879842009209e-06 -2.83354827841832e-06 1.66413418422803e-05 -1.67528894211337e-06 2.0273625987596e-06 9.08622146783997e-07 8.02830213488697e-06 1.82954094858685e-05 -1.67528894211337e-06 5.15243850824205e-05 1.6581281668459e-06 1.85280141160412e-06 2.0915338172981e-06 -1.79710251158863e-06 2.0273625987596e-06 1.6581281668459e-06 2.36671098322615e-05 -4.75857086095935e-07 3.4360078345731e-06 -1.98615693942322e-06 9.08622146783997e-07 1.85280141160412e-06 -4.75857086095935e-07 2.90968508355899e-05 2901 2908 0 0 14 2901 2915 0 0 22 0 0 0 0 0 0 0 0 75 0 32 36 0 0 2848 +17 46 0.999999823637903 -0.000580554817175782 0.000125220871512358 -0.025197005188593 0.000579653068003899 0.999974733470026 0.00708494346277099 0.00424868309698388 -0.000129330905672184 -0.00708486962859316 0.999974893632766 -0.0186698072346441 2.95997761354281e-05 -4.51666720738621e-06 5.96778620598966e-06 6.50123849040858e-06 -3.95587892503804e-06 2.55336101523554e-05 -4.51666720738621e-06 5.28650067791037e-05 -6.22869821547604e-06 1.49242964993243e-05 5.06800287992737e-06 -4.73214399042442e-06 5.96778620598966e-06 -6.22869821547604e-06 1.90341083510275e-05 -5.14211174055435e-06 -7.48640049998343e-08 2.1055914382292e-06 6.50123849040858e-06 1.49242964993243e-05 -5.14211174055435e-06 9.12026426849959e-05 6.57446207186569e-06 -1.71666850195079e-06 -3.95587892503804e-06 5.06800287992737e-06 -7.48640049998343e-08 6.57446207186569e-06 3.28096795528236e-05 -1.74203685613288e-05 2.55336101523554e-05 -4.73214399042442e-06 2.1055914382292e-06 -1.71666850195079e-06 -1.74203685613288e-05 7.35512598767645e-05 2827 2826 0 0 0 2834 2842 0 0 1 0 0 0 0 0 0 0 0 44 0 36 46 0 0 2927 +18 22 0.999999884545807 8.51709071221254e-05 -0.000472921016949381 0.000854957191428493 -8.63487718381147e-05 0.999996893341621 -0.00249115455086643 -0.00108479751052238 0.000472707373852462 0.00249119509940119 0.99999678524219 -0.0026659041595231 2.87951337415566e-05 -8.1447316751151e-06 1.27775667011337e-06 7.81979870637159e-07 5.31105215153364e-06 -4.50331132125919e-06 -8.1447316751151e-06 1.92867969716778e-05 -3.17503369099747e-06 2.5892743891484e-07 -3.64195775451897e-06 7.59631506790355e-06 1.27775667011337e-06 -3.17503369099747e-06 1.28751728410197e-05 -7.40406129811386e-07 1.24555488920971e-06 4.54802424202774e-06 7.81979870637159e-07 2.5892743891484e-07 -7.40406129811386e-07 3.99666323035795e-05 5.57568071074477e-06 9.91166968595255e-07 5.31105215153364e-06 -3.64195775451897e-06 1.24555488920971e-06 5.57568071074477e-06 1.95023844407719e-05 -3.12704309599895e-06 -4.50331132125919e-06 7.59631506790355e-06 4.54802424202774e-06 9.91166968595255e-07 -3.12704309599895e-06 2.92762996930543e-05 3082 3087 0 0 9 3083 3090 0 0 13 0 0 0 0 0 0 0 0 57 0 9 20 0 0 2710 +18 50 0.999971963992064 -0.000277905235086311 -0.00748291377299458 -0.00787547721878323 0.00034482510380959 0.999959949168832 0.00894321831972713 -0.00045987077444314 0.00748012870888884 -0.00894554788410592 0.999932010112463 -0.013171367884805 6.45507841274798e-05 8.04117176630975e-08 3.95306111425715e-06 -2.58052465496389e-06 -3.14720726232283e-06 2.16135670851614e-05 8.04117176630975e-08 4.41586215843775e-05 -4.31071924379123e-06 2.72027821877148e-06 -1.44480663252717e-06 8.94208756045511e-06 3.95306111425715e-06 -4.31071924379123e-06 2.16989410760495e-05 -3.11257067014652e-06 -2.30372542090869e-06 1.58706357571452e-06 -2.58052465496389e-06 2.72027821877148e-06 -3.11257067014652e-06 6.1432932235142e-05 -2.49976885780338e-06 -2.1099120745468e-06 -3.14720726232283e-06 -1.44480663252717e-06 -2.30372542090869e-06 -2.49976885780338e-06 4.14203025002333e-05 -9.91679678686288e-06 2.16135670851614e-05 8.94208756045511e-06 1.58706357571452e-06 -2.1099120745468e-06 -9.91679678686288e-06 7.59905348978095e-05 2980 2988 0 0 9 2980 2995 0 0 14 0 0 0 0 0 0 0 0 58 0 34 38 0 0 2674 +18 47 0.999992472763186 0.000145169304053475 -0.00387728549901568 -0.0115997210844614 -7.71227350451459e-05 0.999846081481886 0.01754444064089 0.00637820108249883 0.00387923562721522 -0.0175440095528683 0.999838566599507 -0.0240384526891783 7.21788782413942e-05 -1.02019673299813e-05 4.15072311262211e-06 5.62014138394799e-06 -8.06551521359927e-06 4.12777953870524e-05 -1.02019673299813e-05 3.45723041131196e-05 -2.39612508335766e-06 -1.9244717147306e-07 -4.86650086847448e-06 1.85582511361808e-05 4.15072311262211e-06 -2.39612508335766e-06 2.06272055641566e-05 -3.37532672783803e-06 -6.32252739935114e-06 5.88132265113927e-06 5.62014138394799e-06 -1.9244717147306e-07 -3.37532672783803e-06 6.62333183861436e-05 6.00922746485993e-06 1.13218667665437e-05 -8.06551521359927e-06 -4.86650086847448e-06 -6.32252739935114e-06 6.00922746485993e-06 3.35211675193903e-05 -1.92758080164653e-05 4.12777953870524e-05 1.85582511361808e-05 5.88132265113927e-06 1.13218667665437e-05 -1.92758080164653e-05 9.13768212480027e-05 2776 2776 0 0 5 2781 2799 0 0 8 0 0 0 0 0 0 0 0 53 0 36 44 0 0 2769 +17 51 0.999998326039465 -0.000279765841534311 0.00180821717211156 0.000364442353592973 0.000268643873354445 0.999981064100241 0.00614811120734743 -0.000288914155467962 -0.00180990296339822 -0.00614761514918693 0.999979465328784 -0.0149037425872252 2.86343688864214e-05 -2.93910433376652e-06 5.28704057547993e-06 1.43625764143588e-06 -6.54990652003299e-07 2.49197953766373e-05 -2.93910433376652e-06 4.41153285832269e-05 -8.29770492324251e-06 1.17749969930009e-05 9.68084640597675e-07 -1.55132711176895e-07 5.28704057547993e-06 -8.29770492324251e-06 2.06778452778027e-05 -7.66670341167077e-06 -4.21412181097836e-06 7.18001479688803e-06 1.43625764143588e-06 1.17749969930009e-05 -7.66670341167077e-06 6.62127814114802e-05 1.07850889690146e-05 -9.20203588317126e-06 -6.54990652003299e-07 9.68084640597675e-07 -4.21412181097836e-06 1.07850889690146e-05 2.73231484757178e-05 -9.12685959109931e-06 2.49197953766373e-05 -1.55132711176895e-07 7.18001479688803e-06 -9.20203588317126e-06 -9.12685959109931e-06 7.18586788882384e-05 2595 2595 0 0 11 2596 2606 0 0 11 0 0 0 0 0 0 0 0 71 0 20 34 0 0 3101 +17 52 0.999806658096607 0.00336939675730309 -0.0193724957397257 -0.0120900641688711 -0.00293232674040482 0.99974151356578 0.0225456761506837 0.00665702793069905 0.0194434535404933 -0.0224845106394575 0.999558101810857 -0.0203038313363636 9.43264674266931e-05 -2.47480105339566e-06 3.35027699989729e-07 1.00431960296527e-05 -1.5847046378521e-05 7.55853962228569e-05 -2.47480105339566e-06 4.26435325673595e-05 -1.08724559771283e-05 1.65922331370483e-05 -2.08018582337247e-06 6.66658863053441e-06 3.35027699989729e-07 -1.08724559771283e-05 1.7661761109597e-05 -4.45877912960124e-06 1.07292067755309e-06 -3.35215274538051e-06 1.00431960296527e-05 1.65922331370483e-05 -4.45877912960124e-06 7.78092037897353e-05 -1.73943179035051e-06 1.25745557451801e-05 -1.5847046378521e-05 -2.08018582337247e-06 1.07292067755309e-06 -1.73943179035051e-06 3.89819483952809e-05 -2.06512012820892e-05 7.55853962228569e-05 6.66658863053441e-06 -3.35215274538051e-06 1.25745557451801e-05 -2.06512012820892e-05 0.000120807896518181 2886 2885 0 0 1 2886 2885 0 0 1 0 0 0 0 0 0 0 0 50 0 40 56 0 0 2707 +18 52 0.999944800129313 0.00380531087100879 -0.00979368692187629 -0.000669776606599354 -0.00363546760018324 0.999843701965595 0.0173018789460211 0.00552980297478294 0.00985799521590299 -0.0172653192530498 0.999802344806919 -0.0265621168133505 6.97560952699253e-05 3.08030742245894e-06 3.72466397001299e-06 1.2086951465269e-05 -9.8500567102514e-06 3.64889129893406e-05 3.08030742245894e-06 4.86108917677135e-05 -4.01479194333436e-06 1.46171647181554e-05 -1.99242177683658e-06 1.46655339329073e-05 3.72466397001299e-06 -4.01479194333436e-06 2.01850325703013e-05 -1.09869661185926e-05 -2.22652629078049e-06 -1.08110861446622e-07 1.2086951465269e-05 1.46171647181554e-05 -1.09869661185926e-05 8.97686698454172e-05 8.85728161686789e-06 1.39769633234366e-05 -9.8500567102514e-06 -1.99242177683658e-06 -2.22652629078049e-06 8.85728161686789e-06 4.04602641034983e-05 -1.37847693505275e-05 3.64889129893406e-05 1.46655339329073e-05 -1.08110861446622e-07 1.39769633234366e-05 -1.37847693505275e-05 9.27298856633186e-05 2876 2885 0 0 5 2879 2892 0 0 14 0 0 0 0 0 0 0 0 58 0 35 37 0 0 2730 +18 49 0.999997982224627 -2.03101856940334e-06 0.00200886598570333 -0.00615909355220366 -3.26717219107999e-05 0.999850782300586 0.0172746075343295 0.00816449757963726 -0.00200860131239119 -0.0172746383111627 0.999848764759944 -0.02574379964536 6.37946504121783e-05 1.84967379805117e-07 6.66827444148039e-06 -2.59412279171396e-06 -1.26031219492119e-05 5.30518680903492e-05 1.84967379805117e-07 5.16143380367729e-05 -1.37158786316262e-06 5.73358208955884e-06 2.92435286840765e-06 1.36546603420958e-05 6.66827444148039e-06 -1.37158786316262e-06 1.96957004322559e-05 -2.98660661601027e-06 -6.17788527336648e-06 5.37017177964848e-06 -2.59412279171396e-06 5.73358208955884e-06 -2.98660661601027e-06 6.53741562910283e-05 1.05504378338638e-05 -1.09791312977676e-05 -1.26031219492119e-05 2.92435286840765e-06 -6.17788527336648e-06 1.05504378338638e-05 3.39821864772647e-05 -2.0366428050287e-05 5.30518680903492e-05 1.36546603420958e-05 5.37017177964848e-06 -1.09791312977676e-05 -2.0366428050287e-05 0.000102544579516591 2742 2744 0 0 4 2745 2763 0 0 8 0 0 0 0 0 0 0 0 57 0 11 14 0 0 2823 +18 21 0.999999318572671 -0.000816861279041135 -0.000834021488779314 -0.000985818973651537 0.000816425576755068 0.999999530159626 -0.000522618220540204 0.000709265752801428 0.000834448003510427 0.000521936947938863 0.999999515639059 -0.00178630496166485 2.24698396043397e-05 -9.05017109839042e-06 1.57942284179525e-06 6.14174747036399e-06 1.85068357051618e-06 -1.17864460181363e-06 -9.05017109839042e-06 2.35228156593951e-05 -1.07772152561448e-06 1.74334185066799e-06 -1.82808992587545e-06 7.48095191607762e-06 1.57942284179525e-06 -1.07772152561448e-06 1.36599333352122e-05 1.63963163694616e-06 4.41940082256472e-07 2.84029678854661e-06 6.14174747036399e-06 1.74334185066799e-06 1.63963163694616e-06 3.6148925782749e-05 6.63924425985323e-07 1.6152330303747e-06 1.85068357051618e-06 -1.82808992587545e-06 4.41940082256472e-07 6.63924425985323e-07 1.86957305548141e-05 -2.56444581796896e-06 -1.17864460181363e-06 7.48095191607762e-06 2.84029678854661e-06 1.6152330303747e-06 -2.56444581796896e-06 2.44222775039171e-05 2777 2787 0 0 9 2778 2793 0 0 18 0 0 0 0 0 0 0 0 76 0 29 33 0 0 2876 +18 44 0.999950114298155 -0.000354869736995682 -0.00998213316765613 -0.0310035785756219 0.000559620669770307 0.999789359217269 0.0205164329411568 0.00268870619180677 0.00997274986215045 -0.0205209956725492 0.999739682615827 -0.0271999334542895 5.86001402973431e-05 1.02070248646389e-05 -1.85852268916258e-07 1.32807592835134e-05 -7.41289614373781e-06 4.98120157301734e-05 1.02070248646389e-05 0.000105965089220655 -3.36026325474987e-07 4.38374666720727e-05 -1.02859461585196e-05 -1.91128067130314e-06 -1.85852268916258e-07 -3.36026325474987e-07 1.62761021417431e-05 2.45602015613502e-06 3.77546893001708e-07 -3.94884431968182e-06 1.32807592835134e-05 4.38374666720727e-05 2.45602015613502e-06 0.00011411526367289 -1.10435179672627e-05 -3.08369886625347e-06 -7.41289614373781e-06 -1.02859461585196e-05 3.77546893001708e-07 -1.10435179672627e-05 3.32698037578528e-05 -9.03920406275068e-06 4.98120157301734e-05 -1.91128067130314e-06 -3.94884431968182e-06 -3.08369886625347e-06 -9.03920406275068e-06 9.969309372703e-05 2698 2698 0 0 2 2703 2717 0 0 2 0 0 0 0 0 0 0 0 27 0 48 51 0 0 2542 +19 23 0.999998949849097 1.91917998138669e-05 0.00144911434289155 6.91187506590573e-05 -1.49156163161291e-05 0.99999564612846 -0.00295084761511795 -0.00361683651002909 -0.00144916466571057 0.00295082290184913 0.999994596268387 0.00273752343764535 3.61362862952866e-05 -2.49886129461816e-06 4.52824062365116e-06 1.6046495100428e-06 -5.09398613613671e-06 1.94191155856301e-06 -2.49886129461816e-06 4.35538257521997e-05 -2.52330867401251e-06 9.87165252756265e-06 -2.86188339037412e-06 -2.61513632389437e-06 4.52824062365116e-06 -2.52330867401251e-06 1.31044703780423e-05 -2.31179983007573e-07 2.96065064946571e-06 3.96985344643867e-06 1.6046495100428e-06 9.87165252756265e-06 -2.31179983007573e-07 5.22846264895153e-05 -5.59257343590089e-07 -1.79124100333737e-06 -5.09398613613671e-06 -2.86188339037412e-06 2.96065064946571e-06 -5.59257343590089e-07 2.49620260409568e-05 -1.17493677304038e-06 1.94191155856301e-06 -2.61513632389437e-06 3.96985344643867e-06 -1.79124100333737e-06 -1.17493677304038e-06 3.85342690172483e-05 2835 2845 0 0 9 2837 2852 0 0 15 0 0 0 0 0 0 0 0 63 0 13 16 0 0 2803 +18 48 0.999955081103184 0.00020192453923607 -0.00947602249917339 -0.0189618208617893 -4.66671694375424e-05 0.999865811567817 0.0163815957710631 0.00427524854439394 0.00947805877274892 -0.0163804177087054 0.999820908121844 -0.0254752719126815 4.46611466631859e-05 3.26491109850084e-06 2.27724251512581e-06 6.28759002195895e-06 -7.08941068604158e-06 2.8646227752161e-05 3.26491109850084e-06 6.08984361144454e-05 -2.32329654806968e-06 8.75869872256072e-07 -3.3008427503977e-06 8.3291418350675e-06 2.27724251512581e-06 -2.32329654806968e-06 1.77387013650753e-05 -5.29408273011713e-06 -2.90676000381771e-06 1.79348651249248e-06 6.28759002195895e-06 8.75869872256072e-07 -5.29408273011713e-06 9.03087655724079e-05 5.88173092855597e-06 -6.31287714375671e-06 -7.08941068604158e-06 -3.3008427503977e-06 -2.90676000381771e-06 5.88173092855597e-06 3.45150385921297e-05 -1.23097131136823e-05 2.8646227752161e-05 8.3291418350675e-06 1.79348651249248e-06 -6.31287714375671e-06 -1.23097131136823e-05 7.56987781752537e-05 2806 2807 0 0 3 2808 2821 0 0 8 0 0 0 0 0 0 0 0 43 0 41 45 0 0 2823 +19 22 0.999999873116021 0.000227076146639549 0.000449671397598862 0.00238106569654503 -0.000227240145737607 0.999999907681096 0.000364691259485012 -0.000501531625050294 -0.000449588543399774 -0.000364793396605458 0.999999832397946 9.85284884241959e-05 2.96637929255556e-05 -9.12061653236941e-06 3.05270565689629e-06 -2.76709678861107e-06 1.27233975758586e-06 -3.66475599744018e-06 -9.12061653236941e-06 1.55923510173174e-05 -4.02814121080029e-06 -9.87471804611184e-08 -1.47723897089948e-06 4.71446666900167e-06 3.05270565689629e-06 -4.02814121080029e-06 1.15141235749832e-05 1.42752260657597e-06 3.37961490312616e-06 2.21371811802007e-06 -2.76709678861107e-06 -9.87471804611184e-08 1.42752260657597e-06 3.69084815503589e-05 3.22738410284156e-06 5.5462115028464e-06 1.27233975758586e-06 -1.47723897089948e-06 3.37961490312616e-06 3.22738410284156e-06 1.80913216585274e-05 -3.34675173949354e-06 -3.66475599744018e-06 4.71446666900167e-06 2.21371811802007e-06 5.5462115028464e-06 -3.34675173949354e-06 2.48937877438636e-05 3062 3076 0 0 15 3062 3077 0 0 21 0 0 0 0 0 0 0 0 72 0 5 8 0 0 2803 +18 45 0.999998789880785 -0.000368953719545469 -0.00151132727054618 -0.000459970307321479 0.000373166679705521 0.999996043177626 0.00278825675308049 -0.00233155073410181 0.00151029255279252 -0.00278881735593691 0.999994970744433 -0.00767564175707076 7.61782749050386e-05 -1.30663384189191e-05 7.49358612909039e-07 7.99484864345064e-06 -1.07299639108721e-05 4.043205111706e-05 -1.30663384189191e-05 5.34070088440199e-05 -2.87508782693981e-06 1.46415498065771e-05 1.04515056397187e-07 -2.83476374715656e-06 7.49358612909039e-07 -2.87508782693981e-06 1.86060244440992e-05 -2.01280349969742e-07 -3.83765406551001e-06 5.51897024649064e-07 7.99484864345064e-06 1.46415498065771e-05 -2.01280349969742e-07 8.03745085950179e-05 -1.94182388460566e-06 4.14112885287292e-06 -1.07299639108721e-05 1.04515056397187e-07 -3.83765406551001e-06 -1.94182388460566e-06 4.57906426692566e-05 -9.5479266283447e-06 4.043205111706e-05 -2.83476374715656e-06 5.51897024649064e-07 4.14112885287292e-06 -9.5479266283447e-06 7.37032376935712e-05 2853 2853 0 0 10 2853 2873 0 0 12 0 0 0 0 0 0 0 0 28 0 10 12 0 0 2329 +19 21 0.999999897474611 -0.000279785936797059 -0.000356048587954635 -0.000720162611041671 0.000279662901041305 0.999999901187856 -0.000345561775040264 0.000642320842738468 0.000356145236097662 0.00034546216603039 0.999999876908224 -0.00290091652454719 2.94014633409339e-05 -6.93407017781703e-06 4.4167932425456e-06 1.68869936996492e-06 -4.81548910504642e-07 3.80147217133908e-08 -6.93407017781703e-06 2.07277282888696e-05 -4.09682989528793e-06 3.20542520385899e-06 -2.41724720326207e-06 3.71538686232478e-06 4.4167932425456e-06 -4.09682989528793e-06 1.48498925655083e-05 -2.08786030286363e-06 -6.37758976908247e-08 3.07164506583354e-06 1.68869936996492e-06 3.20542520385899e-06 -2.08786030286363e-06 4.24940490087529e-05 1.43001986948135e-07 2.47588467880854e-06 -4.81548910504642e-07 -2.41724720326207e-06 -6.37758976908247e-08 1.43001986948135e-07 1.84756433209129e-05 -2.98052047539427e-06 3.80147217133908e-08 3.71538686232478e-06 3.07164506583354e-06 2.47588467880854e-06 -2.98052047539427e-06 2.47671063202226e-05 2761 2763 0 0 10 2761 2777 0 0 16 0 0 0 0 0 0 0 0 71 0 23 27 0 0 2704 +19 49 0.999998429404656 -0.00107692143842028 0.00140763220930608 -0.00999661203823704 0.00105002750903264 0.999819523061013 0.0189688889574251 0.00738724832677754 -0.00142780616733499 -0.0189673811124341 0.999819083546261 -0.0256331059311838 5.25587799186779e-05 -8.59827422437976e-06 8.62082754820042e-06 -8.56853124165281e-06 -5.92962058375627e-06 2.95948504181335e-05 -8.59827422437976e-06 3.39707550386471e-05 -5.05989641364251e-06 3.7242673332731e-06 3.04824364658152e-06 -4.70925034767698e-06 8.62082754820042e-06 -5.05989641364251e-06 2.09242325113926e-05 -6.75539136538947e-06 -4.05186585140352e-06 3.02924524626748e-06 -8.56853124165281e-06 3.7242673332731e-06 -6.75539136538947e-06 7.73943400095061e-05 1.24217069610175e-05 -9.67709431247029e-06 -5.92962058375627e-06 3.04824364658152e-06 -4.05186585140352e-06 1.24217069610175e-05 3.34040207818238e-05 -1.16204526074848e-05 2.95948504181335e-05 -4.70925034767698e-06 3.02924524626748e-06 -9.67709431247029e-06 -1.16204526074848e-05 8.19511263330892e-05 2731 2743 0 0 5 2733 2750 0 0 14 0 0 0 0 0 0 0 0 59 0 13 16 0 0 2632 +19 50 0.999971280381677 -5.95603243904494e-05 -0.00757857931263033 -0.0128122867348025 0.000174379819213454 0.999885205267497 0.0151507715596906 0.00337791285487614 0.00757680694677653 -0.0151516579866046 0.999856499332153 -0.0149358572407944 6.77303187089738e-05 -1.64999411908004e-06 5.01071196124361e-06 9.21139577117721e-06 -1.35355592048509e-05 2.84173763540348e-05 -1.64999411908004e-06 4.09184383920339e-05 -6.95727263801157e-06 2.4777134904701e-06 1.89025556895626e-06 3.71344945327799e-06 5.01071196124361e-06 -6.95727263801157e-06 1.91441584047235e-05 -6.43080126286796e-06 -9.59827073997133e-07 1.88964743927763e-06 9.21139577117721e-06 2.4777134904701e-06 -6.43080126286796e-06 8.45770817301896e-05 -8.10080191568907e-08 1.04043565670847e-05 -1.35355592048509e-05 1.89025556895626e-06 -9.59827073997133e-07 -8.10080191568907e-08 4.25363232335791e-05 -1.357291773465e-05 2.84173763540348e-05 3.71344945327799e-06 1.88964743927763e-06 1.04043565670847e-05 -1.357291773465e-05 7.2353243035717e-05 2982 2983 0 0 5 2985 2999 0 0 8 0 0 0 0 0 0 0 0 55 0 31 35 0 0 2785 +18 51 0.999976363747542 -0.000305653611793593 -0.0068686623234101 -0.00621879825479924 0.00037599781841827 0.999947474872177 0.0102423689836332 -0.00127094247982704 0.00686517092897042 -0.0102447094944632 0.999923954786308 -0.0146505142241114 6.47510991192904e-05 -1.24043344375344e-08 5.4154137042279e-06 -5.09465317631746e-07 -6.56261816808672e-06 3.22757304983821e-05 -1.24043344375344e-08 4.91334237027188e-05 -6.28853257068933e-06 2.75591592466782e-06 -1.7868897638768e-06 3.86080363185877e-06 5.4154137042279e-06 -6.28853257068933e-06 2.16492002800096e-05 -1.95497609370323e-06 -1.94250185301011e-06 2.23218705380791e-06 -5.09465317631746e-07 2.75591592466782e-06 -1.95497609370323e-06 8.2174460718468e-05 3.22060430780198e-06 -8.91952645011223e-06 -6.56261816808672e-06 -1.7868897638768e-06 -1.94250185301011e-06 3.22060430780198e-06 3.32403614882962e-05 -6.77366261175509e-06 3.22757304983821e-05 3.86080363185877e-06 2.23218705380791e-06 -8.91952645011223e-06 -6.77366261175509e-06 8.34437825100407e-05 2673 2672 0 0 8 2677 2694 0 0 10 0 0 0 0 0 0 0 0 64 0 36 43 0 0 2696 +18 46 0.999949705161871 -0.0004942085760996 -0.0100171305557563 -0.0300504722404431 0.000621054492117712 0.999919618673189 0.012663746830287 0.0046657007868334 0.0100100668332223 -0.0126693310931198 0.999869634808282 -0.0253154514991473 8.31916535130804e-05 4.41355171298713e-06 1.8510822670458e-06 1.1175665443478e-05 -1.14280927863318e-05 4.22134195064236e-05 4.41355171298713e-06 4.70308326616406e-05 -3.33290312679934e-06 8.71526793767153e-06 -2.91857354026805e-07 9.1062199196416e-06 1.8510822670458e-06 -3.33290312679934e-06 1.72134498655381e-05 -3.71357492500231e-06 -3.37835039774108e-07 1.76609507321501e-06 1.1175665443478e-05 8.71526793767153e-06 -3.71357492500231e-06 8.34958228905297e-05 -9.05355661482011e-06 3.88298162212046e-06 -1.14280927863318e-05 -2.91857354026805e-07 -3.37835039774108e-07 -9.05355661482011e-06 3.55614161778913e-05 -1.15883850002656e-05 4.22134195064236e-05 9.1062199196416e-06 1.76609507321501e-06 3.88298162212046e-06 -1.15883850002656e-05 7.97252520120617e-05 2794 2793 0 0 0 2806 2822 0 0 2 0 0 0 0 0 0 0 0 42 0 49 56 0 0 2538 +19 47 0.999989083747759 -2.07676823277889e-05 -0.0046724676586892 -0.0140217569292388 0.000100971469915209 0.999852655008575 0.0171656073899634 0.00660114487141938 0.00467142270410086 -0.0171658917917909 0.999841742461732 -0.0271406864454782 8.76992219079286e-05 -2.56537038510728e-06 -9.03017782869132e-07 6.94960024005628e-06 -1.81861603837775e-05 5.60345837742299e-05 -2.56537038510728e-06 3.32637706261461e-05 -2.84157325435608e-06 2.50154457819394e-06 -2.29026367415648e-07 1.51113303075092e-05 -9.03017782869132e-07 -2.84157325435608e-06 1.57016910696972e-05 -2.69122965154063e-06 -8.7293561535915e-07 3.02965644051236e-06 6.94960024005628e-06 2.50154457819394e-06 -2.69122965154063e-06 7.35117192101481e-05 1.31752399469055e-06 1.60884012926953e-06 -1.81861603837775e-05 -2.29026367415648e-07 -8.7293561535915e-07 1.31752399469055e-06 3.06818980755389e-05 -1.7565206486562e-05 5.60345837742299e-05 1.51113303075092e-05 3.02965644051236e-06 1.60884012926953e-06 -1.7565206486562e-05 8.7550551673475e-05 2777 2779 0 0 3 2781 2803 0 0 6 0 0 0 0 0 0 0 0 57 0 17 20 0 0 2556 +19 45 0.999995124512959 -0.000531138832879781 -0.00307714833125677 -0.0100174523660478 0.000549552674161535 0.99998193088807 0.00598630848071967 -0.0012526849005238 0.00307391316901944 -0.00598797034964448 0.99997734737789 -0.0126431431410083 5.68798172244316e-05 -9.74872178877119e-06 7.58476032896928e-06 7.02326746960143e-06 -1.16104363200939e-05 4.07125548416661e-05 -9.74872178877119e-06 4.53611506214313e-05 -3.37287190980567e-06 8.86240553842961e-06 -5.22054164332402e-06 4.21452976636489e-06 7.58476032896928e-06 -3.37287190980567e-06 1.91431371325996e-05 -4.01175694268482e-06 -4.25694328488829e-06 2.70809889356202e-06 7.02326746960143e-06 8.86240553842961e-06 -4.01175694268482e-06 8.98422395043094e-05 -6.80410882352062e-06 6.90351801328487e-06 -1.16104363200939e-05 -5.22054164332402e-06 -4.25694328488829e-06 -6.80410882352062e-06 5.10140687965464e-05 -1.60764473598942e-05 4.07125548416661e-05 4.21452976636489e-06 2.70809889356202e-06 6.90351801328487e-06 -1.60764473598942e-05 9.60814875181297e-05 2847 2860 0 0 4 2848 2865 0 0 12 0 0 0 0 0 0 0 0 28 0 16 19 0 0 2537 +19 48 0.999936737110361 -0.000352932862714255 -0.0112426516213151 -0.0230746978453815 0.000544832906557589 0.999854140912405 0.0170704439725565 0.00450528597852874 0.0112349870577485 -0.0170754894135037 0.999791079539671 -0.0291642310078969 6.80558833896433e-05 5.34036764721001e-07 -1.88027856523146e-06 8.92261758238341e-06 -9.65005039116309e-06 5.16487567933837e-05 5.34036764721001e-07 6.94294790276002e-05 -6.6964262298461e-07 2.16398711617814e-05 -1.10691813284547e-06 3.20965849807826e-05 -1.88027856523146e-06 -6.6964262298461e-07 1.61305795075308e-05 2.62350040923274e-06 -2.41937097929637e-06 2.04083376587393e-06 8.92261758238341e-06 2.16398711617814e-05 2.62350040923274e-06 8.23038659104308e-05 9.16671236297477e-06 2.84894963895868e-05 -9.65005039116309e-06 -1.10691813284547e-06 -2.41937097929637e-06 9.16671236297477e-06 3.2016077077015e-05 -1.1130821590597e-05 5.16487567933837e-05 3.20965849807826e-05 2.04083376587393e-06 2.84894963895868e-05 -1.1130821590597e-05 0.000123924364222952 2781 2780 0 0 2 2782 2795 0 0 2 0 0 0 0 0 0 0 0 39 0 38 42 0 0 2661 +19 51 0.999969163664816 1.83138754986468e-05 -0.00785311301902697 -0.0085732219047914 0.000122071615974903 0.999840211942429 0.0178755610104646 0.00300588709276426 0.00785218555615059 -0.0178759684358703 0.999809378298919 -0.0158757537973096 6.38056522882639e-05 -1.31691931701425e-06 2.20189846585364e-06 1.10984241919728e-05 -1.21684756739871e-05 3.37209571620207e-05 -1.31691931701425e-06 4.88122036912321e-05 -9.21081740955391e-06 8.07897616896714e-06 7.22359877318457e-07 9.70789086607254e-07 2.20189846585364e-06 -9.21081740955391e-06 2.00132557989329e-05 -2.71749241679289e-06 -1.82231248541607e-06 1.28236652846134e-06 1.10984241919728e-05 8.07897616896714e-06 -2.71749241679289e-06 7.88751036369369e-05 -5.70759549831578e-06 1.14628227130275e-05 -1.21684756739871e-05 7.22359877318457e-07 -1.82231248541607e-06 -5.70759549831578e-06 3.51294502471566e-05 -1.15955430030081e-05 3.37209571620207e-05 9.70789086607254e-07 1.28236652846134e-06 1.14628227130275e-05 -1.15955430030081e-05 7.63800424201186e-05 2653 2653 0 0 4 2657 2678 0 0 9 0 0 0 0 0 0 0 0 68 0 14 16 0 0 2794 +19 52 0.999922336659475 0.00375752950195732 -0.0118828288508331 -0.0045122411598856 -0.00350316386061744 0.999765818569376 0.0213549962133413 0.0084843803966822 0.0119602881412588 -0.0213117102164064 0.999701336657719 -0.0338735176184739 7.3754519047566e-05 -3.93757137066126e-06 5.87468578677135e-06 8.581084247593e-06 -1.24045983529495e-05 3.89742708489525e-05 -3.93757137066126e-06 6.19625785472965e-05 -4.50404956280868e-06 1.65662497445255e-05 4.73597824675622e-06 4.02487558634554e-06 5.87468578677135e-06 -4.50404956280868e-06 2.10096416030234e-05 -6.82088451773497e-06 -5.17597875764064e-06 1.09264517609229e-06 8.581084247593e-06 1.65662497445255e-05 -6.82088451773497e-06 8.52930368030024e-05 1.00541242203893e-05 1.58310604100902e-05 -1.24045983529495e-05 4.73597824675622e-06 -5.17597875764064e-06 1.00541242203893e-05 3.92213714174873e-05 -9.0620471584251e-06 3.89742708489525e-05 4.02487558634554e-06 1.09264517609229e-06 1.58310604100902e-05 -9.0620471584251e-06 8.25798485360626e-05 2890 2891 0 0 3 2892 2905 0 0 6 0 0 0 0 0 0 0 0 61 0 32 34 0 0 2591 +20 23 0.999963687446997 0.000821334707216633 -0.00848228723304435 -0.00442028650164606 -0.000847234951744083 0.999994988892144 -0.00305030876098683 -0.00256234652948541 0.00847973940293503 0.00305738448670283 0.999959372384578 -0.000132978222931209 5.56843952507032e-05 -4.7889584593644e-06 3.48322291492279e-06 -3.24430197361733e-06 -4.98445194261103e-06 -4.97529283229593e-07 -4.7889584593644e-06 5.90893620291982e-05 -8.9450765786261e-07 1.03824729359509e-05 3.33917443587501e-06 -1.15684915289745e-05 3.48322291492279e-06 -8.9450765786261e-07 1.61919250585405e-05 2.76678925922567e-06 3.78076702809445e-06 5.03177999073183e-07 -3.24430197361733e-06 1.03824729359509e-05 2.76678925922567e-06 5.17883351331223e-05 2.93876597846435e-06 -1.40819132076678e-06 -4.98445194261103e-06 3.33917443587501e-06 3.78076702809445e-06 2.93876597846435e-06 2.71812512184509e-05 -6.48504544023325e-06 -4.97529283229593e-07 -1.15684915289745e-05 5.03177999073183e-07 -1.40819132076678e-06 -6.48504544023325e-06 4.52277858147946e-05 2775 2791 0 0 7 2776 2793 0 0 10 0 0 0 0 0 0 0 0 53 0 13 15 0 0 2622 +20 52 0.999836390804854 0.00370603927431429 -0.0177047139265601 -0.0113036520168664 -0.00334445740941573 0.999786119759135 0.0204090504828098 0.00455219869947895 0.0177765639807218 -0.0203464987128133 0.999634940247273 -0.0314352131851511 0.000128387477818349 -2.37371773630029e-06 6.93124078262661e-06 -3.28337955141806e-06 -3.77822313593136e-05 9.47768444608134e-05 -2.37371773630029e-06 8.75628760364416e-05 -6.3453826937226e-06 3.12399790241954e-05 4.93157194006001e-06 3.04368058521435e-05 6.93124078262661e-06 -6.3453826937226e-06 1.99434197771506e-05 -5.27293270531046e-06 -6.92037362495872e-06 5.52447413215522e-06 -3.28337955141806e-06 3.12399790241954e-05 -5.27293270531046e-06 0.000103499881830303 6.97856654176301e-06 1.27036160956653e-05 -3.77822313593136e-05 4.93157194006001e-06 -6.92037362495872e-06 6.97856654176301e-06 5.36285267121525e-05 -4.12842268151441e-05 9.47768444608134e-05 3.04368058521435e-05 5.52447413215522e-06 1.27036160956653e-05 -4.12842268151441e-05 0.000156792160613541 2721 2720 0 0 0 2726 2736 0 0 1 0 0 0 0 0 0 0 0 57 0 23 25 0 0 2813 +20 51 0.999998649504809 -0.000246448072640618 -0.00162488519772816 -0.00485474588163708 0.000272982777844592 0.999866288359485 0.0163502563475161 0.00435210606404222 0.00162063844249869 -0.0163506778322485 0.999865005320951 -0.0219515306022505 7.73020032641428e-05 3.45819040736294e-06 4.14436434769755e-06 -1.55425773506408e-06 -6.47068320117589e-06 3.23389741704568e-05 3.45819040736294e-06 2.53862923504908e-05 -7.00482894260288e-06 -2.22721156081752e-06 -2.06735291484094e-06 8.10483539123209e-06 4.14436434769755e-06 -7.00482894260288e-06 1.98534897923062e-05 -4.274284518119e-06 -4.09553281013547e-06 4.74278961256243e-06 -1.55425773506408e-06 -2.22721156081752e-06 -4.274284518119e-06 7.44017863523847e-05 8.98063724496316e-06 -1.33756861555625e-08 -6.47068320117589e-06 -2.06735291484094e-06 -4.09553281013547e-06 8.98063724496316e-06 3.4583470872648e-05 -1.38584575990698e-05 3.23389741704568e-05 8.10483539123209e-06 4.74278961256243e-06 -1.33756861555625e-08 -1.38584575990698e-05 7.80270046438856e-05 2817 2827 0 0 7 2816 2838 0 0 10 0 0 0 0 0 0 0 0 69 0 14 17 0 0 2686 +20 46 0.999989540151871 -0.000533056661631572 -0.00454262451062943 -0.026846154960003 0.000637554997260043 0.999734487112438 0.0230336449928131 0.0120858199464205 0.00452914014737342 -0.0230363002373421 0.999724369894473 -0.0351111222560206 5.80205433810466e-05 -7.86019630495184e-07 7.33578018035818e-06 -9.81664575640633e-06 -8.42153100784214e-06 4.01092355539696e-05 -7.86019630495184e-07 2.35972363397428e-05 -7.14096742572277e-06 3.3092522466123e-06 -2.54281963550001e-06 1.08883194463726e-05 7.33578018035818e-06 -7.14096742572277e-06 1.83025399528195e-05 -1.2077004054237e-06 -1.43374176238853e-06 6.25858044617391e-08 -9.81664575640633e-06 3.3092522466123e-06 -1.2077004054237e-06 7.6431656461129e-05 3.52999923111323e-07 6.38722896659572e-07 -8.42153100784214e-06 -2.54281963550001e-06 -1.43374176238853e-06 3.52999923111323e-07 3.6223883006312e-05 -1.21749725719982e-05 4.01092355539696e-05 1.08883194463726e-05 6.25858044617391e-08 6.38722896659572e-07 -1.21749725719982e-05 8.86837767260698e-05 3137 3151 0 0 0 3135 3152 0 0 1 0 0 0 0 0 0 0 0 50 0 24 31 0 0 2516 +19 46 0.99996587543003 -0.000599372500250402 -0.00823946163647171 -0.0284501296254089 0.000742502111927038 0.999848695213329 0.0173791648480774 0.00657028693379497 0.00822779837299926 -0.0173846896092167 0.999815020841918 -0.025233168443973 8.80809354925686e-05 2.35701123007651e-05 2.34747463934893e-06 3.31096339689706e-05 -2.01683952625584e-05 5.73161241879164e-05 2.35701123007651e-05 8.49340845207174e-05 -5.7046221167823e-06 3.65002966442236e-05 -6.73742061871204e-06 3.4147264655065e-05 2.34747463934893e-06 -5.7046221167823e-06 1.81175472506897e-05 -4.19802545364899e-06 -4.45569935768924e-07 -1.72764456983206e-07 3.31096339689706e-05 3.65002966442236e-05 -4.19802545364899e-06 0.000107319675572279 -8.03002102197665e-06 3.71842624433296e-05 -2.01683952625584e-05 -6.73742061871204e-06 -4.45569935768924e-07 -8.03002102197665e-06 3.80988499955991e-05 -1.71127544456407e-05 5.73161241879164e-05 3.4147264655065e-05 -1.72764456983206e-07 3.71842624433296e-05 -1.71127544456407e-05 0.000123182767486859 2800 2799 0 0 0 2812 2832 0 0 1 0 0 0 0 0 0 0 0 48 0 26 28 0 0 2637 +20 48 0.999991232238588 -0.000394048962822194 -0.00416895326980192 -0.0174523260905031 0.000472649132950874 0.999821842669249 0.0188695395880487 0.00723368845532402 0.00416077501771174 -0.0188713445965759 0.999813262716778 -0.0284712937123406 6.15099918010428e-05 1.02922838416854e-06 4.84373305952601e-06 5.73588158842705e-06 -9.73634626869498e-06 6.44044262997911e-05 1.02922838416854e-06 2.31911754145453e-05 -5.1183787873446e-06 2.56956810074362e-06 -2.09380207710221e-06 1.79031823578452e-05 4.84373305952601e-06 -5.1183787873446e-06 1.45397333213828e-05 -4.38860813833639e-06 1.11815469283084e-06 1.15692006065669e-06 5.73588158842705e-06 2.56956810074362e-06 -4.38860813833639e-06 7.28711746697179e-05 8.07128546659606e-06 5.77157411783502e-06 -9.73634626869498e-06 -2.09380207710221e-06 1.11815469283084e-06 8.07128546659606e-06 2.86310814454109e-05 -2.13768850273316e-05 6.44044262997911e-05 1.79031823578452e-05 1.15692006065669e-06 5.77157411783502e-06 -2.13768850273316e-05 0.000129558993590006 3160 3159 0 0 5 3159 3172 0 0 6 0 0 0 0 0 0 0 0 40 0 20 24 0 0 2835 +20 22 0.999969747303987 -0.000264330702036287 0.0077739697760806 0.00387157715730923 0.00032406204366845 0.999970430888832 -0.0076832500802048 -0.00345996247742572 -0.00777170898781646 0.00768553688970879 0.999940264746913 0.000265456347605236 4.47144059882761e-05 -2.31133513621317e-06 2.98450877921403e-06 -8.13964294042522e-07 -2.9983127796062e-06 -4.19433053564418e-07 -2.31133513621317e-06 4.99962850134098e-05 -3.18892179653086e-06 1.24337050669614e-05 2.3287879626749e-06 -7.11249251886579e-06 2.98450877921403e-06 -3.18892179653086e-06 1.50708915385678e-05 -9.93762226284213e-07 8.55142797926818e-07 4.14359753476673e-06 -8.13964294042522e-07 1.24337050669614e-05 -9.93762226284213e-07 3.99550091888586e-05 6.54173181917332e-06 -2.18414700666408e-06 -2.9983127796062e-06 2.3287879626749e-06 8.55142797926818e-07 6.54173181917332e-06 2.63793126781036e-05 -5.52632053684269e-06 -4.19433053564418e-07 -7.11249251886579e-06 4.14359753476673e-06 -2.18414700666408e-06 -5.52632053684269e-06 3.90707955233416e-05 2742 2743 0 0 12 2741 2754 0 0 15 0 0 0 0 0 0 0 0 70 0 6 10 0 0 2523 +20 47 0.999999502215811 0.000632464507868987 -0.000771723251008378 -0.0114446969728337 -0.000620428767741228 0.999879710252893 0.0154977447628493 0.00561240634245553 0.000781432194128192 -0.0154972582490113 0.999879604927758 -0.029532679476858 7.41104382995534e-05 -1.84932628474259e-05 -3.0977467628025e-06 1.56607402238793e-05 -6.79303062361774e-06 4.3323904764724e-05 -1.84932628474259e-05 6.53045320395703e-05 -5.84073268591109e-06 1.87529186010795e-05 5.70556011127405e-06 1.25019588981687e-06 -3.0977467628025e-06 -5.84073268591109e-06 1.99392288100933e-05 -5.59847272238511e-06 -1.71506308153352e-06 -2.43887750688802e-06 1.56607402238793e-05 1.87529186010795e-05 -5.59847272238511e-06 9.94354574519869e-05 -6.95766188464464e-07 2.81515893166813e-05 -6.79303062361774e-06 5.70556011127405e-06 -1.71506308153352e-06 -6.95766188464464e-07 3.7720356795597e-05 -1.46481544406884e-05 4.3323904764724e-05 1.25019588981687e-06 -2.43887750688802e-06 2.81515893166813e-05 -1.46481544406884e-05 0.000100168319159492 2863 2874 0 0 3 2865 2884 0 0 6 0 0 0 0 0 0 0 0 57 0 18 24 0 0 2631 +21 24 0.999986582125092 -0.000227724008490158 0.00517529820909514 0.00455780292937032 0.000223831729668348 0.999999691705164 0.000752654591957129 0.00116492675575308 -0.00517546801109811 -0.000751486096982273 0.999986324806251 -0.00531908599185058 3.41936489465321e-05 4.54173073171465e-06 3.68046007283971e-06 6.85497950028318e-06 -2.12345177918451e-07 -6.77245112567311e-07 4.54173073171465e-06 5.08746562161744e-05 -1.72160034776203e-06 6.5146810498273e-06 4.99700822367042e-06 3.44406035437895e-06 3.68046007283971e-06 -1.72160034776203e-06 1.40912269357315e-05 -2.06576683045516e-06 3.32067899453388e-06 -1.26091108873259e-06 6.85497950028318e-06 6.5146810498273e-06 -2.06576683045516e-06 4.31287401088676e-05 4.58241880675283e-06 3.42961348712329e-07 -2.12345177918451e-07 4.99700822367042e-06 3.32067899453388e-06 4.58241880675283e-06 2.09495414056568e-05 -2.03046443759135e-06 -6.77245112567311e-07 3.44406035437895e-06 -1.26091108873259e-06 3.42961348712329e-07 -2.03046443759135e-06 3.75556024998036e-05 2805 2807 0 0 13 2805 2818 0 0 16 0 0 0 0 0 0 0 0 65 0 5 10 0 0 2632 +20 49 0.99999596819171 0.00030983615268395 -0.00282269408232182 -0.0104004665306751 -0.000262473866051867 0.999859438933916 0.0167640532754922 0.00643500243714228 0.00282749143120265 -0.0167632448026148 0.999855489016235 -0.0233792505179749 5.11153229031602e-05 -2.58739905751626e-05 4.97883317896314e-06 -1.36238077084375e-05 -9.6035576372375e-06 3.91169133744426e-05 -2.58739905751626e-05 0.000157536992806551 -6.46753543347855e-06 5.78334033450366e-05 9.82145318803239e-06 -3.08505388706645e-05 4.97883317896314e-06 -6.46753543347855e-06 2.04359454182837e-05 -4.87223574400843e-06 3.2375542983164e-07 3.21554280741219e-06 -1.36238077084375e-05 5.78334033450366e-05 -4.87223574400843e-06 0.000101159636516958 1.73365163553817e-05 -2.97491978246775e-05 -9.6035576372375e-06 9.82145318803239e-06 3.2375542983164e-07 1.73365163553817e-05 3.77110329662078e-05 -1.94171890801453e-05 3.91169133744426e-05 -3.08505388706645e-05 3.21554280741219e-06 -2.97491978246775e-05 -1.94171890801453e-05 9.35898576910398e-05 2785 2802 0 0 4 2787 2805 0 0 7 0 0 0 0 0 0 0 0 59 0 13 16 0 0 2815 +21 48 0.999928167663314 -0.000322303243636223 -0.0119814704484045 -0.0234752191334306 0.000527192847488968 0.999853622816363 0.0171013159930624 0.00435863113518092 0.0119742048248895 -0.017106404111097 0.999781970910258 -0.0249968463519046 4.80189109034738e-05 -5.37360120825581e-07 5.47436152762758e-06 1.03935101932699e-05 -7.24804187273388e-06 3.43964850410764e-05 -5.37360120825581e-07 5.54978806832942e-05 -2.35557470975646e-06 1.31435576654299e-05 2.62261105294362e-07 1.2114588666875e-05 5.47436152762758e-06 -2.35557470975646e-06 1.68744827542628e-05 -1.55485967918925e-06 -1.1517888167476e-06 3.76896825979514e-06 1.03935101932699e-05 1.31435576654299e-05 -1.55485967918925e-06 8.5635776144148e-05 4.55371181419962e-06 3.2276608667352e-06 -7.24804187273388e-06 2.62261105294362e-07 -1.1517888167476e-06 4.55371181419962e-06 2.9576553509501e-05 -1.06904081125562e-05 3.43964850410764e-05 1.2114588666875e-05 3.76896825979514e-06 3.2276608667352e-06 -1.06904081125562e-05 7.26566346778482e-05 2980 2979 0 0 0 2986 2999 0 0 2 0 0 0 0 0 0 0 0 36 0 22 26 0 0 2845 +20 50 0.99999622311836 1.1927246575909e-05 -0.00274838257081599 -0.00732183281548993 3.03267716882332e-05 0.999881818992826 0.0153735853946116 0.00370503430863645 0.00274824112873943 -0.01537361067997 0.999878042195827 -0.0203497449706273 0.000100552186445653 -4.00903779649314e-06 4.25784468893701e-06 -1.4042245279176e-06 -1.66705952085975e-05 4.58996720114574e-05 -4.00903779649314e-06 2.95715310632746e-05 -3.27345481341943e-06 -7.18298267236781e-07 -6.55460001503404e-06 1.15531509104187e-05 4.25784468893701e-06 -3.27345481341943e-06 2.3826451294413e-05 -9.09289243500907e-06 -7.27525186366846e-06 1.84212559853226e-06 -1.4042245279176e-06 -7.18298267236781e-07 -9.09289243500907e-06 8.17302118700362e-05 5.41014224869336e-06 7.0753817789798e-06 -1.66705952085975e-05 -6.55460001503404e-06 -7.27525186366846e-06 5.41014224869336e-06 4.12773167695671e-05 -2.46381580288852e-05 4.58996720114574e-05 1.15531509104187e-05 1.84212559853226e-06 7.0753817789798e-06 -2.46381580288852e-05 8.67802515978595e-05 2865 2866 0 0 6 2864 2880 0 0 8 0 0 0 0 0 0 0 0 60 0 13 17 0 0 2666 +21 52 0.999938491114756 0.00365552163209915 -0.0104714444439441 0.00154610186302321 -0.00343926939892624 0.999781970439215 0.020595703694778 0.00668927195382528 0.0105444493998958 -0.0205584227575643 0.999733047288412 -0.0302782027017833 9.18831357115693e-05 -3.40429430173698e-06 4.18684463786163e-06 1.36186368913692e-05 -1.74516979813687e-05 5.68362387395091e-05 -3.40429430173698e-06 4.05240961121237e-05 -2.37528208006395e-06 -1.51105146222146e-07 8.28570270511625e-07 -1.56758130954068e-08 4.18684463786163e-06 -2.37528208006395e-06 1.9379916233583e-05 -6.56057986957388e-06 -6.84027723046745e-06 4.25238990855044e-06 1.36186368913692e-05 -1.51105146222146e-07 -6.56057986957388e-06 7.71943838706543e-05 2.72089359148033e-06 1.09608049312824e-05 -1.74516979813687e-05 8.28570270511625e-07 -6.84027723046745e-06 2.72089359148033e-06 4.45574134049905e-05 -2.48212584437741e-05 5.68362387395091e-05 -1.56758130954068e-08 4.25238990855044e-06 1.09608049312824e-05 -2.48212584437741e-05 9.38749078710096e-05 2899 2901 0 0 8 2900 2915 0 0 9 0 0 0 0 0 0 0 0 62 0 14 14 0 0 2855 +20 24 0.999998922902191 0.00142240447689453 -0.000361883905800177 0.00269387784565733 -0.00142224297268892 0.999998889085177 0.000446153939411378 -0.000947602103288364 0.000362518115138785 -0.000445638772017994 0.999999834993337 0.00286548915441711 4.19876650916239e-05 3.52710454798738e-06 6.70254938354324e-06 -4.18385529065557e-06 -1.59575980535591e-06 2.69470864351762e-06 3.52710454798738e-06 8.48771674037388e-05 -6.36231649298878e-06 2.75828253653757e-05 -3.25547493939408e-06 -3.46732967192272e-05 6.70254938354324e-06 -6.36231649298878e-06 1.6386128608775e-05 -5.96898912017629e-06 2.73399785351632e-06 2.81135189176893e-06 -4.18385529065557e-06 2.75828253653757e-05 -5.96898912017629e-06 6.22666621027234e-05 3.63217204395159e-06 -2.50593807397601e-05 -1.59575980535591e-06 -3.25547493939408e-06 2.73399785351632e-06 3.63217204395159e-06 2.25584178808089e-05 -2.05941883841313e-06 2.69470864351762e-06 -3.46732967192272e-05 2.81135189176893e-06 -2.50593807397601e-05 -2.05941883841313e-06 5.3072341458292e-05 2879 2880 0 0 10 2880 2891 0 0 12 0 0 0 0 0 0 0 0 61 0 8 13 0 0 2625 +21 23 0.999978969646812 1.30574830757209e-05 0.00648537536324271 0.00450245589289961 2.80054430719401e-05 0.999979955537625 -0.00633148787128069 -0.00384974157950588 -0.00648532804067598 0.00633153634366509 0.999958925240299 0.000447149493882143 4.13963294366577e-05 -6.18395527179255e-06 3.25439249782053e-06 -1.72595176297693e-06 3.6449013767467e-06 1.82655206375726e-06 -6.18395527179255e-06 6.96346126731517e-05 -4.93798492762129e-06 3.02048161498415e-05 -3.23551980942641e-06 -2.96654421935801e-05 3.25439249782053e-06 -4.93798492762129e-06 1.5457387496594e-05 -3.13835470625413e-06 3.89878693891408e-06 5.60685389414859e-06 -1.72595176297693e-06 3.02048161498415e-05 -3.13835470625413e-06 6.76324987886952e-05 -8.57149680719319e-07 -2.55865013860836e-05 3.6449013767467e-06 -3.23551980942641e-06 3.89878693891408e-06 -8.57149680719319e-07 2.58779683658475e-05 2.90256603686823e-07 1.82655206375726e-06 -2.96654421935801e-05 5.60685389414859e-06 -2.55865013860836e-05 2.90256603686823e-07 5.73828404589048e-05 2513 2528 0 0 8 2515 2531 0 0 11 0 0 0 0 0 0 0 0 63 0 11 13 0 0 2713 +21 47 0.999994572007464 -6.07862637984217e-05 -0.00329427695238415 -0.0121906927717626 0.000126041160376823 0.999803715548946 0.019811978400635 0.00761703929944699 0.0032924260408955 -0.0198122860758538 0.999798296283412 -0.0262377215462378 6.61548657466284e-05 -6.28962055425401e-06 2.18918767276113e-06 3.03885014279867e-06 -9.16436433163855e-06 4.33224912275237e-05 -6.28962055425401e-06 1.77470641025565e-05 -3.84180110096887e-06 -2.82003755935356e-07 -3.06560874121942e-06 5.16721968942736e-06 2.18918767276113e-06 -3.84180110096887e-06 1.43242512993001e-05 -1.00046918005524e-06 3.92678460216686e-08 2.13479618846874e-06 3.03885014279867e-06 -2.82003755935356e-07 -1.00046918005524e-06 5.85397266817582e-05 8.16748965682226e-06 3.89468357695664e-06 -9.16436433163855e-06 -3.06560874121942e-06 3.92678460216686e-08 8.16748965682226e-06 3.08396041461887e-05 -1.49501904713366e-05 4.33224912275237e-05 5.16721968942736e-06 2.13479618846874e-06 3.89468357695664e-06 -1.49501904713366e-05 7.52888902344595e-05 3035 3045 0 0 3 3038 3056 0 0 5 0 0 0 0 0 0 0 0 57 0 18 25 0 0 2801 +21 51 0.999983572039529 -2.17725976630425e-05 -0.0057319435637542 -0.00710326716689172 0.00010856252478341 0.999885353924318 0.0151415726336175 0.00208474235733535 0.00573095674754965 -0.0151419461627261 0.999868930210936 -0.0201294280861571 7.92098610935784e-05 -9.91694221286141e-06 6.83266007738718e-06 -1.09690821419459e-06 -1.49178403730629e-05 4.97016114547392e-05 -9.91694221286141e-06 3.72052060654656e-05 -5.74792971341261e-06 3.85962161211351e-06 3.73563031277698e-06 2.1367538927875e-06 6.83266007738718e-06 -5.74792971341261e-06 1.7986268027632e-05 -5.00795147492598e-06 -4.04822206299014e-06 5.2224515001373e-06 -1.09690821419459e-06 3.85962161211351e-06 -5.00795147492598e-06 7.57042100373395e-05 1.20362714140115e-05 -6.3941194111534e-06 -1.49178403730629e-05 3.73563031277698e-06 -4.04822206299014e-06 1.20362714140115e-05 4.28612347683782e-05 -1.98496707032727e-05 4.97016114547392e-05 2.1367538927875e-06 5.2224515001373e-06 -6.3941194111534e-06 -1.98496707032727e-05 9.91328723854388e-05 2920 2928 0 0 4 2923 2939 0 0 7 0 0 0 0 0 0 0 0 67 0 17 24 0 0 2761 +21 49 0.999999568877651 -0.00084791722089243 0.000378524635216715 -0.0101087520682229 0.00084063442228867 0.999822112117387 0.0188424376049084 0.00888162966586124 -0.000394434127599633 -0.0188421112806744 0.999822393860132 -0.0250517808292634 5.22818987464641e-05 -7.8801927211824e-06 3.84359747690617e-06 2.43074079131151e-06 -8.00299364325453e-06 3.64790672591653e-05 -7.8801927211824e-06 2.93856525854597e-05 -4.92591698092989e-06 -4.49662890016225e-06 1.98102472179388e-06 -7.37644201281547e-06 3.84359747690617e-06 -4.92591698092989e-06 1.80762828536022e-05 -1.00283492111002e-06 6.47362464052484e-07 5.86725067995061e-08 2.43074079131151e-06 -4.49662890016225e-06 -1.00283492111002e-06 5.8915878840247e-05 1.17270414794924e-05 -1.29751923545307e-08 -8.00299364325453e-06 1.98102472179388e-06 6.47362464052484e-07 1.17270414794924e-05 3.36592334068757e-05 -1.39835973830161e-05 3.64790672591653e-05 -7.37644201281547e-06 5.86725067995061e-08 -1.29751923545307e-08 -1.39835973830161e-05 7.35552724369359e-05 2985 3001 0 0 8 2986 3003 0 0 10 0 0 0 0 0 0 0 0 60 0 16 20 0 0 2825 +21 50 0.999980836861479 0.000233390863418599 -0.00618639139740228 -0.00787823332480492 -0.000142874346485694 0.999892995473254 0.0146279592029871 0.000868818240570789 0.00618914345754697 -0.0146267950087506 0.999873867730842 -0.0206715043171378 8.09966638641968e-05 9.23345344966068e-06 2.87453885363853e-07 1.75869953973727e-05 -4.78655482447635e-06 4.59506839921621e-05 9.23345344966068e-06 5.50764554079517e-05 -4.07942272280347e-06 6.19436876079494e-06 -1.53405299506517e-06 1.78134242608747e-05 2.87453885363853e-07 -4.07942272280347e-06 1.99664012236751e-05 -4.07298116192038e-06 -3.97649704756769e-06 3.01077703919131e-07 1.75869953973727e-05 6.19436876079494e-06 -4.07298116192038e-06 7.1899371708341e-05 2.52707197869423e-06 1.36269081162177e-05 -4.78655482447635e-06 -1.53405299506517e-06 -3.97649704756769e-06 2.52707197869423e-06 3.87962143945684e-05 -1.41838060441009e-05 4.59506839921621e-05 1.78134242608747e-05 3.01077703919131e-07 1.36269081162177e-05 -1.41838060441009e-05 9.98599019579326e-05 2789 2789 0 0 7 2791 2806 0 0 10 0 0 0 0 0 0 0 0 56 0 17 21 0 0 2735 +22 24 0.999997910007573 -4.17201451141803e-05 0.00204407434202612 0.00128261440404085 4.53018065617814e-05 0.999998463867022 -0.00175220185549075 0.000299477157281879 -0.00204399809994043 0.00175229079366258 0.999996375767803 -0.00560748296329608 3.32416527237034e-05 3.73296252647856e-06 7.74484517033507e-06 5.12152161054835e-06 1.03827247074344e-08 6.06643322775986e-06 3.73296252647856e-06 3.42369476120512e-05 -3.36420920619937e-06 3.04083957817083e-06 1.15005507803248e-06 -1.95395760964406e-06 7.74484517033507e-06 -3.36420920619937e-06 1.39696911477838e-05 3.46781198520251e-07 4.12009419634276e-06 -6.40552706795526e-07 5.12152161054835e-06 3.04083957817083e-06 3.46781198520251e-07 3.82363862638302e-05 3.48168842308176e-06 3.06811171136042e-06 1.03827247074344e-08 1.15005507803248e-06 4.12009419634276e-06 3.48168842308176e-06 2.10083974725866e-05 -2.42193006718723e-06 6.06643322775986e-06 -1.95395760964406e-06 -6.40552706795526e-07 3.06811171136042e-06 -2.42193006718723e-06 3.33294535322574e-05 3101 3103 0 0 9 3101 3115 0 0 11 0 0 0 0 0 0 0 0 64 0 11 14 0 0 2637 +21 25 0.999976417317997 0.000289259924182211 -0.00686156954050501 -0.0015195033255354 -0.000289002144400287 0.999999957495438 3.85601182303281e-05 -0.00202556283753856 0.00686158040275388 -3.65762005681643e-05 0.999976458411176 -0.00392313657930601 5.4529857812956e-05 4.42268595108844e-06 8.57949453991897e-06 -5.96101053861921e-07 -1.06442988730949e-06 8.06231638808996e-06 4.42268595108844e-06 4.63276780888503e-05 -8.3708425005804e-07 3.3695160603285e-06 -1.93777742847132e-06 -2.67783616296305e-06 8.57949453991897e-06 -8.3708425005804e-07 1.79570435209707e-05 -2.15274336275946e-06 3.28788816924338e-06 1.39116663088504e-06 -5.96101053861921e-07 3.3695160603285e-06 -2.15274336275946e-06 4.72481301493263e-05 3.94384880462216e-07 -5.10730683676517e-06 -1.06442988730949e-06 -1.93777742847132e-06 3.28788816924338e-06 3.94384880462216e-07 2.53287848705906e-05 -7.10019049678027e-06 8.06231638808996e-06 -2.67783616296305e-06 1.39116663088504e-06 -5.10730683676517e-06 -7.10019049678027e-06 4.90710510879088e-05 2773 2771 0 0 10 2775 2782 0 0 11 0 0 0 0 0 0 0 0 75 0 12 19 0 0 2719 +22 49 0.999999399554114 -0.00102595694386261 0.000385102272405201 -0.0122598697538106 0.00101444912729869 0.999585278013955 0.0287792090011472 0.0118915489519899 -0.000414468791339559 -0.0287788010541254 0.999585718598214 -0.0272674817943612 9.58525804763288e-05 1.17399254038719e-05 4.00818390654151e-06 1.55226694526147e-05 -1.66428676788649e-05 4.98727797566353e-05 1.17399254038719e-05 4.76751873072287e-05 -4.55882685755988e-06 6.14179306473227e-06 -3.04738044122566e-06 1.49867176162569e-05 4.00818390654151e-06 -4.55882685755988e-06 2.08931286099309e-05 -1.88096628990452e-06 -4.83188350998342e-06 8.49978471502191e-07 1.55226694526147e-05 6.14179306473227e-06 -1.88096628990452e-06 6.92640783919173e-05 3.22483237338236e-06 6.728978029326e-06 -1.66428676788649e-05 -3.04738044122566e-06 -4.83188350998342e-06 3.22483237338236e-06 4.42874776488689e-05 -1.65990538048757e-05 4.98727797566353e-05 1.49867176162569e-05 8.49978471502191e-07 6.728978029326e-06 -1.65990538048757e-05 8.92298645921655e-05 2739 2749 0 0 4 2742 2757 0 0 8 0 0 0 0 0 0 0 0 61 0 14 19 0 0 2403 +22 26 0.999997880371924 0.000117826917986312 0.00205557010973919 -0.00059130962037079 -0.000127193752539136 0.999989607498683 0.00455727071598867 0.00285043464243289 -0.00205501177806122 -0.00455752251194558 0.999987502879484 -0.00598731512861452 3.85084057759809e-05 1.14410196259867e-06 6.55714263925123e-06 4.08870412120552e-06 -7.35726267267081e-07 7.35192505781356e-06 1.14410196259867e-06 5.11092964626766e-05 -7.88656059664164e-06 1.2286734156484e-05 4.022995119671e-06 -8.49226992008147e-07 6.55714263925123e-06 -7.88656059664164e-06 1.5186442456665e-05 -8.0047234389329e-07 2.51417845604772e-06 1.74594428859481e-06 4.08870412120552e-06 1.2286734156484e-05 -8.0047234389329e-07 4.61071759159799e-05 2.78099522349255e-06 2.22338378226462e-06 -7.35726267267081e-07 4.022995119671e-06 2.51417845604772e-06 2.78099522349255e-06 2.27064050730515e-05 -2.1014118585949e-06 7.35192505781356e-06 -8.49226992008147e-07 1.74594428859481e-06 2.22338378226462e-06 -2.1014118585949e-06 3.53877156156731e-05 2942 2959 0 0 17 2943 2961 0 0 19 0 0 0 0 0 0 0 0 67 0 18 25 0 0 2708 +22 25 0.99999232499628 0.000207931169532482 -0.00391237947584103 -0.00140610189138446 -0.000206054054810378 0.999999863481808 0.000480185476116364 -0.00142936356222097 0.0039124787872577 -0.000479375629036094 0.999992231324197 -0.00206741723671442 2.06551261460033e-05 -1.08476395106947e-06 7.35921657272701e-06 4.94637515618537e-06 2.91883565182452e-06 4.20622743689535e-06 -1.08476395106947e-06 2.60998155026771e-05 -1.95317745292512e-06 -6.82731925306849e-07 8.83744341743995e-07 -6.68461749439934e-07 7.35921657272701e-06 -1.95317745292512e-06 1.52824455905786e-05 9.88568190243174e-07 3.22271834357812e-06 4.13395336236818e-09 4.94637515618537e-06 -6.82731925306849e-07 9.88568190243174e-07 3.47767303684534e-05 2.30289725164853e-06 2.07851372368103e-06 2.91883565182452e-06 8.83744341743995e-07 3.22271834357812e-06 2.30289725164853e-06 2.12100241367236e-05 -2.64113224313136e-06 4.20622743689535e-06 -6.68461749439934e-07 4.13395336236818e-09 2.07851372368103e-06 -2.64113224313136e-06 3.26788443290055e-05 3058 3055 0 0 9 3058 3068 0 0 12 0 0 0 0 0 0 0 0 88 0 10 13 0 0 3088 +22 52 0.999921331462778 0.00379080581544417 -0.0119566164517861 -0.00352316453843648 -0.0034030132543664 0.999472795725928 0.0322885444792281 0.0136926531194547 0.0120727124746734 -0.0322453158624021 0.99940706882553 -0.0342525857754216 7.37771723481055e-05 7.09271372087617e-06 5.65879564328725e-06 2.50059323333768e-05 -1.12173983685678e-05 5.58457813427466e-05 7.09271372087617e-06 5.20993010249376e-05 -8.25661949927392e-06 1.61068203620265e-05 1.74441703490453e-06 1.14651446639805e-05 5.65879564328725e-06 -8.25661949927392e-06 2.21919919569889e-05 -5.40298787307151e-06 3.49534489620255e-07 -1.59247827690371e-06 2.50059323333768e-05 1.61068203620265e-05 -5.40298787307151e-06 0.000102853924910758 9.49491597990827e-07 3.21122682624309e-05 -1.12173983685678e-05 1.74441703490453e-06 3.49534489620255e-07 9.49491597990827e-07 3.84695131203835e-05 -2.12935731274003e-05 5.58457813427466e-05 1.14651446639805e-05 -1.59247827690371e-06 3.21122682624309e-05 -2.12935731274003e-05 0.000116319292028468 2873 2875 0 0 2 2875 2888 0 0 10 0 0 0 0 0 0 0 0 63 0 40 42 0 0 2784 +23 25 0.999991079052418 0.000460510960679122 0.00419877901731883 0.00278944303009739 -0.00045427617761254 0.999998793109158 -0.00148573664590556 -0.000893099611927585 -0.00419945814786101 0.0014838159864442 0.999990081371502 -1.44833211089094e-05 1.59795586075925e-05 -2.92531240358911e-06 5.5174428873338e-06 -3.10257860588414e-08 1.6007381741856e-06 2.68140800823691e-06 -2.92531240358911e-06 2.88744934270561e-05 -4.42436336727631e-06 4.48053882057659e-06 -4.81571123075597e-07 -6.44780631932029e-06 5.5174428873338e-06 -4.42436336727631e-06 1.45926853585368e-05 -5.95352373430503e-07 5.00732900799202e-06 5.12084170201167e-07 -3.10257860588414e-08 4.48053882057659e-06 -5.95352373430503e-07 3.42953925973615e-05 4.96412344792511e-06 -2.72242818811156e-06 1.6007381741856e-06 -4.81571123075597e-07 5.00732900799202e-06 4.96412344792511e-06 2.01608609663364e-05 -3.64006234412038e-06 2.68140800823691e-06 -6.44780631932029e-06 5.12084170201167e-07 -2.72242818811156e-06 -3.64006234412038e-06 3.12109182560887e-05 3044 3052 0 0 12 3044 3053 0 0 13 0 0 0 0 0 0 0 0 93 0 8 11 0 0 3089 +23 50 0.999998686596451 -0.000116910891156419 -0.00161652009468239 -0.00440870738199578 0.000133078818014839 0.9999499378906 0.010005198779313 0.00216060001992953 0.00161526945157108 -0.0100054007630329 0.999948640111166 -0.0237702909377083 3.53323335266724e-05 8.33940629368189e-06 2.67815014962274e-06 2.04144240864315e-06 -2.55502707469682e-06 3.57655852637682e-05 8.33940629368189e-06 5.57485921619886e-05 -3.32214845909555e-06 1.8138350752221e-06 -4.87660218113849e-06 2.15088298400464e-05 2.67815014962274e-06 -3.32214845909555e-06 2.17918889859208e-05 -7.15513883807658e-06 -2.89546113856411e-06 1.8637208677499e-06 2.04144240864315e-06 1.8138350752221e-06 -7.15513883807658e-06 7.30432445918955e-05 1.19131554560668e-05 -2.39738504841309e-06 -2.55502707469682e-06 -4.87660218113849e-06 -2.89546113856411e-06 1.19131554560668e-05 3.25576681383526e-05 -1.522605581338e-05 3.57655852637682e-05 2.15088298400464e-05 1.8637208677499e-06 -2.39738504841309e-06 -1.522605581338e-05 0.000100968918858507 2964 2967 0 0 11 2964 2968 0 0 13 0 0 0 0 0 0 0 0 53 0 31 46 0 0 3087 +22 50 0.999967778669586 -0.000149588126540822 -0.00802616010339473 -0.00958603102047111 0.000229337457538875 0.999950608697547 0.00993617480402968 0.00198769178914055 0.00802427734711961 -0.00993769534641019 0.999918423264747 -0.0168056226396317 4.74924164345656e-05 3.42583808686719e-06 1.00931539846939e-05 -5.51162853380258e-06 -7.50614957094201e-06 3.70868974276473e-05 3.42583808686719e-06 4.90792620759652e-05 -7.50848015665432e-06 1.10285498078132e-05 -6.27376192619844e-06 1.38181967884775e-05 1.00931539846939e-05 -7.50848015665432e-06 2.4130065817454e-05 -1.3771672431174e-05 -9.55796146036434e-07 4.47165674900874e-06 -5.51162853380258e-06 1.10285498078132e-05 -1.3771672431174e-05 9.75279084678431e-05 9.88540101847844e-06 4.95116670451143e-06 -7.50614957094201e-06 -6.27376192619844e-06 -9.55796146036434e-07 9.88540101847844e-06 3.74804799829979e-05 -1.47254082099232e-05 3.70868974276473e-05 1.38181967884775e-05 4.47165674900874e-06 4.95116670451143e-06 -1.47254082099232e-05 0.000107263829821019 2947 2947 0 0 6 2953 2968 0 0 12 0 0 0 0 0 0 0 0 58 0 36 40 0 0 3089 +22 51 0.999978186823188 0.000481913430880021 -0.00658738470515269 -0.00423224654092239 -0.000428728087581787 0.999967322134733 0.00807284676664648 0.000194404938143013 0.00659105985676512 -0.00806984647536578 0.999945716280553 -0.0142923227505069 2.565516485401e-05 -4.29613087093908e-07 4.21923951834087e-06 6.15809150047855e-06 -1.94718589408629e-06 1.86592728493984e-05 -4.29613087093908e-07 4.80938974940582e-05 -1.11408509317423e-05 1.4055528112087e-05 1.22716060925821e-06 3.66779187006042e-06 4.21923951834087e-06 -1.11408509317423e-05 2.01697431342521e-05 -8.72085357035037e-06 -2.37493092318456e-06 5.24109191036044e-06 6.15809150047855e-06 1.4055528112087e-05 -8.72085357035037e-06 8.83189760627936e-05 6.14602583665484e-06 7.55723972369316e-07 -1.94718589408629e-06 1.22716060925821e-06 -2.37493092318456e-06 6.14602583665484e-06 3.06259481802641e-05 -7.95072405042174e-06 1.86592728493984e-05 3.66779187006042e-06 5.24109191036044e-06 7.55723972369316e-07 -7.95072405042174e-06 6.37443129009215e-05 2704 2720 0 0 18 2705 2723 0 0 22 0 0 0 0 0 0 0 0 71 0 20 27 0 0 3106 +23 27 0.999995178766829 0.00120439382339246 -0.00286214580629067 -0.00274146462848498 -0.00119738725595383 0.999996285632048 0.00244846602313518 0.000697471739495617 0.00286508409258307 -0.00244502712159644 0.9999929065426 -0.00312164337763352 4.07464723365603e-05 -5.85017472272259e-06 1.05720960529085e-05 -2.14764681225387e-06 -8.8512995100481e-07 6.9644275900267e-06 -5.85017472272259e-06 7.41746218622206e-05 -9.55019431678249e-06 2.63118834760449e-05 3.67133044749337e-06 -1.29805466966439e-05 1.05720960529085e-05 -9.55019431678249e-06 2.11301446665212e-05 -6.39677199319857e-06 3.45724708742709e-06 5.63262381813266e-06 -2.14764681225387e-06 2.63118834760449e-05 -6.39677199319857e-06 5.60400742844792e-05 9.84009748012888e-06 -1.04048008845105e-05 -8.8512995100481e-07 3.67133044749337e-06 3.45724708742709e-06 9.84009748012888e-06 2.6598187176918e-05 -1.8989213812218e-06 6.9644275900267e-06 -1.29805466966439e-05 5.63262381813266e-06 -1.04048008845105e-05 -1.8989213812218e-06 4.18487753953407e-05 2835 2842 0 0 7 2837 2844 0 0 9 0 0 0 0 0 0 0 0 58 0 13 16 0 0 2679 +24 26 0.999999195467188 0.000798071874588714 0.000985974776166804 -0.0016707726717843 -0.000797346929737425 0.999999411689078 -0.000735431418919514 0.000790792719062671 -0.000986561123238203 0.000734644663280232 0.999999243496898 -0.00422470610062451 2.76664036221203e-05 -3.58260743765358e-06 7.00941176435993e-06 -2.98595526658261e-06 4.53657192325333e-06 9.59210750259003e-07 -3.58260743765358e-06 1.60502543694105e-05 -4.97230351077371e-06 1.68275507894499e-06 -2.27112186024778e-06 -2.54264329182994e-06 7.00941176435993e-06 -4.97230351077371e-06 1.50518009390152e-05 -3.43283649292118e-06 2.01332304576985e-06 3.29411669948472e-06 -2.98595526658261e-06 1.68275507894499e-06 -3.43283649292118e-06 4.44993800429168e-05 -2.52441009978429e-07 5.70868235665477e-07 4.53657192325333e-06 -2.27112186024778e-06 2.01332304576985e-06 -2.52441009978429e-07 1.89178100091193e-05 -2.65355785471212e-06 9.59210750259003e-07 -2.54264329182994e-06 3.29411669948472e-06 5.70868235665477e-07 -2.65355785471212e-06 2.48137366515472e-05 2937 2955 0 0 10 2938 2957 0 0 12 0 0 0 0 0 0 0 0 62 0 16 23 0 0 2840 +24 27 0.999997867322324 0.00104502085387956 0.00178137088183555 -0.00177288088764274 -0.00103953021741313 0.999994715249491 -0.00308039770425359 -0.00204176097639978 -0.00178458054757406 0.00307853934589808 0.999993668913841 -0.000640909099920232 4.2033726917117e-05 -7.72351435242112e-06 9.07933904246684e-06 -4.05548312011168e-07 -2.7022097679722e-06 -2.94348027623363e-06 -7.72351435242112e-06 5.33545113558202e-05 -3.16506254739563e-06 6.04990826251956e-06 1.05320380314447e-06 -8.32222365929622e-06 9.07933904246684e-06 -3.16506254739563e-06 1.58658012809495e-05 1.85608505479818e-06 3.54333616548095e-06 3.0183678874486e-06 -4.05548312011168e-07 6.04990826251956e-06 1.85608505479818e-06 4.12248442908962e-05 8.10027475601634e-07 3.53227887664103e-06 -2.7022097679722e-06 1.05320380314447e-06 3.54333616548095e-06 8.10027475601634e-07 2.22185663331664e-05 6.60546940258455e-07 -2.94348027623363e-06 -8.32222365929622e-06 3.0183678874486e-06 3.53227887664103e-06 6.60546940258455e-07 3.66470481801599e-05 2921 2922 0 0 9 2923 2935 0 0 11 0 0 0 0 0 0 0 0 66 0 12 15 0 0 2838 +23 49 0.999914966961354 -0.000215659461849117 -0.0130388779299213 -0.0201190954663706 0.000538372952648425 0.99969348587806 0.0247516554504436 0.00752611684733316 0.0130295434010072 -0.0247565705211795 0.999608595008462 -0.0236277192622452 8.95681308015853e-05 1.07528871500726e-07 -1.94442882540619e-06 1.83532024514245e-05 -1.19517218240709e-05 4.79634851903043e-05 1.07528871500726e-07 5.87951240478316e-05 -7.0952482928124e-06 1.74983169829431e-05 -6.54465241717455e-06 1.44393810215093e-05 -1.94442882540619e-06 -7.0952482928124e-06 1.68808796165054e-05 1.53313489892447e-07 -1.53342432174935e-06 1.06123198496436e-06 1.83532024514245e-05 1.74983169829431e-05 1.53313489892447e-07 7.6903800259933e-05 -1.34930134725542e-06 9.42802413076708e-06 -1.19517218240709e-05 -6.54465241717455e-06 -1.53342432174935e-06 -1.34930134725542e-06 3.51259874242379e-05 -1.28413440372355e-05 4.79634851903043e-05 1.44393810215093e-05 1.06123198496436e-06 9.42802413076708e-06 -1.28413440372355e-05 8.9339148340515e-05 2836 2836 0 0 0 2840 2852 0 0 2 0 0 0 0 0 0 0 0 45 0 16 19 0 0 2396 +24 51 0.999984898138704 0.000407590790584681 -0.00548063538955661 -0.00985803707815879 -0.000277908098338329 0.999720451238086 0.0236419572668404 0.0059660426750282 0.00548873952877232 -0.0236400771163222 0.999705466871278 -0.0217136401860692 6.77121266995197e-05 1.08043254721812e-06 3.14630170917628e-06 3.32834922513206e-06 -1.16063631085732e-05 2.12804605581084e-05 1.08043254721812e-06 4.92984191156864e-05 -9.01972330166662e-06 1.3125554255705e-05 -1.47816874758752e-06 1.15227967842172e-05 3.14630170917628e-06 -9.01972330166662e-06 2.06833124788103e-05 -2.10143429242751e-06 -4.75438099143804e-06 3.75868389274432e-06 3.32834922513206e-06 1.3125554255705e-05 -2.10143429242751e-06 6.83379635183457e-05 5.06296889510922e-06 3.58347081067602e-06 -1.16063631085732e-05 -1.47816874758752e-06 -4.75438099143804e-06 5.06296889510922e-06 3.61998256978469e-05 -7.22385298090468e-06 2.12804605581084e-05 1.15227967842172e-05 3.75868389274432e-06 3.58347081067602e-06 -7.22385298090468e-06 7.69180570162265e-05 2570 2586 0 0 13 2571 2588 0 0 15 0 0 0 0 0 0 0 0 64 0 19 26 0 0 2788 +23 26 0.999992483245581 0.00140213615896724 -0.00361489509238598 -0.0029960933574477 -0.00139451461920562 0.999996801545941 0.00211003006242646 0.00102132757024146 0.00361784207975714 -0.00210497317779543 0.999991240114935 0.00424482086007533 5.09893212867482e-05 2.95678818711184e-06 7.95909903950727e-06 9.84704637106559e-07 -8.64568976460674e-06 1.58308906049549e-05 2.95678818711184e-06 6.36397923164949e-05 -7.07754719485051e-06 1.57922958506686e-05 1.29508014953112e-06 1.15638214593059e-05 7.95909903950727e-06 -7.07754719485051e-06 1.80742340358898e-05 -3.74246396116867e-06 3.56366837820235e-06 1.45367578682523e-06 9.84704637106559e-07 1.57922958506686e-05 -3.74246396116867e-06 4.45921753547492e-05 1.60153506283626e-06 4.29633039508098e-06 -8.64568976460674e-06 1.29508014953112e-06 3.56366837820235e-06 1.60153506283626e-06 2.59566494296839e-05 -6.56025709727548e-06 1.58308906049549e-05 1.15638214593059e-05 1.45367578682523e-06 4.29633039508098e-06 -6.56025709727548e-06 5.06590016905013e-05 2866 2866 0 0 6 2874 2882 0 0 8 0 0 0 0 0 0 0 0 62 0 24 40 0 0 2674 +23 51 0.999997210356612 -0.00119865729837734 -0.00203531316394558 -0.00524445650519534 0.0012173174179461 0.999957013287481 0.00919182873445301 0.000486985203519349 0.00202420781992573 -0.0091942807146942 0.999955682910418 -0.0203827696826123 3.61572505025831e-05 1.68187594870256e-06 6.35645997728002e-06 1.7861837123058e-06 -3.64383930242812e-06 3.75456835531708e-05 1.68187594870256e-06 3.74941647699982e-05 -7.90154211494038e-06 5.54437146453959e-06 1.1926079459354e-06 9.04034670045582e-06 6.35645997728002e-06 -7.90154211494038e-06 1.87250222338183e-05 -2.2904376624231e-06 -4.01437489173957e-06 3.37494288376324e-06 1.7861837123058e-06 5.54437146453959e-06 -2.2904376624231e-06 6.39918329251581e-05 7.11181698285967e-06 -6.13404620497265e-06 -3.64383930242812e-06 1.1926079459354e-06 -4.01437489173957e-06 7.11181698285967e-06 3.20744406892125e-05 -1.1356757263818e-05 3.75456835531708e-05 9.04034670045582e-06 3.37494288376324e-06 -6.13404620497265e-06 -1.1356757263818e-05 9.80401691884496e-05 2650 2650 0 0 11 2655 2668 0 0 12 0 0 0 0 0 0 0 0 64 0 19 31 0 0 3109 +23 52 0.999783679466933 0.00364275358816703 -0.0204774172652953 -0.0106341475252823 -0.00308949551604947 0.999631065196413 0.0269849682553199 0.00811668984698628 0.0205681620233172 -0.0269158659637807 0.999426078742396 -0.0274224978629935 5.44914246108179e-05 1.22142275991567e-07 2.35039917852602e-06 1.51549266747448e-05 -6.2890313764254e-06 3.46533797505553e-05 1.22142275991567e-07 5.5356214517461e-05 -5.17072523121848e-06 2.25474096059397e-05 -1.67546472816524e-06 2.34766046230291e-05 2.35039917852602e-06 -5.17072523121848e-06 1.725068788449e-05 -3.07593544695463e-06 4.95745563172491e-07 5.68106077940399e-08 1.51549266747448e-05 2.25474096059397e-05 -3.07593544695463e-06 7.86402426051657e-05 -4.48203724391224e-06 2.17870898338903e-05 -6.2890313764254e-06 -1.67546472816524e-06 4.95745563172491e-07 -4.48203724391224e-06 3.47078761288759e-05 -1.18265547479424e-05 3.46533797505553e-05 2.34766046230291e-05 5.68106077940399e-08 2.17870898338903e-05 -1.18265547479424e-05 0.000104977713867973 2946 2945 0 0 2 2946 2945 0 0 2 0 0 0 0 0 0 0 0 49 0 35 51 0 0 2702 +25 52 0.999809477712927 0.00420580611933571 -0.0190609409602662 -0.00948254856208301 -0.00358563752706611 0.999466789231582 0.0324542821001703 0.0115094914131918 0.0191872738795455 -0.032379753210911 0.999291449029297 -0.0358223482396517 7.01663103759346e-05 9.57065218743148e-07 2.3146020288427e-06 1.76379712434898e-05 -1.28067539134084e-05 5.37616495804475e-05 9.57065218743148e-07 8.9416727248162e-05 -6.19633604751773e-06 2.45143451581417e-05 2.34595007295849e-06 4.74575558729967e-06 2.3146020288427e-06 -6.19633604751773e-06 1.9427266097368e-05 -5.84812781103945e-06 -3.10916829010714e-08 1.00308122807707e-06 1.76379712434898e-05 2.45143451581417e-05 -5.84812781103945e-06 9.79805048928299e-05 3.35526358048561e-06 1.46733413020148e-05 -1.28067539134084e-05 2.34595007295849e-06 -3.10916829010714e-08 3.35526358048561e-06 3.89305361721367e-05 -2.56766911294649e-05 5.37616495804475e-05 4.74575558729967e-06 1.00308122807707e-06 1.46733413020148e-05 -2.56766911294649e-05 0.000112668280233366 2873 2873 0 0 0 2877 2887 0 0 4 0 0 0 0 0 0 0 0 52 0 38 43 0 0 2730 +25 51 0.999995478634022 -0.000545698097985756 -0.0029571819524203 -0.00195681108761892 0.000573624746814994 0.999955173163115 0.00945106443605075 0.00283183843947681 0.00295189196342059 -0.00945271801707829 0.999950965025749 -0.018199285664396 3.70693769539602e-05 -3.45387846102171e-07 7.94381240299984e-06 -7.96566636090394e-07 -5.58939800377156e-06 3.67469305581318e-05 -3.45387846102171e-07 2.31199664324427e-05 -4.41637916840923e-06 -6.27898824363905e-07 -4.34256911598299e-06 1.46325227219654e-05 7.94381240299984e-06 -4.41637916840923e-06 2.14891740034002e-05 -4.54787932498862e-06 -4.24519098628662e-06 8.61639671647282e-06 -7.96566636090394e-07 -6.27898824363905e-07 -4.54787932498862e-06 6.21981471872312e-05 1.04096818451487e-05 -3.45756955338654e-06 -5.58939800377156e-06 -4.34256911598299e-06 -4.24519098628662e-06 1.04096818451487e-05 3.34292415993853e-05 -2.03452088096845e-05 3.67469305581318e-05 1.46325227219654e-05 8.61639671647282e-06 -3.45756955338654e-06 -2.03452088096845e-05 9.23015253972726e-05 2687 2703 0 0 17 2687 2706 0 0 23 0 0 0 0 0 0 0 0 69 0 9 15 0 0 3095 +25 28 0.999994930596636 -0.00040149305114266 -0.00315873144785849 -0.00326308083507866 0.000394236440817858 0.999997282790203 -0.00229760524035967 -0.00316846180469233 0.00315964533746072 0.00229634830582843 0.999992371683804 0.00665987446497511 2.05714879934676e-05 -9.38169685661393e-07 2.78324599185023e-06 6.8759255537324e-06 -6.05657712296195e-07 -1.5077485088198e-06 -9.38169685661393e-07 5.66168411891806e-05 -1.43145540787857e-06 1.60484628236134e-05 1.92822078124749e-06 -8.10179067866733e-06 2.78324599185023e-06 -1.43145540787857e-06 1.32221307187007e-05 6.05096974383773e-07 2.22862469800587e-06 9.35671617759631e-07 6.8759255537324e-06 1.60484628236134e-05 6.05096974383773e-07 4.17755604645776e-05 2.12997479064342e-06 -5.63318608051278e-07 -6.05657712296195e-07 1.92822078124749e-06 2.22862469800587e-06 2.12997479064342e-06 2.09843100858642e-05 -3.45951899815395e-06 -1.5077485088198e-06 -8.10179067866733e-06 9.35671617759631e-07 -5.63318608051278e-07 -3.45951899815395e-06 2.80358379721511e-05 2529 2546 0 0 12 2532 2551 0 0 18 0 0 0 0 0 0 0 0 62 0 19 26 0 0 3126 +24 52 0.999839005341266 0.00341605799387858 -0.0176151623884079 -0.0123095674134165 -0.00294971394199559 0.999646251893797 0.0264323714854218 0.00902665827674892 0.0176992255719825 -0.0263761563247074 0.99949539058051 -0.0368639487475776 9.29758732183474e-05 3.45198592123345e-06 6.56519990043781e-06 5.15432639414435e-07 -1.93961732050301e-05 6.42902493915834e-05 3.45198592123345e-06 4.45416107051168e-05 -6.45558103079153e-06 -3.31284384672935e-07 9.56839885895682e-07 2.70200099046447e-05 6.56519990043781e-06 -6.45558103079153e-06 1.78782058085519e-05 -1.87502990633035e-06 -3.43419749636934e-06 2.13149322710023e-06 5.15432639414435e-07 -3.31284384672935e-07 -1.87502990633035e-06 8.91275663324855e-05 -1.51829028577099e-06 8.93979605609253e-06 -1.93961732050301e-05 9.56839885895682e-07 -3.43419749636934e-06 -1.51829028577099e-06 3.92398488963699e-05 -2.0523231377431e-05 6.42902493915834e-05 2.70200099046447e-05 2.13149322710023e-06 8.93979605609253e-06 -2.0523231377431e-05 0.000138672992777894 2948 2947 0 0 2 2951 2950 0 0 3 0 0 0 0 0 0 0 0 52 0 39 55 0 0 2612 +26 28 0.999945302664148 -0.0001348955873182 0.010458177809073 0.00392442498144326 0.00017783350336882 0.999991559225221 -0.00410485731250311 -0.00169978268010453 -0.0104575358068115 0.0041064926021427 0.999936886340012 -0.00230296083440016 3.33137429657147e-05 -5.45133843594465e-06 3.1108030578238e-06 1.04714422538778e-06 -2.59280347045212e-06 -9.11054652538057e-07 -5.45133843594465e-06 3.303249760597e-05 -1.73144111807542e-06 3.18556954759322e-06 -1.15710181533224e-06 1.34557691708305e-06 3.1108030578238e-06 -1.73144111807542e-06 1.21290006416608e-05 2.40960214732703e-08 2.9442045231699e-06 1.72277040712817e-06 1.04714422538778e-06 3.18556954759322e-06 2.40960214732703e-08 4.13369485695854e-05 3.6762284039009e-06 2.60276580385255e-06 -2.59280347045212e-06 -1.15710181533224e-06 2.9442045231699e-06 3.6762284039009e-06 2.15540086974506e-05 9.59699199737365e-07 -9.11054652538057e-07 1.34557691708305e-06 1.72277040712817e-06 2.60276580385255e-06 9.59699199737365e-07 3.00531563180878e-05 2738 2741 0 0 11 2738 2762 0 0 14 0 0 0 0 0 0 0 0 83 0 11 13 0 0 2743 +24 50 0.999980509270262 0.000379998140064746 -0.00623190829521274 -0.0137434184263527 -0.000249874128287238 0.999782212837601 0.0208677851357134 0.00570448802752245 0.00623848078512764 -0.0208658212147003 0.999762821304398 -0.0233071289821963 7.46053140183505e-05 -7.91518099070571e-06 2.38153445778398e-06 -5.13575496483347e-07 -1.62076205687666e-05 3.52514958026953e-05 -7.91518099070571e-06 7.32786173590416e-05 -5.56440043724899e-06 1.68467874043335e-05 1.20539207753832e-06 1.26047893324172e-05 2.38153445778398e-06 -5.56440043724899e-06 2.02871573806336e-05 -5.68827195476886e-06 8.65809147994623e-07 1.12800440300041e-06 -5.13575496483347e-07 1.68467874043335e-05 -5.68827195476886e-06 7.88207341700613e-05 7.49053083701286e-06 -7.5867962471583e-06 -1.62076205687666e-05 1.20539207753832e-06 8.65809147994623e-07 7.49053083701286e-06 3.76867596901169e-05 -1.61376627158668e-05 3.52514958026953e-05 1.26047893324172e-05 1.12800440300041e-06 -7.5867962471583e-06 -1.61376627158668e-05 0.000105017897603307 2879 2879 0 0 3 2883 2883 0 0 6 0 0 0 0 0 0 0 0 49 0 37 55 0 0 2777 +25 27 0.999965619601308 0.000122715272251401 0.00829123370400598 0.0019976643855388 -0.000106617922859631 0.999998108818249 -0.00194190436024056 -0.00102011610747648 -0.00829145632509836 0.00194095360267896 0.999963741568224 0.00120118383105414 2.93959106007808e-05 -6.23275308787369e-06 3.48317176884048e-06 3.4067964374043e-06 -2.14276970748374e-07 -8.69533330060101e-07 -6.23275308787369e-06 3.0170959431007e-05 -3.28382423139294e-06 1.90747499793682e-06 -1.8703018824928e-06 -3.22138443743926e-06 3.48317176884048e-06 -3.28382423139294e-06 1.23197595707355e-05 6.18205707027616e-07 4.21390430412778e-06 1.97013509794728e-06 3.4067964374043e-06 1.90747499793682e-06 6.18205707027616e-07 3.35399033778162e-05 4.28295820624309e-06 -5.29111298684786e-07 -2.14276970748374e-07 -1.8703018824928e-06 4.21390430412778e-06 4.28295820624309e-06 2.26038662636134e-05 7.22160813497078e-07 -8.69533330060101e-07 -3.22138443743926e-06 1.97013509794728e-06 -5.29111298684786e-07 7.22160813497078e-07 3.3668086226469e-05 2963 2964 0 0 8 2966 2980 0 0 12 0 0 0 0 0 0 0 0 74 0 8 11 0 0 2697 +24 28 0.99997056861256 -0.000398507280692639 0.00766179486946096 -0.00217679946989513 0.000400427246235615 0.999999888814274 -0.000249057140576481 -7.76594050748711e-05 -0.00766169476649491 0.000252117801900082 0.999970617003279 0.000112951830830919 4.86464842919425e-05 -5.19695337430282e-06 2.77140906858459e-06 6.75267803035959e-06 -4.33928614801869e-06 -4.651810750676e-06 -5.19695337430282e-06 3.49639874493956e-05 -2.5808153526507e-06 5.40099874272545e-06 2.56384385165811e-07 -3.50338064745515e-06 2.77140906858459e-06 -2.5808153526507e-06 1.35515650723055e-05 2.72296112739649e-06 2.09340859217091e-06 2.13924523122326e-06 6.75267803035959e-06 5.40099874272545e-06 2.72296112739649e-06 4.15501196279286e-05 3.50215662670149e-06 -2.44364133391621e-06 -4.33928614801869e-06 2.56384385165811e-07 2.09340859217091e-06 3.50215662670149e-06 2.26772866387534e-05 1.20158320178163e-06 -4.651810750676e-06 -3.50338064745515e-06 2.13924523122326e-06 -2.44364133391621e-06 1.20158320178163e-06 3.02086916214203e-05 2560 2577 0 0 10 2562 2580 0 0 13 0 0 0 0 0 0 0 0 75 0 15 22 0 0 2827 +26 52 0.999864086080004 0.00410289939845017 -0.01596795490739 -0.00741331166977684 -0.00371284693818234 0.999695852956673 0.024380655217674 0.00926462342544438 0.0160631296767434 -0.0243180549747643 0.999575213811963 -0.0322106352056669 6.8839303998362e-05 3.03050174706987e-06 1.03534447696835e-06 1.83614047706831e-05 -9.29944356083151e-06 5.38966539680001e-05 3.03050174706987e-06 4.16851569506517e-05 -6.52503164991827e-06 1.16984539122958e-05 -3.95238712065538e-06 2.7814004943939e-05 1.03534447696835e-06 -6.52503164991827e-06 1.94852611846771e-05 -4.75496561353628e-06 -3.07218977961666e-06 -8.9607430186204e-07 1.83614047706831e-05 1.16984539122958e-05 -4.75496561353628e-06 8.01752848520321e-05 -8.65071451879001e-07 2.33779623243008e-05 -9.29944356083151e-06 -3.95238712065538e-06 -3.07218977961666e-06 -8.65071451879001e-07 3.33744398746459e-05 -1.50838623943657e-05 5.38966539680001e-05 2.7814004943939e-05 -8.9607430186204e-07 2.33779623243008e-05 -1.50838623943657e-05 0.000107570812557082 2777 2776 0 0 3 2787 2800 0 0 6 0 0 0 0 0 0 0 0 61 0 39 41 0 0 3083 +27 31 0.999999708076019 0.000143234960374404 0.000750554210347612 0.00318792078751123 -0.000141938659466766 0.999998498844685 -0.00172689368355367 -0.0023068968502902 -0.000750800435197505 0.00172678664677352 0.99999822725172 0.00360203955450121 4.22021519698333e-05 -1.05183320895117e-05 3.39989000558435e-06 8.88672023142674e-07 -4.22606537666686e-06 -2.3508649193827e-06 -1.05183320895117e-05 1.73467644318951e-05 -6.27303656888157e-06 1.59875134530405e-06 -4.16021374642382e-06 6.74875314115656e-06 3.39989000558435e-06 -6.27303656888157e-06 1.20266997834234e-05 3.59808231610018e-08 2.20916755319121e-06 3.48328643332543e-06 8.88672023142674e-07 1.59875134530405e-06 3.59808231610018e-08 5.23694114446012e-05 -6.92300331970484e-06 6.9951349739319e-06 -4.22606537666686e-06 -4.16021374642382e-06 2.20916755319121e-06 -6.92300331970484e-06 2.33317372194494e-05 -3.50946142691224e-06 -2.3508649193827e-06 6.74875314115656e-06 3.48328643332543e-06 6.9951349739319e-06 -3.50946142691224e-06 4.00046849498506e-05 3161 3173 0 1 14 3161 3176 0 1 18 0 0 0 0 0 0 0 0 76 0 7 11 0 0 2519 +27 29 0.999990982253741 0.00118625554223037 -0.00407777009995111 0.000323449079932813 -0.00119615267190041 0.999996343047977 -0.00242551220542989 -0.00223095925994364 0.00407487791044506 0.00243036796837672 0.999988744277431 0.00435592727856628 4.03544541559196e-05 -1.11975913135203e-05 6.02523395869555e-06 1.87475876730994e-06 -2.86698839910166e-06 4.95927509235549e-06 -1.11975913135203e-05 4.27653933565009e-05 -5.35865355579302e-06 9.87834822716296e-06 1.27398525144525e-06 -6.67729727928703e-06 6.02523395869555e-06 -5.35865355579302e-06 1.60667562664733e-05 -2.17941476209946e-06 2.4507725702064e-06 3.67439571721235e-06 1.87475876730994e-06 9.87834822716296e-06 -2.17941476209946e-06 4.34848034684171e-05 2.37672514038291e-06 -5.76212198873103e-06 -2.86698839910166e-06 1.27398525144525e-06 2.4507725702064e-06 2.37672514038291e-06 2.1296262679363e-05 -2.44889158615256e-06 4.95927509235549e-06 -6.67729727928703e-06 3.67439571721235e-06 -5.76212198873103e-06 -2.44889158615256e-06 3.9762550689243e-05 2767 2779 0 1 9 2768 2780 0 1 12 0 0 0 0 0 0 0 0 67 0 30 34 0 0 2511 +25 29 0.999999088460016 0.00113978614137083 0.000723855433916783 0.00124653365421167 -0.0011380651269793 0.999996535541275 -0.00237354444112543 0.000153282167166163 -0.000726558259209432 0.00237271848291845 0.999996921155309 0.000738219834378355 3.32680681980729e-05 -8.1203269219277e-06 8.30125125930536e-06 -1.6323541177983e-06 1.73529007645195e-06 4.96409874679044e-06 -8.1203269219277e-06 2.01691366906884e-05 -7.80435089715185e-06 1.29768522714379e-06 -3.30556589034294e-06 -4.72260067699651e-07 8.30125125930536e-06 -7.80435089715185e-06 1.59428797037724e-05 7.12040877585075e-07 3.7600009896705e-06 3.18736460278727e-06 -1.6323541177983e-06 1.29768522714379e-06 7.12040877585075e-07 4.01532421157218e-05 4.01731730981661e-06 -4.01015328335238e-06 1.73529007645195e-06 -3.30556589034294e-06 3.7600009896705e-06 4.01731730981661e-06 1.96782652764272e-05 -7.7471986853941e-07 4.96409874679044e-06 -4.72260067699651e-07 3.18736460278727e-06 -4.01015328335238e-06 -7.7471986853941e-07 3.03666684811566e-05 2936 2935 0 0 10 2941 2954 0 0 12 0 0 0 0 0 0 0 0 64 0 31 35 0 0 2624 +26 30 0.999987590343242 0.00037471734807516 -0.00496777077026018 0.0089616488955686 -0.000414411859331127 0.999967979286759 -0.00799178728242858 -0.0087341252438982 0.00496461703736004 0.00799374681021316 0.999955725314679 0.00195211310137666 4.77669323279906e-05 1.22391337733096e-07 5.83730518693398e-06 1.72580778810046e-05 -1.55547317228038e-05 1.04039230175501e-05 1.22391337733096e-07 8.73617427193141e-05 -6.75106775161104e-06 2.10880169679259e-05 -1.73446152857149e-06 -3.81618860374058e-07 5.83730518693398e-06 -6.75106775161104e-06 1.51725855672616e-05 2.76957614283476e-07 1.92128423116326e-06 3.99326424235746e-06 1.72580778810046e-05 2.10880169679259e-05 2.76957614283476e-07 7.193121176511e-05 -1.68077871536238e-05 2.70556915225244e-06 -1.55547317228038e-05 -1.73446152857149e-06 1.92128423116326e-06 -1.68077871536238e-05 4.06711032691008e-05 -4.71703562075555e-06 1.04039230175501e-05 -3.81618860374058e-07 3.99326424235746e-06 2.70556915225244e-06 -4.71703562075555e-06 4.74119391878219e-05 2885 2885 0 0 16 2895 2909 0 0 17 0 0 0 0 0 0 0 0 65 0 24 27 0 0 2753 +28 31 0.99993629840306 0.000516480301942936 -0.0112752997337219 -0.00640688110009258 -0.000550004694972402 0.999995437214023 -0.00297036125265781 -0.0023714685785109 0.0112737141538657 0.0029763735036933 0.99993201997433 0.00278786356592528 3.17823263444854e-05 -1.18763697347523e-05 2.26423832922045e-08 8.33923959853087e-07 -3.94494701242262e-06 6.43172411182072e-07 -1.18763697347523e-05 0.000110258929611095 -3.16714152557218e-06 2.83629992266717e-05 2.39722769274439e-06 -2.45126194508189e-05 2.26423832922045e-08 -3.16714152557218e-06 1.23436542632063e-05 2.00918612826819e-06 5.06546763357422e-06 1.07594594225923e-06 8.33923959853087e-07 2.83629992266717e-05 2.00918612826819e-06 6.12941722568539e-05 -2.18328073496908e-06 -5.65348502202292e-06 -3.94494701242262e-06 2.39722769274439e-06 5.06546763357422e-06 -2.18328073496908e-06 2.60684530326635e-05 9.84037250178677e-07 6.43172411182072e-07 -2.45126194508189e-05 1.07594594225923e-06 -5.65348502202292e-06 9.84037250178677e-07 5.1710400966449e-05 2914 2924 0 1 12 2916 2930 0 1 17 0 0 0 0 0 0 0 0 65 0 14 23 0 0 2630 +26 29 0.99999878043815 0.00115004826466748 0.00105665093677113 0.00439192915500942 -0.00114575653579463 0.999991128958021 -0.0040533007811131 -0.00234018843687918 -0.00106130305470581 0.00405208517314524 0.999991227082306 0.00495329888636899 3.66052084718336e-05 -3.63006533455325e-06 5.21519154862351e-06 1.35539080438846e-06 -9.68771660472294e-07 7.61620535566929e-06 -3.63006533455325e-06 2.02897756804936e-05 -6.52037773766526e-06 1.81417162192586e-06 -3.33559512745577e-06 -5.20689255145424e-06 5.21519154862351e-06 -6.52037773766526e-06 1.48686853119163e-05 -5.48700028678004e-06 2.46457146792214e-06 3.80906052165776e-06 1.35539080438846e-06 1.81417162192586e-06 -5.48700028678004e-06 4.48138005061539e-05 2.46987143592483e-06 -7.00362299759681e-06 -9.68771660472294e-07 -3.33559512745577e-06 2.46457146792214e-06 2.46987143592483e-06 2.50667978580519e-05 1.98719911399114e-06 7.61620535566929e-06 -5.20689255145424e-06 3.80906052165776e-06 -7.00362299759681e-06 1.98719911399114e-06 3.66295278033508e-05 2673 2672 0 0 12 2681 2695 0 0 13 0 0 0 0 0 0 0 0 73 0 29 32 0 0 2520 +29 33 0.999967295257007 0.000407242661503393 -0.00807728727981131 -0.00731422078592288 -0.000430857473716186 0.999995637889147 -0.00292208222263874 -0.000913458175424657 0.00807606204924732 0.0029254668162825 0.99996310875236 0.000208763776009944 4.09395945510848e-05 -1.03279500317808e-05 -4.16356511070684e-06 -2.85392787413215e-06 -2.58869294054574e-06 -7.89002954387892e-07 -1.03279500317808e-05 4.90572637783389e-05 -6.61502662719937e-06 1.15667862845732e-07 3.48070287111991e-06 -4.70776269755519e-06 -4.16356511070684e-06 -6.61502662719937e-06 1.48369146505962e-05 3.02252047508981e-06 2.29339587532309e-07 9.18759538866811e-07 -2.85392787413215e-06 1.15667862845732e-07 3.02252047508981e-06 5.83489498291545e-05 -6.59321127586682e-07 4.63088220839641e-06 -2.58869294054574e-06 3.48070287111991e-06 2.29339587532309e-07 -6.59321127586682e-07 2.54102495530878e-05 -8.69953272456104e-07 -7.89002954387892e-07 -4.70776269755519e-06 9.18759538866811e-07 4.63088220839641e-06 -8.69953272456104e-07 3.79569651351488e-05 2689 2689 0 0 6 2689 2690 0 0 6 0 0 0 0 0 0 0 0 63 0 14 27 0 0 2745 +30 32 0.999989026774764 0.00036298864455968 -0.00467060695248492 -0.00177153162341992 -0.000356504260125505 0.999998971657466 0.0013890963690713 0.000603045924498885 0.00467110637570931 -0.00138741603492803 0.999988127850512 0.0041193010745157 3.92766718180809e-05 -6.12645871646364e-06 2.23595301459008e-06 2.0404469472173e-06 -8.95537976096684e-06 1.8864271313067e-06 -6.12645871646364e-06 0.000270442133615218 -1.18508538494403e-05 8.41126065808769e-05 1.08227962843475e-05 -6.35326408683136e-05 2.23595301459008e-06 -1.18508538494403e-05 1.29959335823565e-05 -3.71298255538107e-07 3.77774183023305e-06 2.95625549897865e-06 2.0404469472173e-06 8.41126065808769e-05 -3.71298255538107e-07 7.47225885496123e-05 9.14058791627197e-06 -2.26166550715199e-05 -8.95537976096684e-06 1.08227962843475e-05 3.77774183023305e-06 9.14058791627197e-06 2.96542281340306e-05 -6.27771706408481e-06 1.8864271313067e-06 -6.35326408683136e-05 2.95625549897865e-06 -2.26166550715199e-05 -6.27771706408481e-06 5.20194831691246e-05 2645 2646 0 0 9 2645 2647 0 0 10 0 0 0 0 0 0 0 0 54 0 11 25 0 0 2654 +30 33 0.999975356403637 0.000221089947947972 -0.00701695836206479 -0.00510484797345524 -0.000206456451031573 0.999997802772271 0.00208610315261621 0.000255964736821649 0.00701740416064673 -0.00208460304721167 0.999973204875501 0.00285978523645946 4.04971413588465e-05 -1.63026647166344e-05 4.16166015677699e-06 -3.84264330358074e-06 -7.9220642067875e-06 -1.097564724922e-06 -1.63026647166344e-05 5.49154458987662e-05 -9.20347265316751e-06 1.20058650923626e-05 6.73034132740555e-06 -1.30381385595159e-06 4.16166015677699e-06 -9.20347265316751e-06 1.5882751972979e-05 -5.23996399042258e-07 -2.56097976446014e-07 1.84307613131602e-06 -3.84264330358074e-06 1.20058650923626e-05 -5.23996399042258e-07 4.93332285050783e-05 4.44298564868506e-06 3.80152181189672e-06 -7.9220642067875e-06 6.73034132740555e-06 -2.56097976446014e-07 4.44298564868506e-06 2.67264673798098e-05 1.25057119681968e-07 -1.097564724922e-06 -1.30381385595159e-06 1.84307613131602e-06 3.80152181189672e-06 1.25057119681968e-07 3.57890969038098e-05 2492 2492 0 0 7 2492 2494 0 0 8 0 0 0 0 0 0 0 0 66 0 12 25 0 0 2657 +27 30 0.999963717901793 -0.000187476056514689 -0.00851632155045116 0.00232993163807041 0.000148434869151872 0.999989479287468 -0.00458467899295692 -0.00624148952581909 0.00851709147021828 0.00458324853210845 0.999953225398959 0.000806836629756456 3.64261770652719e-05 1.89421710893464e-06 2.1515699408602e-06 7.90431490719946e-06 -5.76330440167963e-06 6.261660331527e-06 1.89421710893464e-06 6.05661438209338e-05 -4.07444875937948e-06 7.57391335350665e-06 2.6716315858262e-06 -3.98649596126655e-06 2.1515699408602e-06 -4.07444875937948e-06 1.38596648553541e-05 1.76513746083442e-06 2.13658820627976e-06 2.2107506796261e-06 7.90431490719946e-06 7.57391335350665e-06 1.76513746083442e-06 5.71074853592932e-05 -1.47822272723924e-05 9.59992193684664e-06 -5.76330440167963e-06 2.6716315858262e-06 2.13658820627976e-06 -1.47822272723924e-05 3.07198012687421e-05 -5.37140719207203e-06 6.261660331527e-06 -3.98649596126655e-06 2.2107506796261e-06 9.59992193684664e-06 -5.37140719207203e-06 3.76876236096525e-05 2990 3002 0 1 11 2990 3002 0 1 15 0 0 0 0 0 0 0 0 55 0 26 30 0 0 2778 +29 31 0.999977113965171 -0.000365035464739007 0.00675561211120773 -0.000430102884376145 0.000365184724505205 0.999999933102473 -2.08606642187628e-05 0.000400360408214839 -0.00675560404439172 2.33272331485703e-05 0.99997718037455 -0.00272869903565362 2.09734300034821e-05 2.67223481635268e-06 2.51883458112038e-06 5.44646526802909e-06 -1.13150914741714e-06 1.46820011868635e-06 2.67223481635268e-06 5.19251354683401e-05 -6.63927474418705e-06 1.17484580899577e-05 -1.5203603221825e-07 -1.58064531049345e-05 2.51883458112038e-06 -6.63927474418705e-06 1.335506102822e-05 1.18478954323281e-06 3.6410733063425e-06 2.88489150743716e-06 5.44646526802909e-06 1.17484580899577e-05 1.18478954323281e-06 3.71261627100065e-05 1.9314952727195e-06 -3.67189580677828e-06 -1.13150914741714e-06 -1.5203603221825e-07 3.6410733063425e-06 1.9314952727195e-06 2.0403376710295e-05 -1.20086760773935e-06 1.46820011868635e-06 -1.58064531049345e-05 2.88489150743716e-06 -3.67189580677828e-06 -1.20086760773935e-06 3.13125396104413e-05 2842 2863 0 0 12 2842 2863 0 0 12 0 0 0 0 0 0 0 0 65 0 11 14 0 0 2841 +30 34 0.999998766349355 0.000305487288273619 -0.00154077165214684 -0.00179493218625605 -0.000302448475455489 0.999998009642949 0.00197211436287408 0.00218790349080781 0.00154137104133 -0.00197164592593671 0.999996868388924 -0.00448100112556921 2.25728743847794e-05 -7.19680635288395e-06 3.24506053355221e-06 -3.88853434483181e-06 1.50363954278596e-07 3.60987429313935e-06 -7.19680635288395e-06 4.57557415137448e-05 -4.31345655679581e-06 8.24339305546382e-06 -1.20276988355651e-07 -8.26675884189572e-06 3.24506053355221e-06 -4.31345655679581e-06 1.43826767594753e-05 -1.44875950423933e-06 2.82288654812025e-06 1.41507250412208e-06 -3.88853434483181e-06 8.24339305546382e-06 -1.44875950423933e-06 6.51733528584361e-05 1.04045245729294e-05 2.88781249089572e-06 1.50363954278596e-07 -1.20276988355651e-07 2.82288654812025e-06 1.04045245729294e-05 2.72150002964426e-05 1.16302429145443e-06 3.60987429313935e-06 -8.26675884189572e-06 1.41507250412208e-06 2.88781249089572e-06 1.16302429145443e-06 3.53966260866344e-05 3004 3015 0 0 10 3004 3016 0 0 11 0 0 0 0 0 0 0 0 57 0 13 24 0 0 3052 +28 30 0.999983501996499 -0.000276616026414409 0.00573752720188475 0.00453230514419057 0.000289424859761437 0.999997467746729 -0.00223175567207927 -0.00225576319062185 -0.00573689533362679 0.00223337943557216 0.99998104984456 -0.000221338163156823 1.99002047088149e-05 1.32775765430567e-06 3.92937549167653e-06 2.35916530244773e-06 3.07293373319834e-06 8.51833849392704e-07 1.32775765430567e-06 5.52223183134309e-05 -1.10951756271047e-06 8.10179522948062e-06 5.24637182463435e-06 -1.06531478411461e-05 3.92937549167653e-06 -1.10951756271047e-06 1.39349709578333e-05 -7.51772329042699e-07 3.84055856635779e-06 1.72986492745495e-06 2.35916530244773e-06 8.10179522948062e-06 -7.51772329042699e-07 4.85927690000801e-05 1.88601140467524e-06 -2.17031474635493e-06 3.07293373319834e-06 5.24637182463435e-06 3.84055856635779e-06 1.88601140467524e-06 2.39794612523001e-05 -6.50660683257332e-06 8.51833849392704e-07 -1.06531478411461e-05 1.72986492745495e-06 -2.17031474635493e-06 -6.50660683257332e-06 3.09561904166555e-05 2726 2726 0 1 16 2728 2742 0 1 16 0 0 0 0 0 0 0 0 63 0 23 26 0 0 3134 +31 33 0.999988369019719 0.000117136831585589 0.00482162879582135 -0.00073801728508417 -0.000106540643939612 0.999997579082857 -0.00219783473350889 -0.00321222697134765 -0.00482187457045458 0.0021972954710997 0.999985960610568 -0.0072952403400847 4.40621561439915e-05 -1.78284876607097e-05 1.81223936498596e-06 1.91743450740727e-06 -4.85676515367006e-06 3.91878307199741e-06 -1.78284876607097e-05 0.000123282146161468 -3.32341566992654e-06 3.53254068563107e-05 8.08317246905512e-06 -1.16854944262184e-05 1.81223936498596e-06 -3.32341566992654e-06 1.37909483010184e-05 1.30528772316489e-06 2.67985494472669e-06 6.67051292475544e-07 1.91743450740727e-06 3.53254068563107e-05 1.30528772316489e-06 5.28448800700819e-05 1.91170991304619e-06 6.96910673327507e-07 -4.85676515367006e-06 8.08317246905512e-06 2.67985494472669e-06 1.91170991304619e-06 2.38504223750786e-05 9.23476372273454e-07 3.91878307199741e-06 -1.16854944262184e-05 6.67051292475544e-07 6.96910673327507e-07 9.23476372273454e-07 4.41012063614983e-05 2585 2588 0 0 8 2585 2589 0 0 12 0 0 0 0 0 0 0 0 65 0 11 14 0 0 2838 +28 32 0.999996227949996 0.000813414022798143 -0.00262344113837525 -0.00122987966327631 -0.000817616700949839 0.999998383673887 -0.00160129714423263 -0.00165570609835818 0.00262213438048704 0.00160343607334843 0.99999527669087 0.00892721876882285 4.50791608991792e-05 -4.36155457833047e-06 1.40217327925057e-06 7.44476107688345e-06 -1.21109664522879e-05 1.45649091470729e-05 -4.36155457833047e-06 4.06637635165118e-05 -1.55052648684485e-06 5.56054470675393e-06 -2.40907252461451e-06 3.92895542012931e-06 1.40217327925057e-06 -1.55052648684485e-06 1.40101361806577e-05 2.36829104871466e-06 3.11632745408805e-06 2.28301683758631e-06 7.44476107688345e-06 5.56054470675393e-06 2.36829104871466e-06 5.81072909614013e-05 -8.80554768263864e-06 1.37550717806256e-05 -1.21109664522879e-05 -2.40907252461451e-06 3.11632745408805e-06 -8.80554768263864e-06 3.07219301126e-05 -1.28281033427931e-05 1.45649091470729e-05 3.92895542012931e-06 2.28301683758631e-06 1.37550717806256e-05 -1.28281033427931e-05 4.79949495247229e-05 2982 2993 0 2 9 2982 2993 0 2 9 0 0 0 0 0 0 0 0 51 0 9 13 0 0 2684 +32 36 0.999974782050308 0.000337968588246939 -0.00709373249235586 -0.00671685332559835 -0.000269198800738837 0.999952983982396 0.00969316030551153 -0.00329029020151588 0.00709667495700822 -0.00969100623960288 0.999927858199089 -0.0144629087507825 5.33603152297538e-05 -1.1713116929108e-05 9.95035543446402e-06 1.78336131456273e-06 -1.33867561224184e-05 2.67849696362953e-05 -1.1713116929108e-05 5.98085636308719e-05 -1.08163486129506e-05 1.49390858013482e-05 5.52815975007039e-07 -1.35264974088642e-06 9.95035543446402e-06 -1.08163486129506e-05 1.88609543745971e-05 -4.69151917254431e-06 -1.25166174602841e-07 2.59094543114416e-06 1.78336131456273e-06 1.49390858013482e-05 -4.69151917254431e-06 5.5549853074407e-05 2.92136041114005e-06 5.30865983289539e-06 -1.33867561224184e-05 5.52815975007039e-07 -1.25166174602841e-07 2.92136041114005e-06 4.04179817402229e-05 -1.00587906954274e-05 2.67849696362953e-05 -1.35264974088642e-06 2.59094543114416e-06 5.30865983289539e-06 -1.00587906954274e-05 7.29012164437711e-05 2708 2716 0 0 8 2719 2737 0 0 13 0 0 0 0 0 0 0 0 60 0 14 16 0 0 2624 +29 32 0.999976413959643 1.39913910265853e-05 -0.00686813866004481 -0.00317955375960934 -3.47610729304254e-05 0.999995427240606 -0.00302395263623003 -0.00139260921920232 0.00686806494439546 0.00302412005702997 0.999971841794458 0.0021216820338396 3.60651607163154e-05 -1.667150941369e-05 8.57678776793017e-07 4.9272518369127e-06 -6.45825790671268e-06 -3.79799722542018e-07 -1.667150941369e-05 0.000149226584950109 2.26532187197e-06 2.23700285297385e-05 3.53505607596019e-06 -3.09298011677491e-05 8.57678776793017e-07 2.26532187197e-06 1.3184308225066e-05 1.48234553834067e-06 4.09535805201778e-06 1.15160896032044e-06 4.9272518369127e-06 2.23700285297385e-05 1.48234553834067e-06 5.23109249764163e-05 5.10808690710142e-06 3.22553648076326e-06 -6.45825790671268e-06 3.53505607596019e-06 4.09535805201778e-06 5.10808690710142e-06 2.30221145247219e-05 -7.82690466854717e-08 -3.79799722542018e-07 -3.09298011677491e-05 1.15160896032044e-06 3.22553648076326e-06 -7.82690466854717e-08 4.91817435991803e-05 2858 2859 0 0 8 2858 2860 0 0 9 0 0 0 0 0 0 0 0 58 0 11 25 0 0 2774 +32 35 0.999987512706054 0.000245150439486963 0.00499142597083087 -0.00757993559884163 -0.000264199820710525 0.999992683690203 0.00381611903905134 0.00295396764548796 -0.00499045392875258 -0.00381739011989774 0.99998026125632 -0.00770396276503047 3.35206958332501e-05 -8.00451640023953e-06 3.09247627175579e-06 8.78010372071933e-06 4.90243131692078e-07 2.28105765640104e-06 -8.00451640023953e-06 4.07381809054312e-05 -3.54010485802445e-06 7.32210627010216e-06 2.43655379622067e-06 -8.5011390653667e-06 3.09247627175579e-06 -3.54010485802445e-06 1.3463577176427e-05 2.75254904419375e-08 4.1946130345465e-07 1.03624438617378e-06 8.78010372071933e-06 7.32210627010216e-06 2.75254904419375e-08 5.09565033307598e-05 1.32042049813578e-06 5.56663921583299e-06 4.90243131692078e-07 2.43655379622067e-06 4.1946130345465e-07 1.32042049813578e-06 2.47894094677518e-05 -2.84256282901438e-06 2.28105765640104e-06 -8.5011390653667e-06 1.03624438617378e-06 5.56663921583299e-06 -2.84256282901438e-06 2.99277492681382e-05 2668 2676 0 0 7 2680 2699 0 0 17 0 0 0 0 0 0 0 0 65 0 14 16 0 0 2646 +33 35 0.999999483382871 -0.000269454186421847 -0.000980116540491555 -0.00694771501798112 0.000273821253269628 0.999990024424732 0.0044582589590396 0.00253946319074696 0.000978905466724568 -0.00445852503256613 0.999989581595039 -0.00636822353691446 3.16925290984656e-05 -6.67061577381256e-06 5.01013257805421e-06 2.69609615544324e-06 -8.7606003430383e-07 2.05608388018049e-06 -6.67061577381256e-06 2.40831031753979e-05 -4.32932810039409e-06 -2.45687140210849e-07 8.2724971440469e-09 1.97481016855047e-06 5.01013257805421e-06 -4.32932810039409e-06 1.45670384987809e-05 -1.50101033132401e-06 2.37795006094827e-07 1.23654354066271e-06 2.69609615544324e-06 -2.45687140210849e-07 -1.50101033132401e-06 4.41623141778825e-05 2.19835874465422e-06 -8.73013373964782e-08 -8.7606003430383e-07 8.2724971440469e-09 2.37795006094827e-07 2.19835874465422e-06 2.07837956317925e-05 -2.83579544522122e-06 2.05608388018049e-06 1.97481016855047e-06 1.23654354066271e-06 -8.73013373964782e-08 -2.83579544522122e-06 3.31001822491711e-05 2688 2698 0 0 9 2688 2703 0 0 9 0 0 0 0 0 0 0 0 63 0 13 17 0 0 2642 +31 34 0.999982430992089 5.95047712551272e-05 0.00592740806202135 -0.000757422394164234 -7.56831854977738e-05 0.999996272759499 0.00272923783608017 0.00273335294364908 -0.00592722356647282 -0.00272963849120292 0.999978708320582 -0.00377128011251091 3.15164629570921e-05 -3.36310602588494e-06 4.88421081631993e-06 -8.22138970365751e-07 -5.15834819081665e-06 -8.85138669387065e-07 -3.36310602588494e-06 4.4758527280406e-05 -7.33298178350369e-06 6.91997224515457e-06 1.6393012862485e-06 -8.73840710256413e-06 4.88421081631993e-06 -7.33298178350369e-06 1.5104006551436e-05 -4.0881019599499e-06 1.20118859730822e-06 3.08443796296972e-08 -8.22138970365751e-07 6.91997224515457e-06 -4.0881019599499e-06 5.59163480395869e-05 8.70312821926588e-06 8.96709587936406e-06 -5.15834819081665e-06 1.6393012862485e-06 1.20118859730822e-06 8.70312821926588e-06 2.41456992536317e-05 8.60187887974972e-07 -8.85138669387065e-07 -8.73840710256413e-06 3.08443796296972e-08 8.96709587936406e-06 8.60187887974972e-07 2.93492465871357e-05 2878 2878 0 0 8 2879 2901 0 0 11 0 0 0 0 0 0 0 0 54 0 10 12 0 0 2795 +31 35 0.99999655489108 0.000889543538883443 -0.0024695988062313 -0.0142274319089171 -0.000883673461283985 0.999996784466652 0.00237701021682418 -9.37031032160906e-05 0.00247170531923421 -0.00237481970884 0.999994125434827 -0.0101996174959779 4.1151985773177e-05 -1.81851575415787e-05 6.72972033666804e-06 5.91784833300925e-08 -1.20365021047045e-05 1.05170760626035e-05 -1.81851575415787e-05 0.000102401503368193 -1.81353763056177e-07 1.59704933808152e-05 5.31689615381896e-06 -2.68740252345554e-05 6.72972033666804e-06 -1.81353763056177e-07 1.66433503757122e-05 -9.29942833128822e-07 1.77238020569551e-06 4.6421502409553e-06 5.91784833300925e-08 1.59704933808152e-05 -9.29942833128822e-07 5.70037722968452e-05 -3.08808157068161e-06 -2.63949210905972e-06 -1.20365021047045e-05 5.31689615381896e-06 1.77238020569551e-06 -3.08808157068161e-06 3.14307792192974e-05 -4.33532144778122e-06 1.05170760626035e-05 -2.68740252345554e-05 4.6421502409553e-06 -2.63949210905972e-06 -4.33532144778122e-06 5.53293932664936e-05 2423 2423 0 0 1 2432 2442 0 0 5 0 0 0 0 0 0 0 0 64 0 18 20 0 0 2649 +32 34 0.99999918309305 0.00115834674583215 0.000540412849955876 5.4670043569477e-05 -0.00115929407939837 0.999997786294292 0.0017559737332483 0.00234462388063383 -0.000538377627181191 -0.00175659879619854 0.999998312253676 -0.0059936694343918 3.49527959434982e-05 -4.63604512531468e-06 9.15496820386091e-06 -9.92990551315913e-06 -1.9443932149613e-07 -3.32711827726462e-06 -4.63604512531468e-06 2.33088080612175e-05 -6.49172192945531e-06 8.88508348599861e-07 -7.99421507380836e-07 -2.76107441078562e-06 9.15496820386091e-06 -6.49172192945531e-06 1.78633817696691e-05 -5.19444128856362e-06 2.4166859990341e-06 7.29534976793988e-07 -9.92990551315913e-06 8.88508348599861e-07 -5.19444128856362e-06 5.17448208315376e-05 1.22569167618906e-05 7.25331885532293e-06 -1.9443932149613e-07 -7.99421507380836e-07 2.4166859990341e-06 1.22569167618906e-05 1.97030854570026e-05 1.89046589972938e-06 -3.32711827726462e-06 -2.76107441078562e-06 7.29534976793988e-07 7.25331885532293e-06 1.89046589972938e-06 2.28423055468725e-05 2822 2834 0 0 12 2830 2852 0 0 20 0 0 0 0 0 0 0 0 58 0 11 13 0 0 2706 +34 37 0.999994235609382 -0.000510275329128128 -0.00335683885463412 -0.00415641046927929 0.000563310713233332 0.999874740351483 0.015817278150629 0.00761700012931271 0.00334834721136484 -0.0158190779169486 0.99986926412647 -0.0207829671639989 4.05287937504725e-05 -2.99751887414367e-07 5.20348737526163e-06 2.67842378861757e-06 -5.66647881896439e-06 3.20268403600797e-05 -2.99751887414367e-07 1.79336691145718e-05 -4.51630811867647e-06 7.66954289423673e-07 -2.2386950975602e-06 9.0035699535198e-06 5.20348737526163e-06 -4.51630811867647e-06 1.30295709400892e-05 -8.92793853329261e-07 1.91270361529364e-07 1.95643420168579e-06 2.67842378861757e-06 7.66954289423673e-07 -8.92793853329261e-07 4.51342927655118e-05 4.74669760150098e-06 1.62027471623099e-06 -5.66647881896439e-06 -2.2386950975602e-06 1.91270361529364e-07 4.74669760150098e-06 2.53383820025936e-05 -1.42990100535645e-05 3.20268403600797e-05 9.0035699535198e-06 1.95643420168579e-06 1.62027471623099e-06 -1.42990100535645e-05 7.47051255837251e-05 3131 3131 0 2 9 3133 3153 0 2 11 0 0 0 0 0 0 0 0 64 0 10 12 0 0 2688 +33 36 0.999978651431833 -0.000391385043956981 -0.0065225377208103 -0.00522322949678122 0.000448264099818353 0.99996186906578 0.00872120827458852 -0.000473528757805623 0.00651887565986961 -0.00872394590877913 0.999940696755519 -0.016534214472112 5.72310575457054e-05 -1.49871385478057e-05 8.80277989064184e-06 1.33477959891386e-06 -4.2074297178093e-06 3.1744145875634e-05 -1.49871385478057e-05 0.000102568882958996 -8.16872242269545e-06 2.00570622856426e-05 7.33995725236437e-06 -1.861815376594e-06 8.80277989064184e-06 -8.16872242269545e-06 1.68348823236835e-05 -2.58235046844817e-06 -1.59127666188292e-06 4.74416033590012e-06 1.33477959891386e-06 2.00570622856426e-05 -2.58235046844817e-06 5.4035941558e-05 1.10629040088624e-05 -5.66482547993107e-06 -4.2074297178093e-06 7.33995725236437e-06 -1.59127666188292e-06 1.10629040088624e-05 3.07708972759747e-05 -4.69222868922778e-06 3.1744145875634e-05 -1.861815376594e-06 4.74416033590012e-06 -5.66482547993107e-06 -4.69222868922778e-06 7.90588950113575e-05 2700 2710 0 0 8 2701 2716 0 0 9 0 0 0 0 0 0 0 0 69 0 13 17 0 0 2601 +35 38 0.999997753525465 -0.000494842372209172 -0.00206108589113833 -4.27262886428245e-05 0.0005139971447252 0.999956590370341 0.00930339625393227 0.00146899814722198 0.0020563927054912 -0.00930443474635258 0.999954598340891 -0.0193642400459434 4.96925800959341e-05 -3.24522940720492e-06 8.92410125195031e-06 -5.33243397027133e-06 -2.03080342856903e-06 3.1276818189911e-05 -3.24522940720492e-06 6.21486862275232e-05 -3.19120385521717e-06 6.99909826432763e-06 1.06372798753987e-06 -5.17284142997285e-06 8.92410125195031e-06 -3.19120385521717e-06 1.81868543418301e-05 -3.0765269783643e-06 1.49852653360498e-06 1.67961361038644e-06 -5.33243397027133e-06 6.99909826432763e-06 -3.0765269783643e-06 5.71834361690596e-05 1.11427872340618e-05 -1.23906622271777e-05 -2.03080342856903e-06 1.06372798753987e-06 1.49852653360498e-06 1.11427872340618e-05 2.86988350779433e-05 -7.16311834810368e-06 3.1276818189911e-05 -5.17284142997285e-06 1.67961361038644e-06 -1.23906622271777e-05 -7.16311834810368e-06 8.24632315197905e-05 2840 2847 0 0 11 2840 2859 0 0 12 0 0 0 0 0 0 0 0 74 0 16 23 0 0 2855 +34 36 0.999968051270815 0.000127655783794579 -0.0079925053424847 -0.00721571263929903 -1.84114299618609e-05 0.999906602966929 0.0136669310438133 0.00273567181310032 0.00799350352899337 -0.0136663472492822 0.999874659571986 -0.0148220506269166 7.69659497231453e-05 -1.27698214858237e-05 6.60336931271557e-06 3.36088653719919e-06 -1.51308126157549e-05 3.10951872379488e-05 -1.27698214858237e-05 5.09946941599897e-05 -7.94804992204237e-06 9.99990385636881e-06 2.01625668528689e-06 6.8945292543276e-07 6.60336931271557e-06 -7.94804992204237e-06 1.78818286302272e-05 -2.40617666192731e-06 1.49145760517057e-06 1.5933679924464e-06 3.36088653719919e-06 9.99990385636881e-06 -2.40617666192731e-06 4.37082139267054e-05 4.75968029189109e-06 -2.26431940636288e-06 -1.51308126157549e-05 2.01625668528689e-06 1.49145760517057e-06 4.75968029189109e-06 3.278276247796e-05 -8.13795942465584e-06 3.10951872379488e-05 6.8945292543276e-07 1.5933679924464e-06 -2.26431940636288e-06 -8.13795942465584e-06 7.00243095406245e-05 2914 2914 0 1 5 2918 2934 0 1 7 0 0 0 0 0 0 0 0 68 0 14 17 0 0 2381 +36 40 0.999999964420654 -0.000236005835819329 -0.000124337992368174 0.000805104419302222 0.00023599187833837 0.999999965853091 -0.000112257068491709 0.000457242430456557 0.000124364481445692 0.000112227721741309 0.999999985969207 0.000691709056374428 2.80351696488459e-05 -6.42733339727198e-06 3.33898134743343e-06 5.40984803842715e-07 1.11202959686043e-06 -6.54764589073741e-07 -6.42733339727198e-06 2.16471256915318e-05 -5.16196670056952e-06 1.54636819498624e-07 1.12065160275805e-06 4.39189399058792e-06 3.33898134743343e-06 -5.16196670056952e-06 1.22566609048283e-05 2.04298680252283e-07 5.40474457615385e-07 8.56844052643565e-07 5.40984803842715e-07 1.54636819498624e-07 2.04298680252283e-07 3.89725332964392e-05 4.08879617199425e-06 1.76788299978458e-06 1.11202959686043e-06 1.12065160275805e-06 5.40474457615385e-07 4.08879617199425e-06 1.98653268485325e-05 1.98273829295453e-07 -6.54764589073741e-07 4.39189399058792e-06 8.56844052643565e-07 1.76788299978458e-06 1.98273829295453e-07 2.64348950592002e-05 2803 2814 0 0 11 2803 2816 0 0 14 0 0 0 0 0 0 0 0 80 0 10 13 0 0 2626 +33 37 0.999916159370217 0.000181773551982595 -0.0129476325515839 -0.00653993705024036 -2.75328542710327e-05 0.999929051154452 0.0119118386195531 0.00244526044779718 0.0129488791892183 -0.0119104834382212 0.99984522147781 -0.0199612589530634 4.90507434315148e-05 -3.8557286865518e-06 -3.1842977912215e-07 2.5083395803959e-07 -1.19893945039628e-05 3.74950039736601e-05 -3.8557286865518e-06 6.62820219724002e-05 -4.79907116591466e-06 1.59344557390824e-05 1.02348255072134e-07 -7.19162524903488e-07 -3.1842977912215e-07 -4.79907116591466e-06 1.37846864444026e-05 -3.82480544157387e-06 1.34480685316211e-06 1.87980695693862e-07 2.5083395803959e-07 1.59344557390824e-05 -3.82480544157387e-06 5.35135382044461e-05 7.08393767509502e-06 9.69884758999216e-07 -1.19893945039628e-05 1.02348255072134e-07 1.34480685316211e-06 7.08393767509502e-06 2.95379971440462e-05 -1.36405402274422e-05 3.74950039736601e-05 -7.19162524903488e-07 1.87980695693862e-07 9.69884758999216e-07 -1.36405402274422e-05 8.18033069634592e-05 2856 2868 0 0 9 2857 2876 0 0 11 0 0 0 0 0 0 0 0 59 0 14 17 0 0 3074 +37 39 0.999999273468815 0.000216912606484584 0.00118575324677012 0.000490522415760664 -0.000212181659654576 0.99999202341192 -0.00398849488877395 -0.00413000954340894 -0.00118660894332718 0.00398824039591619 0.999991342911407 0.00383864878513284 4.98590067920635e-05 4.1004499784278e-06 1.07657758907781e-05 1.13253490787495e-06 -8.50839561359742e-06 1.88683678936465e-05 4.1004499784278e-06 3.21271750251835e-05 2.53398086049638e-06 -1.87568178973887e-06 -5.70865724315614e-06 1.93957897341638e-06 1.07657758907781e-05 2.53398086049638e-06 1.8454533912341e-05 -2.2752492709412e-06 1.17453252949073e-06 4.90828798519194e-06 1.13253490787495e-06 -1.87568178973887e-06 -2.2752492709412e-06 4.19278011043212e-05 3.75074167286016e-06 -4.43528242865883e-06 -8.50839561359742e-06 -5.70865724315614e-06 1.17453252949073e-06 3.75074167286016e-06 2.38067472824184e-05 -2.53874693170118e-06 1.88683678936465e-05 1.93957897341638e-06 4.90828798519194e-06 -4.43528242865883e-06 -2.53874693170118e-06 4.24632201731912e-05 3016 3016 0 0 10 3018 3043 0 0 12 0 0 0 0 0 0 0 0 76 0 10 12 0 0 3098 +37 40 0.999994415608595 0.000924688329288405 -0.00321149546459557 0.00101745723104441 -0.000923775641618468 0.999999532516725 0.000285665705736256 -0.00293667839757885 0.00321175811501932 -0.000282697409183783 0.999994802332485 0.000407807200560691 5.38583698214492e-05 3.76118270396229e-06 1.57069847912312e-06 1.15135276508579e-05 -6.68453764874204e-06 1.42640643365604e-05 3.76118270396229e-06 6.05344714374638e-05 -2.33894982548216e-06 1.68198880570761e-05 -4.08689690161515e-06 -2.2263270530577e-07 1.57069847912312e-06 -2.33894982548216e-06 1.62687321054072e-05 -4.33827914500306e-06 2.95681204728193e-06 1.71788569182593e-06 1.15135276508579e-05 1.68198880570761e-05 -4.33827914500306e-06 6.1615385345434e-05 -2.05913750034156e-06 8.60755849231531e-09 -6.68453764874204e-06 -4.08689690161515e-06 2.95681204728193e-06 -2.05913750034156e-06 2.45177313509805e-05 -1.01452111333391e-06 1.42640643365604e-05 -2.2263270530577e-07 1.71788569182593e-06 8.60755849231531e-09 -1.01452111333391e-06 4.01987598917117e-05 2884 2896 0 0 10 2884 2897 0 0 11 0 0 0 0 0 0 0 0 80 0 10 13 0 0 2523 +34 38 0.999981581014995 0.000138660926648516 -0.00606781706210358 -0.00310214254781337 -7.5723446851454e-05 0.999946213301108 0.0103713437284755 -0.000661259866466184 0.00606892879438631 -0.010370693222828 0.999927805806683 -0.017195362646733 6.43174986299301e-05 -4.68790090138433e-06 5.64694895296198e-06 2.66436278436735e-06 -8.28305705339586e-06 2.69365180442317e-05 -4.68790090138433e-06 3.13509684128551e-05 -5.14814415840931e-06 -9.52185083481362e-07 4.16754943731104e-07 -1.24853983513088e-06 5.64694895296198e-06 -5.14814415840931e-06 1.6722137295639e-05 -1.12484316065105e-06 -7.83816016691957e-07 8.25751067788631e-07 2.66436278436735e-06 -9.52185083481362e-07 -1.12484316065105e-06 4.75268393213795e-05 1.03424542482396e-05 -1.31959807130589e-07 -8.28305705339586e-06 4.16754943731104e-07 -7.83816016691957e-07 1.03424542482396e-05 3.95216512455167e-05 -6.77461645818224e-06 2.69365180442317e-05 -1.24853983513088e-06 8.25751067788631e-07 -1.31959807130589e-07 -6.77461645818224e-06 6.43202428947881e-05 3099 3100 0 1 9 3105 3124 0 1 12 0 0 0 0 0 0 0 0 74 0 25 32 0 0 2599 +38 41 0.999988661368947 -0.000200777464849381 -0.00475781693114646 -0.0015901565401531 0.000208615867225179 0.999998621868775 0.00164703975973559 -0.00236980430894163 0.00475747968578292 -0.00164801364066462 0.999987325138714 0.0063085659936242 4.42906565115972e-05 -6.75083669158791e-06 6.66473783882886e-06 3.39794860774334e-06 -5.22000686150722e-06 1.57188111340789e-06 -6.75083669158791e-06 4.17865504078244e-05 -3.94172602372491e-06 1.16720209246671e-05 -4.26664302779868e-07 -6.87845173326518e-06 6.66473783882886e-06 -3.94172602372491e-06 1.44486963999551e-05 -3.24782463226489e-06 2.27548866408658e-06 2.44995240316383e-06 3.39794860774334e-06 1.16720209246671e-05 -3.24782463226489e-06 4.81104055968107e-05 5.36112340368846e-06 -3.17715992162992e-06 -5.22000686150722e-06 -4.26664302779868e-07 2.27548866408658e-06 5.36112340368846e-06 2.95461245182734e-05 -4.21014399448683e-06 1.57188111340789e-06 -6.87845173326518e-06 2.44995240316383e-06 -3.17715992162992e-06 -4.21014399448683e-06 3.26048549155941e-05 3001 3001 0 0 8 3004 3026 0 0 12 0 0 0 0 0 0 0 0 80 0 8 10 0 0 2576 +36 38 0.999999024362973 -0.000728708143053978 0.00119174558719852 0.000130339373891408 0.00072827999834809 0.999999670128931 0.000359652989438439 0.0005354098599928 -0.0011920072761382 -0.00035878471407339 0.999999225195791 -0.000200172899848531 2.56664243875502e-05 -7.15690154571858e-06 7.65383058306532e-06 -2.78347960799994e-06 2.81099645829129e-06 4.72935759554159e-06 -7.15690154571858e-06 2.17053536039672e-05 -6.56559948483654e-06 -2.46296471900806e-06 -5.44991982212721e-07 5.29706083997426e-07 7.65383058306532e-06 -6.56559948483654e-06 1.51973550928786e-05 -2.97788742409345e-06 3.61482133477911e-06 1.12821243659577e-06 -2.78347960799994e-06 -2.46296471900806e-06 -2.97788742409345e-06 4.10235500768409e-05 5.19366171458587e-06 -4.55896160679858e-06 2.81099645829129e-06 -5.44991982212721e-07 3.61482133477911e-06 5.19366171458587e-06 1.77641835353382e-05 -9.05505901252984e-07 4.72935759554159e-06 5.29706083997426e-07 1.12821243659577e-06 -4.55896160679858e-06 -9.05505901252984e-07 2.64683986106878e-05 2970 2972 0 0 14 2978 2997 0 0 15 0 0 0 0 0 0 0 0 79 0 31 38 0 0 2850 +35 39 0.999997204475229 0.000421730951820709 0.00232662518057371 0.00104566363180821 -0.00044121228019962 0.99996479769105 0.00837906381530033 0.00157058227818545 -0.0023230095674371 -0.00838006692702097 0.999962188337563 -0.0239911964244047 5.11214955168374e-05 7.23428131261501e-06 8.90955638831127e-06 9.33593986715319e-07 -6.85754165211786e-06 2.75550487526549e-05 7.23428131261501e-06 3.35035537169602e-05 2.55197389126909e-06 -1.24320910001933e-07 -3.92270311649711e-06 3.87796322089551e-06 8.90955638831127e-06 2.55197389126909e-06 1.65542127438645e-05 -3.77243703225188e-06 -5.14107426357643e-07 3.30490307259135e-07 9.33593986715319e-07 -1.24320910001933e-07 -3.77243703225188e-06 4.31130543825886e-05 8.68092584229144e-06 2.13037098923511e-06 -6.85754165211786e-06 -3.92270311649711e-06 -5.14107426357643e-07 8.68092584229144e-06 3.37597540516444e-05 -1.06435822372454e-05 2.75550487526549e-05 3.87796322089551e-06 3.30490307259135e-07 2.13037098923511e-06 -1.06435822372454e-05 6.59909397732672e-05 2936 2940 0 0 11 2936 2962 0 0 12 0 0 0 0 0 0 0 0 80 0 11 13 0 0 2702 +35 37 0.999952295243846 -0.000698654372353639 -0.00974264433473339 -0.0054542036586831 0.000809608456953577 0.999934813109779 0.0113892082805698 0.00235098467664853 0.00973405212188381 -0.0113965526884125 0.999887677099837 -0.0203057024400562 4.98835488967115e-05 2.91951960834793e-06 1.56748053003824e-06 4.69769842925346e-06 -5.56913133201555e-06 2.74455538534587e-05 2.91951960834793e-06 4.64319216615589e-05 5.85864048923158e-07 2.35537930380964e-06 3.31250777936252e-06 6.91184355683911e-06 1.56748053003824e-06 5.85864048923158e-07 1.41633416356857e-05 -1.30955792382466e-06 1.05828841794868e-06 1.47674059078806e-06 4.69769842925346e-06 2.35537930380964e-06 -1.30955792382466e-06 4.13832831519719e-05 4.46506623283184e-07 7.27490976756013e-06 -5.56913133201555e-06 3.31250777936252e-06 1.05828841794868e-06 4.46506623283184e-07 3.01840266248327e-05 -1.09717372388377e-05 2.74455538534587e-05 6.91184355683911e-06 1.47674059078806e-06 7.27490976756013e-06 -1.09717372388377e-05 6.2952427158516e-05 2816 2816 0 0 7 2818 2835 0 0 9 0 0 0 0 0 0 0 0 64 0 11 13 0 0 2686 +38 42 0.999996688963568 -0.000196380010474636 -0.00256583257320843 0.000903187165994973 0.000191050587234198 0.999997824463755 -0.00207715368481631 -0.00217241376078082 0.00256623490260905 0.00207665660346492 0.999994550953042 0.00490275749520479 2.6165562964457e-05 -8.77313826901711e-07 3.05185909669635e-06 3.52956887594449e-06 2.23321455730681e-06 3.67106857553656e-06 -8.77313826901711e-07 2.56470951532083e-05 1.18709755755055e-06 -3.21554494088676e-06 1.58724229294288e-06 -7.03742150599312e-06 3.05185909669635e-06 1.18709755755055e-06 1.29664371961712e-05 -2.36371487372106e-07 3.00418896670946e-06 7.97756895402147e-07 3.52956887594449e-06 -3.21554494088676e-06 -2.36371487372106e-07 3.29152583259005e-05 1.59135590623277e-06 2.15535160886266e-06 2.23321455730681e-06 1.58724229294288e-06 3.00418896670946e-06 1.59135590623277e-06 1.9676801571074e-05 -2.73007721680253e-07 3.67106857553656e-06 -7.03742150599312e-06 7.97756895402147e-07 2.15535160886266e-06 -2.73007721680253e-07 2.97762607749188e-05 3082 3083 0 0 9 3084 3106 0 0 14 0 0 0 0 0 0 0 0 54 0 10 13 0 0 2831 +39 41 0.999999536729288 -0.00039225011887471 -0.000879022783642003 0.000607973797340997 0.000395576493494135 0.999992750291535 0.00378719996953353 0.00198371321620624 0.000877530881344836 -0.00378754593578516 0.999992442189108 0.0021184142860773 4.8582399256318e-05 -5.82434570028435e-06 2.53240562312773e-06 -3.55889163664537e-06 -1.42590616524542e-08 6.13628834528879e-06 -5.82434570028435e-06 2.71945742667093e-05 -3.49254915250596e-06 -1.39153191672776e-06 -3.6485277912705e-06 3.97247577499603e-06 2.53240562312773e-06 -3.49254915250596e-06 1.57510264953703e-05 -3.23472732353496e-06 1.88476692913328e-06 3.41130573452015e-06 -3.55889163664537e-06 -1.39153191672776e-06 -3.23472732353496e-06 4.19817858740554e-05 7.00417051903831e-06 -6.43247907230313e-06 -1.42590616524542e-08 -3.6485277912705e-06 1.88476692913328e-06 7.00417051903831e-06 2.06698981276865e-05 -4.08703481817072e-06 6.13628834528879e-06 3.97247577499603e-06 3.41130573452015e-06 -6.43247907230313e-06 -4.08703481817072e-06 3.30464298965481e-05 3014 3016 0 0 13 3014 3030 0 0 15 0 0 0 0 0 0 0 0 90 0 19 26 0 0 2485 +36 39 0.999997340485553 0.000150176104745265 -0.00230140586568394 -0.00308926810659597 -0.000159034755675736 0.999992577866281 -0.00384953507526496 -0.00201734077317821 0.00230081067615918 0.00384989084089037 0.999989942254794 0.000441493752737288 4.7676024476559e-05 -4.18112840219301e-06 8.13979747816657e-06 -5.97071252881875e-06 2.97369681694998e-06 3.00266741548971e-06 -4.18112840219301e-06 3.71346743272275e-05 1.83124306117338e-06 2.78282102540833e-07 -2.20130034484809e-07 -1.60559154866904e-05 8.13979747816657e-06 1.83124306117338e-06 1.8296681954614e-05 -2.70515931031694e-06 2.62446731721418e-06 -2.94988149411609e-08 -5.97071252881875e-06 2.78282102540833e-07 -2.70515931031694e-06 5.78777894640169e-05 3.81460394294656e-07 -1.00658554405172e-06 2.97369681694998e-06 -2.20130034484809e-07 2.62446731721418e-06 3.81460394294656e-07 2.43752036652381e-05 -6.32845632680283e-07 3.00266741548971e-06 -1.60559154866904e-05 -2.94988149411609e-08 -1.00658554405172e-06 -6.32845632680283e-07 3.53790119938943e-05 2921 2922 0 0 10 2925 2948 0 0 11 0 0 0 0 0 0 0 0 74 0 12 14 0 0 2688 +40 44 0.999991599249118 0.000270693929272154 0.00409000684459504 -0.00540928896316733 -0.000314538461657047 0.999942456665142 0.0107230790371435 -0.00152753043081534 -0.00408686881956315 -0.0107242754196889 0.999934141541319 -0.0174572194691187 3.86217588228233e-05 -7.30351557439451e-06 6.30478969297781e-06 -2.64827976521063e-06 -2.9280603865516e-06 1.44745309141201e-05 -7.30351557439451e-06 5.18570075222014e-05 -4.36281852656225e-06 9.56573211503574e-06 4.12016538535561e-06 -9.87584189335504e-06 6.30478969297781e-06 -4.36281852656225e-06 1.73576193392365e-05 -1.02042433094875e-06 6.84580679027939e-07 -7.78824796528592e-07 -2.64827976521063e-06 9.56573211503574e-06 -1.02042433094875e-06 6.02352564943081e-05 7.65836339933846e-06 -1.65400096741688e-05 -2.9280603865516e-06 4.12016538535561e-06 6.84580679027939e-07 7.65836339933846e-06 2.99815349553168e-05 4.20031496301677e-06 1.44745309141201e-05 -9.87584189335504e-06 -7.78824796528592e-07 -1.65400096741688e-05 4.20031496301677e-06 4.55293850883692e-05 2509 2509 0 0 7 2513 2527 0 0 19 0 0 0 0 0 0 0 0 27 0 35 38 0 0 2349 +37 41 0.999992225569568 -0.000477758264021773 -0.00391414709281166 -0.00073891536324984 0.000487957997033419 0.999996487088164 0.00260532307473384 -0.000232212883381298 0.00391288862812861 -0.00260721275920634 0.999988945811009 0.00354010841524141 5.68912326058139e-05 7.3960806879252e-06 4.46081801431494e-06 8.75527898686032e-06 -5.68136262937445e-06 1.71242786816804e-05 7.3960806879252e-06 4.48463193309102e-05 -5.8582378388104e-06 6.97157109945362e-06 -5.8801991615898e-06 1.8906628912583e-06 4.46081801431494e-06 -5.8582378388104e-06 1.67279697325803e-05 -4.33248955157283e-06 1.6164075380378e-06 3.89735407843631e-06 8.75527898686032e-06 6.97157109945362e-06 -4.33248955157283e-06 4.96383625528126e-05 5.83214366148605e-06 -2.46806245688379e-06 -5.68136262937445e-06 -5.8801991615898e-06 1.6164075380378e-06 5.83214366148605e-06 2.70568730693042e-05 -4.29967914668183e-06 1.71242786816804e-05 1.8906628912583e-06 3.89735407843631e-06 -2.46806245688379e-06 -4.29967914668183e-06 4.4036133209958e-05 2898 2899 0 0 13 2904 2923 0 0 15 0 0 0 0 0 0 0 0 82 0 21 28 0 0 2497 +40 43 0.999999377904697 0.000776853983517927 -0.000800429951104438 0.00280570467957659 -0.000776179608415844 0.999999343883983 0.000842482533917608 0.00363504485360735 0.000801083911842045 -0.000841860732407169 0.999999324767309 -0.00434089436944016 3.4830462409459e-05 -3.29179027676704e-06 8.24058192347032e-06 -5.7707122703397e-06 2.32425054152159e-06 5.20788151517713e-06 -3.29179027676704e-06 2.10552732794173e-05 -6.96531844939204e-06 3.51767859498997e-06 -1.10069868830009e-06 -1.49003550055603e-06 8.24058192347032e-06 -6.96531844939204e-06 1.61118974810077e-05 -3.49761983395369e-06 2.06216315905442e-06 4.20306664402553e-06 -5.7707122703397e-06 3.51767859498997e-06 -3.49761983395369e-06 5.35637800323349e-05 4.19960000881483e-06 -2.78135352498921e-06 2.32425054152159e-06 -1.10069868830009e-06 2.06216315905442e-06 4.19960000881483e-06 2.00737684435371e-05 8.82251783349621e-07 5.20788151517713e-06 -1.49003550055603e-06 4.20306664402553e-06 -2.78135352498921e-06 8.82251783349621e-07 2.95784654142697e-05 2987 3005 0 0 19 2988 3006 0 0 23 0 0 0 0 0 0 0 0 18 0 12 19 0 0 2775 +41 44 0.999991014263416 0.00010808789324578 -0.00423788973795348 -0.0130365000675972 -6.47005498906309e-05 0.999947600904323 0.0102367602065875 0.000244696698505722 0.00423877414620802 -0.0102363940279604 0.99993862263193 -0.0116886155049486 4.85703373241251e-05 2.96597883243477e-07 3.5908292151788e-06 1.86021963905428e-06 -6.39278282563086e-06 2.20197414865928e-05 2.96597883243477e-07 2.62451395300855e-05 -3.03567741173207e-06 -4.48893754270208e-06 -3.67478103961021e-06 -2.73993826015083e-06 3.5908292151788e-06 -3.03567741173207e-06 1.51289568018326e-05 -7.9779440914436e-07 2.6130198194374e-06 7.90059582433698e-07 1.86021963905428e-06 -4.48893754270208e-06 -7.9779440914436e-07 5.44175856663535e-05 -3.92299932325532e-07 -7.30599179291351e-06 -6.39278282563086e-06 -3.67478103961021e-06 2.6130198194374e-06 -3.92299932325532e-07 3.33211085020209e-05 -4.73396297457593e-06 2.20197414865928e-05 -2.73993826015083e-06 7.90059582433698e-07 -7.30599179291351e-06 -4.73396297457593e-06 5.41697195279147e-05 2869 2869 0 0 4 2874 2881 0 0 4 0 0 0 0 0 0 0 0 27 0 34 37 0 0 2319 +39 43 0.999995308541175 0.000300685666765255 0.00304835755276123 0.0075928709643741 -0.000303077244243514 0.999999646654129 0.000784114661261186 0.00233742702181517 -0.00304812070359694 -0.000785034870426099 0.999995046327945 -0.00181135786164886 3.40072981625602e-05 -3.92624152551097e-06 5.99421153741453e-06 1.69683421926794e-06 1.44465350197399e-06 1.31848325575949e-05 -3.92624152551097e-06 2.6094743338961e-05 -4.83354458143689e-06 -2.15801607899478e-06 -1.28830626726619e-06 -6.50588518711164e-06 5.99421153741453e-06 -4.83354458143689e-06 1.59240752370162e-05 -7.63574188345542e-07 3.54104371886563e-06 8.76602047586512e-07 1.69683421926794e-06 -2.15801607899478e-06 -7.63574188345542e-07 4.03075486102898e-05 1.00433152674571e-05 2.80521392063862e-06 1.44465350197399e-06 -1.28830626726619e-06 3.54104371886563e-06 1.00433152674571e-05 2.11957465763751e-05 -1.62316951248721e-06 1.31848325575949e-05 -6.50588518711164e-06 8.76602047586512e-07 2.80521392063862e-06 -1.62316951248721e-06 3.31488889340459e-05 3113 3118 0 0 15 3113 3131 0 0 18 0 0 0 0 0 0 0 0 18 0 14 21 0 0 3008 +41 43 0.999978904645124 -7.58711718637346e-05 0.00649496022338397 0.00717965355462603 7.27930960717309e-05 0.999999884940204 0.000474152658762818 0.00223129883380803 -0.00649499545059304 -0.000473669868080693 0.999978795110653 -0.00794363208661096 4.41386699238339e-05 -7.57980317293457e-06 5.80804996824347e-06 -3.62213288164224e-08 -3.79810487757294e-06 5.97256460485903e-06 -7.57980317293457e-06 3.57755239826624e-05 -3.36396833278095e-06 7.14261774749816e-07 2.10985322099973e-06 -2.89543837289268e-06 5.80804996824347e-06 -3.36396833278095e-06 1.5846922761034e-05 -3.91773274464823e-06 2.4368572264033e-06 1.49191764481616e-06 -3.62213288164224e-08 7.14261774749816e-07 -3.91773274464823e-06 3.771162975257e-05 5.62249193238239e-06 -8.86760164751019e-07 -3.79810487757294e-06 2.10985322099973e-06 2.4368572264033e-06 5.62249193238239e-06 2.266621858673e-05 -2.88237118532506e-06 5.97256460485903e-06 -2.89543837289268e-06 1.49191764481616e-06 -8.86760164751019e-07 -2.88237118532506e-06 3.81595441773645e-05 3017 3023 0 0 13 3017 3041 0 0 16 0 0 0 0 0 0 0 0 18 0 6 8 0 0 2723 +40 42 0.999987942132096 0.000364456886026038 -0.00489721978216703 0.00112775297463509 -0.000387806574794658 0.999988558566839 -0.00476784453135951 -0.00335957044222605 0.00489542607718327 0.0047696862153497 0.999976642175671 0.0030471031849243 4.50310793817452e-05 -6.7644713037088e-06 8.35437871105152e-06 -2.40886069002637e-06 -1.03657970861896e-05 -3.15871385223506e-06 -6.7644713037088e-06 4.00643803073767e-05 -1.25008557928354e-06 -2.46470243242768e-06 4.75763753127075e-06 -2.61393598344454e-06 8.35437871105152e-06 -1.25008557928354e-06 1.60097794356612e-05 -3.66565686979924e-06 2.32074868418342e-06 -1.00563701985834e-06 -2.40886069002637e-06 -2.46470243242768e-06 -3.66565686979924e-06 4.51091331399126e-05 6.73239332478965e-06 -1.1274481518375e-05 -1.03657970861896e-05 4.75763753127075e-06 2.32074868418342e-06 6.73239332478965e-06 2.58577399016211e-05 -1.23211556601738e-06 -3.15871385223506e-06 -2.61393598344454e-06 -1.00563701985834e-06 -1.1274481518375e-05 -1.23211556601738e-06 4.14763065475039e-05 2937 2956 0 0 21 2937 2956 0 0 23 0 0 0 0 0 0 0 0 61 0 12 19 0 0 2638 +39 42 0.999999696971117 -0.000637566291744202 -0.000446729111152547 0.00265077131689929 0.000637457688575968 0.999999767248837 -0.000243207660565032 -0.000417283073859662 0.000446884068182097 0.000242922815959471 0.999999870641559 0.000514008362651268 3.03426827257611e-05 -1.26884209105029e-06 5.28011556926309e-06 4.5698000862791e-06 3.0197609955887e-06 -1.48995721997825e-06 -1.26884209105029e-06 1.84944000361144e-05 -6.95166045144311e-07 -2.12696645670115e-06 1.34948118008448e-06 4.97738252445541e-06 5.28011556926309e-06 -6.95166045144311e-07 1.29521038979112e-05 9.25476600924093e-07 3.53341765945198e-06 5.76011825755164e-07 4.5698000862791e-06 -2.12696645670115e-06 9.25476600924093e-07 3.22207922146442e-05 2.78180386989981e-06 -8.12003602118933e-08 3.0197609955887e-06 1.34948118008448e-06 3.53341765945198e-06 2.78180386989981e-06 1.81636271968611e-05 8.54793899405231e-07 -1.48995721997825e-06 4.97738252445541e-06 5.76011825755164e-07 -8.12003602118933e-08 8.54793899405231e-07 2.87237603953777e-05 3124 3127 0 0 13 3124 3140 0 0 15 0 0 0 0 0 0 0 0 65 0 16 23 0 0 2574 +42 44 0.999986585810622 0.000408862998870734 -0.00516343198508028 -0.0149949029600409 -0.000381605940998729 0.999985994506068 0.00527874687937649 -0.00054772003830114 0.00516551795294432 -0.00527670567294472 0.999972736529111 -0.00363486090261609 3.59063503626693e-05 -1.18382077827589e-06 4.26323134401122e-06 5.36097318086947e-06 1.57747394195432e-06 1.6311877789452e-05 -1.18382077827589e-06 4.19480065250451e-05 -6.53518665926579e-06 6.43501822596503e-06 -1.35529192233614e-06 -7.05828453817084e-06 4.26323134401122e-06 -6.53518665926579e-06 1.62597435479567e-05 -1.94944361937152e-06 3.97350562307833e-06 1.52245140741653e-06 5.36097318086947e-06 6.43501822596503e-06 -1.94944361937152e-06 7.06055416133563e-05 1.73899727533032e-06 -2.80933825353019e-06 1.57747394195432e-06 -1.35529192233614e-06 3.97350562307833e-06 1.73899727533032e-06 2.3365075528235e-05 -1.02847332370833e-06 1.6311877789452e-05 -7.05828453817084e-06 1.52245140741653e-06 -2.80933825353019e-06 -1.02847332370833e-06 4.70105218258351e-05 2721 2721 0 0 3 2731 2745 0 0 6 0 0 0 0 0 0 0 0 27 0 38 41 0 0 2543 +42 46 0.999999364266001 0.000383599693628757 0.00106033903463547 -0.00708197042129595 -0.000377051044444054 0.999980898532958 -0.00616931128468331 0.00122987008645669 -0.00106268532652306 0.00616890756070191 0.999980407447768 -0.00115368665170811 5.06393618614003e-05 -2.45622221437855e-06 4.24585319708196e-06 -1.35805938962399e-06 -2.79379673589787e-06 1.22021272266726e-06 -2.45622221437855e-06 3.19741458790449e-05 -7.1505613692893e-06 8.12524120367919e-06 -2.06300169029145e-06 2.50650248685155e-06 4.24585319708196e-06 -7.1505613692893e-06 1.70951327359848e-05 -4.15555264080879e-06 1.70871935184674e-06 1.498088996137e-06 -1.35805938962399e-06 8.12524120367919e-06 -4.15555264080879e-06 6.63173498918912e-05 5.33501090859512e-06 5.62137273337371e-06 -2.79379673589787e-06 -2.06300169029145e-06 1.70871935184674e-06 5.33501090859512e-06 2.51901903524486e-05 1.83526536118438e-06 1.22021272266726e-06 2.50650248685155e-06 1.498088996137e-06 5.62137273337371e-06 1.83526536118438e-06 3.23241425211703e-05 3018 3017 0 0 8 3020 3036 0 0 8 0 0 0 0 0 0 0 0 53 0 17 22 0 0 2369 +41 45 0.999992993867584 0.000602723674361314 -0.00369444717371921 0.00539766124726052 -0.00063632980698909 0.999958373706894 -0.00910197439238692 -0.00223798390213876 0.00368880741212858 0.00910426150960606 0.999951751397157 0.0147673647205469 3.33294813497651e-05 -1.20244085802723e-05 3.15611913938941e-06 5.23997969749998e-07 -2.89909130666728e-06 8.76215018350367e-06 -1.20244085802723e-05 4.89981570647568e-05 -3.25312480893599e-06 9.66177412435508e-06 5.84893079539296e-06 -1.04115915081049e-05 3.15611913938941e-06 -3.25312480893599e-06 1.82724795510696e-05 -5.99935381676902e-06 1.34691408782836e-06 3.60987925363476e-07 5.23997969749998e-07 9.66177412435508e-06 -5.99935381676902e-06 6.30176278875884e-05 1.13888978159256e-05 6.30485591890965e-06 -2.89909130666728e-06 5.84893079539296e-06 1.34691408782836e-06 1.13888978159256e-05 2.70100681959016e-05 -3.44297186318631e-06 8.76215018350367e-06 -1.04115915081049e-05 3.60987925363476e-07 6.30485591890965e-06 -3.44297186318631e-06 4.93836695457771e-05 2726 2741 0 0 12 2727 2744 0 0 16 0 0 0 0 0 0 0 0 28 0 9 11 0 0 2547 +44 46 0.99998784420137 8.68661151554389e-05 0.00492989896187633 0.0032971636728721 -3.74987812892317e-05 0.999949867231591 -0.0100130723239447 -0.00312983221950159 -0.00493052160908695 0.0100127657418509 0.999937715299739 -0.00125141387246631 4.71837802891792e-05 9.52257893026706e-06 7.37843044375304e-06 9.76434943064511e-06 -4.19413823201364e-06 1.13089764438613e-05 9.52257893026706e-06 5.24740825191907e-05 -7.96719832297218e-06 2.64381698458549e-05 -2.07912991595756e-06 -1.08574703124225e-06 7.37843044375304e-06 -7.96719832297218e-06 1.73382147419447e-05 -8.49110263990466e-06 6.54402604144769e-08 1.65838378808809e-06 9.76434943064511e-06 2.64381698458549e-05 -8.49110263990466e-06 8.37225598998867e-05 9.77721208279482e-06 2.24489625082897e-06 -4.19413823201364e-06 -2.07912991595756e-06 6.54402604144769e-08 9.77721208279482e-06 2.65445423452671e-05 -1.82617128627995e-06 1.13089764438613e-05 -1.08574703124225e-06 1.65838378808809e-06 2.24489625082897e-06 -1.82617128627995e-06 3.54749198366857e-05 2817 2830 0 0 10 2818 2834 0 0 13 0 0 0 0 0 0 0 0 25 0 8 10 0 0 2273 +43 47 0.999999479249194 0.000380086658648889 -0.00094711956598051 0.000276507136155656 -0.000374743589486697 0.999984051949709 0.00563519418326615 0.00242354003890582 0.000949246323397996 -0.00563483632174841 0.999983673642247 -0.00431239234796444 4.38236445620986e-05 -2.3394769366184e-06 7.34226052136071e-06 -2.27630226386646e-06 -5.7591542158374e-06 1.55274773381501e-05 -2.3394769366184e-06 3.22056940200288e-05 -4.9220651713801e-06 6.32703788916415e-06 8.25874477865349e-08 1.55388439130406e-05 7.34226052136071e-06 -4.9220651713801e-06 1.54274030377481e-05 -1.70313653167359e-06 -5.00986843198734e-07 4.89233040305428e-06 -2.27630226386646e-06 6.32703788916415e-06 -1.70313653167359e-06 5.1348251318634e-05 7.59139844678028e-06 4.66773532630113e-06 -5.7591542158374e-06 8.25874477865349e-08 -5.00986843198734e-07 7.59139844678028e-06 2.31952537495556e-05 -1.42033176893864e-06 1.55274773381501e-05 1.55388439130406e-05 4.89233040305428e-06 4.66773532630113e-06 -1.42033176893864e-06 3.9099915770533e-05 2787 2790 0 0 10 2788 2811 0 0 13 0 0 0 0 0 0 0 0 20 0 9 12 0 0 3047 +42 45 0.999997127260304 0.000836919807013995 -0.00224611584213682 0.0101292809798774 -0.000858276064844432 0.999954277130193 -0.00952402284903462 -0.00292786941025249 0.00223804229990979 0.00952592327646229 0.999952122830086 0.0170833651412057 9.06359682437282e-05 -1.50489691506699e-05 -7.68859038959955e-07 4.58311974403634e-06 -1.7064664339797e-05 3.09716096878177e-05 -1.50489691506699e-05 3.40389514170903e-05 -3.17536267209498e-06 4.04489870242998e-06 3.29242877641145e-06 -1.30816699315085e-06 -7.68859038959955e-07 -3.17536267209498e-06 1.76446422978037e-05 -4.51383057544965e-06 2.93621992662099e-06 5.78235955811671e-08 4.58311974403634e-06 4.04489870242998e-06 -4.51383057544965e-06 5.93438284729393e-05 6.63264157373871e-06 8.89076441038597e-06 -1.7064664339797e-05 3.29242877641145e-06 2.93621992662099e-06 6.63264157373871e-06 3.09401948575926e-05 -2.37058266726191e-06 3.09716096878177e-05 -1.30816699315085e-06 5.78235955811671e-08 8.89076441038597e-06 -2.37058266726191e-06 6.26256939196946e-05 2915 2926 0 1 17 2915 2935 0 1 17 0 0 0 0 0 0 0 0 27 0 6 8 0 0 2298 +45 48 0.999982705946296 -0.000535460379285752 0.00585671328526153 0.0039944883179784 0.000574822761735882 0.99997724671085 -0.00672128256958013 -0.00567143611451826 -0.00585298104525669 0.00672453290346374 0.999960260845457 -0.000367970742649606 4.97866021870953e-05 -1.2969559071249e-06 2.83361309651633e-06 4.94255383018336e-06 -6.81576446026202e-06 1.82588918887822e-05 -1.2969559071249e-06 3.51278931025664e-05 -4.42733984182346e-06 7.95360604973172e-06 6.67861762272961e-07 -8.68436091817939e-06 2.83361309651633e-06 -4.42733984182346e-06 1.49621417266039e-05 -2.13569582717123e-06 1.93465557211708e-06 1.30080873233496e-06 4.94255383018336e-06 7.95360604973172e-06 -2.13569582717123e-06 4.81559690478003e-05 7.24954126346076e-06 2.94931304871787e-06 -6.81576446026202e-06 6.67861762272961e-07 1.93465557211708e-06 7.24954126346076e-06 2.73995201298687e-05 -4.16628786550868e-06 1.82588918887822e-05 -8.68436091817939e-06 1.30080873233496e-06 2.94931304871787e-06 -4.16628786550868e-06 4.06751125927385e-05 2924 2938 0 0 14 2925 2940 0 0 20 0 0 0 0 0 0 0 0 53 0 27 31 0 0 2598 +45 49 0.999978095401716 -0.000291359881378645 -0.00661239942660938 -0.00199274742080419 0.000261833752080576 0.99998999446206 -0.00446569354689147 -0.00368700769807515 0.00661363438993814 0.00446386437831614 0.999968166370794 0.00226225377328206 4.20918771255913e-05 -9.92481231331697e-06 1.2346310884161e-06 7.47295200401583e-06 -5.4083791975534e-06 8.39329255967286e-06 -9.92481231331697e-06 4.14652665206046e-05 -4.40568810611026e-06 7.6982433120821e-06 -2.56771581670349e-07 -5.5160817522481e-06 1.2346310884161e-06 -4.40568810611026e-06 1.73078426466064e-05 -2.00117447791201e-06 -3.26813930502666e-07 3.41941818891248e-06 7.47295200401583e-06 7.6982433120821e-06 -2.00117447791201e-06 4.98616778952622e-05 3.35061671351477e-06 6.12112974053736e-06 -5.4083791975534e-06 -2.56771581670349e-07 -3.26813930502666e-07 3.35061671351477e-06 2.41276670338962e-05 -4.45290461562826e-06 8.39329255967286e-06 -5.5160817522481e-06 3.41941818891248e-06 6.12112974053736e-06 -4.45290461562826e-06 3.85379692141958e-05 2760 2760 0 0 10 2764 2781 0 0 12 0 0 0 0 0 0 0 0 66 0 10 13 0 0 2602 +44 47 0.999977024869759 0.000813328004456192 -0.00672965305075209 -0.00323606293222929 -0.000798265464865225 0.999997171198497 0.00224061760491851 0.000287394074031312 0.00673145637094478 -0.00223519407681627 0.999974845384905 -0.00262273191303544 4.87513023682038e-05 -8.78008828685943e-06 1.59159638180515e-07 5.02084489534064e-06 -2.64818407199619e-06 1.01755450238177e-05 -8.78008828685943e-06 7.55954503224398e-05 -7.58655115363141e-06 1.36591380740502e-05 -3.92916045169138e-06 -1.78840951168903e-05 1.59159638180515e-07 -7.58655115363141e-06 1.77215775779478e-05 -5.09987905166139e-06 -1.18139784166911e-06 4.68556074035492e-06 5.02084489534064e-06 1.36591380740502e-05 -5.09987905166139e-06 5.8987407448129e-05 9.43442525951513e-06 -8.12539681665839e-06 -2.64818407199619e-06 -3.92916045169138e-06 -1.18139784166911e-06 9.43442525951513e-06 3.04242670339461e-05 -5.48134435237028e-06 1.01755450238177e-05 -1.78840951168903e-05 4.68556074035492e-06 -8.12539681665839e-06 -5.48134435237028e-06 5.1934865604544e-05 2876 2888 0 0 7 2877 2891 0 0 8 0 0 0 0 0 0 0 0 20 0 12 15 0 0 2557 +43 45 0.999999889227514 0.000454393166105336 0.000122767304590711 0.00205093531169662 -0.000453975687462575 0.99999418655715 -0.00337946119659547 -0.00184617094262666 -0.000124302194962853 0.00337940508887265 0.999994282068758 0.00657843063908093 4.54534002794492e-05 -1.47685166948664e-05 4.34253362128616e-06 1.85817047085692e-06 -6.94749816361353e-06 1.04842606867979e-05 -1.47685166948664e-05 4.21959480246779e-05 -5.8927901463722e-06 1.22915300629917e-05 -1.88223831369613e-06 -8.6593992726409e-06 4.34253362128616e-06 -5.8927901463722e-06 1.67142182896391e-05 -2.20599152726114e-06 1.19333796230787e-06 1.82174660921908e-06 1.85817047085692e-06 1.22915300629917e-05 -2.20599152726114e-06 5.42218936337118e-05 3.46100260696652e-06 -5.11951150740076e-06 -6.94749816361353e-06 -1.88223831369613e-06 1.19333796230787e-06 3.46100260696652e-06 3.00932139696237e-05 -2.32625441634576e-06 1.04842606867979e-05 -8.6593992726409e-06 1.82174660921908e-06 -5.11951150740076e-06 -2.32625441634576e-06 3.98231083608212e-05 2850 2862 0 0 17 2851 2871 0 0 25 0 0 0 0 0 0 0 0 22 0 12 14 0 0 2182 +43 46 0.999992864023495 0.000486158528869539 -0.00374640520672385 -0.00523248098500208 -0.00050490985076902 0.999987343279957 -0.00500583119342974 -0.00310968499775446 0.00374392416199321 0.0050076870688298 0.99998045286 0.000195279548836848 3.12367125850896e-05 -9.44775723613738e-06 5.31053296193754e-06 -1.35306919345538e-06 -2.70454597281886e-07 3.78006858194555e-06 -9.44775723613738e-06 4.98356324564226e-05 -4.32080899399675e-06 1.09882731891563e-05 1.83665410227849e-06 -1.03194438184977e-05 5.31053296193754e-06 -4.32080899399675e-06 1.76660410848173e-05 -4.0708182572855e-06 2.13313643914949e-06 2.48977113036415e-06 -1.35306919345538e-06 1.09882731891563e-05 -4.0708182572855e-06 5.43753548425641e-05 3.67664852847293e-06 -3.94215700304444e-06 -2.70454597281886e-07 1.83665410227849e-06 2.13313643914949e-06 3.67664852847293e-06 2.60949845167633e-05 4.01283506893295e-06 3.78006858194555e-06 -1.03194438184977e-05 2.48977113036415e-06 -3.94215700304444e-06 4.01283506893295e-06 2.93888038886249e-05 2918 2917 0 0 6 2924 2943 0 0 9 0 0 0 0 0 0 0 0 25 0 13 15 0 0 2615 +44 48 0.999995152085867 0.00142153294147037 0.00277038785379497 0.00326936265560403 -0.00142342339693897 0.999998755373551 0.000680527135981311 -0.000388042879746332 -0.00276941701395561 -0.000684467271733878 0.9999959309087 -0.00318169667380954 4.33890315335197e-05 1.03189790665845e-05 1.08193078855894e-05 3.9973163889764e-07 -7.39243857748134e-06 1.98568035623619e-05 1.03189790665845e-05 5.14203419499535e-05 2.1191693020167e-06 6.65473629074514e-06 -4.87375463407525e-06 8.57885385518399e-06 1.08193078855894e-05 2.1191693020167e-06 2.09422744728379e-05 -6.71327428347463e-06 -2.08323015364133e-06 4.65753997255075e-06 3.9973163889764e-07 6.65473629074514e-06 -6.71327428347463e-06 5.99066532082599e-05 1.38732778181169e-05 5.63034870576564e-07 -7.39243857748134e-06 -4.87375463407525e-06 -2.08323015364133e-06 1.38732778181169e-05 2.78078893492392e-05 -1.12960121595017e-05 1.98568035623619e-05 8.57885385518399e-06 4.65753997255075e-06 5.63034870576564e-07 -1.12960121595017e-05 4.74116981545263e-05 2811 2811 0 2 9 2812 2827 0 2 9 0 0 0 0 0 0 0 0 16 0 10 13 0 0 2719 +45 47 0.99999572379657 -0.000820518810293538 0.00280698013120932 0.00119898887440101 0.000844378567832071 0.999963436593084 -0.00850955355956044 -0.00501146133994774 -0.00279989524968976 0.00851188732484144 0.999959853374504 -1.12037626491669e-07 5.49008963042652e-05 -5.40768725273455e-06 1.27189575735076e-06 -4.25362136259136e-08 -6.53555612427929e-06 1.96841491196455e-05 -5.40768725273455e-06 6.89952206330644e-05 -7.63381878340861e-06 2.31450509116551e-05 2.20461361802295e-06 4.72494143938894e-06 1.27189575735076e-06 -7.63381878340861e-06 1.80459348405799e-05 -7.80554484308482e-06 -2.14355243482835e-06 3.3081019160762e-06 -4.25362136259136e-08 2.31450509116551e-05 -7.80554484308482e-06 6.55250790089466e-05 7.44186616919192e-06 -4.01588901538254e-06 -6.53555612427929e-06 2.20461361802295e-06 -2.14355243482835e-06 7.44186616919192e-06 2.50398765366577e-05 -4.75825694393723e-06 1.96841491196455e-05 4.72494143938894e-06 3.3081019160762e-06 -4.01588901538254e-06 -4.75825694393723e-06 4.50670023475754e-05 2670 2672 0 0 13 2673 2693 0 0 16 0 0 0 0 0 0 0 0 66 0 19 27 0 0 2558 +46 49 0.999999090670587 0.000472137494719868 0.00126322768580947 -0.000615995492564823 -0.000473755181091296 0.99999906780299 0.00128060500513085 -0.00146010701330587 -0.00126262188659355 -0.0012812023013001 0.999998382152009 -0.000428997081389628 4.81836721807498e-05 -2.90001131491708e-05 5.64775482574277e-06 -8.64947087823012e-06 -7.69714722908279e-06 1.57307914095769e-05 -2.90001131491708e-05 0.000109929059582355 -6.59564410034591e-06 3.92918794035771e-05 6.84743705861678e-06 -2.93316135471927e-05 5.64775482574277e-06 -6.59564410034591e-06 1.74637811806009e-05 5.82286677248768e-07 1.68449581902018e-06 1.87513014395608e-06 -8.64947087823012e-06 3.92918794035771e-05 5.82286677248768e-07 6.46806747147849e-05 1.05809818367267e-05 -1.33368194273981e-05 -7.69714722908279e-06 6.84743705861678e-06 1.68449581902018e-06 1.05809818367267e-05 2.6307269880678e-05 -2.7473252943328e-06 1.57307914095769e-05 -2.93316135471927e-05 1.87513014395608e-06 -1.33368194273981e-05 -2.7473252943328e-06 4.22089723790554e-05 2809 2818 0 0 9 2813 2832 0 0 17 0 0 0 0 0 0 0 0 65 0 11 14 0 0 2648 +48 52 0.999961413000582 0.00340729515670469 -0.00809708895805177 0.000800202041364121 -0.00345185871327718 0.999978938752507 -0.00549606430403021 -0.00463704207684866 0.00807819170997319 0.00552380223447214 0.999952114067254 -0.0017314262463948 5.59334537020636e-05 -2.69495994477998e-05 7.48380740861934e-06 -8.20457729706653e-06 -6.70759950007365e-06 2.43338375955999e-05 -2.69495994477998e-05 9.40210737157884e-05 -8.23614058930108e-06 3.22683451203033e-05 6.92748351447711e-06 -3.67282644766048e-05 7.48380740861934e-06 -8.23614058930108e-06 1.85241724402052e-05 -3.17590271886252e-06 2.09636902193316e-07 4.11703949145073e-06 -8.20457729706653e-06 3.22683451203033e-05 -3.17590271886252e-06 7.39651227504804e-05 6.36999253144897e-06 -1.24735145063889e-05 -6.70759950007365e-06 6.92748351447711e-06 2.09636902193316e-07 6.36999253144897e-06 2.71095416853569e-05 -6.99625854540745e-06 2.43338375955999e-05 -3.67282644766048e-05 4.11703949145073e-06 -1.24735145063889e-05 -6.99625854540745e-06 5.70969294508366e-05 2724 2723 0 0 3 2733 2744 0 0 5 0 0 0 0 0 0 0 0 60 0 19 21 0 0 2686 +47 51 0.99999252498112 -7.73586441398734e-05 -0.0038657466969798 -8.62382373267844e-05 5.30151346950522e-05 0.999980172676483 -0.00629693920145047 -0.00462315060322185 0.00386615717224826 0.00629668718862921 0.999972701906991 0.00038370092049974 3.58981367474877e-05 -9.98488090838144e-06 5.16161244012848e-06 2.90941709872342e-06 -2.50474238402949e-06 1.13434648803666e-05 -9.98488090838144e-06 2.84231861096966e-05 -5.01396805939369e-06 3.09973623850007e-06 -1.60536428607045e-06 -8.46588941775609e-06 5.16161244012848e-06 -5.01396805939369e-06 1.50695447499516e-05 -2.07882983614324e-06 3.59366232793412e-06 3.81345199148436e-06 2.90941709872342e-06 3.09973623850007e-06 -2.07882983614324e-06 4.45341332704962e-05 6.88987419247025e-06 1.8238780418031e-06 -2.50474238402949e-06 -1.60536428607045e-06 3.59366232793412e-06 6.88987419247025e-06 2.3161615191794e-05 1.3907258110095e-06 1.13434648803666e-05 -8.46588941775609e-06 3.81345199148436e-06 1.8238780418031e-06 1.3907258110095e-06 2.96889490605821e-05 2940 2940 0 1 10 2942 2962 0 1 12 0 0 0 0 0 0 0 0 69 0 11 14 0 0 2786 +46 50 0.99999834319089 0.000843836816718379 -0.00161293363198643 0.00102837623600876 -0.000838291450169179 0.999993746761696 0.00343565204141793 0.00197270752950178 0.00161582267561004 -0.00343429424072494 0.999992797344135 -0.00577361164151045 2.31965186105652e-05 6.54726818581018e-06 5.68534578284196e-06 4.75849637963364e-06 -1.94167653739802e-06 1.13892084847463e-05 6.54726818581018e-06 2.80830219292178e-05 -1.04918235024175e-06 -3.4883878193218e-06 -3.80145315534325e-06 1.34860449403192e-05 5.68534578284196e-06 -1.04918235024175e-06 1.82464187032064e-05 -5.45289853935772e-06 1.59860350195644e-06 4.18762780036011e-06 4.75849637963364e-06 -3.4883878193218e-06 -5.45289853935772e-06 4.90058910155668e-05 1.82499334258883e-06 7.01729842021451e-07 -1.94167653739802e-06 -3.80145315534325e-06 1.59860350195644e-06 1.82499334258883e-06 2.17036133459857e-05 -7.09755316603474e-06 1.13892084847463e-05 1.34860449403192e-05 4.18762780036011e-06 7.01729842021451e-07 -7.09755316603474e-06 3.89985788951074e-05 2788 2799 0 0 12 2788 2804 0 0 13 0 0 0 0 0 0 0 0 63 0 29 33 0 0 3079 +49 52 0.999916998845818 0.00377240500277758 -0.0123192686336476 0.000922214968982576 -0.00374113133938224 0.99998972343471 0.00256065641445518 -0.000558433612724544 0.0123288018669475 -0.0025143558750537 0.999920836196076 -0.00615417785117292 3.91644890968153e-05 -4.39649495615544e-06 8.69385692966613e-06 -3.32797025342255e-06 -4.74476457655803e-06 1.24266796208668e-05 -4.39649495615544e-06 2.14602054247306e-05 -7.28399461320027e-06 1.66297718431826e-06 2.64488687885242e-07 4.06005071058141e-06 8.69385692966613e-06 -7.28399461320027e-06 1.34778594597094e-05 -1.04664335067061e-06 5.33589751055449e-07 1.80027556791507e-06 -3.32797025342255e-06 1.66297718431826e-06 -1.04664335067061e-06 3.73326957027541e-05 8.99669925505204e-06 7.17864440691561e-07 -4.74476457655803e-06 2.64488687885242e-07 5.33589751055449e-07 8.99669925505204e-06 2.21457205807807e-05 -1.51512504604129e-06 1.24266796208668e-05 4.06005071058141e-06 1.80027556791507e-06 7.17864440691561e-07 -1.51512504604129e-06 2.83694783619453e-05 2930 2943 0 1 4 2932 2945 0 1 8 0 0 0 0 0 0 0 0 58 0 35 37 0 0 2735 +46 48 0.999999870618733 -0.000492214460489891 -0.000128403434513434 -0.00357383834476785 0.000491596140556344 0.999988493893487 -0.0047718354823686 -0.00163616613803582 0.000130750723517341 0.00477177174234964 0.999988606484437 0.00376817099702362 4.60430579105952e-05 -4.62009888087022e-06 6.35392658169401e-06 -2.43346987140117e-06 -6.47208848040096e-06 1.14552071293822e-05 -4.62009888087022e-06 2.32904072462192e-05 -3.13970701571888e-06 5.37989876559574e-07 -1.3471699190865e-06 9.15091639051652e-06 6.35392658169401e-06 -3.13970701571888e-06 1.42988766189431e-05 -1.20549394382328e-06 3.24115127072429e-06 1.40815508183592e-06 -2.43346987140117e-06 5.37989876559574e-07 -1.20549394382328e-06 3.66641294641397e-05 4.37592297121604e-06 3.28583743735484e-06 -6.47208848040096e-06 -1.3471699190865e-06 3.24115127072429e-06 4.37592297121604e-06 2.39182909411116e-05 -4.83040429429207e-06 1.14552071293822e-05 9.15091639051652e-06 1.40815508183592e-06 3.28583743735484e-06 -4.83040429429207e-06 3.87940892440838e-05 3111 3118 0 2 9 3110 3125 0 2 11 0 0 0 0 0 0 0 0 47 0 30 34 0 0 2660 +48 51 0.999999137150092 -1.76527729503787e-05 0.00131354004577762 -0.00167738938979583 2.39517060161349e-05 0.999988501112439 -0.00479552595790948 -0.00184047649801841 -0.00131344028719741 0.00479555328161537 0.999987638695267 -0.00314865769239624 4.30522977795836e-05 -6.81507074561023e-06 5.73806497558849e-06 -5.52931980063019e-06 2.77707849819737e-06 1.93869346201747e-06 -6.81507074561023e-06 2.27445703432222e-05 -3.68352966468309e-06 -3.29249303323241e-06 -5.31133685797706e-06 -8.25649475321089e-07 5.73806497558849e-06 -3.68352966468309e-06 1.57754479507429e-05 -3.54748196204966e-06 1.97530212923469e-06 5.82055918277981e-06 -5.52931980063019e-06 -3.29249303323241e-06 -3.54748196204966e-06 4.66216082663646e-05 8.32026544754555e-06 -1.31191231810195e-06 2.77707849819737e-06 -5.31133685797706e-06 1.97530212923469e-06 8.32026544754555e-06 2.46598622722994e-05 -4.00896685713732e-06 1.93869346201747e-06 -8.25649475321089e-07 5.82055918277981e-06 -1.31191231810195e-06 -4.00896685713732e-06 3.19217879856562e-05 2859 2861 0 0 8 2859 2878 0 0 10 0 0 0 0 0 0 0 0 74 0 12 19 0 0 2662 +49 51 0.999994830254129 -0.000791964173461455 -0.00311644954463477 -0.00211213642755155 0.000761484945708874 0.999951990522559 -0.00976917553583651 -0.00763677818928094 0.0031240367625493 0.00976675190226932 0.99994742409368 0.00223043912164611 6.50279384783598e-05 2.85665805446475e-06 6.93175759321164e-06 1.58360700025487e-06 -1.26671690030586e-05 2.43726334911529e-05 2.85665805446475e-06 4.22308988015054e-05 -4.80532291444023e-06 3.26973364406436e-06 -3.75197438280492e-06 4.02866785187137e-06 6.93175759321164e-06 -4.80532291444023e-06 1.40474469584256e-05 -1.51470033992347e-06 3.04034064556318e-06 4.97074456565231e-06 1.58360700025487e-06 3.26973364406436e-06 -1.51470033992347e-06 4.41702479278442e-05 7.31588259802273e-06 -3.03762642939947e-06 -1.26671690030586e-05 -3.75197438280492e-06 3.04034064556318e-06 7.31588259802273e-06 3.12293590335949e-05 -1.04260530601494e-05 2.43726334911529e-05 4.02866785187137e-06 4.97074456565231e-06 -3.03762642939947e-06 -1.04260530601494e-05 5.05470448372716e-05 2848 2849 0 1 9 2852 2870 0 1 11 0 0 0 0 0 0 0 0 67 0 20 27 0 0 2521 +47 49 0.999990014027633 -0.000503336881302744 0.0044405514295915 0.00256776590864657 0.000512035181749764 0.999997952194185 -0.00195791404556182 -0.00149321324819401 -0.00443955684585491 0.00196016821244458 0.999988223968458 -0.000607651587977835 3.95744779210719e-05 -3.25563998778834e-07 2.71530922931643e-06 4.19565323666338e-06 -3.8378914538309e-06 9.73661820049716e-06 -3.25563998778834e-07 2.91092200360234e-05 -1.29684508714977e-06 -5.6104767800303e-07 -3.53999355714218e-06 -7.63091024773858e-07 2.71530922931643e-06 -1.29684508714977e-06 1.35761742635351e-05 -1.46347343912497e-06 2.56254219900391e-06 3.41778834531555e-06 4.19565323666338e-06 -5.6104767800303e-07 -1.46347343912497e-06 4.40181654199724e-05 4.86516384534974e-06 -4.51625955049782e-06 -3.8378914538309e-06 -3.53999355714218e-06 2.56254219900391e-06 4.86516384534974e-06 2.01970477201906e-05 -9.11138022000024e-07 9.73661820049716e-06 -7.63091024773858e-07 3.41778834531555e-06 -4.51625955049782e-06 -9.11138022000024e-07 3.34934264957155e-05 3017 3018 0 0 13 3018 3029 0 0 15 0 0 0 0 0 0 0 0 64 0 17 28 0 0 2639 +48 50 0.999999404048571 -0.000580359777373987 -0.000924708079178938 -0.00235174978714613 0.000574966440245262 0.999982886106823 -0.00582210503702172 -0.00305683896938652 0.000928071169406784 0.00582156989121735 0.999982623852988 -0.000879727716170086 5.48162770354196e-05 -7.6312984083383e-06 7.91288815694029e-06 -1.47461135766567e-05 -1.13997678320478e-06 1.24538977607111e-06 -7.6312984083383e-06 1.86755061524763e-05 -4.72265880175675e-06 -2.66055321750159e-06 -2.28451884619351e-06 2.08024329138281e-06 7.91288815694029e-06 -4.72265880175675e-06 1.84163819613938e-05 -6.2564838758939e-06 3.83561666706353e-07 2.49840462756126e-06 -1.47461135766567e-05 -2.66055321750159e-06 -6.2564838758939e-06 6.71039969665703e-05 6.42902122023483e-06 -3.27832680186046e-06 -1.13997678320478e-06 -2.28451884619351e-06 3.83561666706353e-07 6.42902122023483e-06 2.63669200820653e-05 -6.19339592810043e-06 1.24538977607111e-06 2.08024329138281e-06 2.49840462756126e-06 -3.27832680186046e-06 -6.19339592810043e-06 2.98614977995586e-05 2885 2885 0 0 10 2889 2906 0 0 14 0 0 0 0 0 0 0 0 60 0 12 15 0 0 2586 +51 53 0.998716976481325 0.0100370448085715 -0.0496352558118875 0.00304554958660461 -0.0100238267091158 0.999949627452073 0.000515224771820898 -0.000652194757431101 0.0496379268917065 -1.70285234002529e-05 0.998767278160395 -0.0220077933096417 4.97407207894498e-05 1.26814504633378e-05 2.23520284627403e-06 8.51149530996981e-06 -8.83667409041779e-06 2.01150689994748e-05 1.26814504633378e-05 5.01720728678887e-05 -2.62467622308489e-06 1.30092117894793e-05 2.04857227066889e-07 1.39792012597683e-05 2.23520284627403e-06 -2.62467622308489e-06 1.27878381082412e-05 -5.11372198373966e-07 1.19723719126275e-07 -6.53818613672224e-07 8.51149530996981e-06 1.30092117894793e-05 -5.11372198373966e-07 4.80915550512271e-05 2.11989776484917e-06 7.45211713172516e-06 -8.83667409041779e-06 2.04857227066889e-07 1.19723719126275e-07 2.11989776484917e-06 2.4955749651574e-05 -2.42082216161659e-06 2.01150689994748e-05 1.39792012597683e-05 -6.53818613672224e-07 7.45211713172516e-06 -2.42082216161659e-06 4.133702378144e-05 2534 2532 0 0 0 2544 2547 0 0 1 0 0 0 0 0 0 0 0 56 0 41 47 0 0 2682 +53 7 0.998764205247649 -0.0101226031901882 0.0486579409828007 0.000946994764460847 0.00999325309712424 0.99994585838048 0.00290089645839512 0.00525055066823831 -0.0486846711868176 -0.00241106042634866 0.998811288271739 0.023962848897803 3.13340627639428e-05 -7.50258289176549e-06 2.32085477024534e-06 -4.60410536381322e-06 2.72488690421055e-06 -2.25428971001151e-06 -7.50258289176549e-06 2.27029904952047e-05 -1.61606028246613e-06 8.96881360133657e-07 -2.65668356918838e-06 5.63926380057816e-06 2.32085477024534e-06 -1.61606028246613e-06 1.27160636283347e-05 1.19708661851391e-06 -9.93057878111493e-07 3.07132763628927e-06 -4.60410536381322e-06 8.96881360133657e-07 1.19708661851391e-06 6.00057618676205e-05 3.15996163569026e-06 5.88544542830519e-06 2.72488690421055e-06 -2.65668356918838e-06 -9.93057878111493e-07 3.15996163569026e-06 2.47317094010561e-05 1.17944008335156e-06 -2.25428971001151e-06 5.63926380057816e-06 3.07132763628927e-06 5.88544542830519e-06 1.17944008335156e-06 3.37009820142518e-05 2977 2984 0 0 25 2970 2977 0 0 25 0 0 0 0 0 0 0 0 58 0 1 1 0 0 2580 +50 53 0.998799509377464 0.00917413569061978 -0.0481183468301635 0.00451097835456716 -0.00930532113417382 0.999953571906175 -0.00250300432910712 -0.00379806290925458 0.0480931498856928 0.00294775616558209 0.99883850529886 -0.0201965843806064 3.64931844449239e-05 2.89934981027907e-07 1.74324904231094e-06 -6.59094446689563e-06 -2.9220202963134e-06 8.73152263161295e-06 2.89934981027907e-07 3.40349167736195e-05 -1.72724513176464e-06 1.9704116358107e-06 2.46862542205683e-06 1.13897139312655e-05 1.74324904231094e-06 -1.72724513176464e-06 1.30138421547176e-05 3.08429841723906e-06 -3.5757792662671e-06 -2.91281744420414e-07 -6.59094446689563e-06 1.9704116358107e-06 3.08429841723906e-06 4.91468629917483e-05 -1.74469074171362e-07 1.33458205459548e-06 -2.9220202963134e-06 2.46862542205683e-06 -3.5757792662671e-06 -1.74469074171362e-07 2.08971724905451e-05 -1.77179866372809e-06 8.73152263161295e-06 1.13897139312655e-05 -2.91281744420414e-07 1.33458205459548e-06 -1.77179866372809e-06 3.26298752878251e-05 2432 2430 0 2 0 2437 2443 0 2 1 0 0 0 0 0 0 0 0 52 0 23 27 0 0 2667 +49 53 0.998613671198835 0.0095113442520892 -0.0517713243533917 0.00301990657860093 -0.00980844175212982 0.999936838341626 -0.00548760400800546 -0.00699427667366428 0.0517158598998501 0.00598779240387063 0.998643888569367 -0.0176111895570534 3.42225031870272e-05 -9.72848671399438e-06 2.44020816527299e-06 -3.88008368576857e-07 -4.92656368505122e-06 1.61294436383597e-05 -9.72848671399438e-06 0.000149154476116048 -1.72888945130887e-07 3.88363008641886e-05 9.85534209389958e-06 -1.96135867494014e-05 2.44020816527299e-06 -1.72888945130887e-07 1.2451484700092e-05 3.09200982684307e-07 1.56253019900484e-06 -3.93890838580676e-06 -3.88008368576857e-07 3.88363008641886e-05 3.09200982684307e-07 5.8509137689121e-05 5.3015899116956e-06 -2.75088857892326e-06 -4.92656368505122e-06 9.85534209389958e-06 1.56253019900484e-06 5.3015899116956e-06 2.45885687918908e-05 -4.65914676001268e-07 1.61294436383597e-05 -1.96135867494014e-05 -3.93890838580676e-06 -2.75088857892326e-06 -4.65914676001268e-07 5.35402950561406e-05 2494 2493 0 2 1 2499 2509 0 2 3 0 0 0 0 0 0 0 0 53 0 41 47 0 0 2669 +53 27 0.99862344944889 -0.0105009858574984 0.0513900331467193 0.00197785433548179 0.0104381088862219 0.999944408716586 0.00149176382736492 0.00202915107651004 -0.0514028412996758 -0.000953295577394223 0.998677545123481 0.020372176285659 3.0136821580174e-05 -1.12439468922455e-05 3.70627579030261e-06 6.09395072897148e-06 6.95959293155001e-07 -2.93378985270492e-07 -1.12439468922455e-05 3.27019847373931e-05 -1.59952701962814e-06 6.21729044000328e-06 1.00813741139176e-06 1.07974554942012e-05 3.70627579030261e-06 -1.59952701962814e-06 1.19131586522723e-05 7.22179324183806e-07 -1.41216751445345e-07 1.24068247141316e-06 6.09395072897148e-06 6.21729044000328e-06 7.22179324183806e-07 6.81702599096319e-05 4.83080611988563e-06 1.31655579009775e-05 6.95959293155001e-07 1.00813741139176e-06 -1.41216751445345e-07 4.83080611988563e-06 2.23580106882231e-05 4.03821606722075e-07 -2.93378985270492e-07 1.07974554942012e-05 1.24068247141316e-06 1.31655579009775e-05 4.03821606722075e-07 3.48781506640715e-05 2920 2930 0 0 28 2916 2930 0 0 28 0 0 0 0 0 0 0 0 62 0 0 0 0 0 2832 +53 22 0.998554020548928 -0.00895835906867269 0.0530058095718531 0.00122019880959621 0.00887859708264914 0.999959070504901 0.00174006575110943 0.00143565147885271 -0.0530192282046315 -0.0012669324255617 0.998592687897731 0.0191914045595319 3.76568760303183e-05 -1.1383884124968e-05 7.84694959854256e-07 2.72169513695003e-06 -2.30994658090522e-06 -1.47860313902329e-06 -1.1383884124968e-05 4.13913380981125e-05 -2.5605212557561e-06 6.99194964646059e-06 3.9557955046824e-07 6.43025833718292e-06 7.84694959854256e-07 -2.5605212557561e-06 1.25623561852349e-05 9.91305764274006e-07 -3.41992287374611e-06 2.61255798530352e-08 2.72169513695003e-06 6.99194964646059e-06 9.91305764274006e-07 5.36868460529552e-05 8.60595102396296e-07 1.46323717636361e-05 -2.30994658090522e-06 3.9557955046824e-07 -3.41992287374611e-06 8.60595102396296e-07 2.75916815434828e-05 -6.14066371799692e-07 -1.47860313902329e-06 6.43025833718292e-06 2.61255798530352e-08 1.46323717636361e-05 -6.14066371799692e-07 3.63382750972346e-05 2700 2711 0 0 26 2696 2710 0 0 26 0 0 0 0 0 0 0 0 64 0 0 2 0 0 2797 +50 52 0.999922957557014 0.00360774390263189 -0.0118770002259493 -0.000769509050062662 -0.0035868623791895 0.999991984791884 0.00177898011809165 -0.0022124266557105 0.0118833231339947 -0.00173624189582924 0.999927883447288 0.00190652754242134 4.41950909255314e-05 -1.27011789111329e-05 6.54370367838511e-06 -1.71392417610868e-06 -4.50964970094825e-06 1.98798465381972e-05 -1.27011789111329e-05 3.46654394891458e-05 -4.90481073311193e-06 2.63420088028897e-06 -1.64332817122964e-06 -8.10453214718117e-06 6.54370367838511e-06 -4.90481073311193e-06 1.43222323725485e-05 -6.58467608018824e-07 2.64803100342079e-06 4.8279167499562e-06 -1.71392417610868e-06 2.63420088028897e-06 -6.58467608018824e-07 4.27228292786116e-05 5.70884711226275e-06 -5.71616243744817e-06 -4.50964970094825e-06 -1.64332817122964e-06 2.64803100342079e-06 5.70884711226275e-06 2.31081428069481e-05 -2.35303357238629e-06 1.98798465381972e-05 -8.10453214718117e-06 4.8279167499562e-06 -5.71616243744817e-06 -2.35303357238629e-06 3.80213227601249e-05 2991 2990 0 1 2 2998 3008 0 1 5 0 0 0 0 0 0 0 0 57 0 18 20 0 0 2689 +53 21 0.998442079179167 -0.00921237805094276 0.0550322325099426 0.00319930538670099 0.00882710916289198 0.999934831844484 0.00723976573994053 0.00608554498727216 -0.0550953416198526 -0.00674271123431341 0.998458331217183 0.0187899453053662 2.48089028145216e-05 -8.47521955465368e-06 2.13614318632258e-06 3.79345669801851e-06 3.02173663091836e-06 1.10203015618302e-07 -8.47521955465368e-06 4.4968123295715e-05 -1.02753524082681e-06 8.48459593363257e-06 1.60381172297372e-06 9.00312171097804e-06 2.13614318632258e-06 -1.02753524082681e-06 1.2350312749656e-05 -5.09668636932159e-07 -1.55971156559823e-06 2.00981775628392e-06 3.79345669801851e-06 8.48459593363257e-06 -5.09668636932159e-07 5.24824323651465e-05 1.43663684493264e-06 1.03691160930874e-05 3.02173663091836e-06 1.60381172297372e-06 -1.55971156559823e-06 1.43663684493264e-06 2.80820702304139e-05 -2.58646805627661e-06 1.10203015618302e-07 9.00312171097804e-06 2.00981775628392e-06 1.03691160930874e-05 -2.58646805627661e-06 3.29087832311007e-05 2787 2798 0 0 25 2783 2799 0 0 25 0 0 0 0 0 0 0 0 71 0 7 9 0 0 2761 +53 24 0.999006289369142 -0.00953941430657665 0.0435365751476446 0.0026787149923793 0.0096151251460734 0.99995260320358 -0.00152993947902504 -0.00107234455138805 -0.0435199169269011 0.00194702878037619 0.9990506623338 0.0241252265190948 6.23311957030068e-05 -5.08804283097365e-05 7.4048502137918e-06 -2.05618434990443e-05 -1.61333077496698e-05 2.54229185519281e-05 -5.08804283097365e-05 0.000160404092220752 -6.93766675798904e-06 4.35992804228554e-05 1.84723306654996e-05 -2.60512820349826e-05 7.4048502137918e-06 -6.93766675798904e-06 1.45131284246025e-05 -8.4261044477714e-07 -5.02292580216324e-07 2.89539464521579e-06 -2.05618434990443e-05 4.35992804228554e-05 -8.4261044477714e-07 7.99467844950546e-05 1.32799007173677e-05 -9.63327644299207e-06 -1.61333077496698e-05 1.84723306654996e-05 -5.02292580216324e-07 1.32799007173677e-05 3.20665668335101e-05 -8.77555853993307e-06 2.54229185519281e-05 -2.60512820349826e-05 2.89539464521579e-06 -9.63327644299207e-06 -8.77555853993307e-06 6.89188461506098e-05 2852 2862 0 0 28 2850 2863 0 0 28 0 0 0 0 0 0 0 0 61 0 0 4 0 0 2596 +53 26 0.998818375821568 -0.00977922113925544 0.0476048207125619 0.00408653000888763 0.00989082920492071 0.999948859509493 -0.00210946991070882 -0.001023751510682 -0.0475817572059367 0.00257782846105747 0.998864020365946 0.0220774968017007 3.89940521699469e-05 -7.18865556324057e-06 3.2812845017725e-06 3.12141656322687e-06 -7.01573738872105e-06 1.08601421062625e-05 -7.18865556324057e-06 5.08183468225774e-05 -8.9888311163414e-08 2.82359801394246e-06 -1.03688121506844e-06 1.46778249811479e-05 3.2812845017725e-06 -8.9888311163414e-08 1.25185718148358e-05 2.48218875674104e-06 5.55721333138902e-08 1.17043006115068e-06 3.12141656322687e-06 2.82359801394246e-06 2.48218875674104e-06 4.75831250472686e-05 3.4007387828373e-06 1.13337167774385e-06 -7.01573738872105e-06 -1.03688121506844e-06 5.55721333138902e-08 3.4007387828373e-06 2.87621320841706e-05 -7.00656493881486e-06 1.08601421062625e-05 1.46778249811479e-05 1.17043006115068e-06 1.13337167774385e-06 -7.00656493881486e-06 5.08296058267417e-05 2901 2922 0 0 35 2899 2920 0 0 35 0 0 0 0 0 0 0 0 62 0 0 2 0 0 2833 +53 9 0.99876865810634 -0.00929038318824091 0.0487324980344477 -0.00106582122113466 0.00919974593162368 0.999955510100455 0.00208386528651376 0.00597641473489775 -0.0487496898375299 -0.00163297273535546 0.998809692154011 0.0270156785179378 4.64064366864336e-05 -9.44816664896631e-06 2.4852522550274e-06 1.51920898281843e-06 -3.62538163627396e-07 -8.99756409556009e-07 -9.44816664896631e-06 2.74452699091255e-05 -3.10880573345266e-06 -3.11918623495431e-06 3.4205881057709e-06 7.7166059789647e-06 2.4852522550274e-06 -3.10880573345266e-06 1.58054153588289e-05 2.77618683468645e-07 -2.63836453592783e-06 -4.77213931856253e-07 1.51920898281843e-06 -3.11918623495431e-06 2.77618683468645e-07 5.24958775130513e-05 2.69690092352685e-06 5.00948278714244e-06 -3.62538163627396e-07 3.4205881057709e-06 -2.63836453592783e-06 2.69690092352685e-06 2.73012585719453e-05 2.17199038548988e-06 -8.99756409556009e-07 7.7166059789647e-06 -4.77213931856253e-07 5.00948278714244e-06 2.17199038548988e-06 2.87776085490469e-05 2967 2982 0 0 24 2962 2978 0 0 24 0 0 0 0 0 0 0 0 51 0 1 2 0 0 2752 +53 25 0.99889426118094 -0.01000625447957 0.0459361497197383 0.00236832012822807 0.0101233293816801 0.999946074074351 -0.00231671006427428 0.000203743901522946 -0.0459104909798854 0.00277917516216279 0.998941691493254 0.0175114876121709 4.10188280332226e-05 -1.26469186405535e-05 4.75177458804279e-06 5.23707454909456e-06 -5.32093188288091e-06 5.70716449357941e-07 -1.26469186405535e-05 5.56598285218125e-05 -4.18182467757515e-06 9.25862376035449e-06 2.15265695554227e-06 1.55648720908222e-05 4.75177458804279e-06 -4.18182467757515e-06 1.3498309299545e-05 1.80939891014602e-06 -3.68342005908376e-06 7.84568447204586e-08 5.23707454909456e-06 9.25862376035449e-06 1.80939891014602e-06 5.20054423627359e-05 -8.03523709275636e-07 1.02814397427679e-05 -5.32093188288091e-06 2.15265695554227e-06 -3.68342005908376e-06 -8.03523709275636e-07 2.74952436700855e-05 -2.17734016259031e-06 5.70716449357941e-07 1.55648720908222e-05 7.84568447204586e-08 1.02814397427679e-05 -2.17734016259031e-06 3.94385680655412e-05 2834 2842 0 0 27 2826 2840 0 0 27 0 0 0 0 0 0 0 0 88 0 0 1 0 0 2746 +53 20 0.998779263767397 -0.0103843943122063 0.0482923039730499 -0.00485241162365162 0.0101584621649626 0.999936290132349 0.00492151631078594 0.00544680431213045 -0.0483403342427404 -0.00442493289473692 0.998821121149416 0.019908766704093 2.72813762962338e-05 -6.61467874259963e-06 2.30269054915752e-06 -1.03998485410401e-06 5.4129384093695e-06 -6.49405185705356e-07 -6.61467874259963e-06 2.36672136222654e-05 -1.9368264891321e-06 -4.11819454911797e-06 2.91316284920441e-06 7.00871594139826e-06 2.30269054915752e-06 -1.9368264891321e-06 1.29896776364101e-05 -7.01922084026681e-07 -2.15288751099786e-06 -7.42779491695836e-07 -1.03998485410401e-06 -4.11819454911797e-06 -7.01922084026681e-07 6.3384034302713e-05 -2.30539647672956e-06 3.94744791331273e-06 5.4129384093695e-06 2.91316284920441e-06 -2.15288751099786e-06 -2.30539647672956e-06 2.51748386895966e-05 2.15176485127573e-06 -6.49405185705356e-07 7.00871594139826e-06 -7.42779491695836e-07 3.94744791331273e-06 2.15176485127573e-06 3.41100411674687e-05 2973 2979 0 0 23 2967 2983 0 0 23 0 0 0 0 0 0 0 0 63 0 9 11 0 0 2751 +53 8 0.999002934034445 -0.00837347729014564 0.0438522823652535 -0.000275949122902715 0.00880902570289995 0.999913681505466 -0.00974836418842056 -0.00114366816780668 -0.0437668693961101 0.0101249403087548 0.998990463781816 0.0338648413140732 4.02849601213654e-05 -2.11366144502781e-05 1.04127882424055e-06 -2.52399257514662e-06 -9.19205610252949e-07 -3.53153455631838e-06 -2.11366144502781e-05 8.827821026133e-05 -6.4835027439781e-06 2.01142390382418e-05 9.64780596774964e-06 3.44627901198773e-06 1.04127882424055e-06 -6.4835027439781e-06 1.64154969813331e-05 -4.6172533411315e-06 -2.38040054770819e-06 -1.96044098855621e-06 -2.52399257514662e-06 2.01142390382418e-05 -4.6172533411315e-06 6.91169841090615e-05 9.05812501502341e-06 5.90370628159448e-06 -9.19205610252949e-07 9.64780596774964e-06 -2.38040054770819e-06 9.05812501502341e-06 2.66781758955949e-05 2.95756354059579e-06 -3.53153455631838e-06 3.44627901198773e-06 -1.96044098855621e-06 5.90370628159448e-06 2.95756354059579e-06 3.86394513556217e-05 2744 2762 0 0 33 2741 2759 0 0 33 0 0 0 0 0 0 0 0 68 0 0 2 0 0 2684 +53 19 0.998530816416717 -0.00888771622685287 0.0534529434777578 0.00259177310260383 0.00866467971550433 0.999952767884711 0.00440287691549518 0.00377594865016482 -0.0534895503027756 -0.00393325564592599 0.998560662908584 0.0216395787769079 3.55522911498371e-05 -1.10579346417422e-05 -3.21291183523937e-07 3.31031495197101e-06 3.51098563793486e-07 -1.9054942183716e-06 -1.10579346417422e-05 4.09051249624996e-05 -2.13223396189029e-06 9.11494218313464e-06 9.68986810454875e-07 8.81679260818337e-06 -3.21291183523937e-07 -2.13223396189029e-06 1.52629236203656e-05 -1.96099033621779e-06 -6.24127222519753e-06 -3.81107406802684e-07 3.31031495197101e-06 9.11494218313464e-06 -1.96099033621779e-06 7.06203071295932e-05 2.75141292308579e-06 7.75059216547287e-06 3.51098563793486e-07 9.68986810454875e-07 -6.24127222519753e-06 2.75141292308579e-06 2.88404005599101e-05 -8.54192933976685e-07 -1.9054942183716e-06 8.81679260818337e-06 -3.81107406802684e-07 7.75059216547287e-06 -8.54192933976685e-07 3.24492605405535e-05 2800 2819 0 0 37 2797 2816 0 0 37 0 0 0 0 0 0 0 0 74 0 0 4 0 0 2576 +53 23 0.999097610587683 -0.00925200034922046 0.0414531664354059 0.00188910366824089 0.00962705662739768 0.99991443088641 -0.00885723917486072 -0.00481254191013776 -0.0413676721447595 0.00924831847666556 0.999101188222033 0.0278506277456225 3.41813387197086e-05 -1.85772469626492e-05 1.31733418861979e-06 -6.14075618074871e-06 -8.47481764652461e-07 -2.02529054673327e-06 -1.85772469626492e-05 8.75651524461588e-05 4.19546508874288e-07 3.54238740785425e-05 2.38087602092958e-06 3.052728581012e-06 1.31733418861979e-06 4.19546508874288e-07 1.29944566856309e-05 -7.14964211687089e-07 1.01602150239926e-07 1.84602274545505e-06 -6.14075618074871e-06 3.54238740785425e-05 -7.14964211687089e-07 8.07879659472841e-05 5.31111142480369e-06 3.94174299969753e-06 -8.47481764652461e-07 2.38087602092958e-06 1.01602150239926e-07 5.31111142480369e-06 2.82522351674345e-05 -1.05198564305559e-06 -2.02529054673327e-06 3.052728581012e-06 1.84602274545505e-06 3.94174299969753e-06 -1.05198564305559e-06 3.46695087407811e-05 2718 2725 0 0 27 2716 2723 0 0 27 0 0 0 0 0 0 0 0 63 0 0 1 0 0 2704 +53 17 0.999127654087518 -0.00899644643274546 0.0407798331182838 -0.00226257945285337 0.00933844252728202 0.999922743563565 -0.00820368182455655 -0.0025576661807613 -0.0407028786296127 0.00857734550409684 0.999134477843381 0.0289561915409571 3.85108287202141e-05 -2.0689530993443e-05 2.20703514448104e-06 -7.89716950089531e-06 5.52488068507284e-07 2.59948878712572e-06 -2.0689530993443e-05 9.48802664784942e-05 -5.78505158372883e-06 2.36356441789835e-05 6.85559315127248e-06 -4.41694367341166e-06 2.20703514448104e-06 -5.78505158372883e-06 1.29496507836381e-05 -7.87915500287922e-07 -8.90441512731637e-07 -5.93686054919163e-07 -7.89716950089531e-06 2.36356441789835e-05 -7.87915500287922e-07 8.9058905541649e-05 4.63444872381221e-06 4.00575254710761e-07 5.52488068507284e-07 6.85559315127248e-06 -8.90441512731637e-07 4.63444872381221e-06 2.59829047720177e-05 1.70326810660036e-06 2.59948878712572e-06 -4.41694367341166e-06 -5.93686054919163e-07 4.00575254710761e-07 1.70326810660036e-06 3.92136745756162e-05 2696 2706 0 0 25 2693 2703 0 0 25 0 0 0 0 0 0 0 0 71 0 1 2 0 0 2681 +53 11 0.998630613540618 -0.0101574068210803 0.0513198283917623 -0.00289359080802035 0.0100043295264456 0.999944710201979 0.00323881611183359 0.0029891711461257 -0.0513498889016827 -0.00272096044643379 0.99867701750067 0.0296204399349908 3.05675515258266e-05 -1.08008182069105e-05 3.67537409670672e-06 3.72414889820203e-06 -6.86039499511774e-07 2.45877148399045e-06 -1.08008182069105e-05 3.5179916758883e-05 -2.89184560471432e-06 4.57388273860962e-07 1.76088574534357e-06 6.14347831599686e-06 3.67537409670672e-06 -2.89184560471432e-06 1.24473870156875e-05 -8.68227317012227e-07 1.56833302080558e-06 1.4565866488074e-06 3.72414889820203e-06 4.57388273860962e-07 -8.68227317012227e-07 6.35538227081305e-05 3.85487321571429e-06 1.01153926278427e-05 -6.86039499511774e-07 1.76088574534357e-06 1.56833302080558e-06 3.85487321571429e-06 3.00197914244073e-05 -5.33727759565218e-06 2.45877148399045e-06 6.14347831599686e-06 1.4565866488074e-06 1.01153926278427e-05 -5.33727759565218e-06 3.77962411684286e-05 2961 2970 0 0 24 2958 2974 0 0 24 0 0 0 0 0 0 0 0 73 0 9 12 0 0 2627 +53 18 0.998640300987971 -0.00949287921020627 0.0512585064838588 0.00363008722977713 0.00921246420234631 0.99994129512106 0.00570410509524867 0.00323740162351764 -0.0513096457401126 -0.00522413207313786 0.998669128739898 0.0210976151893097 3.24029655804234e-05 -1.36398745566398e-05 9.37355434887906e-07 1.85056951550469e-06 4.70303584410521e-06 3.21961483484712e-07 -1.36398745566398e-05 5.48779985334842e-05 -4.29166774772108e-06 2.08621327168206e-05 -3.17410562697219e-06 3.87203539912296e-06 9.37355434887906e-07 -4.29166774772108e-06 1.39165358095891e-05 -9.68315019055746e-07 -4.74255780674108e-06 1.07619061520763e-06 1.85056951550469e-06 2.08621327168206e-05 -9.68315019055746e-07 7.10256721223659e-05 1.01240597084694e-06 8.34660291176143e-06 4.70303584410521e-06 -3.17410562697219e-06 -4.74255780674108e-06 1.01240597084694e-06 2.71005002145298e-05 1.03895827092696e-06 3.21961483484712e-07 3.87203539912296e-06 1.07619061520763e-06 8.34660291176143e-06 1.03895827092696e-06 2.8074650962966e-05 2819 2832 0 0 24 2815 2828 0 0 24 0 0 0 0 0 0 0 0 67 0 0 1 0 0 2727 +53 12 0.998676593470538 -0.00988400752916567 0.0504714577681709 0.00205522962169795 0.00962642229637766 0.999939384323974 0.00534412495773529 0.00440427658687746 -0.0505212197779573 -0.00485119294148176 0.99871120564415 0.0272435337008981 2.61934316969127e-05 -8.95676393847514e-06 1.40140119204403e-06 2.74602371879858e-06 4.57882825979951e-06 1.43823241661771e-06 -8.95676393847514e-06 4.78129439211866e-05 1.36204604547121e-06 8.28755214263731e-06 -1.37755284293839e-06 6.72331538896492e-06 1.40140119204403e-06 1.36204604547121e-06 1.26196216893015e-05 -2.79211264900036e-07 -2.98629429287621e-06 9.2379670255705e-07 2.74602371879858e-06 8.28755214263731e-06 -2.79211264900036e-07 6.20415053773725e-05 3.88803551065687e-06 8.57934570380882e-06 4.57882825979951e-06 -1.37755284293839e-06 -2.98629429287621e-06 3.88803551065687e-06 2.25782336746823e-05 -1.2135346961662e-06 1.43823241661771e-06 6.72331538896492e-06 9.2379670255705e-07 8.57934570380882e-06 -1.2135346961662e-06 3.16625259294073e-05 2770 2784 0 0 23 2763 2777 0 0 23 0 0 0 0 0 0 0 0 67 0 0 1 0 0 2745 +54 4 0.999154100240902 -0.0161431246972159 0.037821733127987 -0.00466136223034161 0.016011831278525 0.999864688490699 0.00377173282519415 0.00430987946117579 -0.0378775029655147 -0.0031629471077992 0.999277384180534 0.0742137744153153 4.11040277248004e-05 -1.10771577579797e-05 1.21001502612405e-06 1.38329065794429e-05 -3.89008633691269e-07 3.76996605797281e-06 -1.10771577579797e-05 3.73576689657211e-05 -2.37327054663392e-06 8.09605506644693e-06 -4.01923229154792e-06 1.44198526394632e-05 1.21001502612405e-06 -2.37327054663392e-06 1.28213299989714e-05 1.65889375603373e-06 -3.41792382010714e-07 1.05983329120161e-06 1.38329065794429e-05 8.09605506644693e-06 1.65889375603373e-06 8.71085859394352e-05 -4.9184123759389e-06 2.53755474737178e-05 -3.89008633691269e-07 -4.01923229154792e-06 -3.41792382010714e-07 -4.9184123759389e-06 3.10008139746985e-05 -4.47620871254681e-06 3.76996605797281e-06 1.44198526394632e-05 1.05983329120161e-06 2.53755474737178e-05 -4.47620871254681e-06 4.3366812462715e-05 2884 2891 0 0 34 2873 2889 0 0 40 0 0 0 0 0 0 0 0 43 0 10 12 0 0 2877 +53 16 0.998556822647363 -0.00851877598211234 0.0530254882124555 0.000969271016449067 0.00843867483375951 0.999962889750426 0.0017343266786709 0.00355616847271411 -0.0530382947638096 -0.00128435888475991 0.998591653134955 0.0194386831239953 3.44120835314473e-05 -1.1448948447845e-05 1.59818023731635e-06 -2.40778344995358e-06 7.80170352851492e-07 1.03060131625441e-06 -1.1448948447845e-05 4.54076040862059e-05 -4.82066716693556e-07 3.34737298074015e-06 3.27044636527317e-06 7.39274577279536e-06 1.59818023731635e-06 -4.82066716693556e-07 1.3461426077839e-05 1.91826555991606e-06 -1.63380030048313e-06 2.03896126331197e-06 -2.40778344995358e-06 3.34737298074015e-06 1.91826555991606e-06 6.3234125276334e-05 -4.58773216516207e-08 2.29904189442621e-06 7.80170352851492e-07 3.27044636527317e-06 -1.63380030048313e-06 -4.58773216516207e-08 2.57213736338e-05 -3.41941610600732e-06 1.03060131625441e-06 7.39274577279536e-06 2.03896126331197e-06 2.29904189442621e-06 -3.41941610600732e-06 3.66744132859496e-05 2801 2808 0 0 24 2795 2802 0 0 24 0 0 0 0 0 0 0 0 72 0 1 2 0 0 2774 +53 10 0.998436366288011 -0.008190650361522 0.0552967966544849 0.00216553886823645 0.00819263862495712 0.999966421582647 0.000190734257151818 0.00530225003498843 -0.0552965021131809 0.000262590653470629 0.998469943413519 0.0235614068385732 3.28625059679352e-05 -8.21153115134568e-06 2.32617245627029e-06 4.09774307086273e-06 5.81254556496128e-06 -2.48082663909021e-07 -8.21153115134568e-06 4.4287622123962e-05 -2.75590009256112e-06 5.90156843904933e-06 5.01074706727784e-07 9.57276457354189e-06 2.32617245627029e-06 -2.75590009256112e-06 1.35449520176363e-05 -4.95617435163511e-08 -9.80177371954281e-07 -6.02981139246347e-07 4.09774307086273e-06 5.90156843904933e-06 -4.95617435163511e-08 7.07867405588385e-05 -2.82922382816629e-07 8.31794285148177e-06 5.81254556496128e-06 5.01074706727784e-07 -9.80177371954281e-07 -2.82922382816629e-07 2.83962551307713e-05 1.95053031323186e-06 -2.48082663909021e-07 9.57276457354189e-06 -6.02981139246347e-07 8.31794285148177e-06 1.95053031323186e-06 3.40093450202833e-05 2767 2778 0 0 25 2763 2779 0 0 25 0 0 0 0 0 0 0 0 69 0 9 13 0 0 2786 +54 3 0.999349116672497 -0.0159231367270717 0.0323696883313906 -0.00796682194735789 0.0156629042713704 0.999843068903089 0.00827713695899747 0.00722443696971857 -0.0324964065042009 -0.00776474617892274 0.999441690285677 0.062211276685782 2.87941063246036e-05 -7.48283234367137e-06 2.81039789060341e-06 6.57174732504252e-06 -4.17304509608253e-07 5.44412532464416e-06 -7.48283234367137e-06 4.75770742055608e-05 -2.14377693862847e-06 6.15752615510715e-06 -2.94994670337434e-06 -2.16307231611792e-06 2.81039789060341e-06 -2.14377693862847e-06 1.46739937772881e-05 -3.37322403273157e-06 -8.75964875683423e-08 6.33239192344036e-07 6.57174732504252e-06 6.15752615510715e-06 -3.37322403273157e-06 9.66831803229219e-05 3.65362001222211e-06 1.09827917107187e-05 -4.17304509608253e-07 -2.94994670337434e-06 -8.75964875683423e-08 3.65362001222211e-06 3.47873775918167e-05 -4.23391619745376e-06 5.44412532464416e-06 -2.16307231611792e-06 6.33239192344036e-07 1.09827917107187e-05 -4.23391619745376e-06 3.35916094136817e-05 2876 2889 0 0 31 2867 2881 0 0 35 0 0 0 0 0 0 0 0 34 0 0 0 0 0 2819 +53 13 0.998740038950588 -0.00899079335939884 0.0493710464923132 0.00604785307757359 0.00856555582763092 0.999924434831239 0.00881792950707608 0.00545131901928244 -0.0494465959429089 -0.00838392880436224 0.998741580133451 0.023342282877993 3.48787414340209e-05 -2.47860170786596e-06 3.30146512266197e-06 1.01895528432799e-06 -5.35806188277744e-07 4.85706517894811e-06 -2.47860170786596e-06 5.31142406499764e-05 -4.58176387047959e-06 1.79036098634482e-05 2.15215765700979e-06 1.10719527354396e-05 3.30146512266197e-06 -4.58176387047959e-06 1.42837394690071e-05 -2.28119057852085e-06 1.52613636301539e-07 1.78083189877679e-06 1.01895528432799e-06 1.79036098634482e-05 -2.28119057852085e-06 6.17741362594846e-05 7.45812896535167e-06 1.08186249391951e-05 -5.35806188277744e-07 2.15215765700979e-06 1.52613636301539e-07 7.45812896535167e-06 2.63370587445335e-05 2.14597363065407e-06 4.85706517894811e-06 1.10719527354396e-05 1.78083189877679e-06 1.08186249391951e-05 2.14597363065407e-06 3.55498800073068e-05 2802 2813 0 0 28 2798 2811 0 0 28 0 0 0 0 0 0 0 0 61 0 0 1 0 0 2602 +54 2 0.998975027133785 -0.0160992943662456 0.0423049392383776 -0.00219719534881482 0.0157506121910275 0.999839287439019 0.00856256439635756 0.0042022022099175 -0.0424359915479974 -0.00788745930847741 0.99906805304093 0.0654316214388306 3.61915758100659e-05 -8.88065988008079e-06 3.41775050034238e-06 -5.4150008415309e-07 -4.72299896809753e-06 5.07891935312876e-06 -8.88065988008079e-06 2.80470622341433e-05 -5.47314305128693e-06 7.35138060037137e-06 -2.62829189697467e-07 -1.13887105873796e-06 3.41775050034238e-06 -5.47314305128693e-06 1.32648911500885e-05 -2.52948751350296e-06 2.46550114566995e-07 1.85556265550293e-06 -5.4150008415309e-07 7.35138060037137e-06 -2.52948751350296e-06 8.04157669730278e-05 3.99780586779756e-06 8.43446006827671e-06 -4.72299896809753e-06 -2.62829189697467e-07 2.46550114566995e-07 3.99780586779756e-06 2.92140093052431e-05 1.12833406034817e-06 5.07891935312876e-06 -1.13887105873796e-06 1.85556265550293e-06 8.43446006827671e-06 1.12833406034817e-06 3.27339261049019e-05 2805 2819 0 0 36 2798 2812 0 0 41 0 0 0 0 0 0 0 0 43 0 0 0 0 0 2676 +54 27 0.999157372845293 -0.0172204415400125 0.0372558811741118 -0.00279734728074383 0.016943627782853 0.99982654118857 0.00773311143441512 0.00385341845300871 -0.0373825864066234 -0.00709534552139376 0.999275836946678 0.0836161713592587 4.23758635978161e-05 1.00278483400171e-05 2.98079127548759e-06 4.13403346322132e-06 -2.74485879236659e-06 1.90674172785037e-05 1.00278483400171e-05 0.000147191554010928 2.77843560504418e-07 3.44962272854271e-05 -6.60044091434941e-06 6.44134652291036e-05 2.98079127548759e-06 2.77843560504418e-07 1.2267568162297e-05 1.34793018021515e-06 -3.50930253973131e-06 3.02651867841045e-06 4.13403346322132e-06 3.44962272854271e-05 1.34793018021515e-06 7.21403410718347e-05 -2.15225160138345e-06 2.80478305697209e-05 -2.74485879236659e-06 -6.60044091434941e-06 -3.50930253973131e-06 -2.15225160138345e-06 3.31770271002637e-05 -7.09141390727826e-06 1.90674172785037e-05 6.44134652291036e-05 3.02651867841045e-06 2.80478305697209e-05 -7.09141390727826e-06 6.94250470031615e-05 2855 2868 0 0 35 2850 2864 0 0 39 0 0 0 0 0 0 0 0 31 0 0 0 0 0 2941 +54 25 0.998489928417595 -0.016635846022197 0.0523556250631305 0.00344823139082015 0.0167340243064761 0.99985894322568 -0.00143738726071714 -0.00451684139631312 -0.052324327794398 0.002311337005449 0.998627469300796 0.0891729944694342 7.16226648790996e-05 4.40204253448923e-05 1.75862886551391e-06 2.10053212071455e-05 -1.53571139485316e-05 3.76539750906678e-05 4.40204253448923e-05 0.000150799565464318 -6.07289312976017e-06 4.32893753228688e-05 -1.3110015306745e-05 5.91567072021171e-05 1.75862886551391e-06 -6.07289312976017e-06 1.34951655097571e-05 -2.20150874416664e-06 -1.65504746893393e-06 -2.12439251530398e-07 2.10053212071455e-05 4.32893753228688e-05 -2.20150874416664e-06 9.09857563663362e-05 -7.57077635533272e-06 2.66199236979152e-05 -1.53571139485316e-05 -1.3110015306745e-05 -1.65504746893393e-06 -7.57077635533272e-06 3.55017786447594e-05 -1.65291350606211e-05 3.76539750906678e-05 5.91567072021171e-05 -2.12439251530398e-07 2.66199236979152e-05 -1.65291350606211e-05 8.09878009861319e-05 2684 2695 0 0 36 2673 2688 0 0 38 0 0 0 0 0 0 0 0 50 0 0 0 0 0 2847 +54 6 0.998674798037275 -0.0166630570302038 0.0486928156468343 -0.000633554649150884 0.0165125041057834 0.999857559525315 0.00349254466513656 0.00393015329991153 -0.0487440762899955 -0.00268387601980091 0.998807695122612 0.0831744317037279 2.96420923291617e-05 -3.10630315868288e-06 3.85958622565641e-06 5.22919820507659e-06 -4.60353462480668e-06 5.10692930553385e-06 -3.10630315868288e-06 2.45056245925098e-05 -1.8806885347075e-06 2.29184389818029e-06 -1.12145463920789e-06 4.31057298252928e-06 3.85958622565641e-06 -1.8806885347075e-06 1.22258465688409e-05 3.98100765955717e-07 -9.90608848128406e-08 1.47305625728275e-07 5.22919820507659e-06 2.29184389818029e-06 3.98100765955717e-07 7.17591026385735e-05 -6.03935355173324e-06 1.34058276776895e-05 -4.60353462480668e-06 -1.12145463920789e-06 -9.90608848128406e-08 -6.03935355173324e-06 3.65767819709857e-05 -8.99439118458312e-06 5.10692930553385e-06 4.31057298252928e-06 1.47305625728275e-07 1.34058276776895e-05 -8.99439118458312e-06 3.51909136200147e-05 2630 2638 0 0 34 2620 2636 0 0 41 0 0 0 0 0 0 0 0 39 0 16 18 0 0 2842 +54 5 0.998725779036309 -0.0164151084343484 0.0477217194095684 -0.00284591149623571 0.0162073080344605 0.999857426479464 0.00473813044769707 0.00579790089226831 -0.0477926924811012 -0.00395865241614695 0.998849431904757 0.0838861541080243 4.09906762167034e-05 -1.01757242597719e-05 2.96396026593047e-06 9.23885146349807e-06 -1.61781411437169e-06 2.37280799450977e-06 -1.01757242597719e-05 3.30767425794465e-05 -2.04803289425666e-06 -2.55592742616905e-06 -1.09449033778813e-06 8.40447124089249e-06 2.96396026593047e-06 -2.04803289425666e-06 1.2820290787663e-05 -2.97377315502227e-07 5.14929731510303e-08 1.96843851522378e-06 9.23885146349807e-06 -2.55592742616905e-06 -2.97377315502227e-07 5.98592072522797e-05 2.0269594408668e-06 7.78196088292461e-06 -1.61781411437169e-06 -1.09449033778813e-06 5.14929731510303e-08 2.0269594408668e-06 3.2194315416208e-05 -6.38988648073302e-06 2.37280799450977e-06 8.40447124089249e-06 1.96843851522378e-06 7.78196088292461e-06 -6.38988648073302e-06 3.80655402698968e-05 2594 2606 0 0 34 2588 2600 0 0 37 0 0 0 0 0 0 0 0 40 0 0 0 0 0 2569 +54 52 0.999501522142739 -0.0132968106019943 0.0286339320066802 -0.0121186699802171 0.0130797366525749 0.999884383430862 0.00775501516331943 0.00539981211190198 -0.028733738417543 -0.00737662517000267 0.999559881986894 0.0806650091650474 4.77859166913732e-05 -4.99905379573669e-07 1.52577143745401e-06 1.71250951631517e-06 -1.42421388280081e-05 1.74815028413625e-05 -4.99905379573669e-07 4.54834623829134e-05 -8.92120142153362e-07 6.57942945485543e-07 1.90229058432616e-06 1.80054794879849e-05 1.52577143745401e-06 -8.92120142153362e-07 1.32818066048629e-05 -3.22771202126936e-07 -3.16983333397509e-06 1.28866580911149e-06 1.71250951631517e-06 6.57942945485543e-07 -3.22771202126936e-07 4.37554252313663e-05 7.84507271664501e-07 6.90359989445961e-06 -1.42421388280081e-05 1.90229058432616e-06 -3.16983333397509e-06 7.84507271664501e-07 3.46849297972176e-05 -1.36397283269926e-05 1.74815028413625e-05 1.80054794879849e-05 1.28866580911149e-06 6.90359989445961e-06 -1.36397283269926e-05 4.45533375990998e-05 2755 2754 0 0 23 2734 2748 0 0 28 0 0 0 0 0 0 0 0 40 0 11 13 0 0 2995 +54 7 0.999127547484814 -0.0157071003412747 0.0386966517395138 0.00163126284652756 0.0156722653709858 0.999876458324385 0.00120340634245809 0.00342141346338425 -0.0387107731144895 -0.000595892232537542 0.999250279438202 0.0897126601144886 3.76487271771542e-05 -1.25170917397687e-05 5.37500378223831e-07 5.36842033263618e-07 -4.68990867624702e-06 2.98838959395511e-06 -1.25170917397687e-05 7.99347205982058e-05 1.75190340805486e-06 1.83040064890182e-05 -1.62172357763043e-06 7.1735161405728e-06 5.37500378223831e-07 1.75190340805486e-06 1.24208216839375e-05 1.58211001173635e-06 -3.69234558384263e-07 1.67201367809464e-06 5.36842033263618e-07 1.83040064890182e-05 1.58211001173635e-06 7.04968610909966e-05 4.88645160819323e-06 1.36770108979493e-05 -4.68990867624702e-06 -1.62172357763043e-06 -3.69234558384263e-07 4.88645160819323e-06 2.79520654411726e-05 -3.28637038666941e-06 2.98838959395511e-06 7.1735161405728e-06 1.67201367809464e-06 1.36770108979493e-05 -3.28637038666941e-06 3.82978511012606e-05 2807 2822 0 0 38 2798 2813 0 0 42 0 0 0 0 0 0 0 0 33 0 0 2 0 0 2572 +54 24 0.998967025216679 -0.0166048659131584 0.0422984746503324 0.000313676437868451 0.0164440621295924 0.999856188212442 0.00414677151084407 0.00165240609455115 -0.042361248215992 -0.00344692925530412 0.999096413429801 0.0919484649844486 4.09773570179073e-05 -8.58092162709665e-06 4.39895867003015e-06 4.86763397139746e-06 -7.52061284062529e-06 -7.44467071431846e-06 -8.58092162709665e-06 5.66933478618704e-05 -3.36015191966255e-06 -1.80866321961252e-06 2.97790831261901e-06 3.00810085733849e-05 4.39895867003015e-06 -3.36015191966255e-06 1.31806620847181e-05 -2.20360331359695e-06 -1.85938055190634e-06 -2.11543607126109e-06 4.86763397139746e-06 -1.80866321961252e-06 -2.20360331359695e-06 6.78444873242291e-05 4.80724773680788e-06 5.05493333458853e-06 -7.52061284062529e-06 2.97790831261901e-06 -1.85938055190634e-06 4.80724773680788e-06 3.16859171495099e-05 -3.67671815724782e-07 -7.44467071431846e-06 3.00810085733849e-05 -2.11543607126109e-06 5.05493333458853e-06 -3.67671815724782e-07 5.36856504430264e-05 2835 2849 0 0 37 2832 2847 0 0 39 0 0 0 0 0 0 0 0 29 0 0 0 0 0 2547 +54 51 0.998905549307954 -0.0164236914172163 0.0437945878163724 -0.00559773427372815 0.0161281637232194 0.999844774639449 0.00709288101593463 0.00295593574411556 -0.0439042810747532 -0.00637879192490478 0.999015377818023 0.0803864227978082 3.78828340048484e-05 1.48848495590891e-06 6.88344412917379e-06 2.73343523444426e-06 -5.2683477210251e-06 1.22472570583639e-05 1.48848495590891e-06 6.61051220485279e-05 -2.68550163707161e-06 1.96602267968708e-05 -3.06784408664585e-06 1.43466088106141e-05 6.88344412917379e-06 -2.68550163707161e-06 1.42136135467031e-05 6.42001031566444e-07 7.22047051454071e-07 3.07036536180559e-06 2.73343523444426e-06 1.96602267968708e-05 6.42001031566444e-07 5.04561402706192e-05 2.64494297327358e-06 -1.17596259691312e-06 -5.2683477210251e-06 -3.06784408664585e-06 7.22047051454071e-07 2.64494297327358e-06 2.93860175499134e-05 -2.13576024767792e-06 1.22472570583639e-05 1.43466088106141e-05 3.07036536180559e-06 -1.17596259691312e-06 -2.13576024767792e-06 4.01628692472178e-05 2726 2747 0 0 42 2713 2737 0 0 55 0 0 0 0 0 0 0 0 49 0 0 0 0 0 2858 +54 1 0.99878924563823 -0.0162392826979556 0.04643628424918 -0.0029060817649739 0.0158017861638665 0.999827380358089 0.00977307732055399 0.00743352912751895 -0.0465869761998587 -0.00902746829061015 0.998873444668951 0.0798971331205958 4.24034985373008e-05 -1.1881917746541e-05 4.24362582876532e-06 8.25588644010502e-06 -5.25192836024645e-06 1.12067260966087e-05 -1.1881917746541e-05 2.93313465489773e-05 -5.60610691905804e-06 -4.82963139625731e-06 1.49141647488396e-06 -1.1091642514348e-06 4.24362582876532e-06 -5.60610691905804e-06 1.47754774075138e-05 -8.53592623560167e-07 -6.192355977364e-07 -9.26502342445323e-07 8.25588644010502e-06 -4.82963139625731e-06 -8.53592623560167e-07 6.37883714617271e-05 -1.04766738115646e-06 1.12876364620716e-05 -5.25192836024645e-06 1.49141647488396e-06 -6.192355977364e-07 -1.04766738115646e-06 2.77588095563684e-05 -3.63736585664549e-06 1.12067260966087e-05 -1.1091642514348e-06 -9.26502342445323e-07 1.12876364620716e-05 -3.63736585664549e-06 3.98345224849346e-05 2657 2664 0 0 30 2647 2663 0 0 42 0 0 0 0 0 0 0 0 38 0 11 13 0 0 2692 +54 50 0.998749059834724 -0.016558951149255 0.0471817402825646 -0.00439487162301794 0.0163538370126439 0.999855078812417 0.00473005158318289 0.00190601828238057 -0.04725322734183 -0.00395253208111971 0.998875122323071 0.0796731919800392 3.19743261478411e-05 -8.44028217881809e-07 3.61043660495282e-06 -2.21167173937763e-07 -1.7475799584496e-06 -3.68522079931511e-07 -8.44028217881809e-07 8.58480221353621e-05 -5.40461176178034e-07 1.14997688545428e-05 4.84236755299082e-06 4.64758414570639e-06 3.61043660495282e-06 -5.40461176178034e-07 1.41621444734627e-05 2.80285538257847e-06 -8.69148020493692e-07 2.39798293953215e-07 -2.21167173937763e-07 1.14997688545428e-05 2.80285538257847e-06 4.89225865659438e-05 -2.15058276048411e-08 2.36616211298221e-06 -1.7475799584496e-06 4.84236755299082e-06 -8.69148020493692e-07 -2.15058276048411e-08 3.13128815230018e-05 -9.07611007130689e-06 -3.68522079931511e-07 4.64758414570639e-06 2.39798293953215e-07 2.36616211298221e-06 -9.07611007130689e-06 2.98024848778222e-05 2722 2728 0 0 32 2712 2728 0 0 41 0 0 0 0 0 0 0 0 46 0 15 17 0 0 2859 +54 8 0.99867769353103 -0.0156489791247389 0.0489691116510858 0.00309789573983562 0.0155281850654506 0.999875379483261 0.00284622061310448 0.00325178469754163 -0.0490075495420465 -0.00208205560896688 0.99879623804474 0.0928301112746406 3.37309088994737e-05 -2.70349455134227e-06 1.45454450755985e-06 3.84508716420145e-06 -3.34922440589321e-08 6.09983529701822e-06 -2.70349455134227e-06 3.21334993531548e-05 -1.75958673201519e-06 -2.67444263908668e-06 5.78967145323181e-06 1.19819389540072e-05 1.45454450755985e-06 -1.75958673201519e-06 1.33114937857046e-05 3.23956723885396e-07 -3.35786872274516e-06 -9.92123660386257e-07 3.84508716420145e-06 -2.67444263908668e-06 3.23956723885396e-07 6.47163894746528e-05 -6.89415086844456e-07 9.38000166165088e-06 -3.34922440589321e-08 5.78967145323181e-06 -3.35786872274516e-06 -6.89415086844456e-07 2.89307385394425e-05 -2.27932626684266e-06 6.09983529701822e-06 1.19819389540072e-05 -9.92123660386257e-07 9.38000166165088e-06 -2.27932626684266e-06 4.25741017198652e-05 2603 2621 0 0 44 2597 2621 0 0 60 0 0 0 0 0 0 0 0 42 0 0 1 0 0 2846 +54 28 0.9984899753301 -0.0171218545128441 0.052197808989813 0.00438563076271358 0.0169942272496269 0.99985141693823 0.00288795547094342 0.00103460144358384 -0.0522395004329486 -0.00199653315903123 0.998632589318945 0.0898899338012333 3.64430595421651e-05 -7.16162949644884e-06 3.80944165282489e-06 3.23647993603115e-07 -3.8466860243998e-06 6.83674844641137e-06 -7.16162949644884e-06 6.31944620052791e-05 -9.52325283324554e-07 1.26740412263202e-05 -1.02005061642666e-06 3.46364272797294e-05 3.80944165282489e-06 -9.52325283324554e-07 1.34806072172461e-05 2.79115962106897e-07 -5.99383141986417e-07 3.50484303976298e-06 3.23647993603115e-07 1.26740412263202e-05 2.79115962106897e-07 6.65502311441968e-05 2.52452932924562e-06 1.27009434527462e-05 -3.8466860243998e-06 -1.02005061642666e-06 -5.99383141986417e-07 2.52452932924562e-06 3.0155716726046e-05 -4.53958847145687e-06 6.83674844641137e-06 3.46364272797294e-05 3.50484303976298e-06 1.27009434527462e-05 -4.53958847145687e-06 6.00473209018714e-05 2647 2665 0 0 48 2640 2664 0 0 63 0 0 0 0 0 0 0 0 42 0 0 0 0 0 2866 +54 22 0.999427694530922 -0.0168154334326319 0.0293517393535682 -0.00855159543055004 0.0165638154079079 0.999824131011315 0.00879471810815317 0.0059170646620014 -0.0294944642897583 -0.00830350805032734 0.999530453928402 0.0779180213081637 2.85036454572546e-05 -7.30357779489032e-06 2.73899376671899e-06 6.83880696837364e-06 5.97196749401545e-07 -8.06752376080334e-07 -7.30357779489032e-06 6.59907121196337e-05 -2.8194817092432e-06 1.92388088209499e-05 -4.25787834279567e-06 1.41616695294213e-05 2.73899376671899e-06 -2.8194817092432e-06 1.38529317806758e-05 7.45260962864397e-07 -1.45988582777635e-07 6.21232880087053e-07 6.83880696837364e-06 1.92388088209499e-05 7.45260962864397e-07 8.10937588636411e-05 7.57799556463479e-07 2.18991824059519e-05 5.97196749401545e-07 -4.25787834279567e-06 -1.45988582777635e-07 7.57799556463479e-07 2.66096878849436e-05 -1.83690285652123e-06 -8.06752376080334e-07 1.41616695294213e-05 6.21232880087053e-07 2.18991824059519e-05 -1.83690285652123e-06 4.02252706731466e-05 2838 2851 0 0 32 2828 2843 0 0 37 0 0 0 0 0 0 0 0 33 0 0 0 0 0 2873 +54 26 0.998933309219344 -0.0171041988408327 0.0428916089008568 -0.000350916722373771 0.0169644244711022 0.999849538183008 0.00362067639934262 -0.000525630124566097 -0.0429470841205206 -0.00288918279756506 0.999073170787959 0.0925639613224117 3.56486379595463e-05 -6.50071613746971e-06 3.34323501680703e-06 3.4874823144648e-06 -5.25534468044538e-06 8.94970599482322e-06 -6.50071613746971e-06 4.45562893617528e-05 -2.33896489242767e-06 3.60848803903158e-06 -1.74802776808868e-06 2.31449882255812e-05 3.34323501680703e-06 -2.33896489242767e-06 1.28274977584469e-05 -6.57070762552945e-07 -2.76559809831184e-06 1.01957326014264e-06 3.4874823144648e-06 3.60848803903158e-06 -6.57070762552945e-07 7.12149185532685e-05 3.67122965743378e-06 1.38644094048446e-05 -5.25534468044538e-06 -1.74802776808868e-06 -2.76559809831184e-06 3.67122965743378e-06 3.80548439469462e-05 -5.63972061215985e-06 8.94970599482322e-06 2.31449882255812e-05 1.01957326014264e-06 1.38644094048446e-05 -5.63972061215985e-06 5.76856367976759e-05 2864 2882 0 0 45 2861 2885 0 0 58 0 0 0 0 0 0 0 0 27 0 0 0 0 0 2947 +54 19 0.999388555997616 -0.0162221022470262 0.0309734973757641 -0.00832487097470747 0.0160721589371563 0.999857909842432 0.00508387968212554 0.005204223969342 -0.0310515675626566 -0.00458296020172219 0.999507276925832 0.0839557289940798 5.28920593015717e-05 -1.56187966587553e-06 -6.09445043885096e-07 1.35529992598202e-05 -5.85077116478715e-06 1.50913389599752e-05 -1.56187966587553e-06 8.17891888498066e-05 -1.78515635089535e-06 2.62089935017565e-05 -6.08147583351928e-06 2.74682395163153e-05 -6.09445043885096e-07 -1.78515635089535e-06 1.44162320252666e-05 -3.47389235350792e-06 -2.66906702351762e-06 -1.07709837631931e-07 1.35529992598202e-05 2.62089935017565e-05 -3.47389235350792e-06 9.12043400957044e-05 2.67777459478829e-07 2.70258257309508e-05 -5.85077116478715e-06 -6.08147583351928e-06 -2.66906702351762e-06 2.67777459478829e-07 3.12920495299155e-05 -1.07577250996603e-05 1.50913389599752e-05 2.74682395163153e-05 -1.07709837631931e-07 2.70258257309508e-05 -1.07577250996603e-05 6.31215090354149e-05 2912 2932 0 0 42 2906 2930 0 0 58 0 0 0 0 0 0 0 0 35 0 0 1 0 0 2526 +54 9 0.998944170453306 -0.0155848735499845 0.0432163861722194 0.00367668127104611 0.0154581733759814 0.999875186450045 0.0032644137859156 0.00428471421010533 -0.0432618676577134 -0.00259292073125426 0.999060402362564 0.0923375082091563 2.96160688407824e-05 -8.78575629177206e-06 2.52908885893222e-06 1.71488697345077e-06 -4.54127682235118e-06 2.74377717714201e-06 -8.78575629177206e-06 4.73758596516483e-05 -3.2463998642876e-06 1.08371277197769e-05 -1.7532151359227e-06 -5.7658273465542e-06 2.52908885893222e-06 -3.2463998642876e-06 1.37694856424889e-05 6.17878475096004e-07 -4.73891563345896e-07 1.92700242462957e-06 1.71488697345077e-06 1.08371277197769e-05 6.17878475096004e-07 7.5855837282238e-05 -4.16992625655741e-06 2.57002837881396e-06 -4.54127682235118e-06 -1.7532151359227e-06 -4.73891563345896e-07 -4.16992625655741e-06 3.55146226256348e-05 -6.72863286723747e-06 2.74377717714201e-06 -5.7658273465542e-06 1.92700242462957e-06 2.57002837881396e-06 -6.72863286723747e-06 3.74194021045403e-05 2792 2812 0 0 37 2786 2807 0 0 42 0 0 0 0 0 0 0 0 32 0 0 1 0 0 2828 +54 17 0.998726704892123 -0.016451579934494 0.0476897730439167 0.00117532461698775 0.0162566985814801 0.999857852845143 0.00447144888508757 0.00100476088200111 -0.0477565564771187 -0.00369047714530292 0.998852187108727 0.0879833931563459 3.10502380878193e-05 -6.42705144267716e-06 9.49240132004077e-07 -4.89849236246413e-06 -3.3016544304293e-06 2.35289841755956e-06 -6.42705144267716e-06 2.70256289545879e-05 2.71919641698305e-07 -2.47184918940108e-06 -7.81276420600674e-07 4.57722452708945e-06 9.49240132004077e-07 2.71919641698305e-07 1.51628821814273e-05 -2.98585408650604e-06 -4.00292393327626e-06 1.14048810591281e-07 -4.89849236246413e-06 -2.47184918940108e-06 -2.98585408650604e-06 8.8646193012039e-05 6.05065292377523e-06 -3.31437643308908e-06 -3.3016544304293e-06 -7.81276420600674e-07 -4.00292393327626e-06 6.05065292377523e-06 3.04226084036732e-05 -6.56023237512277e-06 2.35289841755956e-06 4.57722452708945e-06 1.14048810591281e-07 -3.31437643308908e-06 -6.56023237512277e-06 3.43085353711908e-05 2547 2571 0 0 37 2542 2566 0 0 43 0 0 0 0 0 0 0 0 43 0 0 1 0 0 2851 +54 23 0.999098822294278 -0.0160084370122592 0.0393099635539292 0.00280581793613666 0.0157498598377088 0.999852300967232 0.00687882007498233 0.00288856554861592 -0.0394142766682231 -0.00625349461948925 0.999203387003749 0.0784397108010267 3.51521364307934e-05 -1.40689502758705e-06 2.06722681669778e-06 1.04952059102531e-05 -5.36664147166287e-06 6.13021158643093e-06 -1.40689502758705e-06 6.25243149677207e-05 1.57126159023678e-06 9.06747740852875e-06 7.74592105997895e-07 1.31617663820147e-05 2.06722681669778e-06 1.57126159023678e-06 1.37763111192656e-05 7.95910361870924e-07 -2.04024815617268e-06 9.01003358224218e-07 1.04952059102531e-05 9.06747740852875e-06 7.95910361870924e-07 7.91560497013245e-05 -6.10341625754495e-06 1.63498434169119e-05 -5.36664147166287e-06 7.74592105997895e-07 -2.04024815617268e-06 -6.10341625754495e-06 3.28091280031099e-05 -7.59595510758526e-06 6.13021158643093e-06 1.31617663820147e-05 9.01003358224218e-07 1.63498434169119e-05 -7.59595510758526e-06 4.55601746022509e-05 2667 2684 0 0 35 2664 2681 0 0 44 0 0 0 0 0 0 0 0 38 0 0 1 0 0 2874 +54 10 0.999206686882674 -0.015631015823272 0.0366287896781004 -0.00483913205557049 0.0153413613072633 0.999848889530837 0.00817561845937438 0.00864468560342962 -0.0367510479060107 -0.00760719713730881 0.999295497352772 0.0889771994711243 3.11288987349533e-05 -1.47289333535725e-05 1.99300740734372e-06 7.34854571969834e-06 1.57452483155272e-06 2.07834299100167e-06 -1.47289333535725e-05 5.95185845355375e-05 -4.63818518558863e-06 -2.88254929298686e-06 3.0539484794039e-06 -9.58301658849288e-06 1.99300740734372e-06 -4.63818518558863e-06 1.58331212895221e-05 -2.69165730437669e-06 -2.11225525816423e-06 -9.40172179529038e-09 7.34854571969834e-06 -2.88254929298686e-06 -2.69165730437669e-06 7.12173423230971e-05 1.78221296663415e-06 8.63591577223904e-06 1.57452483155272e-06 3.0539484794039e-06 -2.11225525816423e-06 1.78221296663415e-06 2.90088702046067e-05 -2.25161586754921e-06 2.07834299100167e-06 -9.58301658849288e-06 -9.40172179529038e-09 8.63591577223904e-06 -2.25161586754921e-06 3.61230938492729e-05 2772 2780 0 0 32 2765 2781 0 0 41 0 0 0 0 0 0 0 0 40 0 13 15 0 0 2892 +54 21 0.999489895549035 -0.0163936541818507 0.0274079696064005 -0.0142456166995052 0.016047074195499 0.999789076402561 0.0128177266267331 0.00948632035101549 -0.0276123179965687 -0.0123713705255077 0.999542149729653 0.0760059796516487 4.56492375929539e-05 -3.20242924355785e-06 1.44323296395487e-06 5.97347798482179e-06 -2.83027835663789e-06 8.38118425697574e-06 -3.20242924355785e-06 4.83841568668942e-05 -2.70453565116999e-06 9.30515954693254e-06 4.33701497351321e-06 6.46096484194137e-06 1.44323296395487e-06 -2.70453565116999e-06 1.56953553790949e-05 -2.03729097597666e-07 -4.24767927983506e-06 8.61936453987529e-07 5.97347798482179e-06 9.30515954693254e-06 -2.03729097597666e-07 8.61380603406505e-05 2.30423361532876e-06 1.70245334344035e-05 -2.83027835663789e-06 4.33701497351321e-06 -4.24767927983506e-06 2.30423361532876e-06 3.26679971562856e-05 -1.48234685062701e-06 8.38118425697574e-06 6.46096484194137e-06 8.61936453987529e-07 1.70245334344035e-05 -1.48234685062701e-06 4.00148283088885e-05 2712 2717 0 0 29 2700 2716 0 0 40 0 0 0 0 0 0 0 0 32 0 12 14 0 0 2712 +54 16 0.999360789507797 -0.0159413180790365 0.0319982307675921 -0.00575935377579163 0.0157197264128617 0.999850766789907 0.00716479944867852 0.00642087045253418 -0.0321076719158812 -0.00665721620033423 0.999462244848 0.0846228360556302 3.20676382691767e-05 -5.32402092931697e-06 1.03318039148264e-06 3.80449053622959e-06 2.63624597240922e-06 4.01996208966889e-06 -5.32402092931697e-06 0.000102308212038668 -1.31492367128335e-06 3.03195284069998e-07 3.13186117941562e-06 2.04212478527716e-05 1.03318039148264e-06 -1.31492367128335e-06 1.54058918809882e-05 -2.06089089411333e-06 -2.3195428136735e-06 2.17325727811329e-06 3.80449053622959e-06 3.03195284069998e-07 -2.06089089411333e-06 7.41460062613367e-05 4.16247124932563e-06 4.52209131271202e-06 2.63624597240922e-06 3.13186117941562e-06 -2.3195428136735e-06 4.16247124932563e-06 2.53010165918144e-05 2.68894393383927e-07 4.01996208966889e-06 2.04212478527716e-05 2.17325727811329e-06 4.52209131271202e-06 2.68894393383927e-07 4.68480600878739e-05 2774 2787 0 0 33 2764 2777 0 0 36 0 0 0 0 0 0 0 0 37 0 1 5 0 0 2875 +55 53 0.999447235447595 -0.0167254323856064 0.0287312280919824 -0.00297715713262753 0.0164889758330195 0.999828363939323 0.00844726810242981 0.0172339643099742 -0.0288675809886646 -0.00796885022639645 0.999551479511652 0.153408511227442 3.2951119765451e-05 2.44488961445024e-06 7.045271011059e-06 3.40058230630787e-06 -7.03237423603173e-07 1.52919042974048e-05 2.44488961445024e-06 3.99075200684582e-05 -2.45034030651626e-06 5.72743627077919e-07 2.21481861281089e-06 1.03583575348162e-05 7.045271011059e-06 -2.45034030651626e-06 1.38037506677899e-05 -9.88376182295805e-07 2.69608265969569e-07 6.75391904096535e-07 3.40058230630787e-06 5.72743627077919e-07 -9.88376182295805e-07 5.3083840989424e-05 2.03085388071039e-06 6.04211811382965e-06 -7.03237423603173e-07 2.21481861281089e-06 2.69608265969569e-07 2.03085388071039e-06 2.14572749735675e-05 -2.43270515817261e-06 1.52919042974048e-05 1.03583575348162e-05 6.75391904096535e-07 6.04211811382965e-06 -2.43270515817261e-06 4.23440942831366e-05 2594 2597 0 9 35 2563 2581 0 0 45 0 0 0 0 0 0 0 0 46 0 0 0 0 0 2805 +54 20 0.998843027100604 -0.0159521577278532 0.0453666824478886 -0.00282746152280383 0.0157713749836822 0.999866204725378 0.00434008976776062 0.0043776903047405 -0.0454298463966801 -0.0036195734408671 0.998960974084814 0.0880081088162821 3.37834865144248e-05 -4.36597776114684e-06 1.28036005175169e-06 8.28806406809616e-06 -4.46216892916451e-06 2.64865988875945e-06 -4.36597776114684e-06 6.56630396049841e-05 -4.56388557765426e-06 1.53413389371195e-05 3.55805539696044e-06 1.32944828770055e-05 1.28036005175169e-06 -4.56388557765426e-06 1.59782053890732e-05 -1.31646368595064e-06 -2.32088312004818e-06 -1.40110549013857e-06 8.28806406809616e-06 1.53413389371195e-05 -1.31646368595064e-06 8.86373412335223e-05 2.57906721509099e-06 6.15967258555943e-06 -4.46216892916451e-06 3.55805539696044e-06 -2.32088312004818e-06 2.57906721509099e-06 3.07417826739973e-05 -2.01046047876301e-06 2.64865988875945e-06 1.32944828770055e-05 -1.40110549013857e-06 6.15967258555943e-06 -2.01046047876301e-06 3.48487884967675e-05 2798 2803 0 0 32 2789 2805 0 0 40 0 0 0 0 0 0 0 0 38 0 14 16 0 0 2675 +55 3 0.996905852983772 -0.0270195536856927 0.0738150662488632 -0.0199131190579692 0.0257660183158747 0.999508050738562 0.0178820806660249 0.0208268487687065 -0.0742619188201066 -0.0159248305305324 0.997111612200826 0.147185359939565 2.95549693070407e-05 -9.36910771152454e-06 3.11685534516707e-06 3.16245846419966e-06 -2.14621746330816e-06 5.60432692472195e-06 -9.36910771152454e-06 5.75159319689108e-05 -1.8972760770316e-06 6.73723117252564e-06 7.15970733079528e-06 9.07983840358967e-06 3.11685534516707e-06 -1.8972760770316e-06 1.47193465554275e-05 1.53665876024043e-07 -1.77932265200154e-06 2.0666488756259e-06 3.16245846419966e-06 6.73723117252564e-06 1.53665876024043e-07 6.56969442202027e-05 3.38978970512334e-06 7.29758808803042e-06 -2.14621746330816e-06 7.15970733079528e-06 -1.77932265200154e-06 3.38978970512334e-06 3.42264061589762e-05 3.40520122186302e-06 5.60432692472195e-06 9.07983840358967e-06 2.0666488756259e-06 7.29758808803042e-06 3.40520122186302e-06 3.74990819706807e-05 2784 2798 0 16 48 2729 2743 0 0 54 0 0 0 0 0 0 0 0 38 0 0 0 0 0 2799 +54 18 0.999440014378314 -0.0166107399191882 0.029047219812115 -0.00956359461340567 0.0162536930251967 0.999789946886673 0.0124851739029079 0.00801899011431926 -0.0292485063297071 -0.0120060577909764 0.999500064759278 0.0803920495089816 3.22203136224819e-05 -7.41589436123501e-06 2.68910476757455e-06 7.65609594984751e-06 -1.35011219362766e-06 2.23736397441162e-06 -7.41589436123501e-06 4.62414954745075e-05 -1.56017991507898e-06 7.33935893929654e-06 -1.58977929512697e-06 4.64972318210158e-06 2.68910476757455e-06 -1.56017991507898e-06 1.34995562132071e-05 1.21171597930912e-06 -2.2765941676245e-06 2.34356869115231e-06 7.65609594984751e-06 7.33935893929654e-06 1.21171597930912e-06 7.26868630351906e-05 3.11561753883657e-06 1.46764912836223e-05 -1.35011219362766e-06 -1.58977929512697e-06 -2.2765941676245e-06 3.11561753883657e-06 3.15575634245247e-05 4.3272568402554e-07 2.23736397441162e-06 4.64972318210158e-06 2.34356869115231e-06 1.46764912836223e-05 4.3272568402554e-07 3.46102572610836e-05 2920 2937 0 0 32 2908 2925 0 0 36 0 0 0 0 0 0 0 0 34 0 0 5 0 0 2682 +55 5 0.997503356489391 -0.0264530012286995 0.0654774199124627 -0.0120348812779543 0.0258963110315714 0.999621035130632 0.00933633757524375 0.0197606018054461 -0.0656995804199285 -0.00761740443702572 0.997810372907743 0.169100137655486 6.03851263503943e-05 -1.79442874939573e-06 -3.84513792312356e-06 1.55015288029638e-05 -8.16517472316213e-06 1.42077995661172e-05 -1.79442874939573e-06 3.53151760562964e-05 -5.61599483980818e-07 -3.04801838896405e-06 7.28981458267923e-07 1.35313462001054e-05 -3.84513792312356e-06 -5.61599483980818e-07 1.41984747224032e-05 -1.9426004703878e-06 2.51343524371628e-06 -1.58549899401459e-06 1.55015288029638e-05 -3.04801838896405e-06 -1.9426004703878e-06 5.88143263604566e-05 -4.46015012837695e-06 5.63446973242212e-06 -8.16517472316213e-06 7.28981458267923e-07 2.51343524371628e-06 -4.46015012837695e-06 2.77438843531069e-05 -2.28661939344959e-06 1.42077995661172e-05 1.35313462001054e-05 -1.58549899401459e-06 5.63446973242212e-06 -2.28661939344959e-06 4.11898473257715e-05 2541 2553 0 11 52 2506 2518 0 0 62 0 0 0 0 0 0 0 0 43 0 0 0 0 0 2645 +55 2 0.997454403999292 -0.0263486978529284 0.0662605317204206 -0.0112218948606246 0.0253761775396992 0.999558167346248 0.0154764241633192 0.0210096602534589 -0.0666390392779747 -0.0137555884230515 0.997682325307632 0.151014081582309 3.72032393402337e-05 -7.96707103598929e-06 1.38063668476809e-06 1.14987751558133e-05 -5.81058772080327e-06 1.11215303347923e-05 -7.96707103598929e-06 9.05776440819351e-05 -7.4204035911689e-06 1.7017801583827e-05 9.72118861928614e-06 3.4534101577464e-05 1.38063668476809e-06 -7.4204035911689e-06 1.62209443647011e-05 -7.80575453051345e-06 -5.13522842145343e-06 -4.91329756697734e-06 1.14987751558133e-05 1.7017801583827e-05 -7.80575453051345e-06 9.63347881444928e-05 9.55787527319363e-06 2.68884799130733e-05 -5.81058772080327e-06 9.72118861928614e-06 -5.13522842145343e-06 9.55787527319363e-06 2.9176753535446e-05 1.41106432713848e-06 1.11215303347923e-05 3.4534101577464e-05 -4.91329756697734e-06 2.68884799130733e-05 1.41106432713848e-06 5.49312337330042e-05 2729 2743 0 17 52 2680 2694 0 0 60 0 0 0 0 0 0 0 0 44 0 0 0 0 0 2665 +55 52 0.998582926912898 -0.0234101077885917 0.0477923103793503 -0.0246934130236777 0.0225483489084132 0.999574726092973 0.0184915904579055 0.0230571098811876 -0.0482048756825915 -0.0173877488331571 0.99868611492848 0.164923312403838 3.4130838278756e-05 -1.51555584388419e-06 1.98313761486427e-06 8.08226092366772e-06 -1.08453545868927e-06 8.17792818750355e-06 -1.51555584388419e-06 5.19460539465494e-05 1.86745345120181e-06 4.27193442009687e-06 -2.29687392920074e-06 1.70133743947252e-05 1.98313761486427e-06 1.86745345120181e-06 1.41609624008063e-05 -2.29834890035481e-06 3.13428068030337e-07 1.42699273472574e-06 8.08226092366772e-06 4.27193442009687e-06 -2.29834890035481e-06 6.5979493933167e-05 -3.35024277204367e-06 1.04911069735285e-05 -1.08453545868927e-06 -2.29687392920074e-06 3.13428068030337e-07 -3.35024277204367e-06 2.70875246635038e-05 -3.83728098579589e-06 8.17792818750355e-06 1.70133743947252e-05 1.42699273472574e-06 1.04911069735285e-05 -3.83728098579589e-06 3.7510222056075e-05 2880 2881 0 16 44 2804 2820 0 0 50 0 0 0 0 0 0 0 0 31 0 0 0 0 0 2948 +55 1 0.997412754639375 -0.0264841679935985 0.0668310236969371 -0.0125345619442325 0.0256108328748642 0.999575471818573 0.0138910538884828 0.0186085261916244 -0.0671705450487748 -0.0121435161449973 0.99766760641683 0.170262831505176 3.26720875172662e-05 -6.45896673947308e-06 3.1694770023658e-06 1.16262239081274e-05 -7.07640840076324e-06 6.24025968946266e-06 -6.45896673947308e-06 3.28184207494608e-05 -2.79509676867595e-06 4.53601197100631e-06 -3.00904361939782e-06 1.07962505210758e-05 3.1694770023658e-06 -2.79509676867595e-06 1.62354632244898e-05 -2.59267968536756e-06 -3.66325919088813e-06 -1.20139128821454e-06 1.16262239081274e-05 4.53601197100631e-06 -2.59267968536756e-06 7.38718954295144e-05 4.51626369077814e-06 1.00681225045466e-05 -7.07640840076324e-06 -3.00904361939782e-06 -3.66325919088813e-06 4.51626369077814e-06 3.22327183013966e-05 -4.10655290832935e-06 6.24025968946266e-06 1.07962505210758e-05 -1.20139128821454e-06 1.00681225045466e-05 -4.10655290832935e-06 4.17119101137698e-05 2605 2610 0 15 57 2566 2584 0 0 59 0 0 0 0 0 0 0 0 35 0 0 0 0 0 2653 +54 11 0.999105969063753 -0.0166657726740994 0.0388524722810991 -0.00603730442964008 0.016406948810789 0.999841095371961 0.00697108572009003 0.00643959284750435 -0.0389624769733455 -0.00632740282990845 0.999220640980524 0.0908083293641199 3.44814342126451e-05 -1.12818757971393e-05 3.53343982054906e-06 5.24751527075309e-06 -1.05644598175392e-06 -3.03446279957295e-06 -1.12818757971393e-05 4.12740856624067e-05 -3.70697817695941e-06 3.52025135876234e-06 1.84700237644831e-06 1.91226938727341e-05 3.53343982054906e-06 -3.70697817695941e-06 1.37529169444949e-05 1.31813209800622e-06 -9.03932068313642e-07 7.39671457650447e-07 5.24751527075309e-06 3.52025135876234e-06 1.31813209800622e-06 8.06365478537588e-05 9.11787861092148e-07 1.50458995050876e-05 -1.05644598175392e-06 1.84700237644831e-06 -9.03932068313642e-07 9.11787861092148e-07 3.00254990066785e-05 -2.56380203759663e-06 -3.03446279957295e-06 1.91226938727341e-05 7.39671457650447e-07 1.50458995050876e-05 -2.56380203759663e-06 4.77627628997036e-05 2925 2932 0 0 33 2916 2932 0 0 40 0 0 0 0 0 0 0 0 42 0 11 13 0 0 2569 +55 6 0.997471580226934 -0.026610729674589 0.065896249557681 -0.015911195873116 0.0258794708589021 0.999593927782792 0.0119261279480645 0.0190212885582689 -0.066186853888408 -0.0101906136202056 0.997755206333897 0.167190141322089 4.46225338382303e-05 -5.19047025173079e-07 -1.37365948636035e-06 2.65607136008512e-06 -9.99339660497177e-06 1.36156998516932e-05 -5.19047025173079e-07 4.847453175102e-05 -3.63079160731495e-06 1.21079517468526e-06 1.78181768170666e-06 2.14978053611192e-05 -1.37365948636035e-06 -3.63079160731495e-06 1.6278160295305e-05 -5.92808690104434e-07 -9.82833741331793e-07 -1.91584384548865e-06 2.65607136008512e-06 1.21079517468526e-06 -5.92808690104434e-07 5.69025566498354e-05 2.53272286975637e-06 6.3726319049884e-06 -9.99339660497177e-06 1.78181768170666e-06 -9.82833741331793e-07 2.53272286975637e-06 3.40590520139375e-05 -4.57033046152374e-06 1.36156998516932e-05 2.14978053611192e-05 -1.91584384548865e-06 6.3726319049884e-06 -4.57033046152374e-06 4.75009011296161e-05 2568 2572 0 21 53 2526 2544 0 0 59 0 0 0 0 0 0 0 0 27 0 0 0 0 0 2766 +55 4 0.997630721209727 -0.0262553122030069 0.0635893283474706 -0.0150553680902228 0.025504231059321 0.999595372864629 0.012594631622081 0.0203851657387862 -0.0638942743650208 -0.0109429945054266 0.997896674297806 0.158136848022413 4.21397899865873e-05 -2.57852508672109e-06 3.07835606520905e-06 1.68475734668646e-06 -4.04742220567204e-06 1.24748045108838e-05 -2.57852508672109e-06 6.9386211033207e-05 1.12575138182495e-06 1.30641767554522e-05 -4.21841119729492e-06 1.05615005865836e-05 3.07835606520905e-06 1.12575138182495e-06 1.69143451657445e-05 -1.55948284573152e-06 -3.44917491665554e-06 3.58714244055141e-06 1.68475734668646e-06 1.30641767554522e-05 -1.55948284573152e-06 8.36445301239579e-05 2.33342819742009e-06 3.35614103870683e-06 -4.04742220567204e-06 -4.21841119729492e-06 -3.44917491665554e-06 2.33342819742009e-06 2.87052012600953e-05 -8.00039942716933e-06 1.24748045108838e-05 1.05615005865836e-05 3.58714244055141e-06 3.35614103870683e-06 -8.00039942716933e-06 4.38108793200145e-05 2833 2838 0 21 55 2775 2793 0 0 62 0 0 0 0 0 0 0 0 44 0 0 0 0 0 2798 +55 27 0.99701100112093 -0.027066816994618 0.0723633267727626 -0.0100514966875917 0.0260389056824571 0.999546715810298 0.0151108670733517 0.0211172422748008 -0.0727395286945266 -0.0131814388679029 0.997263862092009 0.168467876231713 4.16767692444308e-05 -1.61236583284868e-05 2.4999038607224e-06 -5.04099477197191e-06 -4.26694319063602e-06 3.99665706337001e-06 -1.61236583284868e-05 4.29216411885633e-05 -1.7295645182736e-06 6.70925341912074e-06 1.11548198809303e-06 2.23450313019401e-06 2.4999038607224e-06 -1.7295645182736e-06 1.50856691031903e-05 -2.03332948314778e-06 -1.31384158958039e-06 6.99259407896521e-07 -5.04099477197191e-06 6.70925341912074e-06 -2.03332948314778e-06 6.06770001922927e-05 4.85910680802273e-06 8.79808053416222e-06 -4.26694319063602e-06 1.11548198809303e-06 -1.31384158958039e-06 4.85910680802273e-06 2.81632195167741e-05 2.42524906820839e-06 3.99665706337001e-06 2.23450313019401e-06 6.99259407896521e-07 8.79808053416222e-06 2.42524906820839e-06 3.37820663073497e-05 2787 2801 0 15 56 2745 2759 0 0 65 0 0 0 0 0 0 0 0 34 0 0 0 0 0 2915 +55 7 0.996878450853562 -0.026920276483146 0.0742203000389622 -0.0110863682817838 0.0260589759775472 0.999581640030397 0.0125488917894212 0.0226853438898836 -0.0745270688730223 -0.0105756147912055 0.997162911653348 0.174346326673138 2.74611426918924e-05 -6.45101035144376e-06 5.56776144292197e-06 -1.13293741792087e-05 4.41270335941765e-06 -2.65339112429077e-06 -6.45101035144376e-06 3.22348017677831e-05 9.35049110061107e-08 2.25986506907748e-06 -8.72405387766268e-07 6.6505385708068e-06 5.56776144292197e-06 9.35049110061107e-08 1.54297528398262e-05 -2.07934499644459e-06 1.24394627862943e-06 3.1800073362413e-06 -1.13293741792087e-05 2.25986506907748e-06 -2.07934499644459e-06 7.00518770108312e-05 4.62667751617081e-06 5.47489444880128e-06 4.41270335941765e-06 -8.72405387766268e-07 1.24394627862943e-06 4.62667751617081e-06 2.67974926627665e-05 1.12968190154421e-06 -2.65339112429077e-06 6.6505385708068e-06 3.1800073362413e-06 5.47489444880128e-06 1.12968190154421e-06 3.14084664002378e-05 2882 2896 0 12 48 2831 2847 0 0 56 0 0 0 0 0 0 0 0 32 0 0 0 0 0 2639 +55 28 0.997439179306974 -0.0275220447834632 0.0660122763913407 -0.0184473812570372 0.0268525496257098 0.999578792865476 0.0110080621454102 0.0173285045183287 -0.0662874359289036 -0.00920727454437359 0.997758087881745 0.172372472675948 3.88281119332156e-05 -5.3452209885119e-06 5.28484569422291e-06 1.57373449570833e-07 -1.15668845024947e-05 6.20021306415059e-06 -5.3452209885119e-06 2.15436084762491e-05 -2.22465380791419e-06 1.78620863434399e-06 -3.75674567505444e-07 3.31915312946408e-06 5.28484569422291e-06 -2.22465380791419e-06 1.65793225036676e-05 4.1366175549023e-06 -6.21295723154032e-06 2.52169811686859e-06 1.57373449570833e-07 1.78620863434399e-06 4.1366175549023e-06 6.28100099409186e-05 -2.08946351452273e-07 6.44581687778787e-06 -1.15668845024947e-05 -3.75674567505444e-07 -6.21295723154032e-06 -2.08946351452273e-07 3.66640123761213e-05 -1.57374912910898e-06 6.20021306415059e-06 3.31915312946408e-06 2.52169811686859e-06 6.44581687778787e-06 -1.57374912910898e-06 2.95326192763768e-05 2553 2565 0 15 46 2514 2533 0 0 50 0 0 0 0 0 0 0 0 39 0 14 19 0 0 2838 +55 51 0.99732958490476 -0.0263157970196185 0.0681261910055204 -0.0152399130592924 0.0253535360623893 0.999566737052715 0.0149511332989177 0.0205839860565029 -0.0684901254403256 -0.0131839677264136 0.997564677458137 0.163731367585549 3.02247663650288e-05 -8.95277795521654e-06 1.73775962864837e-06 2.15902783673956e-07 -1.53766352273218e-06 1.59862370462386e-06 -8.95277795521654e-06 4.04224617257568e-05 -2.53461451535605e-06 6.43582570743179e-06 -5.63115788170772e-07 4.83671408347014e-06 1.73775962864837e-06 -2.53461451535605e-06 1.36267240486652e-05 8.97061121124572e-07 -6.15913228308702e-07 1.21885988026516e-06 2.15902783673956e-07 6.43582570743179e-06 8.97061121124572e-07 5.60550019845662e-05 -2.59736643938658e-06 1.01834443258605e-05 -1.53766352273218e-06 -5.63115788170772e-07 -6.15913228308702e-07 -2.59736643938658e-06 2.31523329610562e-05 1.95713759456307e-06 1.59862370462386e-06 4.83671408347014e-06 1.21885988026516e-06 1.01834443258605e-05 1.95713759456307e-06 3.26052850899768e-05 2666 2679 0 18 45 2613 2632 0 0 52 0 0 0 0 0 0 0 0 43 0 13 18 0 0 2827 +55 21 0.997184880144048 -0.0274669574647576 0.0697702018037047 -0.013622153265755 0.026236461644288 0.999484711431322 0.0184921522661819 0.0203091817292744 -0.0702421731760079 -0.016609571417621 0.99739167795046 0.166932583882396 3.08511544321495e-05 -1.2020590159505e-05 2.4583087162379e-06 -1.31109222336586e-06 5.34506028999695e-07 2.00815166862399e-06 -1.2020590159505e-05 3.50436812643058e-05 -2.0616813320179e-06 1.75007676234753e-06 5.18534017232146e-06 2.21849164096439e-07 2.4583087162379e-06 -2.0616813320179e-06 1.6423440285277e-05 -4.28632394435228e-06 -5.85488129783412e-06 -3.67747522567693e-07 -1.31109222336586e-06 1.75007676234753e-06 -4.28632394435228e-06 6.80907652324226e-05 9.88521703738114e-06 1.28092320131321e-06 5.34506028999695e-07 5.18534017232146e-06 -5.85488129783412e-06 9.88521703738114e-06 3.04179403128575e-05 3.64006791619092e-06 2.00815166862399e-06 2.21849164096439e-07 -3.67747522567693e-07 1.28092320131321e-06 3.64006791619092e-06 2.82482409329265e-05 2704 2710 0 15 55 2658 2676 0 0 64 0 0 0 0 0 0 0 0 39 0 0 0 0 0 2675 +55 8 0.997460976803227 -0.0262485511901832 0.0662013090140117 -0.0138430489205274 0.025582945451661 0.999613470657746 0.0108821956237542 0.0199611258245088 -0.0664613621344738 -0.00916094099929962 0.997746944121222 0.177403961393112 3.47137500146844e-05 -7.39787586576819e-06 3.54981212327391e-06 6.68548306184911e-06 -3.83961882082415e-06 6.86552754874483e-06 -7.39787586576819e-06 3.54241426502517e-05 -5.47173816413814e-06 4.89359148872241e-06 1.50886802568098e-06 1.17577174202504e-05 3.54981212327391e-06 -5.47173816413814e-06 1.55274038069962e-05 -2.68363167538936e-06 -1.62132966945059e-06 -3.43334876700223e-07 6.68548306184911e-06 4.89359148872241e-06 -2.68363167538936e-06 7.34866223671958e-05 1.92820528601519e-06 1.06326895587929e-05 -3.83961882082415e-06 1.50886802568098e-06 -1.62132966945059e-06 1.92820528601519e-06 3.43433100389667e-05 -4.21256618385358e-07 6.86552754874483e-06 1.17577174202504e-05 -3.43334876700223e-07 1.06326895587929e-05 -4.21256618385358e-07 4.01329801738746e-05 2679 2692 0 20 47 2646 2665 0 0 54 0 0 0 0 0 0 0 0 37 0 14 19 0 0 2813 +55 29 0.997260835347751 -0.0281346810638862 0.0684051606455203 -0.00828367489730488 0.0269941268008563 0.999481676317634 0.0175412606032449 0.0223240993031159 -0.0688632224032925 -0.0156466746219464 0.997503402587435 0.164416762876966 3.76977386335608e-05 -2.82293234593936e-06 1.88810426690226e-06 1.89604534060149e-06 -6.5341459542553e-07 1.50654518102242e-05 -2.82293234593936e-06 5.77636931242358e-05 -3.12160512639064e-06 9.56200457200188e-07 -3.88791326408643e-06 2.63842291246129e-05 1.88810426690226e-06 -3.12160512639064e-06 1.47631718639928e-05 -1.1357815478486e-06 -5.71182377724185e-06 -8.10695183656275e-07 1.89604534060149e-06 9.56200457200188e-07 -1.1357815478486e-06 7.54098710901613e-05 1.01469861465541e-05 -1.12012312329465e-06 -6.5341459542553e-07 -3.88791326408643e-06 -5.71182377724185e-06 1.01469861465541e-05 3.34380955843022e-05 -4.10326268847681e-06 1.50654518102242e-05 2.63842291246129e-05 -8.10695183656275e-07 -1.12012312329465e-06 -4.10326268847681e-06 5.89243172733808e-05 2777 2784 0 16 60 2735 2752 0 0 68 0 0 0 0 0 0 0 0 34 0 0 0 0 0 2638 +55 20 0.997192195855707 -0.0271814646466455 0.0697774498254096 -0.0115090939378712 0.0261449231848953 0.999534464739434 0.0157256729493511 0.0217686854128396 -0.070172412785441 -0.0138571922739489 0.997438625032213 0.168841266827201 2.9523508291251e-05 -7.90097800435037e-06 3.72869583323742e-06 6.08939141205059e-06 2.93456506332362e-06 2.61061987544785e-06 -7.90097800435037e-06 5.23817978105844e-05 -1.34836563420506e-06 -7.01552057460662e-07 2.69899700339681e-06 1.81941790814353e-05 3.72869583323742e-06 -1.34836563420506e-06 1.42015260164674e-05 -7.30460203362611e-07 -5.79919070814807e-06 -5.38375982977366e-07 6.08939141205059e-06 -7.01552057460662e-07 -7.30460203362611e-07 6.31188739592359e-05 9.29229679543129e-06 1.85356867973015e-06 2.93456506332362e-06 2.69899700339681e-06 -5.79919070814807e-06 9.29229679543129e-06 3.02472481496083e-05 2.00717381284215e-06 2.61061987544785e-06 1.81941790814353e-05 -5.38375982977366e-07 1.85356867973015e-06 2.00717381284215e-06 3.70033008159865e-05 2905 2911 0 14 58 2856 2874 0 0 65 0 0 0 0 0 0 0 0 45 0 0 0 0 0 2652 +55 26 0.997865187703319 -0.0274852049226053 0.0592421360197451 -0.0185207255804511 0.0266638503973256 0.999537676219375 0.0146107118224976 0.0193864694512789 -0.0596163253799546 -0.0129998972431872 0.998136712289383 0.167296310383645 4.00003976661954e-05 -9.94373062826951e-07 3.61635595302908e-06 5.03601853983831e-06 -9.44933425880634e-06 1.15111586666622e-05 -9.94373062826951e-07 6.63841924436583e-05 5.00696324916307e-07 1.08625396554148e-05 -1.95629175235782e-06 2.30222863424889e-05 3.61635595302908e-06 5.00696324916307e-07 1.47467484478329e-05 2.16768915012982e-06 -3.4005862654368e-06 1.91434291585401e-06 5.03601853983831e-06 1.08625396554148e-05 2.16768915012982e-06 8.73158855422509e-05 -5.46291805508248e-06 1.76392670543792e-05 -9.44933425880634e-06 -1.95629175235782e-06 -3.4005862654368e-06 -5.46291805508248e-06 3.02737247198493e-05 -1.06216012211841e-06 1.15111586666622e-05 2.30222863424889e-05 1.91434291585401e-06 1.76392670543792e-05 -1.06216012211841e-06 5.37985583356269e-05 2718 2731 0 13 45 2659 2678 0 0 49 0 0 0 0 0 0 0 0 32 0 14 19 0 0 2929 +55 18 0.996960813328115 -0.0269578499093333 0.073091798557766 -0.0096271725915521 0.0255948616189662 0.999481787621494 0.0195207395261958 0.0234451693957883 -0.0735801586492524 -0.0175906378852351 0.997134158331737 0.168896096002469 3.1876640164899e-05 -1.37711541702644e-05 3.25228124772e-06 9.71091515706113e-06 2.35259153748228e-06 6.26413250081969e-06 -1.37711541702644e-05 5.59153604394185e-05 -4.46432953926436e-06 5.78450480584531e-06 -2.13574783743468e-06 1.82567882074434e-06 3.25228124772e-06 -4.46432953926436e-06 1.64023282626226e-05 -4.46749024936601e-06 -3.02466039204515e-06 1.84553320792057e-06 9.71091515706113e-06 5.78450480584531e-06 -4.46749024936601e-06 7.43543153422447e-05 1.33857560691939e-05 8.29185904142256e-06 2.35259153748228e-06 -2.13574783743468e-06 -3.02466039204515e-06 1.33857560691939e-05 3.60155912502676e-05 8.76868328166891e-06 6.26413250081969e-06 1.82567882074434e-06 1.84553320792057e-06 8.29185904142256e-06 8.76868328166891e-06 3.64619845676207e-05 2816 2836 0 16 51 2772 2793 0 0 58 0 0 0 0 0 0 0 0 41 0 0 0 0 0 2648 +55 24 0.997718543614259 -0.0277506863261685 0.0615435385452369 -0.0104827036408402 0.0268376397659734 0.999517867203406 0.0156132710520905 0.0193466913720127 -0.0619471453743778 -0.013925966737746 0.997982273705493 0.168496555080453 3.35949959506931e-05 2.50847845659026e-06 5.1527398646015e-06 1.01416081822556e-05 -7.36822525497329e-06 1.04009974134864e-05 2.50847845659026e-06 5.37347438469958e-05 -1.51912686396503e-06 7.710838196323e-06 2.14424864791094e-06 1.47751898199545e-05 5.1527398646015e-06 -1.51912686396503e-06 1.38844091324305e-05 -2.61658459876732e-06 2.89005569714308e-08 -3.6954524192246e-07 1.01416081822556e-05 7.710838196323e-06 -2.61658459876732e-06 8.20392118975627e-05 2.37632124102131e-07 1.03600797399974e-05 -7.36822525497329e-06 2.14424864791094e-06 2.89005569714308e-08 2.37632124102131e-07 2.92597701833169e-05 -2.22400386610979e-06 1.04009974134864e-05 1.47751898199545e-05 -3.6954524192246e-07 1.03600797399974e-05 -2.22400386610979e-06 4.1445662964773e-05 2895 2910 0 14 52 2853 2868 0 0 59 0 0 0 0 0 0 0 0 32 0 0 0 0 0 2660 +55 19 0.996854615055119 -0.0266754985039928 0.0746277041243643 -0.0088361511325843 0.0255316994394537 0.999542106101839 0.0162391641790055 0.0220153168633889 -0.0750267203537751 -0.0142827136449197 0.997079232219734 0.170838482048486 2.79819693381561e-05 -7.62306004991655e-06 1.62502769579039e-06 5.21283164957924e-07 -8.03063396763534e-07 4.59760595722627e-06 -7.62306004991655e-06 5.10881219380798e-05 -2.13864572300064e-06 1.01775944337415e-05 -6.20274224501033e-07 -1.15738040484987e-06 1.62502769579039e-06 -2.13864572300064e-06 1.51168490180492e-05 -3.72805401496092e-06 -7.41202614514475e-07 3.63581203748938e-07 5.21283164957924e-07 1.01775944337415e-05 -3.72805401496092e-06 8.59837350016813e-05 5.31430688454649e-06 8.29542857316776e-06 -8.03063396763534e-07 -6.20274224501033e-07 -7.41202614514475e-07 5.31430688454649e-06 3.0641664373662e-05 2.67472660979627e-06 4.59760595722627e-06 -1.15738040484987e-06 3.63581203748938e-07 8.29542857316776e-06 2.67472660979627e-06 3.35727777784071e-05 2774 2791 0 19 47 2731 2750 0 0 57 0 0 0 0 0 0 0 0 39 0 12 17 0 0 2650 +55 25 0.99738891984919 -0.0277212788657285 0.0666848802961651 -0.0146118677495604 0.0267345519456323 0.999520146422839 0.015644188286187 0.0200761508845901 -0.0670865582239218 -0.0138205496604113 0.997651435178015 0.161556878618729 3.28029599694311e-05 -6.99413518997186e-06 8.07817252817014e-06 4.80062734503351e-07 -8.12853854857284e-06 3.40068705946937e-06 -6.99413518997186e-06 4.13705334611307e-05 -1.34544366797e-06 5.69201495205946e-06 -4.1474003308641e-06 1.30576629653522e-05 8.07817252817014e-06 -1.34544366797e-06 1.44019921694718e-05 4.23132210939876e-06 -3.14521397763144e-06 4.06013760750068e-06 4.80062734503351e-07 5.69201495205946e-06 4.23132210939876e-06 6.13943283569998e-05 -2.48342139677257e-06 9.94787005599732e-06 -8.12853854857284e-06 -4.1474003308641e-06 -3.14521397763144e-06 -2.48342139677257e-06 3.32588683034408e-05 -7.02204067998239e-06 3.40068705946937e-06 1.30576629653522e-05 4.06013760750068e-06 9.94787005599732e-06 -7.02204067998239e-06 4.0821448694049e-05 2845 2857 0 24 54 2789 2804 0 0 60 0 0 0 0 0 0 0 0 47 0 0 0 0 0 2794 +55 23 0.99738915590801 -0.0274203134028888 0.066805674085327 -0.0113582618318284 0.0267404239605282 0.99958133236209 0.0110503266756838 0.0172545151802207 -0.0670807081322103 -0.00923506394755753 0.997704812151553 0.171546896664265 3.92578073844429e-05 -3.23561452023806e-06 3.7106443685994e-06 4.68230526009498e-07 -1.21795088525586e-05 9.04700029712021e-06 -3.23561452023806e-06 4.60484708405373e-05 2.65917082434867e-06 3.78343641389633e-06 -8.28660493849503e-06 2.31593974832504e-05 3.7106443685994e-06 2.65917082434867e-06 1.52031771379771e-05 5.98858878325618e-07 -3.90303910707242e-06 3.46057621722973e-06 4.68230526009498e-07 3.78343641389633e-06 5.98858878325618e-07 8.05770952556423e-05 5.7697642142218e-06 4.21141860352517e-06 -1.21795088525586e-05 -8.28660493849503e-06 -3.90303910707242e-06 5.7697642142218e-06 3.89514294808437e-05 -7.87363369980703e-06 9.04700029712021e-06 2.31593974832504e-05 3.46057621722973e-06 4.21141860352517e-06 -7.87363369980703e-06 4.78219636872067e-05 2658 2674 0 14 49 2628 2646 0 0 58 0 0 0 0 0 0 0 0 29 0 0 0 0 0 2832 +55 22 0.997111945661304 -0.0276873439812586 0.0707190130219024 -0.0132726750620974 0.0266071582964514 0.999515159692263 0.0161711061074214 0.0212220157982735 -0.0711324605712196 -0.0142427711002237 0.997365187142839 0.166852801689643 3.10619437872241e-05 -1.02616385768935e-05 2.33846483823402e-06 6.3136599721021e-06 -4.38739135789141e-06 4.90281795438305e-06 -1.02616385768935e-05 5.34524865158917e-05 5.61957188661478e-07 -6.42109965997016e-06 -9.18994956553026e-06 -2.69198397241737e-06 2.33846483823402e-06 5.61957188661478e-07 1.49799257665971e-05 4.59814512552785e-07 -7.06395180470455e-08 4.83054911307991e-06 6.3136599721021e-06 -6.42109965997016e-06 4.59814512552785e-07 5.18478538200506e-05 7.44508736629982e-06 7.33741950028905e-06 -4.38739135789141e-06 -9.18994956553026e-06 -7.06395180470455e-08 7.44508736629982e-06 2.9742610496746e-05 1.73910237262929e-06 4.90281795438305e-06 -2.69198397241737e-06 4.83054911307991e-06 7.33741950028905e-06 1.73910237262929e-06 3.38995170079128e-05 2733 2747 0 18 54 2681 2695 0 0 59 0 0 0 0 0 0 0 0 34 0 0 1 0 0 2832 +55 16 0.997533638282952 -0.0257973731575519 0.0652773776445249 -0.013351703042147 0.0248110836413367 0.999566100494409 0.0158751652257117 0.024078702822473 -0.0656585913839041 -0.0142164088493218 0.99774086971363 0.167070426449943 3.01421082086606e-05 -1.22844236971391e-05 3.79608103207184e-07 -5.7963790336715e-06 -1.29350688593222e-06 -1.47893204024727e-06 -1.22844236971391e-05 4.52394617003249e-05 -2.07323136877166e-06 -2.06980738217736e-06 -2.72622766519867e-06 7.19237995353744e-06 3.79608103207184e-07 -2.07323136877166e-06 1.60987969300015e-05 -6.4953360417193e-07 -4.55683109004817e-06 3.11916171093526e-06 -5.7963790336715e-06 -2.06980738217736e-06 -6.4953360417193e-07 7.08272296621406e-05 5.70995286493958e-06 -8.73120850868983e-07 -1.29350688593222e-06 -2.72622766519867e-06 -4.55683109004817e-06 5.70995286493958e-06 2.91824177562301e-05 7.22910019954737e-07 -1.47893204024727e-06 7.19237995353744e-06 3.11916171093526e-06 -8.73120850868983e-07 7.22910019954737e-07 2.89962212601267e-05 2689 2703 0 12 46 2638 2654 0 0 54 0 0 0 0 0 0 0 0 46 0 0 0 0 0 2823 +56 2 0.995116966792304 -0.0455571675409712 0.0875600758778077 -0.0137787390307983 0.044730723934193 0.998934276652103 0.0113786319855526 0.0337094774509462 -0.087985139304354 -0.00740644416596174 0.996094252491404 0.279803555241595 3.76448355534981e-05 -8.02887128633723e-06 4.09785567304174e-06 3.81791973505143e-06 -3.95019731538085e-06 1.14166593515801e-05 -8.02887128633723e-06 3.88193512976291e-05 -4.968546495599e-06 3.25096922242245e-07 8.41577059791571e-07 4.67584527727234e-06 4.09785567304174e-06 -4.968546495599e-06 1.45270795617698e-05 -3.89211099824835e-06 -2.53867226540266e-07 -7.41363021294052e-07 3.81791973505143e-06 3.25096922242245e-07 -3.89211099824835e-06 6.37003274821707e-05 8.4799079924429e-06 7.09626663646458e-06 -3.95019731538085e-06 8.41577059791571e-07 -2.53867226540266e-07 8.4799079924429e-06 2.99170066506837e-05 4.87156565802879e-06 1.14166593515801e-05 4.67584527727234e-06 -7.41363021294052e-07 7.09626663646458e-06 4.87156565802879e-06 4.25872470978176e-05 2454 2468 0 0 86 2369 2383 0 0 96 0 0 0 0 0 0 0 0 25 0 0 0 0 0 2454 +55 9 0.99703882756443 -0.0267311459717499 0.0721042451176337 -0.0065472015333986 0.0255169731073821 0.999517535531177 0.0177081972295425 0.025052454563824 -0.0725428177863525 -0.015815878120428 0.997239889688983 0.173767287603392 3.69578202273746e-05 -6.83403688760166e-06 4.13258266371689e-06 4.06031496979168e-06 -5.03295462872239e-07 6.35897306373094e-06 -6.83403688760166e-06 4.57953370654251e-05 -2.07195506913414e-06 6.1177996547293e-06 -2.48151248805893e-07 1.44634950836851e-05 4.13258266371689e-06 -2.07195506913414e-06 1.63713572264219e-05 -3.31894440414803e-06 -5.2554781006298e-07 -5.14691335802478e-07 4.06031496979168e-06 6.1177996547293e-06 -3.31894440414803e-06 8.0635437947302e-05 5.41039431575675e-06 6.60350849872647e-06 -5.03295462872239e-07 -2.48151248805893e-07 -5.2554781006298e-07 5.41039431575675e-06 2.69929983755e-05 1.53208715574119e-06 6.35897306373094e-06 1.44634950836851e-05 -5.14691335802478e-07 6.60350849872647e-06 1.53208715574119e-06 4.18013260980862e-05 2884 2904 0 16 50 2842 2864 0 0 59 0 0 0 0 0 0 0 0 27 0 0 0 0 0 2776 +56 3 0.996039791454492 -0.0463706236886198 0.075858414813517 -0.0330864241838835 0.0451062982873562 0.99881461648057 0.0182970970261287 0.0363990840878231 -0.0766169412995797 -0.0148029444199434 0.996950709484876 0.273314995577335 3.33386565654245e-05 -4.05142155773412e-06 5.570658757934e-06 -3.42995851204886e-06 -4.6810164376822e-06 9.02097518453791e-06 -4.05142155773412e-06 3.82639587500154e-05 -3.89220225917406e-07 1.77310564216864e-06 -1.35292064881362e-06 2.28608007722309e-05 5.570658757934e-06 -3.89220225917406e-07 1.42864960580921e-05 -1.12389493387488e-06 -2.21919653344051e-06 2.19368758202526e-06 -3.42995851204886e-06 1.77310564216864e-06 -1.12389493387488e-06 7.9433417903416e-05 3.74620099136395e-06 -4.17814929175718e-06 -4.6810164376822e-06 -1.35292064881362e-06 -2.21919653344051e-06 3.74620099136395e-06 2.82416227204954e-05 -2.61234342944794e-06 9.02097518453791e-06 2.28608007722309e-05 2.19368758202526e-06 -4.17814929175718e-06 -2.61234342944794e-06 5.87879158597516e-05 2574 2588 0 0 79 2498 2512 0 0 90 0 0 0 0 0 0 0 0 24 0 0 0 0 0 2442 +55 17 0.997568334243824 -0.0270295963708776 0.0642403256064976 -0.0190818501079847 0.0260447195890625 0.999530805880087 0.0161195743812274 0.0228853998257189 -0.0646458900126566 -0.0144072556974692 0.99780425930527 0.168169844371889 3.07829855350483e-05 -7.75722960446926e-06 1.36029315752363e-06 5.38026313429173e-07 -7.50407466359268e-06 2.7713882214366e-06 -7.75722960446926e-06 3.52768552768982e-05 -2.1064468381578e-06 8.74400973858363e-06 2.46785128961329e-06 8.50932165496688e-06 1.36029315752363e-06 -2.1064468381578e-06 1.42507910706181e-05 2.19521483585533e-06 1.4927313058101e-06 1.50944598346594e-06 5.38026313429173e-07 8.74400973858363e-06 2.19521483585533e-06 7.89320426520006e-05 2.50506202784602e-06 7.90077245231516e-06 -7.50407466359268e-06 2.46785128961329e-06 1.4927313058101e-06 2.50506202784602e-06 3.22979627102645e-05 -2.1970689350293e-06 2.7713882214366e-06 8.50932165496688e-06 1.50944598346594e-06 7.90077245231516e-06 -2.1970689350293e-06 3.38816626473905e-05 2664 2685 0 18 44 2619 2643 0 0 54 0 0 0 0 0 0 0 0 38 0 0 0 0 0 2801 +56 53 0.999211072526609 -0.0354106965685665 0.0179809651785842 -0.0217574158469248 0.0350961534212062 0.999230404420073 0.0175173884335485 0.040421990705928 -0.0185874300337541 -0.0168725057719822 0.9996848633413 0.257783382759602 4.9915432417551e-05 1.24443637477093e-05 3.40528012838473e-06 -1.5460616702278e-06 -4.09238188479507e-06 3.31812197366909e-05 1.24443637477093e-05 5.22176088799025e-05 -2.4608080601801e-06 9.13544211606073e-06 -5.64725804422326e-06 4.93682955943938e-05 3.40528012838473e-06 -2.4608080601801e-06 1.46096411669443e-05 7.32581342496634e-07 -4.54231955542455e-07 -1.66527850134126e-06 -1.5460616702278e-06 9.13544211606073e-06 7.32581342496634e-07 4.78813942973275e-05 3.0370367589299e-06 1.10451994193914e-05 -4.09238188479507e-06 -5.64725804422326e-06 -4.54231955542455e-07 3.0370367589299e-06 3.17302060312305e-05 -1.48540572549982e-05 3.31812197366909e-05 4.93682955943938e-05 -1.66527850134126e-06 1.10451994193914e-05 -1.48540572549982e-05 0.000111575847830831 2354 2354 0 0 49 2292 2295 0 0 64 0 0 0 0 0 0 0 0 22 0 0 0 0 0 2436 +56 5 0.996945160987085 -0.0464124579599944 0.0628190236357399 -0.0309878879570436 0.0453471260751691 0.998804018907817 0.0182803164719693 0.0381538305689151 -0.0635923276909929 -0.0153758108633134 0.997857505007171 0.27562624436191 6.4658449361808e-05 -9.5853837072137e-06 -2.29760861147673e-06 7.62748273456096e-06 -6.60576216332153e-06 2.49975562610375e-05 -9.5853837072137e-06 0.000129833163634542 1.73079673718802e-06 7.99488262469139e-06 1.31650736694108e-06 4.60598002233004e-05 -2.29760861147673e-06 1.73079673718802e-06 1.56178889903713e-05 -2.11730654831889e-06 6.49246008791927e-07 -9.86075163201228e-07 7.62748273456096e-06 7.99488262469139e-06 -2.11730654831889e-06 7.17922834001997e-05 -2.06476733876412e-06 6.84688516248473e-06 -6.60576216332153e-06 1.31650736694108e-06 6.49246008791927e-07 -2.06476733876412e-06 3.11625256947758e-05 -3.3258348596229e-06 2.49975562610375e-05 4.60598002233004e-05 -9.86075163201228e-07 6.84688516248473e-06 -3.3258348596229e-06 8.80347709264668e-05 2400 2412 0 0 81 2336 2348 0 0 93 0 0 0 0 0 0 0 0 22 0 0 0 0 0 2509 +55 10 0.997120613614278 -0.0254830700917833 0.0714219507167324 -0.0147660136093587 0.024591292092592 0.999608609073824 0.013337804118837 0.0237948700592489 -0.0717338850105228 -0.0115430413753439 0.997357011273849 0.174726336047126 4.39016929935966e-05 -2.73918272201497e-05 7.81426889229354e-08 2.86842339389452e-07 -7.28490633625717e-08 2.49550988216286e-06 -2.73918272201497e-05 0.000101858280532886 -2.09322138372631e-06 5.84270412748896e-06 1.9484504164141e-06 1.07425614843379e-05 7.81426889229354e-08 -2.09322138372631e-06 1.62899031534246e-05 -4.0384245605591e-06 -5.20219296702072e-06 2.39722625293496e-06 2.86842339389452e-07 5.84270412748896e-06 -4.0384245605591e-06 8.93931969697658e-05 9.1308227722161e-06 2.18947820495454e-06 -7.28490633625717e-08 1.9484504164141e-06 -5.20219296702072e-06 9.1308227722161e-06 3.20995380647169e-05 2.92807218941305e-06 2.49550988216286e-06 1.07425614843379e-05 2.39722625293496e-06 2.18947820495454e-06 2.92807218941305e-06 3.49396862099696e-05 2681 2687 0 17 53 2628 2646 0 0 63 0 0 0 0 0 0 0 0 34 0 0 0 0 0 2839 +56 54 0.99844304063954 -0.0282656231940237 0.0480889711256371 -0.00879710284308468 0.0283710610173718 0.99959631799594 -0.00151127287706171 0.0279609010964183 -0.0480268414037135 0.00287325502067764 0.998841912872287 0.224127294640737 6.44697255500448e-05 1.09109688482382e-05 5.03524635878711e-06 1.28071228573174e-05 -9.45078405077341e-06 3.71445702669726e-05 1.09109688482382e-05 5.80650050116046e-05 -7.08578139312248e-06 1.96780200786099e-05 -2.6827148523947e-06 3.01121813234173e-05 5.03524635878711e-06 -7.08578139312248e-06 1.56350699586063e-05 -2.16104204666784e-06 5.96344196096825e-07 -1.90507200431675e-06 1.28071228573174e-05 1.96780200786099e-05 -2.16104204666784e-06 6.51164714436194e-05 1.83126899346389e-07 2.01586730795759e-05 -9.45078405077341e-06 -2.6827148523947e-06 5.96344196096825e-07 1.83126899346389e-07 2.77812582765712e-05 -3.47663699293e-06 3.71445702669726e-05 3.01121813234173e-05 -1.90507200431675e-06 2.01586730795759e-05 -3.47663699293e-06 7.99824486613482e-05 3002 3015 0 0 51 2912 2930 0 0 62 0 0 0 0 0 0 0 0 53 0 0 0 0 0 2590 +56 52 0.997248422477513 -0.0418690330862517 0.0611765309128803 -0.0262319136468833 0.0410385738966568 0.999048398161134 0.01476934609931 0.0393710913969699 -0.0617366934540625 -0.012218109513952 0.998017684453169 0.284079649083923 4.14288848314493e-05 -1.34205186028e-06 3.1525305303602e-06 5.45387827461076e-06 -3.70721849313703e-06 1.55184209451262e-05 -1.34205186028e-06 0.000138990997356221 -7.46785385663177e-06 2.73336687182415e-05 -9.2588462983649e-06 6.53092052673991e-05 3.1525305303602e-06 -7.46785385663177e-06 1.52740933478244e-05 -1.97271536284628e-07 2.86584330746762e-07 8.03313701669112e-07 5.45387827461076e-06 2.73336687182415e-05 -1.97271536284628e-07 5.38323248725769e-05 -3.15777703416047e-06 2.53618860702359e-05 -3.70721849313703e-06 -9.2588462983649e-06 2.86584330746762e-07 -3.15777703416047e-06 2.70547713769908e-05 -8.43225393470447e-06 1.55184209451262e-05 6.53092052673991e-05 8.03313701669112e-07 2.53618860702359e-05 -8.43225393470447e-06 8.2997081527412e-05 2605 2619 0 0 74 2516 2530 0 0 85 0 0 0 0 0 0 0 0 27 0 0 0 0 0 2666 +56 4 0.995794985439314 -0.0461905323256559 0.0791124623393069 -0.0204873174827003 0.0450818742742631 0.998859227149797 0.015743854344763 0.0364426306160158 -0.0797494300031997 -0.0121111131272939 0.996741365326524 0.286294728296348 4.65903707709319e-05 -4.96120072754577e-08 3.52086038014843e-06 -5.82397216825403e-06 -8.80966111189395e-06 1.76154440793002e-05 -4.96120072754577e-08 5.83788296736505e-05 -7.46289916851761e-07 1.01170814709336e-05 -1.02647695135725e-05 3.48605936699237e-05 3.52086038014843e-06 -7.46289916851761e-07 1.51032479500171e-05 2.80816479822702e-07 5.62491870408127e-07 3.468612412328e-06 -5.82397216825403e-06 1.01170814709336e-05 2.80816479822702e-07 7.41036988237712e-05 1.50129225046993e-06 2.37438888240191e-05 -8.80966111189395e-06 -1.02647695135725e-05 5.62491870408127e-07 1.50129225046993e-06 3.54451561493697e-05 -1.62312344066333e-05 1.76154440793002e-05 3.48605936699237e-05 3.468612412328e-06 2.37438888240191e-05 -1.62312344066333e-05 8.72809595902355e-05 2622 2639 0 0 84 2533 2550 0 0 99 0 0 0 0 0 0 0 0 27 0 0 0 0 0 2482 +56 6 0.996427099128238 -0.046512363836078 0.0704956462007821 -0.0253335590582248 0.0454083798142131 0.998820705393094 0.0171836410778032 0.0360347120363886 -0.0712117628312466 -0.0139211525536828 0.997364069107186 0.288549612619568 5.34945505326305e-05 -1.6680831355109e-05 -3.63074382436316e-06 6.08500505679822e-06 -6.71668755022021e-06 1.71186042468206e-05 -1.6680831355109e-05 0.000104199302549002 -2.03482788212698e-06 1.00216718335018e-05 -3.41087836649174e-07 3.30410628283619e-05 -3.63074382436316e-06 -2.03482788212698e-06 1.46987481381995e-05 -3.29118115242543e-07 -2.40313803695376e-06 -1.91672811045093e-06 6.08500505679822e-06 1.00216718335018e-05 -3.29118115242543e-07 7.04433292451432e-05 -6.76767979412221e-06 1.87993246732685e-05 -6.71668755022021e-06 -3.41087836649174e-07 -2.40313803695376e-06 -6.76767979412221e-06 3.41878291364953e-05 -6.61716418223623e-06 1.71186042468206e-05 3.30410628283619e-05 -1.91672811045093e-06 1.87993246732685e-05 -6.61716418223623e-06 7.91896808674406e-05 2431 2444 0 0 80 2358 2371 0 0 93 0 0 0 0 0 0 0 0 28 0 0 0 0 0 2437 +56 28 0.996836023567402 -0.0468406404457189 0.0642175717460919 -0.0307331921483461 0.0457548709889867 0.998785499882142 0.0182761321389793 0.0377439894851751 -0.064995645231898 -0.0152800401771441 0.99776855355993 0.28423110238355 5.04208949746739e-05 1.78728815169323e-06 1.90334045024723e-06 3.90423586148286e-06 -1.00761747391398e-05 2.18030184610348e-05 1.78728815169323e-06 0.000130576938209648 1.06373336165191e-06 8.08983335570858e-06 -8.10362986058462e-06 7.45581748862656e-05 1.90334045024723e-06 1.06373336165191e-06 1.61426339776195e-05 1.76015870402743e-06 -1.91896795955654e-06 3.11150727501568e-06 3.90423586148286e-06 8.08983335570858e-06 1.76015870402743e-06 6.3394053245786e-05 -5.70052464145355e-07 1.75418693796077e-07 -1.00761747391398e-05 -8.10362986058462e-06 -1.91896795955654e-06 -5.70052464145355e-07 3.6361585466434e-05 -1.27192204575374e-05 2.18030184610348e-05 7.45581748862656e-05 3.11150727501568e-06 1.75418693796077e-07 -1.27192204575374e-05 0.000108418574278065 2410 2417 0 0 83 2343 2350 0 0 94 0 0 0 0 0 0 0 0 21 0 0 0 0 0 2472 +56 1 0.996753699317619 -0.045943623098414 0.066115402087813 -0.0262829298784373 0.0446297798833439 0.998778320404735 0.0212143686462818 0.0391367638615735 -0.0670092952075051 -0.0181947845847912 0.997586439447583 0.282423498854704 4.297329026358e-05 -1.39413346641203e-05 2.76790770201709e-06 -6.36012474444017e-07 -2.04750098291441e-06 5.61186025129168e-06 -1.39413346641203e-05 0.000100725605901298 -2.74832622672637e-06 1.1932978976667e-05 1.98796650387402e-06 2.56289446324924e-05 2.76790770201709e-06 -2.74832622672637e-06 1.55033064456101e-05 1.78683169457424e-06 -2.15314910368968e-06 -3.79479126912458e-06 -6.36012474444017e-07 1.1932978976667e-05 1.78683169457424e-06 5.8241524128668e-05 5.53465983566643e-06 1.24619228969463e-05 -2.04750098291441e-06 1.98796650387402e-06 -2.15314910368968e-06 5.53465983566643e-06 3.30389042331147e-05 2.22328538422052e-06 5.61186025129168e-06 2.56289446324924e-05 -3.79479126912458e-06 1.24619228969463e-05 2.22328538422052e-06 6.13311520537264e-05 2411 2422 0 0 79 2337 2348 0 0 93 0 0 0 0 0 0 0 0 23 0 0 0 0 0 2422 +56 25 0.996196272197808 -0.0474170452296014 0.0731068470178105 -0.022069835802873 0.0465030310864497 0.998817849903519 0.0141552398031379 0.0350389934713468 -0.0736916233975363 -0.0107017071444505 0.997223655006855 0.290417313784126 4.33310829497075e-05 7.88896429137568e-06 4.99084016020231e-06 -7.77526150154887e-06 -8.07789906120034e-06 2.30283008080876e-05 7.88896429137568e-06 9.57192754681286e-05 3.86553623792622e-06 -2.76131816305632e-05 -3.59377955450962e-06 6.76453254513195e-05 4.99084016020231e-06 3.86553623792622e-06 1.43899686866278e-05 -1.51574681022137e-06 -4.12297786678805e-07 5.27036160621988e-06 -7.77526150154887e-06 -2.76131816305632e-05 -1.51574681022137e-06 6.97487902675683e-05 -1.97919796800599e-07 -2.14490554566341e-05 -8.07789906120034e-06 -3.59377955450962e-06 -4.12297786678805e-07 -1.97919796800599e-07 3.42543154292874e-05 -1.01338059850996e-05 2.30283008080876e-05 6.76453254513195e-05 5.27036160621988e-06 -2.14490554566341e-05 -1.01338059850996e-05 0.00010740722503661 2711 2726 0 0 86 2627 2642 0 0 98 0 0 0 0 0 0 0 0 34 0 0 0 0 0 2442 +56 23 0.996250221976921 -0.047107898805782 0.0725695602924473 -0.0195883506127266 0.0461749474935628 0.998828396012863 0.0144813515370053 0.0345645397906372 -0.0731667235490401 -0.0110761540471326 0.997258215998556 0.290694121153016 4.37084497363756e-05 -4.7725765128378e-06 2.18466466932888e-06 1.24988687482698e-06 -7.16110554693329e-06 2.26049446075072e-05 -4.7725765128378e-06 4.46102750673093e-05 8.38651446331477e-07 6.53180595807947e-06 -5.18248941817691e-06 2.05582988387406e-05 2.18466466932888e-06 8.38651446331477e-07 1.45567716447619e-05 -4.60359717771103e-06 -8.77183314902288e-07 2.20235576549521e-06 1.24988687482698e-06 6.53180595807947e-06 -4.60359717771103e-06 7.04617392141498e-05 7.11043723296426e-06 3.70478365825306e-06 -7.16110554693329e-06 -5.18248941817691e-06 -8.77183314902288e-07 7.11043723296426e-06 3.33285679917868e-05 -1.72079083650901e-05 2.26049446075072e-05 2.05582988387406e-05 2.20235576549521e-06 3.70478365825306e-06 -1.72079083650901e-05 8.34827870547094e-05 2566 2576 0 0 81 2504 2514 0 0 97 0 0 0 0 0 0 0 0 20 0 0 0 0 0 2475 +56 7 0.99637066601323 -0.0455729541369973 0.0718929882504452 -0.019684412302572 0.0446145970206268 0.998893432617864 0.0148811291771739 0.0397968535711381 -0.0724916108321411 -0.0116196438898874 0.997301333717565 0.293499490062021 3.29490337807639e-05 -7.68587703870884e-06 4.08815563049616e-06 -2.17804027309031e-06 -3.70592196189416e-06 8.48572218755148e-06 -7.68587703870884e-06 5.93224193973719e-05 5.52921762392663e-07 1.02695159021479e-05 -2.32436641771618e-06 2.56990401271095e-05 4.08815563049616e-06 5.52921762392663e-07 1.61229893299745e-05 -3.18478441119836e-06 -2.81755785301793e-07 2.72502208754005e-06 -2.17804027309031e-06 1.02695159021479e-05 -3.18478441119836e-06 7.18390802981493e-05 1.19477000844307e-05 3.76665209280968e-06 -3.70592196189416e-06 -2.32436641771618e-06 -2.81755785301793e-07 1.19477000844307e-05 3.16405950279939e-05 -4.51351163804552e-06 8.48572218755148e-06 2.56990401271095e-05 2.72502208754005e-06 3.76665209280968e-06 -4.51351163804552e-06 6.12889554498731e-05 2588 2599 0 0 82 2507 2518 0 0 94 0 0 0 0 0 0 0 0 18 0 0 0 0 0 2503 +56 29 0.996566300446782 -0.0473655177232246 0.0679125654398802 -0.0209175812526341 0.0462640926189146 0.998772396567912 0.0177012312605111 0.0363440877235415 -0.0686676237244569 -0.0144985373331417 0.99753423493494 0.280540241985429 4.6647593925472e-05 1.29659057984017e-05 2.83788700711725e-06 4.11636812178369e-06 -2.55714293854866e-06 3.65909252190773e-05 1.29659057984017e-05 0.000168545267475563 4.61928950406444e-07 -8.45587174936067e-06 -5.06296281117455e-06 0.000155886364445693 2.83788700711725e-06 4.61928950406444e-07 1.32004740614495e-05 1.44288798957067e-06 -4.78064112113873e-06 2.81965644897023e-06 4.11636812178369e-06 -8.45587174936067e-06 1.44288798957067e-06 6.02273734924012e-05 4.52817506273982e-06 4.06316765126801e-06 -2.55714293854866e-06 -5.06296281117455e-06 -4.78064112113873e-06 4.52817506273982e-06 3.54326637501938e-05 -7.31182281515521e-06 3.65909252190773e-05 0.000155886364445693 2.81965644897023e-06 4.06316765126801e-06 -7.31182281515521e-06 0.000202766621898885 2722 2736 0 0 83 2636 2650 0 0 98 0 0 0 0 0 0 0 0 23 0 0 0 0 0 2505 +56 22 0.996333641423113 -0.0474313570787255 0.0712007116132245 -0.0322627189530108 0.0459872182132949 0.998704398907509 0.0217875965584646 0.0399973620369147 -0.072141879165724 -0.0184333927550535 0.997224026636932 0.28369663573877 3.93658940512266e-05 -8.17657705032164e-06 1.43448976970431e-06 9.96423642260041e-07 -9.13191273179018e-08 4.5661269577999e-06 -8.17657705032164e-06 4.36651844111938e-05 3.25615562147857e-06 -4.22901489641039e-06 -3.12777872634339e-06 2.4464746290696e-05 1.43448976970431e-06 3.25615562147857e-06 1.40523957057608e-05 1.03386514784772e-07 1.31352838576067e-06 4.09784658041062e-06 9.96423642260041e-07 -4.22901489641039e-06 1.03386514784772e-07 5.32185126997424e-05 5.6779036423898e-06 -6.30267089621419e-07 -9.13191273179018e-08 -3.12777872634339e-06 1.31352838576067e-06 5.6779036423898e-06 3.22721870234678e-05 -9.28112545649392e-06 4.5661269577999e-06 2.4464746290696e-05 4.09784658041062e-06 -6.30267089621419e-07 -9.28112545649392e-06 7.00255635361172e-05 2611 2626 0 0 82 2534 2549 0 0 95 0 0 0 0 0 0 0 0 24 0 0 0 0 0 2478 +56 30 0.996233453742839 -0.0468131689487354 0.0729892653517788 -0.0227612512679953 0.0457682995396089 0.998825159004273 0.0159237086553962 0.0372673053027993 -0.073648953834171 -0.0125231367103639 0.997205596978911 0.29151539885366 4.34668035307813e-05 1.28873412872281e-06 4.57539266382154e-06 2.22436259779693e-06 -5.90521456638887e-06 1.96994289377165e-05 1.28873412872281e-06 7.45544248156937e-05 -2.63723760128095e-06 1.37276138948324e-05 1.61324074699611e-06 5.0834980213151e-05 4.57539266382154e-06 -2.63723760128095e-06 1.25617682105506e-05 -1.40551834479164e-06 1.50359995955157e-07 -2.29365400585966e-06 2.22436259779693e-06 1.37276138948324e-05 -1.40551834479164e-06 4.97413024047494e-05 4.28414294989378e-06 2.45139497324147e-05 -5.90521456638887e-06 1.61324074699611e-06 1.50359995955157e-07 4.28414294989378e-06 3.31659098840477e-05 -5.1336275999106e-06 1.96994289377165e-05 5.0834980213151e-05 -2.29365400585966e-06 2.45139497324147e-05 -5.1336275999106e-06 0.000105213927890018 2775 2787 0 0 82 2691 2703 0 0 95 0 0 0 0 0 0 0 0 18 0 0 0 0 0 2490 +56 26 0.995191763466272 -0.0467627835384187 0.0860615826291368 -0.018694594695176 0.0459889537498846 0.998881894134519 0.0109534333990108 0.0342996996440276 -0.0864775697038471 -0.00694288455719868 0.996229605207626 0.304984426571435 4.66582090750231e-05 -1.01197954933044e-05 6.48906320961615e-06 -3.31654894090338e-06 -7.45351717675178e-06 1.64394142907717e-05 -1.01197954933044e-05 6.35040086312444e-05 -6.05819889200036e-06 2.91947174241875e-06 -5.54587024618348e-08 4.05328991041e-05 6.48906320961615e-06 -6.05819889200036e-06 1.50590884479022e-05 -2.257685570034e-06 2.81316323440158e-07 2.82284245240929e-08 -3.31654894090338e-06 2.91947174241875e-06 -2.257685570034e-06 6.19390617506532e-05 2.98753535757668e-06 3.20228816627645e-06 -7.45351717675178e-06 -5.54587024618348e-08 2.81316323440158e-07 2.98753535757668e-06 3.02210791616017e-05 -3.80778615583124e-06 1.64394142907717e-05 4.05328991041e-05 2.82284245240929e-08 3.20228816627645e-06 -3.80778615583124e-06 9.85978007504707e-05 2588 2595 0 0 87 2502 2509 0 0 97 0 0 0 0 0 0 0 0 19 0 0 0 0 0 2625 +56 20 0.996384386394235 -0.0451665322718639 0.0719592864911682 -0.0174876559933568 0.044003551320837 0.998875156821523 0.0176665943501131 0.0407017703554698 -0.0726762823824788 -0.0144362546150884 0.997251098034868 0.285999959913828 4.41924351112463e-05 -6.88765877927489e-06 2.27921947273901e-06 5.14497205013744e-06 3.76724328241731e-06 1.59491028567422e-05 -6.88765877927489e-06 7.68701210593678e-05 4.10936469187031e-07 3.9230802922505e-06 -3.70794004663634e-06 4.71641889084458e-05 2.27921947273901e-06 4.10936469187031e-07 1.45003467970041e-05 -4.95496487195451e-07 -1.82886414809903e-06 3.53044007192378e-06 5.14497205013744e-06 3.9230802922505e-06 -4.95496487195451e-07 6.51294999308932e-05 5.56249221337644e-06 8.56697504163306e-06 3.76724328241731e-06 -3.70794004663634e-06 -1.82886414809903e-06 5.56249221337644e-06 3.08098089784657e-05 -1.68562055093811e-06 1.59491028567422e-05 4.71641889084458e-05 3.53044007192378e-06 8.56697504163306e-06 -1.68562055093811e-06 8.53574737907625e-05 2623 2637 0 0 84 2533 2547 0 0 99 0 0 0 0 0 0 0 0 23 0 0 0 0 0 2434 +56 27 0.996275916312325 -0.04603023617456 0.0729075848849159 -0.0201098505003672 0.0451009546838189 0.998879473239841 0.0143423089740007 0.0365719041818409 -0.0734860698543956 -0.0110006953331058 0.99723557008339 0.286707957959525 5.03068696660815e-05 -4.51319530856977e-06 7.10062279369955e-06 -4.47561055856546e-06 -6.51703364491296e-06 2.04779818525478e-05 -4.51319530856977e-06 8.05505362458404e-05 -5.28235368476663e-06 8.37584112888221e-06 1.28725393892119e-06 8.14551044711734e-05 7.10062279369955e-06 -5.28235368476663e-06 1.71746878752287e-05 -1.63705678092886e-06 -2.88139381951432e-06 -4.52677485677157e-07 -4.47561055856546e-06 8.37584112888221e-06 -1.63705678092886e-06 6.83947369657584e-05 1.01965042695359e-06 1.51694220033695e-05 -6.51703364491296e-06 1.28725393892119e-06 -2.88139381951432e-06 1.01965042695359e-06 3.25880820194578e-05 -6.07671592781971e-06 2.04779818525478e-05 8.14551044711734e-05 -4.52677485677157e-07 1.51694220033695e-05 -6.07671592781971e-06 0.000147162164200293 2576 2590 0 0 85 2496 2510 0 0 101 0 0 0 0 0 0 0 0 21 0 0 0 0 0 2609 +56 24 0.995194475456961 -0.0468852017540295 0.0859635613293674 -0.0175650524042029 0.045766463974434 0.998840439936757 0.0149400911048911 0.0351298256836533 -0.0865643506024321 -0.0109340478977168 0.996186257585071 0.297314734515347 3.98367707006937e-05 -1.14440777517758e-07 4.263233558991e-06 4.49770269577482e-06 -7.59479083181231e-06 1.82697195099475e-05 -1.14440777517758e-07 4.90913144400494e-05 -5.36317729186554e-06 -4.69723496650831e-06 -4.5848394250429e-06 2.63559066357447e-05 4.263233558991e-06 -5.36317729186554e-06 1.3591562319276e-05 -6.0083993321729e-07 2.11405649938055e-06 5.84578522843597e-07 4.49770269577482e-06 -4.69723496650831e-06 -6.0083993321729e-07 5.7204307574653e-05 4.23016636257035e-06 1.39067975889973e-08 -7.59479083181231e-06 -4.5848394250429e-06 2.11405649938055e-06 4.23016636257035e-06 3.34152805531414e-05 -1.08567059059607e-05 1.82697195099475e-05 2.63559066357447e-05 5.84578522843597e-07 1.39067975889973e-08 -1.08567059059607e-05 8.02869726081064e-05 2594 2609 0 0 87 2507 2522 0 0 104 0 0 0 0 0 0 0 0 22 0 0 0 0 0 2522 +56 17 0.996480229651783 -0.0471693708184895 0.069297924714361 -0.0279335043170798 0.0459717063345505 0.99876623286543 0.018778027172413 0.0364865788398862 -0.0700981749392898 -0.0155261889846112 0.997419261557443 0.290451686833223 4.22991795880739e-05 3.00072482270437e-06 8.04571527818914e-07 6.63519354142794e-06 -5.67365820427274e-06 1.86800143610496e-05 3.00072482270437e-06 0.000139304443922789 1.9344476436751e-06 1.28889215961241e-05 5.55886080024558e-06 6.67486514446314e-05 8.04571527818914e-07 1.9344476436751e-06 1.56618441338689e-05 -1.58879085011811e-06 8.49636173426064e-07 1.77921782916003e-06 6.63519354142794e-06 1.28889215961241e-05 -1.58879085011811e-06 5.68704751328092e-05 6.68533206904316e-06 9.84780307198953e-06 -5.67365820427274e-06 5.55886080024558e-06 8.49636173426064e-07 6.68533206904316e-06 3.0516554249368e-05 -2.78755428176937e-06 1.86800143610496e-05 6.67486514446314e-05 1.77921782916003e-06 9.84780307198953e-06 -2.78755428176937e-06 9.24412141111351e-05 2536 2546 0 0 75 2467 2477 0 0 93 0 0 0 0 0 0 0 0 29 0 0 0 0 0 2452 +56 8 0.996155704391885 -0.0471728341371415 0.0738142013909092 -0.0267142519499428 0.046149971054013 0.998814215781258 0.0155029843895856 0.0362118867737849 -0.0744579933870214 -0.0120368630772185 0.997151503608172 0.300174729345122 6.89603455633543e-05 1.29676477171154e-05 4.10889086715472e-06 1.0674148810776e-05 -1.16479021188947e-05 5.26830708649397e-05 1.29676477171154e-05 0.000147786964556277 3.31428490714805e-06 8.45094106113932e-06 -6.95269706833208e-06 7.79339021545529e-05 4.10889086715472e-06 3.31428490714805e-06 1.502023514304e-05 -2.33194824664594e-07 -2.29837647085807e-07 2.85599200104614e-06 1.0674148810776e-05 8.45094106113932e-06 -2.33194824664594e-07 6.98413429539629e-05 2.8821788481873e-06 1.44190359957003e-05 -1.16479021188947e-05 -6.95269706833208e-06 -2.29837647085807e-07 2.8821788481873e-06 3.42193036758642e-05 -1.35892706384899e-05 5.26830708649397e-05 7.79339021545529e-05 2.85599200104614e-06 1.44190359957003e-05 -1.35892706384899e-05 0.000142743774093455 2522 2529 0 0 83 2455 2462 0 0 96 0 0 0 0 0 0 0 0 27 0 0 0 0 0 2445 +56 10 0.996022778956324 -0.0450335829710833 0.0768804279703712 -0.0163583431969325 0.0439535328756356 0.998910455120884 0.0156840555322461 0.039649695484821 -0.0775029725099063 -0.0122425101582444 0.996916952507657 0.301262224420649 3.69625863149085e-05 -2.25423147505567e-06 8.27599129572779e-08 3.14917265486021e-06 -2.99492431057953e-06 4.44539972560177e-06 -2.25423147505567e-06 4.22644096490802e-05 2.22781879645876e-07 -4.75159511837435e-06 -2.22447670410225e-06 2.11568348045826e-05 8.27599129572779e-08 2.22781879645876e-07 1.54095514988981e-05 -5.36237815336721e-06 -2.63391786588673e-06 2.71275107869329e-06 3.14917265486021e-06 -4.75159511837435e-06 -5.36237815336721e-06 6.96304857538862e-05 1.25459382091694e-05 -2.15738756496723e-06 -2.99492431057953e-06 -2.22447670410225e-06 -2.63391786588673e-06 1.25459382091694e-05 3.46113201266776e-05 -9.16727254665377e-06 4.44539972560177e-06 2.11568348045826e-05 2.71275107869329e-06 -2.15738756496723e-06 -9.16727254665377e-06 5.12852441824882e-05 2552 2569 0 0 85 2466 2483 0 0 100 0 0 0 0 0 0 0 0 24 0 0 0 0 0 2501 +56 9 0.995992923103482 -0.0454677219214385 0.0770115795907146 -0.016545027719308 0.0443869728398633 0.998891218867493 0.0156885152747781 0.0398148137589493 -0.0776395116541537 -0.0122073392960318 0.996906759480252 0.303520429865742 4.79619631984266e-05 -5.47514878584218e-06 5.39699666316653e-06 -1.8321183508662e-06 -7.33525093337576e-06 1.54054293179126e-05 -5.47514878584218e-06 6.10774462460411e-05 -1.93377490347412e-06 3.4745148111491e-06 4.74838204042494e-06 3.17653793712831e-05 5.39699666316653e-06 -1.93377490347412e-06 1.71653330672527e-05 -8.57487878640602e-06 -2.12876904774265e-06 4.65763779253968e-06 -1.8321183508662e-06 3.4745148111491e-06 -8.57487878640602e-06 9.30032640903246e-05 8.07219825910453e-06 -9.04485622426723e-07 -7.33525093337576e-06 4.74838204042494e-06 -2.12876904774265e-06 8.07219825910453e-06 3.42389256433072e-05 9.815170979048e-07 1.54054293179126e-05 3.17653793712831e-05 4.65763779253968e-06 -9.04485622426723e-07 9.815170979048e-07 7.42440093906165e-05 2707 2718 0 0 84 2626 2637 0 0 95 0 0 0 0 0 0 0 0 20 0 0 0 0 0 2453 +56 21 0.996523451643789 -0.0463014932219269 0.0692616925101398 -0.0257085889048771 0.0448158225240298 0.998733835573522 0.0228531777242245 0.0388689043106766 -0.0702321320724635 -0.0196697078275248 0.997336728601998 0.282102315587913 4.12296257956177e-05 -5.65575728351216e-06 3.12527340869616e-06 2.44720368923083e-06 -2.90796871373939e-06 1.41904530605261e-05 -5.65575728351216e-06 5.11781174476349e-05 -2.94540905956203e-06 6.3959114512875e-06 -5.15077879516253e-06 1.71921052444317e-05 3.12527340869616e-06 -2.94540905956203e-06 1.6623583050583e-05 -2.38026795786762e-06 -2.24536042386116e-06 3.22713377002339e-06 2.44720368923083e-06 6.3959114512875e-06 -2.38026795786762e-06 6.03509419687911e-05 4.02124386340466e-06 8.69440992028268e-06 -2.90796871373939e-06 -5.15077879516253e-06 -2.24536042386116e-06 4.02124386340466e-06 3.17919468139759e-05 -6.8594972312459e-06 1.41904530605261e-05 1.71921052444317e-05 3.22713377002339e-06 8.69440992028268e-06 -6.8594972312459e-06 5.30355484855188e-05 2540 2550 0 0 81 2464 2474 0 0 94 0 0 0 0 0 0 0 0 26 0 0 0 0 0 2463 +57 54 0.99730556863345 -0.059551791040754 0.0428390821160991 -0.0212202680155588 0.0592616077020372 0.998210323191276 0.00801327192462858 0.0451648650029003 -0.0432396186995371 -0.00545296783472654 0.999049848864666 0.355027250053941 3.30577914505805e-05 -1.06199194681624e-05 4.70035992404832e-06 1.51826684746542e-06 -4.92587055727341e-06 1.33269697985495e-05 -1.06199194681624e-05 4.36882954832715e-05 -5.00116525415671e-06 -2.32172288635903e-07 8.99892282128047e-07 1.46419313041269e-06 4.70035992404832e-06 -5.00116525415671e-06 1.55045670249615e-05 1.19907138303523e-06 1.51835323383871e-06 2.43399755755327e-06 1.51826684746542e-06 -2.32172288635903e-07 1.19907138303523e-06 4.72557199069318e-05 2.72868684843872e-06 9.23260872630205e-06 -4.92587055727341e-06 8.99892282128047e-07 1.51835323383871e-06 2.72868684843872e-06 2.79539572496587e-05 4.66268787715516e-06 1.33269697985495e-05 1.46419313041269e-06 2.43399755755327e-06 9.23260872630205e-06 4.66268787715516e-06 6.86394967305186e-05 2254 2260 0 0 126 2188 2194 0 0 134 0 0 0 0 0 48 30 0 34 0 0 0 0 0 2401 +57 3 0.992526387565684 -0.0776798222270113 0.0941127791779302 -0.0341291815263912 0.0762365830547703 0.9969117458305 0.01884023432225 0.048745819522853 -0.0952856410480983 -0.0115245930064403 0.995383258029835 0.430885788123444 5.70627907075006e-05 -1.35828064088014e-05 -1.25436568617595e-06 4.67455631889523e-06 -2.63152721396589e-06 2.23694065229652e-05 -1.35828064088014e-05 0.000144402138357556 2.42215620895791e-06 -2.60590471657042e-05 -9.66499863928515e-06 9.53524306809068e-05 -1.25436568617595e-06 2.42215620895791e-06 1.60798309877206e-05 -1.42481227470891e-06 1.06348921215022e-06 2.35444307374287e-06 4.67455631889523e-06 -2.60590471657042e-05 -1.42481227470891e-06 7.2299358837293e-05 1.50022306027123e-06 -1.30320596070852e-05 -2.63152721396589e-06 -9.66499863928515e-06 1.06348921215022e-06 1.50022306027123e-06 2.93136631151419e-05 -8.87533249722054e-06 2.23694065229652e-05 9.53524306809068e-05 2.35444307374287e-06 -1.30320596070852e-05 -8.87533249722054e-06 0.00015738144677751 2139 2141 0 0 125 2092 2094 0 0 132 0 0 0 0 0 42 42 0 19 0 0 0 0 0 2146 +56 18 0.996233955694967 -0.0469674910009209 0.0728831963448164 -0.0253493633745049 0.0456129415044549 0.998756135036105 0.020140563424411 0.0391999650173077 -0.0737384912218159 -0.0167402961986925 0.997137100601272 0.286119648869237 3.22974830002084e-05 -1.70211027793063e-06 1.93327868248226e-06 2.68963382575392e-06 4.46219137133089e-07 5.20096666107254e-06 -1.70211027793063e-06 3.18167302685382e-05 -1.04750122977287e-06 -7.53341283008414e-07 -4.60499736043797e-07 1.08469727358322e-05 1.93327868248226e-06 -1.04750122977287e-06 1.39745483341872e-05 -4.59830686896698e-07 -9.98697210956914e-07 7.48157375733583e-07 2.68963382575392e-06 -7.53341283008414e-07 -4.59830686896698e-07 7.43057197976935e-05 9.06538354896654e-06 2.38828731704179e-06 4.46219137133089e-07 -4.60499736043797e-07 -9.98697210956914e-07 9.06538354896654e-06 3.12669307253648e-05 4.28510196026282e-06 5.20096666107254e-06 1.08469727358322e-05 7.48157375733583e-07 2.38828731704179e-06 4.28510196026282e-06 4.55363688283257e-05 2666 2676 0 0 82 2590 2600 0 0 93 0 0 0 0 0 0 0 0 24 0 0 0 0 0 2417 +57 2 0.993616664388029 -0.0773681427145803 0.0820980800220278 -0.0296507339259736 0.0759565133400952 0.996906797999526 0.020185246680406 0.0498075916162091 -0.0834058291225672 -0.0138205135660452 0.996419821698238 0.423771648443234 5.29948823409951e-05 -2.15127043833297e-05 2.15228984092425e-06 8.02890771693449e-06 -9.52335980127974e-06 1.76136227040435e-05 -2.15127043833297e-05 7.00734791357084e-05 -3.0972568823826e-06 1.2930440534078e-06 3.28825640859545e-06 -4.41748636898394e-07 2.15228984092425e-06 -3.0972568823826e-06 1.53448195120755e-05 -3.37637497428263e-06 4.635923872533e-07 -4.01885675457193e-07 8.02890771693449e-06 1.2930440534078e-06 -3.37637497428263e-06 5.53931796842828e-05 7.91691811589819e-06 9.23701426227114e-06 -9.52335980127974e-06 3.28825640859545e-06 4.635923872533e-07 7.91691811589819e-06 3.03473166576715e-05 -2.11865563706189e-06 1.76136227040435e-05 -4.41748636898394e-07 -4.01885675457193e-07 9.23701426227114e-06 -2.11865563706189e-06 7.52258731626905e-05 2046 2049 0 0 130 1995 1998 0 0 138 0 0 0 0 0 39 39 0 21 0 0 0 0 0 2283 +57 53 0.996800601895544 -0.0678558202266483 0.0422391728381314 -0.0245569617104881 0.0670250692954783 0.997534787759304 0.0207843040763159 0.0564526989262664 -0.0435453803131525 -0.0178867233267923 0.998891317903011 0.412611684591925 5.89605160489322e-05 -1.23549146613963e-05 6.78048964243439e-06 3.03641375041614e-06 -1.11209465792579e-05 2.82877296889196e-05 -1.23549146613963e-05 7.78421300090578e-05 -1.61080421303334e-06 -6.22806133842119e-06 9.50636372130684e-06 4.5736439420254e-05 6.78048964243439e-06 -1.61080421303334e-06 1.67608392797393e-05 -8.29431238909385e-08 2.77321178952357e-07 1.27999294874138e-06 3.03641375041614e-06 -6.22806133842119e-06 -8.29431238909385e-08 4.78914462729414e-05 1.09112690169882e-06 5.38064163707962e-06 -1.11209465792579e-05 9.50636372130684e-06 2.77321178952357e-07 1.09112690169882e-06 3.20107399329821e-05 5.38556088987407e-06 2.82877296889196e-05 4.5736439420254e-05 1.27999294874138e-06 5.38064163707962e-06 5.38556088987407e-06 0.000143067081214125 2038 2041 0 0 118 1990 1993 0 0 128 0 0 0 0 0 37 35 0 12 0 0 0 0 0 2152 +57 4 0.99387715724543 -0.0774157917148194 0.078835217377199 -0.0320957719556838 0.0761189314488218 0.996911376675696 0.0193291316322991 0.051120832044228 -0.0800881051145056 -0.0132099298914442 0.996700252418665 0.428856888100571 7.86520456345387e-05 -5.98881963580226e-06 1.30917200808517e-06 -3.09490435825628e-06 -6.81911804062909e-06 5.47528564816833e-05 -5.98881963580226e-06 0.000137061777046647 -9.64248634553314e-07 -1.21467419380755e-05 -2.81054610925866e-07 0.000110979367819182 1.30917200808517e-06 -9.64248634553314e-07 1.50744067544919e-05 -7.64665326834654e-07 7.09948231269678e-07 2.14605028985733e-06 -3.09490435825628e-06 -1.21467419380755e-05 -7.64665326834654e-07 5.79095948739263e-05 1.5415422691549e-06 -1.27944899821964e-05 -6.81911804062909e-06 -2.81054610925866e-07 7.09948231269678e-07 1.5415422691549e-06 2.97081623405055e-05 -1.49388152646467e-05 5.47528564816833e-05 0.000110979367819182 2.14605028985733e-06 -1.27944899821964e-05 -1.49388152646467e-05 0.000256254041649844 2026 2030 0 0 148 1973 1977 0 0 157 0 0 0 0 0 41 41 0 27 0 0 0 0 0 2170 +57 55 0.998322959189188 -0.0493628455992242 0.0302420010926886 -0.0135714424777045 0.0497597431601365 0.998682807948561 -0.0125146741314164 0.0294728896153068 -0.029584406642356 0.0139985207191847 0.999464258641245 0.298510021146611 4.44446553548521e-05 -2.2953772972495e-06 5.03374710197604e-06 1.72612578239909e-06 -6.08180217092163e-06 2.96213672541027e-05 -2.2953772972495e-06 5.78362688779878e-05 -4.29953292225984e-06 9.22243794315456e-06 -8.93590651621138e-07 4.4573819474817e-05 5.03374710197604e-06 -4.29953292225984e-06 1.52064393147711e-05 7.28053789172948e-07 -6.27218441621556e-07 -6.90399445629844e-06 1.72612578239909e-06 9.22243794315456e-06 7.28053789172948e-07 4.08858085316655e-05 7.62661264253195e-09 1.66985367466975e-05 -6.08180217092163e-06 -8.93590651621138e-07 -6.27218441621556e-07 7.62661264253195e-09 3.12544730234032e-05 3.34166445640728e-06 2.96213672541027e-05 4.4573819474817e-05 -6.90399445629844e-06 1.66985367466975e-05 3.34166445640728e-06 0.000152595772888987 2707 2714 0 0 102 2634 2641 0 0 111 0 0 0 0 0 71 14 0 25 0 0 0 0 0 2745 +57 1 0.993904195656074 -0.0775215571241936 0.0783891449008855 -0.0337450964780027 0.0756599410294798 0.996782800410357 0.0264503710654791 0.0530899860573068 -0.0801874253275865 -0.0203582166980874 0.996571883926196 0.425110906173921 5.02300308562721e-05 -6.6404652527569e-06 3.61444990270797e-06 4.8892884357967e-06 -8.40534110882449e-06 1.4335672272538e-05 -6.6404652527569e-06 5.21070201782802e-05 -4.95966799604585e-06 -4.62677028164499e-06 4.31836647131332e-06 1.67017827783902e-05 3.61444990270797e-06 -4.95966799604585e-06 1.61125718403703e-05 4.80618951507323e-07 -6.16186400173799e-08 -4.30101410866237e-06 4.8892884357967e-06 -4.62677028164499e-06 4.80618951507323e-07 5.56769796744304e-05 3.80859057498553e-07 7.14773527690854e-06 -8.40534110882449e-06 4.31836647131332e-06 -6.16186400173799e-08 3.80859057498553e-07 3.3427102903735e-05 1.27540592073511e-06 1.4335672272538e-05 1.67017827783902e-05 -4.30101410866237e-06 7.14773527690854e-06 1.27540592073511e-06 9.34902292845535e-05 2086 2090 0 0 148 2037 2041 0 0 152 0 0 0 0 0 40 40 0 18 0 0 0 0 0 2296 +57 29 0.992610385684337 -0.0786951973664486 0.0923671377874594 -0.022641275326129 0.0775015782995363 0.996856597173857 0.0164447569772115 0.0470949329711432 -0.0933709140614605 -0.00916463760409621 0.995589213393211 0.451582111637704 3.1829309265156e-05 -8.12851860793152e-06 3.88064835926316e-06 2.59027642695403e-06 -2.01574519255705e-06 4.46318623415592e-07 -8.12851860793152e-06 3.39189193819366e-05 -3.86838383481598e-06 -3.32768747275653e-06 -2.14197846174482e-06 1.32098254080012e-05 3.88064835926316e-06 -3.86838383481598e-06 1.66746453285141e-05 -2.26193118080849e-06 -3.9441407993142e-06 2.2560388916655e-08 2.59027642695403e-06 -3.32768747275653e-06 -2.26193118080849e-06 6.05189212338582e-05 2.77781212132579e-06 6.76772735985236e-07 -2.01574519255705e-06 -2.14197846174482e-06 -3.9441407993142e-06 2.77781212132579e-06 4.23169575270708e-05 -7.90371001635289e-06 4.46318623415592e-07 1.32098254080012e-05 2.2560388916655e-08 6.76772735985236e-07 -7.90371001635289e-06 5.64814494917459e-05 2306 2309 0 0 153 2257 2260 0 0 162 0 0 0 0 0 36 35 0 20 0 0 0 0 0 2208 +57 28 0.993261611820429 -0.0787776912026137 0.085002622622303 -0.0325875511418009 0.077178945864724 0.996775862125247 0.0219383454180052 0.049997435273205 -0.0864568146480891 -0.0152301035208348 0.996139178602895 0.436390063519036 8.05812243264358e-05 -6.7084840813772e-06 -1.8250045479237e-07 -1.75654233898645e-07 -2.98822054696157e-06 5.03107330928343e-05 -6.7084840813772e-06 9.82017650515031e-05 -4.25587029865396e-06 -2.03037905520318e-06 4.12278263306646e-06 9.1096695203058e-05 -1.8250045479237e-07 -4.25587029865396e-06 1.59770125578427e-05 -9.11829486807201e-07 1.75602855341628e-07 -7.7877585708914e-06 -1.75654233898645e-07 -2.03037905520318e-06 -9.11829486807201e-07 7.067415541755e-05 3.56347035778665e-06 -6.12339664937144e-06 -2.98822054696157e-06 4.12278263306646e-06 1.75602855341628e-07 3.56347035778665e-06 3.40503863323131e-05 3.37737200643399e-06 5.03107330928343e-05 9.1096695203058e-05 -7.7877585708914e-06 -6.12339664937144e-06 3.37737200643399e-06 0.000247179012750311 2052 2059 0 0 144 2001 2008 0 0 152 0 0 0 0 0 27 27 0 20 0 0 0 0 0 2166 +57 5 0.993406016541148 -0.0781376751647541 0.0838986890225068 -0.0331476743276645 0.0763991824459463 0.996794636448941 0.0237406332732354 0.052509517697948 -0.085484801113642 -0.0171742966805228 0.996191443605139 0.430839613712716 5.69646525069246e-05 -1.22977113351252e-05 9.85625279237661e-07 4.68658127454431e-06 -1.02831139542812e-05 4.03281169482469e-05 -1.22977113351252e-05 3.79880482187084e-05 -2.64983384065019e-06 1.75031142824381e-06 2.08665156774179e-06 1.37802339464178e-06 9.85625279237661e-07 -2.64983384065019e-06 1.57652273889612e-05 -7.18367839352432e-06 2.44801300607763e-06 -1.30145853826834e-06 4.68658127454431e-06 1.75031142824381e-06 -7.18367839352432e-06 7.95279101118977e-05 9.03191465177818e-06 8.49874381543056e-06 -1.02831139542812e-05 2.08665156774179e-06 2.44801300607763e-06 9.03191465177818e-06 3.27808964685529e-05 -6.35836972884528e-06 4.03281169482469e-05 1.37802339464178e-06 -1.30145853826834e-06 8.49874381543056e-06 -6.35836972884528e-06 9.73993592812471e-05 2042 2043 0 0 128 1992 1993 0 0 132 0 0 0 0 0 35 35 0 19 0 0 0 0 0 2200 +57 6 0.993409599437667 -0.0780720754432241 0.083917333019361 -0.0306069660869589 0.0764859900859497 0.996828861472414 0.0219571003591796 0.0510894959758476 -0.0853654559272474 -0.015393893971267 0.996230779971556 0.431946471400722 5.04943864328625e-05 -1.96627667160862e-05 -7.93960328468257e-08 2.12032075018772e-06 -9.07430923564488e-06 3.33255217592462e-06 -1.96627667160862e-05 5.36235118136348e-05 -2.0055214961627e-06 -7.46961680070892e-06 -1.06963663923519e-06 7.44655768298939e-06 -7.93960328468257e-08 -2.0055214961627e-06 1.5796344012072e-05 -1.85333708279827e-06 3.12402074895765e-07 1.31099965304493e-06 2.12032075018772e-06 -7.46961680070892e-06 -1.85333708279827e-06 6.47543158017186e-05 2.59308032975357e-06 1.32493459190135e-05 -9.07430923564488e-06 -1.06963663923519e-06 3.12402074895765e-07 2.59308032975357e-06 3.32599945992292e-05 1.08331024806438e-06 3.33255217592462e-06 7.44655768298939e-06 1.31099965304493e-06 1.32493459190135e-05 1.08331024806438e-06 7.18155724276729e-05 2087 2091 0 0 149 2035 2039 0 0 155 0 0 0 0 0 33 33 0 25 0 0 0 0 0 2133 +57 30 0.99341132619027 -0.0779028716790859 0.0840540277502508 -0.0346445014665967 0.0760838171301959 0.996797010375897 0.0246368195303748 0.0543930903403364 -0.0857040825619582 -0.0180793442863735 0.996156587862766 0.428913094775202 5.37472315529585e-05 -9.2382306677324e-06 3.05237727540723e-06 1.94006687059646e-06 -5.3310022403639e-06 8.89004707771066e-06 -9.2382306677324e-06 6.0584968973681e-05 6.87293414671402e-07 -9.02235051663628e-06 -6.98001100663738e-07 4.17622020157942e-05 3.05237727540723e-06 6.87293414671402e-07 1.58227708758813e-05 -2.23434420171978e-06 8.14163638077544e-07 6.08480036231334e-06 1.94006687059646e-06 -9.02235051663628e-06 -2.23434420171978e-06 6.15278295660684e-05 4.20622230981504e-07 -3.04917308266355e-06 -5.3310022403639e-06 -6.98001100663738e-07 8.14163638077544e-07 4.20622230981504e-07 3.69517527466235e-05 -6.96743087027521e-06 8.89004707771066e-06 4.17622020157942e-05 6.08480036231334e-06 -3.04917308266355e-06 -6.96743087027521e-06 0.000148055064281108 2404 2407 0 0 145 2342 2345 0 0 153 0 0 0 0 0 40 39 0 17 0 0 0 0 0 2115 +57 26 0.993238901620485 -0.0782014750748241 0.0857963495951583 -0.0306835938869918 0.0770141099252249 0.996883898234174 0.0170681080926338 0.0493985510712116 -0.0868637506682639 -0.0103451794357628 0.996166485122986 0.445719253437791 7.24645460045581e-05 -5.08564473107987e-06 2.91121791866175e-06 -3.86689617393324e-06 -1.41018905928733e-05 6.20654469522005e-05 -5.08564473107987e-06 0.000125956677510637 -3.51255846461295e-06 -1.0673007009868e-05 -1.76678256366034e-06 0.000106487462056694 2.91121791866175e-06 -3.51255846461295e-06 1.77191483046646e-05 1.06416920057725e-06 2.3540780026033e-06 -3.15280000456311e-06 -3.86689617393324e-06 -1.0673007009868e-05 1.06416920057725e-06 5.52039205615355e-05 -4.94393934381048e-06 -9.76320828487711e-06 -1.41018905928733e-05 -1.76678256366034e-06 2.3540780026033e-06 -4.94393934381048e-06 2.97826191071292e-05 -1.38004558201253e-05 6.20654469522005e-05 0.000106487462056694 -3.15280000456311e-06 -9.76320828487711e-06 -1.38004558201253e-05 0.000242111186995449 2031 2038 0 0 149 1979 1986 0 0 159 0 0 0 0 0 30 30 0 16 0 0 0 0 0 2428 +57 25 0.992628774581624 -0.0782789496456755 0.0925230885506557 -0.0283167570489509 0.0769947832516407 0.996880107948137 0.0173739382220661 0.0480902632969864 -0.0935944401373049 -0.0101220758582962 0.995558950718491 0.444784919515901 3.80878722055224e-05 -8.66400529988193e-06 4.10863073420164e-06 3.91404454709697e-06 -5.87481283988687e-06 1.0846083542329e-07 -8.66400529988193e-06 4.91300777447569e-05 -7.85835489691239e-07 1.94935729006449e-06 6.06100732356373e-09 2.09711089591713e-05 4.10863073420164e-06 -7.85835489691239e-07 1.53759829645286e-05 1.52544131235944e-06 2.68199399573125e-06 2.78777568257937e-07 3.91404454709697e-06 1.94935729006449e-06 1.52544131235944e-06 5.4339698959872e-05 -3.38845937828867e-06 1.66783622673289e-05 -5.87481283988687e-06 6.06100732356373e-09 2.68199399573125e-06 -3.38845937828867e-06 3.18259220182627e-05 -3.72579495598396e-07 1.0846083542329e-07 2.09711089591713e-05 2.78777568257937e-07 1.66783622673289e-05 -3.72579495598396e-07 9.47663722272112e-05 2326 2329 0 0 130 2273 2276 0 0 136 0 0 0 0 0 34 31 0 29 0 0 0 0 0 2142 +57 7 0.992801994201566 -0.0778152495190092 0.0910438754210726 -0.0258577871550944 0.0764406841085664 0.996902600846035 0.0184939514281373 0.0542205281691616 -0.0922009876433425 -0.0114013757374398 0.995675141051983 0.448773493871265 3.97155071554019e-05 -9.27692864828972e-06 3.74795628537844e-06 -3.43347752304669e-06 -1.44248593601992e-06 1.69306330703399e-05 -9.27692864828972e-06 6.17401832316822e-05 8.98839903435936e-07 -4.09684603748714e-06 4.03747211568743e-07 3.77824529115523e-05 3.74795628537844e-06 8.98839903435936e-07 1.86833464282364e-05 -7.01571072386353e-06 1.50849565610709e-06 1.91232323633188e-06 -3.43347752304669e-06 -4.09684603748714e-06 -7.01571072386353e-06 7.82764398149775e-05 1.74559180602797e-05 7.2240937903539e-06 -1.44248593601992e-06 4.03747211568743e-07 1.50849565610709e-06 1.74559180602797e-05 3.59088088304271e-05 -5.06982830133444e-07 1.69306330703399e-05 3.77824529115523e-05 1.91232323633188e-06 7.2240937903539e-06 -5.06982830133444e-07 0.000117506265958305 2192 2194 0 0 132 2140 2142 0 0 140 0 0 0 0 0 42 42 0 15 0 0 0 0 0 2199 +57 23 0.993990045503923 -0.0782244579588282 0.0765814835071548 -0.0301480985898214 0.0763593805986074 0.996714965192374 0.0269911681140457 0.0530219177683164 -0.078441280163611 -0.0209812377759555 0.996697924763407 0.41602658552635 6.55412355776997e-05 -1.28345671153469e-06 4.14476595442562e-07 8.83519218254288e-07 -2.50558515267218e-06 2.59923190478089e-05 -1.28345671153469e-06 5.79188438281735e-05 2.56036977591194e-06 -8.57412252658056e-06 -9.32638851853034e-07 4.72722135799778e-05 4.14476595442562e-07 2.56036977591194e-06 1.74988691122911e-05 -5.40584534012148e-06 1.1790875315635e-06 2.91155377382375e-06 8.83519218254288e-07 -8.57412252658056e-06 -5.40584534012148e-06 7.68992262756517e-05 1.10233631904503e-05 -2.31430157620581e-06 -2.50558515267218e-06 -9.32638851853034e-07 1.1790875315635e-06 1.10233631904503e-05 3.3118636937388e-05 -4.76401072361577e-06 2.59923190478089e-05 4.72722135799778e-05 2.91155377382375e-06 -2.31430157620581e-06 -4.76401072361577e-06 0.00016008504304549 2168 2170 0 0 137 2112 2114 0 0 146 0 0 0 0 0 39 39 0 18 0 0 0 0 0 2157 +57 31 0.992320823484577 -0.0784321305044693 0.0956440493884538 -0.0304100689875847 0.0765403158500048 0.996794293344972 0.0232962830614501 0.0529547941798791 -0.0971646197361602 -0.0157967610423022 0.995142954058411 0.441971097817284 6.04704033494457e-05 -1.45052227563989e-05 6.04725881645334e-06 -5.15125113365207e-06 -8.73963454631111e-06 3.87289599548201e-05 -1.45052227563989e-05 0.000125785707114243 -5.32600660345981e-06 -3.94525218370539e-06 4.82784455111508e-06 3.88665284611462e-05 6.04725881645334e-06 -5.32600660345981e-06 1.47134099327421e-05 1.12995230250549e-06 1.57956863066361e-06 1.26694453826799e-06 -5.15125113365207e-06 -3.94525218370539e-06 1.12995230250549e-06 5.22587417535763e-05 8.53197948608199e-06 6.61589952743976e-07 -8.73963454631111e-06 4.82784455111508e-06 1.57956863066361e-06 8.53197948608199e-06 3.12550668224104e-05 -4.83665305336424e-06 3.87289599548201e-05 3.88665284611462e-05 1.26694453826799e-06 6.61589952743976e-07 -4.83665305336424e-06 0.000159182173442164 2215 2218 0 0 131 2174 2177 0 0 136 0 0 0 0 0 41 41 0 26 0 0 0 0 0 2229 +57 19 0.991793606606427 -0.0782020370010506 0.101142885580259 -0.0256307584226036 0.0769329893886304 0.996901484742867 0.0163934395779569 0.0495962460587271 -0.102111493174588 -0.00847768402062494 0.994736835467202 0.464100029711521 4.62334876622154e-05 -9.73425273786789e-07 3.57147456442156e-06 -5.62696300208696e-07 -4.03677594410723e-06 2.9193246742642e-05 -9.73425273786789e-07 0.00013215760090291 1.81677921742915e-06 -3.8065834841981e-05 -7.36479982860309e-06 9.29210444999961e-05 3.57147456442156e-06 1.81677921742915e-06 1.73503333279484e-05 -6.59351617688615e-06 1.07080544420653e-06 2.4711967863622e-06 -5.62696300208696e-07 -3.8065834841981e-05 -6.59351617688615e-06 0.000103985803553767 1.22673279726432e-05 -2.21006679395464e-05 -4.03677594410723e-06 -7.36479982860309e-06 1.07080544420653e-06 1.22673279726432e-05 3.06637635717897e-05 -9.04546947723352e-06 2.9193246742642e-05 9.29210444999961e-05 2.4711967863622e-06 -2.21006679395464e-05 -9.04546947723352e-06 0.00017397664491686 2329 2336 0 0 153 2275 2282 0 0 157 0 0 0 0 0 39 39 0 23 0 0 0 0 0 2194 +57 27 0.99120771826595 -0.0778144464867302 0.107014817515956 -0.0204340140685196 0.0766524493953187 0.996946005446939 0.0149353347833531 0.0495874758673966 -0.107850179655426 -0.00660107122795439 0.994145243214962 0.46213582081507 4.74783187399003e-05 -1.51561894561159e-05 4.62690332453897e-06 -6.64469977162855e-07 -7.00092633076728e-06 1.31469203586564e-05 -1.51561894561159e-05 5.53153305786526e-05 -1.61592223866696e-06 4.15165421820193e-06 -6.23195139427706e-07 2.71329762380211e-05 4.62690332453897e-06 -1.61592223866696e-06 1.48417473207981e-05 5.03844332996718e-07 8.73659477536201e-07 2.03777255985993e-06 -6.64469977162855e-07 4.15165421820193e-06 5.03844332996718e-07 6.0389238473851e-05 -5.07137696962134e-07 1.56124142050238e-05 -7.00092633076728e-06 -6.23195139427706e-07 8.73659477536201e-07 -5.07137696962134e-07 3.11448871829441e-05 -9.73650290379926e-06 1.31469203586564e-05 2.71329762380211e-05 2.03777255985993e-06 1.56124142050238e-05 -9.73650290379926e-06 0.000109251199531676 2194 2197 0 0 132 2142 2145 0 0 141 0 0 0 0 0 34 34 0 19 0 0 0 0 0 2369 +57 20 0.992881196596972 -0.0780982297690599 0.0899310622149233 -0.0300236374876369 0.0762960452808118 0.996812672375019 0.0233111489867159 0.0549234702000554 -0.0914649819257272 -0.0162838171050795 0.995675145005546 0.44077750282689 5.38863006983307e-05 -8.36923278821202e-06 8.87679385600032e-06 9.30702866531609e-06 -2.56400937970493e-06 2.47793894374993e-05 -8.36923278821202e-06 4.29352817321629e-05 -3.9435220550546e-06 -2.3425997049874e-06 4.48287677573369e-06 9.26702171034061e-06 8.87679385600032e-06 -3.9435220550546e-06 1.58683595498215e-05 4.70055421675473e-08 5.40688462760595e-07 1.11007126478721e-06 9.30702866531609e-06 -2.3425997049874e-06 4.70055421675473e-08 6.05515865379805e-05 6.87113409272997e-06 7.90054274003446e-06 -2.56400937970493e-06 4.48287677573369e-06 5.40688462760595e-07 6.87113409272997e-06 2.94511548760405e-05 3.91115125837796e-06 2.47793894374993e-05 9.26702171034061e-06 1.11007126478721e-06 7.90054274003446e-06 3.91115125837796e-06 8.15239451814295e-05 2264 2268 0 0 150 2209 2213 0 0 160 0 0 0 0 0 30 28 0 17 0 0 0 0 0 2270 +57 24 0.993127711504601 -0.0783337830245593 0.0869549715582426 -0.0277457037741143 0.0767687106098844 0.996823426827365 0.0212042637091075 0.0523365888775202 -0.0883397629209482 -0.0143831208439205 0.995986552179225 0.448278067801114 5.55818776065874e-05 -1.41475451809182e-05 3.16245504490182e-06 -9.37900443851085e-07 -1.13100737194453e-05 2.39680990653831e-05 -1.41475451809182e-05 8.87985090381521e-05 2.38021056189946e-06 -1.13728314637196e-05 3.04363181612989e-06 1.97744796269398e-05 3.16245504490182e-06 2.38021056189946e-06 1.59238735669504e-05 -4.50451297532305e-06 4.2069008301295e-06 -1.06974310880737e-06 -9.37900443851085e-07 -1.13728314637196e-05 -4.50451297532305e-06 5.9496827740615e-05 7.27180621459502e-06 -8.45503039489507e-07 -1.13100737194453e-05 3.04363181612989e-06 4.2069008301295e-06 7.27180621459502e-06 3.08291731664723e-05 -6.00645994480236e-06 2.39680990653831e-05 1.97744796269398e-05 -1.06974310880737e-06 -8.45503039489507e-07 -6.00645994480236e-06 0.000116253616283515 2226 2229 0 0 133 2173 2176 0 0 138 0 0 0 0 0 30 30 0 19 0 0 0 0 0 2227 +57 8 0.993334320246663 -0.0780339736301777 0.0848388306118359 -0.0327748373061918 0.0764306989448614 0.99683239011714 0.0219894127286142 0.0511753321552797 -0.0862860155465474 -0.015358547224074 0.996152015782866 0.443286218138094 5.12682236653193e-05 -1.26226011010194e-05 2.18357759439493e-06 -6.41506022471017e-06 -6.73516995239166e-06 2.18570569961883e-05 -1.26226011010194e-05 5.29809796759109e-05 2.21419437296471e-07 -1.30169258845234e-05 5.68155105965038e-06 1.9108142648669e-05 2.18357759439493e-06 2.21419437296471e-07 1.52364497090037e-05 -3.41790572907726e-06 6.21672375006003e-07 1.54917671135325e-06 -6.41506022471017e-06 -1.30169258845234e-05 -3.41790572907726e-06 9.57899279924524e-05 3.67675166550535e-06 -5.7518648400328e-06 -6.73516995239166e-06 5.68155105965038e-06 6.21672375006003e-07 3.67675166550535e-06 3.697639717105e-05 -4.41841052449178e-06 2.18570569961883e-05 1.9108142648669e-05 1.54917671135325e-06 -5.7518648400328e-06 -4.41841052449178e-06 0.000113597700327399 2219 2226 0 0 147 2168 2175 0 0 154 0 0 0 0 0 26 26 0 25 0 0 0 0 0 2139 +57 22 0.991266960292954 -0.0783665146951976 0.106058959103387 -0.0301941477459603 0.0767209976612528 0.996861631232605 0.0195135003044696 0.0524918764807027 -0.107255311986999 -0.0112061389781614 0.994168356215271 0.464569172911138 4.79199783771387e-05 -1.68239455246094e-05 3.21874230048371e-06 3.31573592212553e-06 -4.87997683949607e-06 1.47470402071369e-06 -1.68239455246094e-05 5.57621868347693e-05 -2.61705136589249e-06 4.33189434936382e-06 8.80577691955208e-07 1.37292272265523e-05 3.21874230048371e-06 -2.61705136589249e-06 1.61903254792517e-05 1.01332388049664e-07 2.87738306958088e-06 2.09662609133095e-06 3.31573592212553e-06 4.33189434936382e-06 1.01332388049664e-07 5.77238585703077e-05 3.27580423917759e-06 6.13906682454073e-06 -4.87997683949607e-06 8.80577691955208e-07 2.87738306958088e-06 3.27580423917759e-06 3.24839164421888e-05 -1.10928572910547e-05 1.47470402071369e-06 1.37292272265523e-05 2.09662609133095e-06 6.13906682454073e-06 -1.10928572910547e-05 8.40716001408659e-05 2187 2190 0 0 128 2135 2138 0 0 135 0 0 0 0 0 49 49 0 22 0 0 0 0 0 2164 +57 21 0.992639626984205 -0.0783712233056744 0.0923283396267331 -0.0280762681097152 0.0766472095024588 0.996813799447505 0.0220783719172072 0.0515731580694521 -0.0937644720357527 -0.0148391572739307 0.995483813627955 0.446391125721234 8.47729418053711e-05 6.45348219825601e-05 5.37080511106092e-06 -4.98819102191111e-06 -2.59691580991356e-06 0.000132134360709894 6.45348219825601e-05 0.000335448248733439 -8.27839385611789e-06 -3.47396381151502e-05 -7.10010871106781e-06 0.000344664563036453 5.37080511106092e-06 -8.27839385611789e-06 1.60366323656884e-05 -9.11742493565031e-07 1.49700303745733e-06 -4.38786722936976e-06 -4.98819102191111e-06 -3.47396381151502e-05 -9.11742493565031e-07 5.8727522670801e-05 1.037440099624e-05 -2.59270702691767e-05 -2.59691580991356e-06 -7.10010871106781e-06 1.49700303745733e-06 1.037440099624e-05 2.61966361633518e-05 -2.47795718190181e-06 0.000132134360709894 0.000344664563036453 -4.38786722936976e-06 -2.59270702691767e-05 -2.47795718190181e-06 0.000504120844695064 2088 2092 0 0 151 2037 2041 0 0 161 0 0 0 0 0 39 39 0 21 0 0 0 0 0 2251 +58 56 0.997379625761673 -0.0702538951129471 -0.0172705627286148 -0.0408593476272634 0.0705606743864306 0.997347840907274 0.017845880973811 0.0228202917402355 0.0159710157985054 -0.0190177406402112 0.999691578535753 0.289438157079801 3.25036861018557e-05 -9.07523026408518e-06 3.32725568594042e-06 -2.9932443453881e-06 8.58327106603519e-07 9.79504766175678e-06 -9.07523026408518e-06 3.07795076220176e-05 -3.58993500447438e-06 -4.88600497451315e-07 1.89297623228333e-06 -9.26296500912539e-06 3.32725568594042e-06 -3.58993500447438e-06 1.66448578529205e-05 -1.25842115750727e-07 -1.75967998092813e-06 2.30490368283303e-06 -2.9932443453881e-06 -4.88600497451315e-07 -1.25842115750727e-07 5.22284443148375e-05 1.692777360457e-06 1.05166378439419e-05 8.58327106603519e-07 1.89297623228333e-06 -1.75967998092813e-06 1.692777360457e-06 2.83915144370919e-05 -5.83449272559934e-06 9.79504766175678e-06 -9.26296500912539e-06 2.30490368283303e-06 1.05166378439419e-05 -5.83449272559934e-06 7.40028334067502e-05 2554 2565 0 0 107 2493 2504 0 0 132 0 0 0 0 0 239 129 0 46 0 0 0 0 0 2850 +57 9 0.993052676400159 -0.0775461017728236 0.0885041467634124 -0.0223748650905362 0.0757814764124101 0.996856089826948 0.0231323152253294 0.0544453732171518 -0.09001971854675 -0.0162646326354935 0.995807166070819 0.446148581664966 4.00266001635837e-05 -3.79962675130608e-06 4.42460048310383e-06 4.80822367901849e-07 -5.77522682381423e-06 5.53426113800897e-06 -3.79962675130608e-06 4.06569777796971e-05 -8.14864294501854e-07 1.44422454447086e-06 -2.23424518941228e-06 1.32920959556573e-05 4.42460048310383e-06 -8.14864294501854e-07 1.58972653268916e-05 -5.1915725949932e-06 1.52472482877019e-06 1.45096347615002e-06 4.80822367901849e-07 1.44422454447086e-06 -5.1915725949932e-06 6.6505284429031e-05 1.05545962516388e-05 -5.12493308736299e-06 -5.77522682381423e-06 -2.23424518941228e-06 1.52472482877019e-06 1.05545962516388e-05 3.48899741958947e-05 -7.88775436424667e-06 5.53426113800897e-06 1.32920959556573e-05 1.45096347615002e-06 -5.12493308736299e-06 -7.88775436424667e-06 7.37721234967773e-05 2226 2228 0 0 137 2168 2170 0 0 144 0 0 0 0 0 29 28 0 19 0 0 0 0 0 2145 +58 2 0.991032299896923 -0.116465768788748 0.0655034751861481 -0.0607893876528172 0.113591882521627 0.992461071080894 0.0460207194006879 0.0636677481164595 -0.0703694876079776 -0.0381673563324714 0.996790543757504 0.571350781568308 0.000147512113614643 -1.48431603262994e-05 3.8878089296426e-06 9.59317457351111e-06 -1.52040106063038e-06 8.57811664852386e-05 -1.48431603262994e-05 8.61461169040596e-05 -8.32406666188126e-06 -1.13741463275111e-05 3.78368524789198e-06 8.39213406103416e-05 3.8878089296426e-06 -8.32406666188126e-06 1.5697335802706e-05 2.16627451038738e-06 1.48386698052303e-06 -3.87176385904052e-06 9.59317457351111e-06 -1.13741463275111e-05 2.16627451038738e-06 4.72815568050772e-05 4.34501143699801e-06 5.03621499443134e-06 -1.52040106063038e-06 3.78368524789198e-06 1.48386698052303e-06 4.34501143699801e-06 2.85281496214517e-05 7.96612002845594e-07 8.57811664852386e-05 8.39213406103416e-05 -3.87176385904052e-06 5.03621499443134e-06 7.96612002845594e-07 0.00036402231981021 1798 1801 0 0 180 1769 1772 0 0 201 0 0 0 0 0 149 149 0 20 0 0 0 0 0 1905 +58 3 0.991935227178561 -0.115034413961002 0.0532126741187231 -0.0675164482362625 0.113265167658537 0.992942552261468 0.0351580674065858 0.0588717319830426 -0.0568815161322207 -0.0288473831244946 0.997964088336533 0.564216382268796 5.84701771338866e-05 -1.22997678233669e-05 -2.00605669702101e-06 -3.59628093434096e-06 -2.76377631258409e-06 1.49178562377897e-05 -1.22997678233669e-05 5.27711894036454e-05 -3.55464756330926e-06 -7.70000132713984e-06 -7.56128383339273e-06 2.03316068365185e-05 -2.00605669702101e-06 -3.55464756330926e-06 1.62573004806389e-05 1.52151596291714e-06 3.68593306613013e-06 1.36696483519393e-06 -3.59628093434096e-06 -7.70000132713984e-06 1.52151596291714e-06 7.37684166032138e-05 5.68093434254889e-06 -2.93793690302755e-06 -2.76377631258409e-06 -7.56128383339273e-06 3.68593306613013e-06 5.68093434254889e-06 3.01199325842481e-05 -4.16710189245705e-06 1.49178562377897e-05 2.03316068365185e-05 1.36696483519393e-06 -2.93793690302755e-06 -4.16710189245705e-06 0.000146975070767316 1870 1872 0 0 175 1839 1841 0 0 192 0 0 0 0 0 175 175 0 19 0 0 0 0 0 2000 +58 6 0.990742684557059 -0.116450095270107 0.0697732635631699 -0.0579327920462005 0.114140946223285 0.992803774179632 0.0362285849838567 0.0628448716122214 -0.0734899815752165 -0.0279292192204228 0.99690480053103 0.596004310063896 8.88722137291118e-05 -1.02981745742034e-05 3.4161292714716e-06 -8.26284616043355e-06 7.313669812901e-06 9.97933553714888e-05 -1.02981745742034e-05 0.000242082786790142 -6.50774568581794e-06 -2.8629420199756e-05 1.52302467580027e-05 0.000233189426583739 3.4161292714716e-06 -6.50774568581794e-06 1.62463251795943e-05 1.34331224212506e-06 -8.57147167752576e-07 -1.41336073791091e-05 -8.26284616043355e-06 -2.8629420199756e-05 1.34331224212506e-06 5.84482562113433e-05 1.9523775759194e-06 -4.05794753532164e-05 7.313669812901e-06 1.52302467580027e-05 -8.57147167752576e-07 1.9523775759194e-06 2.97486312010327e-05 3.49158852380376e-05 9.97933553714888e-05 0.000233189426583739 -1.41336073791091e-05 -4.05794753532164e-05 3.49158852380376e-05 0.000547093983606887 1804 1808 0 0 198 1777 1781 0 0 213 0 0 0 0 0 151 151 0 25 0 0 0 0 0 1973 +58 54 0.994673678201479 -0.0989626307647945 0.028821374104145 -0.0551317330326555 0.0983397467981515 0.994903340803486 0.0222853462557167 0.054523525454035 -0.030879897875731 -0.0193323606983909 0.999336125503832 0.522060509200109 5.38074789807498e-05 -1.86843590819764e-05 7.83401122360533e-06 -4.78209616956459e-06 -9.79593361240387e-06 -4.53436042196009e-07 -1.86843590819764e-05 6.51738673359012e-05 -5.69589943491251e-06 -3.6939710414428e-06 1.8320634573125e-06 3.134236431918e-05 7.83401122360533e-06 -5.69589943491251e-06 1.86423828982957e-05 1.95658954257418e-06 1.82219177028351e-06 -5.17693742056007e-06 -4.78209616956459e-06 -3.6939710414428e-06 1.95658954257418e-06 4.81537764342987e-05 4.48443974089915e-06 1.15202403790356e-05 -9.79593361240387e-06 1.8320634573125e-06 1.82219177028351e-06 4.48443974089915e-06 3.19433230188692e-05 3.83072084835935e-06 -4.53436042196009e-07 3.134236431918e-05 -5.17693742056007e-06 1.15202403790356e-05 3.83072084835935e-06 0.000164441325414405 1918 1924 0 0 170 1882 1888 0 0 192 0 0 0 0 0 203 185 0 31 0 0 0 0 0 2025 +58 4 0.991525738005351 -0.115909163829768 0.0586666567415195 -0.064701456361509 0.113976385035558 0.992856315391988 0.0352947678908796 0.0606131548418565 -0.0623385476825492 -0.0283090573232116 0.997653498338126 0.575282141450918 5.82802624056261e-05 -1.7405914680716e-05 6.81358098889834e-06 -1.35336367994682e-05 -1.41808023172696e-06 3.51035503534068e-05 -1.7405914680716e-05 6.87528966445061e-05 -6.34894415415129e-06 2.92681667534179e-06 -2.5193344602919e-06 4.13300864317272e-05 6.81358098889834e-06 -6.34894415415129e-06 1.87488325072255e-05 -2.92114036627648e-06 -9.2307859575009e-07 -1.0305300032204e-07 -1.35336367994682e-05 2.92681667534179e-06 -2.92114036627648e-06 6.61311864686039e-05 6.58873791814224e-06 -1.08100314864511e-05 -1.41808023172696e-06 -2.5193344602919e-06 -9.2307859575009e-07 6.58873791814224e-06 2.77022530823053e-05 -1.45574387940337e-06 3.51035503534068e-05 4.13300864317272e-05 -1.0305300032204e-07 -1.08100314864511e-05 -1.45574387940337e-06 0.000186873615418406 1834 1838 0 0 191 1806 1810 0 0 213 0 0 0 0 0 152 152 0 26 0 0 0 0 0 2010 +58 55 0.996100709389604 -0.0881957314766921 0.00221126724268709 -0.0460726243041253 0.0881774407815123 0.996077835255197 0.00732700829419892 0.041599623804654 -0.00284880514430915 -0.00710345427321092 0.999970712194431 0.444385820680117 7.90346665187416e-05 -3.66073033788698e-05 6.02325818787935e-06 3.25129924513906e-06 -5.06189106956767e-06 1.38262625350738e-05 -3.66073033788698e-05 0.00014161546098362 -3.82290384387725e-06 5.20956451880727e-06 -1.53114020299172e-05 0.000106891932619202 6.02325818787935e-06 -3.82290384387725e-06 1.81201268842241e-05 5.76187199516963e-07 2.45903054397911e-06 6.62493889412289e-06 3.25129924513906e-06 5.20956451880727e-06 5.76187199516963e-07 6.54532215661932e-05 -1.58814986827564e-06 8.52762982942226e-06 -5.06189106956767e-06 -1.53114020299172e-05 2.45903054397911e-06 -1.58814986827564e-06 2.96580360496171e-05 -1.04587037972529e-05 1.38262625350738e-05 0.000106891932619202 6.62493889412289e-06 8.52762982942226e-06 -1.04587037972529e-05 0.000327579918764828 2187 2194 0 0 154 2143 2150 0 0 172 0 0 0 0 0 208 142 0 0 0 0 0 0 0 2388 +58 30 0.991416073691431 -0.116570600712203 0.0592069580021059 -0.0611137029547698 0.114690195848903 0.992811251658241 0.0342341577512336 0.0601880331859878 -0.0627720304148853 -0.0271498366549818 0.997658538061596 0.593491911434967 7.92617800127504e-05 -4.68248341723491e-05 -6.93177318831566e-07 1.09271247109999e-05 -3.10953877937802e-06 -4.37683965644694e-06 -4.68248341723491e-05 0.000205596740829997 3.04280557813142e-06 -5.23843231010354e-05 1.19940003334547e-05 5.85521464338248e-05 -6.93177318831566e-07 3.04280557813142e-06 1.59827780724122e-05 -2.577417276183e-06 4.1411607040286e-06 6.23229232923399e-07 1.09271247109999e-05 -5.23843231010354e-05 -2.577417276183e-06 6.07831787580395e-05 6.14954475968623e-07 -1.4659493919634e-05 -3.10953877937802e-06 1.19940003334547e-05 4.1411607040286e-06 6.14954475968623e-07 2.62916336452449e-05 3.08570573986585e-06 -4.37683965644694e-06 5.85521464338248e-05 6.23229232923399e-07 -1.4659493919634e-05 3.08570573986585e-06 0.000192775396511407 1966 1969 0 0 194 1933 1936 0 0 213 0 0 0 0 0 183 182 0 16 0 0 0 0 0 2000 +58 29 0.991604908345696 -0.117198881844371 0.0546271712534472 -0.0651847878848906 0.115327514282914 0.992666002314033 0.0362459970093367 0.0596074883514492 -0.0584745260267122 -0.0296416926693746 0.997848735962343 0.587974637412604 0.00010607106061226 4.36629851910309e-05 3.89123530089676e-06 -1.72707428216067e-05 5.92427073292651e-06 0.000141024151283976 4.36629851910309e-05 0.000363010740020867 -6.73232313456259e-08 -0.000105776106125788 1.60825669910191e-05 0.000478842977581345 3.89123530089676e-06 -6.73232313456259e-08 1.55501734265479e-05 -8.71955723128507e-08 1.91876015685915e-06 4.11898414675211e-07 -1.72707428216067e-05 -0.000105776106125788 -8.71955723128507e-08 8.12512482272478e-05 -7.970147532398e-08 -0.000142418755280614 5.92427073292651e-06 1.60825669910191e-05 1.91876015685915e-06 -7.970147532398e-08 2.9048698502567e-05 2.81106853595397e-05 0.000141024151283976 0.000478842977581345 4.11898414675211e-07 -0.000142418755280614 2.81106853595397e-05 0.000849155323299184 2028 2031 0 0 193 1992 1995 0 0 214 0 0 0 0 0 195 194 0 19 0 0 0 0 0 2030 +58 28 0.990824788382685 -0.117763634394066 0.0663171557043021 -0.0623867469205828 0.115217502212813 0.992493608945923 0.0410044312890492 0.0644110182371908 -0.0706481840548517 -0.0329873099206166 0.996955701861398 0.58367379292438 9.0759137398108e-05 -1.82233239891998e-05 1.11056605434053e-06 -1.47593179929891e-06 1.01315073063886e-06 8.1183664014237e-05 -1.82233239891998e-05 0.00027267345236621 -7.97462691704991e-07 -2.43960956531371e-05 4.79397771247358e-06 0.000181225929958514 1.11056605434053e-06 -7.97462691704991e-07 1.56662119864337e-05 2.2995695798665e-06 1.6713630751781e-06 -2.67548726028778e-06 -1.47593179929891e-06 -2.43960956531371e-05 2.2995695798665e-06 4.65648247463461e-05 3.80468685164879e-06 -3.81618697303899e-05 1.01315073063886e-06 4.79397771247358e-06 1.6713630751781e-06 3.80468685164879e-06 2.85137837863627e-05 5.65682140708467e-06 8.1183664014237e-05 0.000181225929958514 -2.67548726028778e-06 -3.81618697303899e-05 5.65682140708467e-06 0.000454060436195452 1762 1764 0 0 188 1738 1740 0 0 203 0 0 0 0 0 154 154 0 20 0 0 0 0 0 2012 +58 27 0.991483532189522 -0.115751582366281 0.0596822970125275 -0.0591545520881151 0.114471936363269 0.993125721887295 0.0244433285598095 0.056867688215759 -0.0621013782635552 -0.0174032096333172 0.997918106415665 0.599884653049502 0.000114984959062403 -1.24660692437941e-05 1.35505250388345e-06 2.18272584571888e-06 1.48528578332238e-06 6.88660652895081e-05 -1.24660692437941e-05 0.000128430015915998 -6.95029407765051e-06 -1.07275082031778e-05 1.70077981266617e-05 0.000209792986649313 1.35505250388345e-06 -6.95029407765051e-06 1.52124253394767e-05 -2.51831740110231e-07 1.82460602639438e-06 -8.70686750167955e-06 2.18272584571888e-06 -1.07275082031778e-05 -2.51831740110231e-07 5.65890463997906e-05 5.7853227421963e-06 -5.33772972266048e-06 1.48528578332238e-06 1.70077981266617e-05 1.82460602639438e-06 5.7853227421963e-06 2.90909808021205e-05 4.0654122708669e-05 6.88660652895081e-05 0.000209792986649313 -8.70686750167955e-06 -5.33772972266048e-06 4.0654122708669e-05 0.000654700706155923 1849 1852 0 0 181 1824 1827 0 0 199 0 0 0 0 0 152 152 0 19 0 0 0 0 0 2133 +58 26 0.99084361107905 -0.116649946737278 0.0679832943451479 -0.0616955572889015 0.114549129841715 0.992834388020241 0.0340349058611932 0.061344285526214 -0.0714663223926812 -0.0259358418152303 0.997105760124271 0.604781879415814 0.000141099051707166 -1.81648779168211e-05 6.40020081730443e-06 -8.57065187010627e-06 -6.84738755790821e-07 0.000132945389088815 -1.81648779168211e-05 0.000165701160042505 -5.96175184187119e-06 -3.49098898389548e-05 1.2511457140587e-05 0.000329088120876303 6.40020081730443e-06 -5.96175184187119e-06 1.68973451370286e-05 2.85835935756042e-07 1.62806500742462e-07 -6.61155481555748e-06 -8.57065187010627e-06 -3.49098898389548e-05 2.85835935756042e-07 5.9389680087112e-05 2.30057040190929e-06 -8.10432822411188e-05 -6.84738755790821e-07 1.2511457140587e-05 1.62806500742462e-07 2.30057040190929e-06 2.87618698097072e-05 4.34671828763504e-05 0.000132945389088815 0.000329088120876303 -6.61155481555748e-06 -8.10432822411188e-05 4.34671828763504e-05 0.00111492477638498 1851 1853 0 0 181 1825 1827 0 0 200 0 0 0 0 0 152 152 0 15 0 0 0 0 0 2085 +58 24 0.991155986861389 -0.116634813376923 0.0632939966928641 -0.0579246111338693 0.114360985647567 0.992695153410272 0.0384434306153043 0.0647424797399881 -0.0673154861123566 -0.0308650725624795 0.997254216649481 0.591958235976912 8.2112188955253e-05 -7.52583276368816e-06 1.26094688154861e-07 -2.06469659873816e-06 -4.25445564954533e-06 7.16493676005521e-05 -7.52583276368816e-06 0.000198803643910431 -4.28262716765091e-06 -2.19027962334949e-05 4.18516812865376e-06 0.000132581021164967 1.26094688154861e-07 -4.28262716765091e-06 1.60824388637312e-05 -1.92345258258789e-06 3.95226612091544e-06 -6.46631174135138e-06 -2.06469659873816e-06 -2.19027962334949e-05 -1.92345258258789e-06 6.19670785747173e-05 1.04492050546279e-05 -3.83637484242699e-05 -4.25445564954533e-06 4.18516812865376e-06 3.95226612091544e-06 1.04492050546279e-05 3.42512868248855e-05 3.23634464084066e-06 7.16493676005521e-05 0.000132581021164967 -6.46631174135138e-06 -3.83637484242699e-05 3.23634464084066e-06 0.000410414033770517 1787 1790 0 0 184 1762 1765 0 0 204 0 0 0 0 0 147 147 0 18 0 0 0 0 0 2045 +58 8 0.990784585485586 -0.117339133750104 0.0676567280832487 -0.0660807882394938 0.114461299562305 0.992409694517218 0.0449623078895003 0.0685736981459696 -0.0724190311082907 -0.0368038845642317 0.996695017552671 0.592570082623372 9.44189134802906e-05 4.96175570520642e-06 2.14573017091083e-06 8.88474227033761e-06 -4.42131047925703e-06 8.29640648315516e-05 4.96175570520642e-06 0.000322506489426276 -5.18760743026927e-06 -4.24085367695368e-05 1.62623827343415e-05 0.000198878373101786 2.14573017091083e-06 -5.18760743026927e-06 1.65468689388585e-05 -2.20088098128094e-06 3.90591344438838e-07 -2.58143930682271e-06 8.88474227033761e-06 -4.24085367695368e-05 -2.20088098128094e-06 6.66657700375668e-05 8.14292822966884e-06 -2.11766408110567e-05 -4.42131047925703e-06 1.62623827343415e-05 3.90591344438838e-07 8.14292822966884e-06 3.29479766277965e-05 8.76412225472964e-06 8.29640648315516e-05 0.000198878373101786 -2.58143930682271e-06 -2.11766408110567e-05 8.76412225472964e-06 0.000405657521802407 1775 1777 0 0 177 1752 1754 0 0 202 0 0 0 0 0 158 158 0 24 0 0 0 0 0 1989 +58 23 0.990652378581367 -0.118392635315239 0.0677572779426115 -0.0589234675547453 0.115863914466772 0.992454491329467 0.040120268747924 0.0640216705973807 -0.0719959591610261 -0.0318946162084106 0.996894836640958 0.594312447085206 7.97839091366167e-05 -3.14103985398165e-05 1.30140200670637e-06 -7.95102305300094e-06 -3.1462812822663e-06 3.18628741003517e-05 -3.14103985398165e-05 0.00016154533848223 7.04948608857667e-06 -1.89755122642581e-05 -3.92333259391056e-06 9.34122129475876e-05 1.30140200670637e-06 7.04948608857667e-06 1.53393587940334e-05 4.15537093874436e-08 2.94662873761551e-06 1.54590185231419e-06 -7.95102305300094e-06 -1.89755122642581e-05 4.15537093874436e-08 5.67071557190819e-05 1.51186291568171e-06 -1.79225260589581e-05 -3.1462812822663e-06 -3.92333259391056e-06 2.94662873761551e-06 1.51186291568171e-06 2.34727512559608e-05 -5.89978237382833e-06 3.18628741003517e-05 9.34122129475876e-05 1.54590185231419e-06 -1.79225260589581e-05 -5.89978237382833e-06 0.000272117591027602 1823 1825 0 0 183 1796 1798 0 0 207 0 0 0 0 0 150 150 0 16 0 0 0 0 0 2016 +62 2 0.980651378938591 -0.184582232922241 -0.0652094492790725 -0.328310787296283 0.188915049094697 0.979633398313715 0.068040496278836 0.056912053969354 0.0513222876671386 -0.0790430528115007 0.995549204505156 0.903701677345625 0.000125303668502279 -7.87885625287839e-05 4.22062012945129e-06 2.75880799415806e-05 1.6161322308573e-05 -2.9716954451255e-05 -7.87885625287839e-05 0.000232550536734497 -9.51854412154011e-06 -5.75579087036831e-05 -6.41295359566218e-06 -6.36132931039285e-05 4.22062012945129e-06 -9.51854412154011e-06 1.7874955368959e-05 3.90421728049229e-06 8.50893636835894e-07 -7.43533746631621e-06 2.75880799415806e-05 -5.75579087036831e-05 3.90421728049229e-06 0.000100533632208494 1.02462425564384e-05 -1.93579265952491e-05 1.6161322308573e-05 -6.41295359566218e-06 8.50893636835894e-07 1.02462425564384e-05 3.54306149195843e-05 7.67823922561032e-06 -2.9716954451255e-05 -6.36132931039285e-05 -7.43533746631621e-06 -1.93579265952491e-05 7.67823922561032e-06 0.000530224345155 828 828 0 0 25 828 828 0 0 30 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1415 +62 64 0.999123228779623 -0.0346354222808786 -0.0235193800174894 0.114978476785706 0.0351388037779962 0.999154623176741 0.0213378408841321 -0.00136105903103582 0.0227604521491411 -0.0221455753587546 0.999495640465728 -0.0302364263219372 3.01209773076907e-05 -9.16219109574166e-06 -2.35218117336572e-07 3.44470052400815e-06 -1.16812391499725e-06 -5.62741837212092e-06 -9.16219109574166e-06 6.9345585869414e-05 -2.24012886755969e-06 -1.11392600660382e-06 -1.67258189413373e-06 -3.07151937957173e-05 -2.35218117336572e-07 -2.24012886755969e-06 1.12375679268135e-05 -1.9197484827667e-06 1.97135943800908e-06 9.83601040847849e-07 3.44470052400815e-06 -1.11392600660382e-06 -1.9197484827667e-06 7.29593720829938e-05 9.94815798579385e-06 -6.81503276070837e-06 -1.16812391499725e-06 -1.67258189413373e-06 1.97135943800908e-06 9.94815798579385e-06 1.90717994032789e-05 -2.17854271397852e-07 -5.62741837212092e-06 -3.07151937957173e-05 9.83601040847849e-07 -6.81503276070837e-06 -2.17854271397852e-07 8.96239437630219e-05 3316 3213 0 34 180 3304 3213 0 0 210 0 0 0 0 0 0 0 0 317 0 0 0 0 0 3514 +63 65 0.99868391647786 -0.0498969793285306 0.0118628167958401 0.120756782231227 0.0494335085266962 0.998106926410386 0.0365908688931074 -0.00207918754918514 -0.0136661334394379 -0.0359562915982686 0.999259917084297 -0.0140962707262663 3.0572224872621e-05 -2.60342245321552e-05 -1.1069436442297e-06 -6.30060372870532e-07 -4.09371530159117e-06 8.35293663057794e-06 -2.60342245321552e-05 0.000191562747547099 -9.00564178721294e-06 2.31017349302975e-06 -6.48598257825469e-07 -0.000116121863344533 -1.1069436442297e-06 -9.00564178721294e-06 1.12345159462355e-05 -2.04021130682683e-06 1.71112176568665e-06 4.13780595770622e-06 -6.30060372870532e-07 2.31017349302975e-06 -2.04021130682683e-06 5.38326872349684e-05 7.95022844043481e-06 8.33320638168639e-06 -4.09371530159117e-06 -6.48598257825469e-07 1.71112176568665e-06 7.95022844043481e-06 1.69004695251665e-05 7.10766771451964e-06 8.35293663057794e-06 -0.000116121863344533 4.13780595770622e-06 8.33320638168639e-06 7.10766771451964e-06 0.000178354018723086 3186 3070 0 30 230 3183 3070 0 0 255 0 0 0 0 0 0 0 0 300 0 0 0 0 0 3499 +63 7 0.982664499878137 -0.178015220151435 -0.0517789732776361 -0.379258585278134 0.180963218123475 0.981703402811416 0.0592515197685499 0.0580665058383357 0.0402839219248312 -0.0675944546758321 0.996899290465908 0.940918561195212 9.99793123729091e-05 -1.40963420294813e-05 -1.16848692676141e-06 -1.77052998982693e-05 1.95405174979776e-05 1.92456928374526e-05 -1.40963420294813e-05 0.00011101254514118 -4.39407026216828e-06 -4.11019112016959e-05 -1.05306755665708e-06 -3.19205297956282e-05 -1.16848692676141e-06 -4.39407026216828e-06 1.46530016070363e-05 -5.28616749660209e-07 4.94704204591049e-06 1.75842466015136e-05 -1.77052998982693e-05 -4.11019112016959e-05 -5.28616749660209e-07 0.000103404028792101 -2.50570544353457e-06 -8.68853684009382e-05 1.95405174979776e-05 -1.05306755665708e-06 4.94704204591049e-06 -2.50570544353457e-06 3.43439352448269e-05 -1.7368058854112e-06 1.92456928374526e-05 -3.19205297956282e-05 1.75842466015136e-05 -8.68853684009382e-05 -1.7368058854112e-06 0.000908141431024643 885 886 0 0 20 885 886 0 0 20 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1355 +64 66 0.999056165113108 -0.0431032678257156 -0.00537468624519742 0.126105285323237 0.0431744045060912 0.998970737940864 0.0139081103471916 -0.00114027204332986 0.00476966927932087 -0.0141270322654786 0.999888832428053 -0.0197177486295101 2.28614945060036e-05 -4.61009828855026e-06 -1.72194621364264e-06 2.04328996270906e-06 1.08432966559844e-06 1.98192163726014e-06 -4.61009828855026e-06 2.2982875684445e-05 -1.95545634301648e-06 1.50883659458456e-06 -1.12410385885496e-06 7.72947891332519e-08 -1.72194621364264e-06 -1.95545634301648e-06 1.20648974630396e-05 -1.86163734474002e-06 1.34743357770953e-06 1.0267762626847e-06 2.04328996270906e-06 1.50883659458456e-06 -1.86163734474002e-06 7.6661979756284e-05 1.25502515930299e-05 7.76364357473511e-06 1.08432966559844e-06 -1.12410385885496e-06 1.34743357770953e-06 1.25502515930299e-05 1.77806342070957e-05 2.51599796115002e-06 1.98192163726014e-06 7.72947891332519e-08 1.0267762626847e-06 7.76364357473511e-06 2.51599796115002e-06 0.000119095692149909 3518 3413 0 46 216 3518 3413 0 1 237 0 0 0 0 0 0 0 0 326 0 0 0 0 0 3536 +64 68 0.992830457989461 -0.0846464901940543 -0.084395813795855 0.330528747776665 0.086125055415559 0.996185559651408 0.0140287409156298 0.0202629372706833 0.0828864073181101 -0.0211967554082895 0.996333549089891 0.0109993366164948 2.54882662283074e-05 -1.99933076093105e-06 -1.95960248471836e-06 -1.60389787551516e-06 -2.13324598428327e-06 -2.25040093636213e-06 -1.99933076093105e-06 4.82524423168731e-05 -2.88911483295187e-06 5.42614743001727e-06 -2.63209639980202e-07 -3.80322719394948e-05 -1.95960248471836e-06 -2.88911483295187e-06 1.13639738971233e-05 1.05152203708166e-06 2.18665288275991e-06 1.07632519153664e-06 -1.60389787551516e-06 5.42614743001727e-06 1.05152203708166e-06 8.07863661978878e-05 2.42471237045557e-06 8.56710448586468e-06 -2.13324598428327e-06 -2.63209639980202e-07 2.18665288275991e-06 2.42471237045557e-06 1.7598587317448e-05 1.17551933512148e-05 -2.25040093636213e-06 -3.80322719394948e-05 1.07632519153664e-06 8.56710448586468e-06 1.17551933512148e-05 0.000190905410961786 3108 3021 0 70 565 3108 3021 0 62 595 0 0 0 0 0 0 0 0 201 0 0 0 0 0 2898 +64 7 0.987543885633965 -0.153437258791248 -0.0348436731932357 -0.441188949541623 0.154634085713913 0.987361396528654 0.0347242304509058 0.0446644458514503 0.0290753070902386 -0.0396797210122871 0.998789340280519 0.989471393814395 8.28256268056004e-05 -2.72072904639378e-05 -2.8692503542314e-07 -1.38623207252353e-05 1.58922784439305e-05 -2.11894426442126e-05 -2.72072904639378e-05 9.82344556145309e-05 -7.23131201931625e-07 -3.83940930768385e-05 4.30066051985433e-06 -7.43779414300768e-05 -2.8692503542314e-07 -7.23131201931625e-07 1.30405950629974e-05 1.15213687616428e-07 2.38643256788744e-06 -4.14818428348784e-06 -1.38623207252353e-05 -3.83940930768385e-05 1.15213687616428e-07 0.000107757029104663 -3.96769278483855e-06 5.12083973000299e-05 1.58922784439305e-05 4.30066051985433e-06 2.38643256788744e-06 -3.96769278483855e-06 3.39533635318233e-05 -1.40566108190495e-05 -2.11894426442126e-05 -7.43779414300768e-05 -4.14818428348784e-06 5.12083973000299e-05 -1.40566108190495e-05 0.000551676150348984 878 879 0 0 8 878 879 0 0 9 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1344 +65 3 0.988958772052535 -0.129594562744807 -0.0718734755478269 -0.548783692933933 0.131916883920011 0.990849696094072 0.0285449730621455 0.0422880391415328 0.067516538101238 -0.0377111264385825 0.997005209628093 0.966774670573606 8.5644555110947e-05 -7.18237678230386e-05 -8.27397905399721e-07 1.64709468314182e-05 1.32661015937083e-05 4.37025614140292e-05 -7.18237678230386e-05 0.000532602349404379 -1.01037400306019e-05 -0.000211494154621603 3.67316747669098e-06 -0.000541439895717035 -8.27397905399721e-07 -1.01037400306019e-05 1.54922520826375e-05 5.79756843118136e-06 6.00804904309742e-06 7.66376241994378e-06 1.64709468314182e-05 -0.000211494154621603 5.79756843118136e-06 0.000163427773689567 -2.9941891821855e-06 0.000223218905008149 1.32661015937083e-05 3.67316747669098e-06 6.00804904309742e-06 -2.9941891821855e-06 3.05870867115669e-05 -1.09897798999829e-05 4.37025614140292e-05 -0.000541439895717035 7.66376241994378e-06 0.000223218905008149 -1.09897798999829e-05 0.000817868753831573 678 678 0 0 0 678 678 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1272 +65 2 0.989943233596804 -0.128795899843255 -0.0585150445566737 -0.539748969630266 0.131284410871797 0.990501901968249 0.0408703518375646 0.0497339431440118 0.0526953291853125 -0.0481414414080776 0.997449549551858 0.98169919972876 7.12003754742114e-05 -3.28565721561804e-05 -2.1896203057938e-06 1.34386096671662e-05 4.81617565762118e-06 -6.65634236490374e-06 -3.28565721561804e-05 0.000368596398877228 -2.50180711242299e-06 -0.000165901293082341 1.4971512757392e-05 -0.000370166076110555 -2.1896203057938e-06 -2.50180711242299e-06 1.79247240929812e-05 -7.26747937427386e-07 1.27030218022628e-06 -5.9420383218691e-06 1.34386096671662e-05 -0.000165901293082341 -7.26747937427386e-07 0.000164352023689358 -4.91439914788906e-06 0.000150400864339539 4.81617565762118e-06 1.4971512757392e-05 1.27030218022628e-06 -4.91439914788906e-06 3.51688678868589e-05 -2.48472157494444e-05 -6.65634236490374e-06 -0.000370166076110555 -5.9420383218691e-06 0.000150400864339539 -2.48472157494444e-05 0.000846367978082519 643 643 0 0 0 643 643 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1238 +65 68 0.994419100334072 -0.0607434673086657 -0.0862605591802871 0.256597115442023 0.0614204715081348 0.998098363514614 0.0052136771255013 0.0133746004217175 0.0857798261276692 -0.0104827443339819 0.996258969094249 0.0492666362279108 3.40254907837247e-05 -6.47242157332964e-06 1.44614929228947e-06 -8.59440646966125e-07 -4.12110498306112e-06 -1.32945257005969e-06 -6.47242157332964e-06 3.89163435959082e-05 -5.05025272241109e-06 7.17836028885333e-06 -2.09439552714427e-08 5.2038126301634e-06 1.44614929228947e-06 -5.05025272241109e-06 1.21292863818024e-05 1.53890118638253e-06 4.34043016703894e-07 9.26355849231593e-07 -8.59440646966125e-07 7.17836028885333e-06 1.53890118638253e-06 7.94196586542341e-05 -1.94348726984617e-06 1.51063434050336e-05 -4.12110498306112e-06 -2.09439552714427e-08 4.34043016703894e-07 -1.94348726984617e-06 1.9259821922333e-05 4.08544758564587e-06 -1.32945257005969e-06 5.2038126301634e-06 9.26355849231593e-07 1.51063434050336e-05 4.08544758564587e-06 0.000341401777815256 3046 2957 0 63 381 3046 2957 0 62 411 0 0 0 0 0 0 0 0 355 0 0 0 0 0 2929 +65 5 0.990189411547671 -0.12905961811378 -0.0535587922866377 -0.536959411981768 0.13099463886932 0.990788469991557 0.0343309236590877 0.0503411587587288 0.0486346979673382 -0.041010031749745 0.997974370136584 0.984804096226127 0.00016044950494489 -8.15445361549788e-05 2.90794249345183e-06 8.35115318770622e-05 4.32700728797886e-05 5.1979867153008e-05 -8.15445361549788e-05 0.000579635892257135 9.6785796300645e-07 -0.000202237574513039 -4.26650921199204e-07 -0.000718198648083127 2.90794249345183e-06 9.6785796300645e-07 1.65780481059308e-05 3.01307033755514e-06 5.54307068440106e-06 3.38579091742664e-06 8.35115318770622e-05 -0.000202237574513039 3.01307033755514e-06 0.00019092581114078 2.01642553215524e-05 0.000218672811047737 4.32700728797886e-05 -4.26650921199204e-07 5.54307068440106e-06 2.01642553215524e-05 4.37045690329911e-05 -2.92787727785743e-05 5.1979867153008e-05 -0.000718198648083127 3.38579091742664e-06 0.000218672811047737 -2.92787727785743e-05 0.0015023216219392 672 672 0 0 0 672 672 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1287 +65 38 0.989216761758777 -0.129103278542973 -0.0691559232816307 -0.552236885725009 0.131576049066254 0.990774391510784 0.0324630318755098 0.0487000003303849 0.0643268339621508 -0.0412122384236897 0.997077534516005 1.01193526868141 0.00011734915404892 -6.50489747047231e-05 8.45214028619429e-07 3.88878103171682e-05 2.52532365359208e-05 -1.1597346023523e-05 -6.50489747047231e-05 0.00044679101183938 -1.02237389135833e-05 -0.0001396846504981 2.38006164020478e-05 8.09488878995865e-05 8.45214028619429e-07 -1.02237389135833e-05 1.80839571877861e-05 5.08932230607052e-06 6.01725364785474e-06 -5.84184236481788e-06 3.88878103171682e-05 -0.0001396846504981 5.08932230607052e-06 0.000176092971242483 1.22324483918452e-05 1.80491776557497e-05 2.52532365359208e-05 2.38006164020478e-05 6.01725364785474e-06 1.22324483918452e-05 4.38766628396166e-05 1.77489321623125e-05 -1.1597346023523e-05 8.09488878995865e-05 -5.84184236481788e-06 1.80491776557497e-05 1.77489321623125e-05 0.00056082114932474 665 665 0 0 0 665 665 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1202 +65 29 0.990352603463831 -0.129386271434443 -0.049607595957718 -0.538620232959249 0.130923177153351 0.990965844850759 0.0290829163478183 0.0460912566325554 0.045396503130571 -0.0352971259951068 0.998345266127907 0.988796918386427 9.6052564543197e-05 -6.24386807647071e-05 1.60933675860589e-06 3.12537787773582e-05 1.40722727489994e-05 1.14545160830189e-05 -6.24386807647071e-05 0.000266050893402684 -2.98127971744023e-06 -0.000109626498955262 1.03924861864035e-05 -0.000227328921245902 1.60933675860589e-06 -2.98127971744023e-06 1.42347348414317e-05 9.04271310400872e-07 5.1222214212992e-06 1.21882737286029e-05 3.12537787773582e-05 -0.000109626498955262 9.04271310400872e-07 0.000141935450427028 4.04210566019934e-06 4.48901720729647e-05 1.40722727489994e-05 1.03924861864035e-05 5.1222214212992e-06 4.04210566019934e-06 3.06696343301516e-05 -2.77537428595848e-05 1.14545160830189e-05 -0.000227328921245902 1.21882737286029e-05 4.48901720729647e-05 -2.77537428595848e-05 0.00100236633925968 829 829 0 0 0 831 831 0 0 0 0 0 0 0 0 0 0 0 0 0 9 9 0 0 1297 +65 35 0.98980564751744 -0.129856345242042 -0.0584988012096111 -0.544963472860502 0.131985888719835 0.990663962796079 0.0341267929346363 0.0469828216176039 0.0535210736198097 -0.0414999086450568 0.997703990300247 0.982430571140221 7.58810913558542e-05 -2.05018876124508e-05 -1.02615517232102e-06 -8.72569366356702e-06 1.38654640540793e-05 -5.50343907587081e-05 -2.05018876124508e-05 0.000234750131216215 1.32612256449543e-06 -6.58914068657118e-05 6.43759640886419e-06 -0.000308861610090147 -1.02615517232102e-06 1.32612256449543e-06 1.69476813090238e-05 -7.1235024246184e-07 4.40934300942429e-06 -1.98109294877889e-05 -8.72569366356702e-06 -6.58914068657118e-05 -7.1235024246184e-07 9.65361216802664e-05 -2.06483916346134e-06 0.000147272044061679 1.38654640540793e-05 6.43759640886419e-06 4.40934300942429e-06 -2.06483916346134e-06 3.71492731221151e-05 -4.59471960008492e-05 -5.50343907587081e-05 -0.000308861610090147 -1.98109294877889e-05 0.000147272044061679 -4.59471960008492e-05 0.00134363543872338 690 690 0 0 0 692 692 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1258 +66 68 0.996065938292084 -0.0428155645957712 -0.0775852692374952 0.163062193212581 0.0432935851541461 0.999052308318499 0.00448895622391572 0.00797835243628558 0.0773195451280591 -0.00783024085356756 0.996975614179888 0.0242979524878397 4.78851922706508e-05 7.03065366360655e-06 -1.62413440802532e-06 8.46390528705692e-06 -2.65612035582972e-06 5.8684685536021e-05 7.03065366360655e-06 3.5117875802627e-05 -1.74915209555887e-06 1.86608656963252e-06 3.96087022176951e-06 3.09388219110378e-05 -1.62413440802532e-06 -1.74915209555887e-06 1.30312722360287e-05 -3.16585916049088e-07 1.33462773964583e-06 1.14930264804882e-06 8.46390528705692e-06 1.86608656963252e-06 -3.16585916049088e-07 0.000159043264000973 -3.29485367980621e-06 -3.40541532702226e-05 -2.65612035582972e-06 3.96087022176951e-06 1.33462773964583e-06 -3.29485367980621e-06 1.81715814961071e-05 9.10920879908695e-06 5.8684685536021e-05 3.09388219110378e-05 1.14930264804882e-06 -3.40541532702226e-05 9.10920879908695e-06 0.000356397943971301 3169 3082 0 62 262 3169 3082 0 32 278 0 0 0 0 0 0 0 0 404 0 0 0 0 0 3248 +70 3 0.997686839115089 -0.0676141897283634 -0.00702085492800829 -0.980017434147081 0.0675862451843397 0.99770482838758 -0.00414425795422305 0.0446701437438726 0.00728495150468272 0.00366015839625831 0.999966765808789 0.983689359309043 3.35383374273851e-05 -3.5019905580671e-05 -2.21680702945197e-06 5.95862931681591e-06 4.37975374505298e-06 5.84602246461362e-05 -3.5019905580671e-05 0.000312088669799937 6.40088973923418e-07 -0.000141349657696142 5.59081485663321e-06 -0.00040923321022734 -2.21680702945197e-06 6.40088973923418e-07 1.26366003943391e-05 -2.95871770366947e-06 2.63699280112874e-06 -1.07915286945232e-07 5.95862931681591e-06 -0.000141349657696142 -2.95871770366947e-06 0.000183186172664014 -3.51197551266963e-06 0.000161069722224374 4.37975374505298e-06 5.59081485663321e-06 2.63699280112874e-06 -3.51197551266963e-06 2.26849369285808e-05 -1.1524746120265e-05 5.84602246461362e-05 -0.00040923321022734 -1.07915286945232e-07 0.000161069722224374 -1.1524746120265e-05 0.000727322227656812 772 772 0 0 0 775 775 0 0 0 0 0 0 0 0 0 0 0 0 0 84 84 0 0 1590 +70 4 0.997643020126984 -0.0680707036814828 -0.00864775648462867 -0.98098904568669 0.0680590896202028 0.997679959411565 -0.00163061602062174 0.0474939237055195 0.00873869051854346 0.00103821425787949 0.999961277949889 0.977349749897351 3.30343112254501e-05 -2.23519700903977e-06 -3.7015358940171e-06 -8.15333770481138e-06 8.21293131579336e-06 3.20256305507507e-06 -2.23519700903977e-06 6.60659045135531e-05 -2.84252624779559e-06 -1.7240726876646e-05 -7.42087347676168e-07 -5.91095204638005e-05 -3.7015358940171e-06 -2.84252624779559e-06 1.31194805948929e-05 -4.05699023874936e-08 3.42370578634678e-06 -9.14149921999931e-08 -8.15333770481138e-06 -1.7240726876646e-05 -4.05699023874936e-08 0.000161521964788299 -8.02233660439884e-06 4.16180671407753e-05 8.21293131579336e-06 -7.42087347676168e-07 3.42370578634678e-06 -8.02233660439884e-06 2.36857766772637e-05 -8.63972637612033e-07 3.20256305507507e-06 -5.91095204638005e-05 -9.14149921999931e-08 4.16180671407753e-05 -8.63972637612033e-07 0.000160257901855995 701 701 0 0 0 706 706 0 0 0 0 0 0 0 0 0 0 0 0 0 120 121 0 0 1605 +71 4 0.9963858708385 -0.0848113455466458 0.00471508854326569 -1.09329177847943 0.0846989373282441 0.996198186230488 0.0203780216545258 0.0543190337937374 -0.00642545009081645 -0.0199050098631874 0.999781228156179 0.977000240691192 4.34996153256818e-05 -5.51630667370699e-05 -8.08276735437464e-07 1.61857187410182e-05 4.59959548925167e-06 0.000130697268619824 -5.51630667370699e-05 0.000727036898540536 2.30947193988859e-06 -0.0003043988253389 2.25564181317676e-05 -0.0011501826834439 -8.08276735437464e-07 2.30947193988859e-06 1.56302942881693e-05 -9.11507084336006e-06 2.79104170477663e-06 -1.27529779290414e-05 1.61857187410182e-05 -0.0003043988253389 -9.11507084336006e-06 0.000301225665774591 -5.93710315772477e-06 0.000489303779442043 4.59959548925167e-06 2.25564181317676e-05 2.79104170477663e-06 -5.93710315772477e-06 2.44845703180032e-05 -2.69551660559499e-05 0.000130697268619824 -0.0011501826834439 -1.27529779290414e-05 0.000489303779442043 -2.69551660559499e-05 0.00229591523862449 686 686 0 0 0 688 688 0 0 0 0 0 0 0 0 0 0 0 0 0 114 114 0 0 1476 +71 3 0.996352886797301 -0.0838381395458519 0.0158773841729584 -1.08973507705453 0.0835281293159279 0.996318986962572 0.0192750572205758 0.0524124304511065 -0.0174349242518304 -0.0178785507065063 0.999688141792713 0.985124978379926 4.17885118472272e-05 -1.04799869762664e-06 -7.53104088625359e-07 1.91172572757667e-05 5.919053758485e-06 5.40708657322336e-05 -1.04799869762664e-06 0.000175415753147476 -9.47121664481173e-07 -3.16646946097864e-05 7.18883678316305e-06 -0.000150649362116906 -7.53104088625359e-07 -9.47121664481173e-07 1.45709963881454e-05 -3.75084236729229e-06 3.43203643320284e-06 -2.66428754594492e-06 1.91172572757667e-05 -3.16646946097864e-05 -3.75084236729229e-06 0.000146903838369097 6.28895139439434e-06 6.79704948523729e-05 5.919053758485e-06 7.18883678316305e-06 3.43203643320284e-06 6.28895139439434e-06 2.17434928575641e-05 1.09457507767875e-05 5.40708657322336e-05 -0.000150649362116906 -2.66428754594492e-06 6.79704948523729e-05 1.09457507767875e-05 0.000442333221253215 747 747 0 0 0 746 746 0 0 0 0 0 0 0 0 0 0 0 0 0 77 77 0 0 1461 +74 77 0.999338594123505 -0.0170654140514227 -0.0321114611705783 0.43756815377955 0.0175637758864763 0.999728641458088 0.0153021967369476 0.00211010048377488 0.031841609128084 -0.0158560742814898 0.999367148167536 0.00667143071755058 4.17632416273074e-05 5.34653822032077e-06 3.45445187147822e-06 3.04151311086586e-06 2.98537882120254e-06 -9.12478065378805e-06 5.34653822032077e-06 9.6642306073557e-05 1.86437705338742e-06 6.53410931492429e-06 7.70864127147595e-07 -6.36019569831816e-05 3.45445187147822e-06 1.86437705338742e-06 1.24833993151557e-05 2.05724472225565e-06 -7.85769225316078e-07 -3.58961497029743e-06 3.04151311086586e-06 6.53410931492429e-06 2.05724472225565e-06 0.00017393937160637 3.74598299418614e-07 5.27055346485769e-06 2.98537882120254e-06 7.70864127147595e-07 -7.85769225316078e-07 3.74598299418614e-07 1.74874306641294e-05 1.20859536034026e-06 -9.12478065378805e-06 -6.36019569831816e-05 -3.58961497029743e-06 5.27055346485769e-06 1.20859536034026e-06 0.000190844503582564 3162 3101 0 785 511 3162 3101 0 641 556 0 0 0 0 0 0 0 0 835 0 0 0 0 0 3319 +75 4 0.993660034101433 -0.111158270729728 -0.0168396994603588 -1.66343760902775 0.111527101015745 0.993499232255235 0.0228250136315786 0.0432898167970304 0.0141930394406066 -0.0245583866863103 0.999597640690895 0.942323016316561 9.90568607789319e-05 -7.21964679684819e-05 7.24626686906812e-06 2.26093086548843e-05 1.62036797296726e-05 3.73654218482966e-05 -7.21964679684819e-05 0.00021817035289875 -1.4912908102013e-05 -6.15527069629545e-05 -6.49882092045957e-06 5.95889520447899e-05 7.24626686906812e-06 -1.4912908102013e-05 1.64464382132325e-05 8.50470756379399e-06 4.67011756063682e-06 1.62312916923381e-05 2.26093086548843e-05 -6.15527069629545e-05 8.50470756379399e-06 0.000351388793332292 -1.19853032137883e-05 0.000332453627368379 1.62036797296726e-05 -6.49882092045957e-06 4.67011756063682e-06 -1.19853032137883e-05 2.27231779945921e-05 -1.55025899786993e-05 3.73654218482966e-05 5.95889520447899e-05 1.62312916923381e-05 0.000332453627368379 -1.55025899786993e-05 0.00174559157398123 543 543 0 0 0 544 544 0 0 0 0 0 0 0 0 12 12 0 0 0 117 117 0 0 835 +75 77 0.999106568459245 -0.0196307038446244 -0.0374259312263205 0.315794077162996 0.019989362871128 0.999757557773871 0.00923314930190743 0.00854548739939257 0.0372356043807401 -0.00997302063517341 0.999256748101213 -0.00617482642131148 4.55568408106126e-05 -1.44990382734403e-05 -1.30663457965357e-06 8.2162807265011e-06 1.70538752844854e-06 5.19286068378385e-06 -1.44990382734403e-05 9.3206235555982e-05 -7.18046159050993e-07 4.01398506340894e-05 -1.54804284456198e-06 -1.04671788588128e-05 -1.30663457965357e-06 -7.18046159050993e-07 1.33532484319014e-05 5.97009998444999e-06 -1.8342936607733e-06 4.44876524020855e-07 8.2162807265011e-06 4.01398506340894e-05 5.97009998444999e-06 0.000269894591837074 -5.58049137956755e-06 4.69908373650192e-05 1.70538752844854e-06 -1.54804284456198e-06 -1.8342936607733e-06 -5.58049137956755e-06 1.91805286845766e-05 -1.51700321023675e-06 5.19286068378385e-06 -1.04671788588128e-05 4.44876524020855e-07 4.69908373650192e-05 -1.51700321023675e-06 0.000203515931957944 3266 3205 0 467 376 3266 3205 0 339 401 0 0 0 0 0 0 0 0 1481 0 0 0 0 0 3443 +76 2 0.994151557942943 -0.107588452678468 0.00934904753827347 -1.78161823889335 0.107205719151683 0.993630894757913 0.0347070419909124 0.0541906311521046 -0.0130235794154378 -0.0335017885021328 0.999353799485632 0.950651819655223 0.000112488730809011 -3.86769140209791e-05 2.72732125110975e-06 3.19698733479997e-05 2.37848550963523e-05 -9.0453611679839e-05 -3.86769140209791e-05 0.000214893482851923 -6.60665844139396e-06 -0.000208905232492707 9.9771785863298e-06 -0.00027980590224568 2.72732125110975e-06 -6.60665844139396e-06 1.49174749087563e-05 3.15642626162204e-06 4.27606446591733e-06 8.64874438780377e-07 3.19698733479997e-05 -0.000208905232492707 3.15642626162204e-06 0.00093982009687843 -3.22575176027328e-05 0.000210718537968715 2.37848550963523e-05 9.9771785863298e-06 4.27606446591733e-06 -3.22575176027328e-05 2.82238134465013e-05 -6.29899053055607e-05 -9.0453611679839e-05 -0.00027980590224568 8.64874438780377e-07 0.000210718537968715 -6.29899053055607e-05 0.000878098424632945 572 572 0 0 0 571 571 0 0 0 0 0 0 0 0 23 23 0 0 0 116 116 0 0 739 +76 49 0.993974443911083 -0.107366309207138 0.0220744308848388 -1.77980147856553 0.106537350922022 0.993663492940601 0.0358141823249168 0.0596315170281537 -0.0257797926712027 -0.0332466305709573 0.999114639991582 0.968046344343326 0.000128840169250677 -8.55369429529494e-05 6.381268452023e-07 4.60291361881121e-05 2.51202485911771e-05 -3.99486156569037e-05 -8.55369429529494e-05 0.000527251479372328 1.17552048533673e-05 -0.000330581547394746 8.17468728420265e-06 -0.000735774082247906 6.381268452023e-07 1.17552048533673e-05 1.53637795608201e-05 -1.41007980161919e-05 6.36484651852527e-07 -1.97802935550929e-05 4.60291361881121e-05 -0.000330581547394746 -1.41007980161919e-05 0.000558216651474846 -1.94949412901154e-05 0.000771427008856697 2.51202485911771e-05 8.17468728420265e-06 6.36484651852527e-07 -1.94949412901154e-05 2.88246222223582e-05 -8.65705138334858e-05 -3.99486156569037e-05 -0.000735774082247906 -1.97802935550929e-05 0.000771427008856697 -8.65705138334858e-05 0.00220362608947211 566 566 0 0 0 566 566 0 0 0 0 0 0 0 0 30 30 0 0 0 133 134 0 0 777 +76 38 0.994082844550905 -0.108090245910451 0.0107608972023373 -1.79868334526293 0.107694329534322 0.993658746943143 0.0323144860633256 0.0536948699199473 -0.0141855403751132 -0.0309643886166378 0.999419820236653 0.972943001341528 0.000101240486924839 -2.08556195130725e-05 -2.34068203021076e-06 -1.67410685663406e-05 2.09444947416948e-05 -9.80897213699199e-06 -2.08556195130725e-05 0.000438058352168691 -5.9440309586156e-06 -0.000436484630765004 4.32401726806051e-05 -0.000565045053351312 -2.34068203021076e-06 -5.9440309586156e-06 1.45962898944564e-05 7.72287600742661e-06 6.07245800352326e-07 1.11260596373783e-05 -1.67410685663406e-05 -0.000436484630765004 7.72287600742661e-06 0.000865263617282882 -6.39805109233299e-05 0.000640845321148759 2.09444947416948e-05 4.32401726806051e-05 6.07245800352326e-07 -6.39805109233299e-05 2.97758799351422e-05 -9.06383573150235e-05 -9.80897213699199e-06 -0.000565045053351312 1.11260596373783e-05 0.000640845321148759 -9.06383573150235e-05 0.00174606353121015 625 625 0 0 0 622 622 0 0 0 0 0 0 0 0 33 33 0 0 0 138 139 0 0 719 +76 6 0.994187749779086 -0.107316793584783 0.00859208961075242 -1.79613549847395 0.10697760971111 0.993705986950367 0.033229542872187 0.0592016316509832 -0.0121040988799499 -0.0321172432453053 0.999410813167751 0.973735275237039 0.000128975982507306 -8.81363943907098e-05 -3.94104294941941e-06 5.45754625142158e-05 2.02050270082622e-05 7.45131491230403e-05 -8.81363943907098e-05 0.000660658953493464 2.72959983307719e-06 -0.000510566832630142 3.22104940301629e-05 -0.00178684052605536 -3.94104294941941e-06 2.72959983307719e-06 1.4675593634339e-05 -9.38849871199634e-06 4.98477749228998e-06 -1.15520094756794e-05 5.45754625142158e-05 -0.000510566832630142 -9.38849871199634e-06 0.000603086353831089 -3.29473643041823e-05 0.00136519792206739 2.02050270082622e-05 3.22104940301629e-05 4.98477749228998e-06 -3.29473643041823e-05 2.62911116193389e-05 -0.000160632231496925 7.45131491230403e-05 -0.00178684052605536 -1.15520094756794e-05 0.00136519792206739 -0.000160632231496925 0.00629364988369062 591 591 0 0 0 589 589 0 0 0 0 0 0 0 0 14 14 0 0 0 139 140 0 0 777 +76 79 0.999474996969126 -0.0322045011403046 0.00354972391452217 0.402949579866366 0.0321489644330329 0.999374595105866 0.0147262603151633 0.0279862313472827 -0.0040217557669253 -0.0146044090359893 0.9998852617762 -0.0122328794050971 5.40128956503425e-05 -1.34853409413206e-05 5.01040589211609e-06 7.58775298857301e-07 -2.47981187060885e-06 -4.83746554887566e-06 -1.34853409413206e-05 5.85482881783005e-05 2.66814684988617e-06 1.02462896251276e-05 -9.04641077684732e-07 4.22988048634064e-06 5.01040589211609e-06 2.66814684988617e-06 1.38277106019706e-05 1.7550207854217e-06 -4.13507810861341e-07 2.65438649555626e-06 7.58775298857301e-07 1.02462896251276e-05 1.7550207854217e-06 0.000351071032347303 7.19377833916985e-06 0.00019002990324048 -2.47981187060885e-06 -9.04641077684732e-07 -4.13507810861341e-07 7.19377833916985e-06 1.77412995069485e-05 5.00830307977264e-06 -4.83746554887566e-06 4.22988048634064e-06 2.65438649555626e-06 0.00019002990324048 5.00830307977264e-06 0.000257977482105011 3167 3101 0 607 543 3167 3101 0 462 581 0 0 0 0 0 0 0 0 1325 0 0 0 0 0 3380 +76 80 0.999779761627499 -0.0153338025636937 0.0143283892674547 0.565818521173964 0.0146944643127455 0.998936280746603 0.0437078908974782 0.0322008435065863 -0.0149833560534181 -0.0434877167379717 0.998941598660449 -0.0428785032941601 4.69313023193266e-05 -8.3468201288077e-06 -4.06883507307676e-07 1.57154412658385e-05 1.55690855684598e-06 5.9158753183196e-06 -8.3468201288077e-06 3.73295190876888e-05 -2.45019550590859e-06 7.19961944568775e-06 -5.18154102034993e-07 -2.56215682539506e-05 -4.06883507307676e-07 -2.45019550590859e-06 1.26663754451691e-05 -3.70337559033037e-06 7.03840043897055e-07 3.53338884891936e-06 1.57154412658385e-05 7.19961944568775e-06 -3.70337559033037e-06 0.000210457358814763 4.23868385367067e-06 5.26815164925155e-05 1.55690855684598e-06 -5.18154102034993e-07 7.03840043897055e-07 4.23868385367067e-06 1.807014010874e-05 1.9001469696372e-07 5.9158753183196e-06 -2.56215682539506e-05 3.53338884891936e-06 5.26815164925155e-05 1.9001469696372e-07 0.000164790634970807 3300 3239 0 1086 740 3300 3239 0 914 787 0 0 0 0 0 0 0 0 865 0 0 0 0 0 3186 +77 81 0.997445649202258 0.0377659001215114 0.0606293136650805 0.579593987750725 -0.0381292913606993 0.999261056268768 0.00484753184170981 0.0207278303331467 -0.0604014406104489 -0.00714690231061794 0.998148580001767 -0.0169791787845255 4.86743349456691e-05 -9.23225579670346e-06 -2.96969672206113e-06 -1.55240773000503e-06 7.77250736103339e-06 6.33071610646634e-06 -9.23225579670346e-06 7.61033561703244e-05 1.95772354040549e-06 4.21997372647965e-05 3.98566401892895e-06 1.34917732524909e-05 -2.96969672206113e-06 1.95772354040549e-06 1.24386514592228e-05 -1.79982865080445e-06 -1.00804119240037e-06 3.48931188307423e-07 -1.55240773000503e-06 4.21997372647965e-05 -1.79982865080445e-06 0.000233884388642831 1.83783273172606e-05 4.22574854101233e-05 7.77250736103339e-06 3.98566401892895e-06 -1.00804119240037e-06 1.83783273172606e-05 1.87938297079121e-05 -9.60351359313361e-07 6.33071610646634e-06 1.34917732524909e-05 3.48931188307423e-07 4.22574854101233e-05 -9.60351359313361e-07 0.000723667802160541 3138 3093 0 1329 612 3138 3093 0 1155 650 0 0 0 0 0 0 0 0 902 0 0 0 0 0 3312 +77 37 0.993701271671643 -0.0940326245942707 0.0609561169208777 -1.89028063065569 0.0930248453873738 0.995479198791938 0.0191714087436572 0.0625125870625415 -0.0624832843151987 -0.0133802198963297 0.997956316126469 1.05410462374707 0.000120006843572262 8.35019124974764e-06 4.87005340231613e-06 -4.080202080359e-05 1.86219218803464e-05 -5.17324903363807e-05 8.35019124974764e-06 0.00137121132932632 4.679896253557e-06 -0.000742107793909482 7.32599377071405e-05 -0.00145482864330914 4.87005340231613e-06 4.679896253557e-06 1.95590104600962e-05 -3.38596893610193e-06 -4.46221212731497e-06 -9.13409357979964e-06 -4.080202080359e-05 -0.000742107793909482 -3.38596893610193e-06 0.00123013373349988 -8.06326543775094e-05 0.000776130595513302 1.86219218803464e-05 7.32599377071405e-05 -4.46221212731497e-06 -8.06326543775094e-05 3.79160451255829e-05 -8.33654824058315e-05 -5.17324903363807e-05 -0.00145482864330914 -9.13409357979964e-06 0.000776130595513302 -8.33654824058315e-05 0.00166791730741444 573 573 0 0 0 574 574 0 0 0 0 0 0 0 0 28 28 0 0 0 144 145 0 0 721 +77 80 0.999216694947284 -0.00160787973411875 0.0395399957181025 0.436401364869796 0.000784526597582192 0.999782724101419 0.020830004953524 0.0210003230336266 -0.0395648967728293 -0.0207826685270866 0.999000850666429 -0.0288975368211543 4.53556314070103e-05 -3.52898326566429e-06 -2.57649347578757e-06 2.58271599649198e-05 3.34756212653606e-06 -4.49475650712505e-06 -3.52898326566429e-06 2.28546678475578e-05 4.88524893527026e-07 2.89420185632951e-06 -1.77688812856571e-06 -5.69168967689641e-06 -2.57649347578757e-06 4.88524893527026e-07 1.26092416992009e-05 -1.12820970246728e-06 4.71905662651056e-08 1.15964120942099e-07 2.58271599649198e-05 2.89420185632951e-06 -1.12820970246728e-06 0.000229901810830854 6.96729704658095e-06 1.23443637745973e-05 3.34756212653606e-06 -1.77688812856571e-06 4.71905662651056e-08 6.96729704658095e-06 1.62184248757792e-05 1.83350674586036e-06 -4.49475650712505e-06 -5.69168967689641e-06 1.15964120942099e-07 1.23443637745973e-05 1.83350674586036e-06 0.000120547808379507 3337 3276 0 801 506 3337 3276 0 652 535 0 0 0 0 0 0 0 0 1231 0 0 0 0 0 3431 +77 79 0.999695086010159 -0.0181483595199283 0.0167443140760462 0.2610233143584 0.0181711186001372 0.999834161768211 -0.00120806046144615 0.018254082183864 -0.0167196129130312 0.00151195502386467 0.999859074338001 -0.0473561827188725 4.45853277929342e-05 -7.91075895406071e-06 3.98389987314558e-06 1.61307265945098e-05 -1.50068302954196e-06 1.97100177226089e-06 -7.91075895406071e-06 4.89085568072835e-05 -1.35901824706841e-06 -7.60655474958716e-06 -2.12186347755912e-06 -3.82185593337798e-05 3.98389987314558e-06 -1.35901824706841e-06 1.44154753335197e-05 1.32455688439326e-06 -2.075641994494e-06 9.45513355017775e-07 1.61307265945098e-05 -7.60655474958716e-06 1.32455688439326e-06 0.000119599545158922 -6.81671251103371e-07 4.74501453993762e-05 -1.50068302954196e-06 -2.12186347755912e-06 -2.075641994494e-06 -6.81671251103371e-07 1.66815391694007e-05 4.45191978613143e-07 1.97100177226089e-06 -3.82185593337798e-05 9.45513355017775e-07 4.74501453993762e-05 4.45191978613143e-07 0.000193784021818771 3153 3087 0 348 320 3153 3087 0 223 350 0 0 0 0 0 0 0 0 1658 0 0 0 0 0 3605 +78 80 0.998915155740772 0.00886729380597777 0.0457152352279512 0.302087768124493 -0.00939268848911609 0.999892141824399 0.0112907980569469 0.00922581077244233 -0.0456101856424074 -0.0117079382631956 0.998890702302955 -0.0169892126157308 6.12583932170152e-05 -5.34077448667803e-06 -4.32139258914711e-07 6.24496248831502e-06 4.68105391247312e-06 -6.09625747038113e-06 -5.34077448667803e-06 0.000496271757702342 4.00600004892442e-06 3.73645356256247e-05 1.89431765788615e-05 -0.000744824211044565 -4.32139258914711e-07 4.00600004892442e-06 1.18408872315235e-05 -1.74860868289332e-06 1.41260996380276e-06 -3.221977374808e-06 6.24496248831502e-06 3.73645356256247e-05 -1.74860868289332e-06 0.000150551828723982 5.28777851494405e-06 -5.10104354195546e-05 4.68105391247312e-06 1.89431765788615e-05 1.41260996380276e-06 5.28777851494405e-06 1.4816653263895e-05 -3.50153094648386e-05 -6.09625747038113e-06 -0.000744824211044565 -3.221977374808e-06 -5.10104354195546e-05 -3.50153094648386e-05 0.00141371788584791 3044 2983 0 536 290 3044 2983 0 407 322 0 0 0 0 0 0 0 0 1487 0 0 0 0 0 3650 +78 37 0.99598488136605 -0.0830068872533847 0.0335257029569826 -2.02896403517805 0.0829331384273692 0.996548658815685 0.00358680404351572 0.0602258642435348 -0.0337077237564741 -0.000792010835557974 0.999431419397046 1.01203432271015 0.000100160367821535 -6.10752400457414e-05 4.08732968403304e-06 2.619679074144e-05 1.45529576743722e-05 5.71309828555665e-05 -6.10752400457414e-05 0.000326958338949364 3.09258514904698e-06 -0.000154238190160566 5.42072263434824e-06 -0.000381014147750643 4.08732968403304e-06 3.09258514904698e-06 1.57143483149373e-05 1.00462521578335e-05 3.39750357353843e-08 -2.74023052684013e-07 2.619679074144e-05 -0.000154238190160566 1.00462521578335e-05 0.000651423766334517 -3.97227871615678e-05 0.000272956428182272 1.45529576743722e-05 5.42072263434824e-06 3.39750357353843e-08 -3.97227871615678e-05 2.57936079167758e-05 -1.99340081061118e-05 5.71309828555665e-05 -0.000381014147750643 -2.74023052684013e-07 0.000272956428182272 -1.99340081061118e-05 0.000713357164397755 560 560 0 0 0 561 561 0 0 0 0 0 0 0 0 21 21 0 0 0 182 183 0 0 511 +79 82 0.996361755316989 0.0810458353359483 0.0263595355867017 0.440080128282128 -0.0801905351110453 0.996264763995222 -0.0320312050998504 -0.00588519153775588 -0.0288570722744435 0.0298008824742292 0.999139217918857 -0.00983191173357111 4.50205236624074e-05 -8.16976782761805e-06 2.53529200436867e-06 -2.38045272650433e-06 -6.45613987839298e-07 -1.93202440344676e-06 -8.16976782761805e-06 7.74363882863809e-05 -1.11803561929158e-07 4.44554634979787e-05 7.25662289825823e-06 2.19243981545776e-05 2.53529200436867e-06 -1.11803561929158e-07 1.38424741514445e-05 1.2654650529536e-06 8.73600568021176e-07 1.38949138713345e-06 -2.38045272650433e-06 4.44554634979787e-05 1.2654650529536e-06 0.000246349683573356 2.74786188201897e-05 0.000139582443910358 -6.45613987839298e-07 7.25662289825823e-06 8.73600568021176e-07 2.74786188201897e-05 1.90373067862151e-05 4.71333200646562e-05 -1.93202440344676e-06 2.19243981545776e-05 1.38949138713345e-06 0.000139582443910358 4.71333200646562e-05 0.000749394325280177 3148 3112 0 1087 281 3148 3112 0 935 308 0 0 0 0 0 0 0 0 1333 0 0 0 0 0 3575 +79 53 0.997823445212071 -0.0641001213540182 0.0154772939337747 -2.18713430327113 0.0640312424316612 0.997935834688703 0.00490610199849558 0.0777606199290446 -0.0157598279740026 -0.00390439323864109 0.999868183079984 1.01292270822941 0.000136612437571862 -0.000371446061401782 -2.7838211802917e-07 0.000260883556113756 5.48141737829803e-06 0.000554811573865235 -0.000371446061401782 0.0028161774353159 1.24284808222578e-05 -0.00249872053742571 7.85523872272826e-05 -0.00505323901169556 -2.7838211802917e-07 1.24284808222578e-05 1.77474954994546e-05 -1.09968364900815e-05 2.52574310092413e-06 -9.8142852768145e-06 0.000260883556113756 -0.00249872053742571 -1.09968364900815e-05 0.00255044517114484 -9.51326835856039e-05 0.00473880012259759 5.48141737829803e-06 7.85523872272826e-05 2.52574310092413e-06 -9.51326835856039e-05 2.50330065831585e-05 -0.000188513937364647 0.000554811573865235 -0.00505323901169556 -9.8142852768145e-06 0.00473880012259759 -0.000188513937364647 0.00975472804305032 478 478 0 0 0 478 478 0 0 0 0 0 0 0 0 20 20 0 0 0 179 179 0 0 415 +79 37 0.996949065231317 -0.0759391340436169 0.0180501871211635 -2.20843325203543 0.0757688806503223 0.997075891010701 0.00993701616245766 0.0725170483177808 -0.0187520148090984 -0.00853905650065123 0.999787700691841 0.979134633302005 0.000170525145727924 -0.000155648783933947 1.20652685460438e-05 -7.95934330912812e-05 2.79516847659256e-05 -3.00780038397151e-05 -0.000155648783933947 0.000468405204594884 7.19824905144243e-06 -2.62336544300673e-05 -3.77444412432408e-05 0.000129201554868708 1.20652685460438e-05 7.19824905144243e-06 1.9009779214154e-05 -2.11564156862387e-06 9.935336802317e-07 1.20934007964492e-05 -7.95934330912812e-05 -2.62336544300673e-05 -2.11564156862387e-06 0.000802057829876559 -5.66280952278928e-05 0.000449584150848236 2.79516847659256e-05 -3.77444412432408e-05 9.935336802317e-07 -5.66280952278928e-05 2.72974345571914e-05 -4.77332471963493e-05 -3.00780038397151e-05 0.000129201554868708 1.20934007964492e-05 0.000449584150848236 -4.77332471963493e-05 0.000820348751741398 508 508 0 0 0 507 507 0 0 0 0 0 0 0 0 28 28 0 0 0 201 202 0 0 406 +79 36 0.997075050773754 -0.0758395485553151 -0.00947132511544163 -2.22685882665937 0.075995402526866 0.996957192432731 0.0173509438194796 0.0781960956791994 0.00812661794943033 -0.0180199703543909 0.999804600284041 1.02005756908125 0.00012076546236318 -6.0478483340771e-05 1.61975951074627e-06 -1.47937558297174e-05 1.29742150624165e-05 4.59374323148816e-05 -6.0478483340771e-05 0.000666910577938507 9.5767691755604e-06 1.4459731960175e-05 7.52864373293234e-06 -0.000670017089620944 1.61975951074627e-06 9.5767691755604e-06 1.70967432535281e-05 -2.84656583706284e-06 3.04319463187995e-06 -1.0832747968357e-05 -1.47937558297174e-05 1.4459731960175e-05 -2.84656583706284e-06 0.000568420017745396 -1.4662332111935e-05 8.62951961993365e-05 1.29742150624165e-05 7.52864373293234e-06 3.04319463187995e-06 -1.4662332111935e-05 2.31298117365601e-05 -1.77162647862906e-05 4.59374323148816e-05 -0.000670017089620944 -1.0832747968357e-05 8.62951961993365e-05 -1.77162647862906e-05 0.000857926040982384 509 509 0 0 0 509 509 0 0 0 0 0 0 0 0 19 19 0 0 0 168 169 0 0 316 +80 53 0.995482060289926 -0.0810350035155074 -0.0494853093974991 -2.37146684726841 0.0804345040667699 0.996661413424593 -0.014011336339769 0.018223010645677 0.0504555070974149 0.00996770764694982 0.998676567567202 0.933213995334879 0.000208815460234592 -8.47330837537086e-05 1.49048367577089e-06 -1.53478340900994e-05 4.0991866043745e-05 0.000108549930355389 -8.47330837537086e-05 0.00104731181154032 2.45690054922756e-05 -0.00124728026883855 1.18083350709097e-05 -0.000917278960719361 1.49048367577089e-06 2.45690054922756e-05 2.03549270218909e-05 -3.77008618503229e-05 5.08317920366555e-08 -2.65337201801048e-05 -1.53478340900994e-05 -0.00124728026883855 -3.77008618503229e-05 0.00187697568548842 -4.18526226479509e-05 0.00123998702798228 4.0991866043745e-05 1.18083350709097e-05 5.08317920366555e-08 -4.18526226479509e-05 3.38035148727511e-05 -8.57244383096142e-06 0.000108549930355389 -0.000917278960719361 -2.65337201801048e-05 0.00123998702798228 -8.57244383096142e-06 0.00148210002781149 423 423 0 0 0 424 424 0 0 0 0 0 0 0 0 11 11 0 0 0 121 121 0 0 290 +80 6 0.995675926864679 -0.0920701206187058 0.0123507712884652 -2.33059449226406 0.0921811005790184 0.995703916420219 -0.00873816465161656 0.0208711180152418 -0.0114931874692748 0.00983888787896495 0.999885544913567 0.917306302743562 0.000120274090621865 -0.000104548997825614 2.49950885607224e-06 0.000129984722935411 1.01299117621673e-05 0.000115443381965643 -0.000104548997825614 0.00116562464409951 1.77672585245608e-05 -0.000224021304379234 1.09503684798419e-06 0.000151231829228323 2.49950885607224e-06 1.77672585245608e-05 1.54623082198617e-05 7.94655080031143e-06 2.8857662514323e-06 3.73673996216169e-05 0.000129984722935411 -0.000224021304379234 7.94655080031143e-06 0.00115179118911385 -3.66348738496792e-05 0.001350078387339 1.01299117621673e-05 1.09503684798419e-06 2.8857662514323e-06 -3.66348738496792e-05 2.11835093843722e-05 -8.8958965845468e-05 0.000115443381965643 0.000151231829228323 3.73673996216169e-05 0.001350078387339 -8.8958965845468e-05 0.00507336198022219 496 496 0 0 0 497 497 0 0 0 0 0 0 0 0 23 23 0 0 0 257 259 0 0 318 +80 84 0.993558909382526 0.113287504576942 0.0025758286697258 0.592409450406091 -0.113087589251564 0.992738147847282 -0.0410142288238841 -0.0220277435861028 -0.00720352301836103 0.0404587582048393 0.999155242262506 0.0167574956130478 6.78482671051626e-05 -1.73974387851898e-05 -4.37909070614436e-06 -2.93304589912491e-05 2.03089011880666e-06 -2.24859562633713e-06 -1.73974387851898e-05 4.12674693830078e-05 -2.81599978496733e-06 2.14137673008298e-05 2.4318650173383e-06 1.44865848033975e-05 -4.37909070614436e-06 -2.81599978496733e-06 1.74621559734967e-05 5.46030461887824e-06 -5.84636216072681e-07 -2.16985321194216e-06 -2.93304589912491e-05 2.14137673008298e-05 5.46030461887824e-06 0.000211469782796007 1.3137619677441e-05 0.000127978226040072 2.03089011880666e-06 2.4318650173383e-06 -5.84636216072681e-07 1.3137619677441e-05 2.24732647955013e-05 3.20346558648634e-05 -2.24859562633713e-06 1.44865848033975e-05 -2.16985321194216e-06 0.000127978226040072 3.20346558648634e-05 0.000405243158684785 3261 3249 0 1603 411 3261 3249 0 1428 449 0 0 0 0 0 0 0 0 2035 0 0 0 0 0 3429 +81 83 0.998258137553883 0.0532124689888397 -0.0254779110518069 0.294818454490614 -0.0545371434184974 0.997024432900562 -0.0544791720482577 0.00482593272917445 0.0225031285647631 0.0557737693134074 0.998189809535928 -0.0498420640537873 5.09077686377414e-05 -1.73507823518122e-05 3.99544655876414e-06 5.39134896985772e-07 -9.94614308424068e-07 2.30918706632638e-06 -1.73507823518122e-05 3.28620768526684e-05 -1.80043328724099e-06 1.63043777881796e-06 -2.64298681255339e-07 -1.36439638267223e-05 3.99544655876414e-06 -1.80043328724099e-06 1.32672062980591e-05 -3.94783574670259e-06 2.57539259717989e-06 -2.12547094497803e-06 5.39134896985772e-07 1.63043777881796e-06 -3.94783574670259e-06 0.000106051146560776 4.7068051539725e-06 -1.45675336585945e-05 -9.94614308424068e-07 -2.64298681255339e-07 2.57539259717989e-06 4.7068051539725e-06 1.37429826595568e-05 2.89254545663653e-06 2.30918706632638e-06 -1.36439638267223e-05 -2.12547094497803e-06 -1.45675336585945e-05 2.89254545663653e-06 0.000158614592738187 3290 3265 0 609 173 3290 3265 0 498 208 0 0 0 0 0 0 0 0 2445 0 0 0 0 0 3650 +82 54 0.988050762345155 -0.137957133547173 -0.0687278715850045 -2.63306014009048 0.139335335945492 0.990121470237375 0.0156568940705464 -0.110238405025146 0.0658889610338058 -0.025046027198476 0.997512577031217 0.829160137314659 0.000228535409769395 -0.000255675843328408 3.36524523162759e-06 0.000214335346492257 4.521486221122e-05 0.000101915346883857 -0.000255675843328408 0.00114359479724618 -2.24610315170333e-05 0.000765832182513266 -6.23920653245059e-05 -0.00124183592872125 3.36524523162759e-06 -2.24610315170333e-05 2.39947046686718e-05 2.54678302861086e-05 -3.65344284561065e-06 5.31130962576523e-06 0.000214335346492257 0.000765832182513266 2.54678302861086e-05 0.00456623015900289 -4.67160086957015e-05 -0.00193171930329014 4.521486221122e-05 -6.23920653245059e-05 -3.65344284561065e-06 -4.67160086957015e-05 3.74936873091896e-05 5.5611395063466e-05 0.000101915346883857 -0.00124183592872125 5.31130962576523e-06 -0.00193171930329014 5.5611395063466e-05 0.00190473692370752 408 408 0 0 0 408 408 0 0 0 0 0 0 0 0 42 42 0 0 0 216 217 0 0 114 +81 5 0.990868797231753 -0.131119926634456 -0.0314100543118729 -2.52077324268171 0.13129833976466 0.991336078797076 0.00367761475436803 -0.0691900071745123 0.0306557114995527 -0.00776812169140912 0.999499816727269 0.895788250468693 0.000198775905234342 -0.000170033971897743 -2.68347796378393e-06 0.000122059432369129 2.24479290676043e-05 0.000129604282718064 -0.000170033971897743 0.000569840140465502 -4.28166656316543e-06 -0.000381499987700289 1.12114776397743e-05 -0.000580679616482296 -2.68347796378393e-06 -4.28166656316543e-06 1.49289343859449e-05 8.1371284427271e-07 2.89076892113018e-06 9.33380586394102e-07 0.000122059432369129 -0.000381499987700289 8.1371284427271e-07 0.000403634391617268 -6.84908112786044e-06 0.000365478388442626 2.24479290676043e-05 1.12114776397743e-05 2.89076892113018e-06 -6.84908112786044e-06 2.47134224769888e-05 -2.10513292485377e-05 0.000129604282718064 -0.000580679616482296 9.33380586394102e-07 0.000365478388442626 -2.10513292485377e-05 0.000720878447000897 425 425 0 0 0 425 425 0 0 0 0 0 0 0 0 17 17 0 0 0 158 158 0 0 178 +82 3 0.987899959352011 -0.155075133648998 0.00231802416718699 -2.66854300599905 0.154837984692833 0.987024699967853 0.0425139994546787 -0.106911009082459 -0.00888081125552371 -0.041640660142652 0.999093182147855 0.936408163041185 0.000128939780694304 -0.000202919278773875 -2.35830691301419e-06 0.000183155867661466 1.26232633810707e-05 3.05261041216412e-05 -0.000202919278773875 0.00114424777864171 3.75336380240967e-06 -0.000637409998458647 2.0442324568593e-05 -0.0011608629043724 -2.35830691301419e-06 3.75336380240967e-06 1.82254494743773e-05 -1.59330532583041e-05 -3.42490412306649e-07 2.10135802223389e-06 0.000183155867661466 -0.000637409998458647 -1.59330532583041e-05 0.00213465914468612 -4.48204795115127e-05 0.000517133556896863 1.26232633810707e-05 2.0442324568593e-05 -3.42490412306649e-07 -4.48204795115127e-05 2.33762042396028e-05 -7.41511885010175e-05 3.05261041216412e-05 -0.0011608629043724 2.10135802223389e-06 0.000517133556896863 -7.41511885010175e-05 0.00205709834331666 422 422 0 0 0 423 423 0 0 0 0 0 0 0 0 49 49 0 0 0 267 268 0 0 97 +83 2 0.982608031565362 -0.185450766983356 -0.00945882278768826 -2.7928766648266 0.185679888444545 0.980691580583011 0.0613759138491403 -0.173952741395041 -0.00210602242751486 -0.0620647790528637 0.998069901294821 0.993550520414099 0.000169291341582418 -9.79390253131455e-05 -3.09157722147142e-06 0.000174919925531458 2.46135063099373e-05 5.40968963737603e-05 -9.79390253131455e-05 0.00129490238218186 2.82219964752355e-05 -0.000502225329588129 5.63916086465143e-05 -0.00146644857342507 -3.09157722147142e-06 2.82219964752355e-05 2.22469852813041e-05 -1.87548235003909e-05 2.04335363240388e-06 -3.20549398834569e-05 0.000174919925531458 -0.000502225329588129 -1.87548235003909e-05 0.000617048303722802 5.82527782045871e-06 0.000431721099699948 2.46135063099373e-05 5.63916086465143e-05 2.04335363240388e-06 5.82527782045871e-06 2.97233783513492e-05 -7.32233982230522e-05 5.40968963737603e-05 -0.00146644857342507 -3.20549398834569e-05 0.000431721099699948 -7.32233982230522e-05 0.00181628465774287 404 404 0 0 0 405 405 0 0 0 0 0 0 0 0 39 39 0 0 0 158 158 0 0 17 +82 55 0.989051202005604 -0.128132498935555 -0.0732105356338862 -2.644677167474 0.128686363233034 0.991681162393313 0.00287959582272643 -0.131784773516781 0.072232539268159 -0.0122692652908252 0.997312350971398 0.732989237949399 0.0001507905311655 -0.000193898776707251 6.90759503777787e-06 0.000199919312024568 3.24373652497371e-05 0.00027273016885071 -0.000193898776707251 0.000623402020448843 -1.26444818116917e-05 -0.000659791781290126 -4.11804326617688e-05 -0.00100216882475952 6.90759503777787e-06 -1.26444818116917e-05 2.30966457820889e-05 3.25051487315736e-05 -1.25558403244376e-06 3.5177178438078e-05 0.000199919312024568 -0.000659791781290126 3.25051487315736e-05 0.00214295826427805 2.90131170009332e-05 0.00191881346505686 3.24373652497371e-05 -4.11804326617688e-05 -1.25558403244376e-06 2.90131170009332e-05 2.72787120797486e-05 5.24129891236227e-05 0.00027273016885071 -0.00100216882475952 3.5177178438078e-05 0.00191881346505686 5.24129891236227e-05 0.0024095111121124 388 388 0 0 0 389 389 0 0 0 0 0 0 0 0 48 48 0 0 0 276 279 0 0 153 +83 87 0.998445198285888 -0.0490982580913185 -0.0263921782400059 0.564828239141101 0.0500832207447614 0.998019839307647 0.038053532663466 0.0348075566205352 0.0244715553180722 -0.0393161722543822 0.998927115248945 0.0211956688982431 5.90454951492507e-05 -2.40298790415663e-05 -3.00752354778588e-06 -3.17319311844772e-05 1.56167861869883e-06 1.89241478843854e-06 -2.40298790415663e-05 7.09605251148609e-05 2.86063900253884e-06 2.66910162386016e-05 1.95342653817887e-06 4.48644501657947e-05 -3.00752354778588e-06 2.86063900253884e-06 1.6296931431003e-05 8.85593977420704e-06 1.53539485896068e-06 3.71598345409507e-06 -3.17319311844772e-05 2.66910162386016e-05 8.85593977420704e-06 0.000187537828917686 -2.77541388472876e-06 0.000117175277598565 1.56167861869883e-06 1.95342653817887e-06 1.53539485896068e-06 -2.77541388472876e-06 1.51318538390439e-05 1.35587582151188e-05 1.89241478843854e-06 4.48644501657947e-05 3.71598345409507e-06 0.000117175277598565 1.35587582151188e-05 0.000428693749235026 3115 3090 0 792 882 3115 3090 0 678 936 0 0 0 0 0 0 0 0 2893 0 0 0 0 0 2910 +84 87 0.997045387766438 -0.0679563437300754 -0.0358110329439398 0.430069703815103 0.0687219053444549 0.997423197158143 0.0205977061017948 0.0455061108907795 0.0343190101765754 -0.0229978502836237 0.999146287799155 0.0382746212348508 4.65058054041837e-05 -1.23321214865199e-05 -5.08144091450277e-06 -3.7766597731722e-05 2.5034270782753e-06 3.76080472659292e-05 -1.23321214865199e-05 3.8181887238554e-05 -1.93181175522196e-06 -1.20137618102855e-05 9.69861927979196e-07 -2.46843123573204e-05 -5.08144091450277e-06 -1.93181175522196e-06 1.90590545396785e-05 9.17741360673928e-07 -4.11452712699869e-06 -5.36254365692439e-07 -3.7766597731722e-05 -1.20137618102855e-05 9.17741360673928e-07 0.000219569394688928 5.63364915545684e-06 -4.31686120802876e-05 2.5034270782753e-06 9.69861927979196e-07 -4.11452712699869e-06 5.63364915545684e-06 1.73263985187809e-05 -1.49371770137078e-06 3.76080472659292e-05 -2.46843123573204e-05 -5.36254365692439e-07 -4.31686120802876e-05 -1.49371770137078e-06 0.00014874286316636 3227 3202 0 401 725 3227 3202 0 290 787 0 0 0 0 0 0 0 0 3306 0 0 0 0 0 3057 +84 58 0.991749714160622 -0.0927135222106462 -0.0885251786873123 -2.82842829202335 0.0924460533332106 0.995692198849102 -0.00712547360906397 -0.30993504049948 0.0888044575763949 -0.00111711697521103 0.996048452819553 0.371718102329983 0.000141276168840138 -0.000144445116379999 2.22764327759935e-06 5.27729145198471e-05 1.45196229827011e-05 1.70519300848525e-05 -0.000144445116379999 0.000580057678064241 -2.04998117460869e-05 -9.13518298216396e-05 -2.28445630659727e-05 -0.000349310136027921 2.22764327759935e-06 -2.04998117460869e-05 2.13270170670801e-05 9.71127433416281e-06 2.72163840110875e-06 1.51096181770573e-05 5.27729145198471e-05 -9.13518298216396e-05 9.71127433416281e-06 0.000500272111821552 3.99413873081692e-05 -2.95674523380929e-05 1.45196229827011e-05 -2.28445630659727e-05 2.72163840110875e-06 3.99413873081692e-05 1.79681219404837e-05 4.09070508588836e-06 1.70519300848525e-05 -0.000349310136027921 1.51096181770573e-05 -2.95674523380929e-05 4.09070508588836e-06 0.000484606617952276 394 394 0 0 0 394 394 0 0 0 0 0 0 0 0 101 101 0 0 0 373 379 0 0 36 +86 89 0.989408439587995 -0.127968087682195 -0.0685208596488024 0.41554135588819 0.127488322082953 0.991775155662826 -0.0113476139540981 0.0748787439586768 0.0694094187018033 0.00249181559106387 0.997585145965264 0.0268760757361039 5.430547321606e-05 -1.4520159891294e-05 -1.05575470905182e-06 1.75538939522719e-05 -1.601337173517e-06 6.35323201998459e-06 -1.4520159891294e-05 2.82089116503106e-05 1.02329769280107e-06 -7.37241047044002e-06 -2.88424120692243e-07 -2.074489008085e-05 -1.05575470905182e-06 1.02329769280107e-06 1.60822750299152e-05 -2.13132970360507e-06 3.12635517813043e-06 2.38110408516287e-07 1.75538939522719e-05 -7.37241047044002e-06 -2.13132970360507e-06 0.000191056365468252 1.06921380624682e-07 4.09075560563133e-05 -1.601337173517e-06 -2.88424120692243e-07 3.12635517813043e-06 1.06921380624682e-07 1.28778306718791e-05 5.99287332058003e-07 6.35323201998459e-06 -2.074489008085e-05 2.38110408516287e-07 4.09075560563133e-05 5.99287332058003e-07 9.9258160374252e-05 3129 3069 0 199 871 3129 3069 0 93 923 0 0 0 0 0 0 0 0 3487 0 0 0 0 0 2894 +86 59 0.99807741871805 -0.0318241865464563 -0.0531854058532086 -3.11014257174355 0.0304373382182898 0.999180388395258 -0.0266855745391802 -0.23366820917841 0.0539910611796026 0.025015447166842 0.998228026412675 0.147998840428707 9.12159301550419e-05 -5.42183497303646e-05 2.96573426261213e-06 1.35099373218291e-05 2.89119567368052e-06 7.11910547466653e-06 -5.42183497303646e-05 0.000197509306441999 -9.39259968715042e-06 -7.2998083934666e-05 -1.1267025939153e-05 -0.000185030436851319 2.96573426261213e-06 -9.39259968715042e-06 1.88605564463442e-05 1.80713903063551e-06 5.54357186369572e-06 9.17357329788279e-06 1.35099373218291e-05 -7.2998083934666e-05 1.80713903063551e-06 0.00017789187470063 1.31754689663881e-05 7.3758237886333e-05 2.89119567368052e-06 -1.1267025939153e-05 5.54357186369572e-06 1.31754689663881e-05 1.31111652045746e-05 1.92853859099254e-05 7.11910547466653e-06 -0.000185030436851319 9.17357329788279e-06 7.3758237886333e-05 1.92853859099254e-05 0.000462267093587227 504 504 0 0 0 505 505 0 0 0 0 0 0 0 0 119 119 0 0 0 581 581 0 0 0 +86 88 0.995376270541622 -0.0763472398452901 -0.0582853241447394 0.280847060348891 0.0762869036424529 0.997080569563287 -0.0032628410929251 0.0440775455070555 0.0583642731069162 -0.00119865230835313 0.998294633290866 -0.0108156015857525 8.52383179068169e-05 -6.22293701388995e-05 -2.63006668111309e-06 2.48834009776345e-05 2.62070593117343e-06 5.24835430492901e-05 -6.22293701388995e-05 0.000211090704702654 -4.80965092604568e-06 -1.75437635320344e-05 -4.02860200653793e-07 -0.000182777326171637 -2.63006668111309e-06 -4.80965092604568e-06 1.45701979771609e-05 -1.29187607319459e-06 2.78915595655978e-06 1.48433701154265e-07 2.48834009776345e-05 -1.75437635320344e-05 -1.29187607319459e-06 0.000110501846471382 -2.67752105911732e-06 4.51867862341312e-06 2.62070593117343e-06 -4.02860200653793e-07 2.78915595655978e-06 -2.67752105911732e-06 1.21199582761036e-05 8.01080523172586e-07 5.24835430492901e-05 -0.000182777326171637 1.48433701154265e-07 4.51867862341312e-06 8.01080523172586e-07 0.000314658329742899 2948 2911 0 113 520 2948 2911 0 35 568 0 0 0 0 0 0 0 0 3590 0 0 0 0 0 3272 +86 90 0.986535526954905 -0.152558040789735 -0.0589380882469489 0.580877277389525 0.152349276173927 0.988293964112863 -0.00804602680610132 0.10405174078439 0.0594756429564913 -0.00104148378844726 0.998229213761264 0.0332864518439506 6.43790256589627e-05 -3.54425844439523e-05 9.2017516332207e-07 -1.32684198174679e-05 -1.03085652248894e-06 3.73432018986101e-05 -3.54425844439523e-05 4.67271580252154e-05 5.22788290767279e-07 -1.14786932546746e-05 -5.86385272753805e-07 -3.68200333800535e-05 9.2017516332207e-07 5.22788290767279e-07 1.50316339151237e-05 -1.76332898426368e-06 2.74095924768671e-06 8.79824032173996e-07 -1.32684198174679e-05 -1.14786932546746e-05 -1.76332898426368e-06 0.000312395503332904 -5.99287892212051e-06 -3.82573166677339e-05 -1.03085652248894e-06 -5.86385272753805e-07 2.74095924768671e-06 -5.99287892212051e-06 1.20053409514608e-05 2.47060061515525e-06 3.73432018986101e-05 -3.68200333800535e-05 8.79824032173996e-07 -3.82573166677339e-05 2.47060061515525e-06 0.00012665612428761 2961 2901 0 467 1229 2961 2901 0 342 1284 0 0 0 0 0 0 0 0 3135 0 0 0 0 0 2512 +88 90 0.997065436696705 -0.0762140725431304 -0.0072062536174791 0.299405284460443 0.076243209693693 0.997081784270445 0.00385855564553644 0.0357549934085387 0.00689114797494079 -0.00439666037539872 0.999966590170457 -0.0205617115528698 6.90612919643793e-05 -1.84593402099357e-05 1.21076605416077e-05 2.43816203100981e-05 -1.87876515203699e-06 6.52174775684208e-06 -1.84593402099357e-05 4.66652745598421e-05 -8.57942738022864e-07 -1.93242518371553e-05 -6.26689094613674e-07 -1.98268872114812e-05 1.21076605416077e-05 -8.57942738022864e-07 1.77347314852542e-05 -3.87092200596535e-06 2.22769854924036e-06 -3.48685360309707e-06 2.43816203100981e-05 -1.93242518371553e-05 -3.87092200596535e-06 0.000165081218996707 -3.59526871967859e-06 -8.07716475173589e-06 -1.87876515203699e-06 -6.26689094613674e-07 2.22769854924036e-06 -3.59526871967859e-06 1.30083907052773e-05 5.95370720982273e-06 6.52174775684208e-06 -1.98268872114812e-05 -3.48685360309707e-06 -8.07716475173589e-06 5.95370720982273e-06 0.000218208495685695 3201 3141 0 196 524 3201 3141 0 99 565 0 0 0 0 0 0 0 0 3395 0 0 0 0 0 3240 +89 91 0.999814822260445 -0.0170875156847516 -0.00885087543912303 0.317531883652938 0.0172363343195107 0.999706573288143 0.0170198737863703 0.0100252319925156 0.00855745099556878 -0.0171692787327041 0.999815976017716 0.00606578068428072 7.57773872637401e-05 -1.80482457355979e-05 4.48175936795236e-06 1.001481189198e-05 -4.35921248343972e-07 2.24088248354874e-06 -1.80482457355979e-05 6.6968317402361e-05 -4.77953762674196e-06 -1.43936770627381e-06 -7.56717926874042e-07 -2.62004947328887e-05 4.48175936795236e-06 -4.77953762674196e-06 1.55087113189305e-05 -2.79164161147451e-06 5.47904316418385e-06 2.45105794150788e-06 1.001481189198e-05 -1.43936770627381e-06 -2.79164161147451e-06 0.000171790441577277 -4.20997468356416e-06 -4.56939483721942e-06 -4.35921248343972e-07 -7.56717926874042e-07 5.47904316418385e-06 -4.20997468356416e-06 1.23574264950819e-05 8.26874421704475e-07 2.24088248354874e-06 -2.62004947328887e-05 2.45105794150788e-06 -4.56939483721942e-06 8.26874421704475e-07 0.000290260617112564 3141 3078 0 463 372 3141 3078 0 353 402 0 0 0 0 0 0 0 0 3082 0 0 0 0 0 3397 +90 94 0.980057340897857 0.105245098509299 -0.16855585955994 0.577764366860331 -0.109956603175061 0.993757812441839 -0.0188402661608788 -0.0358279234620662 0.165520856602497 0.0369983709179025 0.985512032691127 0.0234589708652875 7.01103686075928e-05 6.56345157545119e-05 -1.01541606664438e-05 2.38137882749982e-05 -8.36530938470151e-07 -1.08079951050536e-05 6.56345157545119e-05 0.00541468336720822 -7.50323399074158e-05 -0.000852207602422831 -9.29038910547223e-05 -0.00136364794049383 -1.01541606664438e-05 -7.50323399074158e-05 2.03532255728127e-05 2.37916126873952e-05 7.70612779136593e-06 3.21309921949386e-05 2.38137882749982e-05 -0.000852207602422831 2.37916126873952e-05 0.000692053396986156 5.87984549676561e-05 0.000503831054722924 -8.36530938470151e-07 -9.29038910547223e-05 7.70612779136593e-06 5.87984549676561e-05 1.95715216901525e-05 6.00404356179351e-05 -1.08079951050536e-05 -0.00136364794049383 3.21309921949386e-05 0.000503831054722924 6.00404356179351e-05 0.000881040308784988 2810 2783 0 992 346 2810 2783 0 822 384 0 0 0 0 0 0 0 0 2207 0 0 0 0 0 3452 +89 93 0.997607039770163 0.0375315971501631 -0.0580652513675004 0.598606015204441 -0.0384319803754416 0.999156477223403 -0.0144677885988565 -0.00169674743534428 0.0574732727920971 0.0166647303571766 0.998207949115157 -0.00639960142246982 0.00111071076191934 -0.000209777992434413 3.07843516619609e-05 0.00028493312267088 6.80494531915638e-05 5.27102410226751e-05 -0.000209777992434413 9.35781159277909e-05 -8.59896836127648e-06 -5.73075889000111e-05 -1.11026632639004e-05 5.05731468783757e-06 3.07843516619609e-05 -8.59896836127648e-06 1.66596294941642e-05 6.88798310011223e-06 3.92671658794863e-06 2.12216325477396e-06 0.00028493312267088 -5.73075889000111e-05 6.88798310011223e-06 0.000217563008354643 2.32722049500947e-05 5.39380801635544e-05 6.80494531915638e-05 -1.11026632639004e-05 3.92671658794863e-06 2.32722049500947e-05 1.8789699487538e-05 1.87991335288673e-05 5.27102410226751e-05 5.05731468783757e-06 2.12216325477396e-06 5.39380801635544e-05 1.87991335288673e-05 0.000317364381356752 3270 3302 0 1069 617 3270 3302 0 903 653 0 0 0 0 0 0 0 0 2378 0 0 0 0 0 3178 +90 92 0.999175380549422 0.0323084062079691 -0.0245911730549389 0.316479832263485 -0.0321789923009163 0.999466206870538 0.00564037040594253 -0.0104120812944632 0.0247602778339554 -0.00484440007839195 0.999681679550779 0.0411494241418733 4.91300183121229e-05 -2.33374998056799e-06 9.79329919663837e-06 2.01920911222249e-06 2.2693388705762e-06 -7.81207783871857e-06 -2.33374998056799e-06 7.49631893264881e-05 -2.55952653406895e-07 -1.73942621711241e-05 1.98009668121362e-06 2.17045701536294e-05 9.79329919663837e-06 -2.55952653406895e-07 1.67608056542769e-05 -1.8913014103301e-06 3.61828978689313e-06 -6.06420801714371e-06 2.01920911222249e-06 -1.73942621711241e-05 -1.8913014103301e-06 0.000112514847285331 -3.95261810098538e-06 -4.61671348573604e-05 2.2693388705762e-06 1.98009668121362e-06 3.61828978689313e-06 -3.95261810098538e-06 1.23630156217598e-05 4.30615494690316e-06 -7.81207783871857e-06 2.17045701536294e-05 -6.06420801714371e-06 -4.61671348573604e-05 4.30615494690316e-06 0.000350520970173572 3143 3169 0 636 215 3143 3169 0 516 243 0 0 0 0 0 0 0 0 3085 0 0 0 0 0 3572 +91 65 0.989765667023952 0.10337969556663 0.0983695223388906 -3.42137223473931 -0.100822642572592 0.994432707503628 -0.0306330702294639 0.178949420994159 -0.100988707909895 0.0204016859978464 0.994678366148141 0.0831464254124337 5.15728856926529e-05 -4.62741895177291e-07 1.29269824704316e-05 -6.25368788766614e-06 1.74370993147822e-06 -1.75494599529434e-05 -4.62741895177291e-07 4.92027868075422e-05 -2.73460030647924e-06 2.30944416283546e-05 7.51131177348942e-07 1.57358214871337e-05 1.29269824704316e-05 -2.73460030647924e-06 1.98315344649628e-05 -2.72431969575765e-06 5.10909065745058e-06 9.07683693686034e-06 -6.25368788766614e-06 2.30944416283546e-05 -2.72431969575765e-06 0.000216856193721899 1.43717551802983e-05 8.40537146751398e-05 1.74370993147822e-06 7.51131177348942e-07 5.10909065745058e-06 1.43717551802983e-05 1.38427706750244e-05 1.82319979873217e-05 -1.75494599529434e-05 1.57358214871337e-05 9.07683693686034e-06 8.40537146751398e-05 1.82319979873217e-05 0.000323141289817012 473 473 0 0 0 472 472 0 0 0 0 0 0 0 0 93 93 0 0 0 351 351 0 0 0 +91 94 0.989308209315594 0.0999911470035183 -0.106165142592537 0.408176185154785 -0.103357959973502 0.994286186232652 -0.026685426304324 -0.0304530974772195 0.102890228354732 0.0373731238706145 0.993990367418751 -0.00156801823745939 5.82496582892465e-05 1.8852936437186e-06 2.82150229873712e-06 1.69657800099818e-06 -1.85546548981874e-06 1.80595350041645e-06 1.8852936437186e-06 3.3340373177238e-05 9.38870705409756e-07 -9.60142090780767e-06 -7.2567956010805e-07 5.75266427083718e-06 2.82150229873712e-06 9.38870705409756e-07 1.62797121607926e-05 1.31835044477623e-07 3.40755860144604e-06 -5.5071415795054e-06 1.69657800099818e-06 -9.60142090780767e-06 1.31835044477623e-07 0.000187930067636324 1.14505523475015e-05 3.92629421842733e-05 -1.85546548981874e-06 -7.2567956010805e-07 3.40755860144604e-06 1.14505523475015e-05 1.33816110879132e-05 9.81333472275331e-06 1.80595350041645e-06 5.75266427083718e-06 -5.5071415795054e-06 3.92629421842733e-05 9.81333472275331e-06 0.000202238632010769 3262 3235 0 617 147 3262 3235 0 476 181 0 0 0 0 0 0 0 0 2694 0 0 0 0 0 3674 +92 95 0.991371851689076 0.0877635065353724 -0.0973623058436271 0.42182977353809 -0.0871187238739212 0.996138714720361 0.0108622735118649 -0.0263718856874823 0.097939673417629 -0.00228647236649155 0.995189726843563 -0.046864282187531 7.21868119026647e-05 1.82479413059907e-05 5.34234913807372e-06 1.60077154373268e-05 1.34356892468473e-06 1.92923889421503e-05 1.82479413059907e-05 0.000106490502827102 7.16594954938246e-06 3.85902276222493e-05 1.93061402407127e-06 0.000191514000720547 5.34234913807372e-06 7.16594954938246e-06 1.63838814449094e-05 4.4014939621678e-06 4.2669174356656e-06 8.3855688965615e-06 1.60077154373268e-05 3.85902276222493e-05 4.4014939621678e-06 0.000121933693798247 -9.30692559305459e-07 0.000211049165543097 1.34356892468473e-06 1.93061402407127e-06 4.2669174356656e-06 -9.30692559305459e-07 1.30023283736691e-05 1.10825266889664e-05 1.92923889421503e-05 0.000191514000720547 8.3855688965615e-06 0.000211049165543097 1.10825266889664e-05 0.000955356014669804 3144 3119 0 485 212 3144 3119 0 490 246 0 0 0 0 0 0 0 0 2718 0 0 0 0 0 3589 +90 93 0.995306713342012 0.0613180821238064 -0.0748641381502483 0.454210083914087 -0.0634825108076752 0.997620880172157 -0.0268802951264457 -0.0195744165329582 0.0730377792507051 0.0315067016551964 0.996831385216645 -0.0186230962586932 5.56494069609797e-05 2.46675451064885e-06 -1.70857569894039e-06 7.97599433762799e-07 -7.62483093219116e-07 5.57562556387117e-06 2.46675451064885e-06 3.84367947541736e-05 -3.56959205647147e-09 -1.236593804437e-05 1.29737300418408e-08 6.99141113109806e-06 -1.70857569894039e-06 -3.56959205647147e-09 1.6156230439993e-05 1.89702875111817e-07 4.0929947019884e-06 3.12436627478051e-06 7.97599433762799e-07 -1.236593804437e-05 1.89702875111817e-07 0.000125505818578427 2.18991037439974e-06 3.01896605337334e-05 -7.62483093219116e-07 1.29737300418408e-08 4.0929947019884e-06 2.18991037439974e-06 1.29848291376846e-05 1.01798203199844e-05 5.57562556387117e-06 6.99141113109806e-06 3.12436627478051e-06 3.01896605337334e-05 1.01798203199844e-05 0.000243115547311625 3206 3245 0 803 310 3206 3245 0 651 342 0 0 0 0 0 0 0 0 2657 0 0 0 0 0 3496 +92 66 0.992715128552307 0.0609591945872765 0.103926176388079 -3.50354736748318 -0.058344644966657 0.997903258694361 -0.0280176496317943 0.0934319894562994 -0.105416203437092 0.0217500087918555 0.994190304303187 0.168090824774618 5.03413893944321e-05 -3.85931744247626e-06 1.04130383422797e-05 2.72680615229093e-07 2.44796527053759e-06 -2.06961203493149e-05 -3.85931744247626e-06 9.36883476674688e-05 -6.2356741286485e-06 -2.82518652853942e-05 -2.72339889392741e-06 6.04439902364762e-05 1.04130383422797e-05 -6.2356741286485e-06 2.36891242163525e-05 8.95459504654393e-06 6.79404192006114e-06 -1.85647686779282e-07 2.72680615229093e-07 -2.82518652853942e-05 8.95459504654393e-06 0.000905616242763002 5.15546658830418e-05 -0.00046230500281924 2.44796527053759e-06 -2.72339889392741e-06 6.79404192006114e-06 5.15546658830418e-05 1.6195562943197e-05 -1.88142493056065e-05 -2.06961203493149e-05 6.04439902364762e-05 -1.85647686779282e-07 -0.00046230500281924 -1.88142493056065e-05 0.00108473119715273 385 385 0 0 0 389 389 0 0 0 0 0 0 0 0 85 85 0 0 0 358 358 0 0 0 +92 94 0.993013848965385 0.0746534988263699 -0.0913802542999992 0.285846732966967 -0.0774349828177675 0.996624212300262 -0.0272764164232618 -0.0167494879353912 0.0890354940400927 0.0341618876800495 0.995442437427284 -0.0108956874574539 6.69964679391352e-05 -8.70217562862459e-06 5.89876530559614e-06 8.72156141111109e-06 -1.78295532054273e-06 -4.1199274096292e-05 -8.70217562862459e-06 9.37826332771781e-05 7.15504330210069e-06 -1.36992027423457e-05 -3.5801245472e-06 1.9309725752596e-05 5.89876530559614e-06 7.15504330210069e-06 1.62726214326338e-05 -2.56211188935244e-06 3.41993462108627e-06 -8.7956123597529e-06 8.72156141111109e-06 -1.36992027423457e-05 -2.56211188935244e-06 6.07294162312064e-05 3.69413392686667e-08 2.49176105000665e-05 -1.78295532054273e-06 -3.5801245472e-06 3.41993462108627e-06 3.69413392686667e-08 1.20200288457022e-05 7.43640898935697e-06 -4.1199274096292e-05 1.9309725752596e-05 -8.7956123597529e-06 2.49176105000665e-05 7.43640898935697e-06 0.000284921051753464 3166 3139 0 368 74 3166 3139 0 366 112 0 0 0 0 0 0 0 0 3061 0 0 0 0 0 3738 +91 95 0.988008637613416 0.111041425201559 -0.107278767193179 0.56135465129506 -0.111201351321404 0.993787668354556 0.00450884582894192 -0.042935006617811 0.10711298457972 0.00747476525531395 0.994218756823066 -0.0101109409707635 5.08955520499005e-05 -1.05284112543414e-06 4.8911955659057e-06 1.21775495214464e-05 1.13075479798179e-06 1.14763320196958e-05 -1.05284112543414e-06 8.63063837120498e-05 4.57247673040832e-06 1.83718126965078e-06 -1.25981148653953e-06 -2.23073989827766e-05 4.8911955659057e-06 4.57247673040832e-06 1.50456801147667e-05 -4.24232405325369e-07 1.85017475737667e-06 -3.91482702839592e-06 1.21775495214464e-05 1.83718126965078e-06 -4.24232405325369e-07 8.56556991672917e-05 3.99506998034262e-07 7.70657975168726e-05 1.13075479798179e-06 -1.25981148653953e-06 1.85017475737667e-06 3.99506998034262e-07 1.27173020816141e-05 5.66089154358414e-06 1.14763320196958e-05 -2.23073989827766e-05 -3.91482702839592e-06 7.70657975168726e-05 5.66089154358414e-06 0.000258948330833613 3007 2982 0 827 321 3007 2982 0 669 359 0 0 0 0 0 0 0 0 2213 0 0 0 0 0 3474 +93 95 0.995900519742129 0.0553976840013154 -0.071507002346954 0.283914148763308 -0.0529059575042721 0.997940123901469 0.0362831747243289 -0.0132229585978142 0.0733697106298848 -0.0323512861384278 0.996779955580607 -0.0526614729721625 7.0704453625624e-05 -1.88810524472237e-05 5.74964693645391e-06 1.00885400491233e-05 3.3112173127573e-06 -3.14622264008578e-05 -1.88810524472237e-05 9.54380183303075e-05 7.86558932766986e-06 -1.61068889058749e-05 -3.98316241433161e-06 5.78073815229548e-05 5.74964693645391e-06 7.86558932766986e-06 2.18813294107709e-05 2.02354968672312e-06 1.90926333421044e-06 -3.64801145326603e-06 1.00885400491233e-05 -1.61068889058749e-05 2.02354968672312e-06 8.96506693285739e-05 -1.7859696811077e-06 3.33105066963434e-05 3.3112173127573e-06 -3.98316241433161e-06 1.90926333421044e-06 -1.7859696811077e-06 1.39172505668061e-05 -3.09101905005778e-06 -3.14622264008578e-05 5.78073815229548e-05 -3.64801145326603e-06 3.33105066963434e-05 -3.09101905005778e-06 0.000386294283493321 3200 3175 0 284 146 3200 3175 0 289 174 0 0 0 0 0 0 0 0 3101 0 0 0 0 0 3604 +96 100 0.981429213660049 -0.131986813980205 -0.139198345931168 0.605241527325918 0.132257058191528 0.991188214712545 -0.00734803194600356 0.0950213669142008 0.138941603320032 -0.0111983905232678 0.990237257891535 -0.0991739188867882 0.000121277754920843 -2.61786387834302e-05 3.33203918696469e-06 3.76352161181777e-05 -6.67391323700514e-07 -1.74152811225119e-05 -2.61786387834302e-05 3.88879627622022e-05 -3.62347699112954e-07 -2.6309739404452e-05 -8.70174093909878e-07 -3.7306122553505e-07 3.33203918696469e-06 -3.62347699112954e-07 2.11005874785327e-05 -1.70323028964885e-06 7.46682075710985e-06 -1.94112051325454e-06 3.76352161181777e-05 -2.6309739404452e-05 -1.70323028964885e-06 0.000280669207043883 -7.12880070508229e-06 2.58386236663313e-05 -6.67391323700514e-07 -8.70174093909878e-07 7.46682075710985e-06 -7.12880070508229e-06 1.51051273479888e-05 -2.71375562186795e-06 -1.74152811225119e-05 -3.7306122553505e-07 -1.94112051325454e-06 2.58386236663313e-05 -2.71375562186795e-06 0.000194576106848604 3028 3048 0 502 1187 3028 3048 0 372 1251 0 0 0 0 0 0 0 0 1693 0 0 0 0 0 2570 +94 96 0.999936150232645 -0.0111812149738979 -0.00163581466723292 0.273207504625113 0.0112559115391016 0.998332099780503 0.0566244028955271 0.0121956143511634 0.000999956670046898 -0.0566392000257643 0.998394211274835 -0.0195462431067154 6.84557598071092e-05 -9.30676548209299e-06 4.25885277408312e-06 4.34268844756072e-06 4.37102206586457e-06 -1.15457234479322e-05 -9.30676548209299e-06 3.52350617046016e-05 3.75471884085021e-06 -1.3090573374524e-06 -1.78267331554717e-06 -2.72959989081404e-06 4.25885277408312e-06 3.75471884085021e-06 1.51638507997193e-05 -4.2783793867461e-06 3.93015838878208e-06 -2.22143795728149e-06 4.34268844756072e-06 -1.3090573374524e-06 -4.2783793867461e-06 9.02004173238858e-05 3.3452009730763e-06 -8.62700127602527e-06 4.37102206586457e-06 -1.78267331554717e-06 3.93015838878208e-06 3.3452009730763e-06 1.29795837041664e-05 -3.42505628345953e-06 -1.15457234479322e-05 -2.72959989081404e-06 -2.22143795728149e-06 -8.62700127602527e-06 -3.42505628345953e-06 0.000151837764747959 3219 3192 0 330 317 3219 3192 0 240 357 0 0 0 0 0 0 0 0 2776 0 0 0 0 0 3487 +93 67 0.997106833145492 0.00347307924076476 0.075933530242936 -3.55630141579596 -0.00507598469769378 0.999768130537281 0.0209265272163876 -0.0114544263440625 -0.0758432440888197 -0.0212514207190202 0.996893263816898 0.256550884268118 6.10793975709809e-05 -6.33617737902419e-06 1.5555181469164e-05 1.40717082738854e-05 5.93504299638886e-06 -4.66608568619611e-06 -6.33617737902419e-06 7.29018714987928e-05 -7.72399749006166e-06 -2.15330984534755e-05 -3.47678611609599e-06 2.0129848219388e-05 1.5555181469164e-05 -7.72399749006166e-06 1.9287840966625e-05 5.68962808095172e-07 7.19314715655392e-06 7.8286129408451e-06 1.40717082738854e-05 -2.15330984534755e-05 5.68962808095172e-07 0.000363414057375693 1.65288796981615e-05 7.86695066126489e-05 5.93504299638886e-06 -3.47678611609599e-06 7.19314715655392e-06 1.65288796981615e-05 1.36462615629649e-05 1.30560208314245e-05 -4.66608568619611e-06 2.0129848219388e-05 7.8286129408451e-06 7.86695066126489e-05 1.30560208314245e-05 0.00042841774658142 400 400 0 0 0 403 403 0 0 0 0 0 0 0 0 87 87 0 0 0 366 366 0 0 0 +95 98 0.994328587784099 -0.0880117452889623 -0.0597042059361871 0.435174482483386 0.0897709896835766 0.995584137115356 0.0274480479361042 0.0625076887568774 0.0570248097455048 -0.0326520843969003 0.997838670556532 -0.058038218131935 8.97081746033126e-05 1.610767435963e-05 -6.86793889628704e-08 3.36259353931449e-05 -4.11521263967641e-06 2.4701062807111e-05 1.610767435963e-05 3.23586142342329e-05 6.91893528441448e-06 1.50290366940259e-05 -2.41513782044303e-06 8.67757774204465e-06 -6.86793889628704e-08 6.91893528441448e-06 1.93624322557164e-05 -5.13206604021413e-06 4.11469248129776e-06 -7.05144483961575e-07 3.36259353931449e-05 1.50290366940259e-05 -5.13206604021413e-06 0.000503475918595975 6.3945964818446e-06 -9.73899374038729e-06 -4.11521263967641e-06 -2.41513782044303e-06 4.11469248129776e-06 6.3945964818446e-06 1.48358207506503e-05 -6.09901854265357e-06 2.4701062807111e-05 8.67757774204465e-06 -7.05144483961575e-07 -9.73899374038729e-06 -6.09901854265357e-06 0.00018040617675374 2910 2879 0 361 798 2910 2879 0 243 857 0 0 0 0 0 0 0 0 2280 0 0 0 0 0 2982 +96 99 0.988835497750196 -0.107964933777997 -0.102703122948796 0.43750659240791 0.107824194504011 0.994145771872105 -0.00693738772008626 0.0721188321925922 0.102850870043398 -0.00421394626572276 0.994687861184696 -0.0669757510033684 8.51604286668369e-05 -2.29242846506094e-05 -3.62039046130979e-06 -4.83454086729337e-06 3.12180752613356e-06 -5.78774449639959e-05 -2.29242846506094e-05 6.36576527701923e-05 -7.07171145539218e-06 6.54727082573483e-06 -1.17754425085417e-06 7.04120498425704e-05 -3.62039046130979e-06 -7.07171145539218e-06 2.02507003617773e-05 -4.94158743718639e-06 3.64296653668613e-06 -8.3408691007809e-07 -4.83454086729337e-06 6.54727082573483e-06 -4.94158743718639e-06 0.00015962682916082 -4.60706190968985e-06 4.1341101969594e-05 3.12180752613356e-06 -1.17754425085417e-06 3.64296653668613e-06 -4.60706190968985e-06 1.48286515270031e-05 -1.13578279451174e-05 -5.78774449639959e-05 7.04120498425704e-05 -8.3408691007809e-07 4.1341101969594e-05 -1.13578279451174e-05 0.000427731332422222 3021 3012 0 309 839 3021 3012 0 200 886 0 0 0 0 0 0 0 0 2146 0 0 0 0 0 2938 +95 99 0.985614942542563 -0.127475358440733 -0.110964940531803 0.566345680787354 0.131818443723293 0.99073454676548 0.0326948885877802 0.0888746758312118 0.105769007422728 -0.0468517965056306 0.993286376747917 -0.0775995928504111 7.57994041710274e-05 -2.22164305720189e-05 3.09609209645031e-06 6.8281463471149e-06 2.187047598643e-07 -9.81523966785226e-06 -2.22164305720189e-05 4.62939516279401e-05 -3.52555088099076e-06 8.99469832673953e-06 -4.62554994795071e-07 3.54165592194615e-05 3.09609209645031e-06 -3.52555088099076e-06 1.8508918161547e-05 4.98599428415629e-06 6.6046267927722e-06 7.83757204138325e-06 6.8281463471149e-06 8.99469832673953e-06 4.98599428415629e-06 0.000248731191064004 -7.04356630107448e-06 6.95548284838734e-05 2.187047598643e-07 -4.62554994795071e-07 6.6046267927722e-06 -7.04356630107448e-06 1.51373726992784e-05 -4.66377530307125e-06 -9.81523966785226e-06 3.54165592194615e-05 7.83757204138325e-06 6.95548284838734e-05 -4.66377530307125e-06 0.000267758456281071 2937 2928 0 481 1125 2937 2928 0 360 1179 0 0 0 0 0 0 0 0 1800 0 0 0 0 0 2645 +98 100 0.99521365188553 -0.0625794997525105 -0.0750572668793166 0.299660785282652 0.062184892991363 0.998035822543557 -0.00758524907030422 0.0279416513194426 0.0753845221800878 0.00288151531860431 0.997150375161715 -0.0581331717818408 7.00726060987583e-05 -1.16065643614084e-05 -1.34473853096418e-05 3.18705547939086e-06 7.5774272204866e-06 -3.4814036403206e-05 -1.16065643614084e-05 7.10320689898483e-05 1.77582212518059e-05 -1.99614805391517e-05 -1.37945771850951e-07 7.51017226292243e-05 -1.34473853096418e-05 1.77582212518059e-05 2.62446738594224e-05 -1.65920667721443e-05 2.71070122770971e-06 1.34590313401181e-05 3.18705547939086e-06 -1.99614805391517e-05 -1.65920667721443e-05 0.000271616616024892 -8.55495319580111e-06 -3.32545583929628e-05 7.5774272204866e-06 -1.37945771850951e-07 2.71070122770971e-06 -8.55495319580111e-06 1.78701197656659e-05 -1.44309426826474e-05 -3.4814036403206e-05 7.51017226292243e-05 1.34590313401181e-05 -3.32545583929628e-05 -1.44309426826474e-05 0.000337958631459225 3464 3474 0 245 473 3464 3474 0 158 505 0 0 0 0 0 0 0 0 2481 0 0 0 0 0 3322 +95 97 0.998333019735372 -0.0525738091041165 -0.0238154635129734 0.291055953442771 0.0532867444278066 0.998117579063506 0.0303615090647955 0.035645255402651 0.0221744126041588 -0.0315799455460257 0.999255223886756 -0.00546205567947314 5.36250766058379e-05 -3.7394564922149e-06 2.56345398683253e-06 1.51021243538609e-05 1.11173625251118e-06 5.3902266068962e-06 -3.7394564922149e-06 2.30287516014964e-05 -9.65284882831305e-10 -7.52477920052821e-07 -9.17743304952087e-07 1.04435402706288e-05 2.56345398683253e-06 -9.65284882831305e-10 1.70017325681613e-05 -7.07836777539835e-06 3.58900228793784e-06 -1.07535493865332e-06 1.51021243538609e-05 -7.52477920052821e-07 -7.07836777539835e-06 0.000143560783605852 5.43789608411327e-06 2.50600679458551e-05 1.11173625251118e-06 -9.17743304952087e-07 3.58900228793784e-06 5.43789608411327e-06 1.4320440569508e-05 1.50561344078708e-06 5.3902266068962e-06 1.04435402706288e-05 -1.07535493865332e-06 2.50600679458551e-05 1.50561344078708e-06 0.00011130971584784 3444 3409 0 205 471 3444 3409 0 116 525 0 0 0 0 0 0 0 0 2716 0 0 0 0 0 3322 +97 101 0.988212451131107 -0.0955259813544403 -0.119628334084029 0.567528153232679 0.0928202875258122 0.995289052321925 -0.0280017240853055 0.0687722163056629 0.121739663434209 0.0165677160283232 0.992423783034511 -0.0588704729740027 9.4609546472266e-05 -3.55596536681486e-06 2.96880094986662e-06 4.04824651378974e-05 -3.78860525177812e-06 -1.29076840848847e-05 -3.55596536681486e-06 2.86514864895065e-05 -4.49691535185328e-06 -7.68456646318147e-06 -1.62072312875126e-07 2.62047690667929e-06 2.96880094986662e-06 -4.49691535185328e-06 2.00658893781363e-05 1.27288544405647e-05 6.20126982765027e-06 -1.18261766544823e-06 4.04824651378974e-05 -7.68456646318147e-06 1.27288544405647e-05 0.000730335854322227 -4.02656384290803e-05 -8.96144797178654e-05 -3.78860525177812e-06 -1.62072312875126e-07 6.20126982765027e-06 -4.02656384290803e-05 1.70538358167947e-05 4.75827517866757e-06 -1.29076840848847e-05 2.62047690667929e-06 -1.18261766544823e-06 -8.96144797178654e-05 4.75827517866757e-06 0.000136752036226493 3285 3297 0 364 981 3285 3297 0 206 1032 0 0 0 0 0 0 0 0 1580 0 0 0 0 0 2760 +99 101 0.998746383873486 -0.0192574856290915 -0.04620400358065 0.291510796223621 0.0184127373838189 0.999656711009161 -0.0186395074071719 0.00682892116168603 0.046547092300915 0.0177653984360844 0.998758108260823 -0.034117502698216 6.34963257695164e-05 -9.29473003410149e-06 -1.09108518504211e-05 3.01463173717718e-06 6.3671300900917e-06 -6.36126773759159e-06 -9.29473003410149e-06 9.58008752948887e-05 1.16594129251783e-05 4.27449767261739e-06 -3.95906824056584e-06 8.80205098329403e-05 -1.09108518504211e-05 1.16594129251783e-05 2.52033671741779e-05 -8.36385670215493e-06 1.75712536362258e-06 1.31143672116663e-05 3.01463173717718e-06 4.27449767261739e-06 -8.36385670215493e-06 0.000139878658027246 -1.18146631125918e-06 5.39200091269416e-05 6.3671300900917e-06 -3.95906824056584e-06 1.75712536362258e-06 -1.18146631125918e-06 1.59054955244053e-05 -1.2017917612695e-05 -6.36126773759159e-06 8.80205098329403e-05 1.31143672116663e-05 5.39200091269416e-05 -1.2017917612695e-05 0.000315762775308609 3440 3449 0 324 330 3440 3449 0 252 360 0 0 0 0 0 0 0 0 2347 0 0 0 0 0 3444 +97 99 0.99349442301098 -0.0718936555766961 -0.0883183657791459 0.277059123666617 0.0718031424621727 0.997409956926077 -0.0042055388808711 0.042023503867825 0.0883919689713752 -0.00216335677616502 0.996083420055179 -0.087024013529617 7.49457876721942e-05 -1.83183278689338e-05 -9.58739883086914e-06 3.8276928806845e-05 5.70161425623379e-06 -3.03265423482968e-05 -1.83183278689338e-05 8.0995150396504e-05 5.26486021993597e-06 -1.98169156519579e-06 -2.5883881084976e-06 6.65089789420574e-05 -9.58739883086914e-06 5.26486021993597e-06 2.32415388624015e-05 -1.65633128252317e-05 2.59827601293459e-06 4.14248719851173e-06 3.8276928806845e-05 -1.98169156519579e-06 -1.65633128252317e-05 0.000275699268204314 -6.85312812730569e-06 6.72338959099879e-05 5.70161425623379e-06 -2.5883881084976e-06 2.59827601293459e-06 -6.85312812730569e-06 1.64245531221421e-05 -1.49874065328614e-05 -3.03265423482968e-05 6.65089789420574e-05 4.14248719851173e-06 6.72338959099879e-05 -1.49874065328614e-05 0.000383981675386933 3235 3223 0 147 484 3235 3223 0 39 526 0 0 0 0 0 0 0 0 2636 0 0 0 0 0 3298 +98 101 0.994037972734853 -0.0596734293222543 -0.0912556332184812 0.466192838690711 0.0578321839966371 0.998068389329768 -0.0226920407822074 0.033948889674181 0.0924334747554324 0.0172792376453412 0.995568923124378 -0.0511891934008144 8.36985033491969e-05 6.85022249397236e-06 5.86199086591796e-06 -3.19184494362601e-05 2.43097706737148e-06 1.82212049095494e-05 6.85022249397236e-06 2.95520484290079e-05 2.49643313123752e-06 4.38731337270792e-06 1.01005632972387e-06 -8.65201895469723e-06 5.86199086591796e-06 2.49643313123752e-06 2.25425948761606e-05 -1.88786847176307e-05 5.15267784669478e-06 5.61216839666973e-07 -3.19184494362601e-05 4.38731337270792e-06 -1.88786847176307e-05 0.000315933763121751 -1.05226584759808e-05 -6.94176089746201e-05 2.43097706737148e-06 1.01005632972387e-06 5.15267784669478e-06 -1.05226584759808e-05 1.49192233863644e-05 -9.20340138683919e-08 1.82212049095494e-05 -8.65201895469723e-06 5.61216839666973e-07 -6.94176089746201e-05 -9.20340138683919e-08 0.000108241424450752 3443 3452 0 449 689 3443 3452 0 343 733 0 0 0 0 0 0 0 0 1714 0 0 0 0 0 3041 +101 103 0.994292917419111 0.103722962966483 -0.0249627987943337 0.283758423133016 -0.104326658110361 0.994247805951073 -0.024233216233128 -0.0356924985525337 0.0223056669417569 0.0266992006421792 0.99939462171224 -0.0865281964697679 8.28574171860672e-05 7.88302691751274e-06 2.94150128696169e-06 1.87399080516086e-05 4.31692657602337e-06 2.16960319649886e-05 7.88302691751274e-06 4.11918380681806e-05 -3.77761772264967e-07 9.75204654853618e-07 2.0656172489218e-06 5.44475067749583e-06 2.94150128696169e-06 -3.77761772264967e-07 2.56902682871806e-05 -1.81017482388558e-05 4.49389786680887e-07 -3.55714430076664e-06 1.87399080516086e-05 9.75204654853618e-07 -1.81017482388558e-05 0.00022535745275587 2.05845723793033e-05 -1.26463830482953e-05 4.31692657602337e-06 2.0656172489218e-06 4.49389786680887e-07 2.05845723793033e-05 2.00404712425761e-05 -5.64694914709335e-08 2.16960319649886e-05 5.44475067749583e-06 -3.55714430076664e-06 -1.26463830482953e-05 -5.64694914709335e-08 9.76925370073404e-05 3538 3481 0 529 4 3541 3497 0 526 11 0 0 0 0 0 0 0 0 2499 0 0 8 0 0 3831 +100 104 0.987458082503438 0.149631803122029 -0.0503672392839231 0.534811454335559 -0.150592005307467 0.988469402899081 -0.0158204762826492 -0.0595667941751734 0.0474192285482325 0.0232069607399229 0.998605454489963 -0.12776910492835 9.41996551227631e-05 8.5976935717301e-06 1.61264146804093e-05 2.03566705764646e-05 -1.35040465443018e-06 -3.22530317326545e-05 8.5976935717301e-06 5.28291231004155e-05 1.70270461256922e-06 -3.70303650432933e-06 -6.71127088869863e-07 2.86233241708898e-06 1.61264146804093e-05 1.70270461256922e-06 2.52158920887656e-05 -3.00839637277214e-06 -1.67820601014504e-06 1.49398634625392e-06 2.03566705764646e-05 -3.70303650432933e-06 -3.00839637277214e-06 0.00035419529217867 3.44373162762655e-05 -0.000185326773300512 -1.35040465443018e-06 -6.71127088869863e-07 -1.67820601014504e-06 3.44373162762655e-05 2.37256347102978e-05 -2.04555776929322e-05 -3.22530317326545e-05 2.86233241708898e-06 1.49398634625392e-06 -0.000185326773300512 -2.04555776929322e-05 0.000264197480345819 3418 3391 0 932 156 3418 3391 0 923 188 0 0 0 0 0 0 0 0 1943 0 0 0 0 0 3584 +103 105 0.995183806941954 0.0751379446338737 0.0629561726657243 0.255482345779203 -0.0787739703151293 0.995237915459917 0.0574121348827097 -0.0236641043586869 -0.0583425402370405 -0.0620949346339639 0.996363571740503 -0.0849552456040253 7.58253512934269e-05 1.08996166015775e-05 2.66416279605554e-06 -6.06889532910497e-07 -1.52715091451228e-06 2.0512572407973e-05 1.08996166015775e-05 3.25688714369217e-05 5.16351656916675e-06 7.05395376750596e-07 4.35230264035344e-07 1.46173639914248e-05 2.66416279605554e-06 5.16351656916675e-06 1.9096627717725e-05 -1.11421025694037e-05 -2.97083575880065e-06 2.22809534813304e-06 -6.06889532910497e-07 7.05395376750596e-07 -1.11421025694037e-05 8.66627392986273e-05 1.40947495029776e-05 -6.66658697132127e-06 -1.52715091451228e-06 4.35230264035344e-07 -2.97083575880065e-06 1.40947495029776e-05 2.01573776318567e-05 -4.95301639975696e-06 2.0512572407973e-05 1.46173639914248e-05 2.22809534813304e-06 -6.66658697132127e-06 -4.95301639975696e-06 0.000112899060889956 3576 3565 0 615 58 3576 3565 0 514 95 0 0 0 0 0 0 0 0 2532 0 0 0 0 0 3779 +100 103 0.993410128489447 0.107260524976016 -0.0403917862497934 0.430676428107034 -0.108481329598966 0.993665195558109 -0.0293475768148873 -0.0408385060431975 0.0369880756869035 0.033535934731786 0.998752833957754 -0.0513028338310959 8.94958966467119e-05 3.08467289109717e-05 9.06546092050847e-06 2.38893724673605e-05 2.25613561793945e-06 3.60178739972851e-05 3.08467289109717e-05 7.00286914770076e-05 8.86105858290391e-06 3.28624360002104e-05 1.42675036533364e-06 4.09069057565809e-05 9.06546092050847e-06 8.86105858290391e-06 2.58399322303736e-05 -1.03364233949295e-06 3.66922331214136e-06 5.06166309287844e-06 2.38893724673605e-05 3.28624360002104e-05 -1.03364233949295e-06 0.000259982541121342 1.8624954370461e-05 6.2172260172183e-05 2.25613561793945e-06 1.42675036533364e-06 3.66922331214136e-06 1.8624954370461e-05 1.9469156698457e-05 5.48417262107483e-06 3.60178739972851e-05 4.09069057565809e-05 5.06166309287844e-06 6.2172260172183e-05 5.48417262107483e-06 0.000238562668579522 3437 3396 0 676 146 3437 3396 0 661 171 0 0 0 0 0 0 0 0 2078 0 0 0 0 0 3679 +102 104 0.994649438157599 0.0975829307830029 -0.033912634704091 0.252606120058323 -0.0982350201297207 0.994998228338974 -0.0181219872645378 -0.0251102996848315 0.0319746148199915 0.0213564328037799 0.999260489954952 -0.13019249760431 6.23633384193171e-05 1.47649389861506e-06 -8.44923338209913e-06 1.44177325435013e-05 7.49467990165637e-06 2.37058714011041e-06 1.47649389861506e-06 2.93783447675001e-05 1.71860855528493e-06 -2.98836781711456e-06 -3.36528467667919e-06 3.4955764800548e-06 -8.44923338209913e-06 1.71860855528493e-06 2.22507523803733e-05 -6.86955633686596e-06 -1.31205814001563e-06 2.40840194363815e-06 1.44177325435013e-05 -2.98836781711456e-06 -6.86955633686596e-06 0.000158818227695202 1.33390296179008e-05 2.35442241742827e-05 7.49467990165637e-06 -3.36528467667919e-06 -1.31205814001563e-06 1.33390296179008e-05 2.14707520893495e-05 4.94669324781671e-06 2.37058714011041e-06 3.4955764800548e-06 2.40840194363815e-06 2.35442241742827e-05 4.94669324781671e-06 9.6225581152585e-05 3225 3184 0 693 3 3225 3195 0 559 12 0 0 0 0 0 0 0 0 2419 0 0 3 0 0 3837 +104 108 0.995777839659471 -0.0293434847794555 0.0869796179809707 0.564106833202857 0.0258156433881651 0.998808646508545 0.0414106292662001 0.0237730840285075 -0.0880911266789841 -0.0389903521498004 0.995349037192312 -0.188795847294411 5.97810882961434e-05 -3.57308660234091e-06 3.1115628411584e-06 -9.75898203060864e-06 -1.95998640061162e-06 -5.8898051134153e-06 -3.57308660234091e-06 2.37917008849984e-05 -2.71568500673559e-06 2.62828852893303e-06 -1.16101956480104e-06 -8.64927557944589e-07 3.1115628411584e-06 -2.71568500673559e-06 1.7488238602715e-05 -3.13755185406506e-06 6.00729479884504e-06 6.34574639837723e-06 -9.75898203060864e-06 2.62828852893303e-06 -3.13755185406506e-06 0.0001251827503966 -1.7233347395519e-07 3.29525343064194e-05 -1.95998640061162e-06 -1.16101956480104e-06 6.00729479884504e-06 -1.7233347395519e-07 1.46606299488433e-05 2.77609829171573e-07 -5.8898051134153e-06 -8.64927557944589e-07 6.34574639837723e-06 3.29525343064194e-05 2.77609829171573e-07 0.000115744211225721 2988 2938 0 886 693 2988 2938 0 758 749 0 0 0 0 0 0 0 0 1699 0 0 0 0 0 2955 +101 104 0.989223512579956 0.144971188021158 -0.0204987024640197 0.406130154113745 -0.145067360839284 0.98941635332733 -0.00327728356627986 -0.0561500112419112 0.0198066397478065 0.00621565862824101 0.999784508086476 -0.120704238668556 8.4284236458071e-05 -2.45593749501221e-06 -5.28322234430316e-06 1.2721336101054e-06 -3.62329205054465e-06 2.41009023780905e-05 -2.45593749501221e-06 3.37000188400318e-05 6.6398876268235e-07 -8.84414733482501e-06 -1.52041601375942e-06 7.98146020345651e-06 -5.28322234430316e-06 6.6398876268235e-07 2.09753623321958e-05 -4.45403455520632e-06 -6.00302327886119e-07 -1.89629712235548e-06 1.2721336101054e-06 -8.84414733482501e-06 -4.45403455520632e-06 0.000155933472083062 1.09282635534552e-05 -3.54973439914007e-06 -3.62329205054465e-06 -1.52041601375942e-06 -6.00302327886119e-07 1.09282635534552e-05 1.96912167261794e-05 6.13077284724826e-07 2.41009023780905e-05 7.98146020345651e-06 -1.89629712235548e-06 -3.54973439914007e-06 6.13077284724826e-07 0.000164142835170845 3537 3509 0 851 16 3537 3510 0 850 38 0 0 0 0 0 0 0 0 2123 0 0 0 0 0 3817 +105 107 0.997996263094016 -0.0208962978840275 0.0597227225193308 0.325672195289506 0.0189079850784585 0.999254271129529 0.0336658540611503 0.0270357696494331 -0.060381677275907 -0.0324691602006561 0.997647135356591 -0.0326188126002437 0.000122576942381095 3.20644145072361e-05 -9.49227655661414e-06 1.68000545223774e-05 4.85911958576755e-06 7.70111655134478e-05 3.20644145072361e-05 3.90944633053535e-05 1.16274350392374e-07 -9.03463764328197e-06 -1.67211468995828e-08 3.97800478127374e-05 -9.49227655661414e-06 1.16274350392374e-07 2.32830519843958e-05 -2.29364295018407e-05 8.40668598755187e-07 -1.81111743860967e-06 1.68000545223774e-05 -9.03463764328197e-06 -2.29364295018407e-05 0.000165123168322692 2.05331328846397e-05 -2.62276638562262e-05 4.85911958576755e-06 -1.67211468995828e-08 8.40668598755187e-07 2.05331328846397e-05 2.16166872677158e-05 -6.23746348144749e-06 7.70111655134478e-05 3.97800478127374e-05 -1.81111743860967e-06 -2.62276638562262e-05 -6.23746348144749e-06 0.00018093025729475 3155 3109 0 349 453 3155 3109 0 276 503 0 0 0 0 0 0 0 0 2493 0 0 0 0 0 3334 +107 110 0.991156836784759 -0.132364672172072 -0.00936581313126571 0.423676785798103 0.131641138309825 0.989708620136059 -0.0561022096968624 0.0882024374780755 0.0166953765852512 0.0543731623979804 0.998381101389404 -0.149495047835007 9.4617765614277e-05 1.6447655152432e-05 -7.35741921600286e-06 2.30262481650093e-05 3.25273870002245e-06 3.15591392652487e-05 1.6447655152432e-05 4.68461516492043e-05 3.80375749232787e-06 -5.26871783712278e-06 1.95377582027126e-07 2.15369460770382e-05 -7.35741921600286e-06 3.80375749232787e-06 1.90540675768304e-05 -1.33348255319517e-05 1.3758933442698e-06 -2.93976313475805e-07 2.30262481650093e-05 -5.26871783712278e-06 -1.33348255319517e-05 0.000168528685754289 1.86103143848605e-08 2.87928878346411e-06 3.25273870002245e-06 1.95377582027126e-07 1.3758933442698e-06 1.86103143848605e-08 1.56162287118845e-05 2.29091590975343e-06 3.15591392652487e-05 2.15369460770382e-05 -2.93976313475805e-07 2.87928878346411e-06 2.29091590975343e-06 0.000170733147681218 3421 3342 0 174 408 3421 3342 0 91 411 0 0 0 0 0 0 0 0 2888 0 0 0 0 0 2744 +107 109 0.995637007243538 -0.089904198246578 -0.0249836935774287 0.297197420650408 0.0888854211826219 0.99526743197969 -0.0392698451963055 0.0579499675496226 0.028395980495816 0.0368778250198394 0.998916259910453 -0.101990820528251 6.39501702646629e-05 6.15140040174799e-06 -6.91978817772776e-06 -7.30597521759111e-07 3.62397042298616e-06 3.19348704658076e-05 6.15140040174799e-06 3.55313834551255e-05 -3.13718399859459e-06 1.74218777170833e-05 1.67469561837061e-06 3.33742360817829e-05 -6.91978817772776e-06 -3.13718399859459e-06 1.88505620738333e-05 -4.38223123864068e-06 -7.9638183729927e-07 -4.81131377105282e-06 -7.30597521759111e-07 1.74218777170833e-05 -4.38223123864068e-06 0.000247824302669833 8.56054440281005e-06 0.000103953274694551 3.62397042298616e-06 1.67469561837061e-06 -7.9638183729927e-07 8.56054440281005e-06 1.57102121373426e-05 7.40246392452976e-06 3.19348704658076e-05 3.33742360817829e-05 -4.81131377105282e-06 0.000103953274694551 7.40246392452976e-06 0.000196608488564059 3499 3430 0 91 293 3499 3430 0 18 296 0 0 0 0 0 0 0 0 3050 0 0 0 0 0 3190 +108 112 0.993644896343153 -0.0894382726333625 0.0683419004679044 0.542403729496406 0.0905750782682378 0.995795196262163 -0.0137143099681304 0.0867809017836648 -0.066827951995458 0.0198172270905813 0.99756769311287 -0.154147441939777 9.2632261619036e-05 -1.93692821314201e-05 4.16647019406462e-06 -7.32533529590587e-06 2.07351101622492e-06 -1.70552470741393e-05 -1.93692821314201e-05 3.14275468856848e-05 -5.41490167619721e-07 -6.55287062774028e-06 -1.0103383567675e-06 -1.14426117822256e-06 4.16647019406462e-06 -5.41490167619721e-07 1.89191774442846e-05 6.28579486825293e-07 3.72515794751219e-06 3.87318967507077e-06 -7.32533529590587e-06 -6.55287062774028e-06 6.28579486825293e-07 0.000102161301280058 -5.82444610571023e-07 3.74519983496114e-05 2.07351101622492e-06 -1.0103383567675e-06 3.72515794751219e-06 -5.82444610571023e-07 1.51206513166227e-05 -4.77524083287816e-06 -1.70552470741393e-05 -1.14426117822256e-06 3.87318967507077e-06 3.74519983496114e-05 -4.77524083287816e-06 0.000136687207878901 3243 3161 0 604 429 3243 3161 0 490 430 0 0 0 0 0 0 0 0 3068 0 0 0 0 0 2780 +107 111 0.98638333459263 -0.16105791651355 0.0332906107819857 0.555055197507785 0.162166211610079 0.98618437936053 -0.0338007354553291 0.114718773962713 -0.0273868043035046 0.0387390943828111 0.998873988807618 -0.131109369913412 9.38513905138113e-05 -4.93143454846669e-05 8.87635897846523e-06 -2.42680810861585e-05 3.36129981548498e-06 -2.94600733688331e-05 -4.93143454846669e-05 0.000118549223770025 -7.18716094069453e-06 2.61446687941701e-05 -4.48156231391756e-07 0.000210031318552321 8.87635897846523e-06 -7.18716094069453e-06 1.62920158644623e-05 1.61912863634929e-06 4.9498495797557e-06 -1.16994486402948e-05 -2.42680810861585e-05 2.61446687941701e-05 1.61912863634929e-06 0.000117408994645497 2.21221969356749e-06 0.000154416416348028 3.36129981548498e-06 -4.48156231391756e-07 4.9498495797557e-06 2.21221969356749e-06 1.33010882107072e-05 6.39127461441197e-06 -2.94600733688331e-05 0.000210031318552321 -1.16994486402948e-05 0.000154416416348028 6.39127461441197e-06 0.000887757294927493 3417 3327 0 354 610 3417 3327 0 248 615 0 0 0 0 0 0 0 0 2952 0 0 0 0 0 2469 +110 113 0.996238749474426 0.0415599783523651 0.0760336915122742 0.42155731405275 -0.0415275799786977 0.999135340646182 -0.00200777811289804 0.0047815286615558 -0.0760513914846112 -0.00115726884893593 0.997103227645997 -0.100010203803382 5.95590407435589e-05 1.72739188001033e-05 6.82100080367934e-06 9.4896246584501e-06 -1.98913624819895e-06 5.19885143515551e-06 1.72739188001033e-05 7.97047074551542e-05 5.91670101404217e-06 1.27825266628085e-06 1.03316948106271e-06 9.86680321490275e-05 6.82100080367934e-06 5.91670101404217e-06 1.82367414262011e-05 -1.73048304558454e-06 1.14444385952719e-06 7.83547399815231e-06 9.4896246584501e-06 1.27825266628085e-06 -1.73048304558454e-06 0.000100805438275443 3.29784756337055e-06 4.01216385628659e-05 -1.98913624819895e-06 1.03316948106271e-06 1.14444385952719e-06 3.29784756337055e-06 1.58180881605096e-05 1.43190110748739e-05 5.19885143515551e-06 9.86680321490275e-05 7.83547399815231e-06 4.01216385628659e-05 1.43190110748739e-05 0.000473978984803266 3158 3087 0 867 182 3158 3087 0 746 180 0 0 0 0 0 0 0 0 2860 0 0 0 0 0 3185 +106 109 0.993559887996253 -0.112810492948409 -0.0106085647290317 0.440608685523931 0.112505154247607 0.993311957635424 -0.0259604523497496 0.0800987172905195 0.0134662256254355 0.0245997459177638 0.9996066792835 -0.0920045115247154 9.75153189477553e-05 -1.23931420710753e-05 -5.21387370726997e-06 1.0965757482839e-05 4.01219286232727e-06 5.00258897907169e-05 -1.23931420710753e-05 5.34805155016446e-05 -5.96306757827856e-06 2.24917948949789e-05 2.49104869745021e-06 5.66632019953648e-05 -5.21387370726997e-06 -5.96306757827856e-06 1.88762359006687e-05 -8.92231858658931e-06 2.49358401559575e-06 -8.83404174091827e-06 1.0965757482839e-05 2.24917948949789e-05 -8.92231858658931e-06 0.000156667053550206 5.39232925592605e-06 0.000104908034251028 4.01219286232727e-06 2.49104869745021e-06 2.49358401559575e-06 5.39232925592605e-06 1.45465582915861e-05 7.91935875459421e-06 5.00258897907169e-05 5.66632019953648e-05 -8.83404174091827e-06 0.000104908034251028 7.91935875459421e-06 0.000322102505492162 3499 3430 0 248 552 3499 3430 0 158 614 0 0 0 0 0 0 0 0 2632 0 0 0 0 0 2858 +110 112 0.998511086355947 -0.00244521310238287 0.054494324081968 0.297489845871037 0.0016137218832763 0.99988169045991 0.0152970907271894 0.0113527215577304 -0.0545252815302228 -0.015186375996806 0.998396898862438 -0.0449106319638593 5.68590165020091e-05 5.26748595824275e-06 1.52699417670505e-05 6.08015324548506e-06 -3.31280585610198e-06 -1.36186975471884e-05 5.26748595824275e-06 4.04509693101053e-05 -1.7540123105604e-06 -6.8718159049285e-06 1.49863873531769e-06 5.64044244529751e-06 1.52699417670505e-05 -1.7540123105604e-06 2.43882608225325e-05 -5.23038591086089e-06 -3.33836966553221e-07 -1.86494540758068e-06 6.08015324548506e-06 -6.8718159049285e-06 -5.23038591086089e-06 8.09739676325403e-05 1.4052863196187e-06 3.76171293904542e-06 -3.31280585610198e-06 1.49863873531769e-06 -3.33836966553221e-07 1.4052863196187e-06 1.58805398819949e-05 3.0805483030543e-06 -1.36186975471884e-05 5.64044244529751e-06 -1.86494540758068e-06 3.76171293904542e-06 3.0805483030543e-06 0.00015794672517378 3299 3216 0 454 160 3299 3216 0 348 159 0 0 0 0 0 0 0 0 3330 0 0 0 0 0 3106 +108 110 0.996298107180315 -0.0859140370428123 0.0029765530279661 0.258511467856016 0.0859586111978478 0.995178944093962 -0.0472227317397422 0.0514464308436886 0.00109489262454001 0.0473037786126297 0.998879949613119 -0.137438226433098 0.000117203058154513 8.53368265147828e-06 -1.13433204160889e-05 1.85547814453098e-05 1.70812760572479e-05 5.07773095854673e-05 8.53368265147828e-06 4.03292548962055e-05 4.58710259856706e-07 -7.16437093675715e-06 1.86168366016425e-06 9.05820838482418e-06 -1.13433204160889e-05 4.58710259856706e-07 2.48277427975578e-05 -2.03776233721919e-05 -2.2026164041385e-06 -1.00199499592908e-05 1.85547814453098e-05 -7.16437093675715e-06 -2.03776233721919e-05 9.96224848359622e-05 7.5852473107311e-06 1.57135265580756e-05 1.70812760572479e-05 1.86168366016425e-06 -2.2026164041385e-06 7.5852473107311e-06 1.70192030584458e-05 1.02848880997265e-05 5.07773095854673e-05 9.05820838482418e-06 -1.00199499592908e-05 1.57135265580756e-05 1.02848880997265e-05 0.00014468940747019 3469 3390 0 67 264 3469 3390 0 2 265 0 0 0 0 0 0 0 0 3258 0 0 0 0 0 3078 +109 113 0.995987681952145 -0.00242381756441785 0.0894576017340467 0.534108451676405 0.00305318813168943 0.999971538880957 -0.00689923693486012 0.0392405574090375 -0.0894383331789306 0.00714468588989374 0.995966735399185 -0.177441336269052 7.1303664473231e-05 -6.8756392621528e-06 1.07437922697861e-05 2.21892590794138e-05 1.97478169688807e-06 -2.72753516411838e-05 -6.8756392621528e-06 6.12609709676524e-05 6.71673494832989e-06 -9.3808081580003e-06 -2.29055406553461e-06 9.28782080912417e-05 1.07437922697861e-05 6.71673494832989e-06 2.05586211623714e-05 2.0037676216516e-06 2.53149744088737e-06 1.17308803500093e-05 2.21892590794138e-05 -9.3808081580003e-06 2.0037676216516e-06 0.000104564817926927 -3.08603695633325e-07 1.26817585636808e-07 1.97478169688807e-06 -2.29055406553461e-06 2.53149744088737e-06 -3.08603695633325e-07 1.70179642458968e-05 -1.52540755508295e-06 -2.72753516411838e-05 9.28782080912417e-05 1.17308803500093e-05 1.26817585636808e-07 -1.52540755508295e-06 0.000526399377420729 2956 2885 0 929 261 2956 2885 0 808 261 0 0 0 0 0 0 0 0 2797 0 0 0 0 0 2917 +111 115 0.990825647371895 0.131345803295901 0.031824777558052 0.556929050631209 -0.131193035112242 0.991333169556263 -0.00685087407352487 -0.0595883568891329 -0.0324487911655129 0.00261283257935082 0.999469984070462 -0.168234188574654 4.23209287884874e-05 3.20204642557037e-06 7.47690123126073e-06 -8.72273794471314e-07 2.2465386902644e-06 -1.07526091679178e-05 3.20204642557037e-06 3.34688916476168e-05 -1.31503441701002e-06 -1.22546204273719e-05 -6.43545768585663e-07 -1.10663440510846e-05 7.47690123126073e-06 -1.31503441701002e-06 1.60407836048789e-05 3.60666771346009e-07 4.84598065111564e-06 1.17330228675936e-06 -8.72273794471314e-07 -1.22546204273719e-05 3.60666771346009e-07 9.85210501898657e-05 2.04885546884475e-06 3.91795404198507e-05 2.2465386902644e-06 -6.43545768585663e-07 4.84598065111564e-06 2.04885546884475e-06 1.2533755529126e-05 3.71879121639753e-06 -1.07526091679178e-05 -1.10663440510846e-05 1.17330228675936e-06 3.91795404198507e-05 3.71879121639753e-06 8.09589753185392e-05 3270 3219 0 1576 110 3269 3218 0 1417 92 0 0 0 0 0 0 0 0 2098 0 1 1 0 0 3363 +112 114 0.996947607486342 0.0778965328939319 0.0052533884649497 0.264977135375882 -0.0777029030227802 0.996515051055348 -0.0303316976443623 -0.0211172947937274 -0.00759781475764579 0.0298309098631131 0.999526082715027 -0.0859657032120637 8.35942864160782e-05 3.48458409809757e-06 -6.28982424340525e-06 1.91752639401946e-05 1.23770261498642e-05 1.62557038917184e-05 3.48458409809757e-06 2.32220443668422e-05 5.88263492313403e-06 -7.22401345343123e-06 1.7575396224908e-07 -5.61983491856175e-06 -6.28982424340525e-06 5.88263492313403e-06 1.92413158386841e-05 -9.98740687402533e-06 -3.04850229383972e-06 -5.17021512336107e-06 1.91752639401946e-05 -7.22401345343123e-06 -9.98740687402533e-06 8.45544151576661e-05 1.16277662043295e-05 2.65950350875754e-05 1.23770261498642e-05 1.7575396224908e-07 -3.04850229383972e-06 1.16277662043295e-05 1.58761755457281e-05 4.88605273125036e-06 1.62557038917184e-05 -5.61983491856175e-06 -5.17021512336107e-06 2.65950350875754e-05 4.88605273125036e-06 8.9569499644356e-05 3487 3421 0 665 31 3486 3420 0 553 22 0 0 0 0 0 0 0 0 3092 0 12 14 0 0 3430 +110 114 0.99505745243538 0.0803897207128694 0.0582937317086346 0.56036527887514 -0.0796098713824972 0.99670429039592 -0.0155828715205797 -0.0120100967554627 -0.0593543151866288 0.0108650959531656 0.998177847359204 -0.142286443281228 4.62397129815279e-05 2.18554749978013e-05 1.12421305300795e-05 4.09169757900483e-06 -9.06529570446364e-08 1.04504645839625e-05 2.18554749978013e-05 5.21551898790339e-05 1.08193661687993e-05 -6.21775125455358e-06 -1.11251518170705e-06 4.45370256899563e-05 1.12421305300795e-05 1.08193661687993e-05 1.8423406307588e-05 2.17688585298569e-06 3.03444083197168e-06 6.32171859153981e-06 4.09169757900483e-06 -6.21775125455358e-06 2.17688585298569e-06 8.55383869334887e-05 1.40272691011626e-06 1.67890108397041e-06 -9.06529570446364e-08 -1.11251518170705e-06 3.03444083197168e-06 1.40272691011626e-06 1.46102747059581e-05 4.40907586680586e-07 1.04504645839625e-05 4.45370256899563e-05 6.32171859153981e-06 1.67890108397041e-06 4.40907586680586e-07 0.00027796054905592 3192 3128 0 1366 210 3192 3128 0 1216 205 0 0 0 0 0 0 0 0 2366 0 0 0 0 0 3188 +113 115 0.99814311365095 0.0598021140834119 -0.0115772113369511 0.271749677219543 -0.0596695864404598 0.99815224594691 0.0114732020449462 -0.0315122199687415 0.0122419412353737 -0.0107610902000794 0.99986715808276 -0.0637996681623616 5.613179693374e-05 1.59822761422403e-06 6.82152444750689e-06 -1.3852723457776e-05 -6.48362462430808e-07 -2.56272954997871e-05 1.59822761422403e-06 0.000129143895530719 2.53660071383963e-06 2.49835739461645e-05 5.44118663288718e-06 0.000311026106704654 6.82152444750689e-06 2.53660071383963e-06 1.533724278824e-05 -4.4665609714154e-06 4.05194389991105e-06 -1.03757344102204e-05 -1.3852723457776e-05 2.49835739461645e-05 -4.4665609714154e-06 7.4420368707313e-05 1.56876250390186e-06 0.000141490712829797 -6.48362462430808e-07 5.44118663288718e-06 4.05194389991105e-06 1.56876250390186e-06 1.31793981496656e-05 2.39891217318626e-05 -2.56272954997871e-05 0.000311026106704654 -1.03757344102204e-05 0.000141490712829797 2.39891217318626e-05 0.00117719922615585 3427 3376 0 604 60 3427 3376 0 502 62 0 0 0 0 0 0 0 0 3159 0 0 0 0 0 3402 +111 113 0.996342875138489 0.0708941471321778 0.0476958600212862 0.269206833005809 -0.0703661159095041 0.997440862885801 -0.0126623369659189 -0.0114134128580534 -0.0484714853556111 0.00925985680393469 0.998781642882663 -0.0800835293397696 0.000108729000205802 2.78059447145366e-05 -2.58837175014887e-07 2.75778199804873e-05 -2.47239010479086e-06 1.76120742679675e-05 2.78059447145366e-05 4.70192240929315e-05 1.45301296021938e-06 9.21138469863167e-06 -2.57821346752267e-06 1.07695880312078e-05 -2.58837175014887e-07 1.45301296021938e-06 1.934448700828e-05 -1.39682051314525e-05 3.01151198494518e-06 -1.68946925762005e-06 2.75778199804873e-05 9.21138469863167e-06 -1.39682051314525e-05 0.000149341787899943 6.93668337686404e-06 4.83786801410171e-05 -2.47239010479086e-06 -2.57821346752267e-06 3.01151198494518e-06 6.93668337686404e-06 1.7329752353757e-05 9.33918350766929e-06 1.76120742679675e-05 1.07695880312078e-05 -1.68946925762005e-06 4.83786801410171e-05 9.33918350766929e-06 0.000208420685027626 3118 3047 0 638 46 3114 3043 0 521 37 0 0 0 0 0 0 0 0 3107 0 5 5 0 0 3359 +111 114 0.993600814936365 0.108955490600878 0.029767795110025 0.419689636134169 -0.10802504841078 0.993656559491808 -0.0312606892878522 -0.0310739525287963 -0.0329849886105641 0.0278449788440398 0.999067889424706 -0.112469713342948 6.42975913650892e-05 -4.15297207587656e-06 5.54214893750521e-06 -9.89303555620871e-06 8.96758071631978e-07 -2.18871967877969e-05 -4.15297207587656e-06 3.21051336156653e-05 2.55515143341547e-06 -2.47437773524917e-06 -4.39951009856258e-07 1.47664838909115e-06 5.54214893750521e-06 2.55515143341547e-06 1.98489328425326e-05 -6.36859679152845e-06 1.23259602497147e-06 3.32203434057373e-06 -9.89303555620871e-06 -2.47437773524917e-06 -6.36859679152845e-06 8.4302772263875e-05 6.55055729372416e-06 3.16104481992221e-05 8.96758071631978e-07 -4.39951009856258e-07 1.23259602497147e-06 6.55055729372416e-06 1.55184217854381e-05 2.22264924119557e-06 -2.18871967877969e-05 1.47664838909115e-06 3.32203434057373e-06 3.16104481992221e-05 2.22264924119557e-06 0.000127448350775716 3308 3244 0 1131 71 3303 3239 0 978 55 0 0 0 0 0 0 0 0 2624 0 5 5 0 0 3399 +112 116 0.992450929384916 0.111796378265524 0.0504254159103114 0.535483175875684 -0.112251614996637 0.99365997509275 0.0062792379571755 -0.0692175962325137 -0.0494037214556019 -0.0118921699192375 0.998708089784472 -0.137354976906144 5.61462431142962e-05 1.99272577739647e-06 7.51104680019001e-06 -2.46260257793631e-06 -1.74173739373234e-06 2.07244457547961e-05 1.99272577739647e-06 5.57564875912182e-05 4.9455222041011e-06 4.07981932830338e-06 -2.51978936654608e-06 5.45363054776388e-05 7.51104680019001e-06 4.9455222041011e-06 1.77430829278649e-05 -9.90009829885421e-07 3.42475727575864e-06 1.23291662877516e-05 -2.46260257793631e-06 4.07981932830338e-06 -9.90009829885421e-07 8.33515847417717e-05 2.24899337243597e-06 7.61709188213623e-05 -1.74173739373234e-06 -2.51978936654608e-06 3.42475727575864e-06 2.24899337243597e-06 1.39729785753082e-05 -4.90743973573908e-06 2.07244457547961e-05 5.45363054776388e-05 1.23291662877516e-05 7.61709188213623e-05 -4.90743973573908e-06 0.000404237188798358 3256 3207 0 1442 129 3256 3207 0 1304 125 0 0 0 0 0 0 0 0 2283 0 0 0 0 0 3338 +112 115 0.99427257415246 0.104022907609764 0.0245210721758159 0.406013433505465 -0.103807980725647 0.994548241837459 -0.00988421952822539 -0.045481875644888 -0.0254155744752064 0.00728212540601737 0.999650448518714 -0.0962334530638875 5.04634134695523e-05 -2.7091468767655e-07 7.87301431591883e-06 -2.88153456314092e-06 1.53140345350978e-06 -1.28849670149445e-05 -2.7091468767655e-07 4.72363460370177e-05 1.40099302268479e-06 -1.00976910700683e-06 1.48221293892943e-06 5.03542702181682e-05 7.87301431591883e-06 1.40099302268479e-06 1.37443504211529e-05 -2.14120795328191e-06 4.6270098928369e-06 2.44994634323908e-06 -2.88153456314092e-06 -1.00976910700683e-06 -2.14120795328191e-06 8.68591683383604e-05 4.48920290980967e-06 2.16721697332136e-05 1.53140345350978e-06 1.48221293892943e-06 4.6270098928369e-06 4.48920290980967e-06 1.22400270207123e-05 -7.81114863802793e-07 -1.28849670149445e-05 5.03542702181682e-05 2.44994634323908e-06 2.16721697332136e-05 -7.81114863802793e-07 0.000309372523092353 3409 3358 0 1068 58 3409 3358 0 941 53 0 0 0 0 0 0 0 0 2668 0 0 0 0 0 3408 +114 117 0.998760345070367 0.0261899083629501 0.0423303887870443 0.412174677113236 -0.0278668067162884 0.998830029826397 0.0395223051002403 -0.0361700745425932 -0.0412457779458586 -0.0406529238424462 0.998321654370324 -0.0703056111186933 5.07619444557493e-05 9.38441820410549e-06 9.4333672680087e-06 2.26278103641289e-06 1.31606413556473e-06 3.83346066335609e-05 9.38441820410549e-06 5.69258883226263e-05 1.68738776329329e-06 3.760838121173e-06 2.02580631349324e-06 5.40626845566577e-05 9.4333672680087e-06 1.68738776329329e-06 1.48960093894187e-05 -1.72386298460099e-06 3.6216393142179e-06 8.30554087976689e-06 2.26278103641289e-06 3.760838121173e-06 -1.72386298460099e-06 6.04658883778496e-05 1.25914685228472e-06 6.08674859407249e-05 1.31606413556473e-06 2.02580631349324e-06 3.6216393142179e-06 1.25914685228472e-06 1.38352242017605e-05 7.25251406658131e-06 3.83346066335609e-05 5.40626845566577e-05 8.30554087976689e-06 6.08674859407249e-05 7.25251406658131e-06 0.000387601481542817 3266 3227 0 770 237 3266 3227 0 662 237 0 0 0 0 0 0 0 0 2988 0 0 0 0 0 3229 +114 116 0.998608916896395 0.034503988082743 0.0398711161292823 0.252494607609723 -0.0361224781304768 0.998521825738218 0.0406119452640466 -0.0297688612014617 -0.0384109055962238 -0.041995694193603 0.998379168452785 -0.0602780092801892 5.22687956379354e-05 -6.54993119487144e-07 1.39712828266216e-05 -2.7383590218253e-06 -1.92672230912215e-06 2.22338871470055e-05 -6.54993119487144e-07 3.33407733204764e-05 -2.14047208372856e-06 -2.6392362139813e-07 -6.46450833181802e-07 3.38005934247839e-06 1.39712828266216e-05 -2.14047208372856e-06 1.55738694563799e-05 -1.4366928604516e-06 1.93684371115388e-06 2.18175134117659e-06 -2.7383590218253e-06 -2.6392362139813e-07 -1.4366928604516e-06 6.94355715660083e-05 2.48742625424323e-06 3.60611511389236e-05 -1.92672230912215e-06 -6.46450833181802e-07 1.93684371115388e-06 2.48742625424323e-06 1.29276447308914e-05 1.87283564294599e-06 2.22338871470055e-05 3.38005934247839e-06 2.18175134117659e-06 3.60611511389236e-05 1.87283564294599e-06 0.000165559508253194 3414 3365 0 475 109 3414 3365 0 391 114 0 0 0 0 0 0 0 0 3290 0 0 0 0 0 3353 +113 117 0.997853499535689 0.0621548240440253 0.020619682646311 0.549934696858723 -0.0627902051911241 0.99752164037708 0.0317484977829899 -0.0629698785895889 -0.0185952573640391 -0.0329750637220953 0.999283173868193 -0.10094010539213 3.93551752082199e-05 5.62720593828708e-07 5.21447801260918e-06 -4.36018066932452e-06 -2.4553716271805e-07 2.03765245136242e-06 5.62720593828708e-07 3.28692218011197e-05 1.81181556353119e-06 -7.95988350490539e-06 -1.09610210828109e-06 -4.29498712312568e-06 5.21447801260918e-06 1.81181556353119e-06 1.38802676533165e-05 -5.4018860468615e-06 4.51392377116428e-06 -1.92678674529851e-06 -4.36018066932452e-06 -7.95988350490539e-06 -5.4018860468615e-06 7.60923989459463e-05 4.77084800316629e-06 2.82118933547153e-05 -2.4553716271805e-07 -1.09610210828109e-06 4.51392377116428e-06 4.77084800316629e-06 1.36660428744169e-05 6.15363164475704e-07 2.03765245136242e-06 -4.29498712312568e-06 -1.92678674529851e-06 2.82118933547153e-05 6.15363164475704e-07 0.000159679792360974 3359 3320 0 1260 242 3359 3320 0 1135 242 0 0 0 0 0 0 0 0 2472 0 0 0 0 0 3227 +116 118 0.999101419692551 -0.0415596841593116 0.00831539661751598 0.279376261174251 0.0414659775075436 0.999077801463311 0.011140885628152 0.00616862114321876 -0.00877073985888433 -0.0107860685986108 0.999903362753878 -0.00784414961107141 6.13125985790311e-05 1.26215304761396e-06 7.57742805262485e-06 -3.47332737325482e-06 8.31283117601519e-07 -3.59360026572787e-06 1.26215304761396e-06 2.84837253650238e-05 6.75741496468665e-07 3.99617430434738e-06 4.8814869779122e-07 1.69071211896144e-05 7.57742805262485e-06 6.75741496468665e-07 1.42335325342224e-05 -3.66711141472394e-06 3.1098103277353e-06 -3.10904267342671e-06 -3.47332737325482e-06 3.99617430434738e-06 -3.66711141472394e-06 5.56829764343469e-05 -1.18370263522106e-06 3.1140657338637e-05 8.31283117601519e-07 4.8814869779122e-07 3.1098103277353e-06 -1.18370263522106e-06 1.24676177597163e-05 7.35299479652422e-07 -3.59360026572787e-06 1.69071211896144e-05 -3.10904267342671e-06 3.1140657338637e-05 7.35299479652422e-07 0.000164653413767765 3494 3455 0 243 343 3494 3455 0 167 343 0 0 0 0 0 0 0 0 3505 0 0 0 0 0 3143 +115 117 0.999414298234549 0.000388120804988519 0.0342185599724083 0.281590788153585 -0.00100004836358063 0.999839861335077 0.0178676128434557 -0.0120263695193721 -0.0342061454656187 -0.0178913679659733 0.999254641502701 -0.0342872906536363 8.84906809391456e-05 -2.44691809835912e-05 3.13347576283537e-06 9.22039286983139e-06 1.94438753223201e-06 -7.06269374114081e-06 -2.44691809835912e-05 8.70939427905721e-05 -3.17831563294782e-07 -1.09932938221445e-05 1.01781620612582e-06 5.67137305845e-05 3.13347576283537e-06 -3.17831563294782e-07 1.50943425487919e-05 -5.0516919314977e-06 4.75832986505575e-06 4.35319379910467e-06 9.22039286983139e-06 -1.09932938221445e-05 -5.0516919314977e-06 4.41813879448778e-05 4.11672460029004e-07 1.64605127169417e-05 1.94438753223201e-06 1.01781620612582e-06 4.75832986505575e-06 4.11672460029004e-07 1.23387337442756e-05 9.0011197830257e-07 -7.06269374114081e-06 5.67137305845e-05 4.35319379910467e-06 1.64605127169417e-05 9.0011197830257e-07 0.000299501408742068 3307 3268 0 407 216 3307 3268 0 326 220 0 0 0 0 0 0 0 0 3368 0 0 0 0 0 3246 +116 119 0.995438749942122 -0.0855023434189975 -0.0423207323131862 0.412320747350347 0.0860404321245757 0.996230283832804 0.0110573782709335 0.0225910270550086 0.0412157634101425 -0.0146482368997103 0.999042886968447 -0.0743095028861481 4.83254463890516e-05 -8.31889992561139e-06 5.51981363723398e-06 5.72276949166279e-06 -2.27526132868312e-06 1.20950038855446e-05 -8.31889992561139e-06 2.17083940904614e-05 -2.08832104299688e-06 -4.87887671433167e-06 9.98875124318448e-07 -1.16556525295364e-05 5.51981363723398e-06 -2.08832104299688e-06 1.59711296108745e-05 -1.26508990093554e-06 4.18648256076293e-06 -5.26855276008839e-08 5.72276949166279e-06 -4.87887671433167e-06 -1.26508990093554e-06 5.68821106192226e-05 7.19429972829308e-07 1.19071447722845e-05 -2.27526132868312e-06 9.98875124318448e-07 4.18648256076293e-06 7.19429972829308e-07 1.44076909732862e-05 9.62980392760394e-08 1.20950038855446e-05 -1.16556525295364e-05 -5.26855276008839e-08 1.19071447722845e-05 9.62980392760394e-08 6.84863468203684e-05 3372 3343 0 347 557 3372 3343 0 254 563 0 0 0 0 0 0 0 0 3385 0 0 0 0 0 2973 +115 119 0.996932239103024 -0.0781559981643154 -0.0042131446653709 0.550906016884779 0.0782480756300628 0.996473335859722 0.0303006531413143 0.0079441670145244 0.00183010852787161 -0.0305373684448709 0.999531950380396 -0.0709430021914249 4.79002210954039e-05 -7.3187125374644e-06 6.4615122005734e-06 5.44666633579382e-06 -5.30214644574602e-07 1.37781276601328e-05 -7.3187125374644e-06 2.54507466391536e-05 -1.62302537411065e-06 -3.63691975210718e-06 -4.71689593519767e-07 -1.34612123424224e-05 6.4615122005734e-06 -1.62302537411065e-06 1.40649915489993e-05 -1.9454252522879e-06 3.66562063870234e-06 3.833688777542e-06 5.44666633579382e-06 -3.63691975210718e-06 -1.9454252522879e-06 6.51326220449881e-05 -2.16717864289471e-08 1.6328349609834e-05 -5.30214644574602e-07 -4.71689593519767e-07 3.66562063870234e-06 -2.16717864289471e-08 1.42709790742309e-05 -1.90784146222344e-06 1.37781276601328e-05 -1.34612123424224e-05 3.833688777542e-06 1.6328349609834e-05 -1.90784146222344e-06 7.44811598203411e-05 3356 3327 0 702 609 3356 3327 0 592 614 0 0 0 0 0 0 0 0 3022 0 0 0 0 0 2921 +119 121 0.996753772410229 -0.0712266800409378 0.037532349198045 0.255908956835521 0.0722192494011805 0.997055356292853 -0.0257875261252775 0.0230008131905345 -0.0355850699297921 0.0284143720338435 0.99896262505662 -0.0576075177130026 4.95729880054758e-05 3.11543061942157e-06 1.13591518572045e-05 -5.66823445657224e-06 -8.51555264751599e-07 5.04711056978043e-06 3.11543061942157e-06 3.49824933425471e-05 4.61582983476132e-06 -3.55276966659257e-06 -3.80687340589917e-07 6.92363235481511e-06 1.13591518572045e-05 4.61582983476132e-06 1.73663236017685e-05 -2.6108589276689e-07 3.05186041177462e-06 -1.91568379383198e-06 -5.66823445657224e-06 -3.55276966659257e-06 -2.6108589276689e-07 6.90239459639704e-05 5.52363567231104e-06 3.00978159322938e-05 -8.51555264751599e-07 -3.80687340589917e-07 3.05186041177462e-06 5.52363567231104e-06 1.41889757832135e-05 -1.07165275804558e-06 5.04711056978043e-06 6.92363235481511e-06 -1.91568379383198e-06 3.00978159322938e-05 -1.07165275804558e-06 0.000176187011357801 3447 3395 0 140 454 3447 3395 0 55 485 0 0 0 0 0 0 0 0 3610 0 0 0 0 0 3170 +118 122 0.991588239076008 -0.121744752453763 0.0439429104192496 0.520882565604916 0.122289942747823 0.992444747038631 -0.00992945004326085 0.0544921622778439 -0.0424020521776546 0.015219701882733 0.998984697903689 -0.061936898533912 6.73541331703622e-05 1.32336843477235e-05 4.15117940739849e-06 -2.34803125455438e-06 -3.45723300560229e-06 0.000140894753591025 1.32336843477235e-05 0.000266956096821329 -1.56443242755241e-05 0.000154988448104942 9.51988980429683e-06 0.00145292849574912 4.15117940739849e-06 -1.56443242755241e-05 1.44483360507545e-05 -8.82069511017205e-06 3.0683167466413e-06 -8.19477525944798e-05 -2.34803125455438e-06 0.000154988448104942 -8.82069511017205e-06 0.000225756954632915 7.25013314125663e-06 0.0010449691714703 -3.45723300560229e-06 9.51988980429683e-06 3.0683167466413e-06 7.25013314125663e-06 1.57608920288787e-05 3.90666562399116e-05 0.000140894753591025 0.00145292849574912 -8.19477525944798e-05 0.0010449691714703 3.90666562399116e-05 0.00962881540617955 3315 3264 0 468 913 3315 3264 0 368 920 0 0 0 0 0 0 0 0 3281 0 0 0 0 0 2753 +117 120 0.990728352789942 -0.122598262555894 -0.0585405585590375 0.396745401908745 0.12155462978932 0.992360851760567 -0.0210810784786788 0.0443508169512974 0.0606778621484762 0.0137697462329131 0.998062418455766 -0.0848420290774968 6.7972751569007e-05 -4.20979809634463e-05 1.28569144006731e-05 -9.91352909761503e-06 -2.08766572071551e-06 -8.65243914988287e-06 -4.20979809634463e-05 6.45605610622746e-05 -1.19881399236775e-05 1.6686099365044e-05 4.01486762074843e-06 7.26955452228889e-05 1.28569144006731e-05 -1.19881399236775e-05 1.84726951776601e-05 -7.96798216958903e-06 5.0192187872421e-07 -7.10299340596709e-06 -9.91352909761503e-06 1.6686099365044e-05 -7.96798216958903e-06 8.1898175156151e-05 5.79099860254432e-06 9.23000980648541e-05 -2.08766572071551e-06 4.01486762074843e-06 5.0192187872421e-07 5.79099860254432e-06 1.54781840511375e-05 4.97135167814435e-06 -8.65243914988287e-06 7.26955452228889e-05 -7.10299340596709e-06 9.23000980648541e-05 4.97135167814435e-06 0.000475414374653414 3371 3332 0 186 685 3371 3332 0 103 700 0 0 0 0 0 0 0 0 3545 0 0 0 0 0 2930 +122 125 0.992763435139055 0.117621645300253 -0.0242055862925355 0.415320483021013 -0.118377316055492 0.992433528618108 -0.0325960475841756 -0.0487088434043717 0.0201884346694351 0.0352255565104822 0.999175453698761 -0.0933928627445522 4.9140150272025e-05 2.52602807168586e-06 3.60885088226566e-06 -2.19082842321728e-06 1.78106872232004e-06 -1.47327175924607e-05 2.52602807168586e-06 2.76646421366173e-05 1.19600679403905e-06 -5.11736367647247e-07 -1.30780712403709e-06 -4.9872859711139e-06 3.60885088226566e-06 1.19600679403905e-06 1.3341168522661e-05 3.67498065997086e-08 4.04623957171007e-06 7.99428960669496e-07 -2.19082842321728e-06 -5.11736367647247e-07 3.67498065997086e-08 7.03861035895426e-05 2.82428778620796e-06 1.17465857834746e-05 1.78106872232004e-06 -1.30780712403709e-06 4.04623957171007e-06 2.82428778620796e-06 1.53207310158814e-05 -1.45286057991358e-06 -1.47327175924607e-05 -4.9872859711139e-06 7.99428960669496e-07 1.17465857834746e-05 -1.45286057991358e-06 9.31365812895148e-05 3382 3369 0 1092 121 3382 3369 0 979 154 0 0 0 0 0 0 0 0 2683 0 0 0 0 0 3470 +120 123 0.994700346027883 0.00113027583294033 0.102810233384383 0.416938371173421 0.000467736842770371 0.999879480935941 -0.0155178872762955 -0.00268819332645314 -0.102815382284247 0.0154837359773205 0.994579937001511 -0.0148036074360037 6.53328074318486e-05 5.21692768401893e-06 3.95822894322196e-06 7.94504655988489e-07 6.55478158326846e-06 2.35524606729163e-06 5.21692768401893e-06 3.97041312667682e-05 -4.00845744423438e-07 -9.10285828111086e-06 -3.75952486071585e-06 -4.44589407635777e-06 3.95822894322196e-06 -4.00845744423438e-07 1.85364350788917e-05 -3.47699946529343e-06 1.91618981726543e-06 2.96505428191891e-06 7.94504655988489e-07 -9.10285828111086e-06 -3.47699946529343e-06 7.3506448912486e-05 8.57167503148101e-06 -4.87905204486276e-06 6.55478158326846e-06 -3.75952486071585e-06 1.91618981726543e-06 8.57167503148101e-06 1.63114978891179e-05 2.91202975272302e-06 2.35524606729163e-06 -4.44589407635777e-06 2.96505428191891e-06 -4.87905204486276e-06 2.91202975272302e-06 0.000145532304310658 3153 3111 0 721 470 3153 3111 0 607 512 0 0 0 0 0 0 0 0 3056 0 0 0 0 0 3147 +124 128 0.996906511207356 0.0575032596253085 0.053579688734085 0.562301672285955 -0.0604008676299593 0.996705477004422 0.0541288028588887 -0.0263124492612542 -0.0502905866134528 -0.0571976157007674 0.997095426554661 -0.0816083112066601 4.55448024026733e-05 -6.77923594225483e-06 5.46514428530877e-06 -1.01331832912102e-06 1.11767554220819e-06 7.54378294164727e-06 -6.77923594225483e-06 3.54871880967354e-05 -9.9163190770105e-07 -6.57223158984081e-07 1.17763135330143e-06 -4.67523768120478e-06 5.46514428530877e-06 -9.9163190770105e-07 1.40182417176953e-05 -2.127608002998e-06 2.47735643847326e-06 2.23601209040576e-06 -1.01331832912102e-06 -6.57223158984081e-07 -2.127608002998e-06 5.32076700220908e-05 -1.82729922331427e-06 1.02847113764362e-05 1.11767554220819e-06 1.17763135330143e-06 2.47735643847326e-06 -1.82729922331427e-06 1.31274675947286e-05 4.96264745163489e-07 7.54378294164727e-06 -4.67523768120478e-06 2.23601209040576e-06 1.02847113764362e-05 4.96264745163489e-07 0.00012549746743457 3189 3181 0 1165 547 3189 3181 0 1052 597 0 0 0 0 0 0 0 0 2559 0 0 0 0 0 3140 +123 125 0.996206189020637 0.084371076478002 -0.0213248777469557 0.271778341276981 -0.0849332977340146 0.996020803983754 -0.026998017845406 -0.0299860486395524 0.0189621700499889 0.0287067846597067 0.999408003080572 -0.0606837699446417 4.65411634043315e-05 -4.3387316378672e-06 4.22010418020715e-06 -8.83507511484126e-06 1.65377382746039e-06 -1.839344899988e-05 -4.3387316378672e-06 3.6533035778829e-05 -1.65164233280113e-06 4.70944407535066e-06 7.83808454700483e-07 1.47161577796918e-05 4.22010418020715e-06 -1.65164233280113e-06 1.37055513567922e-05 1.29976344698171e-06 4.01455169804882e-06 2.24461036895508e-06 -8.83507511484126e-06 4.70944407535066e-06 1.29976344698171e-06 5.27191164995376e-05 2.17333428919667e-06 3.95256821792471e-05 1.65377382746039e-06 7.83808454700483e-07 4.01455169804882e-06 2.17333428919667e-06 1.28539727946477e-05 4.94658789906724e-06 -1.839344899988e-05 1.47161577796918e-05 2.24461036895508e-06 3.95256821792471e-05 4.94658789906724e-06 0.000158801300116134 3473 3460 0 665 41 3473 3460 0 570 71 0 0 0 0 0 0 0 0 3132 0 0 0 0 0 3545 +123 126 0.993315011150017 0.115347590903773 -0.00449687633114822 0.41361188575913 -0.115392562318357 0.993253160311622 -0.0115202470711428 -0.0463363021553872 0.00313770388117093 0.0119621404302031 0.999923528081364 -0.0623137703119099 4.75548867868935e-05 1.91332798270902e-06 1.60841475324061e-06 2.07422047391999e-06 1.07310771091126e-06 -3.27517354208447e-06 1.91332798270902e-06 2.35990893716564e-05 -9.10811809173599e-07 -4.0466150158243e-06 5.39564937324485e-07 -1.11969198679142e-05 1.60841475324061e-06 -9.10811809173599e-07 1.3530347473832e-05 -1.45220917623735e-06 3.14159701076587e-06 -2.3220689262402e-06 2.07422047391999e-06 -4.0466150158243e-06 -1.45220917623735e-06 4.42580095974767e-05 5.53077955556798e-08 1.11755558078907e-05 1.07310771091126e-06 5.39564937324485e-07 3.14159701076587e-06 5.53077955556798e-08 1.43894240287978e-05 3.50208811354612e-06 -3.27517354208447e-06 -1.11969198679142e-05 -2.3220689262402e-06 1.11755558078907e-05 3.50208811354612e-06 9.67780087117024e-05 3372 3368 0 1047 141 3372 3368 0 938 174 0 0 0 0 0 0 0 0 2720 0 0 0 0 0 3478 +121 124 0.997022189426839 0.0712138045025075 0.0295862778799598 0.425643649909353 -0.0702310999347324 0.99698395756243 -0.0330239453292934 -0.028230997469186 -0.0318488051968859 0.0308477294372402 0.999016552013077 -0.0135515787439719 5.11888455457669e-05 5.44955163444239e-06 8.53267901389719e-06 1.38581578654302e-06 5.02294226878343e-06 -6.16311381329093e-06 5.44955163444239e-06 5.16067900717188e-05 7.22451339656831e-07 -1.02290399401616e-05 -6.24057715326463e-07 1.47212797748921e-05 8.53267901389719e-06 7.22451339656831e-07 1.63120982976905e-05 -6.08609012434121e-06 -2.3444786378431e-07 1.12403383558969e-06 1.38581578654302e-06 -1.02290399401616e-05 -6.08609012434121e-06 9.05502582128356e-05 1.07993175384442e-05 -8.97947929457738e-07 5.02294226878343e-06 -6.24057715326463e-07 -2.3444786378431e-07 1.07993175384442e-05 1.66675095861319e-05 3.73464316242555e-06 -6.16311381329093e-06 1.47212797748921e-05 1.12403383558969e-06 -8.97947929457738e-07 3.73464316242555e-06 0.000210651620666571 3370 3342 0 977 266 3370 3342 0 856 305 0 0 0 0 0 0 0 0 2811 0 0 0 0 0 3356 +125 127 0.999073911258297 0.0330575276031698 0.0275412365701599 0.270185549492227 -0.0337202957689877 0.999144110967776 0.0239580293777475 -0.00367562401460904 -0.0267256711103732 -0.0248645407594568 0.99933352446344 -0.0590215482477863 3.45868233930743e-05 -1.49931384836587e-06 5.22421539112392e-06 4.53601406310809e-06 2.28523269144401e-06 2.14102071888403e-05 -1.49931384836587e-06 2.59547627304951e-05 2.76884709383313e-06 1.41844269254132e-06 2.08621681279765e-07 -6.70166681004373e-06 5.22421539112392e-06 2.76884709383313e-06 1.22301585432521e-05 -3.43173308415856e-06 4.11763859002637e-06 -3.74458808875935e-06 4.53601406310809e-06 1.41844269254132e-06 -3.43173308415856e-06 8.7913996751662e-05 5.36980991026981e-06 1.96060221653449e-05 2.28523269144401e-06 2.08621681279765e-07 4.11763859002637e-06 5.36980991026981e-06 1.33796602837956e-05 7.90568775227385e-06 2.14102071888403e-05 -6.70166681004373e-06 -3.74458808875935e-06 1.96060221653449e-05 7.90568775227385e-06 0.000122219872895225 3357 3351 0 453 211 3357 3351 0 379 253 0 0 0 0 0 0 0 0 3314 0 0 0 0 0 3418 +124 127 0.996473474764752 0.0773444425332964 0.0325338485192818 0.41848379927666 -0.0783176038099977 0.996483480023245 0.0297829980731046 -0.030334911764131 -0.0301158932081085 -0.0322259406375661 0.999026787291663 -0.0540659472270281 5.13916184631422e-05 8.19132052656252e-06 3.60530177795223e-06 -1.05399602009893e-06 1.25477851919624e-06 9.99004311022632e-06 8.19132052656252e-06 3.36604163381177e-05 1.66593527493873e-06 -1.71301649962734e-06 -2.35290425568263e-07 -3.06936201606601e-06 3.60530177795223e-06 1.66593527493873e-06 1.49118154072734e-05 -1.58885724976381e-06 4.07328400360588e-06 2.62993377071349e-07 -1.05399602009893e-06 -1.71301649962734e-06 -1.58885724976381e-06 6.33469874224416e-05 5.7134256679552e-07 4.60598113206875e-05 1.25477851919624e-06 -2.35290425568263e-07 4.07328400360588e-06 5.7134256679552e-07 1.4471045325747e-05 1.13144457866909e-05 9.99004311022632e-06 -3.06936201606601e-06 2.62993377071349e-07 4.60598113206875e-05 1.13144457866909e-05 0.000224084409246551 3294 3288 0 899 268 3294 3288 0 796 320 0 0 0 0 0 0 0 0 2856 0 0 0 0 0 3360 +124 126 0.9973121971597 0.0731231800492263 0.00462406055106683 0.266674131538157 -0.0732221595505807 0.996946598490162 0.0271292298019193 -0.0290581606151188 -0.00262616588219604 -0.0273948954804443 0.999621239747523 -0.0819116567202514 4.94738698400198e-05 -4.39734242918526e-06 1.21900102524278e-05 -4.5140604228253e-06 -1.30255141469391e-06 -4.76157158781048e-06 -4.39734242918526e-06 6.85439579906898e-05 -2.002709542857e-07 2.9702829772379e-06 1.49966381164531e-06 1.17926995734823e-05 1.21900102524278e-05 -2.002709542857e-07 1.56719366275098e-05 -4.77132732938668e-06 1.77106713126708e-06 -9.11077080058289e-06 -4.5140604228253e-06 2.9702829772379e-06 -4.77132732938668e-06 6.52920558429307e-05 4.82006302677826e-06 5.5678166908836e-05 -1.30255141469391e-06 1.49966381164531e-06 1.77106713126708e-06 4.82006302677826e-06 1.46649439676743e-05 1.18593757572861e-05 -4.76157158781048e-06 1.17926995734823e-05 -9.11077080058289e-06 5.5678166908836e-05 1.18593757572861e-05 0.00022099730630619 3383 3379 0 597 70 3383 3379 0 513 115 0 0 0 0 0 0 0 0 3180 0 0 0 0 0 3538 +127 129 0.998741921941829 -0.0496229757148015 0.00722036267439523 0.28212665614852 0.0493664557089556 0.99826204302367 0.0321845694229901 0.0392848325194284 -0.00880490810158201 -0.0317876350082192 0.999455861883809 0.0252496080489614 3.3278892496005e-05 -8.87893815588334e-06 1.09507411811305e-05 -1.22986743527162e-07 2.83744421435222e-06 -3.82482890049656e-06 -8.87893815588334e-06 2.31620364332494e-05 -1.64527656691637e-06 1.86790193868352e-06 -1.7286763180693e-06 4.48264179889965e-06 1.09507411811305e-05 -1.64527656691637e-06 1.30996557718035e-05 -6.25184690035547e-07 2.31010833955248e-06 -3.14487040156477e-07 -1.22986743527162e-07 1.86790193868352e-06 -6.25184690035547e-07 9.84062231923116e-05 5.70239033738773e-06 4.37075595024914e-07 2.83744421435222e-06 -1.7286763180693e-06 2.31010833955248e-06 5.70239033738773e-06 1.41915792063716e-05 -3.36467906411742e-06 -3.82482890049656e-06 4.48264179889965e-06 -3.14487040156477e-07 4.37075595024914e-07 -3.36467906411742e-06 0.000164161088395968 3411 3393 0 177 472 3411 3393 0 107 537 0 0 0 0 0 0 0 0 3573 0 0 0 0 0 3187 +125 128 0.997656709009419 0.0138215312025555 0.0670078819521374 0.425386287561915 -0.0166995451672317 0.998953389974927 0.0425822715318104 0.00889229515365411 -0.0663491986364748 -0.0436014900297917 0.996843364780786 -0.0437872740104663 3.22569661004748e-05 -1.04739801019943e-05 6.62948717964257e-06 2.36542111480606e-06 1.55937154363152e-06 2.34539591972327e-05 -1.04739801019943e-05 0.000966821404653748 1.20064803141767e-05 0.000219979997986946 5.52984551871329e-05 -0.000647781168884658 6.62948717964257e-06 1.20064803141767e-05 1.24046624123445e-05 1.81260888718988e-06 3.61883199945477e-06 -9.8215107735094e-06 2.36542111480606e-06 0.000219979997986946 1.81260888718988e-06 9.63417771587796e-05 1.10761074477781e-05 -0.000121497010919337 1.55937154363152e-06 5.52984551871329e-05 3.61883199945477e-06 1.10761074477781e-05 1.45919403746464e-05 -3.73510526938034e-05 2.34539591972327e-05 -0.000647781168884658 -9.8215107735094e-06 -0.000121497010919337 -3.73510526938034e-05 0.000640869880684372 3238 3230 0 668 493 3238 3230 0 576 549 0 0 0 0 0 0 0 0 3077 0 0 0 0 0 3184 +128 130 0.994468293770096 -0.0818274692093953 -0.0658564952664453 0.294878389333487 0.0831718992414656 0.996373829539196 0.0179339618033781 0.0531592875495732 0.0641501976813896 -0.0233121661838403 0.997667928243289 -0.0424425545978107 4.35954639638713e-05 -1.7934333915361e-05 1.08468153981095e-06 2.71557722719737e-05 3.48070375295296e-06 8.98338823598772e-06 -1.7934333915361e-05 4.10476342425801e-05 -1.87350959540972e-07 -6.53878598203703e-07 2.08142868856601e-06 -2.20021044569574e-05 1.08468153981095e-06 -1.87350959540972e-07 1.41910014533215e-05 -3.6353038902958e-06 1.56311956268485e-06 -1.60663789524026e-06 2.71557722719737e-05 -6.53878598203703e-07 -3.6353038902958e-06 0.000166722926255727 7.48642198495129e-06 2.50219349047271e-05 3.48070375295296e-06 2.08142868856601e-06 1.56311956268485e-06 7.48642198495129e-06 1.43343473978398e-05 -4.61064180974523e-06 8.98338823598772e-06 -2.20021044569574e-05 -1.60663789524026e-06 2.50219349047271e-05 -4.61064180974523e-06 0.000113713526734489 3339 3300 0 98 580 3339 3300 0 23 640 0 0 0 0 0 0 0 0 3629 0 0 0 0 0 3109 +125 129 0.999253576718805 -0.0177036421929328 0.0343346831612062 0.56859212330458 0.0157024800333777 0.998210322002336 0.0577025577318218 0.0274585386025212 -0.035294780569897 -0.0571203475225551 0.997743225666517 -0.0411863292604404 6.46957677900309e-05 3.44477026541633e-06 1.02519240577644e-05 -8.14430376590435e-06 3.50859517082338e-06 2.87634745461299e-05 3.44477026541633e-06 4.83425617848103e-05 8.65400737173308e-07 -1.0198445842142e-05 -1.06472781260602e-06 2.64494401133371e-05 1.02519240577644e-05 8.65400737173308e-07 1.5635357517176e-05 7.40332745555626e-07 2.31589362583081e-06 -3.38048008301774e-06 -8.14430376590435e-06 -1.0198445842142e-05 7.40332745555626e-07 0.000103968436148457 8.10472207493003e-07 -1.0529346267566e-06 3.50859517082338e-06 -1.06472781260602e-06 2.31589362583081e-06 8.10472207493003e-07 1.43740185401561e-05 2.79986876824456e-06 2.87634745461299e-05 2.64494401133371e-05 -3.38048008301774e-06 -1.0529346267566e-06 2.79986876824456e-06 0.000221701745002396 3256 3238 0 850 842 3256 3238 0 750 908 0 0 0 0 0 0 0 0 2869 0 0 0 0 0 2819 +126 128 0.998764569946608 -0.0167506149618015 0.0467840861593723 0.285591680604602 0.0152909506020695 0.999390381558214 0.0313855393232794 0.0219665271832341 -0.0472812928022402 -0.0306313915343316 0.998411837471701 -0.0100563440262153 3.02804957204982e-05 3.58655632251665e-06 9.92595097568544e-06 1.0963952411587e-07 1.89608415249545e-06 4.61148403906538e-05 3.58655632251665e-06 6.83110671790175e-05 -6.14676118980198e-07 2.51989698816049e-05 1.15543611243036e-06 0.000212916243349476 9.92595097568544e-06 -6.14676118980198e-07 1.17734261281529e-05 -2.8903244064842e-06 2.65116231123428e-06 -3.57309645291502e-06 1.0963952411587e-07 2.51989698816049e-05 -2.8903244064842e-06 6.8077767151845e-05 2.72422436281239e-06 0.000130552217985581 1.89608415249545e-06 1.15543611243036e-06 2.65116231123428e-06 2.72422436281239e-06 1.21773388337657e-05 2.32540926096345e-06 4.61148403906538e-05 0.000212916243349476 -3.57309645291502e-06 0.000130552217985581 2.32540926096345e-06 0.0011944907134641 3421 3413 0 303 380 3421 3413 0 222 436 0 0 0 0 0 0 0 0 3460 0 0 0 0 0 3292 +126 129 0.998495261503656 -0.0474064247519629 0.0275652615982987 0.428077774742368 0.0462475650017838 0.998077580836909 0.0412590034071334 0.0461047235313907 -0.0294682114515278 -0.0399220931688274 0.998768166788904 0.00275271990404709 3.69834702438649e-05 -3.25333279864061e-06 7.83192101227804e-06 -4.23321272137416e-06 3.0267256454717e-06 -6.02500554631973e-07 -3.25333279864061e-06 2.36747496350165e-05 -1.40064196490966e-07 -3.57499081195007e-06 -1.93010122395589e-06 -5.55960380236106e-06 7.83192101227804e-06 -1.40064196490966e-07 1.2235112009899e-05 -1.31298506041326e-06 2.78001782617579e-06 2.0258322594048e-06 -4.23321272137416e-06 -3.57499081195007e-06 -1.31298506041326e-06 7.49074740858549e-05 2.50856989552515e-06 -3.06179940844953e-07 3.0267256454717e-06 -1.93010122395589e-06 2.78001782617579e-06 2.50856989552515e-06 1.37370928263424e-05 5.09077054122233e-07 -6.02500554631973e-07 -5.55960380236106e-06 2.0258322594048e-06 -3.06179940844953e-07 5.09077054122233e-07 0.000105797818719043 3383 3365 0 425 712 3383 3365 0 335 772 0 0 0 0 0 0 0 0 3308 0 0 0 0 0 2946 +129 131 0.993577624129106 -0.108402919193444 -0.0324393578897568 0.257888812024958 0.107820395241743 0.993984912345219 -0.0192030310102524 0.0587492154217438 0.0343258969274587 0.0155820775381822 0.999289213220937 -0.00613790770659004 3.76211882840273e-05 -4.39364015057364e-06 8.51006225823919e-06 7.02992017214876e-06 1.73960373536251e-06 -1.64448700294461e-05 -4.39364015057364e-06 2.47030175906881e-05 -1.91228998428991e-06 -1.31537732989496e-06 1.22326552805464e-06 5.84178804459296e-06 8.51006225823919e-06 -1.91228998428991e-06 1.34539888007802e-05 -4.04362085682617e-06 -8.60082808520455e-07 -3.76092996312519e-06 7.02992017214876e-06 -1.31537732989496e-06 -4.04362085682617e-06 0.000186969607050991 -3.92153685638582e-06 1.01465061370566e-05 1.73960373536251e-06 1.22326552805464e-06 -8.60082808520455e-07 -3.92153685638582e-06 1.57240096951402e-05 4.06165309634933e-06 -1.64448700294461e-05 5.84178804459296e-06 -3.76092996312519e-06 1.01465061370566e-05 4.06165309634933e-06 0.000132553117572172 3449 3394 0 1 581 3413 3394 0 0 629 0 0 0 0 0 0 0 0 3729 0 0 0 0 0 3117 +130 132 0.996136568141474 -0.0845199963747224 0.0238392077079481 0.263837348079107 0.0849891970673739 0.996192870040773 -0.0194062377026361 0.0441462760173466 -0.0221082336058052 0.0213573381474625 0.999527433397446 -0.0301671841030946 4.03397775437011e-05 -2.36117696797886e-06 8.64359125022298e-06 -3.66618594518075e-06 3.11890197201843e-07 2.62323195694699e-07 -2.36117696797886e-06 2.72855231210031e-05 -1.59810321017539e-06 4.19450381180023e-06 -4.74375584708889e-07 -7.46832676874554e-06 8.64359125022298e-06 -1.59810321017539e-06 1.24613998576186e-05 -6.05899510547586e-07 2.88826839604743e-06 -3.41471785611819e-06 -3.66618594518075e-06 4.19450381180023e-06 -6.05899510547586e-07 0.00023912799649731 -9.62324524804663e-06 6.34309942765578e-05 3.11890197201843e-07 -4.74375584708889e-07 2.88826839604743e-06 -9.62324524804663e-06 1.36777195467547e-05 -5.87691315831256e-07 2.62323195694699e-07 -7.46832676874554e-06 -3.41471785611819e-06 6.34309942765578e-05 -5.87691315831256e-07 0.000106224137090761 3375 3304 0 103 514 3375 3304 0 13 553 0 0 0 0 0 0 0 0 3610 0 0 0 0 0 3172 +129 132 0.990078730638741 -0.138284047534384 -0.0249324955487405 0.414190835545213 0.13786172017697 0.990289048878942 -0.0179372734908774 0.0857182752518204 0.0271708160831904 0.0143220762443138 0.999528201145633 -0.0818267919317927 5.74242809431847e-05 -2.48872627633927e-05 9.9217284360596e-06 2.14254630458683e-06 1.52287519157456e-06 3.09452927307917e-05 -2.48872627633927e-05 0.000121466703224076 6.29624404574471e-07 -1.20951349744197e-05 7.53472971743647e-07 -8.95239080361472e-05 9.9217284360596e-06 6.29624404574471e-07 1.48620160370981e-05 2.68564623576371e-06 3.2676457973173e-06 -2.26708457476929e-06 2.14254630458683e-06 -1.20951349744197e-05 2.68564623576371e-06 0.000139188781057017 -3.37002141870455e-06 2.70290848496228e-05 1.52287519157456e-06 7.53472971743647e-07 3.2676457973173e-06 -3.37002141870455e-06 1.35671847436879e-05 -1.86411973245121e-06 3.09452927307917e-05 -8.95239080361472e-05 -2.26708457476929e-06 2.70290848496228e-05 -1.86411973245121e-06 0.000150791368491064 3326 3255 0 158 915 3326 3255 0 63 968 0 0 0 0 0 0 0 0 3563 0 0 0 0 0 2749 +128 131 0.98869123517996 -0.138468980404429 -0.0575845721012449 0.419071312557684 0.138244207552949 0.990366757977866 -0.00788820451486576 0.0895148399144952 0.0581221176178477 -0.00016173487225749 0.998309467692984 -0.0160668255167668 5.25954870328198e-05 -3.00939269735197e-06 4.87789418290179e-06 2.01225884974453e-05 4.05083749834473e-06 1.47913169726282e-05 -3.00939269735197e-06 3.20117786536429e-05 1.07401615171954e-06 -4.99288175530689e-06 2.18288398602528e-06 9.9498105972671e-06 4.87789418290179e-06 1.07401615171954e-06 1.33255916614966e-05 -8.63779059122837e-07 3.20501459585077e-07 -2.88882380988542e-07 2.01225884974453e-05 -4.99288175530689e-06 -8.63779059122837e-07 0.000153536807508445 1.67576330861627e-06 4.21929847279521e-05 4.05083749834473e-06 2.18288398602528e-06 3.20501459585077e-07 1.67576330861627e-06 1.66918797797365e-05 3.97425269490736e-06 1.47913169726282e-05 9.9498105972671e-06 -2.88882380988542e-07 4.21929847279521e-05 3.97425269490736e-06 0.000227635917620539 3364 3309 0 120 945 3364 3309 0 35 1010 0 0 0 0 0 0 0 0 3584 0 0 0 0 0 2737 +130 134 0.996867070935122 -0.0411538672049156 0.0675455557332306 0.578297197965066 0.0417554842899893 0.999099568777857 -0.0075187232698542 0.04680485413504 -0.0671753110669333 0.0103155650344688 0.997687860355673 -0.0427204123615933 4.45760468297459e-05 9.98634721379418e-07 8.0283132271318e-06 2.32707929716079e-05 -3.13459089511835e-07 1.13521029278743e-05 9.98634721379418e-07 4.8308101477962e-05 -1.21792523858332e-06 1.12308495414725e-05 -1.56418069322847e-06 5.40314867764919e-05 8.0283132271318e-06 -1.21792523858332e-06 1.72498807921231e-05 -1.0310304567316e-05 1.57645163698679e-06 -1.52464787947781e-07 2.32707929716079e-05 1.12308495414725e-05 -1.0310304567316e-05 0.000292826685619033 -6.6041189401859e-06 9.08334477055116e-05 -3.13459089511835e-07 -1.56418069322847e-06 1.57645163698679e-06 -6.6041189401859e-06 1.38728171178983e-05 -1.36142341049442e-05 1.13521029278743e-05 5.40314867764919e-05 -1.52464787947781e-07 9.08334477055116e-05 -1.36142341049442e-05 0.000486321654900772 3245 3188 0 906 870 3245 3188 0 777 919 0 0 0 0 0 0 0 0 2833 0 0 0 0 0 2868 +132 135 0.99581813216068 0.0891006672583975 0.0201821394833018 0.4597607156026 -0.0886627486193361 0.995826506081194 -0.0216445557447134 -0.0471694538499258 -0.0220264538062653 0.0197646371135398 0.999562001304817 -0.0196263414009793 4.17012925924191e-05 -1.86656917696734e-06 1.0556986283781e-05 4.01386108412504e-06 1.1844061467425e-06 1.09886221290777e-05 -1.86656917696734e-06 4.81328413481326e-05 -4.82277562742749e-06 -9.58828194266714e-06 2.71779249149752e-06 -1.92161546761347e-05 1.0556986283781e-05 -4.82277562742749e-06 1.50147382068861e-05 1.32221159187747e-06 2.19228412786126e-06 2.52044991387302e-06 4.01386108412504e-06 -9.58828194266714e-06 1.32221159187747e-06 0.000130084166110681 2.47696657837951e-07 6.5489968373065e-05 1.1844061467425e-06 2.71779249149752e-06 2.19228412786126e-06 2.47696657837951e-07 1.35103504123046e-05 2.24723043007458e-07 1.09886221290777e-05 -1.92161546761347e-05 2.52044991387302e-06 6.5489968373065e-05 2.24723043007458e-07 0.000245151712483041 3282 3236 0 1217 213 3282 3236 0 1073 252 0 0 0 0 0 0 0 0 2542 0 0 0 0 0 3573 +131 133 0.997556718677617 -0.0261895394107924 0.0647665117680135 0.272028719668427 0.0252629066009458 0.999567016991729 0.0150852276193919 0.00972753309946456 -0.0651335441321718 -0.0134121798268412 0.997786417456699 -0.0298924355510691 2.7263899016431e-05 2.9248370903604e-06 1.05304917808676e-05 -3.16834479661636e-06 1.13073785955689e-06 1.08662788073622e-06 2.9248370903604e-06 1.91663324025152e-05 -1.4296825854399e-06 5.63927860285976e-06 -1.02816337625827e-06 -5.10293992291714e-06 1.05304917808676e-05 -1.4296825854399e-06 1.18152424766218e-05 1.23524662597898e-06 1.7690302945377e-06 1.30265009452801e-06 -3.16834479661636e-06 5.63927860285976e-06 1.23524662597898e-06 0.000190696290356576 -1.27253315828906e-05 7.01698928469201e-05 1.13073785955689e-06 -1.02816337625827e-06 1.7690302945377e-06 -1.27253315828906e-05 1.30138664856008e-05 -6.25966911718231e-06 1.08662788073622e-06 -5.10293992291714e-06 1.30265009452801e-06 7.01698928469201e-05 -6.25966911718231e-06 8.44844642561296e-05 3478 3405 0 349 328 3478 3405 0 230 359 0 0 0 0 0 0 0 0 3382 0 0 0 0 0 3391 +134 138 0.990763635559395 0.133533074562795 -0.0235867855151652 0.561789176826157 -0.133920893769861 0.990867626409526 -0.0157016287509858 -0.093244360483209 0.0212746954152796 0.0187153661828795 0.999598480592897 -0.0120494895917593 4.26412170800053e-05 1.05830692981672e-05 5.70289090325355e-06 -2.27625751852795e-05 -1.63752538067127e-07 -1.40891413301503e-05 1.05830692981672e-05 3.3346694815297e-05 4.95958585505145e-06 -5.99634745313411e-06 -1.92996228957908e-06 -2.07607540388872e-05 5.70289090325355e-06 4.95958585505145e-06 1.35339155098387e-05 2.03214788933366e-06 3.22400098294556e-06 -5.92373450997336e-06 -2.27625751852795e-05 -5.99634745313411e-06 2.03214788933366e-06 0.000183703869243268 1.67199147068206e-06 5.38943932934532e-06 -1.63752538067127e-07 -1.92996228957908e-06 3.22400098294556e-06 1.67199147068206e-06 1.25779943133316e-05 1.74731589546047e-06 -1.40891413301503e-05 -2.07607540388872e-05 -5.92373450997336e-06 5.38943932934532e-06 1.74731589546047e-06 8.89114957607237e-05 3363 3357 0 1586 222 3363 3357 0 1437 259 0 0 0 0 0 0 0 0 2158 0 0 0 0 0 3583 +133 135 0.995966136016107 0.0849953926952017 -0.0287617650663814 0.270562315815996 -0.0860312545498258 0.995607793479064 -0.0369289155585661 -0.0343027102267482 0.0254966497745949 0.0392543600678583 0.99890390732339 -0.0503483977117217 5.56320968129349e-05 1.13156182490569e-05 1.1118001950933e-06 -9.44965155134113e-06 9.06298483097015e-07 -2.86764197302047e-05 1.13156182490569e-05 4.9494839923548e-05 2.99438582047824e-07 1.11556916368313e-05 4.17306405088119e-07 1.31058900692901e-05 1.1118001950933e-06 2.99438582047824e-07 1.31083931557237e-05 -1.50331076188598e-06 4.07445032242275e-06 -3.15809260517068e-06 -9.44965155134113e-06 1.11556916368313e-05 -1.50331076188598e-06 0.000450784313003929 -2.23896216915985e-06 2.77822816494497e-05 9.06298483097015e-07 4.17306405088119e-07 4.07445032242275e-06 -2.23896216915985e-06 1.21033668067205e-05 2.29288006664315e-06 -2.86764197302047e-05 1.31058900692901e-05 -3.15809260517068e-06 2.77822816494497e-05 2.29288006664315e-06 0.000219952529649537 3394 3346 0 732 25 3394 3348 0 608 46 0 0 0 0 0 0 0 0 3049 0 0 0 0 0 3772 +134 136 0.994910564441588 0.0892066388452978 -0.0468523675863435 0.270579409421923 -0.0906217028146107 0.995463155703123 -0.0289967690710494 -0.041684542156711 0.0440531013834626 0.0330950332150307 0.998480867635927 -0.0354964520590291 4.47102728571078e-05 3.9647044726987e-06 6.50390580633921e-06 1.29608007722425e-05 -3.44501533732163e-07 -1.72035604065065e-05 3.9647044726987e-06 4.93803765986692e-05 -1.64165843453168e-06 -2.05201230582218e-05 -2.2721673665646e-06 -2.06031855927013e-05 6.50390580633921e-06 -1.64165843453168e-06 1.46818935979542e-05 -2.17451032034971e-06 2.12929035592829e-06 -3.0880119756442e-06 1.29608007722425e-05 -2.05201230582218e-05 -2.17451032034971e-06 0.000205682733842351 5.59745457684345e-06 4.03159326669754e-05 -3.44501533732163e-07 -2.2721673665646e-06 2.12929035592829e-06 5.59745457684345e-06 1.31191529465906e-05 4.92762034673137e-06 -1.72035604065065e-05 -2.06031855927013e-05 -3.0880119756442e-06 4.03159326669754e-05 4.92762034673137e-06 0.00014498967553176 3380 3340 0 732 14 3381 3352 0 621 27 0 0 0 0 0 0 0 0 3058 0 0 2 0 0 3791 +136 138 0.999034717297164 0.042688374496891 0.0103603242125111 0.278067589708347 -0.0428653872985682 0.998927379043086 0.0175114239813492 -0.0264799286257803 -0.00960167728675069 -0.017938619816586 0.999792985428662 -0.036948035493031 4.5742749438549e-05 -5.57784807466265e-06 5.94775524850162e-06 1.4460113385927e-06 7.57921821669581e-07 1.00667190445743e-06 -5.57784807466265e-06 9.60928277729225e-05 -2.71482059622311e-06 -1.90080936346292e-05 -5.88020639181013e-07 4.27219282808796e-05 5.94775524850162e-06 -2.71482059622311e-06 1.46222701731311e-05 2.1700266243912e-06 3.76198686639427e-06 1.11260443992341e-06 1.4460113385927e-06 -1.90080936346292e-05 2.1700266243912e-06 0.000198432003603313 8.78018732933369e-06 3.13820402651597e-05 7.57921821669581e-07 -5.88020639181013e-07 3.76198686639427e-06 8.78018732933369e-06 1.28543230080058e-05 1.22781933952278e-06 1.00667190445743e-06 4.27219282808796e-05 1.11260443992341e-06 3.13820402651597e-05 1.22781933952278e-06 0.000480797761947648 3213 3207 0 536 158 3213 3207 0 454 198 0 0 0 0 0 0 0 0 3237 0 0 0 0 0 3634 +139 143 0.983184995875481 -0.149322852442489 -0.10511874059257 0.519337162336574 0.146824904793033 0.988671665365399 -0.0311574298703422 0.0942374476610074 0.108580436625786 0.0151994684790953 0.993971460827778 -0.0619119086992143 6.74754703747254e-05 -2.7842034980689e-05 3.8463389028578e-06 -7.83845156005695e-05 7.413723593966e-06 7.11616573413275e-06 -2.7842034980689e-05 4.50983865998934e-05 -4.59606583459481e-07 3.97555560783596e-05 -4.48010491619558e-06 8.84285910754129e-07 3.8463389028578e-06 -4.59606583459481e-07 1.45927256158601e-05 -6.23441118729533e-06 3.46654006269315e-06 -9.01371717804603e-06 -7.83845156005695e-05 3.97555560783596e-05 -6.23441118729533e-06 0.00116000177104575 -0.000100592408443409 7.71428373378133e-06 7.413723593966e-06 -4.48010491619558e-06 3.46654006269315e-06 -0.000100592408443409 2.21352640257237e-05 9.69681417571197e-06 7.11616573413275e-06 8.84285910754129e-07 -9.01371717804603e-06 7.71428373378133e-06 9.69681417571197e-06 0.000198701530777384 3167 3102 0 323 1113 3167 3102 0 203 1165 0 0 0 0 0 0 0 0 3405 0 0 0 0 0 2596 +142 145 0.999380361766882 0.0113037642262138 0.0333334281017575 0.453721936761725 -0.0113032410075687 0.99993609549234 -0.000204142742928985 0.0146363194164226 -0.0333336055268806 -0.000172759523162176 0.999444266028239 -0.0870350236315471 6.49543131559193e-05 1.91749012504445e-05 7.95461131028917e-07 -5.27176637140439e-05 3.1863287611365e-06 -1.75917701438144e-08 1.91749012504445e-05 4.81767643704285e-05 3.30617367465401e-06 6.52134256158887e-05 -1.93481019247744e-06 2.17373263651409e-05 7.95461131028917e-07 3.30617367465401e-06 1.5461149074064e-05 6.21218889737595e-06 4.70885514967423e-06 -1.04731080451936e-05 -5.27176637140439e-05 6.52134256158887e-05 6.21218889737595e-06 0.00142967431314194 -6.88214538529935e-05 2.43477413478081e-05 3.1863287611365e-06 -1.93481019247744e-06 4.70885514967423e-06 -6.88214538529935e-05 1.52658354292386e-05 6.55146993564535e-06 -1.75917701438144e-08 2.17373263651409e-05 -1.04731080451936e-05 2.43477413478081e-05 6.55146993564535e-06 0.000209796998752199 3385 3323 0 848 492 3385 3323 0 713 529 0 0 0 0 0 0 0 0 2896 0 0 0 0 0 3275 +145 149 0.98972759782179 0.118839508817279 0.0794761175069397 0.584871075384028 -0.123334924153312 0.990880711855613 0.054257822999187 -0.0835486673387046 -0.0723033788560785 -0.0635026457447434 0.995359048479197 -0.123492905837825 5.79845900397626e-05 -4.01933802848457e-06 8.12351442570422e-06 -3.61895162928142e-06 9.79063440655322e-07 -1.19936747238137e-05 -4.01933802848457e-06 2.80086075947914e-05 -2.89504265836343e-06 3.19833749474671e-05 2.60414050853809e-06 1.34146849881353e-06 8.12351442570422e-06 -2.89504265836343e-06 1.64649657025261e-05 1.0535692522881e-05 5.31039672150532e-06 9.51718611184994e-06 -3.61895162928142e-06 3.19833749474671e-05 1.0535692522881e-05 0.00129124900436335 7.94441386804069e-05 0.000175122058810322 9.79063440655322e-07 2.60414050853809e-06 5.31039672150532e-06 7.94441386804069e-05 1.77794322158441e-05 7.34648427857958e-06 -1.19936747238137e-05 1.34146849881353e-06 9.51718611184994e-06 0.000175122058810322 7.34648427857958e-06 0.000128072407463766 3035 3019 0 1616 315 3035 3019 0 1458 345 0 0 0 0 0 0 0 0 2040 0 0 0 0 0 3520 +148 150 0.9950428336049 -0.0785218395116437 0.0610252407716662 0.343255703378994 0.0799033566666438 0.996591092440118 -0.0205340707706857 0.0467742540348196 -0.0592048383574795 0.0253084015441529 0.997924983115637 -0.0334593819153214 6.7506787077149e-05 -5.76775197845175e-06 1.26438137244909e-05 2.43398001809923e-05 2.1813419084336e-06 -8.86365430715173e-06 -5.76775197845175e-06 5.07108408115972e-05 1.29607036672931e-06 -1.14395276280173e-05 -9.48665997232048e-07 3.81875093978868e-05 1.26438137244909e-05 1.29607036672931e-06 1.74385609911172e-05 5.03820513772373e-06 4.97472766908805e-06 3.4007360666608e-06 2.43398001809923e-05 -1.14395276280173e-05 5.03820513772373e-06 0.00017143705476278 2.10237148895392e-06 -6.2050894758033e-06 2.1813419084336e-06 -9.48665997232048e-07 4.97472766908805e-06 2.10237148895392e-06 1.13890350794173e-05 -1.72306320232682e-06 -8.86365430715173e-06 3.81875093978868e-05 3.4007360666608e-06 -6.2050894758033e-06 -1.72306320232682e-06 0.000303271725709744 3055 3022 0 206 633 3055 3022 0 129 690 0 0 0 0 0 0 0 0 3530 0 0 0 0 0 3143 +147 151 0.989445524743678 -0.0930772057986138 0.111059386480521 0.581713354641221 0.0918448415904533 0.995641991664005 0.0161724923422045 0.0493315230767163 -0.112080679146461 -0.00580156841350924 0.993682174121088 -0.195470314689803 4.52928445520013e-05 -5.80089634147568e-06 1.48866974964011e-05 1.02535631488497e-05 1.2479900028539e-06 3.88319236392913e-06 -5.80089634147568e-06 2.56200886948584e-05 9.4821828900838e-07 -1.22164072552905e-06 -6.20440015731784e-07 -6.59244313506685e-06 1.48866974964011e-05 9.4821828900838e-07 1.74564342525795e-05 8.56544397144952e-06 3.07070940028012e-06 3.16857169714205e-06 1.02535631488497e-05 -1.22164072552905e-06 8.56544397144952e-06 0.000473740192792661 -9.8239373528834e-06 1.50177684993062e-06 1.2479900028539e-06 -6.20440015731784e-07 3.07070940028012e-06 -9.8239373528834e-06 1.24450598468781e-05 5.30541251303287e-07 3.88319236392913e-06 -6.59244313506685e-06 3.16857169714205e-06 1.50177684993062e-06 5.30541251303287e-07 7.78265883155066e-05 2724 2683 0 642 1026 2724 2683 0 535 1080 0 0 0 0 0 0 0 0 2967 0 0 0 0 0 2716 +150 152 0.996527222877952 -0.062338223602401 0.0552036225374239 0.289638033747667 0.062465633723005 0.998046944645988 -0.000583854768605177 0.0431295033511319 -0.0550594103377497 0.00403015643672791 0.998474946692382 -0.135576345287186 4.32553446224156e-05 -1.17501122991591e-05 1.0720133239537e-05 -1.167358578476e-07 2.06862221590879e-06 1.24011693906343e-05 -1.17501122991591e-05 9.03910822135999e-05 2.06182232736976e-06 2.20032479773708e-05 -3.49057215916754e-07 9.32080282958298e-05 1.0720133239537e-05 2.06182232736976e-06 1.62482727000342e-05 -4.71033366824051e-06 3.84743538215949e-06 -5.61299843600957e-06 -1.167358578476e-07 2.20032479773708e-05 -4.71033366824051e-06 0.000570134666163485 -2.12201905685951e-05 0.00021181124017476 2.06862221590879e-06 -3.49057215916754e-07 3.84743538215949e-06 -2.12201905685951e-05 1.30816963687433e-05 -8.98565885668866e-06 1.24011693906343e-05 9.32080282958298e-05 -5.61299843600957e-06 0.00021181124017476 -8.98565885668866e-06 0.000467384333049313 3311 3255 0 206 508 3311 3255 0 120 551 0 0 0 0 0 0 0 0 3486 0 0 0 0 0 3258 +148 152 0.981907932903897 -0.140534730551063 0.126912571518096 0.566738471857865 0.142870418707962 0.989696319720243 -0.00944659676377806 0.106013349812023 -0.124277330026869 0.0274077405333924 0.99186892329594 -0.149779851729466 4.68636838449137e-05 -5.35026754261895e-06 6.1747681069208e-06 -1.2231374373039e-06 1.39869996860764e-06 1.28600221305538e-06 -5.35026754261895e-06 4.11216138219383e-05 -7.63797763567134e-07 6.88770485387786e-05 -1.87528867796019e-06 4.85313690340378e-05 6.1747681069208e-06 -7.63797763567134e-07 1.75094858250787e-05 -2.70434464648978e-07 3.05121176028623e-06 -3.99412321578043e-07 -1.2231374373039e-06 6.88770485387786e-05 -2.70434464648978e-07 0.000769022385170943 -2.59339554474896e-05 0.000373158759604458 1.39869996860764e-06 -1.87528867796019e-06 3.05121176028623e-06 -2.59339554474896e-05 1.32965552623814e-05 -1.26311789416419e-05 1.28600221305538e-06 4.85313690340378e-05 -3.99412321578043e-07 0.000373158759604458 -1.26311789416419e-05 0.000355494526378724 2877 2818 0 427 1239 2877 2818 0 336 1296 0 0 0 0 0 0 0 0 3290 0 0 0 0 0 2496 +151 155 0.996700452379469 0.0214803473323187 0.0782738967028285 0.585731512993368 -0.0190853090195759 0.999330340719045 -0.0312189221144 0.0291281079792032 -0.0788920731518029 0.0296220322874821 0.996442961737886 -0.0447547226066052 5.34026982998169e-05 4.99620232581158e-06 1.53482565535804e-06 1.06220250329156e-06 3.93103714148507e-06 4.91540818582457e-05 4.99620232581158e-06 5.22832733045542e-05 -1.88694350828039e-06 5.3642863835131e-06 1.74302451260023e-06 0.000107356368080354 1.53482565535804e-06 -1.88694350828039e-06 1.45944547158205e-05 6.34469334967881e-07 4.87687538746785e-06 -6.34137550164119e-06 1.06220250329156e-06 5.3642863835131e-06 6.34469334967881e-07 0.000282777265581939 4.5241587602062e-06 0.000257993466610334 3.93103714148507e-06 1.74302451260023e-06 4.87687538746785e-06 4.5241587602062e-06 1.26688609641996e-05 2.28521137478149e-05 4.91540818582457e-05 0.000107356368080354 -6.34137550164119e-06 0.000257993466610334 2.28521137478149e-05 0.0010075902003763 3250 3196 0 1190 695 3250 3196 0 1042 737 0 0 0 0 0 0 0 0 2535 0 0 0 0 0 3074 +159 161 0.999249435589651 -0.0386407200653291 -0.00273134153787993 0.295225149204866 0.038729607986914 0.997958508485037 0.050782209557088 0.0131045086499376 0.000763504383511566 -0.050849878024956 0.998706016286026 -0.0246082428258084 5.15859374407268e-05 8.32118770057173e-06 9.23663987992644e-06 -1.75331486207686e-05 7.17801982600275e-07 -2.00048465807589e-05 8.32118770057173e-06 4.76542663469757e-05 2.86615952130186e-06 -3.65491784568834e-05 -1.7995294534248e-06 -6.52315453204316e-06 9.23663987992644e-06 2.86615952130186e-06 1.3732445165211e-05 -3.56540325035132e-06 3.7933298803145e-06 -2.48242594369319e-06 -1.75331486207686e-05 -3.65491784568834e-05 -3.56540325035132e-06 0.000489911321466741 5.11307200749249e-06 1.87892297940495e-05 7.17801982600275e-07 -1.7995294534248e-06 3.7933298803145e-06 5.11307200749249e-06 1.22245788149282e-05 -4.51614225371949e-06 -2.00048465807589e-05 -6.52315453204316e-06 -2.48242594369319e-06 1.87892297940495e-05 -4.51614225371949e-06 0.00023253951424967 3265 3220 0 313 420 3265 3220 0 215 463 0 0 0 0 0 0 0 0 3435 0 0 0 0 0 3364 +161 164 0.995975271041663 -0.0778902327305386 0.0443437833147766 0.395682315799927 0.0795936697008531 0.996101370622197 -0.0380382332414631 0.0280382446132796 -0.0412080964985866 0.0414146241050548 0.998291902047292 -0.0482152778255611 3.45867873368909e-05 -5.59411300758672e-07 7.04694209566566e-06 1.29363934810933e-05 1.55029915333197e-06 -3.57365930720844e-06 -5.59411300758672e-07 7.75852035664758e-05 2.81355125612376e-06 -5.30593534300574e-05 1.63829100870539e-06 2.06329577408751e-05 7.04694209566566e-06 2.81355125612376e-06 1.45176972641374e-05 -1.37067652002832e-05 3.36505265398477e-06 6.37425025970298e-06 1.29363934810933e-05 -5.30593534300574e-05 -1.37067652002832e-05 0.000678298422031737 -3.20843332524411e-05 -0.000148833068447681 1.55029915333197e-06 1.63829100870539e-06 3.36505265398477e-06 -3.20843332524411e-05 1.32170532136137e-05 8.38154757242149e-06 -3.57365930720844e-06 2.06329577408751e-05 6.37425025970298e-06 -0.000148833068447681 8.38154757242149e-06 0.000301008701804831 3213 3146 0 424 658 3213 3146 0 306 692 0 0 0 0 0 0 0 0 3313 0 0 0 0 0 3114 +163 167 0.994320836696848 0.102734021292693 -0.0277811911104174 0.608434452330693 -0.10320772821668 0.994528083824402 -0.016188122834827 -0.0410454614104176 0.0259661038054011 0.0189634214633362 0.999482941374975 -0.0532726675989814 3.92935426112483e-05 1.10692986830707e-05 7.65114880357106e-06 -1.21689289464585e-05 -2.95619818338563e-07 -9.53515168474876e-06 1.10692986830707e-05 5.14210388370869e-05 1.67538487010354e-06 3.10093975818688e-06 1.26335515879617e-07 -1.72311941690109e-05 7.65114880357106e-06 1.67538487010354e-06 1.34871159953694e-05 -3.20649628959982e-06 3.0797634970969e-06 -2.14258991589052e-06 -1.21689289464585e-05 3.10093975818688e-06 -3.20649628959982e-06 0.00028871581473228 1.30772027537623e-05 1.57226941510475e-05 -2.95619818338563e-07 1.26335515879617e-07 3.0797634970969e-06 1.30772027537623e-05 1.2481313129822e-05 1.28349837941686e-06 -9.53515168474876e-06 -1.72311941690109e-05 -2.14258991589052e-06 1.57226941510475e-05 1.28349837941686e-06 0.000235678404191692 3373 3344 0 1583 434 3373 3344 0 1420 477 0 0 0 0 0 0 0 0 2139 0 0 0 0 0 3382 +169 172 0.999043376905155 -0.0376177615311696 -0.0222987685608148 0.406835860058994 0.0382624704386252 0.998840198312287 0.0292274116439443 -0.0219533979926575 0.0211734366100088 -0.0300526579998391 0.999324033199075 -0.0231362483493176 5.23146145090406e-05 8.16372988995844e-07 1.00268645824903e-05 -7.54861455748677e-06 -2.17213827921426e-07 -4.76029525202276e-06 8.16372988995844e-07 3.31237348713365e-05 1.48746341197803e-07 5.88133828179384e-06 -7.45276008435667e-07 6.96730665184874e-06 1.00268645824903e-05 1.48746341197803e-07 1.44324124856123e-05 -2.78266165859246e-06 3.00001771317445e-06 -1.50034759403942e-06 -7.54861455748677e-06 5.88133828179384e-06 -2.78266165859246e-06 0.000305126153236837 1.88214695979417e-06 -8.85426414570093e-06 -2.17213827921426e-07 -7.45276008435667e-07 3.00001771317445e-06 1.88214695979417e-06 1.20447614795465e-05 -3.51823247748653e-06 -4.76029525202276e-06 6.96730665184874e-06 -1.50034759403942e-06 -8.85426414570093e-06 -3.51823247748653e-06 0.000175284305542259 3341 3319 0 519 535 3341 3319 0 465 585 0 0 0 0 0 0 0 0 3183 0 0 0 0 0 3211 +170 173 0.996037008167343 -0.0730629539751056 -0.0507157087841642 0.41680274791563 0.0726634464172283 0.997309546713756 -0.00967944153212321 -0.0024856386806153 0.0512864691299679 0.00595590379663686 0.998666223166753 -0.0126599137165529 5.00680434666631e-05 -3.71066899812458e-06 3.79217566243667e-06 5.4182638170993e-05 1.20154600944189e-08 3.0142330351646e-05 -3.71066899812458e-06 3.76314854968323e-05 2.55487734332014e-06 8.78663301580972e-05 -2.01101951716839e-06 2.6219735924081e-05 3.79217566243667e-06 2.55487734332014e-06 1.4566450735435e-05 -1.58035028668114e-05 3.12341967500186e-06 -6.31946692460525e-06 5.4182638170993e-05 8.78663301580972e-05 -1.58035028668114e-05 0.00112562320459355 -1.19600982628969e-05 0.000415996370537163 1.20154600944189e-08 -2.01101951716839e-06 3.12341967500186e-06 -1.19600982628969e-05 1.2738186412602e-05 -4.5721649284164e-06 3.0142330351646e-05 2.6219735924081e-05 -6.31946692460525e-06 0.000415996370537163 -4.5721649284164e-06 0.000279302688663344 3356 3323 0 440 661 3356 3323 0 346 712 0 0 0 0 0 0 0 0 3314 0 0 0 0 0 3077 +171 173 0.996467565098907 -0.0660972056882565 -0.0518030028672079 0.288244819864219 0.065770939739247 0.997802840339309 -0.00797968023319263 0.00289326493376838 0.0522166179647053 0.00454436035234617 0.998625442093939 -0.0480990041870309 4.90519804751114e-05 -7.14898092456621e-06 3.69162975684495e-06 -1.30879064050855e-05 1.02039379720038e-06 1.31826003340897e-05 -7.14898092456621e-06 2.58051681462561e-05 -8.99649763923622e-07 -1.19258094895391e-07 -5.2602647832985e-07 3.15836426380754e-06 3.69162975684495e-06 -8.99649763923622e-07 1.43500054117939e-05 4.87753148728832e-07 3.86298994171665e-06 -2.37602759689822e-06 -1.30879064050855e-05 -1.19258094895391e-07 4.87753148728832e-07 0.000298730567006651 -5.04768350629044e-06 1.02345159470253e-05 1.02039379720038e-06 -5.2602647832985e-07 3.86298994171665e-06 -5.04768350629044e-06 1.25796898137726e-05 3.03818474753952e-06 1.31826003340897e-05 3.15836426380754e-06 -2.37602759689822e-06 1.02345159470253e-05 3.03818474753952e-06 0.000195800617165953 3353 3320 0 213 452 3353 3320 0 128 503 0 0 0 0 0 0 0 0 3551 0 0 0 0 0 3288 +171 174 0.995058150779558 -0.0936151519298317 -0.0330980346292883 0.435162172406824 0.0933471673925958 0.995587773409161 -0.00955467309576935 0.0106083131592921 0.0338464607742928 0.00641784756307333 0.999406438004935 -0.0432395289926725 6.36741991763939e-05 1.41701905194462e-06 1.8069136998003e-06 4.01102514006042e-05 -8.7545937506811e-07 7.50829956050137e-06 1.41701905194462e-06 3.82612035058467e-05 3.76166127009853e-06 -4.66667086014058e-06 -1.88880364581337e-07 -2.4119955582606e-05 1.8069136998003e-06 3.76166127009853e-06 1.39977434219211e-05 1.09281182189024e-06 4.28597909747149e-06 -3.92970210512009e-06 4.01102514006042e-05 -4.66667086014058e-06 1.09281182189024e-06 0.000391873099423455 -1.34871862780203e-05 4.27461431463119e-05 -8.7545937506811e-07 -1.88880364581337e-07 4.28597909747149e-06 -1.34871862780203e-05 1.36071722909298e-05 1.3797919560619e-06 7.50829956050137e-06 -2.4119955582606e-05 -3.92970210512009e-06 4.27461431463119e-05 1.3797919560619e-06 0.000110020822569039 3320 3285 0 410 754 3320 3285 0 314 819 0 0 0 0 0 0 0 0 3340 0 0 0 0 0 2967 +172 176 0.998466765967923 -0.0486484460129714 0.0264092021477449 0.563888621121024 0.0493479322565124 0.998429656165302 -0.0265142088632367 0.0107826393379498 -0.0250778555615131 0.0277767958944095 0.999299530056067 -0.0242129487059339 4.21959299557172e-05 -2.31791778706955e-06 8.72790126350966e-06 7.60882736003877e-06 6.58497011902183e-07 -1.06087021720806e-06 -2.31791778706955e-06 7.75630654979094e-05 9.24395748422845e-06 -8.80345930507131e-06 -2.76450320618029e-06 6.96045522167878e-05 8.72790126350966e-06 9.24395748422845e-06 1.66975522631147e-05 3.15075795054789e-06 2.10006609109847e-06 -5.91160744693518e-06 7.60882736003877e-06 -8.80345930507131e-06 3.15075795054789e-06 0.000308343065614026 -8.18317440138936e-06 3.87628837438886e-05 6.58497011902183e-07 -2.76450320618029e-06 2.10006609109847e-06 -8.18317440138936e-06 1.23515310527965e-05 4.38830411134397e-06 -1.06087021720806e-06 6.96045522167878e-05 -5.91160744693518e-06 3.87628837438886e-05 4.38830411134397e-06 0.00060593178006995 3319 3285 0 826 866 3319 3285 0 717 928 0 0 0 0 0 0 0 0 2942 0 0 0 0 0 2842 +174 148 0.983841579459905 0.14887356260951 -0.0994605895910082 -3.77075360275639 -0.146638032549726 0.98875136227703 0.029462365914201 0.190000057413527 0.102727960827538 -0.014401595441792 0.994605228275494 0.432075698837035 0.000215969352495516 9.77871577301763e-05 1.67574444088882e-05 1.30907889198144e-05 2.43030407924167e-05 -1.49361115370479e-05 9.77871577301763e-05 0.000117660979113439 5.23456874890916e-06 -1.54245543338498e-05 1.00478146862264e-05 -5.25952052928531e-05 1.67574444088882e-05 5.23456874890916e-06 2.58216210073673e-05 -9.2541098150582e-06 8.09165639876301e-06 -3.67242953200025e-06 1.30907889198144e-05 -1.54245543338498e-05 -9.2541098150582e-06 0.000289570432557328 1.96230703767248e-05 0.000174421866711041 2.43030407924167e-05 1.00478146862264e-05 8.09165639876301e-06 1.96230703767248e-05 1.69112295812329e-05 9.98950082946686e-06 -1.49361115370479e-05 -5.25952052928531e-05 -3.67242953200025e-06 0.000174421866711041 9.98950082946686e-06 0.00027327184295873 305 305 0 0 0 304 304 0 0 0 0 0 0 0 0 73 73 0 0 0 98 98 0 0 0 +174 178 0.997681596433943 0.0653105216012105 -0.019130287640216 0.560487884276856 -0.0656225851998901 0.997713561020627 -0.0161655951706818 -0.0290038974887205 0.0180307639522776 0.0173834957277592 0.999686303611078 -0.0500533696811306 5.72230498413256e-05 5.95901505571296e-06 4.6511223734681e-06 3.21896403233653e-05 1.50521525200026e-06 -1.22586450834126e-05 5.95901505571296e-06 5.05394659342404e-05 2.1612169619607e-06 -6.46070412959535e-06 -1.07075426617003e-08 3.98392435837304e-05 4.6511223734681e-06 2.1612169619607e-06 1.4528803402608e-05 -1.22900468858527e-06 4.51040790871752e-06 1.10211000709408e-06 3.21896403233653e-05 -6.46070412959535e-06 -1.22900468858527e-06 0.000425894859462768 5.46425239056531e-06 4.77663474202898e-05 1.50521525200026e-06 -1.07075426617003e-08 4.51040790871752e-06 5.46425239056531e-06 1.24977844642391e-05 9.19495882925983e-06 -1.22586450834126e-05 3.98392435837304e-05 1.10211000709408e-06 4.77663474202898e-05 9.19495882925983e-06 0.000406677419405962 3309 3288 0 1223 501 3309 3288 0 1102 551 0 0 0 0 0 0 0 0 2543 0 0 0 0 0 3268 +177 181 0.999843189284121 -0.0176435238585477 -0.00151753352835869 0.630936828982844 0.0176695846624659 0.999656883685257 0.0193365115399827 0.00146424061179277 0.00117584863515017 -0.019360293554923 0.999811880512256 -0.048822714736137 3.85068807895395e-05 -4.94484220155464e-06 9.23766175678079e-06 2.61929529074282e-06 -1.62228423389631e-06 1.7169665647866e-06 -4.94484220155464e-06 2.69884897789199e-05 -3.09776952326783e-06 -1.49011055320928e-05 6.11741111826796e-07 -8.86474343629099e-06 9.23766175678079e-06 -3.09776952326783e-06 1.36705116402011e-05 6.74592804138683e-06 1.70827547752569e-06 -4.29436277675515e-06 2.61929529074282e-06 -1.49011055320928e-05 6.74592804138683e-06 0.000129269326728322 -5.41371295210071e-06 -3.47790937581591e-05 -1.62228423389631e-06 6.11741111826796e-07 1.70827547752569e-06 -5.41371295210071e-06 1.22160948820246e-05 5.00860687401826e-06 1.7169665647866e-06 -8.86474343629099e-06 -4.29436277675515e-06 -3.47790937581591e-05 5.00860687401826e-06 0.000122184067616401 3319 3288 0 1079 883 3319 3288 0 962 938 0 0 0 0 0 0 0 0 2669 0 0 0 0 0 2863 +175 178 0.996635116267714 0.0755869596188392 -0.0317026269829603 0.44561131892065 -0.0762465412688543 0.996885612961897 -0.0201380141552972 -0.0291840738688207 0.0300817214696507 0.0224874677356529 0.999294453015857 -0.0523600831659217 5.86164284860703e-05 7.78421197649138e-06 1.171755856369e-05 1.34389107920836e-05 -1.26589830721008e-06 -1.79643930774815e-06 7.78421197649138e-06 3.12415890886439e-05 1.99052388618877e-06 6.94270293839361e-06 -1.21632055992995e-07 -6.64455407322418e-06 1.171755856369e-05 1.99052388618877e-06 1.74561201499761e-05 -1.08964346661562e-07 2.02857464474134e-06 -2.48643612294104e-06 1.34389107920836e-05 6.94270293839361e-06 -1.08964346661562e-07 0.00037061514799909 2.08664750617395e-06 8.52120511485652e-05 -1.26589830721008e-06 -1.21632055992995e-07 2.02857464474134e-06 2.08664750617395e-06 1.36209260740395e-05 2.35086325989376e-06 -1.79643930774815e-06 -6.64455407322418e-06 -2.48643612294104e-06 8.52120511485652e-05 2.35086325989376e-06 0.000104124672301051 3306 3285 0 988 287 3306 3285 0 877 331 0 0 0 0 0 0 0 0 2786 0 0 0 0 0 3487 +179 181 0.998412113287159 -0.0421747797068416 0.0373435402466013 0.285411056946947 0.0422513007153662 0.999106218108504 -0.00126195276577843 0.0173791745361901 -0.0372569406866674 0.00283776207648495 0.99930168992005 0.00626099631702735 3.33099745020673e-05 -1.36382939105828e-05 8.16133611254468e-06 -2.33795035963993e-06 2.60974373007904e-06 1.43423958829458e-05 -1.36382939105828e-05 4.96975377697971e-05 -4.22452425450861e-06 -1.67045116161995e-05 1.01313941395778e-06 3.13078297806807e-05 8.16133611254468e-06 -4.22452425450861e-06 1.15932975986477e-05 2.27132084797314e-06 4.18171438078891e-06 -8.43265616372698e-07 -2.33795035963993e-06 -1.67045116161995e-05 2.27132084797314e-06 0.000357136095627137 -4.80198060380411e-06 -4.4758419237562e-05 2.60974373007904e-06 1.01313941395778e-06 4.18171438078891e-06 -4.80198060380411e-06 1.04476223386994e-05 4.92455624590337e-07 1.43423958829458e-05 3.13078297806807e-05 -8.43265616372698e-07 -4.4758419237562e-05 4.92455624590337e-07 0.000255402975238655 3445 3414 0 267 420 3445 3414 0 182 470 0 0 0 0 0 0 0 0 3505 0 0 0 0 0 3324 +177 179 0.999250845869515 0.0266700544357107 -0.0280438090396897 0.291867179636521 -0.0260079665433283 0.999380410056133 0.0237145877534611 -0.00742265725670536 0.0286589027239263 -0.0229674594248411 0.999325353977486 -0.0309487665896879 5.39845329398963e-05 1.47430857742955e-06 4.95742040996977e-06 -1.09737528177223e-05 1.69756986390847e-06 -1.78611556591318e-06 1.47430857742955e-06 8.00379407536624e-05 -5.06282900243817e-07 -2.54191832029928e-05 -7.75319813236001e-07 -5.42600308251041e-05 4.95742040996977e-06 -5.06282900243817e-07 1.53576557392906e-05 -2.57273416370036e-06 3.72335490409684e-06 -1.06669765505578e-06 -1.09737528177223e-05 -2.54191832029928e-05 -2.57273416370036e-06 0.000222827059102187 1.15137250470373e-06 2.39827886820235e-05 1.69756986390847e-06 -7.75319813236001e-07 3.72335490409684e-06 1.15137250470373e-06 1.10307300204832e-05 1.4069291086831e-06 -1.78611556591318e-06 -5.42600308251041e-05 -1.06669765505578e-06 2.39827886820235e-05 1.4069291086831e-06 0.000181562874587913 3240 3220 0 482 237 3240 3220 0 397 271 0 0 0 0 0 0 0 0 3294 0 0 0 0 0 3547 +178 181 0.99883027228497 -0.0405330978466114 0.0263657950020374 0.489142880993461 0.04000651483293 0.998995167266961 0.0202023401658982 0.0166178109138868 -0.0271581652188617 -0.0191239053598667 0.999448202912853 -0.0396787674571402 5.29335030215767e-05 -4.11222010827075e-06 5.75115776095893e-06 -1.31494411601789e-06 6.11011816840619e-07 1.230271666395e-06 -4.11222010827075e-06 4.02572115795505e-05 2.13472127681134e-06 -1.45277892514776e-05 -2.25735995843894e-06 -6.17962122783436e-06 5.75115776095893e-06 2.13472127681134e-06 1.67102642093067e-05 -7.90843352405717e-06 1.95765752417587e-06 -3.18361031521989e-06 -1.31494411601789e-06 -1.45277892514776e-05 -7.90843352405717e-06 0.000232263800303233 2.39836328791035e-06 8.07575454805432e-05 6.11011816840619e-07 -2.25735995843894e-06 1.95765752417587e-06 2.39836328791035e-06 1.32937839524264e-05 5.64382193330884e-07 1.230271666395e-06 -6.17962122783436e-06 -3.18361031521989e-06 8.07575454805432e-05 5.64382193330884e-07 0.000185520893129608 3242 3211 0 654 722 3242 3211 0 564 779 0 0 0 0 0 0 0 0 3107 0 0 0 0 0 3013 +181 184 0.994709931803532 -0.101483109675825 -0.0159163444904027 0.440557496502738 0.101454736095577 0.994836805125811 -0.0025821872213043 0.0327021513248843 0.0160962136910972 0.000953738744927447 0.999869992692658 -0.092607683282841 6.80682452252619e-05 -1.49151060084448e-05 8.31536308888193e-08 1.90609105230755e-06 4.3047552412672e-06 2.44544650804705e-05 -1.49151060084448e-05 5.77132714367362e-05 -3.91288514177579e-06 -1.76792129992452e-05 2.59407243521424e-07 -1.05809560966278e-05 8.31536308888193e-08 -3.91288514177579e-06 1.48443081380245e-05 7.57446083221701e-06 2.96165321702974e-06 1.37232194127297e-06 1.90609105230755e-06 -1.76792129992452e-05 7.57446083221701e-06 0.000430539381501285 -4.28982935934691e-05 2.31929723592456e-05 4.3047552412672e-06 2.59407243521424e-07 2.96165321702974e-06 -4.28982935934691e-05 1.86132134554281e-05 1.24351890562977e-06 2.44544650804705e-05 -1.05809560966278e-05 1.37232194127297e-06 2.31929723592456e-05 1.24351890562977e-06 0.000275604143220688 3244 3176 0 409 781 3244 3176 0 303 836 0 0 0 0 0 0 0 0 3333 0 0 0 0 0 2953 +185 189 0.982352536777319 0.186337748875003 -0.0161782827074753 0.599140204922662 -0.186237933634874 0.982476163053215 0.00748472495457768 -0.0845342027971346 0.0172894639182151 -0.00433962860500887 0.999841108407227 -0.0810267647089614 5.19504662311195e-05 1.04834443848636e-05 4.54356393758427e-06 -1.30591747714962e-05 -2.01468948666468e-07 -2.59360649707492e-05 1.04834443848636e-05 5.6726070774277e-05 -2.66217507873902e-06 -8.47233880411543e-06 1.63982136461677e-06 -5.63049002889299e-06 4.54356393758427e-06 -2.66217507873902e-06 1.27260751763026e-05 1.00228331824165e-06 2.14181728049267e-06 9.00802004630223e-07 -1.30591747714962e-05 -8.47233880411543e-06 1.00228331824165e-06 0.000290923999690056 1.26482799614537e-05 -3.31510554648966e-05 -2.01468948666468e-07 1.63982136461677e-06 2.14181728049267e-06 1.26482799614537e-05 1.27330063720701e-05 -4.522190286231e-06 -2.59360649707492e-05 -5.63049002889299e-06 9.00802004630223e-07 -3.31510554648966e-05 -4.522190286231e-06 0.000207220631172729 3209 3188 0 1883 140 3209 3188 0 1722 168 0 0 0 0 0 0 0 0 1867 0 0 0 0 0 3696 +186 190 0.984262828017477 0.176418760820207 -0.0101541229902832 0.594215932249967 -0.176571214398446 0.9841436626336 -0.0168480724114495 -0.0685109443965165 0.00702079973345232 0.018375857225882 0.999806499399917 -0.0204331760810273 5.43759384880103e-05 9.50436461227069e-06 9.88620174129761e-06 -2.68761442564643e-05 -3.27020828108183e-06 -1.56369070902334e-05 9.50436461227069e-06 3.31923087946047e-05 1.160249583372e-06 -7.90382801197826e-06 8.80710208052675e-07 1.2136670202338e-05 9.88620174129761e-06 1.160249583372e-06 1.59115396499711e-05 -3.0560385341859e-06 1.68679344219957e-06 -5.6131927479252e-06 -2.68761442564643e-05 -7.90382801197826e-06 -3.0560385341859e-06 0.00030579674538909 2.27952668978446e-05 5.90986640204998e-05 -3.27020828108183e-06 8.80710208052675e-07 1.68679344219957e-06 2.27952668978446e-05 1.53293204815168e-05 9.28697337581645e-06 -1.56369070902334e-05 1.2136670202338e-05 -5.6131927479252e-06 5.90986640204998e-05 9.28697337581645e-06 0.000281985853049807 3187 3173 0 1784 187 3187 3173 0 1634 219 0 0 0 0 0 0 0 0 1958 0 0 0 0 0 3649 +192 194 0.995755236898263 -0.08348256193684 -0.0387578384607008 0.310725509524937 0.0830442059711979 0.996463806756343 -0.0127883415371578 0.0502878822483825 0.0396883867686425 0.00951544413673961 0.999166797025693 -0.0812598787823363 8.25048516914975e-05 -2.14683710310619e-05 -3.84351574814309e-06 -4.87345608546895e-06 3.33235818951162e-06 2.48536757823256e-05 -2.14683710310619e-05 9.19335558605944e-05 -5.10951730967087e-07 -4.74454701339994e-05 3.00442906998649e-06 -2.99714085015272e-05 -3.84351574814309e-06 -5.10951730967087e-07 1.54585245736432e-05 6.60562291218478e-07 4.08439539995482e-06 1.78582799358984e-06 -4.87345608546895e-06 -4.74454701339994e-05 6.60562291218478e-07 0.000192052995739055 -6.32498261810712e-06 7.01985586810192e-05 3.33235818951162e-06 3.00442906998649e-06 4.08439539995482e-06 -6.32498261810712e-06 1.36772998073389e-05 -1.65172178851622e-05 2.48536757823256e-05 -2.99714085015272e-05 1.78582799358984e-06 7.01985586810192e-05 -1.65172178851622e-05 0.000372642545574031 3032 2987 0 141 580 3032 2987 0 63 631 0 0 0 0 0 0 0 0 3574 0 0 0 0 0 3181 +190 193 0.997406227977665 -0.0717462406541821 0.00577003841907655 0.439287742310605 0.0713294445632223 0.995975822850234 0.054261133752457 0.0534195809171854 -0.00963985112268977 -0.0537088191062886 0.998510108121365 -0.0208433068340479 5.40762859790517e-05 -9.31410136907986e-06 5.92735100985961e-06 1.87612973316707e-05 4.97968502090398e-07 1.24370527996775e-05 -9.31410136907986e-06 2.74598732769682e-05 -8.03439839049007e-07 1.25416050022811e-05 -6.083554880293e-07 -6.63537244385168e-06 5.92735100985961e-06 -8.03439839049007e-07 1.62296795547389e-05 -8.89073892893421e-06 4.26442421403971e-06 -3.83502067112357e-06 1.87612973316707e-05 1.25416050022811e-05 -8.89073892893421e-06 0.000419575531706568 4.63136986940508e-06 7.90725040155669e-05 4.97968502090398e-07 -6.083554880293e-07 4.26442421403971e-06 4.63136986940508e-06 1.1270197028797e-05 -2.82206920746593e-06 1.24370527996775e-05 -6.63537244385168e-06 -3.83502067112357e-06 7.90725040155669e-05 -2.82206920746593e-06 0.000160306387432059 2986 2952 0 405 762 2986 2952 0 314 823 0 0 0 0 0 0 0 0 3319 0 0 0 0 0 3006 +192 196 0.991658882432097 -0.116828849989775 0.0544396978646242 0.605678539107452 0.117958528135931 0.992855177047562 -0.0180106371308255 0.0898004616522173 -0.0519465738382198 0.0242820349213203 0.998354614476515 -0.0708735327856341 4.67257341681004e-05 -1.31480535041129e-05 3.23767846356181e-06 5.02849142728851e-06 8.39233263903884e-07 1.9439210604783e-05 -1.31480535041129e-05 0.000138988793963501 1.22440971129693e-06 -5.09765412972411e-05 3.30919062358596e-06 -0.000136947240915771 3.23767846356181e-06 1.22440971129693e-06 1.42968579872059e-05 4.80419502528318e-07 3.13438381439157e-06 6.46323560746026e-07 5.02849142728851e-06 -5.09765412972411e-05 4.80419502528318e-07 0.000210129279893511 -8.52715301489549e-06 6.60997269525914e-05 8.39233263903884e-07 3.30919062358596e-06 3.13438381439157e-06 -8.52715301489549e-06 1.20602681276586e-05 -3.61468989855907e-06 1.9439210604783e-05 -0.000136947240915771 6.46323560746026e-07 6.60997269525914e-05 -3.61468989855907e-06 0.00024470647507902 2531 2553 0 642 1180 2531 2553 0 523 1238 0 0 0 0 0 0 0 0 3078 0 0 0 0 0 2535 +190 194 0.994084501052355 -0.107237981338699 -0.0172052354209883 0.603561490940765 0.107735569496074 0.993689536002553 0.0312114258627728 0.0823543200499235 0.0137496120980704 -0.0328804105423213 0.999364711589178 -0.050250428472686 4.74870866489583e-05 -1.52046569053422e-05 3.75361984302434e-06 4.74400669146117e-06 -1.13263751096449e-06 1.08688940123376e-05 -1.52046569053422e-05 3.65802913314991e-05 1.37898214511157e-06 -1.87448773324614e-05 -6.46707271729201e-07 5.12772627554745e-07 3.75361984302434e-06 1.37898214511157e-06 1.29798621199323e-05 5.0807178221902e-07 3.37596455639894e-06 -1.60661882990743e-06 4.74400669146117e-06 -1.87448773324614e-05 5.0807178221902e-07 0.000297021438764032 -6.34561940060796e-06 -3.37641748967924e-05 -1.13263751096449e-06 -6.46707271729201e-07 3.37596455639894e-06 -6.34561940060796e-06 1.13485636828286e-05 -4.23747574758826e-06 1.08688940123376e-05 5.12772627554745e-07 -1.60661882990743e-06 -3.37641748967924e-05 -4.23747574758826e-06 0.000163038560734659 2874 2829 0 618 1156 2874 2829 0 512 1228 0 0 0 0 0 0 0 0 3068 0 0 0 0 0 2585 +194 198 0.996193043762087 0.00260291635875813 0.0871357813212065 0.587814698656639 0.000253011749338527 0.999463591044053 -0.0327485291636255 0.0166141023735459 -0.0871742825900076 0.0326459033227056 0.99565801832314 -0.0328904798063244 5.52170581221769e-05 6.12535773033902e-06 9.08899303006679e-07 2.27260069536141e-06 3.78631125093358e-06 6.6867950751342e-06 6.12535773033902e-06 7.52277034387813e-05 -1.55085649030483e-06 2.49101182675503e-05 -2.44728355401693e-08 -2.82121729939749e-05 9.08899303006679e-07 -1.55085649030483e-06 1.4784700844901e-05 -2.11247871668561e-06 3.31217445871886e-06 -8.31494159102557e-07 2.27260069536141e-06 2.49101182675503e-05 -2.11247871668561e-06 9.93060107117643e-05 1.63041640758708e-06 -1.37610354598392e-05 3.78631125093358e-06 -2.44728355401693e-08 3.31217445871886e-06 1.63041640758708e-06 1.27566268171527e-05 5.13961429227872e-06 6.6867950751342e-06 -2.82121729939749e-05 -8.31494159102557e-07 -1.37610354598392e-05 5.13961429227872e-06 0.000300391017817748 3055 3000 0 476 742 3055 3000 0 333 788 0 0 0 0 0 0 0 0 2591 0 0 0 0 0 3032 +191 195 0.991085955291519 -0.132501734119319 0.0138535078326962 0.592129231616909 0.132444897210931 0.991178025844704 0.00494674492785457 0.0969773973960614 -0.0143867448258226 -0.00306782300149396 0.999891799163964 -0.0608004391716606 5.08211638575586e-05 -1.29997443270479e-05 2.38125640468396e-06 2.43414692794031e-05 -2.14520431421566e-06 3.61837589699721e-06 -1.29997443270479e-05 4.14251091874672e-05 -3.07442026098335e-06 -1.91003868629287e-05 6.96103273627497e-07 2.89726750851074e-06 2.38125640468396e-06 -3.07442026098335e-06 1.50006851835402e-05 3.4457202974825e-06 4.63977336877763e-06 -1.22926695662745e-06 2.43414692794031e-05 -1.91003868629287e-05 3.4457202974825e-06 0.000153458007760167 -1.76591002959776e-06 -9.82440692373712e-07 -2.14520431421566e-06 6.96103273627497e-07 4.63977336877763e-06 -1.76591002959776e-06 1.26677918204463e-05 -4.81589995385572e-06 3.61837589699721e-06 2.89726750851074e-06 -1.22926695662745e-06 -9.82440692373712e-07 -4.81589995385572e-06 0.000241371482721972 2841 2788 0 517 1211 2841 2788 0 407 1283 0 0 0 0 0 0 0 0 3188 0 0 0 0 0 2501 +195 198 0.996379487748801 0.0282996303265478 0.0801688675036486 0.450203402201543 -0.0257753759612322 0.999144230507987 -0.0323486728732421 -0.00256523448036243 -0.0810157169164969 0.0301651714065017 0.996256250191949 -0.0221247798994458 5.53199691174078e-05 2.88170412171808e-05 5.99869551503091e-06 -2.08026783013722e-06 1.97439320381125e-06 -2.4602146556098e-05 2.88170412171808e-05 0.000376101497011554 7.22154513910841e-06 -4.36615979808406e-07 -4.68244237078362e-06 -0.00105503425734318 5.99869551503091e-06 7.22154513910841e-06 1.35946261814238e-05 -1.47786920827982e-06 3.55739319180168e-06 -2.65532668248639e-05 -2.08026783013722e-06 -4.36615979808406e-07 -1.47786920827982e-06 0.000104948743437268 -1.07284312003506e-06 0.000110269800361569 1.97439320381125e-06 -4.68244237078362e-06 3.55739319180168e-06 -1.07284312003506e-06 1.19338304069369e-05 4.29031785648721e-05 -2.4602146556098e-05 -0.00105503425734318 -2.65532668248639e-05 0.000110269800361569 4.29031785648721e-05 0.00599621758766564 2919 2864 0 239 436 2919 2864 0 120 472 0 0 0 0 0 0 0 0 2836 0 0 0 0 0 3352 +194 196 0.996107877240235 -0.0333273367848003 0.0815989308924173 0.302981158393978 0.0343896555347401 0.999340623179466 -0.0116477661153636 0.0157466810293724 -0.0811569374246892 0.0144085907051589 0.996597182427151 -0.0354636064653742 4.44633590339852e-05 2.07035236310646e-06 -4.05193341985953e-08 1.34160976360282e-05 2.10064830452505e-06 -6.25568205471346e-06 2.07035236310646e-06 2.8452120638342e-05 -8.93972639840084e-07 1.32009654612533e-05 6.48196131044694e-08 -1.5068571838803e-05 -4.05193341985953e-08 -8.93972639840084e-07 1.10451219277987e-05 -1.95333779317529e-06 5.1208147489151e-06 -6.95503794811559e-07 1.34160976360282e-05 1.32009654612533e-05 -1.95333779317529e-06 0.000212724486683901 -9.06384590831572e-07 -2.11736502158563e-06 2.10064830452505e-06 6.48196131044694e-08 5.1208147489151e-06 -9.06384590831572e-07 1.04242870384742e-05 -2.35664936564942e-06 -6.25568205471346e-06 -1.5068571838803e-05 -6.95503794811559e-07 -2.11736502158563e-06 -2.35664936564942e-06 0.000100637648219614 2945 2967 0 381 401 2945 2967 0 263 438 0 0 0 0 0 0 0 0 3338 0 0 0 0 0 3349 +196 222 0.994901590201846 0.0880622367181455 -0.0491514829688336 3.70372920038023 -0.0877145482937587 0.996103252153002 0.00919070551343346 -0.127011926797218 0.0497693061179288 -0.00483254740381221 0.998749048887722 0.088212175263618 0.000112611506054321 2.18979940484122e-05 -1.10213906500871e-06 3.03493716268423e-05 3.34576385047195e-06 -8.87075403052912e-06 2.18979940484122e-05 7.17563569310598e-05 -8.14610907653454e-07 1.26744900822095e-05 6.38131884957847e-06 -6.30727667425162e-05 -1.10213906500871e-06 -8.14610907653454e-07 2.1407713259145e-05 -7.18392630960785e-06 1.93985264054684e-06 3.36063888096859e-06 3.03493716268423e-05 1.26744900822095e-05 -7.18392630960785e-06 0.000327434997595392 3.62836215144523e-05 2.8881655676583e-05 3.34576385047195e-06 6.38131884957847e-06 1.93985264054684e-06 3.62836215144523e-05 4.52781982131311e-05 -7.44474820431576e-06 -8.87075403052912e-06 -6.30727667425162e-05 3.36063888096859e-06 2.8881655676583e-05 -7.44474820431576e-06 0.000123965556292895 2585 2548 0 3803 3860 2585 2548 0 3803 3860 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +196 198 0.999366726803866 0.0352777886133177 0.00465005246015743 0.291770966567194 -0.0351522440709143 0.99907499956551 -0.0247682252080141 -0.00735787349709736 -0.00551951937282675 0.0245890803758521 0.999682405582975 0.00192569972180971 4.00647365723562e-05 1.08296041249742e-05 -8.13736760042794e-07 1.9531176742041e-06 1.53670501194713e-06 -9.64085585126351e-06 1.08296041249742e-05 2.64536324309502e-05 -2.63065722403597e-06 3.06689369258295e-06 3.70972420874324e-07 -6.17303278462946e-06 -8.13736760042794e-07 -2.63065722403597e-06 1.3250296726803e-05 -4.3932117894916e-06 3.10746368802568e-06 -2.78625601238298e-06 1.9531176742041e-06 3.06689369258295e-06 -4.3932117894916e-06 0.000166227498207739 8.7878118991866e-07 -1.35956468037679e-05 1.53670501194713e-06 3.70972420874324e-07 3.10746368802568e-06 8.7878118991866e-07 1.09343074664401e-05 2.43587261550132e-06 -9.64085585126351e-06 -6.17303278462946e-06 -2.78625601238298e-06 -1.35956468037679e-05 2.43587261550132e-06 0.000159976167261941 3359 3304 0 7 200 3359 3304 0 7 223 0 0 0 0 0 0 0 0 3151 0 0 0 0 0 3599 +196 200 0.997066224623315 0.0722300070693175 -0.0253331757617651 0.591534058053974 -0.072607054963181 0.997258211241421 -0.0142925043689193 -0.0400754865136884 0.0242313698536371 0.016089940656457 0.999576887750356 0.0311240024718033 4.85301289206156e-05 6.71804478819438e-06 3.35007487553961e-06 -4.98322778072223e-07 -9.27323504400614e-07 -1.23171502835092e-05 6.71804478819438e-06 3.83770246589951e-05 -8.04903837407037e-07 -1.38067608718017e-05 4.04087739556007e-07 -2.06863696322994e-05 3.35007487553961e-06 -8.04903837407037e-07 1.35341376361729e-05 3.0578745823304e-06 2.87652915253707e-06 1.08728696973984e-06 -4.98322778072223e-07 -1.38067608718017e-05 3.0578745823304e-06 0.000102045262596848 2.15392939841056e-06 1.99978812542599e-05 -9.27323504400614e-07 4.04087739556007e-07 2.87652915253707e-06 2.15392939841056e-06 1.18693160829622e-05 1.54369308078704e-06 -1.23171502835092e-05 -2.06863696322994e-05 1.08728696973984e-06 1.99978812542599e-05 1.54369308078704e-06 0.000144268807842809 3050 3014 0 683 477 3050 3014 0 683 508 0 0 0 0 0 0 0 0 2622 0 0 0 0 0 3330 +197 200 0.997590648343534 0.062340992670151 -0.0304384455980978 0.433685272160591 -0.0625034238892209 0.998034991021622 -0.00441346786492466 -0.0330445928564293 0.0301034938113925 0.00630534133656045 0.99952689925333 0.024610843532542 4.49116186918027e-05 1.16485473551394e-05 -2.66268265907226e-06 -4.10778587562666e-07 -1.02897125754316e-06 -1.64549565404651e-05 1.16485473551394e-05 3.85091684694738e-05 -1.37637289055195e-06 -1.42075407235745e-05 -6.40449841690801e-08 -3.02308445943678e-05 -2.66268265907226e-06 -1.37637289055195e-06 1.31768966647833e-05 6.96912584369849e-07 4.17422980667323e-06 2.16494010585213e-06 -4.10778587562666e-07 -1.42075407235745e-05 6.96912584369849e-07 0.000113662228229373 -4.82256273666451e-07 -9.10916090438718e-06 -1.02897125754316e-06 -6.40449841690801e-08 4.17422980667323e-06 -4.82256273666451e-07 1.23301453117081e-05 -1.67862700022052e-06 -1.64549565404651e-05 -3.02308445943678e-05 2.16494010585213e-06 -9.10916090438718e-06 -1.67862700022052e-06 0.000155328414452761 2967 2931 0 701 281 2967 2931 0 701 318 0 0 0 0 0 0 0 0 2645 0 0 0 0 0 3521 +197 199 0.998813960428186 0.0438865861896928 -0.0210864887161736 0.29325227025647 -0.0440626287309231 0.998997077937056 -0.00795757642406705 -0.017219205066604 0.0207161097478142 0.00887726454707192 0.99974598622404 -0.012587453100926 3.79918516178959e-05 1.22998555011104e-05 2.33296261409826e-07 2.20801405491235e-06 1.25590351797747e-06 -8.5975976902007e-06 1.22998555011104e-05 3.384453326191e-05 -1.87524766008873e-06 -8.21654637024936e-06 -3.34426506764288e-07 -1.68755214686374e-05 2.33296261409826e-07 -1.87524766008873e-06 1.12927317863491e-05 -2.92111519730321e-06 4.17824072772179e-06 1.04747015813241e-06 2.20801405491235e-06 -8.21654637024936e-06 -2.92111519730321e-06 0.000124893125781383 1.20762672106949e-06 3.73622550689106e-05 1.25590351797747e-06 -3.34426506764288e-07 4.17824072772179e-06 1.20762672106949e-06 1.00706850328409e-05 -8.29553271515869e-07 -8.5975976902007e-06 -1.68755214686374e-05 1.04747015813241e-06 3.73622550689106e-05 -8.29553271515869e-07 0.000144530044945699 3228 3183 0 288 172 3228 3183 0 288 198 0 0 0 0 0 0 0 0 2861 0 0 0 0 0 3629 +197 201 0.99783757235342 0.0655301947737685 0.00509634896220775 0.582341044242304 -0.065485345926363 0.997817167460866 -0.00851879036472556 -0.0474127600339243 -0.00564346247769963 0.00816663292217382 0.999950727505099 0.039586958981843 5.07765365384137e-05 1.00820460160681e-05 -1.18212565270728e-06 -2.46842841341916e-05 3.06547280033321e-07 -6.22519578556682e-06 1.00820460160681e-05 3.49634199945806e-05 -3.43924536869606e-06 1.14307851115707e-05 1.16498461734925e-06 -1.68059060459348e-05 -1.18212565270728e-06 -3.43924536869606e-06 1.36117639113235e-05 1.16168574325664e-06 3.1788771924192e-06 1.14128990089707e-06 -2.46842841341916e-05 1.14307851115707e-05 1.16168574325664e-06 0.000194667061308069 2.8109258473144e-06 5.81585494027425e-05 3.06547280033321e-07 1.16498461734925e-06 3.1788771924192e-06 2.8109258473144e-06 1.16691274301842e-05 4.65696133298732e-06 -6.22519578556682e-06 -1.68059060459348e-05 1.14128990089707e-06 5.81585494027425e-05 4.65696133298732e-06 0.000213055163659611 3050 3064 0 1318 478 3050 3064 0 1318 516 0 0 0 0 0 0 0 0 2220 0 0 0 0 0 3324 +198 200 0.998285295157784 0.0388949139669674 -0.0437453442007126 0.291795711832059 -0.03838135020968 0.999184735577589 0.0125194306909527 -0.0219180670451433 0.0441966223575797 -0.0108189581867146 0.998964267987567 -0.0274375136675476 5.09838554832612e-05 7.49343492010028e-06 -1.58087232516072e-06 1.98168785102631e-05 -9.69287857507587e-07 -3.74161464646504e-06 7.49343492010028e-06 7.97815079056558e-05 1.1517664552239e-06 2.72124207454759e-05 -1.04421892461479e-06 0.000249684368451175 -1.58087232516072e-06 1.1517664552239e-06 1.38606085663957e-05 3.66648332560435e-06 3.41883436692007e-06 1.9031813642447e-05 1.98168785102631e-05 2.72124207454759e-05 3.66648332560435e-06 0.000104791596668749 9.3779320000224e-07 0.000167412436459356 -9.69287857507587e-07 -1.04421892461479e-06 3.41883436692007e-06 9.3779320000224e-07 1.27279523518819e-05 -4.87959706122514e-06 -3.74161464646504e-06 0.000249684368451175 1.9031813642447e-05 0.000167412436459356 -4.87959706122514e-06 0.00186784122514839 3013 2977 0 572 180 3013 2977 0 470 211 0 0 0 0 0 0 0 0 2850 0 0 0 0 0 3621 +196 199 0.998131949088043 0.0533990884660893 -0.0296841634663225 0.447039871133012 -0.0538385751458468 0.998448563854778 -0.0142082075785801 -0.0219387364166385 0.028879405048747 0.0157798189888788 0.999458341941628 -0.0110815878749894 4.32032997977276e-05 1.21915994350197e-05 -2.84101433255106e-06 -3.80608841258861e-06 2.24536984352372e-06 -2.20972973184331e-05 1.21915994350197e-05 3.57053812065872e-05 -2.25292071302329e-06 -2.2775602056644e-06 9.73342977502749e-07 5.60073942397786e-06 -2.84101433255106e-06 -2.25292071302329e-06 1.31335205819598e-05 1.73659516022628e-06 4.69267079862669e-06 1.51112717130924e-06 -3.80608841258861e-06 -2.2775602056644e-06 1.73659516022628e-06 0.000134389871899456 -9.70878586353537e-07 3.07841043129514e-05 2.24536984352372e-06 9.73342977502749e-07 4.69267079862669e-06 -9.70878586353537e-07 1.09268481971363e-05 5.2024295305122e-07 -2.20972973184331e-05 5.60073942397786e-06 1.51112717130924e-06 3.07841043129514e-05 5.2024295305122e-07 0.000425253545260316 3175 3130 0 288 333 3175 3130 0 288 365 0 0 0 0 0 0 0 0 2846 0 0 0 0 0 3461 +199 201 0.999582699593992 0.0219914616296876 0.0187297167030676 0.276687357218391 -0.022035743549442 0.999754847677196 0.00216114603154955 -0.0170514628436657 -0.0186775983094834 -0.00257296741845564 0.999822247782101 0.014268588581921 3.85872827268157e-05 6.02582982677557e-07 4.70377928589435e-06 -7.95742262795759e-07 2.60913397518084e-06 5.72120029798845e-06 6.02582982677557e-07 4.51840477000793e-05 -4.7370176638633e-07 1.50309622341601e-05 1.13173532876819e-06 -4.79579781287537e-06 4.70377928589435e-06 -4.7370176638633e-07 1.17462558485107e-05 1.52125190790259e-07 4.24425114991805e-06 2.27825487250792e-06 -7.95742262795759e-07 1.50309622341601e-05 1.52125190790259e-07 0.000129243266098961 5.29893714464143e-06 -2.69282739022613e-05 2.60913397518084e-06 1.13173532876819e-06 4.24425114991805e-06 5.29893714464143e-06 1.10682979239971e-05 -5.58628032454972e-06 5.72120029798845e-06 -4.79579781287537e-06 2.27825487250792e-06 -2.69282739022613e-05 -5.58628032454972e-06 0.000203591943115869 3204 3218 0 489 211 3204 3218 0 388 240 0 0 0 0 0 0 0 0 3139 0 0 0 0 0 3594 +201 203 0.997608226030652 -0.0612312375095289 -0.0320712162074873 0.270734643198396 0.0607243147013435 0.998017370322712 -0.0165495056781545 0.00736993659546178 0.0330209775752919 0.0145624203754296 0.999348563291498 -0.00816066132888951 7.68663504658487e-05 -9.27075138871146e-06 -5.0350495324227e-06 9.791808048308e-06 4.87681083164016e-06 5.71584795768947e-05 -9.27075138871146e-06 7.657845467494e-05 -1.89985639658757e-06 -3.60551365058703e-06 -1.40344697070765e-06 -2.73836699854569e-05 -5.0350495324227e-06 -1.89985639658757e-06 1.40022249933185e-05 1.97315489749686e-06 2.74596797954913e-06 4.38640055858153e-06 9.791808048308e-06 -3.60551365058703e-06 1.97315489749686e-06 0.000108407582550881 -2.39057718174878e-06 4.34505069879861e-05 4.87681083164016e-06 -1.40344697070765e-06 2.74596797954913e-06 -2.39057718174878e-06 1.30417195586925e-05 1.25670418774531e-06 5.71584795768947e-05 -2.73836699854569e-05 4.38640055858153e-06 4.34505069879861e-05 1.25670418774531e-06 0.000341673365229907 3095 3089 0 196 420 3095 3089 0 186 464 0 0 0 0 0 0 0 0 3514 0 0 0 0 0 3343 +199 202 0.999981162846043 0.000493562959827543 -0.00611803470734712 0.446946082098514 -0.000545396620244871 0.999963950503319 -0.00847350201058043 -0.0188566428551356 0.0061136319485428 0.00847667914937043 0.999945383216002 0.0392698992637593 4.33684659927826e-05 3.57188193457758e-06 -6.11656501195908e-07 4.09565712706991e-05 8.54202373789846e-07 -1.3007736844473e-05 3.57188193457758e-06 8.96234127770385e-05 -5.58729820296653e-06 -3.25646385500082e-05 2.29590733332438e-06 -2.0809437369264e-06 -6.11656501195908e-07 -5.58729820296653e-06 1.60582286670623e-05 -9.07039361673106e-06 2.34573688716178e-06 2.45786067663821e-07 4.09565712706991e-05 -3.25646385500082e-05 -9.07039361673106e-06 0.000559391653805308 1.07931562274037e-05 -3.67680867032444e-05 8.54202373789846e-07 2.29590733332438e-06 2.34573688716178e-06 1.07931562274037e-05 1.17900884779366e-05 2.93277436372543e-06 -1.3007736844473e-05 -2.0809437369264e-06 2.45786067663821e-07 -3.67680867032444e-05 2.93277436372543e-06 0.000273035525766663 3009 3023 0 739 479 3009 3023 0 621 526 0 0 0 0 0 0 0 0 2912 0 0 0 0 0 3293 +198 201 0.998897139430607 0.0416565367797788 -0.021661896982161 0.423755219306098 -0.0414757900038178 0.999101390391656 0.00872757475006513 -0.0319769989477923 0.0220059919319722 -0.00781950516169041 0.999727258635132 -0.00836624409930935 4.43786792259473e-05 7.65881588914801e-06 -2.00221822769409e-06 3.37685316323369e-06 -4.30613077408326e-07 -9.6523696360641e-06 7.65881588914801e-06 6.7623939182224e-05 -3.02898927449102e-06 2.11032233241346e-05 2.95070048711113e-06 1.66857946953754e-05 -2.00221822769409e-06 -3.02898927449102e-06 1.45385846793002e-05 1.74317335713175e-06 3.24770908676576e-06 1.76765113979208e-07 3.37685316323369e-06 2.11032233241346e-05 1.74317335713175e-06 0.000188947613151455 4.63648708592775e-06 4.54046531686161e-05 -4.30613077408326e-07 2.95070048711113e-06 3.24770908676576e-06 4.63648708592775e-06 1.24134228657882e-05 4.44741970706747e-06 -9.6523696360641e-06 1.66857946953754e-05 1.76765113979208e-07 4.54046531686161e-05 4.44741970706747e-06 0.000379859939074551 3017 3031 0 989 329 3017 3031 0 767 360 0 0 0 0 0 0 0 0 2675 0 0 0 0 0 3475 +202 228 0.983205722430214 -0.182459436804696 -0.00388088925300432 3.68080464202638 0.182351576591441 0.983039648871173 -0.019517972790648 0.162203993291409 0.00737630633153229 0.0184824962641402 0.999801974111248 -0.0403801092929204 9.93039607746207e-05 7.84553742654517e-06 7.5653203218381e-06 -1.83044640090931e-05 -1.74657209470969e-06 4.18762128344971e-06 7.84553742654517e-06 6.71575836829219e-05 1.94924088850214e-06 -2.63564894792948e-05 -1.02112367232142e-05 -5.64317037810899e-05 7.5653203218381e-06 1.94924088850214e-06 2.3958770669569e-05 -1.85769738440426e-05 -1.58355498101997e-05 -2.77533241629468e-06 -1.83044640090931e-05 -2.63564894792948e-05 -1.85769738440426e-05 0.000142933768431245 5.99869958994696e-05 2.9081040808072e-06 -1.74657209470969e-06 -1.02112367232142e-05 -1.58355498101997e-05 5.99869958994696e-05 7.10303181831682e-05 1.77013211047824e-05 4.18762128344971e-06 -5.64317037810899e-05 -2.77533241629468e-06 2.9081040808072e-06 1.77013211047824e-05 0.000146371016342481 2664 2558 0 3679 3389 2664 2558 0 3679 3389 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +200 203 0.99831648199581 -0.0579945936362612 0.000910430928156215 0.414723193734102 0.0580000704986176 0.998045694863165 -0.0232547368778347 0.0013570052250897 0.000439997347031616 0.0232683921676354 0.9997291574863 0.0249219294467639 5.83730711117881e-05 -9.43338588679086e-06 -1.99930437841077e-07 8.30015975898094e-07 4.28883070017379e-06 9.94944189589571e-06 -9.43338588679086e-06 2.67060352518187e-05 -3.34386106624681e-07 -6.14413291361635e-06 -1.20929763871477e-06 -1.80389151327534e-05 -1.99930437841077e-07 -3.34386106624681e-07 1.09255689800786e-05 9.38050203090167e-07 3.6267161101131e-06 1.94939938263039e-07 8.30015975898094e-07 -6.14413291361635e-06 9.38050203090167e-07 0.000163790302362627 -5.82197004197685e-06 9.19983957719572e-06 4.28883070017379e-06 -1.20929763871477e-06 3.6267161101131e-06 -5.82197004197685e-06 1.12905032587383e-05 1.6643523619215e-06 9.94944189589571e-06 -1.80389151327534e-05 1.94939938263039e-07 9.19983957719572e-06 1.6643523619215e-06 6.76180767634306e-05 3205 3199 0 355 607 3205 3199 0 251 650 0 0 0 0 0 0 0 0 3198 0 0 0 0 0 3160 +198 202 0.999521933470329 0.0188455052011371 -0.0245102314442187 0.574592818372685 -0.0189202722573958 0.999817012774436 -0.00282210285238181 -0.0364780188197143 0.0244525624309861 0.0032844939514812 0.999695595814066 0.0611303383760586 5.46841139077044e-05 1.37662344434052e-06 8.09482058852718e-08 -5.32986976766284e-06 -2.55979740557901e-06 -3.79934719036131e-05 1.37662344434052e-06 8.66496556159875e-05 6.57450694207151e-07 -1.31402520299809e-05 3.80198220596951e-07 5.26967037786904e-05 8.09482058852718e-08 6.57450694207151e-07 1.39883453480237e-05 -2.77200875626477e-06 2.76398117548679e-06 -2.37063249797233e-06 -5.32986976766284e-06 -1.31402520299809e-05 -2.77200875626477e-06 0.000131486119866545 5.39730063769807e-06 0.000113416315447061 -2.55979740557901e-06 3.80198220596951e-07 2.76398117548679e-06 5.39730063769807e-06 1.25698420217552e-05 1.25273478189846e-05 -3.79934719036131e-05 5.26967037786904e-05 -2.37063249797233e-06 0.000113416315447061 1.25273478189846e-05 0.000630216458480333 3071 3085 0 1224 599 3071 3085 0 976 636 0 0 0 0 0 0 0 0 2378 0 0 0 0 0 3184 +200 202 0.999689507225223 -0.0188516368557794 0.0162943220678135 0.288266020351416 0.0191188452208605 0.999682677077114 -0.0164016739802964 -0.00474504745147166 -0.0159799531042051 0.0167081100006246 0.999732704356017 0.0606179985773581 4.04059783964549e-05 -1.03462743711796e-06 1.05584140572019e-05 -6.42471591625309e-06 7.6765578741152e-07 -7.72121586124347e-06 -1.03462743711796e-06 4.28105173507335e-05 4.69335546578779e-06 -9.57587743387311e-06 -9.5317423017269e-07 -9.75748419158177e-06 1.05584140572019e-05 4.69335546578779e-06 1.42792811474359e-05 -6.47811254556087e-06 2.08772766868235e-06 -5.50142201043881e-06 -6.42471591625309e-06 -9.57587743387311e-06 -6.47811254556087e-06 0.000135954231100049 4.22029155719047e-06 -2.26400642919004e-06 7.6765578741152e-07 -9.5317423017269e-07 2.08772766868235e-06 4.22029155719047e-06 1.16869118436085e-05 4.32487299437923e-07 -7.72121586124347e-06 -9.75748419158177e-06 -5.50142201043881e-06 -2.26400642919004e-06 4.32487299437923e-07 0.000174981057440912 3257 3271 0 329 330 3257 3271 0 244 369 0 0 0 0 0 0 0 0 3344 0 0 0 0 0 3450 +203 205 0.997207949137742 -0.0576493917784158 -0.047464237106231 0.248113133934088 0.0589394145237673 0.997916574112681 0.0262422660379233 0.000821712263110084 0.0458524982099484 -0.0289665106422631 0.99852816168054 -0.0167147508490481 4.86885439659388e-05 5.63631683165459e-06 2.56843903994572e-06 -3.90858337542377e-06 -1.37327557746997e-06 -7.36033901696103e-06 5.63631683165459e-06 2.51353455142779e-05 -1.93924875810168e-06 -7.65153056217743e-06 -2.45333745380621e-07 -6.8318456643012e-06 2.56843903994572e-06 -1.93924875810168e-06 1.62877880182694e-05 2.28720250664933e-06 5.45109691291008e-07 -1.42924411927106e-07 -3.90858337542377e-06 -7.65153056217743e-06 2.28720250664933e-06 7.98522998901196e-05 -3.85729710692801e-06 5.52039040272998e-06 -1.37327557746997e-06 -2.45333745380621e-07 5.45109691291008e-07 -3.85729710692801e-06 1.60289813880695e-05 2.24287762423126e-06 -7.36033901696103e-06 -6.8318456643012e-06 -1.42924411927106e-07 5.52039040272998e-06 2.24287762423126e-06 0.000122419064268288 3375 3312 0 111 375 3375 3312 0 58 409 0 0 0 0 0 0 0 0 3675 0 0 0 0 0 3396 +202 204 0.996758394127023 -0.0720098857958672 -0.0358786856641031 0.25791240517037 0.0725140320068296 0.997283285145465 0.0129523870997254 0.00720768602298449 0.0348485135899632 -0.0155121087262436 0.999272212954726 -0.000870093339340584 4.88984734518686e-05 7.37003874333258e-06 3.71379728874021e-06 3.10899359771718e-06 2.40734290800013e-06 -4.5605806982913e-05 7.37003874333258e-06 0.000122135042166987 1.10027383783311e-06 2.46846396691052e-05 -3.88539824371074e-08 4.24061960950639e-06 3.71379728874021e-06 1.10027383783311e-06 1.23151081099872e-05 1.81644930533557e-06 2.99362884504357e-06 8.07807078721958e-07 3.10899359771718e-06 2.46846396691052e-05 1.81644930533557e-06 0.000118965079826441 -4.6374196449907e-06 7.16292378900351e-05 2.40734290800013e-06 -3.88539824371074e-08 2.99362884504357e-06 -4.6374196449907e-06 1.28535309121721e-05 -1.11701170168075e-05 -4.5605806982913e-05 4.24061960950639e-06 8.07807078721958e-07 7.16292378900351e-05 -1.11701170168075e-05 0.000477712191133288 3123 3109 0 66 435 3123 3109 0 44 478 0 0 0 0 0 0 0 0 3676 0 0 0 0 0 3323 +204 206 0.999166208081774 -0.0317479442763434 0.0256701511821703 0.25095958342391 0.0316293853810361 0.999487101542812 0.0050115696111513 -0.00344783291044151 -0.025816092033985 -0.00419545990038157 0.999657905239746 0.00266163093708023 5.09526713334874e-05 3.12268696887142e-07 1.51074619326151e-05 7.22490170967561e-06 -1.2591414100452e-06 -1.815731504049e-05 3.12268696887142e-07 3.48937572296738e-05 -5.21594460592354e-06 1.0289295469737e-05 -1.0265856304986e-06 -2.84326768894617e-06 1.51074619326151e-05 -5.21594460592354e-06 1.61132658265842e-05 4.82748515224364e-06 7.71501849962162e-07 2.31825008803435e-06 7.22490170967561e-06 1.0289295469737e-05 4.82748515224364e-06 0.000106761047192295 -1.01267532094039e-05 1.0497066874347e-05 -1.2591414100452e-06 -1.0265856304986e-06 7.71501849962162e-07 -1.01267532094039e-05 1.46212189176547e-05 -3.82248616029118e-06 -1.815731504049e-05 -2.84326768894617e-06 2.31825008803435e-06 1.0497066874347e-05 -3.82248616029118e-06 0.000151540282426833 3279 3214 0 191 308 3279 3214 0 164 343 0 0 0 0 0 0 0 0 3593 0 0 0 0 0 3467 +208 211 0.991206826664688 0.114711999180364 -0.0659559248086374 0.436384472448312 -0.113944928593526 0.993369417417094 0.0152890087395679 -0.0494509047334131 0.0672724313603637 -0.00763922669295569 0.997705398499176 0.0189085954237083 4.52289559301809e-05 3.73133291090835e-06 2.21654142778378e-06 3.20809924183337e-08 -2.76335395570393e-06 -1.10920554588922e-05 3.73133291090835e-06 3.78673605222233e-05 -1.23966857762137e-06 -5.97155015135819e-06 7.48794555435905e-07 1.52633379040695e-05 2.21654142778378e-06 -1.23966857762137e-06 1.33764655139174e-05 2.00027100235651e-07 -4.6422250818381e-07 2.93146888361608e-06 3.20809924183337e-08 -5.97155015135819e-06 2.00027100235651e-07 7.78010450367851e-05 3.83773646486629e-06 1.48037433792639e-05 -2.76335395570393e-06 7.48794555435905e-07 -4.6422250818381e-07 3.83773646486629e-06 1.65720304724351e-05 -3.98481100878982e-06 -1.10920554588922e-05 1.52633379040695e-05 2.93146888361608e-06 1.48037433792639e-05 -3.98481100878982e-06 0.000264723167963772 3239 3214 0 1154 136 3239 3214 0 1011 165 0 0 0 0 0 0 0 0 2464 0 0 0 0 0 3684 +205 208 0.997418293394077 0.024584249420254 0.0674711989169395 0.405886399636965 -0.0229690268294873 0.999433181127391 -0.0246117912409995 -0.0153954389468603 -0.0680380173825838 0.0229985030388281 0.997417614166012 0.0304437353367604 5.47830957319467e-05 8.77288798359753e-06 3.61043109811243e-06 -3.78426915541624e-06 2.50384952838703e-06 -2.34326685318758e-05 8.77288798359753e-06 5.42408905019258e-05 -4.67815284113577e-06 -3.22959273343797e-05 4.75162032891704e-06 -2.59255190699074e-05 3.61043109811243e-06 -4.67815284113577e-06 1.43703492080145e-05 7.31763581580516e-06 3.37506855104873e-06 4.20486288154809e-06 -3.78426915541624e-06 -3.22959273343797e-05 7.31763581580516e-06 0.000147747758614253 -1.79411397427439e-05 8.68331735017174e-06 2.50384952838703e-06 4.75162032891704e-06 3.37506855104873e-06 -1.79411397427439e-05 1.75820058666442e-05 -6.07878910130785e-06 -2.34326685318758e-05 -2.59255190699074e-05 4.20486288154809e-06 8.68331735017174e-06 -6.07878910130785e-06 0.000163726330316539 3206 3144 0 820 344 3206 3144 0 740 376 0 0 0 0 0 0 0 0 2957 0 0 0 0 0 3449 +209 212 0.998085984080226 0.0471727873526572 -0.0399887048551068 0.45472692916593 -0.0466441106462352 0.998812720270586 0.0140526427298652 -0.023497984714007 0.0406041294036657 -0.0121605081741041 0.999101309535884 0.000470861960390881 5.09159576439043e-05 -3.27435295447037e-06 2.37899305489253e-06 2.67284767830188e-06 6.74633192344505e-07 -5.63247648148773e-06 -3.27435295447037e-06 5.4054497507285e-05 -1.82432919186579e-06 1.05540555099584e-05 8.84328381531932e-07 9.38120107660496e-06 2.37899305489253e-06 -1.82432919186579e-06 1.40848976140037e-05 -3.04298122882535e-06 3.40459881403953e-06 6.77355066083216e-06 2.67284767830188e-06 1.05540555099584e-05 -3.04298122882535e-06 0.000126174055452467 2.3536921065215e-06 3.84130573714882e-05 6.74633192344505e-07 8.84328381531932e-07 3.40459881403953e-06 2.3536921065215e-06 1.26389534748544e-05 -4.94423616522953e-07 -5.63247648148773e-06 9.38120107660496e-06 6.77355066083216e-06 3.84130573714882e-05 -4.94423616522953e-07 0.000209402340104726 3236 3214 0 930 375 3236 3214 0 808 412 0 0 0 0 0 0 0 0 2446 0 0 0 0 0 3424 +206 208 0.999151711579526 0.0332459502008309 0.0243015234696896 0.261991425903554 -0.032156525211055 0.998517243829722 -0.0439234750565895 -0.0103794820796139 -0.0257257679001966 0.0431047627291919 0.998739287449936 0.000248851962350508 0.00476959443772913 -0.000398157158038302 8.65172947857595e-05 7.35143376706484e-05 -0.000215108409017568 -0.00409130201204128 -0.000398157158038302 0.000133347069327133 -1.03085746822568e-05 1.23203238731961e-05 9.73508287810282e-06 0.000678275423644242 8.65172947857595e-05 -1.03085746822568e-05 1.69651310071478e-05 3.53766806332801e-06 -5.4809421922591e-07 -5.24801130956702e-05 7.35143376706484e-05 1.23203238731961e-05 3.53766806332801e-06 0.000114136156844114 -1.14657798261671e-05 6.99876933546857e-05 -0.000215108409017568 9.73508287810282e-06 -5.4809421922591e-07 -1.14657798261671e-05 2.87265062054913e-05 0.000130798929181912 -0.00409130201204128 0.000678275423644242 -5.24801130956702e-05 6.99876933546857e-05 0.000130798929181912 0.00553357700272288 3375 3313 0 533 163 3375 3313 0 411 179 0 0 0 0 0 0 0 0 3180 0 0 0 0 0 3644 +209 211 0.996322932641826 0.0568937973022354 -0.0640602038751296 0.295791201759132 -0.0559793201368621 0.998304003739986 0.0159822349415953 -0.0207803438079216 0.0648608480441455 -0.0123374205264223 0.997818048767283 0.00485040858483951 3.50759111499258e-05 1.00785351755042e-05 -3.25716167143916e-07 -6.56982402557905e-06 -9.93014771262289e-08 -8.62931466838301e-06 1.00785351755042e-05 5.01083337308043e-05 -7.36264614948206e-06 -1.19647047992923e-05 7.0926262549041e-07 -4.11889515961935e-05 -3.25716167143916e-07 -7.36264614948206e-06 1.26063223639689e-05 2.10029526446432e-06 2.27974738828055e-06 6.29606941734392e-06 -6.56982402557905e-06 -1.19647047992923e-05 2.10029526446432e-06 8.65120011917663e-05 3.19333131356828e-07 1.50758373617655e-05 -9.93014771262289e-08 7.0926262549041e-07 2.27974738828055e-06 3.19333131356828e-07 1.26735689865237e-05 6.19045520564434e-07 -8.62931466838301e-06 -4.11889515961935e-05 6.29606941734392e-06 1.50758373617655e-05 6.19045520564434e-07 7.8316047456569e-05 2917 2892 0 615 138 2917 2892 0 505 169 0 0 0 0 0 0 0 0 3017 0 0 0 0 0 3673 +210 212 0.999937752804308 0.000169123704425635 0.0111562499901486 0.299184821331814 -0.000188368439474906 0.999998496186689 0.0017239900494896 0.00248454092053337 -0.0111559416456478 -0.00172598422134466 0.999936280942174 0.00405526228260402 3.21875508044881e-05 1.9866052550268e-06 8.5902843773138e-06 -9.6822169990017e-06 2.33125147939589e-07 -4.36441475507116e-06 1.9866052550268e-06 1.94169193196547e-05 -5.67890417090124e-08 2.52842075853894e-06 3.95652601632742e-08 -4.65099758861654e-06 8.5902843773138e-06 -5.67890417090124e-08 1.29168959698266e-05 -3.51922135893692e-06 1.91900660802189e-06 -1.88021443137507e-06 -9.6822169990017e-06 2.52842075853894e-06 -3.51922135893692e-06 0.000103451395010822 1.84019657219587e-06 6.82299453971473e-06 2.33125147939589e-07 3.95652601632742e-08 1.91900660802189e-06 1.84019657219587e-06 1.19059580656417e-05 2.2563267416328e-06 -4.36441475507116e-06 -4.65099758861654e-06 -1.88021443137507e-06 6.82299453971473e-06 2.2563267416328e-06 9.33508077284625e-05 3521 3499 0 416 307 3521 3499 0 349 355 0 0 0 0 0 0 0 0 2990 0 0 0 0 0 3481 +210 236 0.746078123478647 -0.66578391365163 0.00996062193337531 3.59226161567789 0.665269252453704 0.744705424005399 -0.0532038832852234 0.408628251314407 0.0280045604548488 0.046320748910807 0.99853399181704 -0.193294505747723 0.000175612912548049 -2.31847831549014e-05 1.12972789446213e-06 2.35882567852551e-05 -4.77254621798305e-06 5.59246895667692e-05 -2.31847831549014e-05 7.52921279956745e-05 -6.66075400642844e-06 5.45786542247147e-06 -6.95324007126524e-06 -4.47287410569764e-05 1.12972789446213e-06 -6.66075400642844e-06 2.95803513416012e-05 -8.96795078975898e-06 -5.57048856977966e-06 3.46073010764778e-08 2.35882567852551e-05 5.45786542247147e-06 -8.96795078975898e-06 6.82497584763455e-05 1.76312344092959e-05 2.09458100134496e-05 -4.77254621798305e-06 -6.95324007126524e-06 -5.57048856977966e-06 1.76312344092959e-05 5.16698618678503e-05 -2.52579697530957e-05 5.59246895667692e-05 -4.47287410569764e-05 3.46073010764778e-08 2.09458100134496e-05 -2.52579697530957e-05 0.000157685159006613 2452 2438 0 1838 2041 2452 2438 0 1838 2041 0 0 0 0 0 0 0 0 115 0 0 0 0 0 0 +211 214 0.998387605326105 -0.0509314621784531 0.0250634333555769 0.473055774433709 0.0507821544935144 0.998688219276683 0.00655846498541679 0.0265021139109328 -0.0253645878381944 -0.00527511500660457 0.999664349091967 -0.00360839394927585 5.23543234992983e-05 -1.57958993761228e-05 4.78776167914417e-06 -1.01772998898925e-05 2.5138432748118e-07 -2.57273818671848e-05 -1.57958993761228e-05 5.72934300536806e-05 -2.33984206088815e-06 8.22093736432486e-06 -3.89070147501002e-06 7.49729504548273e-05 4.78776167914417e-06 -2.33984206088815e-06 1.46475886163949e-05 -5.99119235689402e-07 1.50031713166359e-06 4.74966100706111e-06 -1.01772998898925e-05 8.22093736432486e-06 -5.99119235689402e-07 0.000129627438032399 2.15336328885614e-06 6.44536330769854e-05 2.5138432748118e-07 -3.89070147501002e-06 1.50031713166359e-06 2.15336328885614e-06 1.63427073754036e-05 -6.4105789413473e-06 -2.57273818671848e-05 7.49729504548273e-05 4.74966100706111e-06 6.44536330769854e-05 -6.4105789413473e-06 0.000593540265867969 3302 3269 0 592 741 3302 3269 0 487 792 0 0 0 0 0 0 0 0 2859 0 0 0 0 0 3025 +213 240 0.379049275935396 -0.925281673902346 0.0132465223105972 3.49250263626361 0.921008279499772 0.375832090096987 -0.102440173497514 0.468217879472555 0.089807547042118 0.0510300303135673 0.994650964158018 -0.159405852583443 9.55006402718898e-05 -9.56323436807578e-06 8.25746431579348e-07 -8.18083168477367e-07 5.48556668638366e-06 -8.31425321516022e-07 -9.56323436807578e-06 0.000606612722013544 -3.518939790055e-05 6.45500087955554e-05 -0.00024916543463448 -0.000308609651264535 8.25746431579348e-07 -3.518939790055e-05 2.81124440375235e-05 4.24946903892723e-06 -3.40118786335179e-06 2.3358537302695e-05 -8.18083168477367e-07 6.45500087955554e-05 4.24946903892723e-06 4.42982663133907e-05 -7.02386464806919e-05 -4.74356910056513e-05 5.48556668638366e-06 -0.00024916543463448 -3.40118786335179e-06 -7.02386464806919e-05 0.000275933485830019 0.000161137532092356 -8.31425321516022e-07 -0.000308609651264535 2.3358537302695e-05 -4.74356910056513e-05 0.000161137532092356 0.00031075468711169 1095 1135 0 1484 1528 1095 1135 0 1474 1528 0 0 0 0 0 0 0 0 114 0 0 0 0 0 0 +213 217 0.998092981120191 -0.0606350187978716 0.0115670019448662 0.54679911730427 0.0604553675796335 0.998053699193784 0.0152958182656379 0.0516748175484193 -0.0124719513077212 -0.014567361497052 0.999816104295981 -0.0601365989398369 5.70789994342605e-05 8.01248643266053e-06 6.33232886170476e-06 -7.74961076179657e-06 -1.2009434131735e-06 -3.29131112472648e-05 8.01248643266053e-06 3.9740998252214e-05 -1.6900740316855e-06 -6.82540134581365e-06 -2.34453187696045e-07 -3.80968458215526e-06 6.33232886170476e-06 -1.6900740316855e-06 1.40721322973185e-05 -9.99636862672511e-07 -1.36981995468041e-06 1.90264769604498e-06 -7.74961076179657e-06 -6.82540134581365e-06 -9.99636862672511e-07 0.000304455142957753 -9.00462211465418e-06 0.00016986461223016 -1.2009434131735e-06 -2.34453187696045e-07 -1.36981995468041e-06 -9.00462211465418e-06 1.76625414626148e-05 -1.15554163881903e-05 -3.29131112472648e-05 -3.80968458215526e-06 1.90264769604498e-06 0.00016986461223016 -1.15554163881903e-05 0.000296678648778163 3110 3060 0 730 894 3110 3060 0 618 944 0 0 0 0 0 0 0 0 3001 0 0 0 0 0 2864 +214 240 0.405648406976213 -0.913519016007304 0.0305348540312334 3.34810212285481 0.908928336444016 0.399635074312756 -0.118916300767186 0.37122727891795 0.0964295034041671 0.075992202047883 0.992434650796283 -0.145206918067823 7.02484071517003e-05 -1.61740773660426e-06 1.43140471420245e-05 1.91016896432507e-06 -2.34591398207826e-06 1.88339614666523e-05 -1.61740773660426e-06 4.60175262689877e-05 -8.41049995089712e-06 5.78105131536927e-06 -1.03787278569014e-05 -3.06716949115247e-05 1.43140471420245e-05 -8.41049995089712e-06 2.17109116461558e-05 6.12429865093396e-06 -7.63311956131142e-06 4.11397439563699e-06 1.91016896432507e-06 5.78105131536927e-06 6.12429865093396e-06 4.57623331436244e-05 -5.00470101422176e-05 3.02865742095946e-06 -2.34591398207826e-06 -1.03787278569014e-05 -7.63311956131142e-06 -5.00470101422176e-05 0.000144785771761714 2.55818265135113e-06 1.88339614666523e-05 -3.06716949115247e-05 4.11397439563699e-06 3.02865742095946e-06 2.55818265135113e-06 0.000119149425173518 1095 1135 0 1461 1531 1095 1135 0 1451 1531 0 0 0 0 0 0 0 0 115 0 0 0 0 0 0 +212 214 0.999144776167507 -0.0413449930230881 -0.000554805463707349 0.314504054983471 0.0413484974085287 0.999093126517782 0.0101600347922921 0.0172804265240874 0.000134235757742875 -0.0101742860606771 0.999948231601975 -0.0104616476599385 3.6540728541468e-05 -5.34177253499914e-06 6.38260196751103e-06 1.09247294938279e-05 -1.83176499695449e-07 9.06929869588255e-06 -5.34177253499914e-06 3.33224254230145e-05 -4.05183763220966e-07 5.08164059536557e-06 1.35151761255911e-06 7.2128868679814e-06 6.38260196751103e-06 -4.05183763220966e-07 1.23712116963398e-05 2.64662943878641e-06 1.41659788020758e-06 3.64385986966895e-07 1.09247294938279e-05 5.08164059536557e-06 2.64662943878641e-06 0.000162999865189165 4.63072239542491e-06 5.86701170140421e-05 -1.83176499695449e-07 1.35151761255911e-06 1.41659788020758e-06 4.63072239542491e-06 1.30012858435685e-05 3.57320559466601e-06 9.06929869588255e-06 7.2128868679814e-06 3.64385986966895e-07 5.86701170140421e-05 3.57320559466601e-06 0.000177500556360406 3118 3085 0 314 462 3118 3085 0 223 511 0 0 0 0 0 0 0 0 3140 0 0 0 0 0 3316 +213 215 0.99823444916336 -0.0502118556480984 -0.0317293878903837 0.314628667415867 0.0509204999960662 0.998461800811042 0.0219347897487357 0.0237270179195098 0.0305791952751296 -0.0235117390582908 0.999255778538598 -0.0731297866100163 4.24200974825853e-05 -1.67705147546108e-06 5.70870681769767e-06 1.48558843115e-05 -1.84369531665939e-08 -3.13463678537559e-06 -1.67705147546108e-06 7.30988163336309e-05 -3.45455129509029e-06 7.83963424832551e-06 -1.02405294845311e-06 4.87088115032597e-05 5.70870681769767e-06 -3.45455129509029e-06 1.84896981919773e-05 3.45602389781647e-06 -4.75317605418078e-07 2.32402843415516e-06 1.48558843115e-05 7.83963424832551e-06 3.45602389781647e-06 0.000135238164527515 -4.02829672911661e-06 4.13343519047673e-05 -1.84369531665939e-08 -1.02405294845311e-06 -4.75317605418078e-07 -4.02829672911661e-06 1.4213083963858e-05 -6.65456503504841e-06 -3.13463678537559e-06 4.87088115032597e-05 2.32402843415516e-06 4.13343519047673e-05 -6.65456503504841e-06 0.000385333158111896 3163 3116 0 297 480 3163 3116 0 195 522 0 0 0 0 0 0 0 0 3285 0 0 0 0 0 3294 +213 239 0.416550481260337 -0.909030040269964 0.0122508142002593 3.43452841642919 0.904478493987596 0.413030652997393 -0.106415852195417 0.44576683446094 0.0916752446176797 0.0554081724237023 0.994246239094196 -0.123050712775634 0.000144508945671592 -8.21970826756152e-05 2.47472883636455e-05 -3.45995748365706e-06 1.26291634763629e-05 0.000102268415049161 -8.21970826756152e-05 0.000273077644157584 -3.898131341221e-05 3.32005186184212e-06 -4.91078997966574e-05 -0.000267988919211488 2.47472883636455e-05 -3.898131341221e-05 3.32258542456664e-05 -6.74627986982087e-06 2.40683022208465e-06 5.05252795716826e-05 -3.45995748365706e-06 3.32005186184212e-06 -6.74627986982087e-06 4.62467810421222e-05 -1.97702890187971e-05 -4.40476108679719e-05 1.26291634763629e-05 -4.91078997966574e-05 2.40683022208465e-06 -1.97702890187971e-05 0.000116836069328418 8.95542733668439e-05 0.000102268415049161 -0.000267988919211488 5.05252795716826e-05 -4.40476108679719e-05 8.95542733668439e-05 0.000354451141284343 1298 1318 0 1535 1643 1298 1318 0 1526 1643 0 0 0 0 0 0 0 0 118 0 0 0 0 0 0 +214 217 0.999085796646829 -0.0354767032035861 0.0238531857070483 0.429668655882207 0.0351836541621853 0.999301492974744 0.0125951029469095 0.0316351450246192 -0.0242833568183233 -0.0117443462249787 0.999636128255368 -0.039233093828452 5.4573069865143e-05 7.52140224771432e-06 1.45953793188242e-06 7.57043156665544e-06 5.37386306268193e-07 1.96002625817629e-06 7.52140224771432e-06 7.7219233917414e-05 -4.21348094155164e-06 2.13489296265732e-05 3.21350446795453e-06 -2.37401222090853e-05 1.45953793188242e-06 -4.21348094155164e-06 1.34986125335718e-05 5.10398794692046e-06 1.47005672042311e-06 1.08890347876812e-05 7.57043156665544e-06 2.13489296265732e-05 5.10398794692046e-06 9.30228983738727e-05 1.45779122211802e-06 1.51172360197774e-05 5.37386306268193e-07 3.21350446795453e-06 1.47005672042311e-06 1.45779122211802e-06 1.31747309687627e-05 -5.64013630306103e-06 1.96002625817629e-06 -2.37401222090853e-05 1.08890347876812e-05 1.51172360197774e-05 -5.64013630306103e-06 0.000189072208401064 3156 3106 0 579 614 3156 3106 0 459 658 0 0 0 0 0 0 0 0 3155 0 0 0 0 0 3156 +215 217 0.999491294458669 -0.00948667121912267 0.0304492261069759 0.270204117223474 0.00986287050857131 0.999876584389942 -0.0122286456337271 0.017229334140332 -0.0303294590565778 0.0125227416281096 0.999461507440607 -0.0413761755295274 7.29655290515858e-05 1.93498396439673e-06 1.26611702037201e-06 1.21486834742831e-05 2.42861590917187e-06 3.66240411765312e-07 1.93498396439673e-06 3.45147766344115e-05 -3.57272953163486e-06 -3.9696443702513e-07 -1.70444396442805e-06 5.16440326431858e-05 1.26611702037201e-06 -3.57272953163486e-06 1.38017541686308e-05 -5.08969913316318e-07 2.82858992004504e-06 7.8957789789749e-07 1.21486834742831e-05 -3.9696443702513e-07 -5.08969913316318e-07 0.000103650353780659 4.1815424229212e-07 -2.15593992157156e-06 2.42861590917187e-06 -1.70444396442805e-06 2.82858992004504e-06 4.1815424229212e-07 1.24298592739617e-05 -6.80195622450252e-07 3.66240411765312e-07 5.16440326431858e-05 7.8957789789749e-07 -2.15593992157156e-06 -6.80195622450252e-07 0.000467385592676538 3406 3356 0 364 305 3406 3356 0 258 337 0 0 0 0 0 0 0 0 3375 0 0 0 0 0 3472 +215 219 0.998085546949626 0.0387589838598437 0.0481973250338509 0.563391853573814 -0.0372831863296165 0.998819086789863 -0.0311511778489277 0.0272448127205951 -0.0493477961754869 0.0292945905316459 0.998351952959579 -0.021189406779851 8.64913163263036e-05 1.21913163550294e-05 -1.34350404447338e-06 2.84094190080534e-06 5.73484834196951e-06 -2.9329739545864e-05 1.21913163550294e-05 2.79859169585956e-05 -8.05395799391348e-07 7.02337858304336e-06 -1.3734953225873e-06 -2.06303492440009e-05 -1.34350404447338e-06 -8.05395799391348e-07 1.59956321609303e-05 4.03289880947703e-06 2.52962369367386e-06 2.64508001146335e-06 2.84094190080534e-06 7.02337858304336e-06 4.03289880947703e-06 0.000109775813853637 -8.90569770232236e-07 -9.12975714470328e-06 5.73484834196951e-06 -1.3734953225873e-06 2.52962369367386e-06 -8.90569770232236e-07 1.33635980212034e-05 2.42811912022612e-07 -2.9329739545864e-05 -2.06303492440009e-05 2.64508001146335e-06 -9.12975714470328e-06 2.42811912022612e-07 0.000107463466497121 3245 3205 0 1133 624 3245 3205 0 1004 667 0 0 0 0 0 0 0 0 2599 0 0 0 0 0 3181 +216 219 0.99812377826625 0.0486423763025702 0.0371865901521645 0.436652828653117 -0.0479409097299523 0.998659255153451 -0.0195284733304635 0.012445779836832 -0.0380866437714124 0.0177090746227243 0.999117508725693 0.0192076445214746 5.2069114023436e-05 -6.42212977326782e-06 4.83682843350252e-06 -6.90572492000448e-06 8.56156537121239e-07 2.4748571540489e-06 -6.42212977326782e-06 7.07053047138709e-05 -6.07878872240231e-06 1.18245323944707e-05 1.94910506648011e-06 -3.72555268349077e-05 4.83682843350252e-06 -6.07878872240231e-06 1.42275769795009e-05 2.6763729395907e-06 1.49905874332579e-06 -1.60144516305746e-06 -6.90572492000448e-06 1.18245323944707e-05 2.6763729395907e-06 0.000121057908419218 -5.04250895491914e-08 -2.64529445487273e-05 8.56156537121239e-07 1.94910506648011e-06 1.49905874332579e-06 -5.04250895491914e-08 1.20894061313092e-05 1.90164219782441e-06 2.4748571540489e-06 -3.72555268349077e-05 -1.60144516305746e-06 -2.64529445487273e-05 1.90164219782441e-06 0.000204361136409213 2928 2888 0 887 382 2928 2888 0 761 425 0 0 0 0 0 0 0 0 2861 0 0 0 0 0 3427 +217 219 0.998858303726901 0.0470133916017687 0.00847526317688162 0.264550684508127 -0.0468864248721787 0.998793464105801 -0.0146040823826699 0.00828127930647909 -0.00915162491168688 0.0141900341660268 0.999857435183558 -0.0164112469228579 9.21112525474606e-05 7.62086208536233e-06 -6.92161391091692e-06 3.88279600887397e-05 4.59868129931984e-06 -3.18430235437176e-05 7.62086208536233e-06 3.71680177583229e-05 -8.62231405615561e-07 1.49551723404251e-05 -1.18431336559862e-06 -5.79451096986367e-06 -6.92161391091692e-06 -8.62231405615561e-07 1.76058487353642e-05 -7.96556301434048e-07 2.57683111703951e-06 6.39135905218279e-06 3.88279600887397e-05 1.49551723404251e-05 -7.96556301434048e-07 0.000155485323611236 5.53316644499198e-06 2.14958456995833e-06 4.59868129931984e-06 -1.18431336559862e-06 2.57683111703951e-06 5.53316644499198e-06 1.31977232737174e-05 -1.1397641253554e-06 -3.18430235437176e-05 -5.79451096986367e-06 6.39135905218279e-06 2.14958456995833e-06 -1.1397641253554e-06 0.000208569568094114 3276 3236 0 510 155 3276 3236 0 401 189 0 0 0 0 0 0 0 0 3254 0 0 0 0 0 3666 +219 221 0.998213417888049 0.0324017044893105 -0.0502006164747661 0.266154982256664 -0.0318805271603737 0.999429511374862 0.0111482635858906 0.00923075203936407 0.0505332003363713 -0.00952792418059748 0.998676931907698 -0.0491306741960377 5.85820770628971e-05 5.83858962545518e-06 9.47263537188448e-07 5.47373794828624e-06 2.29933423473447e-06 -9.63722796967493e-06 5.83858962545518e-06 2.25785600507994e-05 1.19618819109243e-06 4.14098953144609e-06 -1.77444169291597e-06 -6.4708825576494e-06 9.47263537188448e-07 1.19618819109243e-06 1.52480575516967e-05 -5.89863913353892e-07 2.08683402394301e-07 9.61776516824905e-06 5.47373794828624e-06 4.14098953144609e-06 -5.89863913353892e-07 0.000122628639507302 3.16164346641399e-06 1.08520299097036e-05 2.29933423473447e-06 -1.77444169291597e-06 2.08683402394301e-07 3.16164346641399e-06 1.28964926001224e-05 -2.82091258948613e-06 -9.63722796967493e-06 -6.4708825576494e-06 9.61776516824905e-06 1.08520299097036e-05 -2.82091258948613e-06 6.95001491442514e-05 3068 3034 0 446 203 3068 3034 0 353 232 0 0 0 0 0 0 0 0 3313 0 0 0 0 0 3625 +220 222 0.999533828530834 0.0101498506494685 0.0287942034841448 0.258331317098139 -0.0110633902205961 0.999434715829203 0.031746656394436 0.0101732443945938 -0.028455702755681 -0.0320504185182199 0.999081099637806 0.00572633557521936 5.1565958890905e-05 -3.86766900533939e-06 5.19856232758222e-06 7.88954064679062e-06 1.54723920066938e-06 1.65592213513758e-05 -3.86766900533939e-06 4.83164143521228e-05 -1.88546258587085e-07 1.56143814174516e-07 -1.1711374126391e-06 -2.66937056718248e-06 5.19856232758222e-06 -1.88546258587085e-07 1.66165850381909e-05 -6.96657388501222e-06 2.2839604768074e-06 8.72536917361453e-07 7.88954064679062e-06 1.56143814174516e-07 -6.96657388501222e-06 9.91877778731822e-05 4.40457800048255e-06 1.22044150948695e-05 1.54723920066938e-06 -1.1711374126391e-06 2.2839604768074e-06 4.40457800048255e-06 1.19019041980217e-05 -6.22744165249983e-08 1.65592213513758e-05 -2.66937056718248e-06 8.72536917361453e-07 1.22044150948695e-05 -6.22744165249983e-08 0.000140615007625599 3304 3267 0 390 245 3304 3267 0 285 278 0 0 0 0 0 0 0 0 3351 0 0 0 0 0 3578 +220 224 0.999396940277503 -0.0282076003511773 0.0202506060746946 0.52041542106937 0.0276291904902001 0.999217685129102 0.0282956809088327 0.0198979955026198 -0.0210329169831585 -0.0277191090705763 0.999394450352569 -0.00066063577403355 6.66114989749313e-05 -1.42783014358042e-06 4.15747504022866e-06 5.53564253036415e-05 -1.28210851062967e-06 -1.25984906346893e-05 -1.42783014358042e-06 3.99732636882425e-05 -1.41284904103415e-06 1.70266881150048e-06 -2.42550255878494e-06 -1.6883368438943e-05 4.15747504022866e-06 -1.41284904103415e-06 1.64918858337458e-05 1.02011362296744e-06 1.90231136904167e-06 3.07840860658784e-06 5.53564253036415e-05 1.70266881150048e-06 1.02011362296744e-06 0.00023074237837503 3.6708694444256e-06 -3.98265735314533e-06 -1.28210851062967e-06 -2.42550255878494e-06 1.90231136904167e-06 3.6708694444256e-06 1.43879205789441e-05 2.43548712693766e-06 -1.25984906346893e-05 -1.6883368438943e-05 3.07840860658784e-06 -3.98265735314533e-06 2.43548712693766e-06 0.000117355442962624 2928 2885 0 824 730 2928 2885 0 702 779 0 0 0 0 0 0 0 0 2886 0 0 0 0 0 3055 +218 220 0.998720841034586 0.0435461842555373 -0.0256984731054774 0.259683938389988 -0.0441620035648979 0.998738389140215 -0.023902876369648 0.0107801765320029 0.0246251725740976 0.0250071968519371 0.999383930719973 -0.0468369058606133 9.07617074868013e-05 7.50181639555244e-06 7.33278222314488e-06 3.41291955944509e-05 1.56250270015824e-06 -3.41497909145015e-05 7.50181639555244e-06 3.50516859289911e-05 -2.26126619007576e-06 6.78968957884364e-06 -7.11109169102588e-07 1.00978259998547e-05 7.33278222314488e-06 -2.26126619007576e-06 2.22023816415351e-05 -4.86032205698333e-06 -1.23537557143862e-06 -3.02616479791883e-06 3.41291955944509e-05 6.78968957884364e-06 -4.86032205698333e-06 9.59457790668335e-05 1.22162431450694e-05 4.00138527364981e-05 1.56250270015824e-06 -7.11109169102588e-07 -1.23537557143862e-06 1.22162431450694e-05 1.5095785124339e-05 7.4676736910441e-06 -3.41497909145015e-05 1.00978259998547e-05 -3.02616479791883e-06 4.00138527364981e-05 7.4676736910441e-06 0.000273500540466166 3309 3273 0 479 167 3309 3273 0 378 199 0 0 0 0 0 0 0 0 3275 0 0 0 0 0 3655 +218 222 0.998451641708117 0.0547963509574423 0.00957491995341174 0.537238238210731 -0.0547941045086753 0.998497550880059 -0.000496988547210525 0.00824846200465735 -0.00958776728220901 -2.84301337169631e-05 0.999954035898786 -0.00697508604644099 5.6049923552863e-05 1.1822655752726e-05 8.48636143929068e-07 1.01637693192118e-05 1.27781763016466e-06 -2.40815905827178e-05 1.1822655752726e-05 6.42638672899324e-05 -4.80393756239569e-06 1.96690582643001e-05 6.80789361729948e-07 9.98237290026502e-06 8.48636143929068e-07 -4.80393756239569e-06 1.33933226614391e-05 -2.25738181652136e-06 1.98636014169323e-06 8.96640787757613e-07 1.01637693192118e-05 1.96690582643001e-05 -2.25738181652136e-06 9.33204945162027e-05 2.92186188658144e-06 4.38273833869732e-05 1.27781763016466e-06 6.80789361729948e-07 1.98636014169323e-06 2.92186188658144e-06 1.41915480553587e-05 -1.96577897989431e-08 -2.40815905827178e-05 9.98237290026502e-06 8.96640787757613e-07 4.38273833869732e-05 -1.96577897989431e-08 0.000307230194614738 3134 3097 0 1154 521 3134 3097 0 1002 562 0 0 0 0 0 0 0 0 2566 0 0 0 0 0 3298 +218 221 0.997983125304421 0.0592931621200239 -0.0226716239698243 0.402391001873476 -0.0593566369247809 0.998234554030034 -0.0021365377224177 0.00901256596126876 0.0225049163651033 0.00347793994602123 0.999740682713838 -0.00916703344969685 7.56345300058272e-05 -1.39019364633266e-06 1.33372663417527e-05 6.56463215955586e-06 1.88850984207654e-06 1.67627842020364e-06 -1.39019364633266e-06 4.62352786094154e-05 1.03173010472949e-06 -1.16011448273622e-05 -1.13972010523247e-06 3.05597203382308e-05 1.33372663417527e-05 1.03173010472949e-06 1.89963807306813e-05 3.99580327147329e-06 1.59666205549718e-06 9.62847640698868e-06 6.56463215955586e-06 -1.16011448273622e-05 3.99580327147329e-06 0.000178956159481009 8.19071233196305e-06 3.40701858419127e-05 1.88850984207654e-06 -1.13972010523247e-06 1.59666205549718e-06 8.19071233196305e-06 1.33195030717342e-05 1.497713782041e-06 1.67627842020364e-06 3.05597203382308e-05 9.62847640698868e-06 3.40701858419127e-05 1.497713782041e-06 0.000310032533619594 3334 3300 0 823 304 3334 3300 0 703 346 0 0 0 0 0 0 0 0 2931 0 0 0 0 0 3511 +221 224 0.998758544298769 -0.040603613281121 0.0288568324443407 0.407325573890246 0.0404687462171729 0.9991670506627 0.00524265673228022 0.0224572056714179 -0.0290456669714028 -0.00406834837736883 0.999569806352546 0.0107981989415685 8.49199945492662e-05 -1.85095891206336e-05 5.85506330040775e-06 9.03574091855949e-06 -3.45434354740571e-06 1.73379765157811e-05 -1.85095891206336e-05 5.62478080338162e-05 -4.0866110290373e-06 1.51365836319111e-05 -2.77760809832764e-07 -2.25628016427308e-05 5.85506330040775e-06 -4.0866110290373e-06 1.82016722719485e-05 -2.52546328727093e-06 2.29495544996252e-06 -1.35371996252845e-06 9.03574091855949e-06 1.51365836319111e-05 -2.52546328727093e-06 7.83267964554632e-05 4.06057040120571e-06 1.91826506968481e-05 -3.45434354740571e-06 -2.77760809832764e-07 2.29495544996252e-06 4.06057040120571e-06 1.47189039558956e-05 1.63937519542858e-06 1.73379765157811e-05 -2.25628016427308e-05 -1.35371996252845e-06 1.91826506968481e-05 1.63937519542858e-06 0.000176659879192162 3108 3065 0 523 593 3108 3065 0 426 642 0 0 0 0 0 0 0 0 3199 0 0 0 0 0 3191 +221 225 0.996597837873592 -0.0813116114221463 0.0134599923333701 0.571318337426093 0.0813084533018654 0.996688679054581 0.000782602128770916 0.0364870582412891 -0.0134790566190242 0.000314471568632927 0.9999091039391 -0.0148133506719147 6.67370176241638e-05 -7.08219815964703e-07 4.044472086069e-06 -1.61453290432723e-05 2.48980872734217e-06 2.51115486690312e-05 -7.08219815964703e-07 3.91906870894064e-05 -5.10986740986127e-06 1.25927068939786e-05 -1.55121290026738e-07 6.03589533153182e-05 4.044472086069e-06 -5.10986740986127e-06 1.54733330158655e-05 -4.06539786250805e-06 3.01253176543034e-06 -3.76208983731158e-06 -1.61453290432723e-05 1.25927068939786e-05 -4.06539786250805e-06 0.000144475385271875 -2.98359461987631e-06 0.000200236530721288 2.48980872734217e-06 -1.55121290026738e-07 3.01253176543034e-06 -2.98359461987631e-06 1.25623062833087e-05 -9.57364805644792e-06 2.51115486690312e-05 6.03589533153182e-05 -3.76208983731158e-06 0.000200236530721288 -9.57364805644792e-06 0.000750318210413284 3065 2987 0 770 942 3065 2987 0 653 992 0 0 0 0 0 0 0 0 2923 0 0 0 0 0 2815 +220 223 0.999794060970896 -0.0110537832012388 0.0170190929330855 0.398029067977989 0.0104667540756678 0.99936008193361 0.03420341644878 0.0160165794005597 -0.0173862792582106 -0.0340182379700829 0.999269971918984 0.00407896977993463 5.60968533535027e-05 2.41990844536926e-06 5.45778806428193e-06 -1.74358930118032e-06 -5.37444955378019e-07 -4.0690609997257e-06 2.41990844536926e-06 3.97853238868812e-05 -3.05916551995994e-06 -1.81846309081692e-06 -1.41714487884902e-06 -2.72445952355004e-05 5.45778806428193e-06 -3.05916551995994e-06 1.76611802823002e-05 9.03545444493354e-07 9.1778234105342e-07 3.98062544938172e-06 -1.74358930118032e-06 -1.81846309081692e-06 9.03545444493354e-07 0.000137940430132199 4.37728672949766e-06 -1.03429412272061e-06 -5.37444955378019e-07 -1.41714487884902e-06 9.1778234105342e-07 4.37728672949766e-06 1.34994086097489e-05 -8.10287533941498e-07 -4.0690609997257e-06 -2.72445952355004e-05 3.98062544938172e-06 -1.03429412272061e-06 -8.10287533941498e-07 0.000117656401633595 2874 2831 0 596 486 2874 2831 0 483 525 0 0 0 0 0 0 0 0 3124 0 0 0 0 0 3311 +223 225 0.998279245997967 -0.0580356622132961 -0.00839100239508494 0.282232066171485 0.0579894079737364 0.998301183994807 -0.0056546085118382 0.0116113002722846 0.00870491657545803 0.00515828906041434 0.999948806930327 0.00244028233393431 3.56552773163637e-05 -2.40698336072117e-06 7.93592486045259e-06 -9.85231832076204e-06 1.16634390507036e-06 -2.18265651984818e-06 -2.40698336072117e-06 2.21688770455988e-05 -2.50886455831538e-06 -4.30413584269532e-06 -5.9500252223316e-07 -1.47822990301847e-06 7.93592486045259e-06 -2.50886455831538e-06 1.21871499816258e-05 -2.27067114396589e-06 2.59934822000626e-06 3.44919206546713e-06 -9.85231832076204e-06 -4.30413584269532e-06 -2.27067114396589e-06 5.97833777764609e-05 3.25287254309578e-06 1.77316818256704e-05 1.16634390507036e-06 -5.9500252223316e-07 2.59934822000626e-06 3.25287254309578e-06 1.09184847322095e-05 4.42847000869495e-08 -2.18265651984818e-06 -1.47822990301847e-06 3.44919206546713e-06 1.77316818256704e-05 4.42847000869495e-08 0.000107125721472472 3509 3431 0 253 424 3509 3431 0 149 456 0 0 0 0 0 0 0 0 3465 0 0 0 0 0 3347 +224 252 0.218378827924152 -0.975550719543697 0.0247281441327087 3.28392718500727 0.964485033975225 0.211904737546474 -0.157686402213917 0.332979228360313 0.148591072249591 0.0582852966290314 0.987179577100632 -0.0401081322981829 0.000121103524246622 1.72510131632286e-05 1.58935296299939e-05 -1.34717454215445e-05 2.77841254796321e-05 -4.47881709272694e-05 1.72510131632286e-05 0.000250071905465614 -3.4673474959878e-05 -9.31823108851595e-06 -3.60922885853186e-05 -0.000153363783280515 1.58935296299939e-05 -3.4673474959878e-05 2.86542320836201e-05 -2.19906841491573e-06 2.10823094353984e-05 -4.27722815499717e-06 -1.34717454215445e-05 -9.31823108851595e-06 -2.19906841491573e-06 6.80125601619828e-05 -3.34040150849474e-05 0.0003045558992759 2.77841254796321e-05 -3.60922885853186e-05 2.10823094353984e-05 -3.34040150849474e-05 0.000133458028199417 -4.47945500040349e-05 -4.47881709272694e-05 -0.000153363783280515 -4.27722815499717e-06 0.0003045558992759 -4.47945500040349e-05 0.00209913155935183 776 865 0 1513 1623 776 865 0 1503 1623 0 0 0 0 0 0 0 0 134 0 0 0 0 0 0 +224 251 0.191524451577175 -0.98130422347197 0.0189843473455436 3.16582313905134 0.973536184220355 0.187480104912374 -0.130684766808208 0.318589575318025 0.124682326180309 0.0435112773671274 0.991242193553194 -0.0615347804883955 0.000316099506816714 -8.00237964954711e-05 2.06375818845033e-05 -1.85422343957701e-06 1.45843940822007e-05 -0.000202748344690851 -8.00237964954711e-05 0.000126783404780237 -2.22710523006101e-05 1.49538054536544e-05 -3.22723028288507e-05 7.73329000432003e-05 2.06375818845033e-05 -2.22710523006101e-05 3.05270298778886e-05 -3.49935654344497e-06 2.17912481905297e-05 8.28164717868639e-06 -1.85422343957701e-06 1.49538054536544e-05 -3.49935654344497e-06 3.66421537417855e-05 -3.44934682334847e-05 5.71711924527301e-05 1.45843940822007e-05 -3.22723028288507e-05 2.17912481905297e-05 -3.44934682334847e-05 0.000195074258385505 -1.56425492112079e-06 -0.000202748344690851 7.73329000432003e-05 8.28164717868639e-06 5.71711924527301e-05 -1.56425492112079e-06 0.000722394364875646 748 842 0 1508 1704 748 842 0 1494 1704 0 0 0 0 0 0 0 0 153 0 0 0 0 15 0 +223 227 0.986290592034809 -0.164072161129158 -0.0176406917674498 0.561208971717576 0.16329549093864 0.985808454621396 -0.0389393558765754 0.0526918927059324 0.0237792073613692 0.0355248749382988 0.999085848442407 -0.0591878276177584 6.88213635100814e-05 -2.03666037677916e-05 1.25818816905122e-05 -9.50166684391984e-06 5.77796834266767e-07 5.90857363847756e-06 -2.03666037677916e-05 5.01566858759994e-05 -1.39192006571401e-06 -2.18545891907347e-06 -3.36365674502804e-06 2.77079582297828e-05 1.25818816905122e-05 -1.39192006571401e-06 2.30534400037387e-05 -4.58136821306024e-06 1.14327874321919e-06 1.79046052882281e-05 -9.50166684391984e-06 -2.18545891907347e-06 -4.58136821306024e-06 7.48345155500956e-05 2.41399989439969e-06 2.3733919003146e-05 5.77796834266767e-07 -3.36365674502804e-06 1.14327874321919e-06 2.41399989439969e-06 1.26203571952257e-05 -5.89496068329894e-06 5.90857363847756e-06 2.77079582297828e-05 1.79046052882281e-05 2.3733919003146e-05 -5.89496068329894e-06 0.000280067169115775 3130 3042 0 548 947 3130 3042 0 418 987 0 0 0 0 0 0 0 0 3141 0 0 0 0 0 2610 +222 225 0.996412105153762 -0.0789959412183483 -0.0303736394604952 0.424138172763727 0.0788896624991286 0.99687235188469 -0.00468350281954804 0.0264885603643047 0.0306486191177105 0.00227053273801076 0.999527641852522 -0.024140635286264 6.01500987775321e-05 -7.0541052261785e-06 2.91853951365861e-06 -2.12660309768397e-06 1.87768584967322e-06 -4.03108832454656e-06 -7.0541052261785e-06 3.14215133206379e-05 -4.85122780531116e-06 7.90138224687992e-06 -1.64593650608572e-06 -1.12883926021564e-05 2.91853951365861e-06 -4.85122780531116e-06 1.49617181981194e-05 6.74269491392871e-07 3.15957359302907e-06 6.04466334821402e-07 -2.12660309768397e-06 7.90138224687992e-06 6.74269491392871e-07 9.43832025050797e-05 2.74790362334382e-06 2.38962921283091e-05 1.87768584967322e-06 -1.64593650608572e-06 3.15957359302907e-06 2.74790362334382e-06 1.19365881044161e-05 1.21977220114224e-06 -4.03108832454656e-06 -1.12883926021564e-05 6.04466334821402e-07 2.38962921283091e-05 1.21977220114224e-06 0.000111027509459136 3114 3036 0 451 684 3114 3036 0 340 729 0 0 0 0 0 0 0 0 3262 0 0 0 0 0 3077 +223 250 0.143169170123943 -0.98886569484339 0.0405860356270662 3.17307048420324 0.982110478440162 0.13688374613816 -0.129312985354218 0.350507060334099 0.122317606517042 0.0583736036671004 0.990772893013761 -0.0939442953026173 8.32194494625856e-05 -1.67665704665008e-05 1.16796168386647e-05 8.03755681316608e-06 -4.47449267120773e-05 -1.17895433724206e-05 -1.67665704665008e-05 0.00011901183843793 -5.71570596159649e-06 -9.50114148033899e-06 -8.54842685824478e-06 -9.68029610860793e-05 1.16796168386647e-05 -5.71570596159649e-06 2.7014569391216e-05 1.52131425561405e-06 3.12272221456968e-06 1.53852018728906e-05 8.03755681316608e-06 -9.50114148033899e-06 1.52131425561405e-06 2.4300690745745e-05 -2.57019320773052e-05 -1.16282305700549e-05 -4.47449267120773e-05 -8.54842685824478e-06 3.12272221456968e-06 -2.57019320773052e-05 0.000190066332651571 0.000123244372001729 -1.17895433724206e-05 -9.68029610860793e-05 1.53852018728906e-05 -1.16282305700549e-05 0.000123244372001729 0.000286074823299381 713 813 0 1486 1728 713 813 0 1472 1728 0 0 0 0 0 0 0 0 156 0 0 0 0 48 0 +224 227 0.988334094338847 -0.150151454040133 -0.0255001728826357 0.413081855849201 0.149661108035051 0.988531640589541 -0.0201680017619811 0.0399359457605582 0.0282359825246343 0.0161163396273513 0.999471356712079 -0.0526876096002182 6.43112764652867e-05 -8.12363086089424e-06 1.38952202090895e-05 -4.172941230471e-06 -2.63348344373106e-06 -2.76469613967858e-05 -8.12363086089424e-06 3.42987977224628e-05 -9.70044179651856e-07 -1.20081178805222e-06 -5.99370390692104e-07 2.06043003456643e-05 1.38952202090895e-05 -9.70044179651856e-07 2.37193075624475e-05 -1.27267702145763e-05 1.10952936790244e-06 -4.4038797523123e-06 -4.172941230471e-06 -1.20081178805222e-06 -1.27267702145763e-05 9.43012680827751e-05 3.40924021422049e-06 1.35510696926632e-05 -2.63348344373106e-06 -5.99370390692104e-07 1.10952936790244e-06 3.40924021422049e-06 1.27259203037737e-05 7.33695050008444e-06 -2.76469613967858e-05 2.06043003456643e-05 -4.4038797523123e-06 1.35510696926632e-05 7.33695050008444e-06 0.000339498187507097 3221 3133 0 261 712 3221 3133 0 135 752 0 0 0 0 0 0 0 0 3441 0 0 0 0 0 2900 +224 226 0.994988680417607 -0.0942310234140624 -0.0334371061422299 0.279566143350807 0.0933251540897891 0.995250458125058 -0.0276937035439217 0.0222785847192133 0.0358879012334999 0.0244343984620029 0.999057064795027 -0.0240111098080014 5.31183904709774e-05 -3.65227591066232e-06 3.02813472256683e-06 -6.79249611929908e-06 3.76968846278896e-07 3.53876018242257e-06 -3.65227591066232e-06 3.39846878931442e-05 -4.53209203618807e-06 9.49678460838316e-06 -2.16137612508716e-06 3.82118644825898e-05 3.02813472256683e-06 -4.53209203618807e-06 1.42676532281596e-05 5.77667926850273e-06 5.20572574113783e-06 4.53079999821105e-06 -6.79249611929908e-06 9.49678460838316e-06 5.77667926850273e-06 8.28648219564408e-05 -3.36885909216794e-07 5.44220558446526e-05 3.76968846278896e-07 -2.16137612508716e-06 5.20572574113783e-06 -3.36885909216794e-07 1.16377650894994e-05 1.71070332072923e-06 3.53876018242257e-06 3.82118644825898e-05 4.53079999821105e-06 5.44220558446526e-05 1.71070332072923e-06 0.00042676709725173 3349 3233 0 137 452 3349 3233 0 41 493 0 0 0 0 0 0 0 0 3567 0 0 0 0 0 3248 +225 228 0.989515330538775 -0.141223267230933 0.0302555684355698 0.41834417307138 0.141810158140269 0.98972637640356 -0.0182093080404219 0.0408204975568087 -0.0273731561382835 0.0223089364089723 0.999376316349017 -0.00684511066171473 4.9362256800666e-05 8.75857397495307e-06 2.03571427339745e-06 1.52908566260846e-05 -9.43860482264591e-07 -6.23593867632318e-06 8.75857397495307e-06 3.18382673322646e-05 -5.77558305714348e-06 1.28785686174664e-05 -1.02165626954408e-06 -1.51700839315142e-05 2.03571427339745e-06 -5.77558305714348e-06 1.26674710607615e-05 8.84597011697326e-07 3.49494495247182e-06 4.44122644395663e-06 1.52908566260846e-05 1.28785686174664e-05 8.84597011697326e-07 4.64035898770303e-05 2.35287478454767e-06 3.02419011081314e-06 -9.43860482264591e-07 -1.02165626954408e-06 3.49494495247182e-06 2.35287478454767e-06 9.91777719322627e-06 8.44000243538082e-08 -6.23593867632318e-06 -1.51700839315142e-05 4.44122644395663e-06 3.02419011081314e-06 8.44000243538082e-08 9.98075904592702e-05 3094 2988 0 327 636 3094 2988 0 196 640 0 0 0 0 0 0 0 0 3258 0 0 0 0 0 2949 +226 253 0.320481986945878 -0.945955161951533 0.049599673592395 3.11691909950258 0.937997055414337 0.309611951558641 -0.155890870438529 0.0191075818598934 0.132109121854831 0.0964845636840411 0.986528209882234 -0.122872822410979 9.82703495551079e-05 8.93691993896014e-05 -2.54058826926416e-06 -8.40716813385801e-06 -1.20865183704383e-06 -7.72373340415479e-05 8.93691993896014e-05 0.000455289611486073 -6.59947153613326e-05 -3.17348115498547e-05 -0.000101809035010242 -0.000357976462583891 -2.54058826926416e-06 -6.59947153613326e-05 2.81600475144995e-05 8.58964639409755e-06 2.19375714200366e-05 5.41625177104012e-05 -8.40716813385801e-06 -3.17348115498547e-05 8.58964639409755e-06 2.73948268636419e-05 -3.05979183372785e-05 3.60783067489113e-05 -1.20865183704383e-06 -0.000101809035010242 2.19375714200366e-05 -3.05979183372785e-05 0.000179794712329797 7.43316700813223e-05 -7.72373340415479e-05 -0.000357976462583891 5.41625177104012e-05 3.60783067489113e-05 7.43316700813223e-05 0.00035587361197836 763 849 0 1472 1583 763 849 0 1462 1583 0 0 0 0 0 0 0 0 125 0 0 0 0 0 8 +226 254 0.343444446945133 -0.939031771870478 0.0162862911782231 3.22388751170569 0.926738601391875 0.336033901600517 -0.168038036364881 0.0131389797071417 0.152320309062129 0.07280486517345 0.985645968415786 -0.168495320112907 8.90696634642536e-05 9.26328741514594e-06 9.89100677825368e-06 -6.82071568290818e-06 3.15312710748538e-05 -5.91064678457823e-06 9.26328741514594e-06 5.30477357284175e-05 -1.2222502016313e-05 -4.23659198901754e-06 -5.66762950330177e-06 -3.65621188454884e-05 9.89100677825368e-06 -1.2222502016313e-05 2.29681776695608e-05 3.47697919951324e-06 6.70214043560079e-06 1.14757565963504e-05 -6.82071568290818e-06 -4.23659198901754e-06 3.47697919951324e-06 2.34026710057909e-05 -2.83929605085315e-05 1.5827128966623e-05 3.15312710748538e-05 -5.66762950330177e-06 6.70214043560079e-06 -2.83929605085315e-05 0.000115435865898999 -4.20297843892404e-06 -5.91064678457823e-06 -3.65621188454884e-05 1.14757565963504e-05 1.5827128966623e-05 -4.20297843892404e-06 9.83614153191952e-05 841 923 0 1546 1538 841 923 0 1535 1538 0 0 0 0 0 0 0 0 118 0 0 0 0 0 10 +226 229 0.993471845648833 -0.110456519989465 0.0285140157627589 0.416951340360676 0.11039309926042 0.993880763116496 0.00379372411367798 0.0211481795129337 -0.0287585733092036 -0.000621207524686706 0.999586193663373 -0.0352177790270736 4.85675846631858e-05 7.82343424052973e-06 9.02274881550327e-06 -6.8219395349035e-06 2.97415046176554e-06 -1.70722108114247e-05 7.82343424052973e-06 3.58085064201772e-05 2.20450511917797e-06 1.20266313017673e-06 6.78543312292273e-07 -1.382440728815e-05 9.02274881550327e-06 2.20450511917797e-06 2.20926592240355e-05 -1.83870791164639e-06 4.41207100700699e-06 5.41297911160323e-06 -6.8219395349035e-06 1.20266313017673e-06 -1.83870791164639e-06 9.43741382381331e-05 -8.04951909294738e-06 -7.30753764132892e-06 2.97415046176554e-06 6.78543312292273e-07 4.41207100700699e-06 -8.04951909294738e-06 1.43713479909883e-05 -1.41314212776238e-06 -1.70722108114247e-05 -1.382440728815e-05 5.41297911160323e-06 -7.30753764132892e-06 -1.41314212776238e-06 0.000108280793405196 2770 2654 0 488 675 2770 2654 0 337 675 0 0 0 0 0 0 0 0 2458 0 0 0 0 0 2763 +226 230 0.988303943935215 -0.152418538600886 0.00488911984606996 0.550966159438452 0.152478349556205 0.988176010172428 -0.0160787386419919 0.0345846223128517 -0.00238061309638626 0.0166361657382954 0.999858775363208 -0.0435913541268599 6.49839685568897e-05 6.11005083721568e-06 4.60284062122453e-06 1.36402055317266e-05 1.89052979492621e-06 -3.35983407222145e-05 6.11005083721568e-06 4.70759872271253e-05 -8.35566247389477e-06 9.22224851911699e-06 -1.99975031925385e-06 1.16672295476062e-05 4.60284062122453e-06 -8.35566247389477e-06 2.03457419712846e-05 5.39047518208123e-06 3.55929660381871e-06 1.10395627666342e-05 1.36402055317266e-05 9.22224851911699e-06 5.39047518208123e-06 9.91805707405571e-05 -1.02660830516849e-05 -9.17558910556415e-06 1.89052979492621e-06 -1.99975031925385e-06 3.55929660381871e-06 -1.02660830516849e-05 1.69850259118349e-05 1.099500419308e-06 -3.35983407222145e-05 1.16672295476062e-05 1.10395627666342e-05 -9.17558910556415e-06 1.099500419308e-06 0.000254305408723567 2914 2782 0 629 957 2914 2782 0 533 957 0 0 0 0 0 0 0 0 1703 0 0 0 0 0 2325 +225 229 0.986692175651942 -0.162546378169617 0.00415035554836524 0.554534639924772 0.16259803033783 0.98646571753366 -0.021148727173493 0.0557647355348299 -0.000656534459089278 0.021542123264449 0.999767725968269 -0.0568569025155612 4.95377774010325e-05 9.17096720664636e-07 1.479408779697e-06 -1.51251825135724e-05 4.71697098913901e-06 -9.93705502280556e-06 9.17096720664636e-07 3.34169557890316e-05 -2.29215642509211e-06 1.74233094233229e-05 -4.68714722279865e-06 1.42994262340313e-05 1.479408779697e-06 -2.29215642509211e-06 1.53455637320624e-05 6.2729479087452e-06 3.19094470038432e-06 5.15345852067184e-06 -1.51251825135724e-05 1.74233094233229e-05 6.2729479087452e-06 0.000130320926249024 -1.99880169964982e-05 3.27971931630962e-05 4.71697098913901e-06 -4.68714722279865e-06 3.19094470038432e-06 -1.99880169964982e-05 1.67846390489044e-05 -6.01426322974151e-06 -9.93705502280556e-06 1.42994262340313e-05 5.15345852067184e-06 3.27971931630962e-05 -6.01426322974151e-06 0.00017096947766398 2918 2802 0 603 775 2918 2802 0 457 777 0 0 0 0 0 0 0 0 2327 0 0 0 0 0 2674 +227 229 0.998230447584806 -0.0549056818593916 0.0228328625930699 0.286787570616482 0.0548375988152105 0.998488804974617 0.00359779050839523 -0.00040552108238584 -0.0229958968257547 -0.00233932467083014 0.999732822452711 0.0214579279040971 5.28579522701268e-05 1.75610254477042e-05 2.67432913463546e-06 3.77946963556182e-06 -2.21683210844721e-06 -1.56233325670426e-05 1.75610254477042e-05 4.9787609968349e-05 -2.46135093272236e-06 -3.08433825480265e-06 -1.24191407646947e-07 -2.65277188243511e-05 2.67432913463546e-06 -2.46135093272236e-06 1.49285255697598e-05 3.77349601808225e-06 3.9833889790654e-06 3.92714629400756e-06 3.77946963556182e-06 -3.08433825480265e-06 3.77349601808225e-06 4.25750841132987e-05 1.33600199014454e-06 9.79951984050192e-06 -2.21683210844721e-06 -1.24191407646947e-07 3.9833889790654e-06 1.33600199014454e-06 1.205422078429e-05 -1.50768671444725e-06 -1.56233325670426e-05 -2.65277188243511e-05 3.92714629400756e-06 9.79951984050192e-06 -1.50768671444725e-06 0.000123461021933877 3110 2994 0 367 404 3110 2994 0 238 420 0 0 0 0 0 0 0 0 2573 0 0 0 0 0 3087 +226 228 0.995199438262794 -0.0897573250342236 0.0390089820954219 0.276190771339103 0.0895470631591065 0.995957229015896 0.00710784429751299 0.0148697267855055 -0.0394892588053916 -0.00358058286867312 0.99921357970422 -0.000195261267722017 6.01366508370742e-05 1.15509769145339e-05 -1.51095115759171e-07 6.27268110577673e-06 3.05816132629204e-06 -2.29922642437752e-05 1.15509769145339e-05 5.25459479109113e-05 -1.17638622865633e-06 7.29891109148453e-06 -2.63230749822909e-07 -3.91833413729118e-05 -1.51095115759171e-07 -1.17638622865633e-06 1.51522201817191e-05 1.11765275637101e-06 3.38931563690565e-06 3.8313900736045e-06 6.27268110577673e-06 7.29891109148453e-06 1.11765275637101e-06 6.13172282126341e-05 -8.34076422450064e-08 -1.49204157970053e-05 3.05816132629204e-06 -2.63230749822909e-07 3.38931563690565e-06 -8.34076422450064e-08 1.21316194914618e-05 -1.7645076979588e-06 -2.29922642437752e-05 -3.91833413729118e-05 3.8313900736045e-06 -1.49204157970053e-05 -1.7645076979588e-06 0.00014090119812093 3056 2950 0 206 480 3056 2950 0 84 480 0 0 0 0 0 0 0 0 3385 0 0 0 0 0 3114 +228 230 0.997396557687387 -0.0644834489444503 -0.0322798935187006 0.302520584788621 0.0640051254141472 0.997827016796464 -0.0156393245310899 -0.00998437207054726 0.0332182274371987 0.0135325298188452 0.999356502957094 0.0290086707823991 4.87688632335669e-05 4.97589329482756e-06 -4.81271578986075e-06 -9.53876719940994e-06 3.83747491037057e-06 -2.76977692159826e-05 4.97589329482756e-06 2.28285381406055e-05 -6.52472704143377e-06 -6.33215797522175e-07 -7.81089891727982e-07 -7.56186499914839e-06 -4.81271578986075e-06 -6.52472704143377e-06 1.54661018892203e-05 5.48212826610969e-06 3.81096174953825e-06 3.88976162657331e-06 -9.53876719940994e-06 -6.33215797522175e-07 5.48212826610969e-06 9.25049580423715e-05 -1.51154161537894e-05 1.93231934208128e-05 3.83747491037057e-06 -7.81089891727982e-07 3.81096174953825e-06 -1.51154161537894e-05 1.76088458405436e-05 -1.79124952253954e-06 -2.76977692159826e-05 -7.56186499914839e-06 3.88976162657331e-06 1.93231934208128e-05 -1.79124952253954e-06 6.42857095382334e-05 3421 3289 0 418 421 3421 3289 0 249 429 0 0 0 0 0 0 0 0 1863 0 0 0 0 0 3066 +227 230 0.995178267198745 -0.0977583643946205 0.00796986111496314 0.444026356001681 0.0978649714579099 0.995096799788608 -0.0143110590807881 0.0026424985921645 -0.00653175756176686 0.0150220252083369 0.999865828449895 0.0182160841133204 7.71082372924481e-05 -9.04808669158036e-06 6.31579467493131e-06 -5.07308238293507e-05 1.12228734355353e-05 -5.67846581472405e-05 -9.04808669158036e-06 4.32265188193278e-05 -4.38658869484255e-06 1.30182649084667e-05 -8.69175267602363e-07 4.79667909456898e-05 6.31579467493131e-06 -4.38658869484255e-06 1.86581973044362e-05 -3.99117017465192e-06 3.44536087392404e-06 -2.24652454965328e-06 -5.07308238293507e-05 1.30182649084667e-05 -3.99117017465192e-06 0.000128468027374684 -1.67224672244315e-05 4.64032367465499e-05 1.12228734355353e-05 -8.69175267602363e-07 3.44536087392404e-06 -1.67224672244315e-05 1.83783489475541e-05 -1.2708883259715e-06 -5.67846581472405e-05 4.79667909456898e-05 -2.24652454965328e-06 4.64032367465499e-05 -1.2708883259715e-06 0.000276560792800916 3371 3239 0 606 675 3371 3239 0 486 692 0 0 0 0 0 0 0 0 1721 0 0 0 0 0 2684 +229 256 0.4645683693574 -0.885430056129303 -0.0137784576591704 3.03230348674378 0.880050930016232 0.463363565212816 -0.1039450191728 -0.363161872633277 0.098420479424621 0.0361638235827892 0.994487600271467 -0.0712164452742672 9.96157459846766e-05 5.21808066947381e-05 -1.46760513242109e-06 -4.67444017035164e-06 9.83771639792066e-06 -5.54613579210694e-05 5.21808066947381e-05 7.11140970373819e-05 -8.26437409721539e-06 -7.92091831495257e-06 8.95064160973539e-07 -6.904632246836e-05 -1.46760513242109e-06 -8.26437409721539e-06 1.63482438866868e-05 4.23970811815938e-06 6.65896725122194e-06 9.29090863663231e-06 -4.67444017035164e-06 -7.92091831495257e-06 4.23970811815938e-06 1.88289817416981e-05 -8.48740644196611e-06 8.8950459539092e-06 9.83771639792066e-06 8.95064160973539e-07 6.65896725122194e-06 -8.48740644196611e-06 5.24758287094286e-05 -3.35006708919792e-06 -5.54613579210694e-05 -6.904632246836e-05 9.29090863663231e-06 8.8950459539092e-06 -3.35006708919792e-06 9.78628406742545e-05 870 943 0 1484 1648 870 943 0 1476 1648 0 0 0 0 0 0 0 0 106 0 0 0 0 0 0 +228 255 0.438639523925878 -0.897729795684427 -0.0409460863877957 3.05650725323948 0.888325096058467 0.440034458945441 -0.131332397576945 -0.283786171681414 0.135918695413084 0.0212341442255386 0.990492412568726 -0.0494708219775615 7.14846477808861e-05 2.34414355493631e-05 -4.71722656606509e-07 6.60232179086794e-07 -3.49912065378876e-06 -2.09647322826554e-05 2.34414355493631e-05 6.37018016640121e-05 -1.01530706216853e-05 -3.46678017441697e-06 -1.75648829270976e-05 -5.73372357591061e-05 -4.71722656606509e-07 -1.01530706216853e-05 2.28401652251125e-05 3.10644334281994e-06 1.24134733209699e-05 1.53254856739097e-05 6.60232179086794e-07 -3.46678017441697e-06 3.10644334281994e-06 2.2430214054967e-05 -2.05765190474672e-05 1.24603824983466e-05 -3.49912065378876e-06 -1.75648829270976e-05 1.24134733209699e-05 -2.05765190474672e-05 9.42881601310948e-05 2.01519894634377e-05 -2.09647322826554e-05 -5.73372357591061e-05 1.53254856739097e-05 1.24603824983466e-05 2.01519894634377e-05 0.000167941062269043 913 985 0 1513 1628 913 985 0 1504 1628 0 0 0 0 0 0 0 0 118 0 0 0 0 0 0 +228 232 0.986892331942237 -0.154837671886928 -0.0454842886967594 0.514975697941114 0.15511254045837 0.987893500263196 0.0025557641285391 -0.0162975269840305 0.0445379046000683 -0.00957744759140455 0.998961784830365 0.0138901004462913 8.18764004406594e-05 7.88985160258518e-06 -3.13310985664739e-07 3.57966094934515e-06 -4.08147406959684e-06 -3.06529267666887e-05 7.88985160258518e-06 3.85824737151941e-05 -1.05091214227695e-06 -2.70921842836766e-06 -2.86037742911385e-06 -1.01618724654769e-05 -3.13310985664739e-07 -1.05091214227695e-06 1.59013939580565e-05 -3.986995666625e-07 3.68567470802689e-06 3.05415020370784e-06 3.57966094934515e-06 -2.70921842836766e-06 -3.986995666625e-07 6.45443844963067e-05 -2.99439827703708e-06 9.30446924957452e-06 -4.08147406959684e-06 -2.86037742911385e-06 3.68567470802689e-06 -2.99439827703708e-06 1.76094994961749e-05 -1.04372608517584e-06 -3.06529267666887e-05 -1.01618724654769e-05 3.05415020370784e-06 9.30446924957452e-06 -1.04372608517584e-06 9.12724274178147e-05 3172 3018 0 130 682 3172 3018 0 130 692 0 0 0 0 0 0 0 0 1563 0 0 0 0 0 2301 +230 257 0.495031840651634 -0.866934587750089 -0.058033587719865 2.95612332682093 0.864990988850214 0.49802674445435 -0.0613184394463005 -0.509855127767461 0.0820613547839876 -0.0198439504833438 0.99642970232738 -0.127984012570603 0.000163572273159826 0.000151068498037027 -1.24748279603862e-05 -2.74145500815855e-06 -3.57800162310333e-05 -0.000205784235886943 0.000151068498037027 0.000512494063568894 -3.63052472089924e-05 0.000122219374818142 -0.000287040722517247 0.000311580132829882 -1.24748279603862e-05 -3.63052472089924e-05 2.55964128896248e-05 -1.13485827254016e-05 2.05361593021789e-05 -8.03505875026471e-05 -2.74145500815855e-06 0.000122219374818142 -1.13485827254016e-05 0.000201769186132287 -0.000120407772717721 0.0013071239888675 -3.57800162310333e-05 -0.000287040722517247 2.05361593021789e-05 -0.000120407772717721 0.00030598017368277 -0.000339004740474627 -0.000205784235886943 0.000311580132829882 -8.03505875026471e-05 0.0013071239888675 -0.000339004740474627 0.0105911821205293 852 922 0 1445 1381 852 922 0 1439 1381 0 0 0 0 0 0 0 0 110 0 0 0 0 0 0 +229 232 0.989940988924456 -0.134021303228431 -0.0453335276393039 0.36944402475626 0.133525075284218 0.990949121045656 -0.0138164311305921 -0.0184000516240221 0.046774915474155 0.00762428880588776 0.998876357465022 -0.0350729458223137 7.40664068858945e-05 2.58238599965051e-06 7.97965623749206e-06 5.09086463490477e-06 -4.91554500403644e-06 -3.06654282334198e-05 2.58238599965051e-06 3.87602526945263e-05 -8.33903447423799e-06 7.17556856895909e-06 -3.08181928176667e-06 7.05814054511665e-06 7.97965623749206e-06 -8.33903447423799e-06 2.52728939624493e-05 -1.13366099661535e-05 4.18890566954825e-06 -1.37711970175074e-07 5.09086463490477e-06 7.17556856895909e-06 -1.13366099661535e-05 0.000171959437656092 -3.37805206169484e-05 4.36373445101574e-05 -4.91554500403644e-06 -3.08181928176667e-06 4.18890566954825e-06 -3.37805206169484e-05 2.71598206520467e-05 -7.43020239652432e-06 -3.06654282334198e-05 7.05814054511665e-06 -1.37711970175074e-07 4.36373445101574e-05 -7.43020239652432e-06 0.000205429571974322 3205 3029 0 127 500 3205 3029 0 104 503 0 0 0 0 0 0 0 0 1564 0 0 0 0 0 2608 +231 234 0.984108138766018 -0.175166126215431 0.0291204299618631 0.388977278211609 0.175702093673881 0.984296990274932 -0.0169767256656301 -0.0624959523560721 -0.0256894042963033 0.0218234544101275 0.999431734209251 -0.00154562313806833 5.42165262709792e-05 1.01929121867658e-06 -3.55410826539844e-07 -9.05712894143015e-06 1.45648680759887e-06 -4.03603648325095e-05 1.01929121867658e-06 3.16001103902509e-05 -6.5710418470408e-06 2.39809380736826e-07 -3.08212500704078e-06 4.03794673521945e-06 -3.55410826539844e-07 -6.5710418470408e-06 1.63378281197476e-05 3.44258682016542e-06 4.19221777656742e-06 8.71067185640025e-06 -9.05712894143015e-06 2.39809380736826e-07 3.44258682016542e-06 3.70134260951609e-05 -4.24070615965499e-06 1.45796289185863e-05 1.45648680759887e-06 -3.08212500704078e-06 4.19221777656742e-06 -4.24070615965499e-06 1.76707072709247e-05 -1.61976314652325e-06 -4.03603648325095e-05 4.03794673521945e-06 8.71067185640025e-06 1.45796289185863e-05 -1.61976314652325e-06 0.000136994667660785 3014 2957 0 0 336 3014 2957 0 0 331 0 0 0 0 0 0 0 0 1588 0 0 0 0 0 2387 +231 235 0.96201398028899 -0.271937541606491 0.0240639812490007 0.489469211536564 0.272288884672746 0.962131499784872 -0.0127177201331422 -0.0793262461497784 -0.01969428882205 0.0187869791805618 0.99962952357414 -0.0275535370153217 3.52253784919017e-05 9.70540204335412e-06 -3.9228135593823e-06 -6.6427108152689e-06 2.93377583619222e-06 -1.29614329233454e-05 9.70540204335412e-06 3.11811770303959e-05 -6.45204461869906e-06 8.96569460618299e-06 -6.79914331384305e-06 -7.15586373886715e-06 -3.9228135593823e-06 -6.45204461869906e-06 1.38394424110125e-05 1.92317972050942e-06 5.16884781268972e-06 2.72237535940176e-06 -6.6427108152689e-06 8.96569460618299e-06 1.92317972050942e-06 4.61419361882927e-05 -1.29829288668714e-05 2.87029341099989e-05 2.93377583619222e-06 -6.79914331384305e-06 5.16884781268972e-06 -1.29829288668714e-05 2.40000144204596e-05 -1.18429810877539e-05 -1.29614329233454e-05 -7.15586373886715e-06 2.72237535940176e-06 2.87029341099989e-05 -1.18429810877539e-05 0.000133428506712762 2708 2676 0 0 302 2708 2676 0 0 294 0 0 0 0 0 0 0 0 1601 0 0 0 0 0 1950 +230 258 0.488441323405075 -0.87246529642172 0.0151453005931946 3.11238631243834 0.869640374080451 0.485285626191997 -0.0906834096219097 -0.549409261369111 0.0717683311740773 0.0574644894800367 0.995764600239076 -0.145897689869595 0.000101240858720563 2.07617073430782e-05 -3.03099491963473e-06 -6.88245034642846e-06 4.58132335120055e-05 -1.43207130148468e-05 2.07617073430782e-05 0.000113250392630949 -1.41626650237814e-05 2.919979699868e-06 -6.09251024697539e-05 -0.000111654421167142 -3.03099491963473e-06 -1.41626650237814e-05 2.36145155455431e-05 2.35860539980976e-06 1.29986037457578e-05 1.36907916380653e-05 -6.88245034642846e-06 2.919979699868e-06 2.35860539980976e-06 2.6687876106555e-05 -3.71109936412931e-05 5.09940163521651e-06 4.58132335120055e-05 -6.09251024697539e-05 1.29986037457578e-05 -3.71109936412931e-05 0.000169651930712929 5.54473923997618e-05 -1.43207130148468e-05 -0.000111654421167142 1.36907916380653e-05 5.09940163521651e-06 5.54473923997618e-05 0.000183775512420489 841 920 0 1513 1749 841 920 0 1507 1749 0 0 0 0 0 0 0 0 90 0 0 0 0 0 0 +233 237 0.87331880790126 -0.483787916860133 -0.0571271499906502 0.450616908001697 0.480856437715628 0.87487778764726 -0.0580167474861513 -0.101794389781135 0.0780470760077388 0.0231971589115637 0.996679760878625 -0.0238545509322479 4.16924845935781e-05 1.71447235927964e-06 -7.19790181009336e-07 -4.21657108647062e-06 7.42343318310044e-07 -4.18952034836659e-05 1.71447235927964e-06 3.43560063505905e-05 -5.83491713022936e-06 -6.9939561070001e-07 1.08573207524899e-06 9.13497886176485e-06 -7.19790181009336e-07 -5.83491713022936e-06 1.56086672279467e-05 3.81587167506174e-06 4.64421395361067e-06 2.03823174137794e-06 -4.21657108647062e-06 -6.9939561070001e-07 3.81587167506174e-06 2.39312980953123e-05 -2.54297985312894e-06 1.06905814220415e-05 7.42343318310044e-07 1.08573207524899e-06 4.64421395361067e-06 -2.54297985312894e-06 2.52828730500565e-05 -1.53741069182477e-06 -4.18952034836659e-05 9.13497886176485e-06 2.03823174137794e-06 1.06905814220415e-05 -1.53741069182477e-06 0.000114451967382079 2108 2077 0 0 705 2108 2077 0 0 682 0 0 0 0 0 0 0 0 1342 0 0 0 0 0 2132 +231 233 0.99393562220822 -0.105556430957389 0.0308191302456235 0.246461036990429 0.105560954807286 0.994411725731902 0.00148477172455549 -0.046013839660218 -0.0308036316971372 0.00177752930717488 0.999523874984399 0.0196708495051288 5.00504310855402e-05 6.7898864766279e-06 -3.03677345436484e-06 -1.31273454242909e-05 6.43630972400664e-06 -4.16667669130061e-05 6.7898864766279e-06 6.57817579530604e-05 -8.13411041914671e-06 4.00970720945274e-05 -1.46712324018605e-05 3.71351158167521e-05 -3.03677345436484e-06 -8.13411041914671e-06 1.67319872228543e-05 3.21186279483711e-06 2.50999560585275e-06 -2.87307296357928e-06 -1.31273454242909e-05 4.00970720945274e-05 3.21186279483711e-06 7.38304678039123e-05 -1.40842268880903e-05 7.52657033665898e-05 6.43630972400664e-06 -1.46712324018605e-05 2.50999560585275e-06 -1.40842268880903e-05 2.30027830627081e-05 -2.80053851206273e-05 -4.16667669130061e-05 3.71351158167521e-05 -2.87307296357928e-06 7.52657033665898e-05 -2.80053851206273e-05 0.00023493859332768 2876 2733 0 15 148 2876 2733 0 13 138 0 0 0 0 0 0 0 0 1592 0 0 0 0 0 2911 +232 259 0.546311963103075 -0.836513158750999 0.0422962670562273 2.90559735038721 0.835093329210778 0.540104219643617 -0.10443449349147 -0.819584799281184 0.0645164357208688 0.0923751436241734 0.993631955183753 -0.172225026813142 0.000112800820016257 5.72696312778395e-05 -1.06609850811025e-05 2.99410165574364e-06 -1.07719868971035e-06 -1.83141826659009e-05 5.72696312778395e-05 0.000123410483932015 -1.63978196162223e-05 -1.96509095816311e-06 -2.4664507280506e-05 -9.78854566079241e-05 -1.06609850811025e-05 -1.63978196162223e-05 2.30942978681013e-05 2.40193684538516e-06 1.45973940945081e-05 5.16988919511327e-06 2.99410165574364e-06 -1.96509095816311e-06 2.40193684538516e-06 2.42762980858615e-05 -2.13646912726702e-05 2.19546678471827e-05 -1.07719868971035e-06 -2.4664507280506e-05 1.45973940945081e-05 -2.13646912726702e-05 8.69123280483341e-05 -1.85943493028303e-06 -1.83141826659009e-05 -9.78854566079241e-05 5.16988919511327e-06 2.19546678471827e-05 -1.85943493028303e-06 0.000200517345206193 805 887 0 1523 1729 805 887 0 1518 1684 0 0 0 0 0 0 0 0 91 0 0 0 0 0 243 +232 234 0.990687212943583 -0.134737066024282 0.019615533366311 0.254994633591151 0.135341713694074 0.990225342157865 -0.0337104180141878 -0.0494825172458045 -0.0148817554215806 0.0360512799704587 0.999239129822318 -0.000132575167968357 2.55989969004995e-05 4.5833582618592e-06 -3.25194781182542e-06 -9.06455406035148e-06 -4.01380679094397e-07 -5.55241137686953e-06 4.5833582618592e-06 2.65752663368195e-05 -6.92232275434874e-06 7.15888802424035e-06 -4.07289325196331e-06 1.99036737922585e-05 -3.25194781182542e-06 -6.92232275434874e-06 1.31077659968313e-05 2.90566778588923e-06 2.9808921699878e-06 2.89669851291702e-06 -9.06455406035148e-06 7.15888802424035e-06 2.90566778588923e-06 4.10345464448044e-05 -3.64728885396023e-06 3.52746339545142e-05 -4.01380679094397e-07 -4.07289325196331e-06 2.9808921699878e-06 -3.64728885396023e-06 1.53724073147318e-05 -6.06712167400024e-06 -5.55241137686953e-06 1.99036737922585e-05 2.89669851291702e-06 3.52746339545142e-05 -6.06712167400024e-06 0.00014648069029973 2815 2800 0 0 182 2815 2800 0 0 136 0 0 0 0 0 0 0 0 1606 0 0 0 0 0 2724 +234 238 0.82901275099584 -0.557282604416601 -0.0466257171629478 0.407201948660127 0.553590518976224 0.829606240752858 -0.0727394157492798 -0.104631785761053 0.0792173969904597 0.0344903481942657 0.996260518085252 -0.017999340823395 4.09543238178657e-05 1.76529154539042e-05 2.86653129682211e-06 -6.54115207018351e-06 3.25750736283749e-06 -3.14128090530055e-05 1.76529154539042e-05 3.70967131371549e-05 -4.06414915928068e-06 6.51095080907671e-06 -1.11141429294989e-05 -4.18755197783303e-06 2.86653129682211e-06 -4.06414915928068e-06 1.61949602083978e-05 2.94478887634245e-06 6.37122641191546e-06 -1.20439814800241e-06 -6.54115207018351e-06 6.51095080907671e-06 2.94478887634245e-06 2.47349194362796e-05 -1.29795981216854e-05 1.38841784219654e-05 3.25750736283749e-06 -1.11141429294989e-05 6.37122641191546e-06 -1.29795981216854e-05 4.15355755258854e-05 -1.85943991886731e-07 -3.14128090530055e-05 -4.18755197783303e-06 -1.20439814800241e-06 1.38841784219654e-05 -1.85943991886731e-07 0.00010178496124449 1628 1620 0 0 1043 1628 1620 0 0 1004 0 0 0 0 0 0 0 0 1391 0 0 0 0 0 1784 +233 235 0.985565721549236 -0.169236193061186 0.00439539136940264 0.235775299136854 0.169292808133441 0.985290956340965 -0.0232739439502727 -0.0599808997822134 -0.000391945694187987 0.0236821095104186 0.999719462683262 0.00357380029091789 2.3890637302894e-05 3.41421023532826e-06 -2.62638575995344e-06 -3.68807461628063e-06 2.5545852747566e-07 -1.05965804602134e-05 3.41421023532826e-06 1.74793768530304e-05 -4.46268386531272e-06 1.05256558003516e-07 -3.68020425197213e-06 -7.16761104017949e-06 -2.62638575995344e-06 -4.46268386531272e-06 1.22397436453911e-05 3.10758610568872e-06 4.11914106829837e-06 4.17439640359742e-06 -3.68807461628063e-06 1.05256558003516e-07 3.10758610568872e-06 3.50414508963716e-05 -7.25686519193162e-06 9.29020161971295e-06 2.5545852747566e-07 -3.68020425197213e-06 4.11914106829837e-06 -7.25686519193162e-06 2.18256378692613e-05 -3.26988602788629e-06 -1.05965804602134e-05 -7.16761104017949e-06 4.17439640359742e-06 9.29020161971295e-06 -3.26988602788629e-06 3.94895899317383e-05 2974 2923 0 0 392 2974 2923 0 0 347 0 0 0 0 0 0 0 0 1657 0 0 0 0 0 2743 +234 237 0.906032163157019 -0.418620036281345 -0.0621529126334277 0.320161927261652 0.417584319591583 0.908161191840544 -0.0294378271276573 -0.0949270309115285 0.0687681274737587 0.000717536458448725 0.997632412156494 -0.0198364330126019 3.39067429823643e-05 2.00335999196174e-05 3.84555978080665e-06 -2.13297402268942e-06 1.03577503802716e-06 -9.27144708708833e-06 2.00335999196174e-05 4.39316500975672e-05 7.45285638822788e-07 1.03027456646163e-06 -8.29302374088556e-07 8.88123404445717e-06 3.84555978080665e-06 7.45285638822788e-07 1.65550163679e-05 2.04843944713979e-06 2.02032457977889e-06 -5.05926783054413e-07 -2.13297402268942e-06 1.03027456646163e-06 2.04843944713979e-06 2.58788597250716e-05 -5.88462685340317e-06 1.59359442841263e-05 1.03577503802716e-06 -8.29302374088556e-07 2.02032457977889e-06 -5.88462685340317e-06 2.93666581918573e-05 -5.45585159503168e-06 -9.27144708708833e-06 8.88123404445717e-06 -5.05926783054413e-07 1.59359442841263e-05 -5.45585159503168e-06 0.000131232130957372 2154 2136 0 0 444 2154 2136 0 0 438 0 0 0 0 0 0 0 0 1592 0 0 0 0 0 2197 +235 239 0.847004583670977 -0.531352663059533 -0.0157347608783238 0.377556466194713 0.53038419089795 0.84670894367121 -0.0421494335989187 -0.122512114650143 0.035718976551441 0.0273552950399971 0.998987408603028 -0.0485786284293825 4.98964367710064e-05 2.12030273371157e-05 -6.26084238803923e-06 -1.30141638483608e-06 -9.59976802053384e-06 -1.78171266590983e-05 2.12030273371157e-05 5.52099311755197e-05 -1.61547775155386e-05 1.17045792742104e-05 -1.92607434236426e-05 3.57117818603e-05 -6.26084238803923e-06 -1.61547775155386e-05 1.9991489005607e-05 -2.22464216252529e-07 1.22813077797168e-05 -9.07880901853434e-06 -1.30141638483608e-06 1.17045792742104e-05 -2.22464216252529e-07 4.28031074446778e-05 -3.0304476871959e-05 9.32823895426792e-05 -9.59976802053384e-06 -1.92607434236426e-05 1.22813077797168e-05 -3.0304476871959e-05 7.12209022922803e-05 -7.1473684781433e-05 -1.78171266590983e-05 3.57117818603e-05 -9.07880901853434e-06 9.32823895426792e-05 -7.1473684781433e-05 0.000461051645337852 1298 1318 0 0 808 1298 1318 0 0 793 0 0 0 0 0 0 0 0 1507 0 0 0 0 0 1406 +235 238 0.878894979796853 -0.474950756852916 -0.0443327537237576 0.289604312970405 0.471834232816367 0.879246856573517 -0.0655547248349009 -0.0928306458642661 0.0701147005304825 0.0366980077174724 0.996863674229876 -0.0199901850689765 2.26133840550034e-05 1.09961421735922e-05 7.92514717835275e-07 -4.37857124005714e-06 1.51287517128493e-06 -7.91125426364529e-06 1.09961421735922e-05 2.16939102088817e-05 -5.24840212420231e-06 2.38888811442366e-06 -8.90998102497524e-06 -6.26363094878006e-06 7.92514717835275e-07 -5.24840212420231e-06 1.53506268826828e-05 3.14206797803893e-06 8.35216377197215e-06 2.15779130914891e-06 -4.37857124005714e-06 2.38888811442366e-06 3.14206797803893e-06 2.53328078329106e-05 -1.45693684748055e-05 7.3158383037433e-06 1.51287517128493e-06 -8.90998102497524e-06 8.35216377197215e-06 -1.45693684748055e-05 4.3150139133693e-05 7.09573685144443e-06 -7.91125426364529e-06 -6.26363094878006e-06 2.15779130914891e-06 7.3158383037433e-06 7.09573685144443e-06 8.31869377233668e-05 1628 1620 0 0 900 1628 1620 0 0 853 0 0 0 0 0 0 0 0 1664 0 0 0 0 0 2113 +235 237 0.942212356735634 -0.32936977072498 -0.0612489097638192 0.193801536183367 0.32906334363443 0.944183656503137 -0.0153146553501847 -0.0688444903275159 0.0628744040990559 -0.00572511353075433 0.998005026231957 -0.0403262852871605 3.87815744111507e-05 7.88589774804028e-06 -2.36801866178893e-06 3.02334718664544e-06 -1.34332596693325e-05 -3.07456066779843e-05 7.88589774804028e-06 4.46922849163596e-05 -5.98229688515592e-06 -4.87721101214513e-06 5.04820625552337e-06 1.84839679629639e-05 -2.36801866178893e-06 -5.98229688515592e-06 1.87368720755173e-05 5.24637298284226e-07 1.00589564239387e-05 4.19587934040825e-06 3.02334718664544e-06 -4.87721101214513e-06 5.24637298284226e-07 3.81709297836406e-05 -2.11021193030939e-05 1.36678728607421e-05 -1.34332596693325e-05 5.04820625552337e-06 1.00589564239387e-05 -2.11021193030939e-05 4.82642913439223e-05 1.83944830253271e-05 -3.07456066779843e-05 1.84839679629639e-05 4.19587934040825e-06 1.36678728607421e-05 1.83944830253271e-05 0.00017945542876555 2158 2110 0 0 511 2158 2110 0 0 471 0 0 0 0 0 0 0 0 1756 0 0 0 0 0 2548 +236 238 0.936151384225889 -0.347470388115066 -0.0537114065643114 0.177699528219804 0.343484908216513 0.936443614918202 -0.0713545647203044 -0.0727477319007609 0.0750913020225707 0.0483496169798264 0.99600382072483 -0.0124389590943862 3.59686882881443e-05 2.90507161816715e-05 1.90198244484656e-06 3.19388930976349e-06 -1.25010153103521e-05 -9.13493823940835e-06 2.90507161816715e-05 3.89898365540143e-05 1.88545424442306e-07 7.47890125844109e-06 -1.52769793452134e-05 7.65377543082398e-06 1.90198244484656e-06 1.88545424442306e-07 1.58539127219746e-05 1.39445082067056e-06 1.73445207139233e-06 8.80924368034843e-07 3.19388930976349e-06 7.47890125844109e-06 1.39445082067056e-06 4.92561126034715e-05 -4.95642307282906e-05 2.8829041523124e-05 -1.25010153103521e-05 -1.52769793452134e-05 1.73445207139233e-06 -4.95642307282906e-05 9.54972732480074e-05 -2.30366706416543e-05 -9.13493823940835e-06 7.65377543082398e-06 8.80924368034843e-07 2.8829041523124e-05 -2.30366706416543e-05 0.00011568013999724 1628 1620 0 0 551 1628 1620 0 0 551 0 0 0 0 0 0 0 0 1910 0 0 0 0 0 1799 +236 240 0.896523030779246 -0.442960250401076 -0.00571592923431947 0.36753777244676 0.441938546663982 0.895197718186843 -0.0575444725894487 -0.171491456653983 0.0306068007953003 0.0490638555118365 0.998326580747698 -0.0127960617977981 2.44958649471954e-05 9.15100242532291e-06 -4.8125465579219e-06 -5.6401636292893e-06 5.42034273345587e-06 6.12687979812827e-06 9.15100242532291e-06 2.53133763385172e-05 -4.15021540889152e-06 1.71838062544788e-06 -7.52373539992071e-06 1.88081953201689e-05 -4.8125465579219e-06 -4.15021540889152e-06 1.17429259422469e-05 4.02539813022581e-06 -1.95128210268504e-07 2.3119054366759e-06 -5.6401636292893e-06 1.71838062544788e-06 4.02539813022581e-06 2.2875185852742e-05 -1.25085970670003e-05 3.42570156640588e-05 5.42034273345587e-06 -7.52373539992071e-06 -1.95128210268504e-07 -1.25085970670003e-05 4.64152310029822e-05 -2.09600777509601e-05 6.12687979812827e-06 1.88081953201689e-05 2.3119054366759e-06 3.42570156640588e-05 -2.09600777509601e-05 0.000225037940383939 1095 1135 0 0 768 1095 1135 0 0 729 0 0 0 0 0 0 0 0 1638 0 0 0 0 0 1911 +236 263 0.834158247339434 -0.55150152588766 0.00510738085382615 2.35683590688473 0.549990912800253 0.831111813250865 -0.0822383712873968 -1.80925272497394 0.041109782689129 0.071408828714959 0.996599601118127 -0.124925575728123 7.08631075168574e-05 3.52193105480503e-05 -1.85309646970699e-06 1.56652112744663e-06 -6.97592499302253e-06 -1.13574404361087e-05 3.52193105480503e-05 5.44930520637448e-05 -7.94634158805554e-07 5.9996926315559e-06 -2.75513113762748e-05 -5.73556814728205e-07 -1.85309646970699e-06 -7.94634158805554e-07 1.83493338615455e-05 2.51712455117211e-06 8.89599798552572e-06 -3.18418058708216e-06 1.56652112744663e-06 5.9996926315559e-06 2.51712455117211e-06 3.14043980467754e-05 -3.5438812110542e-05 4.53057159106573e-05 -6.97592499302253e-06 -2.75513113762748e-05 8.89599798552572e-06 -3.5438812110542e-05 0.00014898309890163 -1.19290226769746e-05 -1.13574404361087e-05 -5.73556814728205e-07 -3.18418058708216e-06 4.53057159106573e-05 -1.19290226769746e-05 0.000457568468840717 793 873 0 1475 824 793 873 0 1475 784 0 0 0 0 0 0 0 0 147 0 0 0 0 0 1412 +237 241 0.94298870236137 -0.33213017284467 0.0214908237391807 0.318328411417128 0.332810836472069 0.940391291280793 -0.0700083310042773 -0.254410425584535 0.00304209559024144 0.0731694442333193 0.997314884118856 -0.0177522216086954 3.18406978739162e-05 1.49495128365188e-05 -5.46746760899794e-07 -4.58412523950908e-06 3.43651765797721e-06 -3.89135223343916e-06 1.49495128365188e-05 3.5099322668771e-05 -1.4355617938697e-06 -5.97949907045586e-07 -4.16045103098415e-06 5.00682510445368e-06 -5.46746760899794e-07 -1.4355617938697e-06 1.32444290081014e-05 3.50386607388094e-06 1.14830456487308e-06 5.46136931041122e-06 -4.58412523950908e-06 -5.97949907045586e-07 3.50386607388094e-06 2.00840426261772e-05 -4.66303786956242e-06 2.04691478684876e-05 3.43651765797721e-06 -4.16045103098415e-06 1.14830456487308e-06 -4.66303786956242e-06 4.21457395262618e-05 -8.40493479136465e-06 -3.89135223343916e-06 5.00682510445368e-06 5.46136931041122e-06 2.04691478684876e-05 -8.40493479136465e-06 0.00017146246405539 813 882 0 0 759 813 882 0 0 722 0 0 0 0 0 0 0 0 1632 0 0 0 0 0 1602 +236 239 0.913228733644993 -0.40731625424373 -0.0103319443484255 0.279000109479365 0.406102871793488 0.911981021896236 -0.058060944034516 -0.125555186322669 0.033071703407046 0.0488270901237678 0.998259574311112 -0.00766451330680214 2.35561496431058e-05 1.00513745832745e-05 -1.92459606704831e-06 -5.67650808911176e-06 4.6417191820978e-06 -1.07318830679329e-05 1.00513745832745e-05 3.60800380070396e-05 -1.67938574300773e-06 4.60195799129662e-06 -8.50820991977709e-06 1.51762189998899e-05 -1.92459606704831e-06 -1.67938574300773e-06 1.12046222006397e-05 4.38032893799572e-06 -2.83627934710561e-06 2.60109020963563e-06 -5.67650808911176e-06 4.60195799129662e-06 4.38032893799572e-06 1.98699609680319e-05 -1.11020613286188e-05 1.99669107651748e-05 4.6417191820978e-06 -8.50820991977709e-06 -2.83627934710561e-06 -1.11020613286188e-05 3.89099823553463e-05 -1.2680687233368e-05 -1.07318830679329e-05 1.51762189998899e-05 2.60109020963563e-06 1.99669107651748e-05 -1.2680687233368e-05 0.000120859969161955 1298 1318 0 0 693 1298 1318 0 0 647 0 0 0 0 0 0 0 0 1800 0 0 0 0 0 2105 +237 264 0.9354253430903 -0.353332720659998 0.011636838720162 1.94495345973156 0.352740267948971 0.930654005697408 -0.0972492932964432 -2.27403509781906 0.0235314868141209 0.0950742351553435 0.995192021138606 -0.209614856661493 7.00886474313323e-05 4.73214886364559e-05 -8.919525614116e-06 1.52982964156757e-05 -1.44568653595688e-06 8.26847726933828e-05 4.73214886364559e-05 5.96940482511298e-05 -8.87770209696609e-06 3.8584717675054e-06 -1.23277983585036e-05 1.8855785820785e-05 -8.919525614116e-06 -8.87770209696609e-06 1.75034880614797e-05 -6.50258205279929e-06 1.03817824274555e-05 -1.51110508487491e-05 1.52982964156757e-05 3.8584717675054e-06 -6.50258205279929e-06 6.23088237046622e-05 -1.94253689257908e-05 0.000238527623087041 -1.44568653595688e-06 -1.23277983585036e-05 1.03817824274555e-05 -1.94253689257908e-05 9.20630465780448e-05 2.01720250902407e-05 8.26847726933828e-05 1.8855785820785e-05 -1.51110508487491e-05 0.000238527623087041 2.01720250902407e-05 0.00156970324977103 816 838 0 1492 592 816 838 0 1492 474 0 0 0 0 0 0 0 0 210 0 0 0 0 0 1889 +238 264 0.979131844534325 -0.202914178478899 0.0112546519735039 1.49592759673517 0.203225412231593 0.977765818952852 -0.0517052715954393 -2.49651641071797 -0.00051268129508544 0.0529135092362291 0.99859896740293 -0.109212096883165 5.3742075657294e-05 3.82061000876281e-05 -2.37126721432237e-06 -4.93018581732021e-06 5.61656932516902e-06 -2.13866046608989e-05 3.82061000876281e-05 5.92699622693471e-05 -2.10129997247082e-06 -6.24693274564777e-06 5.76455783149023e-06 -1.15170547285325e-05 -2.37126721432237e-06 -2.10129997247082e-06 1.42366379970409e-05 1.96260100582319e-06 6.98050174516793e-06 1.2884841137751e-05 -4.93018581732021e-06 -6.24693274564777e-06 1.96260100582319e-06 2.5227383359859e-05 -1.11892449994357e-05 2.4703747610341e-05 5.61656932516902e-06 5.76455783149023e-06 6.98050174516793e-06 -1.11892449994357e-05 7.24104635995165e-05 3.46416317105199e-05 -2.13866046608989e-05 -1.15170547285325e-05 1.2884841137751e-05 2.4703747610341e-05 3.46416317105199e-05 0.000247306945760486 0 0 0 1335 0 0 0 0 1302 0 0 0 0 0 0 0 0 0 220 0 186 188 0 311 2112 +237 239 0.975340458956289 -0.217635190276101 0.0366866880001495 0.156932301047288 0.219158042134038 0.974677841066989 -0.0444168740566944 -0.109454198352191 -0.0260910270190856 0.0513617570423551 0.998339235041181 -0.00755746804269117 2.49289208575042e-05 1.63530269313159e-05 -1.77997243777189e-06 -5.553737070508e-06 1.16503010288848e-06 -1.12324230366726e-05 1.63530269313159e-05 2.87066131699849e-05 -4.62820954842154e-06 -3.85249850244748e-07 -6.73924991588071e-06 1.74361216936229e-06 -1.77997243777189e-06 -4.62820954842154e-06 1.83773139266948e-05 2.01963760786628e-07 1.07140911583832e-05 1.34674210859655e-05 -5.553737070508e-06 -3.85249850244748e-07 2.01963760786628e-07 3.72384005611982e-05 -3.59496004524255e-05 3.44924200370236e-06 1.16503010288848e-06 -6.73924991588071e-06 1.07140911583832e-05 -3.59496004524255e-05 9.66433651834543e-05 2.71755135685758e-05 -1.12324230366726e-05 1.74361216936229e-06 1.34674210859655e-05 3.44924200370236e-06 2.71755135685758e-05 0.000164580609622948 1298 1318 0 0 434 1298 1318 0 0 403 0 0 0 0 0 0 0 0 2020 0 0 0 0 0 1834 +238 265 0.980664587774139 -0.195668680912178 -0.00327621670017787 1.55424449704072 0.195254145526548 0.979437226505637 -0.050779306706986 -2.6086527048522 0.0131447685592446 0.04915777298691 0.998704525079611 -0.120722193028417 4.24059198546164e-05 2.94982574780089e-05 2.85810277561953e-07 -1.70178567882444e-06 3.5143832252334e-06 -1.62587213128278e-05 2.94982574780089e-05 4.35456571801193e-05 -2.84131075379279e-06 -2.07206609502234e-06 -8.85470466755908e-06 -2.34814040855853e-05 2.85810277561953e-07 -2.84131075379279e-06 1.54770073134681e-05 -1.50436502629075e-06 9.00841806865332e-06 -9.46697822013526e-07 -1.70178567882444e-06 -2.07206609502234e-06 -1.50436502629075e-06 3.32324887246605e-05 -1.56673216747374e-05 6.40229227730875e-05 3.5143832252334e-06 -8.85470466755908e-06 9.00841806865332e-06 -1.56673216747374e-05 8.45542597092265e-05 1.22210617945469e-05 -1.62587213128278e-05 -2.34814040855853e-05 -9.46697822013526e-07 6.40229227730875e-05 1.22210617945469e-05 0.000375687664955466 0 0 0 1154 0 0 0 0 1116 0 0 0 0 0 0 0 0 0 232 0 34 40 0 515 2317 +237 263 0.926455629363524 -0.372560534855555 0.0536527230322938 1.87049118207125 0.375653575004599 0.924163659657773 -0.0693247557097433 -2.19284632609188 -0.0237562288021769 0.0843811473973555 0.996150321767254 -0.202807356443496 5.43547244133162e-05 4.37564189191658e-05 -8.00999330168285e-07 -4.12448664318324e-06 2.83813885707233e-06 -3.86395978009355e-05 4.37564189191658e-05 5.9204631005308e-05 -2.86439423357134e-06 -1.182523786904e-08 -2.1583964430378e-06 7.34254895394383e-06 -8.00999330168285e-07 -2.86439423357134e-06 1.47723706342479e-05 5.03117629390772e-07 7.64577500249089e-06 4.98516485884265e-06 -4.12448664318324e-06 -1.182523786904e-08 5.03117629390772e-07 2.2102083334866e-05 -1.20586692423928e-05 3.37780392314661e-05 2.83813885707233e-06 -2.1583964430378e-06 7.64577500249089e-06 -1.20586692423928e-05 7.86722566030944e-05 3.08910863689748e-05 -3.86395978009355e-05 7.34254895394383e-06 4.98516485884265e-06 3.37780392314661e-05 3.08910863689748e-05 0.00045949136069918 793 873 0 1454 603 793 873 0 1454 493 0 0 0 0 0 0 0 0 216 0 0 0 0 0 1675 +237 240 0.965817478792812 -0.255630394263528 0.0430081293126013 0.246657210449451 0.257364109414857 0.965435679372692 -0.0412027205325724 -0.185483973061497 -0.0309889148469884 0.0508630565623105 0.998224742547361 0.00304906291652881 4.52904528010315e-05 3.13435562033478e-05 1.59135801124986e-06 -2.91943173842239e-06 1.10589732205686e-06 1.29551864150861e-06 3.13435562033478e-05 4.50129368395808e-05 3.92834272648691e-07 1.46888577297963e-06 -1.167811308071e-05 3.47039349024908e-06 1.59135801124986e-06 3.92834272648691e-07 1.33692098855546e-05 1.39809929303441e-06 2.54538605889182e-06 -1.63839573570318e-06 -2.91943173842239e-06 1.46888577297963e-06 1.39809929303441e-06 2.37792695407446e-05 -1.43734874661724e-05 2.49005794596212e-05 1.10589732205686e-06 -1.167811308071e-05 2.54538605889182e-06 -1.43734874661724e-05 5.35763098365423e-05 -1.27244287713708e-05 1.29551864150861e-06 3.47039349024908e-06 -1.63839573570318e-06 2.49005794596212e-05 -1.27244287713708e-05 0.000228903288308113 1095 1135 0 0 564 1095 1135 0 0 516 0 0 0 0 0 0 0 0 1900 0 0 0 0 0 1935 +239 243 0.976545882513218 -0.213592376809457 -0.0271373527700747 0.204625352989284 0.213287775646922 0.976893408465019 -0.0136964687852538 -0.341349661901694 0.0294357623660148 0.00758716458793531 0.999537878635646 -0.00786023263195767 3.34648878837601e-05 2.80883637480362e-05 1.35942713956433e-06 -1.04538740212528e-06 -6.09490649668831e-06 1.35962258900318e-05 2.80883637480362e-05 4.56762894072984e-05 -7.60381410654947e-07 6.37446032365912e-07 -1.34338753507824e-05 8.13550929932673e-06 1.35942713956433e-06 -7.60381410654947e-07 1.49231451562239e-05 -6.83183203392753e-07 1.25873393554204e-05 4.46662817638648e-06 -1.04538740212528e-06 6.37446032365912e-07 -6.83183203392753e-07 2.58418173792145e-05 -2.43305352449819e-05 2.41080711036504e-05 -6.09490649668831e-06 -1.34338753507824e-05 1.25873393554204e-05 -2.43305352449819e-05 0.000110421507753355 -2.04931871250454e-06 1.35962258900318e-05 8.13550929932673e-06 4.46662817638648e-06 2.41080711036504e-05 -2.04931871250454e-06 0.000198208796507768 568 667 0 0 251 568 667 0 0 285 0 0 0 0 0 0 0 0 1740 0 0 0 0 0 2300 +238 241 0.982881292492569 -0.182611856936647 0.0244392015885741 0.194247857148252 0.183177208958413 0.982803282987763 -0.0233198856489694 -0.220294506813303 -0.0197604399329418 0.027397384083605 0.99942929132532 0.0149279677389445 5.08024210942345e-05 2.71852410801652e-05 2.47555230639679e-06 -1.13817701089261e-05 1.16506208950192e-05 -2.70322137173162e-05 2.71852410801652e-05 5.81739614577458e-05 -1.44138643837599e-06 1.0540877488457e-05 -4.30531829513403e-05 5.0988181018293e-06 2.47555230639679e-06 -1.44138643837599e-06 1.78921323979913e-05 -1.3308882421297e-05 2.72404120555469e-05 1.08137471839769e-05 -1.13817701089261e-05 1.0540877488457e-05 -1.3308882421297e-05 6.07236737195808e-05 -0.000109854137579433 -5.4912504292258e-06 1.16506208950192e-05 -4.30531829513403e-05 2.72404120555469e-05 -0.000109854137579433 0.000296921006974311 6.76954034914306e-05 -2.70322137173162e-05 5.0988181018293e-06 1.08137471839769e-05 -5.4912504292258e-06 6.76954034914306e-05 0.000217105274431069 813 882 0 0 367 813 882 0 0 361 0 0 0 0 0 0 0 0 1923 0 0 0 0 0 1821 +237 265 0.937969251472815 -0.346506158385829 -0.0121311785174372 2.02183727512271 0.343469019413964 0.933388711718566 -0.103993007164745 -2.37427846745114 0.0473573224996643 0.0933755590990027 0.994504041705518 -0.213568617284051 7.98560240134234e-05 7.06450463511417e-05 -8.39782666115418e-06 -1.90564698347015e-06 -1.8243954851106e-05 -3.12622085839876e-05 7.06450463511417e-05 8.84649539538138e-05 -1.02504968463117e-05 -1.8810775591284e-06 -2.21287253166215e-05 -1.43096384047579e-05 -8.39782666115418e-06 -1.02504968463117e-05 1.45999141762676e-05 3.53459828756336e-07 7.3021279724565e-06 1.14935391849979e-05 -1.90564698347015e-06 -1.8810775591284e-06 3.53459828756336e-07 2.40806317515562e-05 -4.11753089529665e-06 3.631107480294e-05 -1.8243954851106e-05 -2.21287253166215e-05 7.3021279724565e-06 -4.11753089529665e-06 7.26772764874925e-05 5.19170205995908e-05 -3.12622085839876e-05 -1.43096384047579e-05 1.14935391849979e-05 3.631107480294e-05 5.19170205995908e-05 0.000339759949564029 726 732 0 1539 640 726 732 0 1539 531 0 0 0 0 0 0 0 0 206 0 0 0 0 0 1863 +239 242 0.983305787696305 -0.177569005750678 -0.0397363319855368 0.145581498069307 0.176614064921775 0.983926008524996 -0.0264023070938269 -0.220642484210565 0.0437858419441283 0.0189435462568484 0.998861322757298 -0.0127698106537954 2.23071980812129e-05 1.25735738965333e-05 -4.07849943680395e-06 5.0219304596569e-06 -1.45136186351173e-05 8.71117722272785e-06 1.25735738965333e-05 3.26607574535459e-05 -6.13676093599713e-07 -9.24318149735776e-06 2.09656022499466e-05 1.72378272821e-05 -4.07849943680395e-06 -6.13676093599713e-07 1.73759525693716e-05 -9.04366179839217e-06 2.90154909312009e-05 -3.0047535192836e-07 5.0219304596569e-06 -9.24318149735776e-06 -9.04366179839217e-06 6.61500594558482e-05 -0.000102852035100543 3.71837014698624e-05 -1.45136186351173e-05 2.09656022499466e-05 2.90154909312009e-05 -0.000102852035100543 0.000250315091285961 -2.66706353049538e-05 8.71117722272785e-06 1.72378272821e-05 -3.0047535192836e-07 3.71837014698624e-05 -2.66706353049538e-05 0.000233057539204148 689 774 0 0 265 689 774 0 0 289 0 0 0 0 0 0 0 0 1978 0 0 0 0 0 2467 +239 265 0.989390240689459 -0.13507964861549 -0.0534830829175898 1.32152076884327 0.13274676707595 0.990127128447191 -0.0450173893490514 -2.62031588595345 0.0590359844445528 0.0374400593327041 0.997553504578991 -0.0493696707379822 4.05906249845281e-05 1.04359568199723e-05 1.58566183970343e-06 -3.15572342076569e-08 2.94345191645925e-07 -1.3219027740104e-05 1.04359568199723e-05 5.80474783654624e-05 -8.25319849998719e-08 -3.83607766016692e-06 -5.13113339290904e-06 -1.34934292305617e-05 1.58566183970343e-06 -8.25319849998719e-08 1.29188901670198e-05 -1.86258089959214e-07 3.89496216117323e-06 2.64454679026677e-06 -3.15572342076569e-08 -3.83607766016692e-06 -1.86258089959214e-07 2.88268748785773e-05 -3.63951378113092e-06 4.24159896378661e-05 2.94345191645925e-07 -5.13113339290904e-06 3.89496216117323e-06 -3.63951378113092e-06 6.53978826552521e-05 2.90170445965307e-05 -1.3219027740104e-05 -1.34934292305617e-05 2.64454679026677e-06 4.24159896378661e-05 2.90170445965307e-05 0.000311419530600222 0 0 0 518 0 0 0 0 557 0 0 0 0 0 0 0 0 0 236 0 726 732 0 957 2214 +240 244 0.979923587248161 -0.198418564362474 -0.0194893938087017 0.165863060994589 0.198267980504623 0.980102812533097 -0.00939599762303951 -0.356921483727572 0.0209659500455904 0.00534323694483347 0.999765911980218 -0.000493694178424915 2.68467294671915e-05 1.7933933706073e-05 -1.78278775205868e-06 2.37017502709096e-06 -8.77798423242597e-06 2.04082724959458e-05 1.7933933706073e-05 3.78552483689076e-05 6.95609417619448e-09 2.63515986237678e-06 -1.26616747601785e-05 6.1615643366542e-06 -1.78278775205868e-06 6.95609417619448e-09 1.27536717341212e-05 2.17757272276811e-06 9.7785933039552e-06 -1.32080888849866e-06 2.37017502709096e-06 2.63515986237678e-06 2.17757272276811e-06 2.63857795380791e-05 -2.0873258229997e-05 3.53702984545602e-05 -8.77798423242597e-06 -1.26616747601785e-05 9.7785933039552e-06 -2.0873258229997e-05 0.000106783243559017 -3.02802398756165e-05 2.04082724959458e-05 6.1615643366542e-06 -1.32080888849866e-06 3.53702984545602e-05 -3.02802398756165e-05 0.000238999649381301 527 630 0 0 84 527 630 0 0 146 0 0 0 0 0 0 0 0 1688 0 0 0 0 0 2395 +239 266 0.99340906628081 -0.110425480859674 -0.0307349997234366 1.35908797351293 0.10970864333978 0.993671296127333 -0.0241115911787568 -2.7197851422636 0.0332030210618665 0.0205807781567266 0.999236704171153 -0.115172252536898 6.04330263408166e-05 3.3755786694257e-05 -2.89578948168767e-06 1.46925741469006e-05 -1.1579161703602e-05 5.03799893016984e-05 3.3755786694257e-05 9.0431585900615e-05 -2.0840596858195e-06 1.4206692490921e-05 -2.45149375446129e-05 5.20502833535997e-05 -2.89578948168767e-06 -2.0840596858195e-06 1.26575004437844e-05 7.6441239544428e-07 2.94619526656557e-06 4.55588877223542e-07 1.46925741469006e-05 1.4206692490921e-05 7.6441239544428e-07 3.97593421113593e-05 -1.53246445137457e-05 0.000111128856271928 -1.1579161703602e-05 -2.45149375446129e-05 2.94619526656557e-06 -1.53246445137457e-05 7.12364021957904e-05 1.47669778116139e-05 5.03799893016984e-05 5.20502833535997e-05 4.55588877223542e-07 0.000111128856271928 1.47669778116139e-05 0.000761846429942023 0 0 0 431 0 0 0 0 471 0 0 0 0 0 0 0 0 0 216 0 664 712 0 1060 2271 +240 267 0.9969911864509 -0.077446435466794 -0.00325941294003085 1.23939589502499 0.077430726128317 0.996986666634429 -0.00469778718240744 -2.77734231972541 0.00361341811412553 0.0044312737059836 0.999983653377832 -0.0968668969710792 3.87708875711431e-05 1.33996296393392e-05 1.48060403850102e-06 -6.76095885233682e-07 6.00524336314651e-06 -3.10573461356978e-06 1.33996296393392e-05 6.24176344018996e-05 3.60613278460157e-06 2.47554755534458e-06 -2.81196244481283e-06 3.6550266071559e-05 1.48060403850102e-06 3.60613278460157e-06 1.25649997154994e-05 -9.50669151710678e-08 1.50235332568522e-06 1.93867992872661e-06 -6.76095885233682e-07 2.47554755534458e-06 -9.50669151710678e-08 2.34020935978143e-05 -1.25355895508829e-05 2.93083589338152e-05 6.00524336314651e-06 -2.81196244481283e-06 1.50235332568522e-06 -1.25355895508829e-05 5.45822917680262e-05 -6.96995142778346e-06 -3.10573461356978e-06 3.6550266071559e-05 1.93867992872661e-06 2.93083589338152e-05 -6.96995142778346e-06 0.000297646752692454 0 0 0 275 0 0 0 0 309 0 0 0 0 0 0 0 0 0 229 0 547 606 0 1204 2277 +241 267 0.999492264428271 0.00315465430200286 0.031705859147528 0.958188344721634 -0.00363077629202465 0.99988134362891 0.0149705085539013 -2.78037413458928 -0.0316548702661265 -0.0150780243758927 0.99938512214729 -0.0913358695440056 4.14279009858526e-05 1.32456333594723e-05 -2.03478879410012e-06 6.85913545233434e-06 -1.63971046104505e-06 4.31126390953488e-05 1.32456333594723e-05 9.75443265003422e-05 1.0967045562665e-06 5.70016132392391e-06 -1.37859957368403e-05 5.95398906255559e-05 -2.03478879410012e-06 1.0967045562665e-06 1.08657165181819e-05 5.00315275812146e-08 1.45391147936599e-07 -5.54165509393117e-06 6.85913545233434e-06 5.70016132392391e-06 5.00315275812146e-08 3.23029783947058e-05 -1.56886619700639e-05 9.39852353233048e-05 -1.63971046104505e-06 -1.37859957368403e-05 1.45391147936599e-07 -1.56886619700639e-05 5.31311617766564e-05 -2.04590801020517e-05 4.31126390953488e-05 5.95398906255559e-05 -5.54165509393117e-06 9.39852353233048e-05 -2.04590801020517e-05 0.000825087275421836 0 0 0 161 0 0 0 0 190 0 0 0 0 0 0 0 0 0 234 0 547 606 0 1296 2325 +240 266 0.99628078502317 -0.0731115683459752 -0.0455992978850356 1.1968699858052 0.0719830095571503 0.997068974168184 -0.0259211706197876 -2.67577184141439 0.0473607826023982 0.0225423895183436 0.998623451029512 -0.0840440821665535 4.37116324221769e-05 2.00919575352367e-05 2.50035219309323e-06 -7.3963859267819e-07 6.0338817597246e-06 -9.64329159064272e-06 2.00919575352367e-05 0.000103166044830591 -6.15322956035702e-07 7.95037533249133e-06 -3.49369926375752e-05 -1.81054103238054e-07 2.50035219309323e-06 -6.15322956035702e-07 1.4395486695649e-05 1.21438126316098e-06 5.90296792004997e-06 1.26695911888372e-06 -7.3963859267819e-07 7.95037533249133e-06 1.21438126316098e-06 2.70858563469157e-05 -1.59272018954865e-05 3.48710225101714e-05 6.0338817597246e-06 -3.49369926375752e-05 5.90296792004997e-06 -1.59272018954865e-05 8.87148689972345e-05 7.12225637883419e-06 -9.64329159064272e-06 -1.81054103238054e-07 1.26695911888372e-06 3.48710225101714e-05 7.12225637883419e-06 0.000252154410754137 0 0 0 330 0 0 0 0 369 0 0 0 0 0 0 0 0 0 213 0 664 712 0 1133 2325 +242 268 0.997802157619162 0.0376510420458661 0.054527546097416 0.809298626790998 -0.0393076771955878 0.99878761985384 0.02963438779843 -2.85186368088887 -0.0533456724021065 -0.0317126072652612 0.998072417100286 -0.0189633867256437 5.13280870029958e-05 1.77321094121289e-05 -1.38365915145525e-06 2.82717243575627e-06 -1.79526438370718e-05 -4.81563695881389e-05 1.77321094121289e-05 9.21520870214864e-05 4.07529065715496e-06 -1.69264548629296e-05 1.20165216283207e-05 9.95749785211823e-06 -1.38365915145525e-06 4.07529065715496e-06 1.40042339023556e-05 -2.63270365541073e-06 9.33841383148823e-06 4.54602009177972e-06 2.82717243575627e-06 -1.69264548629296e-05 -2.63270365541073e-06 3.37511672544446e-05 -2.59570539746676e-05 2.23627637103821e-05 -1.79526438370718e-05 1.20165216283207e-05 9.33841383148823e-06 -2.59570539746676e-05 8.92718613873526e-05 9.23983765425833e-06 -4.81563695881389e-05 9.95749785211823e-06 4.54602009177972e-06 2.23627637103821e-05 9.23983765425833e-06 0.000308442612050672 0 0 0 118 0 0 0 0 139 0 0 0 0 0 0 0 0 0 277 0 370 437 0 1338 2474 +241 245 0.986567495644741 -0.161403421352741 0.0251696665232714 0.113619784940466 0.16148200578504 0.986875034580248 -0.00110811997265395 -0.392062117362558 -0.0246604611656711 0.00515768338141356 0.999682579600762 0.0011598053645477 2.73756221262989e-05 1.68025014564367e-05 -7.43907885875389e-07 3.9528394180788e-07 -2.11723850174282e-06 4.26331469511966e-06 1.68025014564367e-05 4.11222038960909e-05 -6.82019266221357e-07 -2.2777734599609e-06 3.61691990894472e-06 1.20117212956687e-05 -7.43907885875389e-07 -6.82019266221357e-07 1.1902241419504e-05 3.10953593000537e-06 8.38466040570606e-06 -6.21107215714557e-08 3.9528394180788e-07 -2.2777734599609e-06 3.10953593000537e-06 1.6677592012312e-05 -1.15724599024297e-05 9.56337925639058e-06 -2.11723850174282e-06 3.61691990894472e-06 8.38466040570606e-06 -1.15724599024297e-05 8.12309355521701e-05 -4.63640775847464e-06 4.26331469511966e-06 1.20117212956687e-05 -6.21107215714557e-08 9.56337925639058e-06 -4.63640775847464e-06 0.000129888251659276 349 349 0 0 0 468 483 0 0 0 0 0 0 0 0 0 0 0 1731 0 0 68 0 0 2846 +243 247 0.991277693334969 -0.129595580497722 0.0239482820252527 0.0407751922559223 0.13018191290304 0.991179951552346 -0.0247986530600656 -0.424850084422994 -0.0205232611786711 0.0276999847679849 0.99940557662765 -0.024547417700643 2.94595643583711e-05 1.13860075298175e-05 -4.24865356429056e-06 1.65523276925996e-06 -7.35199118183899e-06 1.76367630562968e-05 1.13860075298175e-05 6.38598938676307e-05 -3.05029807099063e-06 -2.21174121291775e-06 9.86611065042043e-06 1.26993730291745e-05 -4.24865356429056e-06 -3.05029807099063e-06 1.22761141572345e-05 -1.7300953009476e-07 6.20934214641519e-06 -1.85798215311236e-06 1.65523276925996e-06 -2.21174121291775e-06 -1.7300953009476e-07 2.9774254319234e-05 -1.83679801800033e-05 3.03477119552029e-05 -7.35199118183899e-06 9.86611065042043e-06 6.20934214641519e-06 -1.83679801800033e-05 0.00010651583163062 -2.26923643456955e-05 1.76367630562968e-05 1.26993730291745e-05 -1.85798215311236e-06 3.03477119552029e-05 -2.26923643456955e-05 0.000229220327069115 3 3 0 0 0 72 72 0 0 0 0 0 0 0 0 0 0 0 1624 0 337 452 0 0 2432 +243 269 0.998147430123827 0.0534547717611859 0.0290567567557082 0.692399533543029 -0.0537569155286743 0.99850676154314 0.00971808548402487 -2.88788278865233 -0.0284938900475847 -0.0112620836700569 0.99953052164572 -0.0608211324519707 6.69690627127257e-05 2.60692163327122e-05 -2.93079234280459e-06 1.88575579870941e-05 -9.27464368304214e-06 0.000121324810250843 2.60692163327122e-05 7.85396868084274e-05 2.198924808734e-06 -1.30886583447446e-05 1.30236209622136e-05 -4.97998223938834e-05 -2.93079234280459e-06 2.198924808734e-06 1.10035674510385e-05 -1.67874922470938e-06 4.05406420352892e-06 -1.12283178868574e-05 1.88575579870941e-05 -1.30886583447446e-05 -1.67874922470938e-06 4.17305794466956e-05 -1.87886475878399e-05 0.000160016881547632 -9.27464368304214e-06 1.30236209622136e-05 4.05406420352892e-06 -1.87886475878399e-05 6.62430317154672e-05 -1.97567690626304e-05 0.000121324810250843 -4.97998223938834e-05 -1.12283178868574e-05 0.000160016881547632 -1.97567690626304e-05 0.0012823851855885 0 0 0 90 0 0 0 0 113 0 0 0 0 0 0 0 0 0 227 0 301 373 0 1361 2355 +244 248 0.996024145072956 -0.0850309151925362 -0.026563996182918 0.0411681180491325 0.0844313310649506 0.996165348845335 -0.0229335582597169 -0.445586014869948 0.0284121939717277 0.0205995442029873 0.999384013286355 -0.0272819021292659 3.11584766706255e-05 1.61924855793029e-05 -2.2121484607205e-06 3.33643066412678e-06 -4.02299173917356e-06 3.42488843358154e-06 1.61924855793029e-05 5.27775774872615e-05 2.61093926944209e-07 -1.15734404352342e-06 4.17363366664315e-06 -1.65394262689028e-05 -2.2121484607205e-06 2.61093926944209e-07 1.15794451524086e-05 6.52764166701391e-08 7.35697962159108e-06 -7.73957643585943e-06 3.33643066412678e-06 -1.15734404352342e-06 6.52764166701391e-08 2.75382357043926e-05 -2.15115069917796e-05 5.06179853723794e-05 -4.02299173917356e-06 4.17363366664315e-06 7.35697962159108e-06 -2.15115069917796e-05 9.35506861921266e-05 -4.97994070772581e-05 3.42488843358154e-06 -1.65394262689028e-05 -7.73957643585943e-06 5.06179853723794e-05 -4.97994070772581e-05 0.000284284959497531 0 0 0 0 0 36 36 0 0 0 0 0 0 0 0 0 0 0 1714 0 536 641 0 0 2554 +242 246 0.987594969627739 -0.152572615517691 0.0371183641891277 0.0777217907078982 0.15297006834964 0.988197645547798 -0.00809762452170246 -0.41366357995678 -0.0354448043455254 0.0136751719506053 0.999278067165005 0.00952217917835703 4.13187187170036e-05 3.2998201741529e-05 1.79246296218831e-06 3.08763525669589e-06 -8.80297408527592e-07 2.95612426915578e-05 3.2998201741529e-05 6.37509239072915e-05 8.9350601576316e-07 -3.9025279839248e-07 -1.02185235288282e-05 2.8885655952434e-05 1.79246296218831e-06 8.9350601576316e-07 1.28773299574399e-05 2.11922868452896e-06 7.41952535735038e-06 5.23659307132472e-06 3.08763525669589e-06 -3.9025279839248e-07 2.11922868452896e-06 2.15949473390053e-05 -1.62902845040056e-05 2.25012468617888e-05 -8.80297408527592e-07 -1.02185235288282e-05 7.41952535735038e-06 -1.62902845040056e-05 0.000115156733440112 -6.59159969041494e-06 2.95612426915578e-05 2.8885655952434e-05 5.23659307132472e-06 2.25012468617888e-05 -6.59159969041494e-06 0.000210636512488963 69 69 0 0 0 221 221 0 0 0 0 0 0 0 0 0 0 0 1737 0 146 262 0 0 2194 +245 249 0.999662336394491 -0.0256882632429781 -0.00391488516655183 0.028567403352809 0.0256906082762164 0.999669790614682 0.000549889803602913 -0.440888813960368 0.00389946672069781 -0.000650279907089449 0.999992185617136 -0.0341705521529769 2.79122997256089e-05 2.18295343612376e-05 -4.48914720461797e-07 1.70742042076497e-06 -6.96132538385372e-06 -8.71345396308123e-06 2.18295343612376e-05 3.48319047867723e-05 -6.26911744900866e-07 -1.68147431480463e-06 1.03258521368358e-06 -8.47983353095438e-06 -4.48914720461797e-07 -6.26911744900866e-07 1.13852892074767e-05 7.11389404704136e-07 3.25997796535264e-06 5.51728001660208e-07 1.70742042076497e-06 -1.68147431480463e-06 7.11389404704136e-07 2.38222212945308e-05 -1.73465488430791e-05 8.51108636673034e-06 -6.96132538385372e-06 1.03258521368358e-06 3.25997796535264e-06 -1.73465488430791e-05 9.28361222291313e-05 2.33020264531144e-05 -8.71345396308123e-06 -8.47983353095438e-06 5.51728001660208e-07 8.51108636673034e-06 2.33020264531144e-05 0.000154674465912748 0 0 0 0 0 9 9 0 0 0 0 0 0 0 0 0 0 0 1647 0 654 756 0 0 2903 +244 270 0.999174203151496 0.0395571756222997 0.009281250635486 0.621256757711895 -0.0395695465816537 0.999216153576929 0.0011530022761745 -2.92500106349452 -0.0092283660468422 -0.00151930500988539 0.999956263529757 -0.0239256752999852 3.53711312830426e-05 2.30854598104651e-05 3.13300737936123e-06 9.22813726536367e-07 -5.76469404687722e-06 3.56912066175801e-06 2.30854598104651e-05 4.46427453379347e-05 3.52746416957421e-06 -2.71797973744471e-06 9.86741728595532e-06 2.21055283788755e-05 3.13300737936123e-06 3.52746416957421e-06 1.21705406019913e-05 -1.38821563803607e-06 5.73907507401586e-06 1.29998733070732e-06 9.22813726536367e-07 -2.71797973744471e-06 -1.38821563803607e-06 2.46141166203338e-05 -1.24668591234553e-05 2.88994999667048e-05 -5.76469404687722e-06 9.86741728595532e-06 5.73907507401586e-06 -1.24668591234553e-05 7.06827468848043e-05 1.54029059487425e-05 3.56912066175801e-06 2.21055283788755e-05 1.29998733070732e-06 2.88994999667048e-05 1.54029059487425e-05 0.000302534036835687 0 0 0 84 0 0 0 0 105 0 0 0 0 0 0 0 0 0 268 0 379 453 0 1643 2601 +246 250 0.998799090151062 0.0408376278354939 0.0270677975864249 0.0314728316899687 -0.0410990887897629 0.999112954665736 0.00917435118982442 -0.424914137478133 -0.0266691284833449 -0.0102757954374708 0.999591499370651 -0.0230757197808178 6.77278765100108e-05 2.76621056459723e-05 -2.71075561209792e-06 1.08899716004057e-05 -2.41492654688093e-05 7.31937786499123e-05 2.76621056459723e-05 4.13817659638591e-05 1.78804545684364e-06 1.81979710875526e-06 3.08167322267593e-06 4.44441077289141e-05 -2.71075561209792e-06 1.78804545684364e-06 1.10561982148933e-05 9.61679015741236e-07 6.48005743803725e-06 2.48538079599251e-06 1.08899716004057e-05 1.81979710875526e-06 9.61679015741236e-07 3.0966427457032e-05 -1.81763783683897e-05 6.86851407260772e-05 -2.41492654688093e-05 3.08167322267593e-06 6.48005743803725e-06 -1.81763783683897e-05 0.000110070476634791 2.79519524038119e-06 7.31937786499123e-05 4.44441077289141e-05 2.48538079599251e-06 6.86851407260772e-05 2.79519524038119e-06 0.000696311070813884 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1704 0 703 803 0 0 2927 +247 251 0.995553938830493 0.0925590554381466 0.0174692912131398 0.0543049432489132 -0.0928384187120281 0.995553893887914 0.0159208157976541 -0.422976315719138 -0.0159180052186677 -0.0174718522489971 0.999720636722503 0.00769517415032405 2.09757128102906e-05 5.60949809440667e-06 -1.37194972428018e-06 -3.22341816324515e-06 1.65880152084102e-06 5.25579223639535e-06 5.60949809440667e-06 3.69545417667569e-05 4.13279518802692e-09 -2.86645928778875e-06 -2.67094041751408e-06 1.6252413373083e-05 -1.37194972428018e-06 4.13279518802692e-09 1.16101860503585e-05 -3.13775385789139e-07 2.56903344227578e-06 2.39520725860364e-06 -3.22341816324515e-06 -2.86645928778875e-06 -3.13775385789139e-07 2.67967897064666e-05 -1.81822281345695e-05 1.02419897147664e-05 1.65880152084102e-06 -2.67094041751408e-06 2.56903344227578e-06 -1.81822281345695e-05 9.28082400504026e-05 -3.71243003211637e-06 5.25579223639535e-06 1.6252413373083e-05 2.39520725860364e-06 1.02419897147664e-05 -3.71243003211637e-06 0.000159704096267732 0 0 0 90 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1708 0 747 841 0 0 3048 +249 253 0.995411485567725 0.0865015572232963 -0.040907884298746 0.101089854588346 -0.0870760286621869 0.996123583319729 -0.0124728499824762 -0.426295280564373 0.0396703873471989 0.015977714236027 0.999085067957436 0.021370622355573 2.43618977784924e-05 1.5717101551701e-05 -2.28016769747903e-06 1.79609902047411e-06 -1.49502924262774e-06 1.95788600690854e-06 1.5717101551701e-05 4.22818104003773e-05 -7.88052944759753e-07 -3.06759150189498e-06 8.70596608210259e-07 8.70709840595404e-06 -2.28016769747903e-06 -7.88052944759753e-07 1.07619824533625e-05 4.60520877926969e-07 3.456880581669e-06 1.23872448736737e-07 1.79609902047411e-06 -3.06759150189498e-06 4.60520877926969e-07 3.05422206044749e-05 -2.83836077619334e-05 1.68031938130688e-05 -1.49502924262774e-06 8.70596608210259e-07 3.456880581669e-06 -2.83836077619334e-05 8.82541243402634e-05 -5.31656365396846e-06 1.95788600690854e-06 8.70709840595404e-06 1.23872448736737e-07 1.68031938130688e-05 -5.31656365396846e-06 0.000110988697048515 0 0 0 157 0 8 8 0 0 0 0 0 0 0 0 0 0 0 1666 0 735 821 0 0 3298 +248 252 0.994946260512833 0.0997973539275918 0.0110646663112849 0.0840404449834806 -0.0998548133355438 0.994990599429839 0.00476689626202994 -0.44575969392831 -0.0105335153321586 -0.00584766579929273 0.999927422295962 0.02200465191195 2.69430224078276e-05 1.54329011721593e-05 -1.90594426387162e-06 -4.73443466137699e-07 -2.46099008806415e-06 -2.89690775684973e-06 1.54329011721593e-05 5.05811022955648e-05 8.41697798753733e-07 -3.37011738181459e-06 -2.09452559388407e-07 -5.88455071522928e-06 -1.90594426387162e-06 8.41697798753733e-07 1.0425983617599e-05 1.6146420845516e-06 2.48338911165833e-06 -4.57615217928306e-06 -4.73443466137699e-07 -3.37011738181459e-06 1.6146420845516e-06 2.76826336488785e-05 -1.82795969030302e-05 3.34401836274141e-05 -2.46099008806415e-06 -2.09452559388407e-07 2.48338911165833e-06 -1.82795969030302e-05 6.42000081609705e-05 -4.41998979455831e-05 -2.89690775684973e-06 -5.88455071522928e-06 -4.57615217928306e-06 3.34401836274141e-05 -4.41998979455831e-05 0.000191146389802876 0 0 0 138 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1521 0 774 863 0 0 3067 +250 254 0.992256214015685 0.0910743454018094 -0.0844575002998066 0.109677494876909 -0.0893581286035395 0.995712989976295 0.0238907188033297 -0.435109589442178 0.0862712617256362 -0.0161587500165817 0.996140634749014 0.0355327300418282 4.16001919025457e-05 2.16603487403478e-05 -1.75814695938164e-06 8.32231928056529e-07 -4.65486947117364e-06 -2.00819349883988e-06 2.16603487403478e-05 3.80265939491992e-05 -2.67362088059845e-06 -1.18710464594436e-06 -1.88515514248534e-06 -6.77080378212851e-06 -1.75814695938164e-06 -2.67362088059845e-06 1.16826464783358e-05 -2.63765770765904e-07 5.17523164171077e-06 3.95643195270598e-06 8.32231928056529e-07 -1.18710464594436e-06 -2.63765770765904e-07 3.07588221205113e-05 -2.70383446858743e-05 1.37004821675312e-05 -4.65486947117364e-06 -1.88515514248534e-06 5.17523164171077e-06 -2.70383446858743e-05 0.000123071675805673 4.14125843171799e-05 -2.00819349883988e-06 -6.77080378212851e-06 3.95643195270598e-06 1.37004821675312e-05 4.14125843171799e-05 0.000152477886945515 0 0 0 0 0 25 25 0 0 0 0 0 0 0 0 0 0 0 1780 0 796 878 0 0 2650 +253 257 0.997781721006288 0.0461417131281559 0.0479852012117235 0.112488324800045 -0.0482508363510441 0.997875963342041 0.0437654952630225 -0.440021019774549 -0.0458638639579722 -0.0459837372751699 0.997888772303333 0.000699621826080968 4.44484345027479e-05 2.36635273891706e-05 -1.64849442170806e-06 3.80141241474266e-06 -1.33888656085932e-05 1.87734141424822e-05 2.36635273891706e-05 3.42375248949676e-05 -3.83113284365679e-06 -2.69080352741084e-06 -7.56751758706162e-07 -4.08174101107342e-07 -1.64849442170806e-06 -3.83113284365679e-06 9.99337117423509e-06 -2.09925496891947e-07 4.30047873927956e-06 -1.7521498409192e-06 3.80141241474266e-06 -2.69080352741084e-06 -2.09925496891947e-07 3.09898455794342e-05 -2.53407295917136e-05 2.41553672662371e-05 -1.33888656085932e-05 -7.56751758706162e-07 4.30047873927956e-06 -2.53407295917136e-05 8.98767073562104e-05 -1.19773027915573e-05 1.87734141424822e-05 -4.08174101107342e-07 -1.7521498409192e-06 2.41553672662371e-05 -1.19773027915573e-05 0.000262610820557176 32 32 0 0 0 114 114 0 0 0 0 0 0 0 0 0 0 0 1777 0 676 746 0 0 2880 +254 258 0.997655658855743 0.00915404164569337 0.0678188017784262 0.122159787015647 -0.00966884942884623 0.999926852455991 0.00726657334485811 -0.458365024649488 -0.0677473224846182 -0.00790526780082837 0.99767119184487 0.0125852291679221 2.81066081991894e-05 -9.12227181606189e-07 -1.14378472208646e-07 -9.95539024384891e-07 -1.04912596704175e-06 -6.21308259828585e-06 -9.12227181606189e-07 6.77384607217694e-05 -1.64405291184511e-06 1.10165957433911e-05 2.67556248614967e-06 4.75883764930223e-05 -1.14378472208646e-07 -1.64405291184511e-06 1.03685767126229e-05 2.17018583780029e-06 1.90059552481075e-06 -3.68123271281052e-07 -9.95539024384891e-07 1.10165957433911e-05 2.17018583780029e-06 2.556886471236e-05 -8.29413190859483e-06 3.21687878895062e-05 -1.04912596704175e-06 2.67556248614967e-06 1.90059552481075e-06 -8.29413190859483e-06 5.8243540898753e-05 -4.28052785716515e-06 -6.21308259828585e-06 4.75883764930223e-05 -3.68123271281052e-07 3.21687878895062e-05 -4.28052785716515e-06 0.000224416467712803 67 67 0 0 0 199 199 0 0 0 0 0 0 0 0 0 0 0 1841 0 588 667 0 0 2909 +251 255 0.995611773283767 0.0791789625741363 -0.0498787408064399 0.111027075636652 -0.0782413571033065 0.996724046206233 0.0204808630899049 -0.423474138941063 0.0513369938483483 -0.0164884080480223 0.998545264603792 -0.000446528427350731 2.57729548997254e-05 1.3851174055483e-05 -1.38111945098421e-06 2.02165325138314e-06 -4.40628350335936e-06 -1.69289018577244e-06 1.3851174055483e-05 2.70094114822024e-05 -1.88439496463539e-06 1.22347773956098e-06 3.69779737485327e-06 5.28148370912394e-06 -1.38111945098421e-06 -1.88439496463539e-06 1.00658575575323e-05 2.09755793310755e-06 3.13137312715686e-06 3.79028248952831e-06 2.02165325138314e-06 1.22347773956098e-06 2.09755793310755e-06 2.45926196313777e-05 -1.15924869571342e-05 1.39114464273109e-05 -4.40628350335936e-06 3.69779737485327e-06 3.13137312715686e-06 -1.15924869571342e-05 6.78162056182731e-05 2.83542598164835e-05 -1.69289018577244e-06 5.28148370912394e-06 3.79028248952831e-06 1.39114464273109e-05 2.83542598164835e-05 0.00019907614457311 23 23 0 0 0 102 102 0 0 0 0 0 0 0 0 0 0 0 1859 0 745 817 0 0 2672 +256 259 0.999004935910562 -0.0427895172256856 0.0125775689990522 0.085391416449894 0.0431038502780468 0.998735232413059 -0.0258842351256821 -0.331543320998712 -0.0114540873726756 0.0264006203038229 0.999585819792394 0.000583788393677849 3.08759042823176e-05 1.78936369470635e-05 -5.1692838674714e-06 4.21163683574337e-06 -7.66048236363028e-06 1.37804066327087e-05 1.78936369470635e-05 2.97057151564529e-05 -1.62847306828307e-06 -2.19996356272684e-06 4.85793809159191e-06 -6.10130168259583e-07 -5.1692838674714e-06 -1.62847306828307e-06 1.05599728883342e-05 -2.29369898326364e-06 8.49872798680203e-06 2.82851403746885e-06 4.21163683574337e-06 -2.19996356272684e-06 -2.29369898326364e-06 3.17417002559346e-05 -3.31500298814531e-05 1.77724035097068e-05 -7.66048236363028e-06 4.85793809159191e-06 8.49872798680203e-06 -3.31500298814531e-05 0.000142460771753273 4.44693730545937e-05 1.37804066327087e-05 -6.10130168259583e-07 2.82851403746885e-06 1.77724035097068e-05 4.44693730545937e-05 0.00026512711680449 421 421 0 0 0 549 549 0 0 0 0 0 0 0 0 0 0 0 2031 0 219 301 0 0 3087 +252 256 0.998313460418554 0.0567340006040611 0.0123080430041364 0.112782778323837 -0.0571088258599434 0.997835369818158 0.0326060845358577 -0.438340106236615 -0.0104315270230168 -0.0332539909682919 0.999392493132027 -0.0295094442569636 5.0305389460922e-05 3.21284892278618e-05 -4.16608659976919e-07 1.18249817363786e-06 -8.16799220526213e-06 -3.45244570788465e-06 3.21284892278618e-05 4.38613673096724e-05 -9.53757131842417e-07 -6.54954757303212e-06 8.9749533504402e-06 -5.35913032289913e-06 -4.16608659976919e-07 -9.53757131842417e-07 1.18150614877506e-05 -2.98908807789916e-06 9.14964906575199e-06 -1.00509230081884e-06 1.18249817363786e-06 -6.54954757303212e-06 -2.98908807789916e-06 3.55797828694645e-05 -3.81928410571025e-05 1.95901172315003e-05 -8.16799220526213e-06 8.9749533504402e-06 9.14964906575199e-06 -3.81928410571025e-05 0.000113335750881764 8.45720486248494e-06 -3.45244570788465e-06 -5.35913032289913e-06 -1.00509230081884e-06 1.95901172315003e-05 8.45720486248494e-06 0.000214747202733778 25 25 0 0 0 112 112 0 0 0 0 0 0 0 0 0 0 0 1770 0 690 763 0 0 2504 +257 261 0.999178201204463 -0.0341139946100158 0.0218896690144137 0.123297167225661 0.0349151364087994 0.998693030215529 -0.0373251208769661 -0.438930064969391 -0.0205877509060048 0.0380587279171679 0.999063400261444 -0.0458513298408458 2.77080072923835e-05 1.09744085283792e-05 -2.84782493516245e-07 1.17009505553814e-06 -1.57252789957297e-06 -8.19424448275522e-06 1.09744085283792e-05 3.37810925220262e-05 2.01345509853979e-06 -3.85765886890096e-07 -1.73321239566323e-06 -1.10954966791412e-05 -2.84782493516245e-07 2.01345509853979e-06 1.19064931536588e-05 1.50551011099623e-06 3.64065918668307e-06 2.07778003935326e-07 1.17009505553814e-06 -3.85765886890096e-07 1.50551011099623e-06 2.28057021371915e-05 -5.13254637850684e-06 1.4181710244907e-05 -1.57252789957297e-06 -1.73321239566323e-06 3.64065918668307e-06 -5.13254637850684e-06 5.91973631965927e-05 -7.18921517114291e-06 -8.19424448275522e-06 -1.10954966791412e-05 2.07778003935326e-07 1.4181710244907e-05 -7.18921517114291e-06 0.000182280827851195 219 219 0 0 0 343 343 0 0 0 0 0 0 0 0 0 0 0 1779 0 418 503 0 0 2721 +255 259 0.998024102169846 -0.036155512232339 0.0513874539483115 0.118164162377595 0.0370714486227933 0.999168281935023 -0.0169838768254579 -0.461398851135121 -0.0507306533082341 0.0188553257789919 0.998534364708941 -0.0423504594733287 3.08100325531548e-05 2.13476410715471e-05 -3.82858484983956e-06 6.05987385328474e-06 -7.32002853220701e-06 1.7077402809021e-05 2.13476410715471e-05 3.1018097505802e-05 -2.7569922090199e-06 2.55434263764758e-06 -4.48766949090348e-06 1.15157981652422e-08 -3.82858484983956e-06 -2.7569922090199e-06 9.26557789718336e-06 1.13643172796131e-06 -7.13747473035942e-07 -3.20738531691697e-06 6.05987385328474e-06 2.55434263764758e-06 1.13643172796131e-06 2.36828237583438e-05 -1.20626491090913e-05 3.12405868303974e-05 -7.32002853220701e-06 -4.48766949090348e-06 -7.13747473035942e-07 -1.20626491090913e-05 5.24101583697251e-05 -7.07181352814629e-06 1.7077402809021e-05 1.15157981652422e-08 -3.20738531691697e-06 3.12405868303974e-05 -7.07181352814629e-06 0.00026598914102918 121 121 0 0 0 301 301 0 0 0 0 0 0 0 0 0 0 0 1766 0 447 529 0 0 2955 +259 263 0.999141600981695 0.0413462227438464 0.00255950240294375 0.144550299898999 -0.0413469867800783 0.999144817342477 0.000246296316775916 -0.432034267686797 -0.00254713013850246 -0.000351912608277478 0.999996694137323 0.0292538363588649 5.26781490033824e-05 2.82725082444237e-05 -1.72527447139111e-06 5.57069120534587e-06 -1.63579075383538e-05 -2.09080901276419e-05 2.82725082444237e-05 3.50661283729163e-05 5.21163869300449e-07 1.31188561445046e-06 -1.83461114064633e-06 -1.41704461843751e-05 -1.72527447139111e-06 5.21163869300449e-07 1.0355383658211e-05 1.56154356783362e-07 1.74549936986644e-06 -8.84793069812127e-07 5.57069120534587e-06 1.31188561445046e-06 1.56154356783362e-07 2.53331923211384e-05 -1.63643443684124e-05 1.27082409440731e-05 -1.63579075383538e-05 -1.83461114064633e-06 1.74549936986644e-06 -1.63643443684124e-05 5.9532476763119e-05 5.96502939641332e-06 -2.09080901276419e-05 -1.41704461843751e-05 -8.84793069812127e-07 1.27082409440731e-05 5.96502939641332e-06 0.000276466671015233 29 29 0 0 0 153 153 0 0 0 0 0 0 0 0 0 0 0 1788 0 582 662 0 0 2925 +261 265 0.99511239399888 0.0660137700885205 -0.0734404892992871 0.140670529994695 -0.0663340231659588 0.997795611340779 -0.0019275268345852 -0.442994603089254 0.0731513546042503 0.00678970896135941 0.997297738477223 0.0329259986629905 2.60714683001305e-05 1.63780880555511e-05 -1.6359866385185e-06 4.88448973673972e-06 -6.87977579550504e-06 4.16595260019128e-06 1.63780880555511e-05 3.39239210549687e-05 1.0547272713231e-06 5.10230306596679e-06 1.69855036237425e-06 6.9772989435961e-06 -1.6359866385185e-06 1.0547272713231e-06 9.78170933232819e-06 3.90275251203311e-07 -5.2689070575699e-07 -8.29001455805572e-07 4.88448973673972e-06 5.10230306596679e-06 3.90275251203311e-07 2.93699749389739e-05 -1.1450744077915e-05 2.28398804727448e-05 -6.87977579550504e-06 1.69855036237425e-06 -5.2689070575699e-07 -1.1450744077915e-05 4.39468668259004e-05 -4.0927664039175e-06 4.16595260019128e-06 6.9772989435961e-06 -8.29001455805572e-07 2.28398804727448e-05 -4.0927664039175e-06 0.000145012280865597 41 41 0 0 0 160 160 0 0 0 0 0 0 0 0 0 0 0 1820 0 616 597 0 0 3140 +260 263 0.999110109367244 0.0347268976577177 0.0239380855384304 0.109774979070083 -0.0347910164482235 0.999392037793518 0.0022671500651793 -0.296958171294998 -0.0238448009988394 -0.00309796287727976 0.99971087224824 0.0417689278337978 4.02326803949986e-05 1.68534029252961e-05 -1.33766507480894e-06 2.44198873948856e-06 -5.40373832035191e-06 -1.24655271639691e-05 1.68534029252961e-05 4.77954370797017e-05 1.15909287013048e-06 1.45962565128475e-06 5.93654089364944e-06 1.12577056696606e-05 -1.33766507480894e-06 1.15909287013048e-06 1.31851850596485e-05 -2.93056063532302e-06 1.50909887292957e-05 2.49855120494409e-06 2.44198873948856e-06 1.45962565128475e-06 -2.93056063532302e-06 4.03382994011287e-05 -5.49813067503551e-05 7.59775308697737e-06 -5.40373832035191e-06 5.93654089364944e-06 1.50909887292957e-05 -5.49813067503551e-05 0.000183928047039927 4.43353218382125e-05 -1.24655271639691e-05 1.12577056696606e-05 2.49855120494409e-06 7.59775308697737e-06 4.43353218382125e-05 0.000201613035162274 313 313 0 0 0 445 445 0 0 0 0 0 0 0 0 0 0 0 2238 0 311 391 0 0 3107 +262 266 0.994285748093523 0.0837524447912523 -0.0661919868986563 0.130382036181816 -0.082920946876417 0.996439960360721 0.0152158458668022 -0.446078737030959 0.067230705092406 -0.00964019646128121 0.997690883442846 0.0329278914031883 2.68447134338114e-05 2.03550604146193e-05 7.02942665737676e-07 2.9924684866519e-06 -2.3660676486305e-06 -5.2477965825807e-06 2.03550604146193e-05 4.16352499808616e-05 1.71857871494586e-06 6.96640895756843e-06 -6.43274097580119e-06 1.14862850378842e-05 7.02942665737676e-07 1.71857871494586e-06 9.10638889536379e-06 2.15824531494336e-06 -2.12225423443982e-06 1.64723849508322e-06 2.9924684866519e-06 6.96640895756843e-06 2.15824531494336e-06 2.38551074120728e-05 -7.80785440929294e-06 1.34815767464348e-05 -2.3660676486305e-06 -6.43274097580119e-06 -2.12225423443982e-06 -7.80785440929294e-06 3.38213081484076e-05 1.0655029429772e-05 -5.2477965825807e-06 1.14862850378842e-05 1.64723849508322e-06 1.34815767464348e-05 1.0655029429772e-05 0.000143608290482507 49 49 0 0 0 183 183 0 0 0 0 0 0 0 0 0 0 0 1895 0 554 602 0 0 2972 +264 268 0.998957133031967 0.00563066004897843 0.0453094033503631 0.128861616956977 -0.00710188812321698 0.999450543451943 0.0323755212884793 -0.43384641166984 -0.0451022122477198 -0.0326635402402787 0.998448237811722 -0.0125399221555965 3.14218616921824e-05 1.60123586846655e-05 3.66589486544038e-06 1.44415497592962e-06 1.5903391649047e-06 -6.20372024871049e-06 1.60123586846655e-05 3.12410696704617e-05 1.94487907582782e-06 -9.6574381267103e-07 6.12827958813126e-06 5.11327402561698e-06 3.66589486544038e-06 1.94487907582782e-06 1.16551347704627e-05 -1.73230793400669e-07 3.48022888268777e-06 -1.3746147012727e-06 1.44415497592962e-06 -9.6574381267103e-07 -1.73230793400669e-07 2.45333135901599e-05 -9.38312225043079e-06 1.43939223364892e-05 1.5903391649047e-06 6.12827958813126e-06 3.48022888268777e-06 -9.38312225043079e-06 5.49543227030706e-05 -8.27007085970417e-06 -6.20372024871049e-06 5.11327402561698e-06 -1.3746147012727e-06 1.43939223364892e-05 -8.27007085970417e-06 0.000150294323814319 267 267 0 0 0 252 252 0 0 0 0 0 0 0 0 0 0 0 1968 0 253 320 0 0 2966 +264 267 0.99911049420542 0.0270008106770065 0.0323909955294039 0.092896671917009 -0.0279730276561912 0.999159988182675 0.0299470823043412 -0.326745229884893 -0.0315551912107561 -0.0308265184148563 0.999026524007281 -0.0325472165817594 3.58857493742627e-05 2.62057440110205e-05 1.38125316418511e-06 -4.7743095818557e-06 2.24496668454219e-06 -7.10499594080388e-06 2.62057440110205e-05 4.15894548600491e-05 -4.19739297080651e-08 -8.44553296979824e-07 2.09583818926234e-06 1.84098035251984e-05 1.38125316418511e-06 -4.19739297080651e-08 1.31659391590247e-05 -3.42026010534706e-06 5.31800687435602e-06 -6.99399398993055e-07 -4.7743095818557e-06 -8.44553296979824e-07 -3.42026010534706e-06 2.83079009739858e-05 -1.26647145444936e-05 3.06965116619844e-05 2.24496668454219e-06 2.09583818926234e-06 5.31800687435602e-06 -1.26647145444936e-05 6.46500075512481e-05 4.73162752341369e-06 -7.10499594080388e-06 1.84098035251984e-05 -6.99399398993055e-07 3.06965116619844e-05 4.73162752341369e-06 0.00035134084268316 581 581 0 0 0 547 547 0 0 0 0 0 0 0 0 0 0 0 2129 0 241 300 0 0 2988 +263 266 0.997452261236618 0.0515259858436114 -0.0493361868895668 0.0909136719019781 -0.0512388491123753 0.998661415969176 0.00706799802482933 -0.324482761970849 0.0496343318238247 -0.00452206117646749 0.998757219782225 -0.0273663403801829 2.14979643894683e-05 9.37726652577249e-06 -8.02813784561146e-07 4.75412789317263e-07 -9.58909473391008e-07 -2.15766457131552e-06 9.37726652577249e-06 3.81497240656642e-05 3.26050655594692e-07 2.02800044903596e-06 5.07441560190069e-06 -9.58367561374834e-06 -8.02813784561146e-07 3.26050655594692e-07 9.75755534013754e-06 1.89229687049714e-07 1.79815295896025e-06 1.83205222582217e-06 4.75412789317263e-07 2.02800044903596e-06 1.89229687049714e-07 2.78694005282508e-05 -1.35457923188603e-05 1.39902737209158e-05 -9.58909473391008e-07 5.07441560190069e-06 1.79815295896025e-06 -1.35457923188603e-05 5.31384964040772e-05 9.2204643053645e-06 -2.15766457131552e-06 -9.58367561374834e-06 1.83205222582217e-06 1.39902737209158e-05 9.2204643053645e-06 0.000129479345232953 380 380 0 0 0 515 515 0 0 0 0 0 0 0 0 0 0 0 2146 0 294 342 0 0 3137 +262 265 0.994373672326275 0.0578306659103662 -0.0887502893782367 0.102914185315071 -0.0578461784846814 0.998322624522537 0.00239937515878357 -0.331982768028297 0.0887401792824172 0.00274798959201255 0.996051017335019 0.0202908552836742 3.44191024202645e-05 1.99007635281628e-05 -1.41392975003005e-06 6.47638783746214e-06 -6.14072745883513e-06 1.16756111293977e-06 1.99007635281628e-05 3.63987968270669e-05 -6.05772079766042e-07 1.00332798037318e-05 4.60767475718506e-06 6.06161407661299e-06 -1.41392975003005e-06 -6.05772079766042e-07 1.12510684147883e-05 -2.01851073460653e-06 3.29099897656466e-06 -2.66230185237692e-06 6.47638783746214e-06 1.00332798037318e-05 -2.01851073460653e-06 3.7122568303958e-05 -1.92868918013142e-05 2.90127821040304e-05 -6.14072745883513e-06 4.60767475718506e-06 3.29099897656466e-06 -1.92868918013142e-05 7.6887718574773e-05 -8.27568324769068e-06 1.16756111293977e-06 6.06161407661299e-06 -2.66230185237692e-06 2.90127821040304e-05 -8.27568324769068e-06 0.00014564729903448 223 223 0 0 0 378 378 0 0 0 0 0 0 0 0 0 0 0 2100 0 427 408 0 0 3018 +265 269 0.998307441467199 -0.0263977487526151 0.051820953021045 0.12484202038143 0.0247300752225621 0.999163682442146 0.0325631550703609 -0.421910897326336 -0.0526372082343086 -0.0312265039580763 0.998125357738122 0.00957680587322548 3.09507616138436e-05 1.81183844093296e-05 9.14412759213384e-07 -2.82335458310628e-07 2.82316325233758e-06 -1.00128365085454e-05 1.81183844093296e-05 4.78413617577902e-05 1.82266583127391e-06 -1.8246653773256e-07 4.9824546979662e-06 -1.26060057986674e-08 9.14412759213384e-07 1.82266583127391e-06 1.14570845908719e-05 3.16185671064018e-07 3.11543695776172e-06 1.70825180423211e-06 -2.82335458310628e-07 -1.8246653773256e-07 3.16185671064018e-07 2.61508226654214e-05 -9.11780096518607e-06 1.77495457839126e-05 2.82316325233758e-06 4.9824546979662e-06 3.11543695776172e-06 -9.11780096518607e-06 5.23133363351979e-05 -8.07142168329725e-06 -1.00128365085454e-05 -1.26060057986674e-08 1.70825180423211e-06 1.77495457839126e-05 -8.07142168329725e-06 0.000171853259946821 123 123 0 0 0 124 124 0 0 0 0 0 0 0 0 0 0 0 2001 0 281 353 0 0 3121 +266 268 0.998835186420871 -0.027874136081798 0.0393865828078205 0.0636392147672267 0.0264944013268958 0.999031540391153 0.0351287347054949 -0.190911989717085 -0.040327621624803 -0.0340442923464869 0.998606363434919 -0.00763559205370761 5.52597944817453e-05 2.38539673797081e-05 -1.72682073429618e-06 1.87952741016856e-06 -7.51161350123174e-06 -1.86424139388074e-05 2.38539673797081e-05 7.30629545505675e-05 8.35409356938408e-07 -2.02779498894503e-06 1.61159228496841e-06 3.44604137493516e-06 -1.72682073429618e-06 8.35409356938408e-07 9.65118045966487e-06 2.94109630224388e-06 -4.21390682350917e-08 -6.15842356333616e-07 1.87952741016856e-06 -2.02779498894503e-06 2.94109630224388e-06 2.28981301790906e-05 -1.17411965243476e-05 9.0586665591695e-06 -7.51161350123174e-06 1.61159228496841e-06 -4.21390682350917e-08 -1.17411965243476e-05 5.09491733339527e-05 -5.28724575022537e-06 -1.86424139388074e-05 3.44604137493516e-06 -6.15842356333616e-07 9.0586665591695e-06 -5.28724575022537e-06 0.000118249294603835 561 561 0 0 0 646 649 0 0 0 0 0 0 0 0 0 0 0 2549 0 15 74 0 0 3182 +263 267 0.99866162235796 0.0493205889060419 -0.015570598553944 0.124836318698386 -0.0490785198403133 0.998673653142744 0.0155638494213427 -0.441119814945193 0.016317564758592 -0.0147788371831978 0.999757632154845 -0.0169954367720676 2.73789115758112e-05 1.90475329359801e-05 -1.26424678418071e-06 8.22218936098285e-07 -5.89713318748726e-06 6.17192731935584e-06 1.90475329359801e-05 2.80793093291871e-05 -1.82671561374787e-06 1.10957447301364e-06 -5.91891774396482e-06 5.1061935430519e-06 -1.26424678418071e-06 -1.82671561374787e-06 9.31426539900226e-06 2.78460388174968e-07 -4.4818008367021e-07 3.51062072338364e-07 8.22218936098285e-07 1.10957447301364e-06 2.78460388174968e-07 2.27850515427513e-05 -1.0393435199845e-05 1.36493247995892e-05 -5.89713318748726e-06 -5.91891774396482e-06 -4.4818008367021e-07 -1.0393435199845e-05 3.74515693506192e-05 -9.32774668105568e-06 6.17192731935584e-06 5.1061935430519e-06 3.51062072338364e-07 1.36493247995892e-05 -9.32774668105568e-06 0.000132775062438354 115 115 0 0 0 278 278 0 0 0 0 0 0 0 0 0 0 0 1809 0 360 419 0 0 3092 +264 266 0.999504444441199 0.0312547832062377 -0.00374220109305737 0.0631434337024514 -0.0311955778389913 0.999401444149248 0.0149529045903721 -0.210939743113303 0.00420731096797406 -0.0148287544698945 0.999881196230477 0.00491498041683708 2.3698566005214e-05 1.37617673787807e-05 9.25744895994104e-07 -1.1538937209831e-06 -5.19960135871343e-06 -7.70382089916101e-06 1.37617673787807e-05 3.03539014060431e-05 4.63261622616223e-07 4.06258866605398e-06 -2.5878380736525e-06 8.69692246786201e-07 9.25744895994104e-07 4.63261622616223e-07 1.13676675385789e-05 -4.03185234827028e-06 1.58009897380926e-06 3.63961674442928e-06 -1.1538937209831e-06 4.06258866605398e-06 -4.03185234827028e-06 3.04588806960151e-05 -1.41397852343811e-05 7.9616865437968e-06 -5.19960135871343e-06 -2.5878380736525e-06 1.58009897380926e-06 -1.41397852343811e-05 5.67844960602174e-05 1.23716159402969e-05 -7.70382089916101e-06 8.69692246786201e-07 3.63961674442928e-06 7.9616865437968e-06 1.23716159402969e-05 0.00011455501716588 769 769 0 0 0 714 714 0 0 0 0 0 0 0 0 0 0 0 2515 0 214 262 0 0 2987 +265 268 0.998315921428731 -0.00266425328739291 0.0579501749464471 0.0904006087764699 0.000389804924641799 0.999230355502246 0.039224287055026 -0.311983077165506 -0.0580100773488877 -0.0391356410101453 0.997548611611836 -0.0230760211716825 2.79991056668097e-05 1.50617626385639e-05 -2.56105012787855e-07 1.01780213037516e-06 -2.06942589259547e-06 3.67951948586338e-06 1.50617626385639e-05 2.9962392952476e-05 -3.7822973155322e-07 5.48220636727062e-07 9.52814833163294e-08 6.13405068160609e-06 -2.56105012787855e-07 -3.7822973155322e-07 1.13564405584221e-05 -5.25702703226414e-07 6.88437755125663e-06 -4.23894989346706e-06 1.01780213037516e-06 5.48220636727062e-07 -5.25702703226414e-07 2.69871761516508e-05 -2.19365690150835e-05 2.04850338822643e-05 -2.06942589259547e-06 9.52814833163294e-08 6.88437755125663e-06 -2.19365690150835e-05 7.90891044098518e-05 -2.79800960562949e-05 3.67951948586338e-06 6.13405068160609e-06 -4.23894989346706e-06 2.04850338822643e-05 -2.79800960562949e-05 0.000113898751129525 403 403 0 0 0 412 412 0 0 0 0 0 0 0 0 0 0 0 2234 0 176 243 0 0 3179 +267 269 0.998958540991163 -0.0455381558451128 -0.00284776105633513 0.064646520809405 0.0455628385500708 0.998918142914729 0.00930438063758594 -0.208897842100952 0.00242097585034253 -0.00942444258378825 0.999952658258338 0.0131346902394101 2.69073526052031e-05 8.92081540725765e-06 -2.41286964745967e-07 1.86814321291904e-07 -2.31600351902217e-06 8.8013603162313e-06 8.92081540725765e-06 3.72188785590823e-05 -3.5873952613079e-07 1.21533909367898e-06 -9.29649472204361e-07 2.04247944639074e-05 -2.41286964745967e-07 -3.5873952613079e-07 9.1805405775009e-06 -8.86381316968539e-07 4.87532547943099e-08 -3.46994827830203e-07 1.86814321291904e-07 1.21533909367898e-06 -8.86381316968539e-07 2.44465103763781e-05 -8.02450347570723e-06 1.84112256368209e-05 -2.31600351902217e-06 -9.29649472204361e-07 4.87532547943099e-08 -8.02450347570723e-06 5.36007671816921e-05 -5.20070600568905e-06 8.8013603162313e-06 2.04247944639074e-05 -3.46994827830203e-07 1.84112256368209e-05 -5.20070600568905e-06 0.000153900191056063 585 585 0 0 0 662 662 0 0 0 0 0 0 0 0 0 0 0 2482 0 10 81 0 0 3093 +267 271 0.994887579575019 -0.100554516729675 -0.00935377852109903 0.11431329354564 0.100530707395923 0.994929484538946 -0.00298289549634041 -0.448394545138088 0.00960629365757816 0.00202730370892846 0.999951803419463 -0.0185709017903073 5.43739530934255e-05 3.76963013395039e-05 7.62278685093892e-07 7.51296186032188e-06 -1.15679905182734e-05 4.16621998587122e-05 3.76963013395039e-05 5.54553243864955e-05 -1.39078844211236e-06 8.90482852331379e-06 -1.29661905073593e-05 5.71249332937756e-05 7.62278685093892e-07 -1.39078844211236e-06 1.35376703143518e-05 -9.30056583900115e-07 3.12504523140578e-06 -4.25306908075288e-06 7.51296186032188e-06 8.90482852331379e-06 -9.30056583900115e-07 3.46058035027634e-05 -9.59805403358092e-06 5.39299982901089e-05 -1.15679905182734e-05 -1.29661905073593e-05 3.12504523140578e-06 -9.59805403358092e-06 5.50767657303466e-05 -2.19154637742578e-05 4.16621998587122e-05 5.71249332937756e-05 -4.25306908075288e-06 5.39299982901089e-05 -2.19154637742578e-05 0.000372713279340191 260 260 0 0 0 365 365 0 0 0 0 0 0 0 0 0 0 0 1997 0 225 301 0 0 3055 +266 269 0.998070079612113 -0.0504504018222554 0.0362059820891986 0.102965316775334 0.0496830991569804 0.998527331264355 0.0217889507834249 -0.311093939202366 -0.0372519239936417 -0.0199480744448638 0.99910678532613 0.0223955271907438 2.27497909772794e-05 6.52605651805935e-06 1.94161345830712e-06 2.96340751263298e-07 1.82975931246343e-06 -7.00337008056108e-06 6.52605651805935e-06 3.72448384434518e-05 1.18732755276323e-06 1.95884434170167e-06 3.5735985932916e-06 1.11722449787483e-05 1.94161345830712e-06 1.18732755276323e-06 1.10785822802669e-05 3.33497814300822e-06 -4.09529793892378e-07 -2.8029093249851e-07 2.96340751263298e-07 1.95884434170167e-06 3.33497814300822e-06 2.09247770776216e-05 -1.67651221944982e-06 5.59108265001011e-06 1.82975931246343e-06 3.5735985932916e-06 -4.09529793892378e-07 -1.67651221944982e-06 3.79224350859841e-05 2.16313771771336e-06 -7.00337008056108e-06 1.11722449787483e-05 -2.8029093249851e-07 5.59108265001011e-06 2.16313771771336e-06 0.000102674673123682 317 317 0 0 0 419 419 0 0 0 0 0 0 0 0 0 0 0 2306 0 94 166 0 0 3077 +268 270 0.998004587982402 -0.0625602537305649 -0.0085473398928775 0.0410004978641152 0.062477052027017 0.997999481682591 -0.00967742379426243 -0.21059518971395 0.00913566287088394 0.00912410074734406 0.999916641750432 0.00571074770389238 2.51291065717739e-05 7.38927953032999e-06 2.75622098366527e-06 -2.01155726376409e-06 -5.47836589555841e-06 -1.08900891730953e-05 7.38927953032999e-06 3.35955339456762e-05 4.452075371591e-06 2.28724663184108e-06 -1.17718968382246e-06 7.00072851039393e-06 2.75622098366527e-06 4.452075371591e-06 1.13681247991798e-05 -3.729252160786e-07 9.60512257466051e-07 1.83381088875275e-06 -2.01155726376409e-06 2.28724663184108e-06 -3.729252160786e-07 3.03095034952463e-05 -1.25023409556046e-05 8.19030005412776e-06 -5.47836589555841e-06 -1.17718968382246e-06 9.60512257466051e-07 -1.25023409556046e-05 6.15860090442274e-05 2.61939945089893e-06 -1.08900891730953e-05 7.00072851039393e-06 1.83381088875275e-06 8.19030005412776e-06 2.61939945089893e-06 0.000109615885488888 646 646 0 0 0 734 734 0 0 0 0 0 0 0 0 0 0 0 2819 0 11 84 0 0 3106 +268 272 0.99729503071838 -0.0636887716943924 -0.0366928067130982 0.102892313821406 0.0630683986550207 0.997850015906157 -0.0178247818268318 -0.450269029523138 0.037749156222578 0.0154624097779854 0.999167611108537 -0.00841229845032578 2.89834711151554e-05 1.58035432603238e-05 8.16063471685853e-07 4.14273478646043e-06 -8.86627236327221e-06 -6.53451225697115e-06 1.58035432603238e-05 3.80837452344367e-05 1.94262431062873e-06 1.76684263658062e-06 7.01680964054063e-06 1.47806054078604e-05 8.16063471685853e-07 1.94262431062873e-06 1.06674751582395e-05 1.11618939302424e-06 1.50471661917929e-06 2.84641505125416e-06 4.14273478646043e-06 1.76684263658062e-06 1.11618939302424e-06 2.23101767144487e-05 -5.31099822233247e-07 1.29228229705512e-05 -8.86627236327221e-06 7.01680964054063e-06 1.50471661917929e-06 -5.31099822233247e-07 5.54999010463013e-05 2.57926056842783e-05 -6.53451225697115e-06 1.47806054078604e-05 2.84641505125416e-06 1.29228229705512e-05 2.57926056842783e-05 0.000133534528294509 317 317 0 0 0 454 454 0 0 0 0 0 0 0 0 0 0 0 2141 0 368 408 0 0 3158 +266 270 0.995168900491646 -0.087167440235717 0.0451740728405293 0.127787967171419 0.0866248319565945 0.996144910312646 0.0138367679283629 -0.434566932991606 -0.046206038379637 -0.00985672465702114 0.99888329998869 0.0292182156786558 4.43356766005955e-05 3.09461848274726e-05 6.19438786133502e-07 5.59819465921322e-06 -3.86467770090097e-06 2.2890192018489e-06 3.09461848274726e-05 5.47670360716926e-05 1.37290076727087e-06 5.98654164773582e-06 2.0068427356385e-06 -6.74222630509254e-06 6.19438786133502e-07 1.37290076727087e-06 1.06389575562862e-05 -3.8630074151024e-07 1.07638715623196e-06 -3.27018355946837e-06 5.59819465921322e-06 5.98654164773582e-06 -3.8630074151024e-07 2.17380696477651e-05 -4.50857334068719e-06 1.03389775331304e-05 -3.86467770090097e-06 2.0068427356385e-06 1.07638715623196e-06 -4.50857334068719e-06 5.00822015757129e-05 3.56201650264955e-06 2.2890192018489e-06 -6.74222630509254e-06 -3.27018355946837e-06 1.03389775331304e-05 3.56201650264955e-06 0.000223420524731818 188 188 0 0 0 300 300 0 0 0 0 0 0 0 0 0 0 0 1997 0 177 251 0 0 2934 +269 272 0.998903495306149 -0.0400512829664264 -0.0242425617025366 0.0643507948054879 0.0396976108838601 0.99910066081837 -0.0148986322328733 -0.343820930041161 0.0248174687523059 0.0139199240314027 0.999595082500754 -0.0489066612409947 3.84594870677299e-05 2.78514371278919e-05 -5.11952601824025e-07 7.85917480303243e-06 9.56541353087554e-07 5.74570098236615e-05 2.78514371278919e-05 3.64574838912597e-05 -1.00615363945828e-06 6.64052728859996e-06 -1.11414903112803e-06 4.25936948870716e-05 -5.11952601824025e-07 -1.00615363945828e-06 8.53422106846785e-06 2.91164422865501e-07 -2.06747425996599e-06 -3.39586209984277e-06 7.85917480303243e-06 6.64052728859996e-06 2.91164422865501e-07 2.67602663243539e-05 -2.27635486893172e-06 5.39051290344813e-05 9.56541353087554e-07 -1.11414903112803e-06 -2.06747425996599e-06 -2.27635486893172e-06 2.79898078861417e-05 -3.08154018238447e-06 5.74570098236615e-05 4.25936948870716e-05 -3.39586209984277e-06 5.39051290344813e-05 -3.08154018238447e-06 0.000474396066846592 625 625 0 0 0 744 744 0 0 0 0 0 0 0 0 0 0 0 2374 0 294 328 0 0 3299 +269 271 0.998433471138411 -0.0557874912465417 -0.00428480231988723 0.039656293164906 0.0557159065544761 0.998329097906882 -0.0153215544004026 -0.224882105013141 0.0051323939167182 0.0150588210975707 0.999873437210848 -0.00852408251138395 5.83921208186508e-05 1.75195655053213e-05 -3.59697309382896e-06 9.6469585721567e-06 -1.83582139074562e-06 6.83579996966975e-05 1.75195655053213e-05 3.92998530736888e-05 -6.97839890855451e-07 4.66477642707149e-06 4.10923421715117e-06 3.55319738515349e-05 -3.59697309382896e-06 -6.97839890855451e-07 9.93530422400215e-06 1.50233694197266e-06 4.09748711713351e-07 -2.44906948069664e-06 9.6469585721567e-06 4.66477642707149e-06 1.50233694197266e-06 2.61467239176631e-05 1.90343713413822e-06 5.44640030052291e-05 -1.83582139074562e-06 4.10923421715117e-06 4.09748711713351e-07 1.90343713413822e-06 5.59810248037503e-05 2.31511143339873e-05 6.83579996966975e-05 3.55319738515349e-05 -2.44906948069664e-06 5.44640030052291e-05 2.31511143339873e-05 0.000506028965736882 792 792 0 0 0 896 896 0 0 0 0 0 0 0 0 0 0 0 2704 0 57 133 0 0 3234 +267 270 0.996564910795982 -0.0827977573211644 0.0017058583711377 0.0861191882567847 0.0828019617515338 0.996562727723902 -0.00256219468289231 -0.332023838978276 -0.00148785089788795 0.00269464173519899 0.999995262591591 0.00518034475743071 2.64038494904013e-05 1.96844595525352e-05 2.20170964871418e-06 1.18242110050511e-06 -2.56585536993334e-06 7.8509412788309e-06 1.96844595525352e-05 3.31286927465599e-05 3.34883304790238e-06 1.25788611575069e-06 5.68231438510229e-06 1.30506204663263e-05 2.20170964871418e-06 3.34883304790238e-06 1.25101698331486e-05 -3.08970317994104e-06 3.9631803501403e-06 -1.01699421336746e-07 1.18242110050511e-06 1.25788611575069e-06 -3.08970317994104e-06 2.23797014752215e-05 -5.36853541771966e-06 1.23932451902021e-05 -2.56585536993334e-06 5.68231438510229e-06 3.9631803501403e-06 -5.36853541771966e-06 5.82695352268799e-05 1.87927067283179e-07 7.8509412788309e-06 1.30506204663263e-05 -1.01699421336746e-07 1.23932451902021e-05 1.87927067283179e-07 0.00011695404345873 409 409 0 0 0 504 504 0 0 0 0 0 0 0 0 0 0 0 2280 0 83 157 0 0 3021 +270 272 0.999547294337855 -0.00180775376662375 -0.0300322894264333 0.0408318851255264 0.00153068758216261 0.999956082907174 -0.00924603982612744 -0.216009932570114 0.0300476850589128 0.00919588403905678 0.999506164232788 -0.0196552508087805 1.71441837222878e-05 1.01113188605941e-05 1.25970893331722e-06 1.79163167642708e-06 -7.67328662825116e-07 -5.13868453822524e-06 1.01113188605941e-05 2.45262957314456e-05 6.46330182026448e-07 1.04947189592421e-06 -8.22581916585805e-07 4.20296517617867e-06 1.25970893331722e-06 6.46330182026448e-07 8.94858939607647e-06 1.0640728374572e-06 -9.4932950392733e-07 3.47323955908553e-07 1.79163167642708e-06 1.04947189592421e-06 1.0640728374572e-06 1.86493975276217e-05 -5.42432977256617e-06 8.45648858394844e-06 -7.67328662825116e-07 -8.22581916585805e-07 -9.4932950392733e-07 -5.42432977256617e-06 5.07743576789739e-05 6.41791873200132e-06 -5.13868453822524e-06 4.20296517617867e-06 3.47323955908553e-07 8.45648858394844e-06 6.41791873200132e-06 0.000102512796984555 852 852 0 0 0 961 961 0 0 0 0 0 0 0 0 0 0 0 2942 0 199 232 0 0 3413 +268 271 0.99677050439593 -0.0797956215139248 -0.00901223354608955 0.0713932488715669 0.0797035063258197 0.996766876834508 -0.0101559994560407 -0.336717300702246 0.00979350017372872 0.00940489408699195 0.999907813411596 -0.0131708754778062 1.5540470032794e-05 8.89822920454729e-06 1.20492005855786e-06 -2.86890231809282e-07 -2.45526292371094e-06 -1.14428978556818e-06 8.89822920454729e-06 2.12547456710222e-05 1.3644011817946e-07 -1.29033324008133e-07 -8.51680582940987e-07 1.619698318496e-06 1.20492005855786e-06 1.3644011817946e-07 9.98572640321335e-06 1.44326991255442e-06 -1.30843588499908e-06 2.10597095872569e-06 -2.86890231809282e-07 -1.29033324008133e-07 1.44326991255442e-06 2.25258516320133e-05 -6.16030873390762e-06 6.92991437123438e-06 -2.45526292371094e-06 -8.51680582940987e-07 -1.30843588499908e-06 -6.16030873390762e-06 5.16134915695431e-05 -2.7065013003091e-06 -1.14428978556818e-06 1.619698318496e-06 2.10597095872569e-06 6.92991437123438e-06 -2.7065013003091e-06 0.000116190974813903 496 496 0 0 0 608 608 0 0 0 0 0 0 0 0 0 0 0 2414 0 148 224 0 0 3138 +271 273 0.999117789263025 0.0351604246450216 0.0229649236216212 0.0428994752069346 -0.0353839675352044 0.999329570784161 0.00940126575585943 -0.213709474164754 -0.022618974769709 -0.0102055619701444 0.999692066831202 -0.00211736158879142 0.000134547542483709 5.09519632827034e-05 -3.58259328673785e-06 3.40900176847056e-05 -3.08869029466466e-06 0.000244083938604716 5.09519632827034e-05 4.65142016000283e-05 -3.07973359247158e-06 2.10709361920506e-05 3.62058255824082e-06 0.0001517787958208 -3.58259328673785e-06 -3.07973359247158e-06 1.05985201367325e-05 -1.35601674829945e-06 -3.11979821738068e-07 -1.2498102066318e-05 3.40900176847056e-05 2.10709361920506e-05 -1.35601674829945e-06 3.91340712378541e-05 -2.96716028511191e-06 0.000175261444764634 -3.08869029466466e-06 3.62058255824082e-06 -3.11979821738068e-07 -2.96716028511191e-06 5.37310211499902e-05 3.8034526791676e-05 0.000244083938604716 0.0001517787958208 -1.2498102066318e-05 0.000175261444764634 3.8034526791676e-05 0.00166717848041691 1432 1432 0 0 0 1553 1553 0 0 0 0 0 0 0 0 0 0 0 2760 0 295 276 0 0 3368 +272 276 0.995899748381851 0.0904441457748565 0.00188352542373056 0.128377275364778 -0.0904493142500987 0.99515288535121 0.0385960662353983 -0.476960209354452 0.00161639248087256 -0.0386081762353115 0.999253119086016 0.0235145420830925 2.63181982350059e-05 9.41532252112133e-06 -1.65652870205842e-06 5.59207043123353e-06 -3.83841672373987e-06 5.51267376130565e-06 9.41532252112133e-06 2.56462025865062e-05 -1.68578915049064e-06 1.50212876595193e-06 1.68695792400712e-06 1.03841598205792e-05 -1.65652870205842e-06 -1.68578915049064e-06 1.21352134085947e-05 -4.33334173103184e-06 2.35816793892637e-06 -2.26123221690215e-06 5.59207043123353e-06 1.50212876595193e-06 -4.33334173103184e-06 2.57891512075532e-05 -1.24754508581796e-05 1.09239463773202e-05 -3.83841672373987e-06 1.68695792400712e-06 2.35816793892637e-06 -1.24754508581796e-05 4.94614833930098e-05 -1.393985341491e-05 5.51267376130565e-06 1.03841598205792e-05 -2.26123221690215e-06 1.09239463773202e-05 -1.393985341491e-05 0.000120100524797271 419 419 0 0 0 466 466 0 0 0 0 0 0 0 0 0 0 0 2147 0 571 615 0 0 3145 +272 246 0.991968353103053 -0.125551298430221 0.015351153197778 -0.733064828389331 0.125779326715491 0.991946090486854 -0.0149169212253745 2.90261856089533 -0.0133546775705736 0.0167279714948256 0.999770887532066 0.0631572687182159 6.06869768666321e-05 3.3005865465345e-05 -7.11761115153232e-06 -6.74065006860812e-06 -1.53921481849535e-05 -5.96786348707348e-05 3.3005865465345e-05 4.42121477290013e-05 -2.57795082117759e-06 1.18168261770152e-06 -1.03670304351513e-06 5.6011283093069e-06 -7.11761115153232e-06 -2.57795082117759e-06 1.13558050156122e-05 2.93182257092806e-06 1.67420787026981e-06 4.36307106048932e-06 -6.74065006860812e-06 1.18168261770152e-06 2.93182257092806e-06 3.60358613001982e-05 -1.50024003132109e-06 0.000114947885142022 -1.53921481849535e-05 -1.03670304351513e-06 1.67420787026981e-06 -1.50024003132109e-06 4.0061417188637e-05 1.05290145250898e-05 -5.96786348707348e-05 5.6011283093069e-06 4.36307106048932e-06 0.000114947885142022 1.05290145250898e-05 0.000864602224042145 0 0 0 0 35 0 0 0 0 38 0 0 0 0 0 427 543 0 2062 926 0 0 0 0 1318 +270 274 0.999275702548818 0.0345576754221445 0.0159322743192584 0.0996796394286367 -0.0346437395097739 0.999386415875192 0.0051578170690331 -0.459010597947878 -0.0157442563605056 -0.00570603483659098 0.999859769946815 -0.0392907529572534 2.5519014875025e-05 1.55730874848428e-05 6.72060346689726e-07 9.26482518635345e-07 -1.8411823750202e-06 4.82655685737024e-06 1.55730874848428e-05 2.65676524429362e-05 -7.05917001349177e-07 2.08700027535499e-06 -2.8545467686002e-06 5.40942117351246e-06 6.72060346689726e-07 -7.05917001349177e-07 1.06209034043275e-05 2.42793952782751e-07 3.03991645557956e-06 -2.10985789138352e-06 9.26482518635345e-07 2.08700027535499e-06 2.42793952782751e-07 2.24142233296554e-05 -9.52366036640214e-06 1.22707271777344e-05 -1.8411823750202e-06 -2.8545467686002e-06 3.03991645557956e-06 -9.52366036640214e-06 5.60507465230488e-05 -1.64515395404928e-05 4.82655685737024e-06 5.40942117351246e-06 -2.10985789138352e-06 1.22707271777344e-05 -1.64515395404928e-05 0.000170504159971053 206 206 0 0 0 377 377 0 0 0 0 0 0 0 0 0 0 0 2246 0 536 574 0 0 3304 +270 273 0.99975472438334 0.0190058419989566 0.0113696544847776 0.0673512591802841 -0.0190604456592196 0.999807221902351 0.00471364436243019 -0.343217539223596 -0.0112778758844235 -0.00492919890187369 0.999924253388086 -0.0158215834732141 2.89698778775629e-05 1.7593691583084e-05 6.29062470188368e-07 8.67482839863377e-06 -3.17950881032519e-06 2.18787650629549e-05 1.7593691583084e-05 2.58590788872609e-05 2.41273395275711e-07 6.17704334998041e-06 4.43949800302479e-06 1.12024842798866e-05 6.29062470188368e-07 2.41273395275711e-07 8.41649119736441e-06 1.54973668469549e-06 -9.11473597959676e-07 -1.40086401030172e-06 8.67482839863377e-06 6.17704334998041e-06 1.54973668469549e-06 2.49252894512545e-05 -4.59618470895128e-06 2.92182526156378e-05 -3.17950881032519e-06 4.43949800302479e-06 -9.11473597959676e-07 -4.59618470895128e-06 3.6279941469346e-05 -3.20442579389928e-06 2.18787650629549e-05 1.12024842798866e-05 -1.40086401030172e-06 2.92182526156378e-05 -3.20442579389928e-06 0.000218364072141939 782 782 0 0 0 921 921 0 0 0 0 0 0 0 0 0 0 0 2543 0 428 413 0 0 3512 +271 245 0.997918140433392 -0.064166941334489 0.00647986371288611 -0.678562980159925 0.0642216906932585 0.997898362658731 -0.00862741256246179 2.91244679197129 -0.00591265071357685 0.009025599304187 0.999941787865043 0.0486282247112151 5.01869654712113e-05 3.0437274042597e-05 -3.93059100756683e-06 -7.48203620743521e-07 -1.56367669464727e-05 2.16222396669725e-05 3.0437274042597e-05 4.4536553720421e-05 -2.12566278720468e-06 1.77161239192424e-06 -1.24162014641327e-05 -4.52528298785602e-06 -3.93059100756683e-06 -2.12566278720468e-06 1.3510886877698e-05 3.5719867782818e-07 3.48226596111221e-06 -4.22840552278195e-06 -7.48203620743521e-07 1.77161239192424e-06 3.5719867782818e-07 2.85632838097779e-05 -1.14647597774084e-05 4.32984566152769e-05 -1.56367669464727e-05 -1.24162014641327e-05 3.48226596111221e-06 -1.14647597774084e-05 6.42853388566163e-05 -1.24373323993077e-05 2.16222396669725e-05 -4.52528298785602e-06 -4.22840552278195e-06 4.32984566152769e-05 -1.24373323993077e-05 0.000475076982744034 0 0 0 0 29 0 0 0 0 30 0 0 0 0 0 476 590 0 1980 820 0 0 0 0 1315 +271 274 0.998229053102591 0.0525308180579781 0.0279154203991958 0.0757099797150275 -0.0527703545753176 0.998575314192387 0.00791401058696121 -0.343924980589189 -0.0274599202456869 -0.00937310192705078 0.99957896023294 -0.0125860535309667 4.14236225593777e-05 2.56704284838822e-05 6.36398860522939e-07 6.76318489671655e-06 -7.1235167861125e-07 1.55696167045629e-05 2.56704284838822e-05 3.79382447463098e-05 -7.81668050922655e-07 5.05010381648045e-06 2.88494908227434e-06 6.86153195007169e-06 6.36398860522939e-07 -7.81668050922655e-07 1.1564471805709e-05 1.57420118338799e-06 6.76203467263545e-06 -5.52182129171144e-06 6.76318489671655e-06 5.05010381648045e-06 1.57420118338799e-06 2.24386368649511e-05 -7.340519812283e-06 3.01349756171495e-05 -7.1235167861125e-07 2.88494908227434e-06 6.76203467263545e-06 -7.340519812283e-06 6.64115627253807e-05 -2.93827271646819e-05 1.55696167045629e-05 6.86153195007169e-06 -5.52182129171144e-06 3.01349756171495e-05 -2.93827271646819e-05 0.000279538437048023 705 705 0 0 0 846 846 0 0 0 0 0 0 0 0 0 0 0 2408 0 437 475 0 0 3270 +271 275 0.995856864421762 0.0897722410276687 0.0144931130170676 0.115023116772914 -0.0898245574632575 0.995953089418953 0.00299875863876472 -0.45912698595401 -0.0141652554013436 -0.00428817183818099 0.999890472562721 0.00255542803432755 2.5680576814788e-05 1.57262783782672e-05 -9.00673071520519e-07 1.28401945917122e-06 -6.46926368623105e-06 -8.44526791502799e-06 1.57262783782672e-05 2.74521935724716e-05 -5.68173338441339e-07 8.51077433172083e-07 2.07677176871457e-06 -7.52749978737241e-06 -9.00673071520519e-07 -5.68173338441339e-07 1.04760385690332e-05 -1.91939038327461e-06 -2.80840694885599e-07 -2.46403911986417e-06 1.28401945917122e-06 8.51077433172083e-07 -1.91939038327461e-06 1.98049848611424e-05 -5.37460120873224e-06 1.0985344744348e-05 -6.46926368623105e-06 2.07677176871457e-06 -2.80840694885599e-07 -5.37460120873224e-06 4.07337990938782e-05 -1.13068326933838e-05 -8.44526791502799e-06 -7.52749978737241e-06 -2.46403911986417e-06 1.0985344744348e-05 -1.13068326933838e-05 0.000145574568666566 197 197 0 0 0 380 380 0 0 0 0 0 0 0 0 0 0 0 2244 0 571 623 0 0 3234 +273 277 0.994765038668764 0.0861157504732643 -0.0550145013860782 0.135480611852649 -0.0852441149059753 0.996197437151532 0.0180029743825005 -0.476281817940539 0.0563556449366805 -0.0132190670301111 0.998323243018324 0.0171711671371771 3.12796766859697e-05 1.54257484007778e-05 -1.77165168675701e-06 5.4774829138146e-06 -2.95288191797864e-06 1.29788230818247e-05 1.54257484007778e-05 3.01126522635653e-05 -4.17259593493218e-06 5.62518067141873e-06 -4.61133737997104e-06 7.63540006045731e-06 -1.77165168675701e-06 -4.17259593493218e-06 1.07609179451075e-05 1.08353507327228e-06 2.47524040489443e-06 -7.51896470209527e-07 5.4774829138146e-06 5.62518067141873e-06 1.08353507327228e-06 2.65660970441617e-05 -2.24638656530463e-06 2.24530809787921e-05 -2.95288191797864e-06 -4.61133737997104e-06 2.47524040489443e-06 -2.24638656530463e-06 3.81775779983806e-05 -1.31892080770244e-05 1.29788230818247e-05 7.63540006045731e-06 -7.51896470209527e-07 2.24530809787921e-05 -1.31892080770244e-05 0.000143285233518805 362 362 0 0 0 362 362 0 0 0 0 0 0 0 0 0 0 0 1923 0 599 634 0 0 3217 +273 275 0.998260847281492 0.0534753033691906 -0.0248127530598753 0.0773131165519495 -0.053501584595384 0.998567686031314 -0.000396055361995873 -0.223134212847879 0.0247560342264324 0.00172288816811367 0.999692037792509 0.0469845687607864 3.6207992889067e-05 7.26429580634589e-06 -1.44741063659602e-06 4.95864220073113e-06 -3.73554291670829e-06 -3.66341760937499e-07 7.26429580634589e-06 3.99696929687829e-05 -1.26383871184174e-06 -1.83110728571654e-06 9.46283509915255e-07 4.03848759308611e-06 -1.44741063659602e-06 -1.26383871184174e-06 1.01111200120873e-05 -2.81241636391888e-07 9.51009192382921e-07 9.25286379199459e-07 4.95864220073113e-06 -1.83110728571654e-06 -2.81241636391888e-07 2.4014490823833e-05 -6.95121593798462e-06 1.55887228632893e-05 -3.73554291670829e-06 9.46283509915255e-07 9.51009192382921e-07 -6.95121593798462e-06 5.7159100077761e-05 7.46686319835497e-06 -3.66341760937499e-07 4.03848759308611e-06 9.25286379199459e-07 1.55887228632893e-05 7.46686319835497e-06 0.000188076441223459 1342 1342 0 0 0 1342 1342 0 0 0 0 0 0 0 0 0 0 0 2773 0 255 307 0 0 3283 +272 274 0.998053952415066 0.0369135420587344 0.0502563277741448 0.0591489592174086 -0.0373091209043443 0.99927956443533 0.00695568826807217 -0.2258851409599 -0.0499633622368357 -0.00881717157685046 0.998712130655964 0.0184480544234138 2.39713761015141e-05 9.59810338715671e-06 -5.82484382689744e-07 2.46695952550841e-06 -1.17953429734327e-06 2.77873016200048e-06 9.59810338715671e-06 2.10451888607919e-05 -1.49290456017691e-06 1.28551883999071e-06 -6.94482969615116e-07 2.64445026598861e-07 -5.82484382689744e-07 -1.49290456017691e-06 1.27066004562303e-05 1.1131044331542e-06 8.51413728880599e-06 -5.23310866677017e-07 2.46695952550841e-06 1.28551883999071e-06 1.1131044331542e-06 2.07385677774754e-05 -5.58000137934665e-06 1.09488132111023e-05 -1.17953429734327e-06 -6.94482969615116e-07 8.51413728880599e-06 -5.58000137934665e-06 7.47251860800627e-05 1.11531932271309e-05 2.77873016200048e-06 2.64445026598861e-07 -5.23310866677017e-07 1.09488132111023e-05 1.11531932271309e-05 9.5382142518376e-05 1463 1463 0 0 0 1506 1506 0 0 0 0 0 0 0 0 0 0 0 2752 0 287 325 0 0 3385 +274 276 0.997194914058869 0.0552078216228144 -0.050541070495087 0.0719722811169567 -0.0539160040139286 0.998191730971196 0.0265769210386938 -0.23149660654127 0.0519169325586159 -0.0237773979314482 0.998368302512311 0.0159626375686047 3.91474227003262e-05 1.63929278258188e-05 -1.89315221006294e-06 1.0041051011439e-05 -3.20168654118929e-06 7.72531800968374e-06 1.63929278258188e-05 2.54092011770244e-05 -2.91283519837377e-06 3.21854083195148e-06 -1.95726319343147e-06 7.60843854671715e-06 -1.89315221006294e-06 -2.91283519837377e-06 1.02743442310094e-05 -6.81648578717088e-07 -2.1232025482302e-06 -1.63357110077653e-06 1.0041051011439e-05 3.21854083195148e-06 -6.81648578717088e-07 2.52310833736297e-05 -7.21462210738445e-06 1.41014761242524e-05 -3.20168654118929e-06 -1.95726319343147e-06 -2.1232025482302e-06 -7.21462210738445e-06 4.02346879684359e-05 -3.94003111717974e-06 7.72531800968374e-06 7.60843854671715e-06 -1.63357110077653e-06 1.41014761242524e-05 -3.94003111717974e-06 7.26644992819981e-05 1423 1423 0 0 0 1493 1493 0 0 0 0 0 0 0 0 0 0 0 2714 0 303 347 0 0 3285 +274 277 0.995039282076936 0.0692186799519994 -0.071453491653785 0.097129974736582 -0.0675204165381934 0.997381192195915 0.0259181558827974 -0.350111688771387 0.0730603892292103 -0.020965013702805 0.997107139542245 -0.0155023001279694 3.64689057101135e-05 1.63709541923575e-05 -2.01623562858255e-06 1.18287688981222e-05 -3.6942189608382e-06 3.51326058786762e-05 1.63709541923575e-05 5.18386340631909e-05 -4.01644362115652e-06 6.69138822340608e-06 -1.16367106322409e-05 8.47761633945392e-06 -2.01623562858255e-06 -4.01644362115652e-06 1.19749115075158e-05 -5.39020386904937e-07 2.69760248608388e-06 -3.55837946001042e-06 1.18287688981222e-05 6.69138822340608e-06 -5.39020386904937e-07 3.37878591583568e-05 -1.30697139227736e-05 4.3258469097554e-05 -3.6942189608382e-06 -1.16367106322409e-05 2.69760248608388e-06 -1.30697139227736e-05 6.29976737417671e-05 -2.46077022566629e-05 3.51326058786762e-05 8.47761633945392e-06 -3.55837946001042e-06 4.3258469097554e-05 -2.46077022566629e-05 0.000245594319927987 723 723 0 0 0 811 811 0 0 0 0 0 0 0 0 0 0 0 2186 0 496 531 0 0 3330 +273 276 0.996415432586977 0.0702165904914624 -0.0471796155374471 0.105517124405477 -0.0691094130587484 0.997303155661594 0.0247043464617336 -0.350601194976118 0.0487870344372595 -0.0213552365283164 0.998580882624756 0.0143006544717865 2.64322398144201e-05 9.66647913344789e-06 -2.74673809830013e-06 6.49250019414081e-06 2.07230097372012e-07 4.05255885465476e-06 9.66647913344789e-06 2.24204450479148e-05 -1.97613642546968e-06 5.23065745829445e-06 -2.70489871870133e-06 2.11850553323166e-05 -2.74673809830013e-06 -1.97613642546968e-06 1.25547545671362e-05 -6.44780374158167e-06 5.11265160808076e-06 -3.04874032876715e-06 6.49250019414081e-06 5.23065745829445e-06 -6.44780374158167e-06 3.275778713547e-05 -2.26730167487326e-05 2.06914191014379e-05 2.07230097372012e-07 -2.70489871870133e-06 5.11265160808076e-06 -2.26730167487326e-05 7.73586017623766e-05 -1.62059650705506e-05 4.05255885465476e-06 2.11850553323166e-05 -3.04874032876715e-06 2.06914191014379e-05 -1.62059650705506e-05 0.000144907211016657 720 720 0 0 0 720 720 0 0 0 0 0 0 0 0 0 0 0 2381 0 408 452 0 0 3044 +272 275 0.996613824199553 0.0734730122697335 0.0369134376935289 0.0977204458587347 -0.0739436576525391 0.997195546340192 0.0115489329485488 -0.341903246065092 -0.0359613807758621 -0.0142393408308661 0.999251730178835 0.0174757018461812 2.15286577419383e-05 7.91030336190612e-06 -7.93469624231958e-07 2.88140936684187e-06 -3.78211305506902e-06 9.9526549238676e-07 7.91030336190612e-06 2.35282353624276e-05 -5.03182862368444e-07 4.79645767273705e-07 -2.58948883203706e-06 1.95236805035091e-06 -7.93469624231958e-07 -5.03182862368444e-07 1.07690435834954e-05 -1.85477627099037e-06 3.06809149508509e-07 -7.02911071731974e-07 2.88140936684187e-06 4.79645767273705e-07 -1.85477627099037e-06 2.26513365371057e-05 -1.04658740098531e-05 1.02986412398623e-05 -3.78211305506902e-06 -2.58948883203706e-06 3.06809149508509e-07 -1.04658740098531e-05 5.03109417847817e-05 -1.08802787528127e-05 9.9526549238676e-07 1.95236805035091e-06 -7.02911071731974e-07 1.02986412398623e-05 -1.08802787528127e-05 0.000104395774382597 919 919 0 0 0 943 943 0 0 0 0 0 0 0 0 0 0 0 2632 0 435 487 0 0 3285 +275 277 0.998731373524325 0.0308274205591031 -0.0398159977884232 0.0663032177629816 -0.0304910692077768 0.999494270710504 0.00902759743479472 -0.222922350740937 0.0400741592149117 -0.00780211244153371 0.99916624683016 0.00987502952354175 5.59905390330019e-05 2.55931995008339e-05 -8.03245558142448e-07 1.40453999782335e-05 3.81078178945467e-07 7.08625721289187e-05 2.55931995008339e-05 5.13500625776447e-05 -2.96738731498758e-06 1.09224485641363e-05 -7.96601677905126e-06 5.39340057785002e-05 -8.03245558142448e-07 -2.96738731498758e-06 1.10562432833195e-05 -1.53305184827096e-07 1.9385126050279e-06 -1.33748503329407e-06 1.40453999782335e-05 1.09224485641363e-05 -1.53305184827096e-07 3.61059307639979e-05 -7.70222618934955e-06 5.4672637550463e-05 3.81078178945467e-07 -7.96601677905126e-06 1.9385126050279e-06 -7.70222618934955e-06 6.03160286539546e-05 -2.51771924205083e-06 7.08625721289187e-05 5.39340057785002e-05 -1.33748503329407e-06 5.4672637550463e-05 -2.51771924205083e-06 0.000369303873810809 1506 1505 0 34 0 1578 1577 0 34 0 0 0 0 0 0 0 0 0 2650 0 262 297 0 0 3375 +273 247 0.986234783142746 -0.163815654784907 -0.0224807421312641 -0.811423434637027 0.16309140239007 0.986124729632103 -0.0309711490657337 2.89041804760316 0.0272423748197659 0.0268784087215681 0.999267433752735 0.0475277002851257 5.68583638608761e-05 3.02913294861187e-05 -3.79136390219537e-06 2.42735085877457e-06 -6.56956121854803e-06 -2.45778741939598e-06 3.02913294861187e-05 4.40844425066768e-05 -7.04717149353869e-07 4.03880140280661e-06 4.26059158463169e-06 4.63666904732431e-06 -3.79136390219537e-06 -7.04717149353869e-07 1.19847906377869e-05 4.98683799873961e-06 4.08483546750632e-06 1.04063695933213e-06 2.42735085877457e-06 4.03880140280661e-06 4.98683799873961e-06 3.00323006295652e-05 3.31266631055869e-06 6.11060651924664e-05 -6.56956121854803e-06 4.26059158463169e-06 4.08483546750632e-06 3.31266631055869e-06 5.74820826500349e-05 2.30913589384342e-05 -2.45778741939598e-06 4.63666904732431e-06 1.04063695933213e-06 6.11060651924664e-05 2.30913589384342e-05 0.00066319962123714 0 0 0 0 48 0 0 0 0 48 0 0 0 0 0 479 593 0 2172 958 0 0 0 0 1346 +274 278 0.994799559494471 0.0880592636571146 -0.0511800988058171 0.129062904139506 -0.0869199851120913 0.995924240468999 0.0240795231340313 -0.476215980104975 0.0530919261067089 -0.0195057255803342 0.998399105594483 -0.00741994188149469 5.19056806437148e-05 3.41290370100985e-05 -2.71423910807057e-06 -6.78005820306403e-08 1.0590446754779e-06 -9.64137936095172e-06 3.41290370100985e-05 6.46729180797074e-05 -5.8397856502806e-06 -3.14101853348547e-07 -7.20515734443347e-06 -1.76452498247326e-05 -2.71423910807057e-06 -5.8397856502806e-06 1.07419875259645e-05 2.99049460056533e-06 3.59858147943641e-06 4.15007786713163e-07 -6.78005820306403e-08 -3.14101853348547e-07 2.99049460056533e-06 3.44865509862764e-05 -1.22764320813319e-06 3.68717347643136e-05 1.0590446754779e-06 -7.20515734443347e-06 3.59858147943641e-06 -1.22764320813319e-06 5.51256521459567e-05 1.5085602007256e-06 -9.64137936095172e-06 -1.76452498247326e-05 4.15007786713163e-07 3.68717347643136e-05 1.5085602007256e-06 0.00026976639147291 380 380 0 0 0 451 451 0 0 0 0 0 0 0 0 0 0 0 1909 0 737 766 0 0 3297 +275 278 0.998178973408989 0.0488855435203512 -0.0353403548213244 0.0994957387838765 -0.0480781351713387 0.998570686507562 0.0233468834378843 -0.349470005599292 0.036431167461718 -0.021605269786224 0.999102588503724 -0.0214709179200334 4.94088234793065e-05 9.4539214774271e-06 -4.07814738404432e-06 9.753684527869e-06 -7.57421435151055e-06 3.0641870265901e-05 9.4539214774271e-06 6.19296179216707e-05 -1.22324152805784e-06 3.53358228749848e-06 -5.34453115995276e-06 5.742854940958e-06 -4.07814738404432e-06 -1.22324152805784e-06 1.10728567452512e-05 -1.82006559752015e-06 3.57165664246207e-06 -5.69625247112847e-06 9.753684527869e-06 3.53358228749848e-06 -1.82006559752015e-06 3.12867267992718e-05 -3.9215945367336e-06 3.31648370447684e-05 -7.57421435151055e-06 -5.34453115995276e-06 3.57165664246207e-06 -3.9215945367336e-06 5.14816963207466e-05 -2.14049723427575e-05 3.0641870265901e-05 5.742854940958e-06 -5.69625247112847e-06 3.31648370447684e-05 -2.14049723427575e-05 0.000234759758934733 977 986 0 113 0 1065 1074 0 113 0 0 0 0 0 0 0 0 0 2212 0 461 490 0 0 3219 +275 279 0.998368178194109 0.0308529531303973 -0.0480528464558452 0.129693082233238 -0.0296424341219605 0.999230027432301 0.0257036646602972 -0.461500979543528 0.0488088810433179 -0.0242373175243732 0.998514018715071 -0.0155260341663289 2.76255669244116e-05 1.87099571090931e-05 -2.50337704858903e-07 4.36642769866628e-06 3.57321898811691e-06 -3.83102897042375e-06 1.87099571090931e-05 3.13375228117417e-05 -1.1284495037854e-07 3.46091858576269e-06 8.27597150481195e-06 5.84077286520988e-07 -2.50337704858903e-07 -1.1284495037854e-07 1.25366609300968e-05 -1.35586811612e-06 3.91772840216217e-06 -3.37629744461694e-06 4.36642769866628e-06 3.46091858576269e-06 -1.35586811612e-06 3.41524643601184e-05 -9.31936523402658e-06 1.80178615104443e-05 3.57321898811691e-06 8.27597150481195e-06 3.91772840216217e-06 -9.31936523402658e-06 4.99451275509041e-05 -8.57098642489642e-06 -3.83102897042375e-06 5.84077286520988e-07 -3.37629744461694e-06 1.80178615104443e-05 -8.57098642489642e-06 0.000155342584258467 552 567 0 115 0 651 666 0 115 0 0 0 0 0 0 0 0 0 1994 0 574 608 0 0 3277 +274 248 0.986140940616386 -0.157029898948851 -0.0535505002436302 -0.868967459171913 0.15564763248064 0.987383932249506 -0.0290995676715927 2.87919542234539 0.0574444056754092 0.0203612664541196 0.998141051698097 0.0233242586629085 5.10583161105016e-05 3.5177442922595e-05 -5.08921352512157e-06 5.8386800032311e-06 -1.04883471925233e-05 2.79793148201033e-05 3.5177442922595e-05 5.12911210569862e-05 -1.06697667513174e-06 1.85250107898324e-06 1.64915292099072e-06 -6.13986052451383e-06 -5.08921352512157e-06 -1.06697667513174e-06 1.21281179092622e-05 2.69018021241173e-06 2.49673671847899e-06 -7.5476483095342e-07 5.8386800032311e-06 1.85250107898324e-06 2.69018021241173e-06 3.04308365782409e-05 -1.80631925321675e-06 3.17160629602984e-05 -1.04883471925233e-05 1.64915292099072e-06 2.49673671847899e-06 -1.80631925321675e-06 5.32346345964942e-05 -8.54778256772369e-06 2.79793148201033e-05 -6.13986052451383e-06 -7.5476483095342e-07 3.17160629602984e-05 -8.54778256772369e-06 0.000260271815618779 0 0 0 0 49 0 0 0 0 58 0 0 0 0 0 620 719 0 2241 912 0 0 0 0 1343 +277 280 0.997808610705875 -0.0517387424497601 -0.0412441381402209 0.108218500852738 0.0510445635077825 0.998539324442572 -0.0177107334142854 -0.33111002557215 0.0421002249104704 0.015566633274068 0.998992117582015 0.0467343178597258 4.84262132430773e-05 -2.07982876028735e-05 -2.86383243296492e-06 5.51477115755227e-06 -7.08433142058877e-06 2.43567993196879e-05 -2.07982876028735e-05 8.32573641911416e-05 -1.00416432962364e-06 6.45519674252087e-06 1.3462278666802e-05 -1.26908443078048e-05 -2.86383243296492e-06 -1.00416432962364e-06 1.27998181084081e-05 -2.0208070237818e-07 1.92062408080862e-06 -6.14261647448353e-06 5.51477115755227e-06 6.45519674252087e-06 -2.0208070237818e-07 3.20057399619817e-05 -8.70144017378038e-06 3.49340478671478e-05 -7.08433142058877e-06 1.3462278666802e-05 1.92062408080862e-06 -8.70144017378038e-06 4.61692368575711e-05 -4.11863337646393e-06 2.43567993196879e-05 -1.26908443078048e-05 -6.14261647448353e-06 3.49340478671478e-05 -4.11863337646393e-06 0.00018015413734633 1302 1302 0 1 0 1349 1349 0 1 0 0 0 0 0 0 0 0 0 2255 0 129 172 0 0 3323 +276 278 0.999489711744447 0.0317355046076442 -0.00362958183555496 0.0632875568667258 -0.0317342889220106 0.999496263724631 0.000392054992917714 -0.219071634704033 0.00364019554655416 -0.000276672733223715 0.999993336192088 -0.0122803152954292 3.53258447846166e-05 1.03716881475426e-07 -2.75105926632008e-06 5.31048642752447e-06 -4.61284416346572e-06 2.86470180404203e-06 1.03716881475426e-07 6.60250171436556e-05 -6.5229741375607e-07 1.38890738091998e-05 3.8666578808123e-06 -8.10725519733231e-06 -2.75105926632008e-06 -6.5229741375607e-07 1.11583566613179e-05 -1.55167620593587e-06 2.21833733387306e-06 -1.01177832860949e-06 5.31048642752447e-06 1.38890738091998e-05 -1.55167620593587e-06 3.1298535950383e-05 -1.47413232003987e-05 5.8705003171667e-06 -4.61284416346572e-06 3.8666578808123e-06 2.21833733387306e-06 -1.47413232003987e-05 6.00434598868391e-05 4.72381595713465e-06 2.86470180404203e-06 -8.10725519733231e-06 -1.01177832860949e-06 5.8705003171667e-06 4.72381595713465e-06 0.000113602426691532 1390 1408 0 168 0 1452 1470 0 181 0 0 0 0 0 0 0 0 0 2708 0 239 268 0 0 3290 +277 281 0.994817056405556 -0.071181201105736 -0.0726103359979084 0.137149468092795 0.0702497292118364 0.997412005903606 -0.0153057513702416 -0.456739327146406 0.0735119026433682 0.0101255660823855 0.997242935839238 0.031314746967416 2.55199533683433e-05 1.50137906210305e-05 -1.19442566661758e-06 2.61910049468454e-06 -1.2663692547657e-07 -1.7108380220465e-06 1.50137906210305e-05 2.60833113653827e-05 -3.2369429988215e-06 -1.38907766929997e-06 1.83377294790675e-06 1.27939881743065e-06 -1.19442566661758e-06 -3.2369429988215e-06 1.14287203942673e-05 1.33690880966872e-06 -6.34163747316116e-07 -2.77017205483948e-06 2.61910049468454e-06 -1.38907766929997e-06 1.33690880966872e-06 2.56561280294971e-05 -2.815644958567e-06 1.70838607575095e-05 -1.2663692547657e-07 1.83377294790675e-06 -6.34163747316116e-07 -2.815644958567e-06 4.13483780778023e-05 -1.36822556352716e-06 -1.7108380220465e-06 1.27939881743065e-06 -2.77017205483948e-06 1.70838607575095e-05 -1.36822556352716e-06 0.000105120204885486 1258 1250 0 0 0 1315 1307 0 0 0 0 0 0 0 0 0 0 0 1833 0 246 290 0 0 3311 +278 280 0.996392623425535 -0.0699702526270112 -0.048019826431298 0.0747830663158208 0.0688175452256937 0.997309563376449 -0.0252543118493977 -0.214486291908262 0.0496576827116344 0.0218586034592621 0.998527073244647 0.0158142513849649 6.31141349596435e-05 -4.98195330089133e-05 -5.76633521637647e-06 8.55664650591214e-06 -6.6480187314666e-06 4.11919669180652e-05 -4.98195330089133e-05 0.000104160265775309 4.23663042343174e-06 2.52416849019254e-07 1.05624606145733e-05 -4.38555210342011e-05 -5.76633521637647e-06 4.23663042343174e-06 1.1086859988132e-05 -2.2710774715585e-06 2.45796677134793e-07 -5.00626943453391e-06 8.55664650591214e-06 2.52416849019254e-07 -2.2710774715585e-06 2.82494272936498e-05 -5.15765299103293e-06 2.46791518330356e-05 -6.6480187314666e-06 1.05624606145733e-05 2.45796677134793e-07 -5.15765299103293e-06 3.80570880612639e-05 2.91229167115253e-06 4.11919669180652e-05 -4.38555210342011e-05 -5.00626943453391e-06 2.46791518330356e-05 2.91229167115253e-06 0.000164107204556419 1691 1692 0 0 0 1700 1734 0 0 1 0 0 0 0 0 0 0 0 2402 0 0 12 0 0 3255 +276 435 -0.929237256123945 0.323133067826988 0.179173497783465 0.0103647563248772 -0.303827951510839 -0.944208117814975 0.127120439477797 -3.00841318667043 0.210253888696427 0.0636871315810363 0.975570218671629 0.568904613142634 4.33653425735427e-05 2.29169274562853e-05 5.87331883384298e-06 2.94779964470163e-06 -2.05063258441588e-05 1.31264187086776e-05 2.29169274562853e-05 8.16426551489743e-05 2.80846837779101e-06 1.07041721917141e-05 -1.38606149871783e-05 -4.29989391177349e-06 5.87331883384298e-06 2.80846837779101e-06 2.17007972686415e-05 -9.29681154018129e-06 -3.28960757151006e-06 7.62109027511807e-06 2.94779964470163e-06 1.07041721917141e-05 -9.29681154018129e-06 3.71519873045412e-05 -4.13536198709489e-06 1.38414203119035e-05 -2.05063258441588e-05 -1.38606149871783e-05 -3.28960757151006e-06 -4.13536198709489e-06 0.000201634229834123 -6.54208024715036e-05 1.31264187086776e-05 -4.29989391177349e-06 7.62109027511807e-06 1.38414203119035e-05 -6.54208024715036e-05 0.000242200161438137 0 0 0 0 47 0 0 0 0 47 0 0 0 0 0 0 0 0 0 517 195 195 0 1161 0 +276 434 -0.951070336997956 0.241555814749514 0.192655138637135 0.00829376475448712 -0.229537586190164 -0.969773168030517 0.0827798229887369 -2.98419997898787 0.206827731720358 0.0345078386566297 0.977768632378161 0.682748034887106 4.96033189966397e-05 1.88264361878584e-05 5.16541592591266e-06 -2.57546211963015e-06 -2.66109204827964e-05 -5.82665473425967e-07 1.88264361878584e-05 9.59083784110414e-05 5.54953872090968e-06 3.89069566290402e-06 2.1317120115866e-05 1.33997869719182e-05 5.16541592591266e-06 5.54953872090968e-06 2.05794029656514e-05 -3.62629869889415e-06 -1.99342086567686e-06 9.03447915771221e-06 -2.57546211963015e-06 3.89069566290402e-06 -3.62629869889415e-06 2.6146718588946e-05 4.52773942587332e-06 1.33962754957056e-05 -2.66109204827964e-05 2.1317120115866e-05 -1.99342086567686e-06 4.52773942587332e-06 0.000128347817203571 7.56435952355767e-06 -5.82665473425967e-07 1.33997869719182e-05 9.03447915771221e-06 1.33962754957056e-05 7.56435952355767e-06 0.000207695209372449 0 0 0 0 180 0 0 0 0 187 0 0 0 0 0 0 0 0 0 487 239 239 0 1019 0 +275 249 0.983839751284431 -0.178586123590163 -0.0128972963689191 -0.99465143743002 0.178364710632079 0.983823347996706 -0.0166628310225687 2.85185392084136 0.0156644116941342 0.0140931329941601 0.99977798025796 0.00393933717136544 5.02648658717203e-05 2.63499364647397e-05 -1.38709181938246e-06 4.24300140089038e-06 -5.1554291046389e-06 1.81746429082499e-05 2.63499364647397e-05 4.20919235397438e-05 1.36259426892674e-06 1.83830112912135e-06 6.11875261248793e-06 -1.67734048189181e-05 -1.38709181938246e-06 1.36259426892674e-06 1.24011763247689e-05 3.14925618994771e-06 3.55071674214996e-06 -9.66986349874838e-06 4.24300140089038e-06 1.83830112912135e-06 3.14925618994771e-06 3.3008619361895e-05 -7.25138285334323e-07 3.39705336255839e-05 -5.1554291046389e-06 6.11875261248793e-06 3.55071674214996e-06 -7.25138285334323e-07 5.27959589653759e-05 -4.41012478317356e-05 1.81746429082499e-05 -1.67734048189181e-05 -9.66986349874838e-06 3.39705336255839e-05 -4.41012478317356e-05 0.000364663023914352 0 0 0 0 58 0 0 0 0 61 0 0 0 0 0 689 789 0 2183 874 0 0 0 0 1498 +278 281 0.993064709251939 -0.0891180468859717 -0.0766841375878447 0.110066988947889 0.0878769320100957 0.995942089778454 -0.0194164525137315 -0.335899055308332 0.0781033165675746 0.012543027025193 0.99686636236468 0.044185645349387 6.38499658348866e-05 -6.62449207815417e-06 -1.09826184125609e-06 1.27660059367766e-05 -9.78986905879325e-06 2.72295233662963e-05 -6.62449207815417e-06 6.90026360101497e-05 -9.17662212328238e-07 1.51670440822582e-07 -4.89074287926819e-06 -9.98705976256775e-06 -1.09826184125609e-06 -9.17662212328238e-07 1.27724120601213e-05 -3.77884906861511e-07 4.23096864662363e-06 -2.22877775413371e-06 1.27660059367766e-05 1.51670440822582e-07 -3.77884906861511e-07 2.67463238298466e-05 -9.15703420565749e-06 1.67591694907435e-05 -9.78986905879325e-06 -4.89074287926819e-06 4.23096864662363e-06 -9.15703420565749e-06 5.90431174397878e-05 -6.70026442246832e-06 2.72295233662963e-05 -9.98705976256775e-06 -2.22877775413371e-06 1.67591694907435e-05 -6.70026442246832e-06 0.000127206600174294 1692 1692 0 0 0 1738 1739 0 0 0 0 0 0 0 0 0 0 0 1851 0 37 80 0 0 3281 +278 434 -0.943282471462542 0.271865128393378 0.190545351544379 0.031403461141165 -0.257743180503629 -0.961449461983106 0.0958299794232977 -2.75389987395918 0.209252555385575 0.0412829748933824 0.976989807545892 0.720710951706713 6.51547461025296e-05 -9.86882806189596e-06 -2.58571762165481e-06 5.21477890756956e-06 -3.45926599492157e-05 3.23542678612341e-05 -9.86882806189596e-06 8.15535787473149e-05 7.72939182494654e-06 1.61639263084514e-06 3.2810138590763e-05 -4.49208678519401e-05 -2.58571762165481e-06 7.72939182494654e-06 2.17577642995895e-05 -3.26042605921672e-07 6.6416075707159e-06 -5.26315090869073e-06 5.21477890756956e-06 1.61639263084514e-06 -3.26042605921672e-07 2.89370379805204e-05 -7.14843741857547e-06 2.16041047786936e-05 -3.45926599492157e-05 3.2810138590763e-05 6.6416075707159e-06 -7.14843741857547e-06 0.00011605097419756 -2.67451911915695e-05 3.23542678612341e-05 -4.49208678519401e-05 -5.26315090869073e-06 2.16041047786936e-05 -2.67451911915695e-05 0.000272396929172757 0 0 0 0 135 0 0 0 0 134 0 0 0 0 0 0 0 0 0 617 115 115 0 1069 0 +276 280 0.997783504508716 -0.0380268375038159 -0.0546080375014763 0.13181010244315 0.0363844561846775 0.998864297385457 -0.0307617742791652 -0.442305363936098 0.0557157920023537 0.0287067071973678 0.998033904976898 0.00723862629101954 3.05235364592742e-05 2.00305770597801e-05 -2.86796598561556e-06 9.73911499123021e-06 -5.77134790923943e-06 1.81112534485101e-05 2.00305770597801e-05 3.92284543697954e-05 -1.01603852483779e-06 8.33123161522433e-06 2.13525253216909e-06 5.19937972025202e-06 -2.86796598561556e-06 -1.01603852483779e-06 1.20152532263752e-05 -4.49268728068012e-06 6.627771123955e-06 -5.41505769551039e-06 9.73911499123021e-06 8.33123161522433e-06 -4.49268728068012e-06 3.75295477564996e-05 -2.01705776744097e-05 2.75038607751468e-05 -5.77134790923943e-06 2.13525253216909e-06 6.627771123955e-06 -2.01705776744097e-05 6.83464581577035e-05 -7.61367424962157e-06 1.81112534485101e-05 5.19937972025202e-06 -5.41505769551039e-06 2.75038607751468e-05 -7.61367424962157e-06 0.000158582426889574 839 839 0 40 0 922 922 0 30 0 0 0 0 0 0 0 0 0 2114 0 339 382 0 0 3272 +277 434 -0.947449601331424 0.255520379058192 0.192480099810042 0.0198953183609425 -0.241837725372392 -0.965953518786211 0.0919147111796793 -2.86762953916165 0.209412911549487 0.0405356069461688 0.976986743536407 0.719258196164959 6.99330005119924e-05 -1.18228910400628e-05 1.57302386924823e-06 -1.88366795331063e-06 -2.82281712439332e-05 4.83609692316225e-05 -1.18228910400628e-05 0.000149603987715022 6.73850360865579e-06 1.63332728701311e-05 7.27823339060384e-05 -3.7802579664214e-05 1.57302386924823e-06 6.73850360865579e-06 2.15215680012346e-05 -3.50730440886287e-06 9.19261589230313e-06 -2.88067897310411e-06 -1.88366795331063e-06 1.63332728701311e-05 -3.50730440886287e-06 2.57337773632188e-05 8.69021616206051e-06 1.18955639430195e-05 -2.82281712439332e-05 7.27823339060384e-05 9.19261589230313e-06 8.69021616206051e-06 0.000126464554029518 -2.47289378381462e-06 4.83609692316225e-05 -3.7802579664214e-05 -2.88067897310411e-06 1.18955639430195e-05 -2.47289378381462e-06 0.00034390476961385 0 0 0 0 189 0 0 0 0 187 0 0 0 0 0 0 0 0 0 524 121 121 0 1046 0 +276 279 0.999794811334804 0.0140810592217651 -0.0145622456783651 0.0964603096299436 -0.014050184141505 0.999898826052364 0.00222035688420745 -0.339725274374329 0.0145920373352633 -0.00201529905884726 0.999891499621889 -0.0184279252480726 3.01780767537858e-05 2.30475717925832e-05 -6.94324366228982e-07 5.77623782992112e-07 4.50982384597422e-06 -2.59147315955824e-05 2.30475717925832e-05 3.04675890535817e-05 -3.08873643800787e-06 4.27165268227614e-06 5.06153622623751e-07 -1.07735126977087e-05 -6.94324366228982e-07 -3.08873643800787e-06 1.0686680947698e-05 -7.99499457710755e-07 7.00190086466666e-07 -1.3608808101767e-08 5.77623782992112e-07 4.27165268227614e-06 -7.99499457710755e-07 3.23741151528663e-05 -1.53002900062717e-05 3.25994251659047e-05 4.50982384597422e-06 5.06153622623751e-07 7.00190086466666e-07 -1.53002900062717e-05 4.2619831191226e-05 -1.43594560463413e-05 -2.59147315955824e-05 -1.07735126977087e-05 -1.3608808101767e-08 3.25994251659047e-05 -1.43594560463413e-05 0.000248220403387783 976 1002 0 164 0 1047 1073 0 177 0 0 0 0 0 0 0 0 0 2339 0 337 371 0 0 3287 +278 435 -0.918446292448626 0.352061764494584 0.180302306885775 0.0447636509827959 -0.331812575842197 -0.933881649134123 0.133287208401619 -2.79713112089625 0.215306345471605 0.0625905695092353 0.974538659165541 0.620187638049568 6.23796715165499e-05 -1.87540739153234e-05 5.01490973941666e-07 -1.42692009787577e-06 -3.02627793929327e-05 1.16331591871253e-05 -1.87540739153234e-05 0.000160922379217473 1.50410852905226e-05 1.29014251406419e-05 6.05313946183028e-05 1.53271742358761e-05 5.01490973941666e-07 1.50410852905226e-05 2.31838690174819e-05 -4.92729437256827e-06 6.84548773586745e-06 3.43543313108458e-06 -1.42692009787577e-06 1.29014251406419e-05 -4.92729437256827e-06 3.35308425846933e-05 7.52992064069963e-06 5.73647513946082e-06 -3.02627793929327e-05 6.05313946183028e-05 6.84548773586745e-06 7.52992064069963e-06 0.00016558116127647 -1.41233844010756e-05 1.16331591871253e-05 1.53271742358761e-05 3.43543313108458e-06 5.73647513946082e-06 -1.41233844010756e-05 0.000205730732606977 0 0 0 0 41 0 0 0 0 41 0 0 0 0 0 0 0 0 0 537 77 77 0 1161 0 +277 279 0.999998555005673 -0.000787058393949517 0.00150682635047011 0.0642394666551571 0.000769841556627059 0.9999348061179 0.0113925790729927 -0.220170792337874 -0.00151569473959881 -0.0113914025932374 0.999933967128037 -0.00954161040467043 2.87952336800705e-05 2.0665523074824e-05 -2.84304205851132e-06 2.54067915365313e-06 -5.35568846194014e-07 1.05364277262161e-05 2.0665523074824e-05 3.30787285163886e-05 -4.48354161185481e-06 3.85177919410418e-06 -1.06356055810838e-06 8.93012383707599e-06 -2.84304205851132e-06 -4.48354161185481e-06 1.08410349128619e-05 -6.68611093283678e-07 -5.97758903115456e-07 -1.91515027789748e-06 2.54067915365313e-06 3.85177919410418e-06 -6.68611093283678e-07 2.55696922052994e-05 -1.3563928018015e-05 1.80478050807632e-05 -5.35568846194014e-07 -1.06356055810838e-06 -5.97758903115456e-07 -1.3563928018015e-05 3.74612510136547e-05 -3.20218572877693e-06 1.05364277262161e-05 8.93012383707599e-06 -1.91515027789748e-06 1.80478050807632e-05 -3.20218572877693e-06 0.000117123043383629 1374 1395 0 106 0 1414 1440 0 123 0 0 0 0 0 0 0 9 0 2597 0 156 190 0 0 3476 +278 436 -0.899796729525253 0.403776970899021 0.165317885624241 0.0538242878601936 -0.394628602305333 -0.914772377101123 0.0863699272623322 -2.82252263355524 0.186102422816572 0.0124762119400134 0.982451134844593 0.506263787760213 0.000117352481559276 2.02345069465775e-05 -5.14050693451041e-08 3.98200989328956e-06 -1.06140241389458e-05 0.00019253905903836 2.02345069465775e-05 7.87299524017636e-05 1.77448067622061e-06 1.14267439896928e-05 -6.2913588273881e-06 -1.63091058204917e-05 -5.14050693451041e-08 1.77448067622061e-06 2.29597705155695e-05 -1.09934377030308e-05 -3.23183039551743e-06 -1.71261842565619e-05 3.98200989328956e-06 1.14267439896928e-05 -1.09934377030308e-05 4.05701862137246e-05 7.94184976211991e-06 3.90352634799017e-05 -1.06140241389458e-05 -6.2913588273881e-06 -3.23183039551743e-06 7.94184976211991e-06 0.000210431945342052 1.20468348302968e-05 0.00019253905903836 -1.63091058204917e-05 -1.71261842565619e-05 3.90352634799017e-05 1.20468348302968e-05 0.00101176209846869 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 533 32 32 0 1356 0 +278 433 -0.977151302346212 0.170389205335697 0.127054519904532 0.0252284292952204 -0.154160306188213 -0.979690993527893 0.128219176398406 -2.75949504544531 0.146321332412803 0.105702771512382 0.983573582288353 0.791255700321342 6.75372385680909e-05 1.74856149980504e-05 3.62184803993163e-07 6.73422268629001e-06 -1.03795256464736e-05 -9.59233010595493e-06 1.74856149980504e-05 8.92273697312874e-05 -7.05613098595834e-06 9.32799286319753e-06 1.60031024242147e-06 -3.1462268710287e-05 3.62184803993163e-07 -7.05613098595834e-06 2.05932205730069e-05 2.66899513623191e-07 -2.97066831701918e-06 7.95612758475108e-06 6.73422268629001e-06 9.32799286319753e-06 2.66899513623191e-07 3.24381667111872e-05 -1.5596712622127e-05 -1.40688555243567e-05 -1.03795256464736e-05 1.60031024242147e-06 -2.97066831701918e-06 -1.5596712622127e-05 0.000111644751147535 2.80993593479568e-05 -9.59233010595493e-06 -3.1462268710287e-05 7.95612758475108e-06 -1.40688555243567e-05 2.80993593479568e-05 0.000190276790949218 0 0 0 0 323 0 0 0 0 323 0 0 0 0 0 0 0 0 0 634 137 137 0 952 0 +278 282 0.996539804337203 -0.0733479795206556 -0.0390959367685018 0.129849151262868 0.0731594248583661 0.997300775968567 -0.00623384366874495 -0.458094617896105 0.0394476479141949 0.00335203710163717 0.999216016145311 0.0135236968151906 3.38656535912764e-05 2.04417295750609e-05 -5.50345512446134e-07 7.8831949487591e-06 -3.00639260746706e-06 2.30432529870992e-06 2.04417295750609e-05 3.90070243912805e-05 -2.23714469273839e-06 4.4369303116942e-06 -3.39452902137021e-06 1.58351672938711e-05 -5.50345512446134e-07 -2.23714469273839e-06 1.14117315210943e-05 -8.74939724222203e-07 1.55921418389514e-06 -4.34704414561484e-06 7.8831949487591e-06 4.4369303116942e-06 -8.74939724222203e-07 2.89274059850023e-05 -1.0443132650863e-05 2.06259228856259e-05 -3.00639260746706e-06 -3.39452902137021e-06 1.55921418389514e-06 -1.0443132650863e-05 4.77158476399539e-05 -3.17769178839727e-06 2.30432529870992e-06 1.58351672938711e-05 -4.34704414561484e-06 2.06259228856259e-05 -3.17769178839727e-06 0.000132050910618081 1533 1533 0 0 0 1591 1591 0 0 0 0 0 0 0 0 0 0 0 1684 0 223 262 0 0 3290 +279 282 0.99815501973709 -0.055138087937911 -0.0254233717708779 0.0852582180332502 0.054865204602268 0.998429719088747 -0.011309525379799 -0.344560576942686 0.0260070355404138 0.00989380103480167 0.999612798439217 0.0057644436052305 3.44799792374118e-05 -7.83721295999284e-06 -1.20137173440991e-06 2.55300781732017e-06 1.06397082578574e-06 5.69652327295048e-07 -7.83721295999284e-06 6.01656212653005e-05 9.79623889545322e-07 -2.66593560932426e-06 2.20749181741816e-06 -5.93900214708132e-06 -1.20137173440991e-06 9.79623889545322e-07 1.19005966935898e-05 4.60241128594803e-08 1.95261804159525e-06 -4.33118107662665e-07 2.55300781732017e-06 -2.66593560932426e-06 4.60241128594803e-08 2.57359721718139e-05 -8.16732289719959e-06 1.62226439151157e-05 1.06397082578574e-06 2.20749181741816e-06 1.95261804159525e-06 -8.16732289719959e-06 4.52141337170876e-05 3.66272821741323e-06 5.69652327295048e-07 -5.93900214708132e-06 -4.33118107662665e-07 1.62226439151157e-05 3.66272821741323e-06 0.000137361218629529 1838 1838 0 0 0 1892 1892 0 0 0 0 0 0 0 0 0 0 0 1921 0 154 193 0 0 3345 +279 434 -0.94749671710872 0.254579960669779 0.193491639854469 -0.0541717418190214 -0.242661288490456 -0.966520090738917 0.0833931248136672 -2.64771843064286 0.208243775744557 0.0320617813511706 0.977551314274724 0.675699886958744 8.25501726628923e-05 -7.87697518467437e-05 -1.55745900322446e-06 -4.21904907287583e-06 -7.27448122462305e-05 4.0101526100123e-05 -7.87697518467437e-05 0.000303601141265624 1.68503508043576e-05 1.35092695887779e-05 0.000186051015641955 -3.42972989110587e-05 -1.55745900322446e-06 1.68503508043576e-05 2.14813691433495e-05 -2.01733292895256e-06 1.09270454684885e-05 -4.37973001654777e-06 -4.21904907287583e-06 1.35092695887779e-05 -2.01733292895256e-06 2.57419128855836e-05 9.92299209931095e-07 1.18218412741521e-05 -7.27448122462305e-05 0.000186051015641955 1.09270454684885e-05 9.92299209931095e-07 0.000248035558366039 -3.49243538343596e-05 4.0101526100123e-05 -3.42972989110587e-05 -4.37973001654777e-06 1.18218412741521e-05 -3.49243538343596e-05 0.00027784465754216 0 0 0 0 132 0 0 0 0 133 0 0 0 0 0 0 0 0 0 670 116 116 0 1214 0 +279 283 0.997039691750463 -0.000597391791148212 -0.0768862549301892 0.118629918620481 -0.00166017093578187 0.999569427640014 -0.0292951047084424 -0.47021831647085 0.0768706504890271 0.0293360264940992 0.996609402244897 0.0046837472476243 2.97898690376256e-05 1.9141920473863e-05 -2.62088977333034e-06 5.58875275703385e-06 -5.57744139573609e-06 3.43799393141797e-06 1.9141920473863e-05 3.62279454348243e-05 -3.54575311834185e-06 4.74456944132506e-06 2.52272613711556e-06 1.79062809538973e-05 -2.62088977333034e-06 -3.54575311834185e-06 1.17155141066386e-05 -1.83243633764372e-06 5.33597948222309e-07 -1.13980824680148e-06 5.58875275703385e-06 4.74456944132506e-06 -1.83243633764372e-06 2.81732255723881e-05 -3.19705895632386e-06 1.41511830415445e-05 -5.57744139573609e-06 2.52272613711556e-06 5.33597948222309e-07 -3.19705895632386e-06 4.51717105380464e-05 1.37361429958274e-05 3.43799393141797e-06 1.79062809538973e-05 -1.13980824680148e-06 1.41511830415445e-05 1.37361429958274e-05 0.000118846861732131 1590 1590 0 0 0 1648 1648 0 0 0 0 0 0 0 0 0 0 0 1721 0 467 489 0 0 3308 +279 432 -0.986314765855113 0.0310111282149734 0.161930517763047 -0.0538916369988197 -0.010941631245653 -0.992298098852562 0.123388669330998 -2.65244649685043 0.164509766767381 0.119928282487597 0.979057579357679 0.824102868929614 6.03265369020848e-05 -5.77088550993134e-06 -5.31215925666074e-06 6.94859772616311e-06 -2.84351551831518e-05 -1.31700603808067e-05 -5.77088550993134e-06 0.00010553083099684 -2.96030959155601e-07 5.83670085008263e-06 2.44805537544098e-05 -5.57126216857744e-06 -5.31215925666074e-06 -2.96030959155601e-07 2.23931964467017e-05 3.22276276114134e-07 8.95004771121933e-06 1.1433803605068e-05 6.94859772616311e-06 5.83670085008263e-06 3.22276276114134e-07 4.55765364968743e-05 -3.23910939511311e-05 3.68126008166421e-06 -2.84351551831518e-05 2.44805537544098e-05 8.95004771121933e-06 -3.23910939511311e-05 0.000136724680930811 2.70210827386406e-06 -1.31700603808067e-05 -5.57126216857744e-06 1.1433803605068e-05 3.68126008166421e-06 2.70210827386406e-06 0.000178152443016808 0 0 0 0 449 0 0 0 0 460 0 0 0 0 0 0 0 0 0 634 137 137 0 686 6 +279 281 0.995201024890404 -0.0710797006525977 -0.0672502506480529 0.0662324834767464 0.0693580926394847 0.997209941996783 -0.0276004813034938 -0.216434796479985 0.069024452496934 0.0228036781662293 0.997354308768749 0.037551389406209 5.83274416758407e-05 -3.31854788667196e-05 -4.15727926832975e-06 3.62046568769098e-06 -4.66928806000484e-06 2.70241659525732e-05 -3.31854788667196e-05 8.82288605107138e-05 -1.55071798560165e-06 7.54668788095427e-06 -7.84932246238994e-07 -6.69472297064764e-06 -4.15727926832975e-06 -1.55071798560165e-06 1.32021696294618e-05 -3.07522833815684e-06 1.80571812896104e-06 -4.10974070825481e-06 3.62046568769098e-06 7.54668788095427e-06 -3.07522833815684e-06 3.06781684748401e-05 -6.87648329469308e-06 1.92524863817814e-05 -4.66928806000484e-06 -7.84932246238994e-07 1.80571812896104e-06 -6.87648329469308e-06 4.856510079638e-05 3.45152883475593e-06 2.70241659525732e-05 -6.69472297064764e-06 -4.10974070825481e-06 1.92524863817814e-05 3.45152883475593e-06 0.000142048300586498 1984 1987 0 0 0 2003 2030 0 0 7 0 0 0 0 0 0 0 0 2153 0 2 20 0 0 3308 +279 433 -0.979343348226947 0.153564418717743 0.13154685700356 -0.0583491864704787 -0.138477755316243 -0.983420935837847 0.117077641923589 -2.64941464576358 0.147344893247809 0.0964428963672034 0.984372008020391 0.75875884080146 4.16718491024443e-05 8.09134004278796e-06 3.32411317502966e-06 6.17620160775263e-06 -1.17380573756183e-05 -2.66479842322595e-05 8.09134004278796e-06 7.39244974784653e-05 -4.73501241321308e-07 -7.15738076595491e-06 2.98380235543829e-05 4.99638669805207e-07 3.32411317502966e-06 -4.73501241321308e-07 2.08999135437099e-05 4.60325704625842e-06 -7.43809787018736e-06 8.50180716892148e-06 6.17620160775263e-06 -7.15738076595491e-06 4.60325704625842e-06 3.58844317491789e-05 -2.81466298101722e-05 7.79741169754737e-06 -1.17380573756183e-05 2.98380235543829e-05 -7.43809787018736e-06 -2.81466298101722e-05 0.000188636962384319 -2.55223969360717e-05 -2.66479842322595e-05 4.99638669805207e-07 8.50180716892148e-06 7.79741169754737e-06 -2.55223969360717e-05 0.000130851054801404 0 0 0 0 304 0 0 0 0 305 0 0 0 0 0 0 0 0 0 648 123 123 0 934 0 +280 283 0.998038185908024 0.0484024088552271 -0.0397112866378285 0.0562481374016212 -0.0482934224144086 0.99882633992231 0.00369973362644698 -0.355642633734314 0.0398437551057107 -0.00177468149666175 0.999204346309934 -0.0265838552907655 6.02537004309488e-05 3.80878022694329e-05 -6.23972836559736e-06 1.64632244691623e-05 1.84961745563915e-06 4.74343781767245e-05 3.80878022694329e-05 6.13021013508699e-05 -6.27823632967657e-06 2.11746501973599e-05 -5.5209751295203e-06 7.62994369410074e-05 -6.23972836559736e-06 -6.27823632967657e-06 1.27307071865753e-05 -5.1011054281114e-06 2.36943090581537e-06 -1.49394950688823e-05 1.64632244691623e-05 2.11746501973599e-05 -5.1011054281114e-06 4.48734695563449e-05 -1.99688179147153e-05 8.05471526458577e-05 1.84961745563915e-06 -5.5209751295203e-06 2.36943090581537e-06 -1.99688179147153e-05 6.14858164069513e-05 -2.64461601426075e-05 4.74343781767245e-05 7.62994369410074e-05 -1.49394950688823e-05 8.05471526458577e-05 -2.64461601426075e-05 0.000343850630709895 1936 1936 0 220 0 2011 2011 0 0 0 0 0 0 0 0 0 0 0 2000 0 505 527 0 0 3215 +279 435 -0.922559643361094 0.335905875001832 0.189870870806199 -0.039764487614541 -0.317502517637522 -0.940488103840825 0.121137433635208 -2.68173177771857 0.21926207089984 0.0514720280651785 0.97430733066706 0.57836283950327 8.23992072361413e-05 3.22238500658437e-06 -4.40294865884708e-06 1.64265059379525e-05 -5.08323266181178e-05 0.000141031251346031 3.22238500658437e-06 0.000110654009052552 4.15520446515972e-07 1.04614081943352e-06 4.04027218012849e-05 -5.79091098723483e-05 -4.40294865884708e-06 4.15520446515972e-07 1.96910735258037e-05 -7.13037465940086e-06 8.31642634991012e-06 -1.8506172099827e-05 1.64265059379525e-05 1.04614081943352e-06 -7.13037465940086e-06 3.96844228060542e-05 -1.90023507677196e-05 6.82318233917778e-05 -5.08323266181178e-05 4.04027218012849e-05 8.31642634991012e-06 -1.90023507677196e-05 0.00020522736615464 -0.000158370140465721 0.000141031251346031 -5.79091098723483e-05 -1.8506172099827e-05 6.82318233917778e-05 -0.000158370140465721 0.000747469776838219 0 0 0 0 41 0 0 0 0 41 0 0 0 0 0 0 0 0 0 604 81 81 0 1215 0 +279 437 -0.895742710994249 0.410405347336639 0.17091649007093 0.0127454492574933 -0.412715711375299 -0.910557587219536 0.0234653348775848 -2.76534541599988 0.165259605725823 -0.0495210181077572 0.985006056570677 0.367504019046653 7.62793404310685e-05 5.76207114386182e-05 5.39570478652521e-06 1.50311772846554e-06 -1.82610117462622e-05 -1.03283026880931e-05 5.76207114386182e-05 9.53584537239176e-05 2.01142898254114e-06 3.85386645756703e-06 -6.02379367975586e-06 -2.52914443537828e-05 5.39570478652521e-06 2.01142898254114e-06 2.12769573321449e-05 -5.36329637431307e-07 -1.80432867867202e-06 3.6521783709292e-06 1.50311772846554e-06 3.85386645756703e-06 -5.36329637431307e-07 3.12160871533148e-05 1.06739768280371e-05 2.43880750390821e-06 -1.82610117462622e-05 -6.02379367975586e-06 -1.80432867867202e-06 1.06739768280371e-05 0.000336594818723239 -3.95462323417318e-05 -1.03283026880931e-05 -2.52914443537828e-05 3.6521783709292e-06 2.43880750390821e-06 -3.95462323417318e-05 0.000191867734360084 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 581 0 0 0 1262 0 +279 436 -0.904827659429912 0.387745641419629 0.175898335099195 -0.0361421651548191 -0.379543390578401 -0.921751897180808 0.0795000296341547 -2.69389993968874 0.192960414072003 0.00517277523783659 0.981192907127594 0.475991682205178 8.19230268610287e-05 2.53920850666427e-05 -3.65066194336973e-06 2.63131331893648e-06 -2.66954164321045e-05 -1.16066254262822e-05 2.53920850666427e-05 0.000134940614976553 -4.75682435341245e-06 1.8542380259413e-05 6.78854842842951e-05 -5.00055359314466e-05 -3.65066194336973e-06 -4.75682435341245e-06 2.55706803625207e-05 -3.41208955574932e-06 -6.28428584420864e-06 4.90071693446227e-06 2.63131331893648e-06 1.8542380259413e-05 -3.41208955574932e-06 3.59469799377008e-05 1.91801365884866e-05 -1.25952550409849e-06 -2.66954164321045e-05 6.78854842842951e-05 -6.28428584420864e-06 1.91801365884866e-05 0.000302475414753608 3.53571959513193e-05 -1.16066254262822e-05 -5.00055359314466e-05 4.90071693446227e-06 -1.25952550409849e-06 3.53571959513193e-05 0.000242760675004059 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 568 17 17 0 1312 0 +280 284 0.987947280195296 0.143339294909977 -0.0584295994289609 0.0844528231894402 -0.141086978382159 0.989146788171506 0.0410255527809964 -0.500915704965829 0.0636760244182244 -0.032287427656982 0.997448187090229 -0.0042621743302423 2.50442619822837e-05 1.33270020355883e-05 8.14047699950375e-07 4.8943149922992e-06 -1.46858457626639e-06 -2.08981907989384e-09 1.33270020355883e-05 2.95956639454198e-05 -4.56141931250343e-06 4.26000384738781e-06 -1.69702453260057e-06 1.20703873109712e-05 8.14047699950375e-07 -4.56141931250343e-06 1.25391344093119e-05 -4.96733237282823e-07 4.80995151097133e-06 2.89625360326764e-06 4.8943149922992e-06 4.26000384738781e-06 -4.96733237282823e-07 3.56108804401387e-05 -8.21026499082892e-06 1.81535610310707e-05 -1.46858457626639e-06 -1.69702453260057e-06 4.80995151097133e-06 -8.21026499082892e-06 5.74670937379363e-05 2.60163574297078e-05 -2.08981907989384e-09 1.20703873109712e-05 2.89625360326764e-06 1.81535610310707e-05 2.60163574297078e-05 0.000137905045324601 1671 1671 0 196 0 1753 1753 0 0 0 0 0 0 0 0 0 0 0 1563 0 962 959 0 0 3151 +280 434 -0.947134299496523 0.20671211175217 0.245370580086917 -0.187941920386759 -0.186737306765366 -0.977066957354859 0.102319788444541 -2.51042428289108 0.260894225653327 0.0510907398681667 0.964014491239875 0.75522661092609 5.35944854817382e-05 -1.24750083627529e-05 1.21922134695801e-06 -6.36924639072286e-07 -4.39315509232767e-05 -3.46154856238035e-06 -1.24750083627529e-05 0.00017315806700118 1.51610716169449e-05 1.12596873853377e-05 8.7461691055356e-05 2.83005798195825e-05 1.21922134695801e-06 1.51610716169449e-05 2.58036875363559e-05 -1.32459682404328e-06 5.31985493240949e-06 5.19592657622301e-06 -6.36924639072286e-07 1.12596873853377e-05 -1.32459682404328e-06 2.85227547045124e-05 2.83702793446248e-06 1.32652752906528e-05 -4.39315509232767e-05 8.7461691055356e-05 5.31985493240949e-06 2.83702793446248e-06 0.000185261866779229 -3.3158646092291e-06 -3.46154856238035e-06 2.83005798195825e-05 5.19592657622301e-06 1.32652752906528e-05 -3.3158646092291e-06 0.00016958517645347 0 0 0 0 132 0 0 0 0 132 0 0 0 0 0 0 0 0 0 689 76 76 0 1177 0 +280 432 -0.981958165487347 -0.015521239843785 0.188460214226866 -0.202181082004916 0.0420434903403797 -0.98960032668276 0.137562852359835 -2.49732740643162 0.184365143540537 0.143004491338863 0.972398688452525 0.882221017123155 4.6486728860097e-05 7.35368562924517e-06 2.18908761658722e-08 6.78560396129005e-06 -1.99525964176136e-05 -3.64987313265231e-05 7.35368562924517e-06 6.70943717177702e-05 4.55623307547879e-06 9.21675939948356e-07 2.24878143776911e-05 1.57502116936615e-05 2.18908761658722e-08 4.55623307547879e-06 1.90049535077502e-05 -1.00375773482666e-06 6.91625312298904e-06 1.23180652826357e-05 6.78560396129005e-06 9.21675939948356e-07 -1.00375773482666e-06 3.03716823038313e-05 -1.68818732688359e-05 -1.63111785510045e-06 -1.99525964176136e-05 2.24878143776911e-05 6.91625312298904e-06 -1.68818732688359e-05 0.000118528722803297 4.7199022095127e-05 -3.64987313265231e-05 1.57502116936615e-05 1.23180652826357e-05 -1.63111785510045e-06 4.7199022095127e-05 0.000230733434437283 0 0 0 0 421 0 0 0 0 438 0 0 0 0 0 0 0 0 0 629 99 99 0 667 7 +280 433 -0.977203064051611 0.108449490067369 0.182518162691473 -0.190868388401308 -0.0828799207074539 -0.986343215992836 0.142330527324377 -2.50993833780802 0.19546122467556 0.123958736557923 0.972845898012267 0.835294319821592 3.89096159422302e-05 2.45259654254841e-05 2.62317352169883e-06 2.72064822253677e-06 -7.58642033388821e-06 -1.27511516313171e-05 2.45259654254841e-05 6.97143811926858e-05 -7.13311596253646e-06 2.92081256599891e-06 1.80732845005264e-05 -1.09275146944531e-05 2.62317352169883e-06 -7.13311596253646e-06 2.32761270388964e-05 -2.4940628335752e-06 -4.8315697714089e-06 4.30151740241773e-06 2.72064822253677e-06 2.92081256599891e-06 -2.4940628335752e-06 2.8416887770087e-05 4.0869584951561e-07 -5.68939346159097e-09 -7.58642033388821e-06 1.80732845005264e-05 -4.8315697714089e-06 4.0869584951561e-07 0.000125788089569841 -2.47656024708211e-07 -1.27511516313171e-05 -1.09275146944531e-05 4.30151740241773e-06 -5.68939346159097e-09 -2.47656024708211e-07 0.000134611330737238 0 0 0 0 308 0 0 0 0 308 0 0 0 0 0 0 0 0 0 665 86 86 0 912 0 +280 282 0.999954010734732 -0.00429498944436514 0.00857493330565758 0.0363258164016254 0.00418097766606955 0.99990321015404 0.0132698812881449 -0.233978377791295 -0.00863109733924437 -0.0132334194114153 0.999875182595009 0.00459577047412792 4.68546713976819e-05 -9.91864223248862e-06 -3.91477649842638e-06 9.35372032560201e-06 2.30461995459916e-06 5.69424805456998e-05 -9.91864223248862e-06 4.12355095464554e-05 -1.04023815872978e-06 -2.42716270262561e-06 1.51948007382185e-06 -1.0926735404207e-05 -3.91477649842638e-06 -1.04023815872978e-06 1.23099771635636e-05 -3.03840720115208e-07 2.24835453411651e-06 -5.23067074013478e-06 9.35372032560201e-06 -2.42716270262561e-06 -3.03840720115208e-07 2.63210259702357e-05 -7.40921597061e-06 2.32619652333533e-05 2.30461995459916e-06 1.51948007382185e-06 2.24835453411651e-06 -7.40921597061e-06 5.19052351938788e-05 2.27606945642728e-05 5.69424805456998e-05 -1.0926735404207e-05 -5.23067074013478e-06 2.32619652333533e-05 2.27606945642728e-05 0.000185216500455665 2281 2258 0 235 0 2310 2310 0 0 0 0 0 0 0 0 0 0 0 2341 0 194 233 0 0 3495 +280 435 -0.927359707185512 0.291127950979629 0.235049972659442 -0.18511347093973 -0.262828693104928 -0.953948044568728 0.144582870161913 -2.54856321469613 0.266317576531399 0.0723024510089627 0.961169758163738 0.645328381638293 6.36074666386992e-05 -3.52667610748332e-05 -1.91893780664833e-06 -1.01681367944019e-05 -2.67678399775673e-05 2.3270400644679e-06 -3.52667610748332e-05 0.000227193278604704 2.37059317542526e-05 2.6402258546109e-05 5.80505644682918e-05 -4.61757183176139e-05 -1.91893780664833e-06 2.37059317542526e-05 2.79158769310196e-05 -2.00221614569287e-06 4.03944302501136e-06 -7.4745072321549e-06 -1.01681367944019e-05 2.6402258546109e-05 -2.00221614569287e-06 3.39774879168927e-05 8.86614059402951e-06 3.11793333874435e-06 -2.67678399775673e-05 5.80505644682918e-05 4.03944302501136e-06 8.86614059402951e-06 0.00020175638216783 4.72217783976435e-05 2.3270400644679e-06 -4.61757183176139e-05 -7.4745072321549e-06 3.11793333874435e-06 4.72217783976435e-05 0.000207913996305661 0 0 0 0 40 0 0 0 0 40 0 0 0 0 0 0 0 0 0 590 33 33 0 1318 0 +281 283 0.99761989600532 0.0685899308516798 -0.00706855572915382 0.0303587033674122 -0.0686124605960155 0.997638891467672 -0.0029954101747637 -0.231463726003353 0.00684641112515102 0.00347327178847834 0.999970531084686 -0.0221256251607635 2.37527100151681e-05 6.79961698339095e-06 -5.95523786007714e-07 2.03747736835738e-06 -1.85202965727633e-06 -1.05260275683861e-06 6.79961698339095e-06 2.76841088498059e-05 1.13366904198423e-06 -8.1036796868741e-07 5.53545593037646e-06 1.63079675267019e-05 -5.95523786007714e-07 1.13366904198423e-06 1.48705044475372e-05 -4.91900488753181e-06 3.66991014023099e-06 3.99420159253198e-07 2.03747736835738e-06 -8.1036796868741e-07 -4.91900488753181e-06 3.06187537235714e-05 -1.91724750079982e-05 6.55662287234957e-06 -1.85202965727633e-06 5.53545593037646e-06 3.66991014023099e-06 -1.91724750079982e-05 7.63144444762967e-05 1.73640002627595e-05 -1.05260275683861e-06 1.63079675267019e-05 3.99420159253198e-07 6.55662287234957e-06 1.73640002627595e-05 9.23373962618771e-05 2402 2361 0 267 0 2461 2420 0 169 0 0 0 0 0 0 0 0 0 2831 0 403 425 0 0 3258 +280 431 -0.961261615111944 -0.154855595789796 0.228025989231414 -0.207394410446926 0.182383929405545 -0.977610684808196 0.104944991511945 -2.50487667913111 0.206669324300851 0.142467867961294 0.96798279788 0.917194076881024 0.000118377757184033 1.4334110310319e-05 -5.76242338678696e-06 -1.34324025911347e-06 -2.3934688035032e-05 -5.80454280378298e-05 1.4334110310319e-05 0.000147887766576762 1.56736987870949e-05 7.71033227138256e-06 6.46557283728074e-06 -2.50516094006931e-05 -5.76242338678696e-06 1.56736987870949e-05 2.49544593288359e-05 1.35040787409025e-06 -1.93418955189402e-06 3.7713874188351e-06 -1.34324025911347e-06 7.71033227138256e-06 1.35040787409025e-06 4.35707791964403e-05 -1.86384798069473e-05 1.56739695115523e-05 -2.3934688035032e-05 6.46557283728074e-06 -1.93418955189402e-06 -1.86384798069473e-05 0.000100670460443418 3.17544661125258e-05 -5.80454280378298e-05 -2.50516094006931e-05 3.7713874188351e-06 1.56739695115523e-05 3.17544661125258e-05 0.000331578542456349 0 0 0 0 369 0 0 0 0 402 0 0 0 0 0 0 0 0 0 592 92 92 0 519 173 +281 435 -0.924974157313365 0.272812602487387 0.26456774600561 -0.241152169170191 -0.245714253162077 -0.960411157589316 0.131281812034088 -2.42408602617712 0.289909148002323 0.0564242173362595 0.955389446038922 0.631260307574732 0.000116043483340782 2.72105482610144e-05 -2.3188469685847e-06 7.68806515463486e-06 2.96717105022004e-05 0.000163749458779478 2.72105482610144e-05 9.8216333480032e-05 -4.44302363181842e-06 1.81488364491711e-05 8.0078291761282e-05 5.2646889648934e-05 -2.3188469685847e-06 -4.44302363181842e-06 2.49308504046783e-05 -7.80046797123847e-06 -1.61720731778893e-06 -1.49238732227117e-05 7.68806515463486e-06 1.81488364491711e-05 -7.80046797123847e-06 4.15025737866717e-05 1.3888271727545e-05 4.86684911975197e-05 2.96717105022004e-05 8.0078291761282e-05 -1.61720731778893e-06 1.3888271727545e-05 0.00041486248134664 0.000158416514666206 0.000163749458779478 5.2646889648934e-05 -1.49238732227117e-05 4.86684911975197e-05 0.000158416514666206 0.000719127955440497 0 0 0 0 40 0 0 0 0 40 0 0 0 0 0 0 0 0 0 624 8 8 0 1426 0 +281 434 -0.944706795541548 0.189516383259625 0.267605326803879 -0.237589483198154 -0.172340702785383 -0.981232016951925 0.0865009310464252 -2.38787241999681 0.278976258167358 0.0355987272897361 0.95963794109773 0.737143286266952 5.72108303409905e-05 3.20483606240601e-05 7.01388255524832e-06 5.16745832181932e-06 -1.65589586449133e-05 1.89617626048177e-06 3.20483606240601e-05 0.000115168862443474 5.47841268006062e-06 3.77490709252281e-06 3.07521332791876e-05 -2.18763522826955e-05 7.01388255524832e-06 5.47841268006062e-06 2.51106767084851e-05 1.04027767267105e-06 1.96871827830327e-06 -1.93532185399364e-06 5.16745832181932e-06 3.77490709252281e-06 1.04027767267105e-06 2.64692457959107e-05 -6.20724056046261e-06 1.58456199941773e-06 -1.65589586449133e-05 3.07521332791876e-05 1.96871827830327e-06 -6.20724056046261e-06 0.000211544649810221 8.86870678513113e-07 1.89617626048177e-06 -2.18763522826955e-05 -1.93532185399364e-06 1.58456199941773e-06 8.86870678513113e-07 0.00018403809851249 0 0 0 0 132 0 0 0 0 132 0 0 0 0 0 0 0 0 0 609 33 33 0 1219 0 +281 431 -0.951170087916145 -0.173013651236306 0.255620305021872 -0.251888654333714 0.200629388340124 -0.975882275048418 0.0860327483031403 -2.39944365985354 0.234570484903495 0.13311672221102 0.962941652375643 0.903196116058387 7.09937571465775e-05 1.89537360965805e-05 2.04440275386797e-06 7.23232884415498e-08 -1.21582458636663e-06 4.43761757376447e-05 1.89537360965805e-05 0.000183871491951879 1.47618795957625e-05 1.87307749016371e-05 1.64163713409028e-05 -2.3065328396244e-05 2.04440275386797e-06 1.47618795957625e-05 2.33775626697196e-05 -7.12320102947498e-07 -1.51937525708236e-06 -2.78205757033054e-05 7.23232884415498e-08 1.87307749016371e-05 -7.12320102947498e-07 4.41132552238761e-05 -1.38106591359254e-05 1.13336388676768e-05 -1.21582458636663e-06 1.64163713409028e-05 -1.51937525708236e-06 -1.38106591359254e-05 9.00853150989334e-05 7.97088276868324e-05 4.43761757376447e-05 -2.3065328396244e-05 -2.78205757033054e-05 1.13336388676768e-05 7.97088276868324e-05 0.000600670663676494 0 0 0 0 388 0 0 0 0 434 0 0 0 0 0 0 0 0 0 618 62 62 0 556 108 +281 433 -0.972894813680619 0.0942005076601876 0.211191727749731 -0.239092315618105 -0.0663688775619247 -0.988591233377928 0.135212963060044 -2.38081756601064 0.221519420377816 0.117531432582393 0.968047265762683 0.81245330326707 6.97157905807448e-05 1.6788341107324e-05 1.71482873655377e-06 7.88984114396309e-06 -2.55460303826122e-05 2.46372081945046e-06 1.6788341107324e-05 8.27390108614913e-05 -1.22453310926752e-05 3.95465621043578e-06 6.47408671240677e-06 1.88755417993825e-06 1.71482873655377e-06 -1.22453310926752e-05 2.49756292269014e-05 7.68717217727902e-07 -1.33883866365362e-07 1.48928795757872e-05 7.88984114396309e-06 3.95465621043578e-06 7.68717217727902e-07 3.22334536923695e-05 -1.15723460774531e-05 -2.99868603458247e-06 -2.55460303826122e-05 6.47408671240677e-06 -1.33883866365362e-07 -1.15723460774531e-05 0.000142068512045297 2.3195763361285e-05 2.46372081945046e-06 1.88755417993825e-06 1.48928795757872e-05 -2.99868603458247e-06 2.3195763361285e-05 0.0003225455956983 0 0 0 0 320 0 0 0 0 320 0 0 0 0 0 0 0 0 0 596 48 48 0 910 0 +281 284 0.986480899878647 0.162254744594679 -0.022996348212933 0.0524501111906036 -0.161400885385814 0.986264492840506 0.0351013441157975 -0.379822726239503 0.0283758413318507 -0.0309151745680941 0.99911914385129 -0.00723220787705172 3.34161044954717e-05 9.27494237913823e-06 3.35383029886761e-07 3.8933913830228e-06 -5.56276861842248e-06 -7.00990591486849e-06 9.27494237913823e-06 3.21587262850299e-05 -4.28560316181169e-06 6.88468611206738e-06 -4.25954559882755e-06 2.31064185415101e-05 3.35383029886761e-07 -4.28560316181169e-06 1.27407049033888e-05 -2.48248480939295e-06 2.4805358612129e-06 2.58827050664635e-06 3.8933913830228e-06 6.88468611206738e-06 -2.48248480939295e-06 3.67069051370053e-05 -1.43941502204565e-05 1.15227803223296e-05 -5.56276861842248e-06 -4.25954559882755e-06 2.4805358612129e-06 -1.43941502204565e-05 6.22153583163737e-05 6.45291104412034e-06 -7.00990591486849e-06 2.31064185415101e-05 2.58827050664635e-06 1.15227803223296e-05 6.45291104412034e-06 0.000126957052799381 2115 2115 0 299 0 2186 2186 0 225 0 0 0 0 0 0 0 0 0 2046 0 834 831 0 0 3040 +281 432 -0.975343267892668 -0.0309841449570294 0.218507419868831 -0.245619344064453 0.0596232570593017 -0.990272672510498 0.125718341130311 -2.37860105679419 0.212486651331542 0.135646661736287 0.96770316015073 0.868017130257495 4.76982144604659e-05 -1.76804233630788e-05 -5.07652480770613e-07 -4.66909228695365e-06 -1.12958224409568e-05 -9.47536289971021e-06 -1.76804233630788e-05 0.000164840341881858 9.14568664000472e-06 1.66574090128479e-05 4.37194183046909e-05 -9.66276931945797e-06 -5.07652480770613e-07 9.14568664000472e-06 2.38986207485382e-05 1.89142943729818e-06 2.9672451335845e-06 4.56381176777282e-06 -4.66909228695365e-06 1.66574090128479e-05 1.89142943729818e-06 3.75850799420926e-05 -3.11855623902243e-06 -4.461630563425e-06 -1.12958224409568e-05 4.37194183046909e-05 2.9672451335845e-06 -3.11855623902243e-06 9.00604886797143e-05 1.22118751167597e-05 -9.47536289971021e-06 -9.66276931945797e-06 4.56381176777282e-06 -4.461630563425e-06 1.22118751167597e-05 8.6722190078303e-05 0 0 0 0 432 0 0 0 0 434 0 0 0 0 0 0 0 0 0 658 53 53 0 689 0 +281 285 0.960223488778156 0.278812318599635 0.0153147835701956 0.0760296150067195 -0.279185529518462 0.957609387414693 0.0709908532330223 -0.521164236716442 0.00512754387622172 -0.0724427507232564 0.997359391674559 -0.00854308576997508 3.07829530694821e-05 1.03891069681817e-05 4.51415749496911e-06 -9.91959732376682e-08 1.36175650050211e-06 -5.23940794943385e-07 1.03891069681817e-05 3.13190612718695e-05 -5.90896799153362e-06 6.20520501600281e-06 -1.83539780256127e-06 2.10827962369343e-05 4.51415749496911e-06 -5.90896799153362e-06 1.69697016097632e-05 -9.37882954936539e-06 9.14567121529244e-06 1.43540444433056e-06 -9.91959732376682e-08 6.20520501600281e-06 -9.37882954936539e-06 5.86860384887372e-05 -3.90577547249395e-05 1.64546304544853e-05 1.36175650050211e-06 -1.83539780256127e-06 9.14567121529244e-06 -3.90577547249395e-05 7.50333716088858e-05 1.50653481890886e-06 -5.23940794943385e-07 2.10827962369343e-05 1.43540444433056e-06 1.64546304544853e-05 1.50653481890886e-06 0.000123100707759709 1728 1729 0 220 0 1808 1809 0 161 0 0 0 0 0 0 0 0 0 1691 0 1365 1370 0 0 2800 +282 285 0.963520953610421 0.266348521535865 -0.0261884903979643 0.0711225197138701 -0.264308217589001 0.962360839875949 0.063267527122401 -0.396067938591825 0.0420539899247499 -0.0540377548471163 0.99765293713921 0.00172598626595021 2.02124993985233e-05 7.05175595835055e-06 2.35686597818399e-06 1.20146762610295e-06 4.44424638713608e-07 2.54374988881056e-06 7.05175595835055e-06 2.54592468154063e-05 -2.68885645589114e-06 3.06596102632543e-06 1.98648364447431e-06 2.04655390536235e-05 2.35686597818399e-06 -2.68885645589114e-06 1.67086251947032e-05 -9.2649396478831e-06 2.9123427102669e-06 7.042475399419e-07 1.20146762610295e-06 3.06596102632543e-06 -9.2649396478831e-06 4.36179237163875e-05 -2.41420379247525e-05 1.09452411754913e-05 4.44424638713608e-07 1.98648364447431e-06 2.9123427102669e-06 -2.41420379247525e-05 5.10076659894957e-05 3.53331935071432e-06 2.54374988881056e-06 2.04655390536235e-05 7.042475399419e-07 1.09452411754913e-05 3.53331935071432e-06 0.000108823591408483 2138 2156 0 409 0 2201 2219 0 288 0 0 0 0 0 0 0 0 0 1846 0 1093 1098 0 0 2845 +282 284 0.987489353979001 0.147476030602534 -0.0558175257052515 0.0466809535870299 -0.146176641386988 0.988897868841036 0.0267094461656516 -0.249434310884843 0.0591368353140054 -0.0182160753011306 0.998083668491609 0.0160674217480524 3.04792475388711e-05 3.13194742330475e-07 -2.3969774953262e-06 7.79379587100905e-06 -7.89035189691175e-06 1.70785054073902e-06 3.13194742330475e-07 4.32195430511939e-05 -2.88355454946165e-06 3.38909115200448e-07 -3.13086875788192e-06 9.37064067893518e-06 -2.3969774953262e-06 -2.88355454946165e-06 1.24025199951941e-05 -3.01856269143343e-06 1.19265353590993e-06 1.42839946577818e-06 7.79379587100905e-06 3.38909115200448e-07 -3.01856269143343e-06 3.27772167109302e-05 -1.03724834022522e-05 1.76456010652944e-05 -7.89035189691175e-06 -3.13086875788192e-06 1.19265353590993e-06 -1.03724834022522e-05 5.64158631499106e-05 1.56879012944489e-05 1.70785054073902e-06 9.37064067893518e-06 1.42839946577818e-06 1.76456010652944e-05 1.56879012944489e-05 0.000111366604779049 2424 2424 0 386 0 2478 2478 0 218 0 0 0 0 0 0 0 0 0 2440 0 597 594 0 0 3064 +282 435 -0.930810184721995 0.285199237921261 0.228590889378684 -0.242234766513183 -0.262863461127104 -0.956896731019416 0.123496748818078 -2.30121334744973 0.253959053435953 0.0548638392157174 0.96565768175085 0.613408720225389 0.000110352561914931 -9.30717946066382e-05 -1.24550145253096e-05 -1.43756026919134e-05 -3.0408037997961e-05 0.000124604926978674 -9.30717946066382e-05 0.000406500559850632 3.38807016904901e-05 6.32773077117595e-05 0.000108984150113665 -0.000331812017982972 -1.24550145253096e-05 3.38807016904901e-05 3.00246074053426e-05 6.65699270060879e-07 1.00371174894364e-05 -5.28925801306875e-05 -1.43756026919134e-05 6.32773077117595e-05 6.65699270060879e-07 5.29516513199683e-05 1.99975468021925e-05 -1.28990677630413e-05 -3.0408037997961e-05 0.000108984150113665 1.00371174894364e-05 1.99975468021925e-05 0.000284109831799653 -1.45067483269377e-05 0.000124604926978674 -0.000331812017982972 -5.28925801306875e-05 -1.28990677630413e-05 -1.45067483269377e-05 0.000722184539606589 0 0 0 0 40 0 0 0 0 40 0 0 0 0 0 0 0 0 0 628 8 8 0 1405 0 +282 434 -0.951742702417166 0.202762263253556 0.230376415884885 -0.240610521701345 -0.188173405423681 -0.97854878992494 0.0838631935218894 -2.28000077810373 0.242438853913568 0.0364654677294957 0.969481135338045 0.717301382896309 7.84290955459083e-05 1.69511100201772e-05 -3.96083960825085e-06 1.07578719159203e-05 -5.35353121395974e-05 7.89608480800609e-05 1.69511100201772e-05 0.000117460693298703 -3.77510301637602e-06 1.12950454974626e-05 4.99006754606055e-05 3.13554885662301e-05 -3.96083960825085e-06 -3.77510301637602e-06 2.00442499686459e-05 -1.37392969629815e-06 1.1360873124659e-05 -1.36390769180101e-05 1.07578719159203e-05 1.12950454974626e-05 -1.37392969629815e-06 2.94664708864539e-05 -6.24580783380391e-06 4.43926705643984e-05 -5.35353121395974e-05 4.99006754606055e-05 1.1360873124659e-05 -6.24580783380391e-06 0.000237221665843356 -7.43056875242237e-05 7.89608480800609e-05 3.13554885662301e-05 -1.36390769180101e-05 4.43926705643984e-05 -7.43056875242237e-05 0.000545083159698616 0 0 0 0 137 0 0 0 0 137 0 0 0 0 0 0 0 0 0 680 31 31 0 1208 0 +282 286 0.918384054063145 0.39450554507974 -0.030595819058797 0.104184511195603 -0.390483312351873 0.91608828021844 0.0911320230277486 -0.545354279608428 0.0639805596822293 -0.0717470399930021 0.995368700650664 0.021733294327606 2.4189126196637e-05 1.42694274401283e-05 8.75861215182377e-06 -6.01214407046136e-06 2.96987178470292e-06 8.73514566691671e-06 1.42694274401283e-05 3.37204277643882e-05 3.98367868168679e-06 -3.12528193418374e-06 -3.74857269105283e-06 1.93853734160282e-05 8.75861215182377e-06 3.98367868168679e-06 1.2623154064988e-05 -1.27037981893442e-06 5.01919898233049e-07 7.29021208011999e-06 -6.01214407046136e-06 -3.12528193418374e-06 -1.27037981893442e-06 2.973798457121e-05 -1.01416138567703e-05 -8.76894516800588e-06 2.96987178470292e-06 -3.74857269105283e-06 5.01919898233049e-07 -1.01416138567703e-05 3.32024232732414e-05 9.72703472337301e-06 8.73514566691671e-06 1.93853734160282e-05 7.29021208011999e-06 -8.76894516800588e-06 9.72703472337301e-06 0.000121067802201601 1900 1829 0 559 0 1974 1903 0 459 0 0 0 0 0 0 0 0 0 1445 0 1516 1495 0 0 2692 +282 433 -0.979885701514178 0.103766344904131 0.170459841702686 -0.250514795639784 -0.0829907765395254 -0.988705344343482 0.124796927350007 -2.27148249424678 0.181484277493766 0.108140130071465 0.977429879475092 0.786189987713648 5.93978600567372e-05 3.17890418918823e-05 6.29233812723271e-06 1.0187925702466e-06 -8.92559872496121e-07 -6.87422246612366e-06 3.17890418918823e-05 0.000110460773665 -1.45212149499066e-05 -1.69296889287712e-06 2.08235567481762e-05 -1.48776111008491e-05 6.29233812723271e-06 -1.45212149499066e-05 3.31310195772568e-05 4.48331149000015e-06 -9.35291504739239e-06 6.86445067745677e-06 1.0187925702466e-06 -1.69296889287712e-06 4.48331149000015e-06 3.71059544933726e-05 -1.62478686921076e-05 1.15257314220314e-05 -8.92559872496121e-07 2.08235567481762e-05 -9.35291504739239e-06 -1.62478686921076e-05 0.00014975190003865 -1.67391508574073e-05 -6.87422246612366e-06 -1.48776111008491e-05 6.86445067745677e-06 1.15257314220314e-05 -1.67391508574073e-05 0.000147888320661431 0 0 0 0 321 0 0 0 0 321 0 0 0 0 0 0 0 0 0 667 43 43 0 861 0 +282 432 -0.981916169123629 -0.0205183778545948 0.188201044056064 -0.251685003138381 0.043909148412093 -0.9916841132184 0.120973576767656 -2.27164459740254 0.184153803922974 0.127049658639649 0.974651609930568 0.8487297682081 8.10533372625654e-05 1.12163489847541e-05 -4.05399386222355e-06 6.48387204523589e-06 -2.48670653256879e-05 1.06059737246158e-05 1.12163489847541e-05 0.000130528289483944 -1.1525577043864e-06 8.1107003446281e-06 3.60324265774961e-05 -1.68578305764347e-05 -4.05399386222355e-06 -1.1525577043864e-06 2.87411144707254e-05 -3.79425526883789e-07 2.51832837066262e-06 1.13079175009433e-05 6.48387204523589e-06 8.1107003446281e-06 -3.79425526883789e-07 2.78080093655225e-05 1.4790444297834e-06 8.83058064495826e-06 -2.48670653256879e-05 3.60324265774961e-05 2.51832837066262e-06 1.4790444297834e-06 8.51600335761575e-05 2.24722493661015e-06 1.06059737246158e-05 -1.68578305764347e-05 1.13079175009433e-05 8.83058064495826e-06 2.24722493661015e-06 0.000212480406531306 0 0 0 0 467 0 0 0 0 464 0 0 0 0 0 0 0 0 0 637 50 50 0 653 0 +283 286 0.940157829251538 0.340376392530053 0.0157215617946506 0.104297244861007 -0.340110467043848 0.934621612335203 0.103958222200848 -0.42418134117728 0.0206912132136185 -0.103084204241836 0.994457400058734 0.0284510756158464 5.0286380766093e-05 7.95071760622382e-06 5.05692289674873e-06 2.15215718600762e-07 8.15434586093657e-06 3.91787881592459e-05 7.95071760622382e-06 7.07818115016906e-05 1.23893424052845e-05 -1.41840074504212e-05 -1.19702718243972e-06 2.30947960877849e-05 5.05692289674873e-06 1.23893424052845e-05 1.61638634562439e-05 -6.0852220918521e-06 5.78905200814925e-06 6.01154010029064e-06 2.15215718600762e-07 -1.41840074504212e-05 -6.0852220918521e-06 4.20197715596999e-05 -1.76944658728645e-05 -7.93162682090417e-06 8.15434586093657e-06 -1.19702718243972e-06 5.78905200814925e-06 -1.76944658728645e-05 4.73717701783484e-05 3.54365565241172e-05 3.91787881592459e-05 2.30947960877849e-05 6.01154010029064e-06 -7.93162682090417e-06 3.54365565241172e-05 0.000204578933323744 2352 2281 0 615 0 2388 2317 0 523 0 0 0 0 0 0 0 0 0 1690 0 1110 1094 0 0 2708 +283 287 0.900393469287682 0.435063239156219 0.00340270465807206 0.145551838445431 -0.431228340629753 0.891364388112727 0.139684093017545 -0.560329491926385 0.0577383642113409 -0.127237987799724 0.990190272502652 0.0548399510168333 3.37743891053097e-05 1.33554601387603e-05 4.76675543728532e-06 -1.73200224815339e-06 6.81672472001929e-06 9.29898936132726e-06 1.33554601387603e-05 5.11548475956147e-05 5.89760979131731e-06 -9.95811286998046e-06 -1.92957375129128e-06 1.03272195390268e-05 4.76675543728532e-06 5.89760979131731e-06 1.36141356491489e-05 -6.28977450228075e-06 -4.62981475195262e-07 -3.14843369633457e-06 -1.73200224815339e-06 -9.95811286998046e-06 -6.28977450228075e-06 5.51423830489718e-05 -1.41034622049049e-05 2.62148494216669e-05 6.81672472001929e-06 -1.92957375129128e-06 -4.62981475195262e-07 -1.41034622049049e-05 3.53377710837178e-05 1.66465463772366e-07 9.29898936132726e-06 1.03272195390268e-05 -3.14843369633457e-06 2.62148494216669e-05 1.66465463772366e-07 0.000173171996055443 2245 2090 0 1214 0 2281 2126 0 1136 0 0 0 0 0 0 0 0 0 1318 0 1309 1296 0 0 2670 +283 434 -0.928154981754347 0.257641892237132 0.268605631380017 -0.113060464525395 -0.236201109574471 -0.965471488026016 0.109881034053288 -2.16721802592556 0.287641036155095 0.038541680986967 0.956962472172406 0.750727531885391 8.09324155952002e-05 1.58162150851709e-05 -1.50590514223401e-06 7.95427885680883e-06 -1.85379950836012e-05 0.000128024932153553 1.58162150851709e-05 0.00011917859885334 2.15742873852025e-06 4.04629185725809e-06 3.22535580771177e-05 6.68415840300291e-06 -1.50590514223401e-06 2.15742873852025e-06 1.98115629786623e-05 1.48917611369147e-06 9.81176983356987e-06 -2.74541829826763e-05 7.95427885680883e-06 4.04629185725809e-06 1.48917611369147e-06 3.04725516395302e-05 1.86271166404906e-06 4.65654942936489e-05 -1.85379950836012e-05 3.22535580771177e-05 9.81176983356987e-06 1.86271166404906e-06 0.000106182849086509 -5.87074415915014e-05 0.000128024932153553 6.68415840300291e-06 -2.74541829826763e-05 4.65654942936489e-05 -5.87074415915014e-05 0.000715227131213009 0 0 0 0 136 0 0 0 0 136 0 0 0 0 0 0 0 0 0 667 42 42 0 1357 0 +283 432 -0.973689090600533 0.0399717101501638 0.224347536721889 -0.116409560584204 -0.00695250735316821 -0.989248554636842 0.146078608257413 -2.14751773619251 0.227774488226869 0.140675369331628 0.963498429150976 0.910425219058638 4.4011552691564e-05 1.1192144847266e-05 1.19572382803886e-05 5.14931686121853e-06 -1.3358133444554e-05 -1.37613131127798e-05 1.1192144847266e-05 8.22224266958885e-05 1.88401052850896e-07 1.0067823643746e-05 9.98162155931014e-06 -3.01448847126455e-05 1.19572382803886e-05 1.88401052850896e-07 2.86242758392515e-05 1.37100658492363e-06 5.26842668017723e-06 9.5847758351328e-06 5.14931686121853e-06 1.0067823643746e-05 1.37100658492363e-06 2.98041130235953e-05 2.371762205941e-06 -4.24876518355384e-06 -1.3358133444554e-05 9.98162155931014e-06 5.26842668017723e-06 2.371762205941e-06 6.72359106624845e-05 2.50697108378587e-06 -1.37613131127798e-05 -3.01448847126455e-05 9.5847758351328e-06 -4.24876518355384e-06 2.50697108378587e-06 0.000180758099814721 0 0 0 0 434 0 0 0 0 426 0 0 0 0 0 0 0 0 0 646 63 63 0 751 0 +283 285 0.977378502180142 0.210635982085914 0.0190721400687972 0.0589923191437686 -0.211481809048272 0.974427757160948 0.0759341195771391 -0.269011061250569 -0.00258996482053754 -0.0782497867408433 0.996930420318911 0.0075352783868902 2.88592615568787e-05 1.655721633535e-06 -9.39163541834854e-07 6.6358834521858e-06 -3.81130441515225e-06 -4.47929823796824e-07 1.655721633535e-06 2.94455402975754e-05 -8.47644285864267e-07 -4.280675230782e-06 3.81542960553812e-06 1.68692301907221e-05 -9.39163541834854e-07 -8.47644285864267e-07 1.55308669755977e-05 -8.98292490110391e-06 9.99100530693338e-06 8.63711041786753e-06 6.6358834521858e-06 -4.280675230782e-06 -8.98292490110391e-06 4.68334557665399e-05 -3.89322370148054e-05 -6.74190600653113e-06 -3.81130441515225e-06 3.81542960553812e-06 9.99100530693338e-06 -3.89322370148054e-05 7.4499148720601e-05 3.25298882165575e-05 -4.47929823796824e-07 1.68692301907221e-05 8.63711041786753e-06 -6.74190600653113e-06 3.25298882165575e-05 0.000104721176498046 2446 2477 0 497 0 2481 2512 0 409 0 0 0 0 0 0 0 0 0 2225 0 752 757 0 0 3069 +283 433 -0.963268178929214 0.163311334766329 0.213175569423976 -0.110056676693849 -0.133754314251363 -0.98012991033729 0.146475739565854 -2.16047927254517 0.232860900285007 0.112582266805462 0.9659715494358 0.849415868255031 7.96503137788995e-05 2.43791114632734e-05 4.81735984434098e-06 6.22943984571973e-06 3.80638253640101e-06 6.8118243074272e-05 2.43791114632734e-05 9.97018472051756e-05 -5.70817016284599e-06 6.24757293476334e-06 1.62984357821327e-05 -1.95497137497376e-05 4.81735984434098e-06 -5.70817016284599e-06 2.39019139684483e-05 1.89507742371374e-06 1.74074384700107e-06 -2.88865240042017e-06 6.22943984571973e-06 6.24757293476334e-06 1.89507742371374e-06 3.01693470332449e-05 -9.78220655271463e-08 1.59503339155871e-05 3.80638253640101e-06 1.62984357821327e-05 1.74074384700107e-06 -9.78220655271463e-08 9.084529634113e-05 -2.02508705570016e-05 6.8118243074272e-05 -1.95497137497376e-05 -2.88865240042017e-06 1.59503339155871e-05 -2.02508705570016e-05 0.000363275959977552 0 0 0 0 290 0 0 0 0 287 0 0 0 0 0 0 0 0 0 681 59 59 0 975 0 +284 286 0.968086245711946 0.249126342000311 0.0272962741943568 0.0969589623359853 -0.250466505399772 0.96552555599148 0.0709008490793249 -0.276134719684593 -0.00869198114215388 -0.0754749392108875 0.997109814922578 0.0074166583187507 3.8142968734551e-05 -5.13418883676348e-06 4.13278547248357e-06 -7.76258632585268e-08 2.43518031321603e-06 1.645212353554e-05 -5.13418883676348e-06 5.92109388111084e-05 9.8851912219474e-06 -5.8177293634961e-06 -9.33833095371837e-07 1.23439698464446e-05 4.13278547248357e-06 9.8851912219474e-06 1.58411047174621e-05 -6.06150978390799e-06 5.02585278961259e-06 5.30930097532599e-06 -7.76258632585268e-08 -5.8177293634961e-06 -6.06150978390799e-06 4.40024087189127e-05 -2.10951151266887e-05 -4.9623777625983e-07 2.43518031321603e-06 -9.33833095371837e-07 5.02585278961259e-06 -2.10951151266887e-05 4.34429976649437e-05 1.39701450852887e-05 1.645212353554e-05 1.23439698464446e-05 5.30930097532599e-06 -4.9623777625983e-07 1.39701450852887e-05 0.000119805630918585 2888 2817 0 361 0 2881 2810 0 382 0 0 0 0 0 0 0 0 0 2361 0 663 650 0 0 2745 +284 432 -0.963039916289531 0.133846070771835 0.233750612773514 0.0529043414459049 -0.10495797801572 -0.985679876921984 0.131981070922745 -2.04685936997714 0.248068422988304 0.102569047816599 0.963297279112784 0.819682605237616 5.51309229204866e-05 3.71831190016042e-05 4.45614682370366e-06 6.14568326819886e-06 -2.79540203563896e-05 -1.23235726236203e-05 3.71831190016042e-05 8.03125346204125e-05 -1.23849316757444e-06 9.02757592373995e-06 -9.89728560524735e-07 -9.52411855071682e-06 4.45614682370366e-06 -1.23849316757444e-06 2.26270974648168e-05 -3.0277192039696e-06 1.07149611657615e-06 1.02639143352788e-05 6.14568326819886e-06 9.02757592373995e-06 -3.0277192039696e-06 2.76489757691217e-05 -6.20053077806129e-06 6.55395348918418e-06 -2.79540203563896e-05 -9.89728560524735e-07 1.07149611657615e-06 -6.20053077806129e-06 0.000107274809598535 1.99370741310363e-05 -1.23235726236203e-05 -9.52411855071682e-06 1.02639143352788e-05 6.55395348918418e-06 1.99370741310363e-05 0.00021692050192786 0 0 0 0 415 0 0 0 0 415 0 0 0 0 0 0 0 0 0 716 65 65 0 552 0 +284 433 -0.941902516420329 0.254481248481302 0.219223501779462 0.0589424123794031 -0.228194212802692 -0.963743418091444 0.138296873893735 -2.06332192315726 0.246469168060453 0.0802366391171597 0.965823498854097 0.7726661445339 5.92996467478142e-05 1.48738572106624e-05 -4.75760660897012e-07 1.97787923787328e-06 6.80698859327286e-06 -8.63788817877549e-06 1.48738572106624e-05 8.07208776421242e-05 -4.48191975811167e-06 1.04964809249519e-05 1.55569299976397e-05 1.92408332078868e-05 -4.75760660897012e-07 -4.48191975811167e-06 2.45648249028425e-05 1.49430295595162e-06 2.65724786912519e-06 6.96952399861131e-06 1.97787923787328e-06 1.04964809249519e-05 1.49430295595162e-06 3.49315521618881e-05 -1.16428842091433e-05 1.17272394402622e-05 6.80698859327286e-06 1.55569299976397e-05 2.65724786912519e-06 -1.16428842091433e-05 0.000155056233605466 4.21347758510391e-06 -8.63788817877549e-06 1.92408332078868e-05 6.96952399861131e-06 1.17272394402622e-05 4.21347758510391e-06 0.000191015411518245 0 0 0 0 270 0 0 0 0 270 0 0 0 0 0 0 0 0 0 704 65 65 0 751 0 +284 287 0.937386257367261 0.348244015002371 0.00575417361819577 0.15170630771734 -0.34677090787735 0.931624108058353 0.108749522915719 -0.415597972995962 0.0325106436250976 -0.103935688286106 0.994052529171158 0.030855192808419 3.96856419425043e-05 1.88242429438211e-05 2.07198760592487e-06 4.04663032393144e-06 1.9682139467602e-06 1.49619308449122e-05 1.88242429438211e-05 4.74332714843968e-05 -2.59506788281432e-06 6.0045442221722e-06 -1.15250508784628e-05 1.24162644396459e-06 2.07198760592487e-06 -2.59506788281432e-06 1.45418165901003e-05 -7.02228710499815e-06 1.69611683537463e-06 -3.76353603102149e-06 4.04663032393144e-06 6.0045442221722e-06 -7.02228710499815e-06 6.12220055992913e-05 -2.02885845017325e-05 2.93887276457619e-05 1.9682139467602e-06 -1.15250508784628e-05 1.69611683537463e-06 -2.02885845017325e-05 3.68986373143528e-05 -2.89262140628448e-06 1.49619308449122e-05 1.24162644396459e-06 -3.76353603102149e-06 2.93887276457619e-05 -2.89262140628448e-06 0.000145876740565482 2857 2702 0 1000 0 2853 2698 0 1002 0 0 0 0 0 0 0 0 0 1885 0 833 818 0 0 2624 +284 434 -0.89499389956894 0.346218818463554 0.281280019688714 0.0590655906559087 -0.331204456326825 -0.93814941896706 0.100892397141809 -2.05730822864935 0.298813533568403 -0.00286311604179357 0.954307222399001 0.676709936879528 4.90066091746263e-05 2.31908293164422e-05 2.227744422515e-06 -1.39172297312343e-06 -1.01217418087378e-05 1.16788361186873e-06 2.31908293164422e-05 7.55604368544067e-05 -2.37871077989286e-06 1.66279145067199e-05 -3.84416484787557e-06 5.57745143958907e-05 2.227744422515e-06 -2.37871077989286e-06 1.90040541482661e-05 9.82646933268734e-08 3.28630239773674e-06 -1.09957531777288e-06 -1.39172297312343e-06 1.66279145067199e-05 9.82646933268734e-08 3.13685189376578e-05 3.2410464279258e-06 3.22326553187979e-05 -1.01217418087378e-05 -3.84416484787557e-06 3.28630239773674e-06 3.2410464279258e-06 8.75088065403116e-05 1.149919587629e-05 1.16788361186873e-06 5.57745143958907e-05 -1.09957531777288e-06 3.22326553187979e-05 1.149919587629e-05 0.000387901587021783 0 0 0 0 119 0 0 0 0 119 0 0 0 0 0 0 0 0 0 724 46 46 0 1166 0 +284 288 0.895151722111757 0.445362739669889 0.018852705749752 0.174222942991928 -0.444146720383811 0.887514050105565 0.122688636953554 -0.543112656303215 0.0379089062445884 -0.118198312081632 0.992266130555907 -0.0300914558907158 4.20309832596486e-05 2.44659068103102e-05 -1.30555103934476e-06 9.46493587837949e-07 8.8265792332973e-07 1.64406762013384e-06 2.44659068103102e-05 3.43741495015584e-05 -3.40298057190076e-06 -1.43252263094117e-06 -2.91686955762082e-06 -2.30071450305993e-05 -1.30555103934476e-06 -3.40298057190076e-06 1.07527382355062e-05 -1.03031111436379e-06 4.61975931416e-06 -2.54528164839562e-06 9.46493587837949e-07 -1.43252263094117e-06 -1.03031111436379e-06 4.43111465117596e-05 -1.85198735031247e-05 1.72384709272939e-05 8.8265792332973e-07 -2.91686955762082e-06 4.61975931416e-06 -1.85198735031247e-05 3.18571100602785e-05 3.86771448334466e-06 1.64406762013384e-06 -2.30071450305993e-05 -2.54528164839562e-06 1.72384709272939e-05 3.86771448334466e-06 0.000139060342124227 2503 2351 0 1752 0 2495 2343 0 1752 0 0 0 0 0 0 0 0 0 1149 0 1069 1044 0 0 2524 +285 436 -0.786729461850972 0.575928978618312 0.22217687873257 0.21699836154382 -0.571095422720413 -0.815690626275264 0.092189046824777 -1.95521426235162 0.234321940934843 -0.0543563592814683 0.970638250947381 0.369421752875626 6.50371132141261e-05 3.50694749892186e-05 1.84427316488231e-07 -3.51713360822391e-06 2.17409296494643e-05 3.78728411921053e-05 3.50694749892186e-05 0.000115045259065087 -2.09633988767755e-06 1.394007613054e-05 7.63868066658784e-05 0.000135977251886116 1.84427316488231e-07 -2.09633988767755e-06 2.22320519908254e-05 -3.58486623941305e-06 -1.41630430676603e-05 -1.1506339854275e-05 -3.51713360822391e-06 1.394007613054e-05 -3.58486623941305e-06 3.9121642269883e-05 2.20091282241498e-05 2.38650516946377e-05 2.17409296494643e-05 7.63868066658784e-05 -1.41630430676603e-05 2.20091282241498e-05 0.000466653797536728 0.00017700630012221 3.78728411921053e-05 0.000135977251886116 -1.1506339854275e-05 2.38650516946377e-05 0.00017700630012221 0.00048324217509043 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 668 77 77 0 1798 0 +285 288 0.94026320460934 0.340110591123141 -0.0151621853188003 0.186094078131673 -0.338524238642373 0.938749638729841 0.0644240299592847 -0.387177340810891 0.036144790902366 -0.0554427776221638 0.997807422552149 -0.013974368497446 3.70055811695249e-05 2.04761328493212e-05 3.63691304389347e-07 -3.97981925171246e-06 5.01870448083832e-06 1.18505741986986e-05 2.04761328493212e-05 3.26073028641605e-05 -6.51342575624917e-07 -5.298792148929e-06 2.57417909147067e-06 -9.55109915791279e-06 3.63691304389347e-07 -6.51342575624917e-07 1.01716930448632e-05 1.08263986043173e-07 2.97910572137933e-06 -1.20579681766903e-06 -3.97981925171246e-06 -5.298792148929e-06 1.08263986043173e-07 3.59664078706088e-05 -1.16719378356511e-05 1.26724108057326e-05 5.01870448083832e-06 2.57417909147067e-06 2.97910572137933e-06 -1.16719378356511e-05 2.43681528388683e-05 2.55079675895458e-06 1.18505741986986e-05 -9.55109915791279e-06 -1.20579681766903e-06 1.26724108057326e-05 2.55079675895458e-06 0.000126746289915442 2880 2728 0 1723 0 2880 2728 0 1723 0 0 0 0 0 0 0 0 0 1426 0 827 798 0 0 2970 +285 287 0.970807096504467 0.237210620455126 -0.0355626618781771 0.135726711342788 -0.235179915309901 0.970488693708995 0.0533113760639803 -0.261611585915571 0.0471591858644201 -0.0433914383986261 0.997944484559288 0.0110974589673701 3.10001822524031e-05 5.91495187137841e-07 3.3835814654589e-07 1.14644807661639e-06 2.8899387222824e-06 7.49864296853013e-06 5.91495187137841e-07 5.15519068848365e-05 5.18092298226948e-06 4.42786173770301e-06 -2.86795146597801e-06 1.7499078793456e-05 3.3835814654589e-07 5.18092298226948e-06 1.38262664399991e-05 -7.81987563386404e-06 3.01381561710062e-07 -6.57233155056984e-08 1.14644807661639e-06 4.42786173770301e-06 -7.81987563386404e-06 6.17655766243826e-05 -1.71538659024001e-05 4.08845612546395e-05 2.8899387222824e-06 -2.86795146597801e-06 3.01381561710062e-07 -1.71538659024001e-05 3.30240649495957e-05 1.86109824365923e-06 7.49864296853013e-06 1.7499078793456e-05 -6.57233155056984e-08 4.08845612546395e-05 1.86109824365923e-06 0.00018972919599249 3218 3063 0 929 0 3218 3063 0 929 0 0 0 0 0 0 0 0 0 2126 0 560 551 0 0 3106 +285 434 -0.857711119377964 0.455850930369253 0.237763674636995 0.218260437918594 -0.448746246552257 -0.889462601094904 0.0865048406665698 -1.92768227733995 0.250915208587804 -0.0324993928400876 0.967463357220502 0.581323753905172 5.787595921735e-05 -1.13236579801818e-05 -1.46603309811142e-06 -1.10774339300306e-06 -3.60189770799898e-05 -5.70745372550856e-06 -1.13236579801818e-05 0.000100469953429094 8.01581794671892e-06 4.9306134765767e-06 3.61212357366477e-05 1.07317818557173e-06 -1.46603309811142e-06 8.01581794671892e-06 2.1890266618262e-05 -8.97229516560138e-07 1.39879516428476e-05 1.99225230340411e-06 -1.10774339300306e-06 4.9306134765767e-06 -8.97229516560138e-07 2.93181164295351e-05 -6.36075957146312e-06 1.42716573118913e-05 -3.60189770799898e-05 3.61212357366477e-05 1.39879516428476e-05 -6.36075957146312e-06 0.000164835164880044 -3.15426576379054e-05 -5.70745372550856e-06 1.07317818557173e-06 1.99225230340411e-06 1.42716573118913e-05 -3.15426576379054e-05 0.000121065103249914 0 0 0 0 107 0 0 0 0 107 0 0 0 0 0 0 0 0 0 769 151 151 0 1428 0 +285 433 -0.914871423789697 0.364954674849062 0.172679944518259 0.213534905916199 -0.350059172341945 -0.930112341279596 0.111128792212735 -1.93995989733704 0.201168719716276 0.041220357897579 0.978688933370818 0.66581560252999 4.45876414705417e-05 2.60183639301512e-05 2.89324969519787e-06 8.11265490949918e-06 -9.42390580974278e-06 2.70050440939857e-05 2.60183639301512e-05 5.79228280821101e-05 -4.16206417391001e-06 1.57189175782174e-06 2.38525662400781e-05 8.43491730736963e-06 2.89324969519787e-06 -4.16206417391001e-06 1.89995381690184e-05 2.68451504971214e-07 -6.19445192188536e-06 2.74165708481296e-06 8.11265490949918e-06 1.57189175782174e-06 2.68451504971214e-07 2.93176028125042e-05 -5.12023563201215e-06 1.48580782322178e-05 -9.42390580974278e-06 2.38525662400781e-05 -6.19445192188536e-06 -5.12023563201215e-06 0.000138893413735666 -3.74337686932255e-05 2.70050440939857e-05 8.43491730736963e-06 2.74165708481296e-06 1.48580782322178e-05 -3.74337686932255e-05 0.000243109065458134 0 0 0 0 257 0 0 0 0 257 0 0 0 0 0 0 0 0 0 758 187 187 0 1001 0 +285 432 -0.949465844972729 0.248083694087971 0.192273477000566 0.219700727752114 -0.229184975659347 -0.966525717178078 0.115335532102753 -1.93843276899926 0.214450125115947 0.0654409562970074 0.97454021213939 0.734901553186803 4.60166637515894e-05 1.21153613957598e-05 9.86583417173627e-07 -1.55833711851859e-06 -1.27835103092306e-05 -2.51663967665952e-05 1.21153613957598e-05 6.43223831596366e-05 3.86193847042353e-06 2.15538575894019e-06 1.47723930837207e-05 6.93419249777731e-06 9.86583417173627e-07 3.86193847042353e-06 1.9116181064965e-05 -1.43719165713352e-06 3.86804053462789e-06 8.98616321426129e-06 -1.55833711851859e-06 2.15538575894019e-06 -1.43719165713352e-06 2.88498574272335e-05 -5.17508646942459e-06 6.00327401411704e-06 -1.27835103092306e-05 1.47723930837207e-05 3.86804053462789e-06 -5.17508646942459e-06 7.67441068929131e-05 3.6727730459827e-05 -2.51663967665952e-05 6.93419249777731e-06 8.98616321426129e-06 6.00327401411704e-06 3.6727730459827e-05 0.000200523510455757 0 0 0 0 410 0 0 0 0 410 0 0 0 0 0 0 0 0 0 753 167 167 0 728 0 +285 402 -0.973863731117851 -0.120670546034039 0.192426745888054 0.194840940963891 0.121651437063517 -0.992549904894599 -0.00675382514598662 -1.95824998012131 0.19180813609855 0.0168316848107499 0.981288099037603 0.799657856949889 0.000137727078043086 8.79019184612698e-05 -1.30212286826186e-05 2.71076526905558e-05 -3.18257596258047e-05 9.98166377565002e-06 8.79019184612698e-05 8.79152115850698e-05 -9.26098015447317e-06 1.50697518320712e-05 -1.18222923417917e-05 4.09890061970498e-06 -1.30212286826186e-05 -9.26098015447317e-06 2.04322453659016e-05 -1.94876114141442e-06 1.45459173682433e-07 7.1308477345309e-07 2.71076526905558e-05 1.50697518320712e-05 -1.94876114141442e-06 4.00558869899786e-05 -1.34282610179734e-05 4.84452250240025e-06 -3.18257596258047e-05 -1.18222923417917e-05 1.45459173682433e-07 -1.34282610179734e-05 6.75636892925753e-05 -1.82301234115749e-05 9.98166377565002e-06 4.09890061970498e-06 7.1308477345309e-07 4.84452250240025e-06 -1.82301234115749e-05 0.000415374642833644 0 0 0 0 469 0 0 0 0 469 0 0 0 0 0 0 0 0 0 540 37 58 0 326 0 +285 401 -0.972681364384355 -0.120556239744162 0.198386381685181 0.201800487076966 0.121339678595272 -0.992576766448425 -0.00824894570147401 -1.95685186177947 0.197908175116103 0.0160485440317165 0.980089178828476 0.812440511951079 0.000102818717258242 8.17983114111498e-05 -3.99579603287731e-06 1.8707968662818e-05 -3.55370005837156e-05 -3.80909358297504e-05 8.17983114111498e-05 0.000106438545595479 -2.14494299829377e-06 1.84997944398882e-05 -2.75554020757172e-05 -6.30167402154232e-05 -3.99579603287731e-06 -2.14494299829377e-06 1.93357292262257e-05 -4.56221696200855e-06 2.24813412471756e-06 2.78801183302935e-06 1.8707968662818e-05 1.84997944398882e-05 -4.56221696200855e-06 3.541508370919e-05 -4.40358244897722e-06 -3.05865816434638e-06 -3.55370005837156e-05 -2.75554020757172e-05 2.24813412471756e-06 -4.40358244897722e-06 5.64321268820238e-05 -4.90886855602612e-06 -3.80909358297504e-05 -6.30167402154232e-05 2.78801183302935e-06 -3.05865816434638e-06 -4.90886855602612e-06 0.000415587889758862 0 0 0 0 478 0 0 0 0 478 0 0 0 0 0 0 0 0 0 546 40 60 0 360 0 +286 288 0.977612190386431 0.210111687257098 -0.0112908850768785 0.146400240670516 -0.209476789211025 0.976912927711162 0.0419595811781576 -0.235621693884053 0.0198464099948475 -0.0386550197100208 0.999055508698858 -0.0394558251576667 4.22591596520246e-05 1.12283089130852e-05 -1.60553306766556e-06 -9.51482320180455e-07 3.32275334562163e-07 8.95777947039482e-06 1.12283089130852e-05 4.39219661048653e-05 3.92284091241607e-07 -1.6824864304601e-06 -7.92070316033338e-07 -2.18638461029531e-05 -1.60553306766556e-06 3.92284091241607e-07 1.23469298913331e-05 -1.64159273135291e-06 1.59224071978175e-06 -1.07370321563665e-07 -9.51482320180455e-07 -1.6824864304601e-06 -1.64159273135291e-06 5.20648369666993e-05 -1.78291788256799e-05 2.78163562088329e-05 3.32275334562163e-07 -7.92070316033338e-07 1.59224071978175e-06 -1.78291788256799e-05 2.82490053570564e-05 -1.34684727249772e-06 8.95777947039482e-06 -2.18638461029531e-05 -1.07370321563665e-07 2.78163562088329e-05 -1.34684727249772e-06 0.000183721060164459 3288 3136 0 1188 0 3263 3111 0 1116 0 0 0 0 0 0 0 0 0 2258 0 368 341 0 0 3313 +286 434 -0.785301152908141 0.56962184977445 0.242555246285624 0.380465481719756 -0.56397906208027 -0.819798892410673 0.0992844073220595 -1.75357758713924 0.255401090005904 -0.0588279207670002 0.965043811939141 0.543825261616238 5.54289820143488e-05 2.43276023432969e-05 3.22493998853571e-07 3.2223834300484e-06 -2.71151437498906e-05 3.64743252941695e-05 2.43276023432969e-05 6.2965319702051e-05 7.83377175887802e-07 4.23578191573177e-06 -5.09592040828971e-06 2.51608430829565e-05 3.22493998853571e-07 7.83377175887802e-07 1.90182015160431e-05 -5.53013521786189e-07 6.83494058644664e-06 -7.42168756442932e-06 3.2223834300484e-06 4.23578191573177e-06 -5.53013521786189e-07 2.70636368010652e-05 -3.10322831635531e-06 1.61615783211169e-05 -2.71151437498906e-05 -5.09592040828971e-06 6.83494058644664e-06 -3.10322831635531e-06 0.000160897737670957 1.51417542269519e-05 3.64743252941695e-05 2.51608430829565e-05 -7.42168756442932e-06 1.61615783211169e-05 1.51417542269519e-05 0.000345666819711314 0 0 0 401 40 0 0 0 345 23 0 0 0 0 0 0 0 0 0 845 331 331 0 1292 0 +286 431 -0.942151840293256 0.241337993632322 0.232606712417238 0.394287523041168 -0.223404451275277 -0.969479801748075 0.100991906373264 -1.79812157533094 0.249880693496762 0.0431843354937755 0.967313161383395 0.714579795325213 4.79983667701681e-05 3.86907259801377e-05 8.82630662304843e-06 5.98320190092562e-06 -1.27305269440856e-05 2.99504086355037e-05 3.86907259801377e-05 8.386783955179e-05 1.10396698873674e-05 1.1914681021531e-05 -6.69799427806903e-06 4.82595766663471e-05 8.82630662304843e-06 1.10396698873674e-05 2.08899661600026e-05 1.87531708360833e-06 -3.64675945660242e-06 -7.00517525795572e-06 5.98320190092562e-06 1.1914681021531e-05 1.87531708360833e-06 5.791820256098e-05 -5.44440128449388e-05 5.06807943073342e-05 -1.27305269440856e-05 -6.69799427806903e-06 -3.64675945660242e-06 -5.44440128449388e-05 0.000137742417501831 -1.42285953724593e-05 2.99504086355037e-05 4.82595766663471e-05 -7.00517525795572e-06 5.06807943073342e-05 -1.42285953724593e-05 0.00044163673323543 0 0 0 65 449 0 0 0 40 433 0 0 0 0 0 0 0 0 0 667 300 300 0 571 0 +286 432 -0.90760358269306 0.375917694219367 0.186926787420947 0.386439093936352 -0.35981043481452 -0.925908720345389 0.115019531328166 -1.7719049072706 0.21631501954628 0.0371339300527077 0.975617180843764 0.679377679332468 5.22364410458386e-05 7.59681573460551e-06 2.28083882913381e-06 5.55631893834096e-08 -9.63860042268084e-06 -1.30258262683148e-06 7.59681573460551e-06 5.10175985112179e-05 2.61408313734382e-06 4.46954360129218e-06 7.87191628295032e-06 -2.30445321630866e-05 2.28083882913381e-06 2.61408313734382e-06 1.89562964874443e-05 -1.25096083143851e-06 2.3791305105554e-07 -7.35155226725483e-07 5.55631893834096e-08 4.46954360129218e-06 -1.25096083143851e-06 2.91303305096299e-05 -8.80388940761636e-06 -2.56304513310909e-06 -9.63860042268084e-06 7.87191628295032e-06 2.3791305105554e-07 -8.80388940761636e-06 8.35903469601469e-05 3.36670684288455e-05 -1.30258262683148e-06 -2.30445321630866e-05 -7.35155226725483e-07 -2.56304513310909e-06 3.36670684288455e-05 0.00018652421540802 0 0 0 212 338 0 0 0 183 325 0 0 0 0 0 0 0 0 0 815 370 370 0 754 0 +286 290 0.916897872466969 0.395492497301065 0.0537026632869576 0.284140504380304 -0.398942554124668 0.912185027370806 0.0936125758058645 -0.473116307063728 -0.0119636939960519 -0.107257449247546 0.994159297902946 -0.0600013156085325 5.72149782236904e-05 3.49904730890288e-05 -7.72004360919246e-06 -9.45270567232507e-07 5.06695934555684e-06 6.70751264209891e-05 3.49904730890288e-05 4.87425730232451e-05 -7.00457063098e-06 1.3539986028467e-05 -1.08739161759779e-06 5.01496379119469e-05 -7.72004360919246e-06 -7.00457063098e-06 1.59749250646096e-05 -7.28245429355211e-06 -2.74010956128104e-06 -1.9378621043084e-06 -9.45270567232507e-07 1.3539986028467e-05 -7.28245429355211e-06 8.68551148207105e-05 -1.4238598142013e-05 2.47714148997344e-05 5.06695934555684e-06 -1.08739161759779e-06 -2.74010956128104e-06 -1.4238598142013e-05 2.87894341033039e-05 -7.24700991362525e-06 6.70751264209891e-05 5.01496379119469e-05 -1.9378621043084e-06 2.47714148997344e-05 -7.24700991362525e-06 0.000348930664815751 2618 2492 0 2376 0 2574 2448 0 2332 0 0 0 0 0 0 0 0 0 887 0 869 863 0 0 2749 +286 289 0.949471985357977 0.313167008532387 0.0207213365219978 0.21503265606106 -0.313849743403829 0.947155459561684 0.0662938457765543 -0.351539049801874 0.0011347183497258 -0.069447535516894 0.997584959903113 -0.0555788548748417 2.88651260782695e-05 6.98266947971787e-06 -2.10806290766222e-06 -6.23065672335888e-07 -1.91339058018968e-07 9.54680338554585e-06 6.98266947971787e-06 4.01025655112885e-05 2.21966971578321e-06 -6.57185464944528e-06 -9.79721055863524e-07 -1.9101577871201e-06 -2.10806290766222e-06 2.21966971578321e-06 1.71416317091047e-05 -1.05547257608866e-05 -6.18315949721314e-07 -2.77322134743339e-06 -6.23065672335888e-07 -6.57185464944528e-06 -1.05547257608866e-05 7.94475145638886e-05 -1.2533177005857e-05 2.54267271307567e-05 -1.91339058018968e-07 -9.79721055863524e-07 -6.18315949721314e-07 -1.2533177005857e-05 2.68134782869313e-05 -8.08693655199934e-06 9.54680338554585e-06 -1.9101577871201e-06 -2.77322134743339e-06 2.54267271307567e-05 -8.08693655199934e-06 0.000128678496461072 3008 2868 0 1834 0 2973 2833 0 1778 0 0 0 0 0 0 0 0 0 1436 0 745 718 0 0 3042 +286 440 -0.449087020631838 0.842995210654513 0.296107957869378 0.591404696598295 -0.873863688044466 -0.48347869030645 0.0510941360322662 -1.89545620581479 0.186233999627735 -0.235812278800562 0.953786908355081 -0.0973655293823645 0.000128936061923709 7.88123404667733e-05 -8.85698211572105e-06 -1.99063000509329e-05 -4.54349050582039e-05 -7.44230545312855e-05 7.88123404667733e-05 0.000106280172569662 -1.56183691589891e-05 1.95359710269963e-05 3.79378405470052e-05 1.52434903758818e-05 -8.85698211572105e-06 -1.56183691589891e-05 2.71631844731237e-05 -3.31069292434621e-06 1.19403215081551e-05 1.56275504293219e-05 -1.99063000509329e-05 1.95359710269963e-05 -3.31069292434621e-06 0.000101089034394075 0.000136662199505964 0.000174345252047448 -4.54349050582039e-05 3.79378405470052e-05 1.19403215081551e-05 0.000136662199505964 0.000399207694237049 0.000380734169441807 -7.44230545312855e-05 1.52434903758818e-05 1.56275504293219e-05 0.000174345252047448 0.000380734169441807 0.000593748156849192 0 0 0 664 0 0 0 0 627 0 0 0 0 0 0 0 0 0 0 491 366 246 0 671 0 +286 433 -0.856258226563842 0.485851626114318 0.175413930016456 0.408996667787768 -0.472958228460579 -0.873946443578984 0.111929119924515 -1.7990627234223 0.207683325216965 0.0128767681395257 0.978111356272437 0.623088152324326 8.09927716473496e-05 5.33645298863083e-05 -1.55379610703371e-06 3.15473006408308e-06 -2.70680824938251e-06 6.8880393785466e-05 5.33645298863083e-05 7.81626222232091e-05 -8.63325386794099e-07 4.21581169849842e-06 2.9394398517275e-05 6.28556691010343e-05 -1.55379610703371e-06 -8.63325386794099e-07 2.29309669295933e-05 2.31617990058904e-06 -7.75105727634656e-06 -3.1108722812626e-06 3.15473006408308e-06 4.21581169849842e-06 2.31617990058904e-06 3.12789321444741e-05 -2.0528049760254e-05 1.15754134734076e-06 -2.70680824938251e-06 2.9394398517275e-05 -7.75105727634656e-06 -2.0528049760254e-05 0.000184334394821391 6.803198446202e-05 6.8880393785466e-05 6.28556691010343e-05 -3.1108722812626e-06 1.15754134734076e-06 6.803198446202e-05 0.000476057610476293 0 0 0 262 197 0 0 0 240 184 0 0 0 0 0 0 0 0 0 855 377 377 0 988 0 +286 402 -0.975931997326457 0.00623313997176523 0.217985973311323 0.406780736130688 -0.0118819334504328 -0.999626456135047 -0.0246123516220431 -1.84201038729153 0.217751133755652 -0.0266100763054145 0.975641505670576 0.789220204662946 0.00011084289000853 0.000101759892263742 -9.82900675911343e-06 2.24794750720715e-05 -3.20806351293202e-05 6.670524528945e-05 0.000101759892263742 0.000158278553550612 -9.23955853001401e-06 2.29690174301905e-05 -3.09279006395473e-05 9.0822197909104e-05 -9.82900675911343e-06 -9.23955853001401e-06 2.05489390069671e-05 -3.40904068538245e-06 6.69528600695977e-07 -1.06720248053269e-05 2.24794750720715e-05 2.29690174301905e-05 -3.40904068538245e-06 6.91004936116495e-05 -4.41104462095204e-05 4.96522682664986e-05 -3.20806351293202e-05 -3.09279006395473e-05 6.69528600695977e-07 -4.41104462095204e-05 8.65200781892078e-05 -4.84786086082499e-05 6.670524528945e-05 9.0822197909104e-05 -1.06720248053269e-05 4.96522682664986e-05 -4.84786086082499e-05 0.000439419433184888 0 0 0 0 409 0 0 0 0 402 0 0 0 0 0 0 0 0 0 515 190 220 0 374 0 +286 336 -0.928936209576589 0.0973855079077818 0.357202437543507 0.379349531384345 -0.0745391304218779 -0.994224297790961 0.0772137534252879 -1.85105409405473 0.362658843230701 0.0451010923550001 0.93082998173402 0.68252583689916 9.27464116328846e-05 2.64927790061947e-05 -5.71731877577547e-06 1.57380144361512e-05 -3.07098937831255e-05 -6.76483243126728e-06 2.64927790061947e-05 0.000147538165380472 3.15132681854561e-06 5.19018636737035e-05 -1.59027143478637e-05 6.74969267278348e-05 -5.71731877577547e-06 3.15132681854561e-06 2.48065102935438e-05 -2.83012088701674e-06 -3.62212386717467e-07 3.16138221290999e-06 1.57380144361512e-05 5.19018636737035e-05 -2.83012088701674e-06 0.000158198167195916 -9.71508229682088e-05 0.000193142371527568 -3.07098937831255e-05 -1.59027143478637e-05 -3.62212386717467e-07 -9.71508229682088e-05 0.000159740989719215 -8.61954916385181e-05 -6.76483243126728e-06 6.74969267278348e-05 3.16138221290999e-06 0.000193142371527568 -8.61954916385181e-05 0.000533841456872858 0 0 0 1 771 0 0 0 0 771 0 0 0 0 0 0 0 0 0 524 133 148 0 503 0 +287 289 0.976387383475788 0.210900532724625 0.0467829315645595 0.152072006002401 -0.2128671736005 0.976178644002501 0.041985966664737 -0.214773210888878 -0.0368136359606021 -0.0509531185493776 0.998022312334475 -0.0569014466266602 6.59707858633438e-05 2.61373335977715e-05 -1.07871794079408e-05 1.56586107823867e-05 -3.74346362233664e-06 8.50455649989621e-05 2.61373335977715e-05 6.25799122096794e-05 -2.19787587006424e-06 5.93313988307298e-06 -3.15386075476214e-06 3.94191901867588e-05 -1.07871794079408e-05 -2.19787587006424e-06 1.71384891311202e-05 -8.35340101762229e-06 1.32260001200533e-06 -1.81205345059483e-05 1.56586107823867e-05 5.93313988307298e-06 -8.35340101762229e-06 6.6951849203594e-05 -8.87860495399164e-06 5.18711586028993e-05 -3.74346362233664e-06 -3.15386075476214e-06 1.32260001200533e-06 -8.87860495399164e-06 2.58724609494617e-05 -5.02884477785185e-08 8.50455649989621e-05 3.94191901867588e-05 -1.81205345059483e-05 5.18711586028993e-05 -5.02884477785185e-08 0.000305453760024729 3216 3076 0 1258 0 3185 3045 0 1108 0 0 0 0 0 0 0 0 0 2165 0 521 494 0 0 3237 +287 436 -0.620089356160633 0.745491282271935 0.24440118337037 0.515051340193841 -0.752871087776711 -0.653059468889187 0.081844091320541 -1.65666873323194 0.220622563592674 -0.133251934885459 0.966214058210228 0.276300368463848 7.763107087661e-05 5.07526620566779e-06 -7.99429311482825e-06 -1.18823514866978e-05 -4.86005204033647e-05 1.23853889612307e-05 5.07526620566779e-06 9.452932040492e-05 7.28024744409611e-06 1.64838108276748e-05 9.03212246005241e-05 7.99053169647846e-05 -7.99429311482825e-06 7.28024744409611e-06 2.09514024500258e-05 -1.2703062840306e-06 1.25999266105159e-05 -7.14114188400553e-06 -1.18823514866978e-05 1.64838108276748e-05 -1.2703062840306e-06 3.89902336727087e-05 3.74807396881373e-05 2.44035678919912e-05 -4.86005204033647e-05 9.03212246005241e-05 1.25999266105159e-05 3.74807396881373e-05 0.000386528902140692 0.000170408765583422 1.23853889612307e-05 7.99053169647846e-05 -7.14114188400553e-06 2.44035678919912e-05 0.000170408765583422 0.00043615620273838 0 0 0 777 0 0 0 0 777 0 0 0 0 0 0 0 0 0 0 582 331 331 0 1277 0 +287 290 0.952138002027622 0.296486939210785 0.0743553627673733 0.234329564279816 -0.301718857756894 0.950582981236181 0.0731964934816477 -0.331924589296929 -0.0489791380969716 -0.0921275781813153 0.994541881154194 -0.0748125609408797 5.70010484699886e-05 3.44365101504803e-05 -6.27477509030104e-06 1.58350808582766e-05 -1.80354255877123e-06 4.96466164440089e-05 3.44365101504803e-05 5.87932406586286e-05 -4.10151482448828e-06 1.62817445577883e-05 -1.3927469403727e-06 1.84607442617417e-05 -6.27477509030104e-06 -4.10151482448828e-06 1.7066925257124e-05 -1.58996120735568e-05 -1.5776401733151e-06 -1.1364647635944e-05 1.58350808582766e-05 1.62817445577883e-05 -1.58996120735568e-05 0.000103042467862334 -6.53965888942898e-06 5.00206648975176e-05 -1.80354255877123e-06 -1.3927469403727e-06 -1.5776401733151e-06 -6.53965888942898e-06 2.53056358839819e-05 -1.33637006443179e-05 4.96466164440089e-05 1.84607442617417e-05 -1.1364647635944e-05 5.00206648975176e-05 -1.33637006443179e-05 0.000321557473307436 2862 2736 0 1883 0 2838 2712 0 1745 0 0 0 0 0 0 0 0 0 1480 0 664 658 0 0 2953 +287 435 -0.661015095495337 0.711628568727525 0.237999629617577 0.530125673625357 -0.705086251426635 -0.69757026920958 0.127471948145506 -1.66568765182816 0.256734145715809 -0.0835493847116068 0.962863998048471 0.383516165315001 5.25111394156583e-05 3.41604837603899e-05 4.68817682773445e-06 1.04964154467976e-07 -1.56249099763227e-05 3.59133614704027e-05 3.41604837603899e-05 9.75067180315078e-05 7.63164121406409e-06 1.83742697751166e-05 -3.50430841669248e-05 9.38565797124129e-05 4.68817682773445e-06 7.63164121406409e-06 1.77570724219972e-05 -2.04987401866537e-06 -2.69920556771728e-06 -3.29868993169918e-06 1.04964154467976e-07 1.83742697751166e-05 -2.04987401866537e-06 3.01583264879234e-05 -1.12772030392235e-05 5.34612982999729e-05 -1.56249099763227e-05 -3.50430841669248e-05 -2.69920556771728e-06 -1.12772030392235e-05 0.000188369622684155 -5.6917400604053e-05 3.59133614704027e-05 9.38565797124129e-05 -3.29868993169918e-06 5.34612982999729e-05 -5.6917400604053e-05 0.000391590694054369 0 0 0 625 0 0 0 0 609 0 0 0 0 0 0 0 0 0 0 540 351 351 0 1314 0 +287 291 0.927131823129761 0.360238110043277 0.103223478979022 0.32014228904026 -0.36939846531472 0.924894284791456 0.0900851585070024 -0.446767369526313 -0.0630186985204769 -0.121651411962828 0.990570329458861 -0.09504346791841 8.03522675425218e-05 4.59893400285764e-05 -6.06786298429955e-06 -3.01760977220063e-06 9.19919125166466e-06 0.000106996176644595 4.59893400285764e-05 6.59308982220108e-05 -9.49846343434777e-06 2.64399227998136e-05 -3.03603702523876e-06 6.67377998961366e-05 -6.06786298429955e-06 -9.49846343434777e-06 1.65150129398683e-05 -8.32730749121311e-06 2.70026205482806e-06 -2.38269560425907e-05 -3.01760977220063e-06 2.64399227998136e-05 -8.32730749121311e-06 0.000129014930159658 -2.41557726272736e-05 0.000112664023542025 9.19919125166466e-06 -3.03603702523876e-06 2.70026205482806e-06 -2.41557726272736e-05 2.78121768892983e-05 -1.5537727361214e-05 0.000106996176644595 6.67377998961366e-05 -2.38269560425907e-05 0.000112664023542025 -1.5537727361214e-05 0.000579420103744435 2599 2487 0 2339 0 2579 2467 0 2231 0 0 0 0 0 0 0 0 0 966 0 935 921 0 0 2712 +287 432 -0.856494033862789 0.470383701369604 0.212502102209081 0.52704078747307 -0.455990437459483 -0.882459691878313 0.1154885845248 -1.65250389945587 0.241848487493631 0.00201635707737051 0.970311930979507 0.630118872562685 0.0001080262221908 3.14503977283961e-05 -1.17855493736634e-05 -2.24896036349329e-06 -1.76492164631337e-05 9.73125432347291e-05 3.14503977283961e-05 8.14468074194377e-05 1.72834844317418e-06 6.27487340242039e-06 -5.79682632421393e-06 -1.16431076606714e-05 -1.17855493736634e-05 1.72834844317418e-06 2.0977138177557e-05 -3.07604896303333e-06 3.13492556357899e-06 -2.04814998245564e-05 -2.24896036349329e-06 6.27487340242039e-06 -3.07604896303333e-06 2.93508259500018e-05 -5.81790155910993e-06 -1.30053876815565e-05 -1.76492164631337e-05 -5.79682632421393e-06 3.13492556357899e-06 -5.81790155910993e-06 6.80007812031536e-05 4.61896143118683e-05 9.73125432347291e-05 -1.16431076606714e-05 -2.04814998245564e-05 -1.30053876815565e-05 4.61896143118683e-05 0.00044580711102 0 0 0 213 284 0 0 0 210 261 0 0 0 0 0 0 0 0 0 752 419 419 0 789 0 +287 434 -0.711405455951067 0.649999710573023 0.267212749505035 0.522596304381785 -0.647607750390162 -0.753996363775013 0.109971291929537 -1.63872410184368 0.27295874940666 -0.0948148705058658 0.957341977275262 0.486051316758644 7.93491876480785e-05 3.9525047522837e-05 -1.43148036413518e-06 -5.81792513503399e-07 -3.55225313557465e-05 9.18309725820912e-05 3.9525047522837e-05 7.45181957056796e-05 1.97963497851218e-06 4.89171697897039e-06 -5.07502649316278e-06 4.4491181472943e-05 -1.43148036413518e-06 1.97963497851218e-06 1.83463942599208e-05 -3.7969677150201e-06 4.61687869236604e-06 -1.9482051631661e-05 -5.81792513503399e-07 4.89171697897039e-06 -3.7969677150201e-06 2.8914177893955e-05 -1.49650961315491e-06 2.05540423136193e-05 -3.55225313557465e-05 -5.07502649316278e-06 4.61687869236604e-06 -1.49650961315491e-06 9.58216894032562e-05 -5.32348273041275e-05 9.18309725820912e-05 4.4491181472943e-05 -1.9482051631661e-05 2.05540423136193e-05 -5.32348273041275e-05 0.000460062961976192 0 0 0 600 0 0 0 0 600 0 0 0 0 0 0 0 0 0 0 774 386 386 0 1234 0 +287 438 -0.546785571482232 0.788283756068162 0.282195426500714 0.607840248911472 -0.821109968370862 -0.570760099166269 0.00336586418490992 -1.68890884462627 0.163719145675912 -0.229873071756526 0.959351037014277 0.0945080430234537 6.54248217763183e-05 5.26672165618906e-05 3.79095110018724e-07 -7.2484188331571e-06 -4.98885922995721e-05 5.07963278764583e-05 5.26672165618906e-05 6.75854166312761e-05 -8.37160533185238e-07 -4.54555655124208e-06 -2.97670510507305e-05 5.16560003425041e-05 3.79095110018724e-07 -8.37160533185238e-07 1.61843367125817e-05 -8.6019365288471e-07 1.31951289703984e-05 -1.82666205463198e-05 -7.2484188331571e-06 -4.54555655124208e-06 -8.6019365288471e-07 2.58912340304972e-05 2.39766582215228e-05 -1.87423387540064e-05 -4.98885922995721e-05 -2.97670510507305e-05 1.31951289703984e-05 2.39766582215228e-05 0.000365164500450102 -0.000276201687433649 5.07963278764583e-05 5.16560003425041e-05 -1.82666205463198e-05 -1.87423387540064e-05 -0.000276201687433649 0.000898811182307647 0 0 0 831 0 0 0 0 814 0 0 0 0 0 0 0 0 0 0 411 291 291 0 1075 0 +287 433 -0.797073536881646 0.571802207010216 0.194206109227359 0.528746764064311 -0.564210372159066 -0.819789349059719 0.0980412113163177 -1.66241530768813 0.215268280875543 -0.0314270460986741 0.976049131971542 0.574577534512787 6.16370464517695e-05 5.0743909365623e-05 -3.96177607267139e-06 -4.97676403014328e-07 2.53811521318105e-06 8.83479710481151e-06 5.0743909365623e-05 8.37419187503921e-05 -6.92593960186879e-06 3.98555641025072e-06 3.28327243855922e-06 1.73424182424802e-07 -3.96177607267139e-06 -6.92593960186879e-06 1.70350970198211e-05 -1.63457940390649e-07 -5.24748925891905e-06 4.20417842951318e-06 -4.97676403014328e-07 3.98555641025072e-06 -1.63457940390649e-07 2.79575359778871e-05 -1.82200956540406e-05 -4.51861896918975e-06 2.53811521318105e-06 3.28327243855922e-06 -5.24748925891905e-06 -1.82200956540406e-05 0.000139538605983982 4.70770135804575e-05 8.83479710481151e-06 1.73424182424802e-07 4.20417842951318e-06 -4.51861896918975e-06 4.70770135804575e-05 0.000271784564077716 0 0 0 349 124 0 0 0 343 101 0 0 0 0 0 0 0 0 0 782 525 525 0 1120 0 +287 431 -0.905883842152119 0.337684654661494 0.255623822312909 0.529863900585518 -0.326034314052367 -0.941252356527597 0.0880092460577123 -1.68002012352498 0.270325896998634 -0.00361598359956179 0.962762085914527 0.670445120581551 6.18427824625239e-05 5.74351766942641e-05 4.15462662302219e-07 6.63780514970997e-06 -1.07655103434331e-05 2.22375506518963e-05 5.74351766942641e-05 0.000104444805222548 -4.47967373288621e-06 1.07993291922225e-05 6.75828020650473e-08 5.63756749054529e-05 4.15462662302219e-07 -4.47967373288621e-06 2.02518098417466e-05 4.16345695568817e-06 -1.00133527222862e-05 -1.09390378680881e-05 6.63780514970997e-06 1.07993291922225e-05 4.16345695568817e-06 5.03316299345131e-05 -4.34666412660205e-05 8.78173729226874e-06 -1.07655103434331e-05 6.75828020650473e-08 -1.00133527222862e-05 -4.34666412660205e-05 0.000119059399436736 5.00629754105436e-05 2.22375506518963e-05 5.63756749054529e-05 -1.09390378680881e-05 8.78173729226874e-06 5.00629754105436e-05 0.000310952981320497 0 0 0 83 412 0 0 0 82 393 0 0 0 0 0 0 0 0 0 617 422 422 0 541 0 +287 402 -0.965664969131189 0.114207045059907 0.233340777086956 0.513386396158486 -0.118418552526561 -0.99295541991425 -0.00407191360789135 -1.68885029985159 0.231231948074599 -0.0315639813965294 0.972386497884471 0.715810135056402 0.000270219662049495 0.000143614768145384 -5.71400619130212e-05 5.96589320256991e-06 -2.76762116482873e-05 0.000270235451563728 0.000143614768145384 0.00024487025941008 -3.04863839378918e-05 1.20787732515755e-05 4.10557032152411e-06 0.000205966848938084 -5.71400619130212e-05 -3.04863839378918e-05 3.12181544296774e-05 -4.4268384258217e-08 1.7361004066484e-07 -7.46679531647386e-05 5.96589320256991e-06 1.20787732515755e-05 -4.4268384258217e-08 5.69666591868301e-05 -3.23301580820501e-05 -9.77134519183431e-06 -2.76762116482873e-05 4.10557032152411e-06 1.7361004066484e-07 -3.23301580820501e-05 8.61415070470064e-05 2.40733931318779e-05 0.000270235451563728 0.000205966848938084 -7.46679531647386e-05 -9.77134519183431e-06 2.40733931318779e-05 0.000809799131793721 0 0 0 0 447 0 0 0 0 435 0 0 0 0 0 0 0 0 0 564 338 368 0 359 0 +287 405 -0.964203087440134 0.111679022847125 0.240499900263649 0.520845158822171 -0.118147379015667 -0.992916134907722 -0.01259943933825 -1.70092263956595 0.237389138341757 -0.0405628511796347 0.970567386687569 0.710997518880164 0.000101974100148064 7.65012836551041e-05 -1.44681493333317e-05 -1.16517794314758e-05 -6.45689755740785e-06 2.92892175186769e-05 7.65012836551041e-05 0.000116773971287868 -1.06228103676945e-05 -1.34821934660878e-07 -1.63567099107811e-05 8.61721679731122e-06 -1.44681493333317e-05 -1.06228103676945e-05 2.01372465016817e-05 2.27861210025037e-06 -5.1993133683782e-06 -1.47313541310768e-05 -1.16517794314758e-05 -1.34821934660878e-07 2.27861210025037e-06 6.3674642673146e-05 -3.19484665628474e-05 -3.50046339103204e-05 -6.45689755740785e-06 -1.63567099107811e-05 -5.1993133683782e-06 -3.19484665628474e-05 8.05161450130132e-05 4.72985485408082e-05 2.92892175186769e-05 8.61721679731122e-06 -1.47313541310768e-05 -3.50046339103204e-05 4.72985485408082e-05 0.000304026787326502 0 0 0 0 451 0 0 0 0 437 0 0 0 0 0 0 0 0 0 530 368 399 0 355 0 +288 291 0.961871039446359 0.262536574349907 0.0766723587937458 0.278620335096814 -0.268543993491782 0.959703310882434 0.0827869472850595 -0.30868055505261 -0.0518481150464179 -0.100220268458578 0.993613441312175 -0.0626161894151888 4.06285615902423e-05 2.13022760480211e-05 4.62175438153543e-06 -1.064079185394e-05 2.08014492844869e-06 2.69534123719404e-05 2.13022760480211e-05 4.14909893619288e-05 -3.92898636031553e-07 1.22508311529855e-05 -2.15417812222859e-06 1.41068824860302e-05 4.62175438153543e-06 -3.92898636031553e-07 1.54550694786045e-05 -9.23326253883714e-06 2.80567252543386e-06 -1.55447630273818e-06 -1.064079185394e-05 1.22508311529855e-05 -9.23326253883714e-06 9.98616770402312e-05 -1.2130739466891e-05 1.58780516610798e-05 2.08014492844869e-06 -2.15417812222859e-06 2.80567252543386e-06 -1.2130739466891e-05 2.06969895353446e-05 -3.54339250420335e-06 2.69534123719404e-05 1.41068824860302e-05 -1.55447630273818e-06 1.58780516610798e-05 -3.54339250420335e-06 0.000275839160217981 2886 2774 0 1830 0 2852 2740 0 1692 0 0 0 0 0 0 0 0 0 1691 0 726 712 0 0 2924 +288 436 -0.542092235500665 0.811778307019743 0.217145086202872 0.605595996402371 -0.81842035865258 -0.568641804538085 0.0826717283879652 -1.50592251554031 0.190588889374157 -0.132900257275264 0.972632200198664 0.288783635941289 0.00013284480655028 1.58609194808775e-05 -1.89170178096125e-05 -8.84916959189635e-06 -5.14666465859634e-07 0.000144066489398795 1.58609194808775e-05 4.15414439571931e-05 -5.47732154083402e-07 3.45022737351788e-06 8.59026903396545e-06 3.89643782035032e-06 -1.89170178096125e-05 -5.47732154083402e-07 2.43862520791231e-05 -1.46886634947169e-06 2.47509107149301e-06 -3.15897494852056e-05 -8.84916959189635e-06 3.45022737351788e-06 -1.46886634947169e-06 2.83300156053283e-05 5.16785154923682e-06 -5.45361049813554e-06 -5.14666465859634e-07 8.59026903396545e-06 2.47509107149301e-06 5.16785154923682e-06 0.000316373182492813 0.000123496848521042 0.000144066489398795 3.89643782035032e-06 -3.15897494852056e-05 -5.45361049813554e-06 0.000123496848521042 0.000627054444873166 0 0 0 1200 0 0 0 0 1166 0 0 0 0 0 0 0 0 0 0 310 404 404 0 1055 0 +288 290 0.979399984940674 0.194738654196152 0.0534090447403621 0.185305750362999 -0.197932543644512 0.978190329926003 0.0629792553597625 -0.204013488842997 -0.0399797156645715 -0.0722532698300097 0.996584711569594 -0.0326208256400653 8.30194454682981e-05 3.20737315235734e-05 -9.44420255921653e-06 2.17311491556723e-05 -4.49966820970401e-06 0.000131320629745577 3.20737315235734e-05 4.8620588523637e-05 -3.28848024857072e-06 1.41962045192038e-05 -3.71126361656128e-06 5.28615695545849e-05 -9.44420255921653e-06 -3.28848024857072e-06 1.71313009703739e-05 -1.1926429048585e-05 -2.56906544479154e-06 -1.6688631009778e-05 2.17311491556723e-05 1.41962045192038e-05 -1.1926429048585e-05 7.89624368585101e-05 -6.20628585992465e-06 8.8989442171609e-05 -4.49966820970401e-06 -3.71126361656128e-06 -2.56906544479154e-06 -6.20628585992465e-06 2.44881184335742e-05 -3.05751509346461e-05 0.000131320629745577 5.28615695545849e-05 -1.6688631009778e-05 8.8989442171609e-05 -3.05751509346461e-05 0.000543277777199275 3145 3019 0 1261 0 3118 2992 0 1111 0 0 0 0 0 0 0 0 0 2199 0 473 467 0 0 3212 +288 292 0.942473124090829 0.324917133709412 0.0785701380203318 0.373837642046434 -0.331300969518537 0.939220213296097 0.0900280985699004 -0.405710297977364 -0.0445429900495193 -0.110879426216472 0.992835170045539 -0.0542296879345979 7.23443276033109e-05 4.62146657603852e-05 -1.44552083379794e-07 3.89223117808258e-07 3.94892530432103e-06 9.29643793205675e-05 4.62146657603852e-05 7.52943375365512e-05 3.710311370878e-06 5.19614159044354e-06 -9.97365401286454e-07 5.57350603270228e-05 -1.44552083379794e-07 3.710311370878e-06 1.42361166012409e-05 2.95888736691501e-06 3.29858980391247e-06 -1.2574983385303e-05 3.89223117808258e-07 5.19614159044354e-06 2.95888736691501e-06 5.46316963284968e-05 -5.23693069031242e-06 5.67970769305535e-05 3.94892530432103e-06 -9.97365401286454e-07 3.29858980391247e-06 -5.23693069031242e-06 1.92345752729353e-05 -6.83650067330438e-07 9.29643793205675e-05 5.57350603270228e-05 -1.2574983385303e-05 5.67970769305535e-05 -6.83650067330438e-07 0.000431833236794622 2618 2518 0 2326 0 2553 2453 0 2194 0 0 0 0 0 0 0 0 0 1220 0 893 891 0 0 2831 +288 432 -0.80816544360687 0.560698915373961 0.180236905372276 0.599885247035456 -0.548158203609709 -0.828012549458099 0.117973733327701 -1.49994525317672 0.215386163843195 -0.00345604374429997 0.976522839562163 0.643077226043544 0.000228645344496591 -7.12105966905305e-05 -3.26978601403653e-05 1.46745432963628e-05 -0.000118853947393861 0.000124752753088003 -7.12105966905305e-05 0.000132604662435217 2.15249034308005e-05 -7.42782178095475e-06 8.54208217730698e-05 3.73231748784152e-05 -3.26978601403653e-05 2.15249034308005e-05 2.84549667399111e-05 -8.78856277594584e-06 2.54584202321525e-05 -9.81736679278978e-06 1.46745432963628e-05 -7.42782178095475e-06 -8.78856277594584e-06 3.27661843921895e-05 -3.10919854282508e-05 1.08669098268386e-05 -0.000118853947393861 8.54208217730698e-05 2.54584202321525e-05 -3.10919854282508e-05 0.000180023500293178 2.77854878236515e-05 0.000124752753088003 3.73231748784152e-05 -9.81736679278978e-06 1.08669098268386e-05 2.77854878236515e-05 0.000601819826046983 0 0 0 295 160 0 0 0 272 135 0 0 0 0 0 0 0 0 0 610 476 476 0 774 0 +288 435 -0.583816785135728 0.783001305901766 0.214632048748346 0.604027357113229 -0.775172905142003 -0.616183732444911 0.139372073974546 -1.4968614802422 0.24138129282836 -0.085009192599317 0.966699802754775 0.413386178425048 7.16597045607576e-05 1.99419954117957e-05 1.94936877256655e-06 -3.04814562790047e-06 -2.43274700185988e-05 8.57828952339261e-05 1.99419954117957e-05 7.05214172396966e-05 5.81475327721591e-06 5.05362000833309e-06 -7.90598212100351e-06 6.512860179812e-05 1.94936877256655e-06 5.81475327721591e-06 1.85927244651749e-05 -7.63902287871604e-06 4.7313525945619e-07 -5.7218441027728e-06 -3.04814562790047e-06 5.05362000833309e-06 -7.63902287871604e-06 2.75948056496812e-05 -2.22343186326967e-06 3.40334170027154e-05 -2.43274700185988e-05 -7.90598212100351e-06 4.7313525945619e-07 -2.22343186326967e-06 0.000199580271823059 -3.91136828791516e-05 8.57828952339261e-05 6.512860179812e-05 -5.7218441027728e-06 3.40334170027154e-05 -3.91136828791516e-05 0.000472284888636545 0 0 0 1013 0 0 0 0 974 0 0 0 0 0 0 0 0 0 0 341 435 435 0 1072 0 +288 431 -0.871654427272 0.435326324290125 0.225187812274934 0.594134799062826 -0.42474333072692 -0.900194765312346 0.0961378567852027 -1.52363716327242 0.244564229641467 -0.0118480329295002 0.969560705523681 0.678465282042388 0.000152933771056874 5.93232118853959e-05 -1.65132224962853e-05 1.5206516256705e-05 -4.65944391096946e-05 0.000139210725088401 5.93232118853959e-05 0.000101882441496638 -3.77418056156887e-06 9.24212289614907e-06 -6.37208731968807e-06 2.0707660862009e-05 -1.65132224962853e-05 -3.77418056156887e-06 2.05167629300636e-05 -2.71410266777235e-06 5.80931619785071e-07 -1.95633948317371e-05 1.5206516256705e-05 9.24212289614907e-06 -2.71410266777235e-06 4.76838414030974e-05 -4.18856391622682e-05 4.40067442420011e-05 -4.65944391096946e-05 -6.37208731968807e-06 5.80931619785071e-07 -4.18856391622682e-05 0.000114595729010303 -4.75020082583909e-05 0.000139210725088401 2.0707660862009e-05 -1.95633948317371e-05 4.40067442420011e-05 -4.75020082583909e-05 0.000513948699007471 0 0 0 124 262 0 0 0 108 243 0 0 0 0 0 0 0 0 0 496 468 468 0 523 0 +288 441 -0.128927912642587 0.948317281494523 0.289951594167824 0.845137983638398 -0.986227867023887 -0.153164592200572 0.062411553430012 -1.52193570945834 0.10359627236122 -0.277911750947796 0.955004120953407 -0.171590654346187 6.57118630232192e-05 4.27344778892427e-05 3.59348832374399e-07 2.25071104331172e-06 1.06990992695088e-05 -1.46426018318814e-05 4.27344778892427e-05 0.000118583368485339 -2.77627035528609e-06 2.65605835127671e-07 4.59396927065376e-06 -6.72745490682462e-05 3.59348832374399e-07 -2.77627035528609e-06 1.8719921015164e-05 -6.24819006499766e-06 -7.38878833070057e-06 -8.67059247115615e-06 2.25071104331172e-06 2.65605835127671e-07 -6.24819006499766e-06 7.86770767350691e-05 8.45157383768996e-05 0.00011373295525462 1.06990992695088e-05 4.59396927065376e-06 -7.38878833070057e-06 8.45157383768996e-05 0.000205025415766785 0.000208537600599166 -1.46426018318814e-05 -6.72745490682462e-05 -8.67059247115615e-06 0.00011373295525462 0.000208537600599166 0.000398944937396176 0 0 0 912 0 0 0 0 879 0 0 0 0 0 0 0 0 0 0 45 845 799 0 340 0 +288 433 -0.735238167403226 0.657417166347087 0.165007595539453 0.589903548659317 -0.648947075379315 -0.753035820856148 0.108649647326355 -1.49694048873183 0.195684773424454 -0.0271978289514648 0.980289624320357 0.578371629978372 7.33429845205465e-05 5.28321392166138e-05 -1.88282927971318e-06 7.72626262455399e-06 -1.30011936596723e-05 5.40345024802821e-05 5.28321392166138e-05 6.28042807075132e-05 -6.03671119864471e-06 4.37152049797358e-06 6.4149566271141e-06 2.23292486798921e-05 -1.88282927971318e-06 -6.03671119864471e-06 1.64485928587253e-05 -3.40546812171437e-06 -9.33925785143827e-06 -6.03503451486634e-06 7.72626262455399e-06 4.37152049797358e-06 -3.40546812171437e-06 2.8925802088862e-05 -2.45402715333372e-05 1.01718651254116e-05 -1.30011936596723e-05 6.4149566271141e-06 -9.33925785143827e-06 -2.45402715333372e-05 0.000156737155529236 1.03966349298418e-05 5.40345024802821e-05 2.23292486798921e-05 -6.03503451486634e-06 1.01718651254116e-05 1.03966349298418e-05 0.00032040409723894 0 0 0 545 4 0 0 0 535 0 0 0 0 0 0 0 0 0 0 685 656 656 0 1030 0 +288 337 -0.87705876388215 0.327619151580289 0.351331205866098 0.557019915700641 -0.30880950404504 -0.94473414586575 0.110063998867785 -1.55203435057422 0.36797366061849 -0.0119618206441493 0.92975926988544 0.658439702631111 0.00039740910653388 -0.000205867779387124 -6.11917822369134e-05 -1.10296817081482e-05 -0.000100506201557555 8.61486195594002e-05 -0.000205867779387124 0.000263440940755026 6.04411759538904e-05 4.9828129749923e-05 5.25383634931613e-05 5.41916355581498e-05 -6.11917822369134e-05 6.04411759538904e-05 5.50222881220933e-05 1.40947834600534e-06 2.52201237743624e-05 1.94583385106409e-05 -1.10296817081482e-05 4.9828129749923e-05 1.40947834600534e-06 9.01717125013696e-05 -3.46450669817003e-05 0.00011880821500892 -0.000100506201557555 5.25383634931613e-05 2.52201237743624e-05 -3.46450669817003e-05 0.0001521686902992 3.33393436069847e-05 8.61486195594002e-05 5.41916355581498e-05 1.94583385106409e-05 0.00011880821500892 3.33393436069847e-05 0.000760636578493524 0 0 0 44 566 0 0 0 32 538 0 0 0 0 0 0 0 0 0 318 138 148 0 456 0 +288 333 -0.905220886998821 0.284499928018235 0.315650022491188 0.610374799650002 -0.249706831857131 -0.957160780006755 0.146593790252981 -1.55966031218443 0.343833744511708 0.0538797937494154 0.937483505967213 0.556626618857649 6.36457131720907e-05 1.46869871012309e-05 6.52547224538636e-06 2.59298899082686e-06 -6.63640900654202e-06 1.8059304096114e-05 1.46869871012309e-05 9.70774154821223e-05 9.69102661243297e-06 1.88643108853726e-05 -9.16386755756498e-07 3.9629998401318e-05 6.52547224538636e-06 9.69102661243297e-06 2.97676784628875e-05 2.35325550051222e-06 -8.23766755627341e-06 3.30385894406409e-06 2.59298899082686e-06 1.88643108853726e-05 2.35325550051222e-06 7.28867621282435e-05 -3.15597447453395e-05 4.34789673785771e-05 -6.63640900654202e-06 -9.16386755756498e-07 -8.23766755627341e-06 -3.15597447453395e-05 8.25442809620506e-05 6.19458843343644e-06 1.8059304096114e-05 3.9629998401318e-05 3.30385894406409e-06 4.34789673785771e-05 6.19458843343644e-06 0.000307284243683535 0 0 0 45 531 0 0 0 31 531 0 0 0 0 0 0 0 0 0 530 205 211 0 554 0 +289 293 0.95533499774321 0.290600296417201 0.0537262487915994 0.403108267222863 -0.293707680805169 0.953768749553037 0.0637257452846529 -0.360253016936532 -0.032723696659012 -0.0766592466586404 0.996520205303785 -0.0574989379552989 4.1521027065788e-05 3.16849576784203e-05 -1.40521883466407e-06 5.62349968191148e-06 5.42028282141761e-07 5.9747830540667e-05 3.16849576784203e-05 5.32705848238935e-05 -3.92088050679391e-06 1.65338593637373e-05 -4.05792480866093e-06 7.55472870968696e-05 -1.40521883466407e-06 -3.92088050679391e-06 1.49990618498418e-05 -2.30558595221634e-06 1.63716326835066e-06 -1.04401222484302e-05 5.62349968191148e-06 1.65338593637373e-05 -2.30558595221634e-06 8.65750155901614e-05 -4.69232576179681e-06 7.73491713141754e-05 5.42028282141761e-07 -4.05792480866093e-06 1.63716326835066e-06 -4.69232576179681e-06 1.72438349925699e-05 -4.800482316134e-06 5.9747830540667e-05 7.55472870968696e-05 -1.04401222484302e-05 7.73491713141754e-05 -4.800482316134e-06 0.000406719943545903 2713 2625 0 2202 0 2683 2595 0 2074 0 0 0 0 0 0 0 0 0 1483 0 740 750 0 0 2571 +289 436 -0.45539593104743 0.872633078169043 0.176425782896562 0.650487656923514 -0.877098788509824 -0.473736846855103 0.0791903726874886 -1.34965671688558 0.152683532772997 -0.11867986694046 0.98112324812072 0.281701748548486 9.1357863283491e-05 5.18520205185245e-05 -3.9094106711251e-06 -8.61285385872506e-06 -6.52873932612951e-05 9.17413506360063e-05 5.18520205185245e-05 8.68042282050976e-05 -4.94340181708133e-06 2.74662298112839e-06 -3.92170021418452e-05 0.000122548141818619 -3.9094106711251e-06 -4.94340181708133e-06 2.31974272231629e-05 -4.76537398911246e-06 8.01108757233934e-06 -1.84570620867064e-05 -8.61285385872506e-06 2.74662298112839e-06 -4.76537398911246e-06 3.10245272913525e-05 1.52940517952659e-06 1.99652133024984e-05 -6.52873932612951e-05 -3.92170021418452e-05 8.01108757233934e-06 1.52940517952659e-06 0.000230306015386671 -0.000116815787761271 9.17413506360063e-05 0.000122548141818619 -1.84570620867064e-05 1.99652133024984e-05 -0.000116815787761271 0.000724300617952907 0 0 0 1368 0 0 0 0 1338 0 0 0 0 0 0 0 0 0 0 131 510 510 0 816 0 +289 292 0.973201377018124 0.225648800991287 0.0442910643496164 0.320729745167051 -0.228287767511649 0.971205183115427 0.06815561234614 -0.27728886589011 -0.0276364790553129 -0.0764402439878656 0.996691082595054 -0.0297221374395045 3.00383136755895e-05 1.10336589500482e-05 2.98944075387202e-06 -1.00577986878411e-05 3.52229432510185e-06 1.36554059205043e-05 1.10336589500482e-05 2.72988189453039e-05 3.39649512146002e-06 2.691387284315e-06 -1.29048294797944e-06 9.58534416517072e-06 2.98944075387202e-06 3.39649512146002e-06 1.30292132381972e-05 2.33496267054611e-06 1.32853137968612e-06 3.12494391425639e-06 -1.00577986878411e-05 2.691387284315e-06 2.33496267054611e-06 5.8377200639958e-05 -9.81059701366978e-06 1.38588858856113e-05 3.52229432510185e-06 -1.29048294797944e-06 1.32853137968612e-06 -9.81059701366978e-06 2.02341926003254e-05 -4.84142170447274e-06 1.36554059205043e-05 9.58534416517072e-06 3.12494391425639e-06 1.38588858856113e-05 -4.84142170447274e-06 0.000153696592553776 2818 2718 0 1724 0 2785 2685 0 1599 0 0 0 0 0 0 0 0 0 1900 0 600 598 0 0 3036 +288 335 -0.891131884918433 0.28547743592026 0.352684841270667 0.579027946682816 -0.260421638275169 -0.958297025451894 0.117674896762775 -1.55289737185257 0.371570362111671 0.0130170884012688 0.928313536155622 0.636013195740416 0.000240740611934653 6.56259280372295e-05 -4.30741946366939e-05 -1.48165680932097e-05 3.42660905392665e-05 0.000192578422519755 6.56259280372295e-05 0.000129302833282184 -1.24843399349995e-05 9.3466742969471e-06 -1.19472326953446e-06 4.65734325122001e-05 -4.30741946366939e-05 -1.24843399349995e-05 3.9988072027272e-05 -2.41880869040916e-06 -1.55092453899232e-05 -3.955220572183e-05 -1.48165680932097e-05 9.3466742969471e-06 -2.41880869040916e-06 6.79994011233768e-05 -1.30958727692433e-05 5.56697172531434e-05 3.42660905392665e-05 -1.19472326953446e-06 -1.55092453899232e-05 -1.30958727692433e-05 6.78692870718496e-05 4.17794088354497e-05 0.000192578422519755 4.65734325122001e-05 -3.955220572183e-05 5.56697172531434e-05 4.17794088354497e-05 0.000562864123132973 0 0 0 38 698 0 0 0 24 669 0 0 0 0 0 0 0 0 0 396 196 204 0 470 0 +289 435 -0.502141112864975 0.847107707924049 0.173962162398575 0.6506240796078 -0.840888322690881 -0.525247424645115 0.13046827838901 -1.35064738729788 0.201893862048458 -0.0807692644471815 0.97607130599553 0.40348696923757 7.85220677605133e-05 3.27137879885876e-05 8.00838456629742e-06 3.1826974808881e-06 -2.85608511030907e-05 0.000113335712654696 3.27137879885876e-05 4.96494761523941e-05 3.3695328044823e-06 6.95827479564695e-06 -3.7058724211448e-06 6.24601256013414e-05 8.00838456629742e-06 3.3695328044823e-06 1.67571588622882e-05 -5.33148441905571e-06 -2.59820996873088e-06 2.08345334111071e-06 3.1826974808881e-06 6.95827479564695e-06 -5.33148441905571e-06 3.3120285372546e-05 -1.18826043114385e-05 5.01081622258742e-05 -2.85608511030907e-05 -3.7058724211448e-06 -2.59820996873088e-06 -1.18826043114385e-05 0.000181225916855366 -4.81035153713217e-05 0.000113335712654696 6.24601256013414e-05 2.08345334111071e-06 5.01081622258742e-05 -4.81035153713217e-05 0.000515571714145768 0 0 0 1360 0 0 0 0 1340 0 0 0 0 0 0 0 0 0 0 168 585 585 0 844 0 +289 291 0.986234042887097 0.158993152350801 0.0454267559498467 0.211673501587225 -0.161470030442248 0.985209184898095 0.0573610604976147 -0.185859091193736 -0.0356348413712124 -0.0639064902649682 0.997319466661742 -0.0246661402152526 3.56511608098042e-05 1.92474796782579e-05 4.24151191027571e-06 -1.01877805975077e-05 3.15965403200641e-07 3.10233236968317e-05 1.92474796782579e-05 3.06521965195358e-05 2.15482783034585e-06 2.26748910189893e-06 -7.73976815247345e-07 6.45636259713882e-06 4.24151191027571e-06 2.15482783034585e-06 1.51444559570142e-05 -4.36409515352282e-06 1.145488415243e-06 -2.6410980271974e-07 -1.01877805975077e-05 2.26748910189893e-06 -4.36409515352282e-06 6.14317524337254e-05 -4.91033912858405e-06 -7.06047395664808e-06 3.15965403200641e-07 -7.73976815247345e-07 1.145488415243e-06 -4.91033912858405e-06 1.88154279703234e-05 -4.86706014600468e-06 3.10233236968317e-05 6.45636259713882e-06 -2.6410980271974e-07 -7.06047395664808e-06 -4.86706014600468e-06 0.000154111897910307 3189 3077 0 1159 0 3151 3039 0 1021 0 0 0 0 0 0 0 0 0 2467 0 435 421 0 0 3246 +289 438 -0.362862219737228 0.899465714117436 0.243500387298628 0.758338558697943 -0.924970877170049 -0.379348059142106 0.0228894388831804 -1.35547045542396 0.112959664812893 -0.216925054229168 0.969630669364904 0.098426214409853 4.3648370808426e-05 4.23746762877039e-05 4.52594816998143e-06 -3.73048231004307e-06 -1.26459892671321e-05 -1.94098772196917e-05 4.23746762877039e-05 8.28670779904354e-05 6.61159519616516e-07 -2.69818802749812e-06 -1.09578916338805e-05 -2.1382503371996e-05 4.52594816998143e-06 6.61159519616516e-07 1.69303202474352e-05 -3.44893223493908e-06 -4.81991633256362e-08 -7.27369729525204e-06 -3.73048231004307e-06 -2.69818802749812e-06 -3.44893223493908e-06 2.25474380600549e-05 2.63700191383441e-05 -6.63911467546025e-06 -1.26459892671321e-05 -1.09578916338805e-05 -4.81991633256362e-08 2.63700191383441e-05 0.000300959442421758 -5.01887410254388e-05 -1.94098772196917e-05 -2.1382503371996e-05 -7.27369729525204e-06 -6.63911467546025e-06 -5.01887410254388e-05 0.000179265082690214 0 0 0 1214 0 0 0 0 1187 0 0 0 0 0 0 0 0 0 0 70 530 530 0 772 0 +289 434 -0.566169062069616 0.796821719759464 0.211015971136739 0.647741243876136 -0.79547918938128 -0.595263327846975 0.113465544469879 -1.34060293940859 0.216021879485649 -0.103618132776627 0.970874775727217 0.511669317940425 8.28228367661577e-05 1.05126491165609e-05 2.63181581249562e-07 -1.27173193591625e-06 -2.3673146648745e-05 3.43602016241882e-05 1.05126491165609e-05 5.10357866123035e-05 1.93488552304876e-07 3.84292736138857e-06 8.1915031373802e-06 1.20669365507062e-05 2.63181581249562e-07 1.93488552304876e-07 2.11663685223567e-05 -2.02441501874892e-06 -7.23650262421151e-06 -4.85961140456533e-06 -1.27173193591625e-06 3.84292736138857e-06 -2.02441501874892e-06 2.72886489656861e-05 -9.73261569099083e-06 1.24873666742542e-05 -2.3673146648745e-05 8.1915031373802e-06 -7.23650262421151e-06 -9.73261569099083e-06 0.000124663227991406 3.12907129539952e-06 3.43602016241882e-05 1.20669365507062e-05 -4.85961140456533e-06 1.24873666742542e-05 3.12907129539952e-06 0.000228129128749758 0 0 0 1136 0 0 0 0 1091 0 0 0 0 0 0 0 0 0 0 303 589 589 0 815 0 +289 433 -0.664988187934355 0.735014923381093 0.132452906026516 0.637589455114851 -0.729982508384701 -0.677145808082607 0.0927312894795148 -1.35828273207196 0.15784881171603 -0.0350230924282808 0.986842001354116 0.582960994202697 6.27452440033925e-05 5.69222048000387e-05 -2.82438389313472e-06 2.57998717868183e-06 -1.81697273788797e-06 5.55425341482902e-05 5.69222048000387e-05 0.000114310650020905 -1.16640385167535e-05 3.86808579219286e-06 2.78168541072539e-05 0.000132951573128563 -2.82438389313472e-06 -1.16640385167535e-05 2.00713857561952e-05 -4.05057432613904e-06 -6.2103771032915e-06 -1.12359389963984e-05 2.57998717868183e-06 3.86808579219286e-06 -4.05057432613904e-06 3.31221260797697e-05 -2.23356241482207e-05 7.3435371351735e-06 -1.81697273788797e-06 2.78168541072539e-05 -6.2103771032915e-06 -2.23356241482207e-05 0.000130388990959493 9.51493116399612e-05 5.55425341482902e-05 0.000132951573128563 -1.12359389963984e-05 7.3435371351735e-06 9.51493116399612e-05 0.000524386278221105 0 0 0 838 0 0 0 0 792 0 0 0 0 0 0 0 0 0 0 470 845 845 0 700 0 +289 432 -0.751603064169278 0.645200504133792 0.137146430492568 0.628819849831019 -0.638845606103248 -0.763793220201345 0.0921748790996391 -1.36457278876145 0.164222792248597 -0.0183364729422003 0.986252831816525 0.621054510404592 0.000194721399291683 5.7443677935505e-06 -2.79091809723179e-05 3.83252580181587e-05 -0.00014922451647694 0.000206424455734882 5.7443677935505e-06 9.90485831714298e-05 3.25024674128691e-06 4.28681233925622e-06 2.19947362245765e-05 1.53543822240718e-05 -2.79091809723179e-05 3.25024674128691e-06 2.79478281754543e-05 -1.25178801844957e-05 2.96047454252995e-05 -3.34269876799609e-05 3.83252580181587e-05 4.28681233925622e-06 -1.25178801844957e-05 3.69562626872196e-05 -4.58530986319225e-05 5.42430444790116e-05 -0.00014922451647694 2.19947362245765e-05 2.96047454252995e-05 -4.58530986319225e-05 0.000205896486268812 -0.000147474093046875 0.000206424455734882 1.53543822240718e-05 -3.34269876799609e-05 5.42430444790116e-05 -0.000147474093046875 0.000577520914943628 0 0 0 466 19 0 0 0 436 3 0 0 0 0 0 0 0 0 0 526 625 625 0 581 0 +289 333 -0.877041485059916 0.381583350992117 0.291877336786404 0.679462791181738 -0.356945385605277 -0.924215382153342 0.135705265506729 -1.42253273102795 0.321540394319279 0.0148348790618073 0.94677964763942 0.605997503030177 6.3182689527073e-05 3.39561390782053e-05 -1.48364579338703e-07 -1.72836651953823e-06 -5.82769050416577e-07 3.02724412327733e-05 3.39561390782053e-05 9.88963288491869e-05 -7.88187905649567e-06 1.44980199892986e-05 -5.31712273762738e-07 4.37981463652702e-05 -1.48364579338703e-07 -7.88187905649567e-06 2.96274255171461e-05 3.66754709831151e-06 -1.16464662080989e-05 -8.14945825010599e-06 -1.72836651953823e-06 1.44980199892986e-05 3.66754709831151e-06 6.78182213204407e-05 -3.73042471696634e-05 2.86575356552108e-05 -5.82769050416577e-07 -5.31712273762738e-07 -1.16464662080989e-05 -3.73042471696634e-05 7.99395723577805e-05 1.49790908577395e-05 3.02724412327733e-05 4.37981463652702e-05 -8.14945825010599e-06 2.86575356552108e-05 1.49790908577395e-05 0.000266604232773614 0 0 0 46 489 0 0 0 43 470 0 0 0 0 0 0 0 0 0 414 310 316 0 519 0 +289 332 -0.875142279616564 0.390889330134313 0.285186819496748 0.695283225918049 -0.376298929473901 -0.920332316146986 0.106712433822492 -1.41895896932928 0.304179397895911 -0.013926932277846 0.952512957629979 0.494592202560698 7.88382943806961e-05 3.88145617279186e-05 7.42298376905097e-06 -1.81911758677434e-06 1.02466498127403e-05 8.08155723889201e-05 3.88145617279186e-05 8.44548388971706e-05 2.41975917146002e-06 2.11630421185222e-06 -5.16014547732616e-06 3.69235557594534e-05 7.42298376905097e-06 2.41975917146002e-06 4.41231510662077e-05 7.6388071386833e-06 -8.09673062978559e-06 2.37315129417163e-07 -1.81911758677434e-06 2.11630421185222e-06 7.6388071386833e-06 0.000129314743660752 -0.000115078761774629 -8.6037738710638e-05 1.02466498127403e-05 -5.16014547732616e-06 -8.09673062978559e-06 -0.000115078761774629 0.000199829835000979 0.0001489352441801 8.08155723889201e-05 3.69235557594534e-05 2.37315129417163e-07 -8.6037738710638e-05 0.0001489352441801 0.000575741728945293 0 0 0 67 399 0 0 0 61 388 0 0 0 0 0 0 0 0 0 490 464 465 0 492 0 +289 335 -0.86706761789812 0.383872989197919 0.317545704043896 0.644906654452873 -0.363293991855623 -0.92335427884132 0.124235064402252 -1.42801351298268 0.3408976700919 -0.00764224506803082 0.940069345642243 0.646319110789645 0.000183543696554746 1.12326119849113e-05 -3.18843662128998e-05 -2.0041533810955e-05 2.04955575400636e-05 0.000192258424656657 1.12326119849113e-05 7.76271312672373e-05 -8.18577753566218e-06 8.18398171649737e-06 -1.74217591610061e-05 -4.22464440717871e-05 -3.18843662128998e-05 -8.18577753566218e-06 3.67375742558592e-05 8.25204001868121e-07 -9.78663481223647e-06 -3.95406662721041e-05 -2.0041533810955e-05 8.18398171649737e-06 8.25204001868121e-07 6.46431773115778e-05 -2.62464199648159e-05 -7.53701264498411e-06 2.04955575400636e-05 -1.74217591610061e-05 -9.78663481223647e-06 -2.62464199648159e-05 8.71009820557287e-05 0.000113551623949897 0.000192258424656657 -4.22464440717871e-05 -3.95406662721041e-05 -7.53701264498411e-06 0.000113551623949897 0.000651922160205625 0 0 0 42 527 0 0 0 42 500 0 0 0 0 0 0 0 0 0 464 268 277 0 442 0 +289 334 -0.874902522207417 0.384371301256146 0.294625659788411 0.634905006307483 -0.3549664876043 -0.922798678255753 0.149804512906995 -1.40813686050861 0.32946072499308 0.0264821105671915 0.943797821838417 0.599070472137957 8.21678927638328e-05 1.66862284790737e-05 7.92733666752981e-07 1.95273094872004e-05 -3.0611381707152e-05 4.64485779759987e-05 1.66862284790737e-05 7.58081880602466e-05 -2.70295212816338e-07 1.99596732749511e-06 2.4528566883222e-06 -1.45191351372885e-07 7.92733666752981e-07 -2.70295212816338e-07 3.5590837053675e-05 -7.43522484461339e-06 -4.59194129640513e-06 4.41287984490184e-06 1.95273094872004e-05 1.99596732749511e-06 -7.43522484461339e-06 9.92462072164409e-05 -6.14855341846456e-05 7.51613556911885e-05 -3.0611381707152e-05 2.4528566883222e-06 -4.59194129640513e-06 -6.14855341846456e-05 9.69701124125117e-05 -5.40133455612813e-05 4.64485779759987e-05 -1.45191351372885e-07 4.41287984490184e-06 7.51613556911885e-05 -5.40133455612813e-05 0.000221045908227628 0 0 0 43 551 0 0 0 43 513 0 0 0 0 0 0 0 0 0 506 291 301 0 483 0 +289 336 -0.853954708120159 0.401030343891396 0.331566011161825 0.644981078704842 -0.383442234005285 -0.915733199049166 0.120019837277917 -1.42603175669591 0.351757600714542 -0.0246449069288194 0.935766647675594 0.680016992797 0.000117831306409991 2.1341035323166e-05 -8.44061175514622e-06 -2.96819116008154e-06 -2.15327521855786e-05 1.72552125954825e-05 2.1341035323166e-05 9.31920365055127e-05 1.25632596818828e-06 1.68288141396135e-06 1.30248221767417e-05 2.16995062462623e-05 -8.44061175514622e-06 1.25632596818828e-06 3.30321116786872e-05 2.91363518829139e-06 -1.63145596947542e-07 8.42592566051515e-06 -2.96819116008154e-06 1.68288141396135e-06 2.91363518829139e-06 6.41201225968881e-05 -2.47415043291005e-05 1.60488842273333e-05 -2.15327521855786e-05 1.30248221767417e-05 -1.63145596947542e-07 -2.47415043291005e-05 8.7278834406009e-05 2.67437893496587e-05 1.72552125954825e-05 2.16995062462623e-05 8.42592566051515e-06 1.60488842273333e-05 2.67437893496587e-05 0.000217129913150361 0 0 0 40 485 0 0 0 39 458 0 0 0 0 0 0 0 0 0 424 289 297 0 445 0 +289 431 -0.825012657872381 0.530666155152646 0.19428727731341 0.638871272706343 -0.522083858983687 -0.847318132283291 0.0973674837543722 -1.3810129874809 0.216292761180424 -0.0211048449286782 0.976100418492628 0.671342417053942 8.9297697374257e-05 5.39394584578787e-05 -3.96991386467809e-06 -2.21750470346848e-06 -8.60742883441062e-06 5.95558992086663e-05 5.39394584578787e-05 8.31543373658783e-05 -3.87746079622356e-06 2.11379602527964e-06 -1.03845391524061e-05 1.30848381681249e-05 -3.96991386467809e-06 -3.87746079622356e-06 2.08589921404672e-05 1.92177485286246e-06 -1.27740669576425e-05 -3.36774226109477e-06 -2.21750470346848e-06 2.11379602527964e-06 1.92177485286246e-06 5.400975664731e-05 -3.88652128985889e-05 5.91739037921274e-05 -8.60742883441062e-06 -1.03845391524061e-05 -1.27740669576425e-05 -3.88652128985889e-05 8.95477752883885e-05 -3.49334265702224e-05 5.95558992086663e-05 1.30848381681249e-05 -3.36774226109477e-06 5.91739037921274e-05 -3.49334265702224e-05 0.000501156167100673 0 0 0 192 170 0 0 0 179 147 0 0 0 0 0 0 0 0 0 441 600 600 0 431 0 +290 435 -0.426726176703416 0.892489051665684 0.146178188431013 0.649176088116185 -0.889483800699166 -0.443394734423021 0.110542651405256 -1.21878754284125 0.163472745159095 -0.082851687628113 0.98306269354875 0.388150332125135 6.00380151035696e-05 3.55156077150731e-05 6.86393494177488e-06 4.4658637470436e-06 -2.94554554102674e-05 7.89907252125313e-05 3.55156077150731e-05 6.8091654176162e-05 8.59317857110076e-06 1.541842146544e-06 6.53329515566906e-06 4.87500352054743e-05 6.86393494177488e-06 8.59317857110076e-06 1.84661671624505e-05 -8.17925733360269e-06 1.47569605771921e-06 -2.66496949219036e-06 4.4658637470436e-06 1.541842146544e-06 -8.17925733360269e-06 2.96600796307553e-05 -1.36244013127706e-05 4.11771868746813e-05 -2.94554554102674e-05 6.53329515566906e-06 1.47569605771921e-06 -1.36244013127706e-05 0.000190773663700105 -7.65877043793219e-05 7.89907252125313e-05 4.87500352054743e-05 -2.66496949219036e-06 4.11771868746813e-05 -7.65877043793219e-05 0.000383231126033517 0 0 0 1487 0 0 0 0 1486 0 0 0 0 0 0 0 0 0 0 118 669 669 0 607 0 +290 293 0.979067805413678 0.202533940021199 0.0201552857070603 0.315310358230092 -0.20315050007656 0.978497003676315 0.0356859652400939 -0.235729489210211 -0.0124942675290628 -0.0390335360422627 0.999159785191012 -0.0582941799204135 2.87570788880752e-05 2.2698896122506e-05 1.17662242698215e-06 -5.86894024856236e-06 6.13622299777855e-07 6.01430676769822e-06 2.2698896122506e-05 5.04796379497457e-05 -1.088357981694e-06 1.06425977625653e-05 -4.13695403102524e-06 4.12467152198601e-05 1.17662242698215e-06 -1.088357981694e-06 1.32862235448586e-05 9.42213831467462e-07 1.90880940306809e-06 3.76225755392963e-07 -5.86894024856236e-06 1.06425977625653e-05 9.42213831467462e-07 7.21561565057597e-05 -6.67228101881547e-06 4.06478160617546e-05 6.13622299777855e-07 -4.13695403102524e-06 1.90880940306809e-06 -6.67228101881547e-06 1.7242437774034e-05 -6.74393216980265e-06 6.01430676769822e-06 4.12467152198601e-05 3.76225755392963e-07 4.06478160617546e-05 -6.74393216980265e-06 0.000201671451663476 3008 2920 0 1556 0 3001 2913 0 1421 0 0 0 0 0 0 0 0 0 2201 0 449 459 0 0 2853 +290 436 -0.374747288466702 0.912664917984521 0.163117188754471 0.66160496477669 -0.919901141550478 -0.387949660897611 0.0572446537552265 -1.21413908197434 0.115526445288435 -0.128599409367757 0.984944583389991 0.27982086738054 6.74792940039339e-05 2.63652952872014e-05 1.74983910898065e-06 -6.59636052986851e-06 -2.1242996073025e-05 4.0293106324219e-05 2.63652952872014e-05 4.21766460647551e-05 2.07432279833934e-06 -1.31982686165178e-06 1.98818280286735e-05 2.25061670375233e-05 1.74983910898065e-06 2.07432279833934e-06 1.87660546683266e-05 -3.69311124259779e-06 3.22544702892704e-06 -2.3847029290915e-06 -6.59636052986851e-06 -1.31982686165178e-06 -3.69311124259779e-06 2.32052733859289e-05 7.78728843853835e-06 5.79554415439514e-07 -2.1242996073025e-05 1.98818280286735e-05 3.22544702892704e-06 7.78728843853835e-06 0.000181077752940556 4.67554691280866e-05 4.0293106324219e-05 2.25061670375233e-05 -2.3847029290915e-06 5.79554415439514e-07 4.67554691280866e-05 0.000235362967657197 0 0 0 1653 0 0 0 0 1646 0 0 0 0 0 0 0 0 0 0 60 515 515 0 596 0 +290 433 -0.598123621602739 0.79419118639011 0.107277643249153 0.639032836734256 -0.792826152979798 -0.60592910646853 0.0653957879798333 -1.2372929673424 0.116939404958629 -0.0459377556539027 0.992076054631601 0.568269120022863 4.32907934345519e-05 3.23104281142302e-05 7.59904216609842e-07 2.8425999860749e-07 -5.76526778330066e-06 1.35510053988189e-05 3.23104281142302e-05 5.97052600356712e-05 -2.02257657900723e-06 2.34972763562676e-06 -3.07605185526102e-06 1.89155868076754e-05 7.59904216609842e-07 -2.02257657900723e-06 1.9126006549085e-05 -4.66463848337899e-06 -3.74831311816541e-06 8.00606785248735e-08 2.8425999860749e-07 2.34972763562676e-06 -4.66463848337899e-06 2.84539476838276e-05 -5.87818050040291e-06 1.16463817454677e-05 -5.76526778330066e-06 -3.07605185526102e-06 -3.74831311816541e-06 -5.87818050040291e-06 8.15971065792386e-05 -7.94960814606046e-07 1.35510053988189e-05 1.89155868076754e-05 8.00606785248735e-08 1.16463817454677e-05 -7.94960814606046e-07 0.000199795205982136 0 0 0 950 0 0 0 0 948 0 0 0 0 0 0 0 0 0 0 393 952 952 0 590 0 +290 294 0.967258979146276 0.251842668162685 0.0313900900540817 0.413947551534262 -0.253315622902166 0.965602424438372 0.0586783870980314 -0.310470356041978 -0.015532625489309 -0.0647087970173967 0.997783297682403 -0.100441902456177 3.76033161187756e-05 2.06453183815766e-05 -1.11874551542658e-06 -8.25090736888004e-06 1.84861828827911e-06 2.37769733961284e-06 2.06453183815766e-05 4.69497339381138e-05 3.51531632141154e-06 1.59938080529183e-06 -1.6357751171546e-06 3.22041835117996e-05 -1.11874551542658e-06 3.51531632141154e-06 1.77153299736549e-05 2.38304122703298e-06 -1.02175975742676e-06 6.39840443689893e-06 -8.25090736888004e-06 1.59938080529183e-06 2.38304122703298e-06 7.73091880084028e-05 -2.16203855761991e-06 1.89156976623544e-05 1.84861828827911e-06 -1.6357751171546e-06 -1.02175975742676e-06 -2.16203855761991e-06 1.95167931966509e-05 -7.50473302970998e-06 2.37769733961284e-06 3.22041835117996e-05 6.39840443689893e-06 1.89156976623544e-05 -7.50473302970998e-06 0.000188497122713914 2726 2648 0 2014 0 2712 2634 0 1881 0 0 0 0 0 0 0 0 0 1629 0 544 565 0 0 2969 +290 442 0.186256304819385 0.957756240122883 0.219115434008441 1.00781972778945 -0.982494510908297 0.180741732780601 0.0451327161439646 -1.14607792295909 0.00362283729891782 -0.223685964104019 0.974654535983269 -0.234998683398621 7.53461115094944e-05 2.65594134290671e-05 4.1803477646431e-06 8.71480803354943e-06 1.92950862202945e-05 -1.50839200807899e-05 2.65594134290671e-05 8.7964176640432e-05 2.83214957493885e-06 -1.66788951188253e-05 -2.30180452738301e-05 -1.83347875965274e-05 4.1803477646431e-06 2.83214957493885e-06 2.02046532436093e-05 -5.77286613234431e-06 -1.97549948423832e-06 -7.39757191768733e-06 8.71480803354943e-06 -1.66788951188253e-05 -5.77286613234431e-06 2.82522500846083e-05 2.56826926083341e-06 1.01905201917126e-05 1.92950862202945e-05 -2.30180452738301e-05 -1.97549948423832e-06 2.56826926083341e-06 4.55032462884111e-05 -2.7136911688378e-05 -1.50839200807899e-05 -1.83347875965274e-05 -7.39757191768733e-06 1.01905201917126e-05 -2.7136911688378e-05 0.000385974164113512 268 278 0 1158 0 249 259 0 1158 0 0 0 0 0 0 0 0 0 0 0 1057 1057 0 0 1 +290 431 -0.775571760986686 0.607029650133116 0.173215032313241 0.63427673193514 -0.60316570550744 -0.79355957312814 0.0803388797307816 -1.25574413403077 0.186224529156935 -0.0421688007412101 0.98160186276531 0.667658200768312 8.2081451947119e-05 5.27450741891387e-05 5.57226837018106e-06 8.7824547921975e-08 -7.79274838290467e-06 6.49141601258618e-05 5.27450741891387e-05 0.000105071557587413 4.16532563608814e-06 7.91055527907696e-06 -2.02007582697447e-05 -3.32825828285976e-05 5.57226837018106e-06 4.16532563608814e-06 2.08437876470394e-05 -2.23838913353442e-06 -5.46467758296017e-06 -1.06387985750526e-05 8.7824547921975e-08 7.91055527907696e-06 -2.23838913353442e-06 3.91625900864403e-05 -2.65245423260727e-05 7.200155674886e-06 -7.79274838290467e-06 -2.02007582697447e-05 -5.46467758296017e-06 -2.65245423260727e-05 8.45470710473408e-05 4.03155086080541e-05 6.49141601258618e-05 -3.32825828285976e-05 -1.06387985750526e-05 7.200155674886e-06 4.03155086080541e-05 0.000463697551249108 0 0 0 229 32 0 0 0 229 14 0 0 0 0 0 0 0 0 0 454 687 687 0 367 0 +290 432 -0.692154493301916 0.712453699307103 0.115463776768261 0.633221284684049 -0.709271279965444 -0.701046638851282 0.0739449901717562 -1.24118504249238 0.133627874405559 -0.0307137835335219 0.990555528318785 0.620268012864431 0.000176783988646187 -2.56717145793275e-05 -1.65221758232339e-05 8.50477578763475e-06 -9.58689857163778e-05 4.19154340823909e-05 -2.56717145793275e-05 0.00012628328045515 -1.35015412334027e-05 1.96323904681626e-05 8.45640974845215e-06 8.01746714078378e-05 -1.65221758232339e-05 -1.35015412334027e-05 7.3987547166416e-05 -2.67343601937908e-05 5.70837548288626e-05 -6.06283512488727e-07 8.50477578763475e-06 1.96323904681626e-05 -2.67343601937908e-05 5.38167280041231e-05 -6.82744265925992e-05 5.74148272129994e-05 -9.58689857163778e-05 8.45640974845215e-06 5.70837548288626e-05 -6.82744265925992e-05 0.000228342721769748 -6.47060726631792e-05 4.19154340823909e-05 8.01746714078378e-05 -6.06283512488727e-07 5.74148272129994e-05 -6.47060726631792e-05 0.000455522287873617 0 0 0 575 0 0 0 0 573 0 0 0 0 0 0 0 0 0 0 446 590 590 0 461 0 +290 434 -0.494292923650936 0.850008923087802 0.182097051869941 0.644706971778044 -0.851381722979898 -0.51567321405069 0.096074440338787 -1.211386566108 0.175566703575563 -0.107545185767404 0.978575682108372 0.488191793045211 0.000125569663704856 1.4189854284219e-05 -7.14685297208157e-06 -1.20167808965659e-06 -3.19509038086831e-05 9.16640723117593e-05 1.4189854284219e-05 6.20547250785039e-05 2.37091886597307e-06 2.88428790836748e-06 -3.55992754541513e-07 2.00237142488286e-05 -7.14685297208157e-06 2.37091886597307e-06 2.22520846741064e-05 -1.16679980574742e-06 -7.60553778558742e-06 -1.01335963383536e-05 -1.20167808965659e-06 2.88428790836748e-06 -1.16679980574742e-06 2.27748628574876e-05 -4.82654394247125e-06 1.46871572173409e-05 -3.19509038086831e-05 -3.55992754541513e-07 -7.60553778558742e-06 -4.82654394247125e-06 0.000147834524874875 1.15984982090665e-05 9.16640723117593e-05 2.00237142488286e-05 -1.01335963383536e-05 1.46871572173409e-05 1.15984982090665e-05 0.000296761902988496 0 0 0 1320 0 0 0 0 1314 0 0 0 0 0 0 0 0 0 0 231 684 684 0 599 0 +290 333 -0.845223015467029 0.467603766909097 0.25873687657009 0.690485567844243 -0.448258222682001 -0.883931503707991 0.133152778981527 -1.29426868866211 0.290968417397485 -0.00343713906501968 0.956726484504454 0.560910218474275 5.26760023153717e-05 2.05476005784972e-05 5.03519979154339e-06 -7.02139658339569e-07 2.89718581631724e-06 3.66343840257385e-05 2.05476005784972e-05 4.34851576191213e-05 3.27095520918125e-06 9.48197435148804e-07 2.50792053404969e-06 5.36250155378819e-06 5.03519979154339e-06 3.27095520918125e-06 2.9019964111633e-05 1.24439791282649e-06 -7.68741318737842e-06 8.10602476045785e-06 -7.02139658339569e-07 9.48197435148804e-07 1.24439791282649e-06 5.91091897123246e-05 -2.3259301976863e-05 7.04035187433106e-06 2.89718581631724e-06 2.50792053404969e-06 -7.68741318737842e-06 -2.3259301976863e-05 7.10015926229248e-05 1.95740094579175e-05 3.66343840257385e-05 5.36250155378819e-06 8.10602476045785e-06 7.04035187433106e-06 1.95740094579175e-05 0.000175379565348329 0 0 0 107 320 0 0 0 104 279 0 0 0 0 0 0 0 0 0 556 410 416 0 468 0 +290 336 -0.820113280910959 0.487432575304877 0.299706007622667 0.634582164386428 -0.472307085028809 -0.872335303122864 0.126321559352041 -1.29031924418923 0.323017373998755 -0.037955282335893 0.945631626288879 0.637963579003563 9.77647545532343e-05 2.41804419119093e-05 -1.00401868805396e-05 -1.29083598246433e-05 1.1205969221917e-06 5.71688272897511e-05 2.41804419119093e-05 6.62786625994048e-05 -4.83411388218426e-06 6.30253926164124e-06 4.61794957119343e-06 3.28494122554646e-05 -1.00401868805396e-05 -4.83411388218426e-06 2.87252205627394e-05 -4.9137480320496e-07 -6.62438884304043e-06 1.2017425672866e-06 -1.29083598246433e-05 6.30253926164124e-06 -4.9137480320496e-07 5.0642886303584e-05 -5.70760066965027e-06 2.46589367142301e-05 1.1205969221917e-06 4.61794957119343e-06 -6.62438884304043e-06 -5.70760066965027e-06 5.35772215667432e-05 3.60133154949755e-05 5.71688272897511e-05 3.28494122554646e-05 1.2017425672866e-06 2.46589367142301e-05 3.60133154949755e-05 0.000361839694198137 0 0 0 76 283 0 0 0 72 240 0 0 0 0 0 0 0 0 0 580 363 371 0 420 0 +290 335 -0.834002130007351 0.469841929875465 0.289290525379074 0.638754555716753 -0.454739972683768 -0.88224415489304 0.121888508074513 -1.29439741963208 0.312493206944995 -0.0298966902509911 0.949449410724589 0.614799148879609 0.000301822686304102 0.000108351348777172 -3.58389278160589e-05 5.3089008559969e-05 -4.60616525706693e-07 0.00047477226917076 0.000108351348777172 9.3988185767249e-05 -1.67278388913424e-05 1.84734876141725e-05 4.26308340533939e-06 0.000168215225064679 -3.58389278160589e-05 -1.67278388913424e-05 3.36624284951594e-05 -1.03006607766189e-05 -7.45358055959599e-06 -6.02001542640505e-05 5.3089008559969e-05 1.84734876141725e-05 -1.03006607766189e-05 6.40569258053782e-05 -2.76168536838863e-06 0.000150386374514839 -4.60616525706693e-07 4.26308340533939e-06 -7.45358055959599e-06 -2.76168536838863e-06 5.74613097840817e-05 2.69816512979739e-05 0.00047477226917076 0.000168215225064679 -6.02001542640505e-05 0.000150386374514839 2.69816512979739e-05 0.00124170711293961 0 0 0 66 306 0 0 0 63 264 0 0 0 0 0 0 0 0 0 607 339 348 0 421 0 +290 334 -0.842322846347528 0.467383096174384 0.268412488404407 0.641102380289522 -0.444864939343035 -0.884053894487791 0.143331424971244 -1.28079251256793 0.304281790885221 0.0013240284798863 0.95258114545915 0.582399916582179 9.03305554004053e-05 3.42214734417553e-05 -1.7842277487206e-06 2.92266541549723e-05 -1.66682609552819e-05 8.10844815067023e-05 3.42214734417553e-05 0.000102544106844788 -3.4610354246318e-06 5.42342788964715e-05 -2.97992346667861e-05 8.85356225877335e-05 -1.7842277487206e-06 -3.4610354246318e-06 3.40669841432548e-05 -4.65575165363054e-06 -8.5630961904449e-06 4.88731336590099e-06 2.92266541549723e-05 5.42342788964715e-05 -4.65575165363054e-06 0.00010285207695452 -4.67904979631164e-05 0.000137789925445248 -1.66682609552819e-05 -2.97992346667861e-05 -8.5630961904449e-06 -4.67904979631164e-05 7.89141052115783e-05 -7.18517777156719e-05 8.10844815067023e-05 8.85356225877335e-05 4.88731336590099e-06 0.000137789925445248 -7.18517777156719e-05 0.000425474654113663 0 0 0 68 317 0 0 0 65 267 0 0 0 0 0 0 0 0 0 645 332 341 0 450 0 +290 327 -0.723456204193104 0.628594162496997 0.285447892774155 0.843603625421889 -0.624769898173617 -0.772041211781547 0.116683082094228 -1.3393158379113 0.293723841304438 -0.0939241512369398 0.951264715451901 0.0252592600345006 0.000109894825777864 2.7545875013407e-05 -3.08611320575123e-06 -7.84632547857981e-06 5.35642115177138e-05 9.91570734455699e-05 2.7545875013407e-05 6.69497405494258e-05 8.53720083616421e-06 -1.9380219824705e-05 4.11566356283207e-05 3.08741838259224e-07 -3.08611320575123e-06 8.53720083616421e-06 2.52290693303484e-05 -6.32624307377679e-06 -1.38556507422525e-06 -2.42144211864561e-05 -7.84632547857981e-06 -1.9380219824705e-05 -6.32624307377679e-06 8.77831401267104e-05 -0.00011062168994529 -6.41345956277824e-06 5.35642115177138e-05 4.11566356283207e-05 -1.38556507422525e-06 -0.00011062168994529 0.000341870824392432 0.000157178171735124 9.91570734455699e-05 3.08741838259224e-07 -2.42144211864561e-05 -6.41345956277824e-06 0.000157178171735124 0.000442695338642749 0 0 0 451 2 0 0 0 449 1 0 0 0 0 0 0 0 0 0 867 0 0 0 527 0 +290 430 -0.849062668253113 0.48713132543827 0.204439861953728 0.641408520329448 -0.494915968114833 -0.86881587021215 0.0147366269024275 -1.26693354173688 0.184799269164849 -0.0886682324412663 0.978768192511322 0.701570036150271 8.97436372756437e-05 6.5750696255779e-05 -3.58247615405223e-06 -1.88794696256215e-06 -9.04335606236979e-06 4.01613116607677e-05 6.5750696255779e-05 0.000170094731558486 -2.12547994748194e-06 8.53157395452494e-06 -1.71452103153011e-05 -3.0669482758467e-05 -3.58247615405223e-06 -2.12547994748194e-06 2.28516098887334e-05 -5.7837138097095e-06 -9.98799989314556e-06 -1.34989209424156e-05 -1.88794696256215e-06 8.53157395452494e-06 -5.7837138097095e-06 7.01473542555952e-05 -4.90017995560466e-05 -2.14998395948399e-05 -9.04335606236979e-06 -1.71452103153011e-05 -9.98799989314556e-06 -4.90017995560466e-05 0.000102750432945659 3.61206837382263e-05 4.01613116607677e-05 -3.0669482758467e-05 -1.34989209424156e-05 -2.14998395948399e-05 3.61206837382263e-05 0.000379822714554411 0 0 0 81 65 0 0 0 81 47 0 0 0 0 0 0 0 0 0 321 633 654 0 407 0 +290 404 -0.891587904377379 0.408401101141758 0.195651601971853 0.638615063271475 -0.42220930254463 -0.905895362766812 -0.0330589861060979 -1.27633421067479 0.163738552615839 -0.112080918553452 0.980116092145968 0.708022005294291 0.000112405686214549 8.16074024390647e-05 -1.11519766210131e-05 2.66591655644795e-05 -6.44561036252323e-05 5.16144795665057e-05 8.16074024390647e-05 0.000122476486953826 -8.11166284041397e-06 2.80106887913101e-05 -5.23593801183786e-05 8.43789145656228e-07 -1.11519766210131e-05 -8.11166284041397e-06 2.26833331806961e-05 -3.35633888497241e-06 -4.37026805724387e-06 -1.2845528995504e-05 2.66591655644795e-05 2.80106887913101e-05 -3.35633888497241e-06 6.4202078598809e-05 -4.49869581928265e-05 -8.4200708431951e-06 -6.44561036252323e-05 -5.23593801183786e-05 -4.37026805724387e-06 -4.49869581928265e-05 0.000118623103768981 1.35052824868384e-05 5.16144795665057e-05 8.43789145656228e-07 -1.2845528995504e-05 -8.4200708431951e-06 1.35052824868384e-05 0.000442460050415552 0 0 0 10 227 0 0 0 10 209 0 0 0 0 0 0 0 0 0 170 663 678 0 307 0 +290 337 -0.804164180991141 0.507474995064524 0.309498141181993 0.613645441399365 -0.499991002208704 -0.859081263170839 0.109491465325532 -1.29372108431336 0.321448234901335 -0.0666971712522895 0.944575311780781 0.671991057492851 0.000244185850656283 -0.000136525922502925 -3.88408442665992e-05 -4.43836541973291e-05 -5.24732927751544e-05 -0.000156360343057737 -0.000136525922502925 0.000276439033142836 5.94205897026875e-05 0.00012280456034871 -3.73054592647964e-05 0.000228703364070769 -3.88408442665992e-05 5.94205897026875e-05 5.65820109488242e-05 1.72348482698616e-05 -6.57315554923254e-06 5.78391311913514e-05 -4.43836541973291e-05 0.00012280456034871 1.72348482698616e-05 0.000172978692310739 -0.000112649799361781 0.000196838849994653 -5.24732927751544e-05 -3.73054592647964e-05 -6.57315554923254e-06 -0.000112649799361781 0.00019433614571105 -6.33296834920137e-05 -0.000156360343057737 0.000228703364070769 5.78391311913514e-05 0.000196838849994653 -6.33296834920137e-05 0.000571406596299157 0 0 0 80 195 0 0 0 77 159 0 0 0 0 0 0 0 0 0 441 208 218 0 395 0 +290 403 -0.89064516539085 0.406971572243928 0.202793808463698 0.636998123016269 -0.423463183069803 -0.904847688695101 -0.0439271311096506 -1.28567340921677 0.165620415258194 -0.124999198591186 0.978235696752712 0.709755984499888 0.000137111841804899 7.90148375707961e-05 -9.10553734391838e-06 1.46783763524707e-05 -6.48596155887439e-05 8.14539190191936e-05 7.90148375707961e-05 0.00012911394930199 -2.48702336179298e-06 1.64011992282371e-05 -3.25856948479126e-05 0.000112181971733771 -9.10553734391838e-06 -2.48702336179298e-06 2.03352780794898e-05 -5.14975766705342e-06 -1.5968916894298e-06 -4.00333304363289e-06 1.46783763524707e-05 1.64011992282371e-05 -5.14975766705342e-06 6.6843518138511e-05 -3.44817155085589e-05 7.57203297629115e-05 -6.48596155887439e-05 -3.25856948479126e-05 -1.5968916894298e-06 -3.44817155085589e-05 0.000121458603909253 -0.000103185693800157 8.14539190191936e-05 0.000112181971733771 -4.00333304363289e-06 7.57203297629115e-05 -0.000103185693800157 0.000835033068258783 0 0 0 10 216 0 0 0 10 203 0 0 0 0 0 0 0 0 0 158 650 672 0 312 0 +291 435 -0.366749732070251 0.922795478387676 0.118081070005569 0.610707158400039 -0.921425797946147 -0.377814391856066 0.0907236693798167 -1.1100601806342 0.128332119540301 -0.075530062714738 0.988850886999957 0.392644344485165 9.23139280831252e-05 5.84556979817829e-05 4.64424102372571e-06 1.87690478815752e-05 -9.6367676103744e-05 0.000203640232401291 5.84556979817829e-05 7.25121868153981e-05 4.53119515936005e-06 1.88066059203074e-05 -5.35514725145858e-05 0.000157520784558272 4.64424102372571e-06 4.53119515936005e-06 1.88203297460645e-05 -7.8199881584705e-06 -2.88390887302486e-06 -1.53108708810473e-06 1.87690478815752e-05 1.88066059203074e-05 -7.8199881584705e-06 3.25122854193819e-05 -3.48594986496372e-05 8.50745489135349e-05 -9.6367676103744e-05 -5.35514725145858e-05 -2.88390887302486e-06 -3.48594986496372e-05 0.000345205206390509 -0.00024518647092408 0.000203640232401291 0.000157520784558272 -1.53108708810473e-06 8.50745489135349e-05 -0.00024518647092408 0.000829846620065081 0 0 0 1666 0 0 0 0 1655 0 0 0 0 0 0 0 0 0 0 73 641 641 0 496 0 +291 436 -0.310797966212569 0.940333550819749 0.138482624905994 0.609819457810956 -0.946146675750462 -0.319971278518306 0.0492427546925578 -1.09034654179946 0.0906150769159405 -0.115720327194852 0.989139885814658 0.281296276330826 6.030272920045e-05 3.00480080061691e-05 -3.22144872251611e-06 2.39713347066442e-06 -1.84852237080931e-07 0.000103392669095012 3.00480080061691e-05 8.73927538397711e-05 1.71425318463091e-06 1.29435147380284e-05 6.07429166886338e-05 0.000146680795590704 -3.22144872251611e-06 1.71425318463091e-06 1.74917600725457e-05 -2.5562191182734e-06 5.54411895294601e-06 -2.92518480640145e-06 2.39713347066442e-06 1.29435147380284e-05 -2.5562191182734e-06 2.84975091735286e-05 1.98354074166805e-05 4.81651287762762e-05 -1.84852237080931e-07 6.07429166886338e-05 5.54411895294601e-06 1.98354074166805e-05 0.000236384922578204 0.000185933041792607 0.000103392669095012 0.000146680795590704 -2.92518480640145e-06 4.81651287762762e-05 0.000185933041792607 0.000719314617976517 0 0 0 1738 0 0 0 0 1724 0 0 0 0 0 0 0 0 0 0 32 756 756 0 512 0 +291 434 -0.441524445785954 0.885279933041653 0.146067121307886 0.568784350235903 -0.88948435792279 -0.453235417140284 0.0582686335892217 -1.10495485264776 0.117786844698755 -0.104197393457989 0.987557169186915 0.476921945093328 6.76604251568095e-05 3.61595891164128e-05 2.09352776937038e-06 3.97446382921834e-06 -3.39044852037792e-05 5.77311326453155e-05 3.61595891164128e-05 0.000115018020251445 1.05934426018714e-06 2.04090082896396e-05 -2.63307500220172e-05 0.000178567875793937 2.09352776937038e-06 1.05934426018714e-06 1.69225914676884e-05 -4.52645367014681e-06 8.61886412539308e-07 -2.46072964499049e-07 3.97446382921834e-06 2.04090082896396e-05 -4.52645367014681e-06 2.98405676026469e-05 -1.57041217537494e-05 7.22612715260977e-05 -3.39044852037792e-05 -2.63307500220172e-05 8.61886412539308e-07 -1.57041217537494e-05 0.000158234134040659 -9.23638369671025e-05 5.77311326453155e-05 0.000178567875793937 -2.46072964499049e-07 7.22612715260977e-05 -9.23638369671025e-05 0.000645337122911859 0 0 0 1428 0 0 0 0 1415 0 0 0 0 0 0 0 0 0 0 185 729 729 0 532 0 +291 438 -0.21533476332017 0.956620278076313 0.196236039704853 0.715235598006952 -0.975752216414859 -0.218843517874411 -0.00388932459988202 -1.07042801512511 0.0392243784824843 -0.192315257474675 0.980548973726 0.0909522329516169 6.51479819759701e-05 3.56934443092175e-05 -3.45380522278698e-06 -3.55665245464546e-06 -3.41516826190382e-05 5.95316528163122e-05 3.56934443092175e-05 8.43911018650293e-05 1.09040484684279e-07 -8.2394434597891e-06 -4.576756953012e-05 5.78246950310954e-05 -3.45380522278698e-06 1.09040484684279e-07 1.64996771336357e-05 -5.15632258440749e-06 8.71527172600898e-06 -5.1695018539586e-06 -3.55665245464546e-06 -8.2394434597891e-06 -5.15632258440749e-06 2.1074371987981e-05 1.4052069457051e-05 -2.81154292736095e-06 -3.41516826190382e-05 -4.576756953012e-05 8.71527172600898e-06 1.4052069457051e-05 0.000212438410714973 -0.000102393874268706 5.95316528163122e-05 5.78246950310954e-05 -5.1695018539586e-06 -2.81154292736095e-06 -0.000102393874268706 0.000610741491716677 0 0 0 1722 0 0 0 0 1709 0 0 0 0 0 0 0 0 0 0 0 736 736 0 429 0 +291 441 0.135625568276594 0.966977071342885 0.215780093444199 0.868527460730176 -0.990570354703511 0.128081553655586 0.0486362827088131 -1.00840741515796 0.0193927205984922 -0.220341687182221 0.975229954050572 -0.160608642002277 0.000101450558603993 -1.30016285045658e-05 -3.80459661550181e-06 -1.50218600498601e-05 -5.01388921759645e-06 -3.78856746443151e-05 -1.30016285045658e-05 7.2272437640472e-05 2.6790169896463e-06 5.81159710650057e-06 1.28793701903183e-05 -2.21298490574621e-05 -3.80459661550181e-06 2.6790169896463e-06 1.60022564687167e-05 -2.99797913222172e-06 8.75333668468256e-06 3.17974687896954e-06 -1.50218600498601e-05 5.81159710650057e-06 -2.99797913222172e-06 2.83106743821086e-05 7.16009802790368e-06 -1.00175089181898e-05 -5.01388921759645e-06 1.28793701903183e-05 8.75333668468256e-06 7.16009802790368e-06 8.14126296626619e-05 -6.3239515936149e-05 -3.78856746443151e-05 -2.21298490574621e-05 3.17974687896954e-06 -1.00175089181898e-05 -6.3239515936149e-05 0.000246233302958826 136 93 0 1460 0 116 78 0 1460 0 0 0 0 0 0 0 0 0 0 0 763 748 0 4 163 +291 294 0.982533800886332 0.186080764789271 -0.0011309691852156 0.314022041855388 -0.185967920964085 0.98211652363734 0.0293779912655972 -0.203244279352636 0.00657742260719975 -0.0286545454325437 0.999567733841935 -0.105678336189344 3.64782902369055e-05 9.70888795165542e-06 1.69744358367489e-06 -2.1572913263568e-05 2.91370514151721e-07 1.32900083190009e-05 9.70888795165542e-06 3.18536065133351e-05 -1.94000177785019e-07 2.98446466001471e-07 1.19285070368584e-06 -3.7238023499666e-06 1.69744358367489e-06 -1.94000177785019e-07 1.59679182962645e-05 -3.94232464702644e-06 1.72650921775551e-06 2.37545033468721e-06 -2.1572913263568e-05 2.98446466001471e-07 -3.94232464702644e-06 8.18720036854028e-05 -2.71525498283569e-06 -7.24251147411886e-06 2.91370514151721e-07 1.19285070368584e-06 1.72650921775551e-06 -2.71525498283569e-06 1.65581797410218e-05 -5.19192244485959e-06 1.32900083190009e-05 -3.7238023499666e-06 2.37545033468721e-06 -7.24251147411886e-06 -5.19192244485959e-06 0.000118743014332802 2980 2902 0 1405 0 2956 2878 0 1279 0 0 0 0 0 0 0 0 0 2268 0 398 419 0 0 2391 +291 437 -0.28258563711516 0.94276622495753 0.17702317016579 0.68351225431622 -0.957506845139655 -0.288324757699542 0.00703388997671607 -1.09113337635711 0.0576714765453715 -0.167513220901598 0.984181549113907 0.179449271870176 4.11287744225044e-05 1.87848491646303e-05 3.76649888098134e-06 -3.79084967385887e-06 -1.29427321066274e-05 3.7275937213761e-05 1.87848491646303e-05 6.17662246629465e-05 3.32047334042554e-06 -5.55346136058477e-06 -2.70836858353465e-05 5.29067242199831e-05 3.76649888098134e-06 3.32047334042554e-06 1.59189869199158e-05 -2.80208368696352e-06 2.51689522918884e-06 -2.57543636657752e-06 -3.79084967385887e-06 -5.55346136058477e-06 -2.80208368696352e-06 2.02310910745879e-05 1.16468506981138e-05 -4.96664348943292e-06 -1.29427321066274e-05 -2.70836858353465e-05 2.51689522918884e-06 1.16468506981138e-05 0.000413298902771203 -0.000150688393556509 3.7275937213761e-05 5.29067242199831e-05 -2.57543636657752e-06 -4.96664348943292e-06 -0.000150688393556509 0.00033833511819622 0 0 0 1791 0 0 0 0 1776 0 0 0 0 0 0 0 0 0 0 17 672 672 0 526 0 +291 433 -0.542761758100444 0.83609575510896 0.0797092355533163 0.579111229340845 -0.835655188886363 -0.547104377337599 0.0485510616293354 -1.12401447968599 0.0842026082197739 -0.040257776724713 0.995635089870867 0.57036616933165 5.29534922726527e-05 5.27451139850719e-05 3.38886832695852e-06 1.37067758787868e-06 -1.10305337835253e-05 8.82696333924833e-05 5.27451139850719e-05 9.11726436770766e-05 8.0626552214554e-07 4.42040963007934e-07 1.71199486108989e-06 9.74683111154756e-05 3.38886832695852e-06 8.0626552214554e-07 1.80728152144253e-05 -5.90796621036066e-06 -4.36758908697973e-06 6.21158783166527e-06 1.37067758787868e-06 4.42040963007934e-07 -5.90796621036066e-06 2.54235223947723e-05 1.00454962052328e-07 1.1708413071369e-05 -1.10305337835253e-05 1.71199486108989e-06 -4.36758908697973e-06 1.00454962052328e-07 7.25030584668902e-05 -4.62499069682636e-05 8.82696333924833e-05 9.74683111154756e-05 6.21158783166527e-06 1.1708413071369e-05 -4.62499069682636e-05 0.000518503801439108 0 0 0 1004 0 0 0 0 993 0 0 0 0 0 0 0 0 0 0 335 851 851 0 501 0 +291 295 0.972150228566556 0.230619604659831 0.0416956957555113 0.418516636594603 -0.231728943005158 0.972483807635403 0.0240195932659291 -0.264226189280158 -0.0350089998672484 -0.033012752588838 0.998841593094122 -0.09958274854778 3.45041529043119e-05 2.73853728560938e-05 -2.43657754483423e-06 -2.56103479332941e-06 1.48756875327751e-06 3.36142234511331e-05 2.73853728560938e-05 7.28889893975774e-05 2.76424069873917e-07 1.69936867299614e-05 -4.14933409887404e-07 6.43442100588937e-05 -2.43657754483423e-06 2.76424069873917e-07 1.89081511033506e-05 5.94945108291786e-06 1.85620605946335e-06 4.45044997878069e-06 -2.56103479332941e-06 1.69936867299614e-05 5.94945108291786e-06 8.33313625351322e-05 -3.09424976075533e-06 3.38531550905025e-05 1.48756875327751e-06 -4.14933409887404e-07 1.85620605946335e-06 -3.09424976075533e-06 1.58235364805097e-05 -3.8141148636545e-06 3.36142234511331e-05 6.43442100588937e-05 4.45044997878069e-06 3.38531550905025e-05 -3.8141148636545e-06 0.00028205887449637 2713 2580 0 1842 0 2688 2555 0 1714 0 0 0 0 0 0 0 0 0 1867 0 464 492 0 0 3012 +291 293 0.990865048991263 0.13485660383844 -0.000388701302951924 0.219006499060704 -0.134837040352878 0.990762866455767 0.0144192579985732 -0.13939437760089 0.00232964298066558 -0.0142351274499025 0.999895961543034 -0.0381606946100872 2.79030477694814e-05 1.68518432716392e-05 -3.62741028447095e-06 1.83134571709817e-06 1.38406330121066e-06 9.72336672575292e-06 1.68518432716392e-05 5.30844806554851e-05 -3.20332478777047e-06 1.21184473150449e-05 -5.15974516807549e-06 3.6507156814934e-05 -3.62741028447095e-06 -3.20332478777047e-06 1.19296789666167e-05 3.32883933083819e-07 9.05057004611997e-07 -3.58524033360376e-06 1.83134571709817e-06 1.21184473150449e-05 3.32883933083819e-07 5.71362642072843e-05 -7.98712202395297e-06 4.94915036055461e-05 1.38406330121066e-06 -5.15974516807549e-06 9.05057004611997e-07 -7.98712202395297e-06 1.55941452986849e-05 -1.20004853548964e-05 9.72336672575292e-06 3.6507156814934e-05 -3.58524033360376e-06 4.94915036055461e-05 -1.20004853548964e-05 0.000151955985995495 3257 3169 0 966 0 3239 3151 0 839 0 0 0 0 0 0 0 0 0 2812 0 310 320 0 0 3287 +291 431 -0.736535899181743 0.662706868062623 0.135404860470995 0.567941078674308 -0.661634877791032 -0.74747289249814 0.0593596114450661 -1.15092751618638 0.140549484904735 -0.0458680935192677 0.989010596651988 0.655354698045859 9.49431111905016e-05 4.01732309486109e-05 5.00345996054349e-06 -3.29577736274318e-06 -1.42930729336765e-05 4.71929457148666e-05 4.01732309486109e-05 0.000114388116225477 4.68376008578945e-06 1.26960790479474e-05 -7.82693032415347e-06 4.21702375500826e-05 5.00345996054349e-06 4.68376008578945e-06 1.562630677212e-05 -2.71968661368075e-06 -6.26981514183804e-06 -2.01261782512422e-06 -3.29577736274318e-06 1.26960790479474e-05 -2.71968661368075e-06 3.1832336089826e-05 -1.07454240259142e-05 1.76795006320978e-05 -1.42930729336765e-05 -7.82693032415347e-06 -6.26981514183804e-06 -1.07454240259142e-05 7.0947608684255e-05 2.77866671935125e-05 4.71929457148666e-05 4.21702375500826e-05 -2.01261782512422e-06 1.76795006320978e-05 2.77866671935125e-05 0.000320448618443892 0 0 0 285 0 0 0 0 281 0 0 0 0 0 0 0 0 0 0 425 610 610 0 330 0 +291 336 -0.794508080382767 0.548751909875639 0.260054324352297 0.568456913148155 -0.53665654787063 -0.834905634121206 0.122197920359735 -1.18105606501364 0.284177162759553 -0.0424726208339536 0.957830578257672 0.612326039898154 8.36914807083912e-05 7.83732550530089e-06 -3.62842983738309e-06 -3.12792075403655e-07 -1.16492867009887e-05 2.76980097179662e-05 7.83732550530089e-06 5.14792572443414e-05 -1.3422455866026e-06 1.31827960958683e-05 -2.59823867859401e-06 1.94056251131239e-05 -3.62842983738309e-06 -1.3422455866026e-06 2.65849978360245e-05 -7.76932859442458e-06 -4.93166617513393e-06 1.01331972201533e-05 -3.12792075403655e-07 1.31827960958683e-05 -7.76932859442458e-06 6.20530595663028e-05 -1.4805147841336e-05 5.07387304738969e-05 -1.16492867009887e-05 -2.59823867859401e-06 -4.93166617513393e-06 -1.4805147841336e-05 5.38956462445379e-05 -1.82200083476949e-05 2.76980097179662e-05 1.94056251131239e-05 1.01331972201533e-05 5.07387304738969e-05 -1.82200083476949e-05 0.000269566154819365 0 0 0 118 87 0 0 0 114 54 0 0 0 0 0 0 0 0 0 740 389 398 0 383 0 +291 333 -0.818511277206924 0.529453404642171 0.222976190204029 0.618258639452427 -0.513866291885644 -0.848281403887926 0.127906582636027 -1.17271221015411 0.256867131312645 -0.00988696772234531 0.966396153096891 0.557301378960741 6.95613584949404e-05 5.41858741322981e-05 5.03305352071283e-06 1.20603945176119e-05 -6.39661016079114e-06 0.000103659033835875 5.41858741322981e-05 7.78775494658817e-05 7.10758285959233e-06 1.1917430918934e-05 -5.27087689684759e-06 9.32338010689707e-05 5.03305352071283e-06 7.10758285959233e-06 2.19207442917791e-05 -3.80338654503855e-06 -3.86446369964985e-06 1.27443658652962e-05 1.20603945176119e-05 1.1917430918934e-05 -3.80338654503855e-06 5.93165518102167e-05 -1.72266756340988e-05 6.85410331450333e-05 -6.39661016079114e-06 -5.27087689684759e-06 -3.86446369964985e-06 -1.72266756340988e-05 6.3606929998992e-05 5.06060998059669e-06 0.000103659033835875 9.32338010689707e-05 1.27443658652962e-05 6.85410331450333e-05 5.06060998059669e-06 0.000483718133444061 0 0 0 171 98 0 0 0 161 64 0 0 0 0 0 0 0 0 0 712 423 435 0 420 0 +291 432 -0.643004002381335 0.760596187304906 0.0896621033593575 0.5821520693608 -0.759463456254427 -0.648349174682405 0.0534659359099238 -1.13544314275164 0.0987983377171044 -0.0337162801311944 0.994536123485946 0.619081549389009 0.00013492950869762 2.36878998637578e-05 -1.24182955248667e-05 1.42853235667602e-05 -6.96532667866396e-05 9.08641745169967e-05 2.36878998637578e-05 0.000117030697651326 6.00635664111131e-06 1.02443917368331e-05 7.4979115327069e-06 0.000128787988587067 -1.24182955248667e-05 6.00635664111131e-06 1.99011326555998e-05 -4.13247240084948e-06 8.07100649686934e-06 1.73627007288497e-06 1.42853235667602e-05 1.02443917368331e-05 -4.13247240084948e-06 2.77964500709035e-05 -1.23547970190045e-05 4.46998210233014e-05 -6.96532667866396e-05 7.4979115327069e-06 8.07100649686934e-06 -1.23547970190045e-05 0.000108240294422797 -3.09838789231932e-05 9.08641745169967e-05 0.000128787988587067 1.73627007288497e-06 4.46998210233014e-05 -3.09838789231932e-05 0.000592666155421927 0 0 0 638 0 0 0 0 629 0 0 0 0 0 0 0 0 0 0 401 819 819 0 390 0 +291 430 -0.816770030527331 0.549593485719425 0.175595323648309 0.578429295807366 -0.557256629499508 -0.830312940142205 0.0067431677463091 -1.15935678129188 0.149505070520135 -0.0923440408861284 0.98443933891408 0.67239982347362 9.70524335262639e-05 9.44444983029199e-05 -4.72338702720142e-06 3.48829862096564e-06 -8.97824064984618e-06 7.16260880908752e-05 9.44444983029199e-05 0.000170448052611564 -3.57783029320034e-06 1.70764158292008e-05 -2.13306828492335e-05 7.92090211649499e-05 -4.72338702720142e-06 -3.57783029320034e-06 1.52789698180639e-05 -5.18370282299161e-06 -3.12579447747509e-06 -8.20234003620382e-06 3.48829862096564e-06 1.70764158292008e-05 -5.18370282299161e-06 5.00852184345209e-05 -2.84277450616732e-05 3.74685033757985e-06 -8.97824064984618e-06 -2.13306828492335e-05 -3.12579447747509e-06 -2.84277450616732e-05 7.6358812383686e-05 1.02587187592841e-05 7.16260880908752e-05 7.92090211649499e-05 -8.20234003620382e-06 3.74685033757985e-06 1.02587187592841e-05 0.000717521162201978 0 0 0 129 4 0 0 0 125 0 0 0 0 0 0 0 0 0 0 360 764 783 0 381 0 +291 337 -0.777961489616826 0.569321968057954 0.265797700064894 0.551843622858249 -0.55974837290046 -0.820159538876756 0.118406460232347 -1.18327450670689 0.285407918089981 -0.0566641639493972 0.956729581864938 0.651531059803852 0.000252942678798115 -0.00012569477074213 -3.04364216698853e-05 -6.40806970431382e-05 -3.41343840903102e-06 -0.000109352985486496 -0.00012569477074213 0.000236683413758891 3.48677920928407e-05 0.000107634232605691 -2.97303156657845e-05 0.000277974463034083 -3.04364216698853e-05 3.48677920928407e-05 3.79839310348739e-05 1.01728987292336e-05 -1.1684711530915e-05 4.36578424340395e-05 -6.40806970431382e-05 0.000107634232605691 1.01728987292336e-05 0.000125592975556598 -5.20210000874535e-05 0.000182232295662351 -3.41343840903102e-06 -2.97303156657845e-05 -1.1684711530915e-05 -5.20210000874535e-05 9.79831348621179e-05 -5.87399128784958e-05 -0.000109352985486496 0.000277974463034083 4.36578424340395e-05 0.000182232295662351 -5.87399128784958e-05 0.000598270826408081 0 0 0 123 41 0 0 0 116 16 0 0 0 0 0 0 0 0 0 591 254 264 0 366 0 +291 335 -0.807341888394618 0.533343304605346 0.252475730865485 0.577609449053974 -0.518309536878045 -0.845466990699223 0.128611008934955 -1.1782587962356 0.282053716913425 -0.0270275243159519 0.959017838053429 0.602134555246154 0.000139804460706221 1.50415272055902e-06 -1.3959522727423e-05 -2.9215901280245e-05 2.44389997307317e-05 6.82654605794065e-05 1.50415272055902e-06 7.72104797293411e-05 2.19871130752816e-06 2.55982098529665e-05 -9.52292675111454e-06 4.16939623913835e-05 -1.3959522727423e-05 2.19871130752816e-06 3.20985105803306e-05 -5.48922290549377e-06 -1.12495802821436e-05 4.47271105920705e-06 -2.9215901280245e-05 2.55982098529665e-05 -5.48922290549377e-06 6.65165326874558e-05 -2.19347393236741e-05 9.6709791147902e-06 2.44389997307317e-05 -9.52292675111454e-06 -1.12495802821436e-05 -2.19347393236741e-05 7.26517429577534e-05 3.09990699038348e-05 6.82654605794065e-05 4.16939623913835e-05 4.47271105920705e-06 9.6709791147902e-06 3.09990699038348e-05 0.00031434935767281 0 0 0 120 108 0 0 0 114 75 0 0 0 0 0 0 0 0 0 778 357 367 0 374 0 +291 338 -0.775710945323466 0.57511370185016 0.259839872324438 0.560774740586621 -0.558436575259151 -0.817322715250383 0.141887880203251 -1.18860635387576 0.293974694009886 -0.0350401067342275 0.955170702127032 0.664517258012213 0.000109354807365228 4.44996036719205e-05 5.75056229615862e-07 3.21926499611808e-05 -3.12654041116603e-05 9.29468926197336e-05 4.44996036719205e-05 6.57309773840955e-05 1.9874404148105e-06 1.8831885495187e-05 -1.45994756662298e-05 2.66169520506161e-05 5.75056229615862e-07 1.9874404148105e-06 2.789339827505e-05 -1.36670298495135e-05 -3.60090219787475e-06 -1.55037128819354e-05 3.21926499611808e-05 1.8831885495187e-05 -1.36670298495135e-05 8.21210629200493e-05 -5.65308971872043e-05 7.85136152422765e-05 -3.12654041116603e-05 -1.45994756662298e-05 -3.60090219787475e-06 -5.65308971872043e-05 0.000123158785866181 -1.98216896564243e-05 9.29468926197336e-05 2.66169520506161e-05 -1.55037128819354e-05 7.85136152422765e-05 -1.98216896564243e-05 0.000366413160851204 0 0 0 117 43 0 0 0 113 21 0 0 0 0 0 0 0 0 0 607 393 402 0 320 0 +291 327 -0.68568314418557 0.682450783956304 0.253178895757956 0.820938106384005 -0.681042331940647 -0.724263972604446 0.107810204025737 -1.20777152952433 0.256943511077118 -0.0985019058935012 0.961393471296072 0.0144449508453033 9.31341202237003e-05 2.12328042314751e-05 -3.56981398453697e-06 7.99407605618978e-06 -1.92926094633535e-05 3.14700434247336e-06 2.12328042314751e-05 7.46152423664567e-05 5.99160472076107e-06 -1.05423273875961e-06 3.44804634240672e-05 5.07442331867547e-05 -3.56981398453697e-06 5.99160472076107e-06 2.74204607471344e-05 -6.27515855868632e-06 2.30472184697565e-06 -9.88564902216534e-07 7.99407605618978e-06 -1.05423273875961e-06 -6.27515855868632e-06 9.72017412010483e-05 -0.000120846768198955 -8.19830928697099e-06 -1.92926094633535e-05 3.44804634240672e-05 2.30472184697565e-06 -0.000120846768198955 0.000340014402070457 0.000148348729200588 3.14700434247336e-06 5.07442331867547e-05 -9.88564902216534e-07 -8.19830928697099e-06 0.000148348729200588 0.000438688263175284 0 0 0 650 1 0 0 0 631 1 0 0 0 0 0 0 0 0 0 863 5 5 0 410 0 +291 334 -0.814529024265651 0.529391277256738 0.237249539922265 0.590613584929782 -0.513046567291929 -0.848250002191844 0.131358873211917 -1.17128088836422 0.270787164427738 -0.0147244472227699 0.962526624169518 0.589156701349449 8.95432059777125e-05 2.66461877428793e-05 -1.61631489884153e-06 -2.78582469695266e-06 -9.80515933757712e-06 1.03158526441382e-05 2.66461877428793e-05 8.45417752469674e-05 7.00622340637593e-06 1.37553084147361e-05 -3.27774438033556e-06 1.57810729723646e-05 -1.61631489884153e-06 7.00622340637593e-06 2.95628048347471e-05 -1.00193554734648e-05 -2.21495516692602e-06 1.33332526779965e-05 -2.78582469695266e-06 1.37553084147361e-05 -1.00193554734648e-05 5.45372800010712e-05 -9.60649276539951e-06 4.70911585130148e-05 -9.80515933757712e-06 -3.27774438033556e-06 -2.21495516692602e-06 -9.60649276539951e-06 4.73632220986679e-05 -2.03583994141053e-05 1.03158526441382e-05 1.57810729723646e-05 1.33332526779965e-05 4.70911585130148e-05 -2.03583994141053e-05 0.000243053343339003 0 0 0 137 100 0 0 0 129 73 0 0 0 0 0 0 0 0 0 762 357 368 0 414 0 +291 403 -0.864159790562443 0.474353950602429 0.16797674220839 0.577099372420941 -0.487767783564551 -0.871662677740626 -0.0478201375004985 -1.17679012448213 0.1237353857698 -0.123257883244478 0.984630412147873 0.703907179959301 0.000125285975660328 0.000124672991944105 -6.44121218807877e-06 3.16390152775506e-05 -7.11697634804879e-05 0.000181294213353558 0.000124672991944105 0.000191613037726303 -8.74459327617383e-06 3.26547857795427e-05 -5.99658033169807e-05 0.000307033975943792 -6.44121218807877e-06 -8.74459327617383e-06 1.72139016191524e-05 -1.1595160619669e-05 -2.55992373179691e-07 -3.44230061600262e-05 3.16390152775506e-05 3.26547857795427e-05 -1.1595160619669e-05 5.32871676708211e-05 -2.22500958762848e-05 7.57720909013103e-05 -7.11697634804879e-05 -5.99658033169807e-05 -2.55992373179691e-07 -2.22500958762848e-05 9.93982748255415e-05 -7.68876649950197e-05 0.000181294213353558 0.000307033975943792 -3.44230061600262e-05 7.57720909013103e-05 -7.68876649950197e-05 0.00113757109882143 0 0 0 13 118 0 0 0 12 101 0 0 0 0 0 0 0 0 0 207 673 700 0 325 0 +292 435 -0.301252513875356 0.94548412432928 0.123720222781372 0.545595668498968 -0.945821894764654 -0.312766331073558 0.0871674568321526 -1.00174943799546 0.121110966751891 -0.0907578800329748 0.988481229434501 0.411848745633954 6.27821305548043e-05 4.94073607393773e-05 8.81156477837807e-06 6.77177774188308e-06 -2.96798955830204e-05 8.87485916622554e-05 4.94073607393773e-05 0.000118802056278268 1.30880735425959e-05 2.90975682931546e-05 -2.03944417843096e-05 0.000212603745152334 8.81156477837807e-06 1.30880735425959e-05 2.01603672457148e-05 -5.96263787693587e-06 -5.77712169246934e-06 3.12070201881752e-05 6.77177774188308e-06 2.90975682931546e-05 -5.96263787693587e-06 4.30173370065913e-05 -1.75022313388664e-05 8.2644413089655e-05 -2.96798955830204e-05 -2.03944417843096e-05 -5.77712169246934e-06 -1.75022313388664e-05 0.00026075876702765 -9.0714138950895e-05 8.87485916622554e-05 0.000212603745152334 3.12070201881752e-05 8.2644413089655e-05 -9.0714138950895e-05 0.000676670406989656 0 0 0 1599 0 0 0 0 1598 0 0 0 0 0 0 0 0 0 0 56 638 638 0 394 0 +292 437 -0.215872276872528 0.958520144040378 0.186113657603849 0.6049167835334 -0.974989465265614 -0.221923508631273 0.0120622940545051 -0.96933433081805 0.0528649477342272 -0.178854940623952 0.982454175784021 0.185506251880468 5.37263562616919e-05 3.58488328929685e-05 3.07992844586195e-06 -5.46316000365089e-06 -4.44526097904819e-05 9.43992090715945e-05 3.58488328929685e-05 5.84154410711915e-05 3.17874006736258e-06 -1.19684536168904e-06 3.67051173631458e-05 6.37914633402653e-05 3.07992844586195e-06 3.17874006736258e-06 1.718532947402e-05 -4.71566891640287e-06 3.04326083559528e-06 -9.16145865991167e-06 -5.46316000365089e-06 -1.19684536168904e-06 -4.71566891640287e-06 3.41819066781363e-05 0.000170310265334361 -1.35453862160596e-05 -4.44526097904819e-05 3.67051173631458e-05 3.04326083559528e-06 0.000170310265334361 0.00236233873479367 -0.000209782391607882 9.43992090715945e-05 6.37914633402653e-05 -9.16145865991167e-06 -1.35453862160596e-05 -0.000209782391607882 0.000440845381179249 0 0 0 1878 0 0 0 0 1875 0 0 0 0 0 0 0 0 0 0 10 864 864 0 398 0 +292 436 -0.244365789194283 0.958473415881968 0.147017251093218 0.587961641695646 -0.966047006171604 -0.253752615266411 0.0486085600726546 -0.992062753916803 0.0838960245681239 -0.130147306130431 0.987938831997537 0.295151210534916 4.42398515411341e-05 1.52384034574178e-05 2.18696671184908e-06 -3.73644415455514e-06 -1.79226605604104e-05 3.11103563669616e-05 1.52384034574178e-05 3.49527697971423e-05 1.21933677159902e-06 2.66547000897713e-08 -1.32305970056405e-05 1.67414832533024e-05 2.18696671184908e-06 1.21933677159902e-06 1.59060685034123e-05 -5.9182803672101e-06 8.00156152031155e-07 -3.17263706853519e-06 -3.73644415455514e-06 2.66547000897713e-08 -5.9182803672101e-06 2.49386367384647e-05 1.42090978647762e-05 2.69694057287391e-06 -1.79226605604104e-05 -1.32305970056405e-05 8.00156152031155e-07 1.42090978647762e-05 0.000258220329955335 -1.75332895783071e-05 3.11103563669616e-05 1.67414832533024e-05 -3.17263706853519e-06 2.69694057287391e-06 -1.75332895783071e-05 0.000171640092391512 0 0 0 1917 0 0 0 0 1916 0 0 0 0 0 0 0 0 0 0 26 768 768 0 359 0 +292 433 -0.483787091493086 0.870678961949649 0.0887028484488688 0.55656228780093 -0.871090368768005 -0.488837184020291 0.0473262819026994 -1.02723253333114 0.0845672486503024 -0.0543723526932088 0.99493317751411 0.583147899143957 6.17010762853449e-05 4.97943200489605e-05 2.3296886631523e-06 7.16119829709474e-06 -2.44142060674222e-05 8.23442956141289e-05 4.97943200489605e-05 9.28287958170716e-05 -7.34717441301973e-06 -4.89692020299313e-07 1.89256985711846e-05 0.000145260669358689 2.3296886631523e-06 -7.34717441301973e-06 1.93433214222372e-05 -5.21578668763205e-06 -1.39007914201448e-05 5.72474350416622e-07 7.16119829709474e-06 -4.89692020299313e-07 -5.21578668763205e-06 3.8039289258383e-05 -2.85430641446212e-05 7.34205411744652e-06 -2.44142060674222e-05 1.89256985711846e-05 -1.39007914201448e-05 -2.85430641446212e-05 0.000199851762247522 -4.02417888369288e-05 8.23442956141289e-05 0.000145260669358689 5.72474350416622e-07 7.34205411744652e-06 -4.02417888369288e-05 0.000620898707163316 0 0 0 888 0 0 0 0 885 0 0 0 0 0 0 0 0 0 0 250 1056 1056 0 372 0 +292 294 0.992496434499343 0.118906112665558 0.0284984890276242 0.220920023288711 -0.119308295030011 0.992774124562759 0.0128478922660095 -0.120049271290349 -0.0267648695704639 -0.0161515934016634 0.999511264462519 -0.0498659601919631 3.16228951463684e-05 2.54814250638996e-05 4.75629318896372e-06 -8.80857489173018e-06 3.85572015519864e-07 1.07775352390568e-06 2.54814250638996e-05 5.80245745198222e-05 3.00046192333846e-07 1.09474264781324e-05 -1.59805696158203e-06 5.2046872744774e-05 4.75629318896372e-06 3.00046192333846e-07 1.4718997492612e-05 -2.57275265535885e-06 -3.30940864703424e-07 -4.42174300832372e-06 -8.80857489173018e-06 1.09474264781324e-05 -2.57275265535885e-06 7.2408017629275e-05 -2.57748714935986e-06 5.99561448330916e-05 3.85572015519864e-07 -1.59805696158203e-06 -3.30940864703424e-07 -2.57748714935986e-06 1.57164582133107e-05 -9.32288333497749e-06 1.07775352390568e-06 5.2046872744774e-05 -4.42174300832372e-06 5.99561448330916e-05 -9.32288333497749e-06 0.000208146574055704 3315 3237 0 860 0 3314 3236 0 751 0 0 0 0 0 0 0 0 0 2922 0 223 244 0 0 3241 +292 296 0.974273980322489 0.21249433328109 0.0750757590038208 0.425979509707595 -0.214466236151619 0.976543329059413 0.0191666382163498 -0.22144803850024 -0.0692419296202302 -0.0347747723642197 0.996993616022432 -0.10649519755142 3.62353408206247e-05 1.43689625930522e-05 6.18279461542632e-06 2.89248152492222e-06 2.45669326724517e-06 1.57302001128247e-05 1.43689625930522e-05 5.15685511478246e-05 3.92147188614137e-06 1.0318882593708e-05 5.52276511912132e-07 3.87284166974504e-05 6.18279461542632e-06 3.92147188614137e-06 1.65529981776513e-05 3.48534905398813e-06 3.41894472149786e-06 3.0173068056163e-06 2.89248152492222e-06 1.0318882593708e-05 3.48534905398813e-06 8.41869725191157e-05 1.90485902555978e-07 2.81505101281557e-05 2.45669326724517e-06 5.52276511912132e-07 3.41894472149786e-06 1.90485902555978e-07 1.8538388461922e-05 -5.69359489153343e-06 1.57302001128247e-05 3.87284166974504e-05 3.0173068056163e-06 2.81505101281557e-05 -5.69359489153343e-06 0.000221632631001598 2657 2510 0 1592 0 2656 2509 0 1476 0 0 0 0 0 0 0 0 0 2074 0 336 371 0 0 3113 +292 431 -0.687205031043619 0.711402436774071 0.147159159620636 0.523886364877745 -0.711392309999348 -0.700044619641514 0.0621169202774867 -1.04755702567925 0.147208106373698 -0.0620008343724631 0.987160407408537 0.677395015119515 0.000125265040368134 6.47860020700351e-05 5.73946269005201e-06 3.68707599435698e-05 -8.41919461476168e-05 0.000205333834254439 6.47860020700351e-05 0.000144930891710972 4.12594778160577e-06 1.65289137380246e-05 -1.68334442690417e-05 4.78672276004837e-05 5.73946269005201e-06 4.12594778160577e-06 1.79621910475221e-05 -1.01139200241216e-05 4.79918213093869e-06 -8.41087619525276e-06 3.68707599435698e-05 1.65289137380246e-05 -1.01139200241216e-05 6.47553541337985e-05 -6.30856600025699e-05 0.000133550555057732 -8.41919461476168e-05 -1.68334442690417e-05 4.79918213093869e-06 -6.30856600025699e-05 0.000155248328211343 -0.000191430820988582 0.000205333834254439 4.78672276004837e-05 -8.41087619525276e-06 0.000133550555057732 -0.000191430820988582 0.000874291867126156 0 0 0 336 0 0 0 0 336 0 0 0 0 0 0 0 0 0 0 329 717 717 0 266 0 +292 335 -0.765766000138251 0.590095072451357 0.255715151097648 0.54637687880695 -0.573190493495381 -0.806541678536574 0.144717583416555 -1.07708946898464 0.291642060064708 -0.0357536886493375 0.955859080905329 0.624021160979521 6.04759193272462e-05 4.37200452946702e-05 -5.10587585459097e-07 1.64524304956034e-05 -6.2649157523963e-06 4.57009454392334e-05 4.37200452946702e-05 0.000102535933722654 3.40992148808686e-06 1.86129046934716e-05 -8.0520874928e-06 6.44016405288813e-05 -5.10587585459097e-07 3.40992148808686e-06 2.60603713691213e-05 -5.24422878082287e-06 -1.0576904910098e-05 1.96984562687209e-05 1.64524304956034e-05 1.86129046934716e-05 -5.24422878082287e-06 0.000105482929426266 -7.21013967954569e-05 9.97936699670621e-05 -6.2649157523963e-06 -8.0520874928e-06 -1.0576904910098e-05 -7.21013967954569e-05 0.000130497219802814 -5.58813084674477e-05 4.57009454392334e-05 6.44016405288813e-05 1.96984562687209e-05 9.97936699670621e-05 -5.58813084674477e-05 0.000398155441865586 0 0 0 173 2 0 0 0 173 0 0 0 0 0 0 0 0 0 0 716 431 440 0 322 0 +292 430 -0.772165877176481 0.600319578129196 0.208269686318145 0.553465787418014 -0.613736726482156 -0.78951071417287 0.000250545829035173 -1.06411656395068 0.164581556351987 -0.127629292566514 0.978071405873686 0.694493336832465 0.000105137404969154 0.00015286713845748 -8.31243973884725e-06 1.16130059026899e-06 -3.34764488881952e-06 -1.81354698623679e-05 0.00015286713845748 0.00056711960116891 -2.19619780089567e-05 1.88756689489977e-05 2.25515206817316e-05 -8.76319228137116e-06 -8.31243973884725e-06 -2.19619780089567e-05 2.05719922892189e-05 -5.41713867305434e-06 -6.02797101400868e-06 4.77984984607315e-06 1.16130059026899e-06 1.88756689489977e-05 -5.41713867305434e-06 3.96292522788193e-05 -1.90504671940319e-05 8.66159248467657e-06 -3.34764488881952e-06 2.25515206817316e-05 -6.02797101400868e-06 -1.90504671940319e-05 7.81408294819079e-05 -6.03072696384999e-06 -1.81354698623679e-05 -8.76319228137116e-06 4.77984984607315e-06 8.66159248467657e-06 -6.03072696384999e-06 0.000307871780552384 0 0 0 141 0 0 0 0 141 0 0 0 0 0 0 0 0 0 0 207 662 682 0 337 0 +292 337 -0.735772054391701 0.623230582211433 0.264996462943592 0.542630094888014 -0.615539080301722 -0.778595333290344 0.122069437615683 -1.09702948083187 0.282402416061773 -0.0733003981905773 0.956491467305159 0.625822640387891 0.000629762159409468 -0.000156426963807255 -7.6449814489202e-05 -0.000133235822618583 -3.50817219685105e-05 -0.000196995442139789 -0.000156426963807255 0.000208451890723154 2.6433592587905e-05 8.999303316555e-05 1.79907613024342e-05 0.000280179643955033 -7.6449814489202e-05 2.6433592587905e-05 4.05470020341427e-05 1.3155983294467e-05 1.14125518727064e-06 6.20080939652529e-05 -0.000133235822618583 8.999303316555e-05 1.3155983294467e-05 0.000126849246735551 -1.37074217610594e-05 0.000276920292720124 -3.50817219685105e-05 1.79907613024342e-05 1.14125518727064e-06 -1.37074217610594e-05 6.91568658095432e-05 -2.95461788216959e-05 -0.000196995442139789 0.000280179643955033 6.20080939652529e-05 0.000276920292720124 -2.95461788216959e-05 0.00111553185885391 0 0 0 159 0 0 0 0 159 0 0 0 0 0 0 0 0 0 0 569 287 296 0 329 0 +292 336 -0.749767491858141 0.604027535665502 0.270184093370824 0.532272956276521 -0.591960493048735 -0.794743529578133 0.134035431372417 -1.07913271373061 0.29568815130514 -0.0594428999254973 0.953433300669846 0.64025296132336 9.22468393852625e-05 4.38797116272712e-05 2.33428629310193e-06 1.45217556113091e-05 -2.6577940562421e-05 5.48884167268695e-05 4.38797116272712e-05 0.000119728136878408 2.34694241028796e-06 1.84883148621403e-05 -2.00361985927431e-05 5.80891454170139e-06 2.33428629310193e-06 2.34694241028796e-06 2.27350427871239e-05 -8.94194318739707e-06 -9.04541667646178e-06 -1.36894042590828e-06 1.45217556113091e-05 1.84883148621403e-05 -8.94194318739707e-06 7.36875608914016e-05 -2.56979796253482e-05 9.25262017816934e-05 -2.6577940562421e-05 -2.00361985927431e-05 -9.04541667646178e-06 -2.56979796253482e-05 6.90424103970677e-05 -3.72921506703389e-05 5.48884167268695e-05 5.80891454170139e-06 -1.36894042590828e-06 9.25262017816934e-05 -3.72921506703389e-05 0.000345148947839309 0 0 0 156 0 0 0 0 155 0 0 0 0 0 0 0 0 0 0 659 438 453 0 344 0 +292 338 -0.73428485957422 0.629620182314869 0.253779768740258 0.527797053859341 -0.612018828873688 -0.775745681515847 0.153790736761334 -1.09089026514362 0.293698311374355 -0.0423917873096359 0.954957715432755 0.667545628994915 8.81713595532926e-05 5.63857496689643e-06 -7.67181398842804e-06 6.22886130905722e-07 -1.87819244477214e-05 -6.81951225292915e-06 5.63857496689643e-06 9.61581187189261e-05 1.21882144040843e-05 1.52787800762771e-05 -4.70921032884371e-06 3.22188702124915e-05 -7.67181398842804e-06 1.21882144040843e-05 2.67359544158561e-05 -4.63770920713923e-06 -6.77249900649732e-06 1.96785219177631e-05 6.22886130905722e-07 1.52787800762771e-05 -4.63770920713923e-06 8.77156340673716e-05 -4.95066628243656e-05 7.09213122674059e-05 -1.87819244477214e-05 -4.70921032884371e-06 -6.77249900649732e-06 -4.95066628243656e-05 0.000103862109538185 -3.52150250848339e-05 -6.81951225292915e-06 3.22188702124915e-05 1.96785219177631e-05 7.09213122674059e-05 -3.52150250848339e-05 0.000256168353399611 0 0 0 145 0 0 0 0 145 0 0 0 0 0 0 0 0 0 0 576 449 458 0 283 0 +293 434 -0.313374068586101 0.937646247086695 0.150386862664363 0.47043277178448 -0.942819502988054 -0.326132503895255 0.0687675409504455 -0.910197642842539 0.113525670767246 -0.120237703018845 0.98623263830072 0.537603212365985 5.91128644833691e-05 3.737644853957e-05 -1.74242267070982e-06 2.46404534311564e-06 -2.12817103409746e-05 9.90079360665727e-05 3.737644853957e-05 5.96566250195264e-05 3.06667862479923e-06 4.75519602541591e-06 -1.12733590266637e-05 8.08957715870236e-05 -1.74242267070982e-06 3.06667862479923e-06 1.69783329348946e-05 -2.5991649603108e-06 9.35812043467791e-07 -1.06511813421349e-05 2.46404534311564e-06 4.75519602541591e-06 -2.5991649603108e-06 2.61199039603986e-05 -1.56706362601328e-05 3.42309279806508e-05 -2.12817103409746e-05 -1.12733590266637e-05 9.35812043467791e-07 -1.56706362601328e-05 0.000173550469831857 -3.58386608914939e-05 9.90079360665727e-05 8.08957715870236e-05 -1.06511813421349e-05 3.42309279806508e-05 -3.58386608914939e-05 0.000426458333826913 0 0 0 1549 0 0 0 0 1554 0 0 0 0 0 0 0 0 0 0 97 855 855 0 243 0 +293 327 -0.586581454346646 0.774482981577377 0.23685081520567 0.679838922054926 -0.772105699860559 -0.623051106170926 0.125140350574951 -0.966937459915586 0.244489234240304 -0.109468855599214 0.963452948510921 0.0229472820868526 6.9240828680657e-05 1.05102506195648e-05 3.35256874871349e-06 2.51244582857698e-05 -4.37976072614614e-05 1.78801991254384e-05 1.05102506195648e-05 4.1104627356307e-05 1.78147389166056e-06 -1.94999029574325e-05 4.92876828776964e-05 2.06023936381328e-05 3.35256874871349e-06 1.78147389166056e-06 1.82585796327831e-05 -1.04375724661738e-05 1.72651953754023e-05 4.82580265536789e-06 2.51244582857698e-05 -1.94999029574325e-05 -1.04375724661738e-05 0.000205723294698394 -0.000337392686753612 -2.72635166144615e-05 -4.37976072614614e-05 4.92876828776964e-05 1.72651953754023e-05 -0.000337392686753612 0.000781001675726854 0.000198732549284662 1.78801991254384e-05 2.06023936381328e-05 4.82580265536789e-06 -2.72635166144615e-05 0.000198732549284662 0.000367756822425693 0 0 0 987 0 0 0 0 998 0 0 0 0 0 0 0 0 0 0 736 130 130 0 81 0 +293 297 0.974505914107365 0.207019949251228 0.0864925660492696 0.464157906799177 -0.209018320818119 0.977802350361828 0.0146254979149304 -0.181241935557568 -0.0815448645356785 -0.0323311651337332 0.996145135424027 -0.106308038095634 3.20743065380438e-05 6.78237518310838e-06 1.56524804294188e-06 -4.62368430617722e-06 -1.42151363049031e-06 -2.81796206492732e-06 6.78237518310838e-06 3.8264446232773e-05 -1.62725791690871e-06 -6.9665828974197e-06 -9.32225409869834e-07 8.07769737488244e-06 1.56524804294188e-06 -1.62725791690871e-06 1.491319074056e-05 5.28549693853636e-06 3.37861562166988e-06 7.98915212636517e-06 -4.62368430617722e-06 -6.9665828974197e-06 5.28549693853636e-06 6.62912799086709e-05 -8.17577194192838e-07 3.06095297460367e-06 -1.42151363049031e-06 -9.32225409869834e-07 3.37861562166988e-06 -8.17577194192838e-07 2.04860891378139e-05 -2.00644626860508e-06 -2.81796206492732e-06 8.07769737488244e-06 7.98915212636517e-06 3.06095297460367e-06 -2.00644626860508e-06 0.000104463180614595 2821 2764 0 1254 0 2832 2775 0 1138 0 0 0 0 0 0 0 0 0 2123 0 157 202 0 0 2724 +293 433 -0.424537084354064 0.901114871411051 0.0880922955200692 0.508492944040393 -0.902213076112158 -0.42920040703914 0.0424096202491188 -0.937471119988787 0.0760251885916021 -0.0614735643938189 0.99520910947415 0.610439488787103 5.11840682682512e-05 4.34794910648491e-05 1.19208468670319e-06 -1.5033763385537e-06 8.05550055603206e-06 9.04265948326062e-05 4.34794910648491e-05 8.79058018770774e-05 -4.32927974042969e-06 -2.96830444547647e-06 2.03002793137314e-05 0.000100674218463911 1.19208468670319e-06 -4.32927974042969e-06 2.24392556140206e-05 -7.29672483485826e-06 -6.21525059532241e-06 -8.40136603323309e-06 -1.5033763385537e-06 -2.96830444547647e-06 -7.29672483485826e-06 3.26107841152023e-05 -8.30688029297794e-06 2.38163207348083e-06 8.05550055603206e-06 2.03002793137314e-05 -6.21525059532241e-06 -8.30688029297794e-06 0.000124440118472553 2.76421726070179e-05 9.04265948326062e-05 0.000100674218463911 -8.40136603323309e-06 2.38163207348083e-06 2.76421726070179e-05 0.0004621148378341 0 0 0 1049 0 0 0 0 1084 0 0 0 0 0 0 0 0 0 0 198 711 711 0 231 0 +293 435 -0.235984221173914 0.966067535394069 0.104999830545437 0.525880188746214 -0.964208055903906 -0.246222095426155 0.0983743089122599 -0.914059367806342 0.12088950445325 -0.0780268978082734 0.989594629599143 0.407749187976823 3.86505902490903e-05 2.39037091109845e-05 4.59295642087809e-06 -2.92656819466524e-06 -1.20891604586168e-06 4.03244382303913e-05 2.39037091109845e-05 5.0063476597977e-05 3.27077667340286e-06 2.64391283419716e-06 -9.99785934458887e-06 5.45577615104829e-05 4.59295642087809e-06 3.27077667340286e-06 2.16501686793483e-05 -5.88944766075453e-06 -9.39583316339655e-06 -2.6662174979637e-06 -2.92656819466524e-06 2.64391283419716e-06 -5.88944766075453e-06 2.66747378783129e-05 -8.50550387471597e-06 1.36348078342887e-05 -1.20891604586168e-06 -9.99785934458887e-06 -9.39583316339655e-06 -8.50550387471597e-06 0.000372286123600107 -1.89535835472036e-05 4.03244382303913e-05 5.45577615104829e-05 -2.6662174979637e-06 1.36348078342887e-05 -1.89535835472036e-05 0.000230291928692773 0 0 0 1885 0 0 0 0 1892 0 0 0 0 0 0 0 0 0 0 37 860 860 0 216 0 +293 295 0.994675010935748 0.0946269796345512 0.0408332872202497 0.219873572250584 -0.0953178381957662 0.995329100304922 0.0153131253465549 -0.0960208309720892 -0.0391935242311138 -0.019123723785806 0.999048622864227 -0.0614117548374088 4.25166326423394e-05 2.84119196841157e-05 1.92376040735139e-07 5.40816644098741e-06 1.04514689523712e-06 3.20209591809611e-05 2.84119196841157e-05 6.49429956903046e-05 3.89843137822012e-06 9.17250651157014e-06 -1.32276293090759e-06 4.78783232906463e-05 1.92376040735139e-07 3.89843137822012e-06 1.95581026449349e-05 -7.0740607105395e-07 1.50917574844733e-06 8.46146207288273e-06 5.40816644098741e-06 9.17250651157014e-06 -7.0740607105395e-07 7.75440749568695e-05 2.59856084922672e-06 3.94853571320048e-05 1.04514689523712e-06 -1.32276293090759e-06 1.50917574844733e-06 2.59856084922672e-06 1.82146326216544e-05 -4.17533831483749e-06 3.20209591809611e-05 4.78783232906463e-05 8.46146207288273e-06 3.94853571320048e-05 -4.17533831483749e-06 0.000207832522480375 3201 3068 0 720 0 3213 3080 0 625 0 0 0 0 0 0 0 0 0 3062 0 101 129 0 0 3430 +293 432 -0.532083774762672 0.841985213139386 0.0891501962360649 0.500108843285301 -0.841575023943304 -0.537486600771521 0.0534755370791376 -0.943263248627667 0.0929426474183574 -0.0465731129053878 0.994581625330555 0.659762496424209 0.00011793532009275 6.84705253353469e-05 -5.22285113477647e-06 2.40179937223105e-06 -5.24484716641438e-05 0.000121486619523655 6.84705253353469e-05 0.000104419529366012 -5.65797166837316e-07 5.66944362989501e-06 -1.39308475005664e-05 0.000135417466784197 -5.22285113477647e-06 -5.65797166837316e-07 2.13933850730107e-05 -8.44397809600565e-06 2.28337913199753e-06 5.75996666484648e-06 2.40179937223105e-06 5.66944362989501e-06 -8.44397809600565e-06 3.18245116003438e-05 -1.27971391663782e-05 2.98827423509386e-05 -5.24484716641438e-05 -1.39308475005664e-05 2.28337913199753e-06 -1.27971391663782e-05 0.000110430770995359 -1.91733411106653e-05 0.000121486619523655 0.000135417466784197 5.75996666484648e-06 2.98827423509386e-05 -1.91733411106653e-05 0.00062351495916984 0 0 0 746 0 0 0 0 756 0 0 0 0 0 0 0 0 0 0 250 954 954 0 152 0 +293 431 -0.636786397628617 0.757555998377901 0.143568774867066 0.488258598267154 -0.757464650982997 -0.649421438896991 0.067075310004274 -0.959339685723452 0.144049943791643 -0.0660356269192938 0.9873646285294 0.714892158034005 7.90747548572889e-05 5.91315431153416e-05 8.2322354319165e-06 -7.11809766101868e-06 1.89988687958665e-06 0.000147107431486186 5.91315431153416e-05 9.67594160352508e-05 9.12242537489787e-06 4.05275452244995e-06 -1.07867464526351e-05 8.91645708571907e-05 8.2322354319165e-06 9.12242537489787e-06 2.20895047395012e-05 -6.94467493846104e-06 -8.81749057703208e-06 -5.82727060382194e-06 -7.11809766101868e-06 4.05275452244995e-06 -6.94467493846104e-06 3.82630168274516e-05 -1.65433007523136e-05 1.51938524344821e-06 1.89988687958665e-06 -1.07867464526351e-05 -8.81749057703208e-06 -1.65433007523136e-05 7.0955889296981e-05 2.42171513554994e-05 0.000147107431486186 8.91645708571907e-05 -5.82727060382194e-06 1.51938524344821e-06 2.42171513554994e-05 0.000593007528696407 0 0 0 409 0 0 0 0 422 0 0 0 0 0 0 0 0 0 0 257 895 895 0 149 0 +293 430 -0.731932088585442 0.657297820702134 0.179541061039466 0.494658719156813 -0.665096202112584 -0.746451976035237 0.0213656127575821 -0.965636078823265 0.148062350495897 -0.103773900251047 0.983518438054069 0.712364311616481 6.16900980881821e-05 2.8701191903476e-05 -5.3258127495955e-06 -5.82958911072557e-06 7.57153584869925e-07 -3.01410583031997e-05 2.8701191903476e-05 0.000117723574951427 1.49058222299385e-06 1.79425510524097e-05 -2.1618628800209e-05 -2.02017828812365e-05 -5.3258127495955e-06 1.49058222299385e-06 1.81599423567216e-05 -8.76436122510493e-06 -7.41119410623628e-06 2.38516683206777e-06 -5.82958911072557e-06 1.79425510524097e-05 -8.76436122510493e-06 4.30461420453731e-05 -1.01492928433669e-05 1.58312018998973e-05 7.57153584869925e-07 -2.1618628800209e-05 -7.41119410623628e-06 -1.01492928433669e-05 5.50498349382524e-05 3.79127122313006e-06 -3.01410583031997e-05 -2.02017828812365e-05 2.38516683206777e-06 1.58312018998973e-05 3.79127122313006e-06 0.000204148046241888 0 0 0 204 0 0 0 0 210 0 0 0 0 0 0 0 0 0 0 180 773 790 0 276 0 +293 336 -0.708718699847107 0.65782038919115 0.25493163799621 0.476350702951544 -0.644146482871207 -0.75074827175702 0.146466177182655 -0.989249855242447 0.287737924319474 -0.0604099993233875 0.955802029130546 0.673190157304118 7.82062782258923e-05 4.27522572799769e-05 7.00623086645678e-06 1.09456407834219e-06 1.87079979978142e-05 9.3842807514341e-05 4.27522572799769e-05 6.58074391658617e-05 -3.58615091948563e-07 9.39301753379292e-07 9.42762002080287e-06 6.30815723032961e-05 7.00623086645678e-06 -3.58615091948563e-07 2.72225762996563e-05 -7.78320878009177e-06 2.70330306325738e-07 1.45930904903981e-05 1.09456407834219e-06 9.39301753379292e-07 -7.78320878009177e-06 5.17354489004644e-05 -1.41932059211018e-05 2.0509050191456e-05 1.87079979978142e-05 9.42762002080287e-06 2.70330306325738e-07 -1.41932059211018e-05 8.17226276774657e-05 6.33949687296205e-05 9.3842807514341e-05 6.30815723032961e-05 1.45930904903981e-05 2.0509050191456e-05 6.33949687296205e-05 0.000420828282085059 0 0 0 232 0 0 0 0 240 0 0 0 0 0 0 0 0 0 0 513 553 562 0 255 0 +293 333 -0.73907029199352 0.640817372886595 0.207673296548533 0.523843272366377 -0.624153339361061 -0.767401130338906 0.146724620016565 -0.97345183895232 0.25339240804935 -0.0211801737786056 0.967131680683484 0.588205188040919 4.98020263191159e-05 3.683819690959e-05 1.08738193346755e-05 1.40278532542998e-05 -1.10607307779593e-05 3.30625166292564e-05 3.683819690959e-05 7.95516107310697e-05 1.96945863683247e-05 1.33214712824427e-05 -1.29664678037919e-05 5.61104063875647e-05 1.08738193346755e-05 1.96945863683247e-05 3.19723842434908e-05 -6.66426489208575e-06 -5.7172819018394e-06 1.93470742259834e-05 1.40278532542998e-05 1.33214712824427e-05 -6.66426489208575e-06 8.89268461266894e-05 -3.86804404047298e-05 6.38886928474742e-05 -1.10607307779593e-05 -1.29664678037919e-05 -5.7172819018394e-06 -3.86804404047298e-05 8.30688011375285e-05 -1.69309609239107e-05 3.30625166292564e-05 5.61104063875647e-05 1.93470742259834e-05 6.38886928474742e-05 -1.69309609239107e-05 0.000284713941086813 0 0 0 357 0 0 0 0 363 0 0 0 0 0 0 0 0 0 0 522 567 577 0 207 0 +294 297 0.985770018952363 0.158064808338504 0.0572100174756908 0.36594585656225 -0.159262104578638 0.987090255644016 0.0169826163418683 -0.113462699447963 -0.0537870967783145 -0.0258523418193434 0.998217714049704 -0.0742079707776814 4.10215479446277e-05 1.06692649942664e-05 -1.50638715105917e-06 -6.39439722821388e-06 9.32000201669075e-07 7.54171929722921e-06 1.06692649942664e-05 5.36643589851706e-05 2.06545694079296e-06 8.15497469540456e-07 -8.65953924009614e-07 2.90685805024842e-05 -1.50638715105917e-06 2.06545694079296e-06 1.60393734477336e-05 6.03376495686508e-06 3.69669478658982e-06 5.90459611279096e-06 -6.39439722821388e-06 8.15497469540456e-07 6.03376495686508e-06 5.66797437492046e-05 2.85960688264318e-07 2.0589069484777e-05 9.32000201669075e-07 -8.65953924009614e-07 3.69669478658982e-06 2.85960688264318e-07 1.79464595255788e-05 -5.68846108808158e-06 7.54171929722921e-06 2.90685805024842e-05 5.90459611279096e-06 2.0589069484777e-05 -5.68846108808158e-06 0.000184797500643161 3149 3092 0 755 0 3179 3122 0 660 0 0 0 0 0 0 0 0 0 2628 0 48 93 0 0 3182 +294 436 -0.129891293056261 0.984925461104315 0.114236982000683 0.469006344074774 -0.989206513802438 -0.136603999564941 0.0530077386207747 -0.83019044405415 0.067813900042685 -0.106118723000767 0.992038351874406 0.341620938924779 4.66470333561275e-05 1.62971722814991e-05 2.22854465870927e-06 -7.89119867725569e-07 -3.08139904665157e-05 2.55708131934375e-05 1.62971722814991e-05 5.38452576372438e-05 -3.00073018021251e-06 2.676548431858e-06 -4.9045313935233e-05 5.08435164026146e-05 2.22854465870927e-06 -3.00073018021251e-06 1.74491921846669e-05 -6.48077524824574e-06 -1.06413173332563e-07 -4.68307616315047e-06 -7.89119867725569e-07 2.676548431858e-06 -6.48077524824574e-06 2.506219837648e-05 1.06664715388934e-06 9.73683921323648e-06 -3.08139904665157e-05 -4.9045313935233e-05 -1.06413173332563e-07 1.06664715388934e-06 0.000369169681602937 -0.000109765522258657 2.55708131934375e-05 5.08435164026146e-05 -4.68307616315047e-06 9.73683921323648e-06 -0.000109765522258657 0.000234307295164761 0 0 0 2068 0 0 0 0 2092 0 0 0 0 0 0 0 0 0 0 0 887 887 0 154 0 +294 296 0.993784858696266 0.0952768881418186 0.0575670844498259 0.229812324663093 -0.0963132135594553 0.995230419015702 0.0154976759444863 -0.0795052524875909 -0.0558159432410916 -0.0209458265972231 0.998221344606629 -0.0356663079650586 2.12442039762089e-05 2.17859043254294e-07 1.89387764756498e-06 -3.62223822373641e-07 5.18287023061113e-07 4.77600929195448e-06 2.17859043254294e-07 2.49187704430412e-05 7.81755930188653e-07 2.03455286289273e-06 -1.94924863002012e-06 9.84879974656024e-06 1.89387764756498e-06 7.81755930188653e-07 1.23654739774001e-05 1.31426007161067e-06 -2.68551529482612e-06 4.15795184027956e-07 -3.62223822373641e-07 2.03455286289273e-06 1.31426007161067e-06 7.29976351539789e-05 -6.94363588469697e-07 1.61070321531122e-05 5.18287023061113e-07 -1.94924863002012e-06 -2.68551529482612e-06 -6.94363588469697e-07 1.96928828067444e-05 -9.13579019470058e-06 4.77600929195448e-06 9.84879974656024e-06 4.15795184027956e-07 1.61070321531122e-05 -9.13579019470058e-06 9.50066478261303e-05 3395 3248 0 592 0 3421 3275 0 515 0 0 0 0 0 0 0 0 0 3100 0 47 82 0 0 3478 +294 435 -0.190292660704747 0.978771752724127 0.0761220030690808 0.413785749952135 -0.976707167935727 -0.19658109007836 0.086017342010645 -0.84536963881111 0.0991554909466979 -0.0579804371572408 0.99338132533392 0.431794224224051 0.000129016827479047 3.61617026234297e-05 -5.3603129424357e-06 -1.13637502504017e-05 -7.4011207704358e-05 6.42994079880805e-05 3.61617026234297e-05 6.67378198520564e-05 8.02908895770572e-06 1.01080567546284e-05 -3.07866967628552e-05 9.61075127421796e-05 -5.3603129424357e-06 8.02908895770572e-06 1.98482331007951e-05 -2.38266419429376e-06 6.13328082008844e-06 6.14881027509558e-06 -1.13637502504017e-05 1.01080567546284e-05 -2.38266419429376e-06 3.5679877927453e-05 -1.28854746284516e-05 3.82928463503073e-05 -7.4011207704358e-05 -3.07866967628552e-05 6.13328082008844e-06 -1.28854746284516e-05 0.000227696475999133 -7.31603888774e-05 6.42994079880805e-05 9.61075127421796e-05 6.14881027509558e-06 3.82928463503073e-05 -7.31603888774e-05 0.00040507636768126 0 0 0 1767 0 0 0 0 1790 0 0 0 0 0 0 0 0 0 0 19 501 501 0 171 0 +294 434 -0.267372339391259 0.954882826146465 0.129270338666632 0.413205795972787 -0.958547612863859 -0.277278849828592 0.0655965952678261 -0.851114973903624 0.0984809930973639 -0.106373059410142 0.989437348309777 0.565290895371131 5.98935392847768e-05 4.30844478941349e-05 6.08681953365102e-06 1.33346237702142e-06 -4.34165025026111e-05 6.99100752012426e-05 4.30844478941349e-05 0.000112431961451213 1.20900144158326e-05 2.11028337631341e-05 -6.03184175516491e-05 0.000164676690016457 6.08681953365102e-06 1.20900144158326e-05 1.75091659048882e-05 4.61743462969227e-07 -3.59266464425749e-06 1.76542882857371e-05 1.33346237702142e-06 2.11028337631341e-05 4.61743462969227e-07 3.13181709656902e-05 -2.7344476971209e-05 6.83713010444708e-05 -4.34165025026111e-05 -6.03184175516491e-05 -3.59266464425749e-06 -2.7344476971209e-05 0.0002399810518108 -0.000183448797207353 6.99100752012426e-05 0.000164676690016457 1.76542882857371e-05 6.83713010444708e-05 -0.000183448797207353 0.000614490987330691 0 0 0 1486 0 0 0 0 1509 0 0 0 0 0 0 0 0 0 0 69 965 965 0 148 0 +294 433 -0.379694880112921 0.923095761729066 0.061041073826312 0.427790803852432 -0.92316128462021 -0.38235106214619 0.039760631962341 -0.870443877733609 0.0600419902601406 -0.0412538477419402 0.997343009927921 0.64021435663613 4.9267407786913e-05 3.22281934047243e-05 4.98541534242922e-06 1.23685778201332e-07 -2.14558871360242e-05 3.9598248845634e-05 3.22281934047243e-05 8.89059740399934e-05 2.64201311384714e-06 1.71691849974711e-05 -4.9976787549962e-05 7.14316201804317e-05 4.98541534242922e-06 2.64201311384714e-06 2.15013203580976e-05 -4.85425310183476e-06 -8.65997856085e-06 1.67821414969244e-05 1.23685778201332e-07 1.71691849974711e-05 -4.85425310183476e-06 4.10969429529239e-05 -2.86025582089041e-05 3.58085510358477e-05 -2.14558871360242e-05 -4.9976787549962e-05 -8.65997856085e-06 -2.86025582089041e-05 0.000182914499575509 -0.000117444384022082 3.9598248845634e-05 7.14316201804317e-05 1.67821414969244e-05 3.58085510358477e-05 -0.000117444384022082 0.000396782533562405 0 0 0 924 0 0 0 0 939 0 0 0 0 0 0 0 0 0 0 177 1165 1165 0 93 0 +294 431 -0.599994379210609 0.790599936124913 0.122304889170304 0.409882879079007 -0.791198138744843 -0.609035522652402 0.0555088947305902 -0.901576471722384 0.118373350727149 -0.0634623758363915 0.990939088284859 0.737109896850679 9.36421135697935e-05 6.22149639485506e-05 -2.7945845927603e-06 -7.28859610920041e-06 -2.48407808531299e-05 8.53439196191459e-06 6.22149639485506e-05 9.80200411243123e-05 -3.24900085552434e-06 4.2937525570301e-06 -2.33479964109965e-05 1.39600769285135e-05 -2.7945845927603e-06 -3.24900085552434e-06 2.01675692151376e-05 -9.49925074550179e-06 -5.79400647903487e-06 3.23435534658642e-06 -7.28859610920041e-06 4.2937525570301e-06 -9.49925074550179e-06 3.55074753859092e-05 -8.66837368067364e-06 3.61009148784655e-05 -2.48407808531299e-05 -2.33479964109965e-05 -5.79400647903487e-06 -8.66837368067364e-06 7.44089674040611e-05 -1.45300958450128e-05 8.53439196191459e-06 1.39600769285135e-05 3.23435534658642e-06 3.61009148784655e-05 -1.45300958450128e-05 0.00043238448363266 0 0 0 428 0 0 0 0 442 0 0 0 0 0 0 0 0 0 0 215 635 635 0 77 0 +294 335 -0.695351824431941 0.682121955479253 0.226264177704584 0.413877970949217 -0.666831060365771 -0.729789291287934 0.150810898985836 -0.925079001408814 0.267996599214678 -0.046013347787515 0.962320422018962 0.699006984535388 6.55688599125587e-05 2.31592844013953e-05 -2.37257570076123e-06 1.4094489995173e-05 -1.3322741201373e-05 -6.17241461654938e-06 2.31592844013953e-05 6.27690715835171e-05 -2.04675445055458e-06 1.22433672637221e-05 -1.45645874746841e-05 -5.71325564551851e-06 -2.37257570076123e-06 -2.04675445055458e-06 2.55130248524807e-05 -6.88158727472474e-06 -6.15418547520521e-06 1.08574481645721e-05 1.4094489995173e-05 1.22433672637221e-05 -6.88158727472474e-06 6.45015746009565e-05 -2.03425539298641e-05 2.58500449855438e-05 -1.3322741201373e-05 -1.45645874746841e-05 -6.15418547520521e-06 -2.03425539298641e-05 7.18454451284568e-05 -1.60663280675209e-06 -6.17241461654938e-06 -5.71325564551851e-06 1.08574481645721e-05 2.58500449855438e-05 -1.60663280675209e-06 0.000127973599318209 0 0 0 253 0 0 0 0 266 0 0 0 0 0 0 0 0 0 0 453 475 484 0 134 0 +294 432 -0.491276211031749 0.86821049183278 0.0697009780833229 0.4462780067397 -0.868541006214884 -0.494329591769688 0.0357039945111318 -0.890218606050875 0.0654538386767816 -0.0429976344965237 0.996928783028245 0.691506783902893 0.00015997196353739 2.52856153542634e-06 -1.35737238440775e-05 -2.15309645904286e-05 1.92280889273942e-06 -1.93860273017829e-05 2.52856153542634e-06 7.75369135344275e-05 6.18172918055597e-06 1.42651006693562e-06 5.48967072600175e-06 2.11714146353531e-05 -1.35737238440775e-05 6.18172918055597e-06 2.03427765086694e-05 -3.15247606535604e-06 -5.04541093865047e-06 2.69110865209351e-06 -2.15309645904286e-05 1.42651006693562e-06 -3.15247606535604e-06 5.067175121582e-05 -5.2303583947839e-05 2.17672869092621e-05 1.92280889273942e-06 5.48967072600175e-06 -5.04541093865047e-06 -5.2303583947839e-05 0.000185408011217382 -1.13295595448672e-06 -1.93860273017829e-05 2.11714146353531e-05 2.69110865209351e-06 2.17672869092621e-05 -1.13295595448672e-06 0.000269631021370303 0 0 0 697 0 0 0 0 712 0 0 0 0 0 0 0 0 0 0 205 813 813 0 64 0 +294 333 -0.71033091441833 0.678437753238851 0.187489218361589 0.446485405152473 -0.663166738990138 -0.734342618211839 0.144743895812459 -0.908361500953489 0.235881046968184 -0.0215205496677296 0.97154361591397 0.633794950437589 8.6324559456245e-05 2.80620859621865e-05 -9.01666597149494e-06 1.24858618471599e-05 -2.22345460251606e-05 2.1328579025983e-05 2.80620859621865e-05 7.36420025926588e-05 -5.19376204793056e-07 3.1035668934287e-05 -3.13393705069226e-05 2.89050164800835e-05 -9.01666597149494e-06 -5.19376204793056e-07 3.00993811731514e-05 -1.30706363766812e-05 -3.32827596886382e-06 -1.22737022502549e-06 1.24858618471599e-05 3.1035668934287e-05 -1.30706363766812e-05 9.16207975004728e-05 -4.53723552565186e-05 4.89957753692314e-05 -2.22345460251606e-05 -3.13393705069226e-05 -3.32827596886382e-06 -4.53723552565186e-05 0.000103017674732873 -2.64657851205175e-05 2.1328579025983e-05 2.89050164800835e-05 -1.22737022502549e-06 4.89957753692314e-05 -2.64657851205175e-05 0.000206471928158517 0 0 0 362 0 0 0 0 378 0 0 0 0 0 0 0 0 0 0 416 581 597 0 132 0 +294 336 -0.677919466302814 0.695638153509055 0.237724118654841 0.433715689692426 -0.682670489390497 -0.715686035532237 0.147494072624933 -0.93301305679664 0.272738336364817 -0.0622981374253022 0.960069133943119 0.714399926964252 5.0485328221145e-05 9.88250676070498e-06 1.52932200249094e-06 -9.13315777925552e-06 -2.63195427097677e-06 -1.35354542613864e-05 9.88250676070498e-06 9.3160286534928e-05 -2.69356268232722e-06 -1.59339790209852e-07 2.95878425429397e-06 -2.81911203807525e-05 1.52932200249094e-06 -2.69356268232722e-06 2.34203913896737e-05 -7.44859470515892e-06 -5.75645113447454e-06 1.03482056392669e-05 -9.13315777925552e-06 -1.59339790209852e-07 -7.44859470515892e-06 4.86300117356757e-05 -5.98647439643704e-06 2.51250906790058e-05 -2.63195427097677e-06 2.95878425429397e-06 -5.75645113447454e-06 -5.98647439643704e-06 5.97421437887571e-05 5.48753037393554e-06 -1.35354542613864e-05 -2.81911203807525e-05 1.03482056392669e-05 2.51250906790058e-05 5.48753037393554e-06 0.000129760011102063 0 0 0 252 0 0 0 0 271 0 0 0 0 0 0 0 0 0 0 452 506 518 0 131 0 +294 337 -0.658252017392503 0.714683641993288 0.236498569691044 0.431089006166618 -0.701137090482417 -0.696412662079872 0.153023476776204 -0.934815532813434 0.274063974189515 -0.0650899067600807 0.95950624911431 0.714102129722027 0.000256017717539116 -4.73892217100842e-05 -2.87687776775117e-05 -6.67950106709952e-05 1.36764857267516e-05 -3.20660790681318e-05 -4.73892217100842e-05 0.000126458017749275 2.85593845397936e-05 3.81899563140823e-05 -1.92928004189191e-05 1.4624692497063e-05 -2.87687776775117e-05 2.85593845397936e-05 5.18934785322064e-05 1.13842633032246e-05 -1.25628774213814e-05 7.9538212997779e-07 -6.67950106709952e-05 3.81899563140823e-05 1.13842633032246e-05 0.000147624443226986 -8.71210074892719e-05 0.000104378790087973 1.36764857267516e-05 -1.92928004189191e-05 -1.25628774213814e-05 -8.71210074892719e-05 0.000168888859528251 -1.49957800688334e-05 -3.20660790681318e-05 1.4624692497063e-05 7.9538212997779e-07 0.000104378790087973 -1.49957800688334e-05 0.0004752811396781 0 0 0 253 0 0 0 0 272 0 0 0 0 0 0 0 0 0 0 403 320 328 0 117 0 +295 441 0.361252278188492 0.918780774784422 0.159181278390899 0.61338635756584 -0.932460164874047 0.355241491375948 0.0657382972707474 -0.620519241556548 0.00385128896471285 -0.17217831074653 0.985058270805226 -0.0812997942567185 4.50459411959313e-05 -5.84687165367069e-07 3.39799916053501e-06 2.2601864432465e-06 1.09355864007906e-05 3.36785138296055e-06 -5.84687165367069e-07 5.32467477376283e-05 -2.99779146025106e-07 5.17250423757373e-08 1.11939286112468e-06 -8.81437525426558e-06 3.39799916053501e-06 -2.99779146025106e-07 1.58987849835315e-05 -5.07722418995984e-07 2.13357674275768e-06 -1.2905055249819e-06 2.2601864432465e-06 5.17250423757373e-08 -5.07722418995984e-07 3.23201650276688e-05 -2.55949756025048e-06 1.0188474495362e-05 1.09355864007906e-05 1.11939286112468e-06 2.13357674275768e-06 -2.55949756025048e-06 5.0067352773959e-05 2.44115495793646e-05 3.36785138296055e-06 -8.81437525426558e-06 -1.2905055249819e-06 1.0188474495362e-05 2.44115495793646e-05 0.000157492328397635 790 744 0 2351 0 835 789 0 2351 0 0 0 0 0 0 0 0 0 0 0 12 12 0 0 228 +295 435 -0.147712644842511 0.987652988542588 0.0521780487995219 0.346382223970123 -0.98466172613491 -0.151808517456707 0.0859968552484079 -0.793473744402024 0.0928561233233935 -0.0386749046604079 0.994928134143798 0.476826903867424 2.87726850871086e-05 6.9063765503995e-06 1.69216954565443e-06 -4.11695294031355e-06 6.65627062466514e-06 7.16682498905758e-06 6.9063765503995e-06 3.90834999996459e-05 5.51416605716277e-06 3.94621837217324e-06 1.22591764615462e-05 6.22095522843398e-06 1.69216954565443e-06 5.51416605716277e-06 1.96451221074439e-05 -1.99666241642708e-06 3.1576953425709e-06 -2.36253637814804e-06 -4.11695294031355e-06 3.94621837217324e-06 -1.99666241642708e-06 3.91649133038023e-05 5.34326746477472e-06 4.72229275517208e-06 6.65627062466514e-06 1.22591764615462e-05 3.1576953425709e-06 5.34326746477472e-06 0.000331095085205378 1.37998683927151e-05 7.16682498905758e-06 6.22095522843398e-06 -2.36253637814804e-06 4.72229275517208e-06 1.37998683927151e-05 0.000112433768291463 0 0 0 1778 0 0 0 0 1802 0 0 0 0 0 0 0 0 0 0 0 830 830 0 113 0 +295 297 0.993126884554853 0.114934058017612 0.0221168144626505 0.254032856369268 -0.115221836096205 0.993264794044452 0.0122056297851079 -0.0594833333468228 -0.0205650106003008 -0.0146700790534998 0.999680883642162 -0.0624517327792923 5.60323735604901e-05 1.07291899708818e-05 1.42586721529684e-06 -4.56576977095733e-06 -7.43626707172418e-07 1.31516833595003e-05 1.07291899708818e-05 6.10905814629495e-05 -5.19067959560895e-07 -4.65756779337315e-06 -3.62260964536579e-06 2.25302683665787e-05 1.42586721529684e-06 -5.19067959560895e-07 1.69824819298613e-05 8.0190393564241e-06 2.2822396456037e-06 4.92845446683402e-06 -4.56576977095733e-06 -4.65756779337315e-06 8.0190393564241e-06 7.73649765780824e-05 -2.10941164110604e-06 1.45920528140726e-05 -7.43626707172418e-07 -3.62260964536579e-06 2.2822396456037e-06 -2.10941164110604e-06 1.68053020555276e-05 -4.31161678060114e-06 1.31516833595003e-05 2.25302683665787e-05 4.92845446683402e-06 1.45920528140726e-05 -4.31161678060114e-06 0.000192724323804973 3253 3190 0 464 0 3285 3227 0 367 0 0 0 0 0 0 0 0 0 2950 0 3 43 0 0 2676 +295 434 -0.227243653168135 0.96749960017436 0.110927209273715 0.337444547407356 -0.970700204581926 -0.234173710893434 0.0538867882788023 -0.808458295987041 0.0781116823491 -0.0954316341097244 0.992366549361546 0.61000540478123 4.49010894759095e-05 2.53555606106133e-05 4.34182737742061e-06 -5.9374954995238e-06 -1.22392707283861e-05 1.77853418333485e-05 2.53555606106133e-05 5.61781969138914e-05 2.97223561749492e-06 2.90696701293224e-06 -2.0008870178494e-05 1.33777128997021e-05 4.34182737742061e-06 2.97223561749492e-06 1.57509119421363e-05 -3.32209668295178e-06 -3.03128977064724e-06 -8.11572282700205e-07 -5.9374954995238e-06 2.90696701293224e-06 -3.32209668295178e-06 3.12542716839178e-05 -2.0659658053982e-05 1.43572126443113e-05 -1.22392707283861e-05 -2.0008870178494e-05 -3.03128977064724e-06 -2.0659658053982e-05 0.000216232389370966 -5.00129617918278e-05 1.77853418333485e-05 1.33777128997021e-05 -8.11572282700205e-07 1.43572126443113e-05 -5.00129617918278e-05 0.000179647040960633 0 0 0 1339 0 0 0 0 1364 0 0 0 0 0 0 0 0 0 0 23 619 619 0 105 0 +295 433 -0.338133187817046 0.940191006111024 0.0413136699486073 0.340567961957572 -0.940169609173075 -0.33942361179455 0.0295417965548864 -0.822232472462678 0.04179776649571 -0.0288527950861412 0.998709398639908 0.682443234818929 7.28745191802799e-05 3.86806869041108e-05 1.39633458549807e-05 -1.89844665657249e-05 2.97382011864566e-05 4.92977328533706e-05 3.86806869041108e-05 0.000100742712168402 7.34551316088045e-06 -8.60946946001925e-06 9.73788612070332e-06 6.79595393517982e-05 1.39633458549807e-05 7.34551316088045e-06 2.56760186590454e-05 -6.3998636478742e-06 3.69452821518092e-06 1.80091345199009e-05 -1.89844665657249e-05 -8.60946946001925e-06 -6.3998636478742e-06 5.07592695174761e-05 -3.86478523098175e-05 -3.0423387384806e-05 2.97382011864566e-05 9.73788612070332e-06 3.69452821518092e-06 -3.86478523098175e-05 0.000243628217343034 9.42389688527363e-05 4.92977328533706e-05 6.79595393517982e-05 1.80091345199009e-05 -3.0423387384806e-05 9.42389688527363e-05 0.000361899442032262 0 0 0 904 0 0 0 0 923 0 0 0 0 0 0 0 0 0 0 120 439 439 0 66 0 +295 327 -0.5193531115242 0.834595068090115 0.183639369062814 0.530812234084393 -0.827888142362408 -0.54465812836627 0.133972933610762 -0.826790871345432 0.211833824697221 -0.0824535961872431 0.973821254229922 0.123546083803232 6.84154347516258e-05 -6.58412801909575e-06 -2.8566861020747e-07 -1.34034384492746e-05 2.06647947692892e-05 1.28287580781175e-05 -6.58412801909575e-06 5.4534933288306e-05 -9.18417237148987e-08 -2.53487555818513e-05 4.68977272363232e-05 2.28044750173356e-05 -2.8566861020747e-07 -9.18417237148987e-08 1.77538479443981e-05 5.2487922265706e-06 -6.7985522528824e-06 -7.05679551885045e-06 -1.34034384492746e-05 -2.53487555818513e-05 5.2487922265706e-06 0.000206886287059923 -0.000354743817391312 -0.000134741770779967 2.06647947692892e-05 4.68977272363232e-05 -6.7985522528824e-06 -0.000354743817391312 0.000827731103546007 0.000296183318406657 1.28287580781175e-05 2.28044750173356e-05 -7.05679551885045e-06 -0.000134741770779967 0.000296183318406657 0.000299316348660567 0 0 0 1033 0 0 0 0 1033 0 0 0 0 0 0 0 0 0 0 546 227 227 0 0 0 +295 333 -0.686038750240789 0.711118676302022 0.153821524444779 0.353432830064462 -0.696424909279417 -0.703023001837177 0.144052089964012 -0.857592490086117 0.210578201396088 -0.00829982543819256 0.97754178120144 0.663268526605379 5.03595042224834e-05 3.10585819117135e-05 9.27349333893828e-06 6.84502170507884e-06 -3.57710528988633e-06 1.83037784762739e-05 3.10585819117135e-05 9.28268390013744e-05 1.00076238014753e-05 1.13534675733764e-05 2.04790498520964e-06 6.88798805022043e-05 9.27349333893828e-06 1.00076238014753e-05 3.10160791468604e-05 -3.34291723800074e-06 -1.11636368998001e-05 1.16453121384075e-05 6.84502170507884e-06 1.13534675733764e-05 -3.34291723800074e-06 7.46815513158398e-05 -3.32705122193283e-05 3.9106594308315e-05 -3.57710528988633e-06 2.04790498520964e-06 -1.11636368998001e-05 -3.32705122193283e-05 8.99550541432768e-05 2.45517671740437e-05 1.83037784762739e-05 6.88798805022043e-05 1.16453121384075e-05 3.9106594308315e-05 2.45517671740437e-05 0.000320060919410799 0 0 0 358 0 0 0 0 378 0 0 0 0 0 0 0 0 0 0 338 485 496 0 86 0 +295 431 -0.566942662935054 0.817524539026732 0.101141707684011 0.319569025384065 -0.817440690987701 -0.573514478375831 0.0535897360587779 -0.852353887072078 0.101817157992453 -0.0522950397497439 0.993427649683616 0.788640076705919 4.44566815956604e-05 4.54650456880388e-05 9.65596510262416e-06 -2.71254496454935e-06 -1.00499656216683e-05 2.10765725331134e-05 4.54650456880388e-05 0.000127905837847581 1.16425694029632e-05 1.04007931511521e-05 -2.92043759975734e-05 -1.69242245829859e-05 9.65596510262416e-06 1.16425694029632e-05 2.15151953681179e-05 -1.04642337600306e-05 -1.27292063066682e-05 -8.11255746271586e-06 -2.71254496454935e-06 1.04007931511521e-05 -1.04642337600306e-05 8.17896177197658e-05 -8.61930095818303e-05 2.67667571805673e-05 -1.00499656216683e-05 -2.92043759975734e-05 -1.27292063066682e-05 -8.61930095818303e-05 0.000239352215952077 -2.05880230737472e-05 2.10765725331134e-05 -1.69242245829859e-05 -8.11255746271586e-06 2.67667571805673e-05 -2.05880230737472e-05 0.000217704122479296 0 0 0 452 0 0 0 0 466 0 0 0 0 0 0 0 0 0 0 126 776 776 0 52 0 +295 334 -0.680375880691556 0.711156257089653 0.177046431693568 0.344617003465143 -0.694787786606289 -0.702777446220726 0.152884900059518 -0.865154091017077 0.23314929241995 -0.0189904998804807 0.972255505697122 0.704488420807181 3.10436696636726e-05 2.15406572729481e-05 1.95011971520194e-06 6.17800072667737e-06 -8.87207760172067e-07 -7.04427422218179e-06 2.15406572729481e-05 5.74896059962425e-05 -2.84777243422909e-07 1.19052131479545e-05 -1.10993008069028e-05 -1.87628117353084e-05 1.95011971520194e-06 -2.84777243422909e-07 2.15056535618442e-05 -8.75039733609021e-06 -4.31940407295855e-06 3.04705819360552e-06 6.17800072667737e-06 1.19052131479545e-05 -8.75039733609021e-06 7.88762735190469e-05 -5.00719859832421e-05 5.96452940617798e-06 -8.87207760172067e-07 -1.10993008069028e-05 -4.31940407295855e-06 -5.00719859832421e-05 0.000111053745767859 -4.39186018218991e-06 -7.04427422218179e-06 -1.87628117353084e-05 3.04705819360552e-06 5.96452940617798e-06 -4.39186018218991e-06 8.74373059862962e-05 0 0 0 291 0 0 0 0 317 0 0 0 0 0 0 0 0 0 0 386 630 638 0 84 0 +296 298 0.994161201697643 0.10721833266754 0.0121545949785046 0.27377670395492 -0.106883761632944 0.993945438001247 -0.0254622814315743 -0.0389231541929289 -0.0148110275906426 0.02401448347355 0.999601889776729 -0.0261034946445121 2.51792630100784e-05 6.83340065313424e-06 6.53784970948593e-06 2.52685060687164e-06 1.69681655697316e-06 4.17560448157862e-06 6.83340065313424e-06 4.37719162870393e-05 -3.29297727060914e-07 6.59553980162393e-07 5.13335672828128e-07 -1.0652292904514e-05 6.53784970948593e-06 -3.29297727060914e-07 1.15631855401836e-05 2.88102747684458e-06 2.70200459205857e-06 8.51848602500388e-07 2.52685060687164e-06 6.59553980162393e-07 2.88102747684458e-06 6.20194943904368e-05 1.64646938238957e-06 3.77830961996721e-06 1.69681655697316e-06 5.13335672828128e-07 2.70200459205857e-06 1.64646938238957e-06 1.59140173975285e-05 6.45151177612256e-07 4.17560448157862e-06 -1.0652292904514e-05 8.51848602500388e-07 3.77830961996721e-06 6.45151177612256e-07 9.55036086814954e-05 3410 3411 0 463 0 3410 3420 0 462 24 0 0 0 0 0 0 0 0 2594 0 0 0 0 0 3250 +296 440 0.284237872157838 0.945944793472427 0.156196285914844 0.46222244566995 -0.95868816359778 0.278515077899815 0.057847699694772 -0.602650107183874 0.0112177096013914 -0.166186037574964 0.98603061002508 0.0610088898172888 3.66063500575794e-05 7.28184054825614e-06 4.81048326609316e-06 7.19429591374389e-07 -5.69034323179494e-06 -9.05428310870897e-06 7.28184054825614e-06 4.05056352954582e-05 2.33105207661225e-06 -7.48231038819991e-06 -8.84623343950631e-06 -8.25551920057641e-06 4.81048326609316e-06 2.33105207661225e-06 1.44951553478353e-05 -3.7437781950065e-06 3.32438563082449e-06 -1.5409797370752e-06 7.19429591374389e-07 -7.48231038819991e-06 -3.7437781950065e-06 2.67093832907277e-05 -2.31437586807452e-06 -8.73489381324124e-06 -5.69034323179494e-06 -8.84623343950631e-06 3.32438563082449e-06 -2.31437586807452e-06 6.34867749521072e-05 -2.14089478420506e-05 -9.05428310870897e-06 -8.25551920057641e-06 -1.5409797370752e-06 -8.73489381324124e-06 -2.14089478420506e-05 9.63623491930388e-05 297 177 0 2381 0 353 233 0 2381 0 0 0 0 0 0 0 0 0 0 0 160 126 0 0 210 +296 437 -0.00342504767486028 0.993953496798677 0.109748417984531 0.311634863081321 -0.999957246806724 -0.00434688988334706 0.00816144025641263 -0.707464042592644 0.00858915636962512 -0.109715772567231 0.993925890417809 0.293479527066621 3.17157868397517e-05 8.70837396371749e-06 5.38266927354488e-06 -2.5547008929279e-06 1.12613062174231e-05 1.27351237546874e-05 8.70837396371749e-06 4.08362828002854e-05 4.52067425753522e-06 -1.90896995529238e-07 -1.00599305871943e-05 1.98629173954487e-05 5.38266927354488e-06 4.52067425753522e-06 1.52472486738012e-05 -3.47099683387315e-06 7.59480565855537e-07 -1.97014611958119e-06 -2.5547008929279e-06 -1.90896995529238e-07 -3.47099683387315e-06 2.58553316940023e-05 2.08477494195422e-05 1.90007360936045e-07 1.12613062174231e-05 -1.00599305871943e-05 7.59480565855537e-07 2.08477494195422e-05 0.000319666267534754 -1.27198221579758e-05 1.27351237546874e-05 1.98629173954487e-05 -1.97014611958119e-06 1.90007360936045e-07 -1.27198221579758e-05 0.000128493025212385 0 0 0 2321 0 0 0 0 2357 0 0 0 0 0 0 0 0 0 0 0 746 746 0 106 5 +296 438 0.0681393216777189 0.988952757461472 0.131641468962675 0.365925218715487 -0.997671821548331 0.0671699259807482 0.0117956573439168 -0.672288281880414 0.00282300013011729 -0.132138732221448 0.991227212155303 0.195534203305142 3.73008874481508e-05 1.26050782659575e-05 3.42619750227442e-06 -2.79172980847824e-06 -4.82647352871325e-05 2.32863519281269e-05 1.26050782659575e-05 3.94418377561009e-05 2.23964880789613e-06 -4.87740163593902e-06 -4.41066280985988e-05 1.87594850712718e-05 3.42619750227442e-06 2.23964880789613e-06 1.44189085003573e-05 -3.77657996837647e-06 5.40929577424677e-06 -7.90554652344953e-07 -2.79172980847824e-06 -4.87740163593902e-06 -3.77657996837647e-06 2.43314574673235e-05 5.15782708290165e-05 -2.30936895091481e-05 -4.82647352871325e-05 -4.41066280985988e-05 5.40929577424677e-06 5.15782708290165e-05 0.000530962711043064 -0.000219259838769873 2.32863519281269e-05 1.87594850712718e-05 -7.90554652344953e-07 -2.30936895091481e-05 -0.000219259838769873 0.000236253435896839 0 0 0 2424 0 0 0 0 2434 0 0 0 0 0 0 0 0 0 0 0 851 837 0 9 26 +296 442 0.516800089541902 0.847680325292068 0.119815414543437 0.622579850212533 -0.855647045009023 0.516021981374368 0.0398678956780954 -0.519673235514731 -0.0280321568347776 -0.12312343745691 0.991995371628308 -0.07957459483027 5.81375933777964e-05 3.86453025456633e-05 1.5488127049436e-05 -2.06706628557861e-05 -4.72649894931784e-05 6.62014641071626e-05 3.86453025456633e-05 6.91548136342094e-05 1.09046297801479e-05 -1.98283970973421e-05 -4.09794501888865e-05 1.9361089324308e-05 1.5488127049436e-05 1.09046297801479e-05 2.00688659923041e-05 -2.1919489340406e-06 -7.52102102123713e-06 4.55683533367605e-06 -2.06706628557861e-05 -1.98283970973421e-05 -2.1919489340406e-06 5.65068127404316e-05 4.38904606751024e-05 -7.43270729012106e-05 -4.72649894931784e-05 -4.09794501888865e-05 -7.52102102123713e-06 4.38904606751024e-05 0.000144216162359643 -0.000189584989792185 6.62014641071626e-05 1.9361089324308e-05 4.55683533367605e-06 -7.43270729012106e-05 -0.000189584989792185 0.000459192468401848 1307 1317 0 2607 0 1307 1317 0 2607 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 151 +296 436 -0.0363520369486348 0.997664454511999 0.0578287611224787 0.287892793793653 -0.998522729437633 -0.0385999389717233 0.0382413847526232 -0.735728280882299 0.0403842569091473 -0.0563531801645201 0.997593820589944 0.38688922203363 5.71435834628018e-05 4.31884856054629e-05 8.69836852399907e-06 6.25538498419179e-06 -3.08779497710708e-05 0.000108568546665935 4.31884856054629e-05 8.2327472332968e-05 7.25874538544884e-06 3.22236175550594e-06 -2.29938575704707e-05 0.000112497771209909 8.69836852399907e-06 7.25874538544884e-06 1.7690840465498e-05 -3.57563727113506e-06 -6.76297815943263e-06 1.6901277880998e-05 6.25538498419179e-06 3.22236175550594e-06 -3.57563727113506e-06 3.31227213260003e-05 4.58315581064984e-06 2.79521132222104e-05 -3.08779497710708e-05 -2.29938575704707e-05 -6.76297815943263e-06 4.58315581064984e-06 0.000260199730572797 -0.000103475341763037 0.000108568546665935 0.000112497771209909 1.6901277880998e-05 2.79521132222104e-05 -0.000103475341763037 0.000468635858923527 0 0 0 1870 0 0 0 0 1902 0 0 0 0 0 0 0 0 0 0 0 937 925 0 85 14 +296 434 -0.176357403424004 0.981016703586397 0.0806492005045502 0.223805405053249 -0.982143204738319 -0.180828361147732 0.0519213750874352 -0.767123737312975 0.0655193989890612 -0.0700523453504983 0.995389309399597 0.632338637355512 4.92745732547812e-05 1.88487548195332e-05 1.61465561887755e-06 -3.29469757633185e-06 -5.53047864003327e-05 2.45303881192831e-05 1.88487548195332e-05 6.4420988374433e-05 6.50763404763925e-06 -1.77208283991848e-06 -2.98954174204471e-05 2.1718856644551e-05 1.61465561887755e-06 6.50763404763925e-06 1.71632139714564e-05 -2.71722330467358e-06 3.2424104174538e-06 1.90717080026816e-06 -3.29469757633185e-06 -1.77208283991848e-06 -2.71722330467358e-06 3.32967710516134e-05 -1.60006420675107e-05 2.08558151523152e-05 -5.53047864003327e-05 -2.98954174204471e-05 3.2424104174538e-06 -1.60006420675107e-05 0.000286599505558676 -4.55754223748173e-05 2.45303881192831e-05 2.1718856644551e-05 1.90717080026816e-06 2.08558151523152e-05 -4.55754223748173e-05 0.000225480613045433 0 0 0 1206 0 0 0 0 1223 0 0 0 0 0 0 0 0 0 0 0 904 904 0 73 0 +296 333 -0.652133603692271 0.746903702450611 0.129833055116565 0.29558806254838 -0.734719598812838 -0.664888444456142 0.134575137187349 -0.827177887658819 0.186839166278472 -0.00762992098652017 0.982360885952869 0.689037967652557 7.28094084934161e-05 2.16341645716757e-05 -2.27802116934013e-06 3.40701066685098e-06 -1.03579282858815e-05 1.48028057342589e-05 2.16341645716757e-05 8.92642613783625e-05 1.32862327158761e-05 2.75566214014988e-05 -2.48493795580725e-05 3.65069778788764e-05 -2.27802116934013e-06 1.32862327158761e-05 2.55398124578589e-05 -6.3886244731437e-06 -1.23254043656886e-05 3.03511790820302e-06 3.40701066685098e-06 2.75566214014988e-05 -6.3886244731437e-06 5.75269252394449e-05 -1.63199860771271e-05 5.70394529134504e-05 -1.03579282858815e-05 -2.48493795580725e-05 -1.23254043656886e-05 -1.63199860771271e-05 6.4509479545071e-05 -1.85836656620669e-05 1.48028057342589e-05 3.65069778788764e-05 3.03511790820302e-06 5.70394529134504e-05 -1.85836656620669e-05 0.000250931584964399 0 0 0 281 0 0 0 0 298 0 0 0 0 0 0 0 0 0 0 265 698 698 0 20 0 +296 330 -0.596344735401316 0.77580047141646 0.206171251897864 0.353567308228816 -0.77984133301026 -0.620800664864817 0.0803369767428556 -0.794705803959855 0.190316714683486 -0.112872330769764 0.975212482005171 0.430874342720595 5.48825072154451e-05 5.33918358492482e-05 1.23858143957508e-05 3.87776116867151e-05 -3.90329758267926e-05 1.5968459427951e-05 5.33918358492482e-05 0.000253039686324143 2.58575069685232e-05 8.50879716678371e-05 -0.000124656212731091 -6.53825229912507e-05 1.23858143957508e-05 2.58575069685232e-05 3.19858687243713e-05 1.15087372041789e-05 -2.10804773012379e-05 1.25188819955587e-05 3.87776116867151e-05 8.50879716678371e-05 1.15087372041789e-05 0.000166851363332465 -0.000164764403877161 6.97862893666802e-05 -3.90329758267926e-05 -0.000124656212731091 -2.10804773012379e-05 -0.000164764403877161 0.000254600142409272 -4.11493368629358e-05 1.5968459427951e-05 -6.53825229912507e-05 1.25188819955587e-05 6.97862893666802e-05 -4.11493368629358e-05 0.000327373596552814 0 0 0 630 0 0 0 0 660 0 0 0 0 0 0 0 0 0 0 366 819 819 0 13 0 +296 432 -0.407062505842998 0.913220212419043 0.0181372535444794 0.254849093991211 -0.912886769884672 -0.407419193309449 0.0254430008569608 -0.800342876805518 0.0306245278551124 -0.0062003671177991 0.999511727665692 0.752077877261054 6.0423401814261e-05 3.90648311213841e-05 5.93420195435688e-06 2.52334413145934e-06 -2.91857800249648e-05 4.52977767498706e-05 3.90648311213841e-05 8.49650062049316e-05 3.56072517076994e-06 5.10594836863386e-06 -2.128420780606e-05 1.08445587378728e-05 5.93420195435688e-06 3.56072517076994e-06 2.43682865345511e-05 -8.67461736788217e-06 -5.99059440932538e-06 -3.20880995694447e-06 2.52334413145934e-06 5.10594836863386e-06 -8.67461736788217e-06 4.17749173034511e-05 -1.66905541064392e-05 2.33002055457083e-05 -2.91857800249648e-05 -2.128420780606e-05 -5.99059440932538e-06 -1.66905541064392e-05 0.000139000666948606 -3.42323341310308e-05 4.52977767498706e-05 1.08445587378728e-05 -3.20880995694447e-06 2.33002055457083e-05 -3.42323341310308e-05 0.000318946886228573 0 0 0 547 0 0 0 0 557 0 0 0 0 0 0 0 0 0 0 124 780 780 0 13 0 +296 332 -0.638907991241863 0.754048169677242 0.152341512837733 0.297043685809284 -0.749838651467586 -0.654668256956293 0.0956633163709182 -0.811196661737455 0.171867901286309 -0.0531114972506996 0.983687243674141 0.636940609848717 6.96405624047697e-05 4.21613027329302e-05 9.4012416082763e-06 2.40789719264282e-05 -1.58895574136702e-05 4.14561567892811e-05 4.21613027329302e-05 0.00010779106947333 9.1260102008246e-06 1.90621471766268e-05 -2.64737502331776e-05 2.70612506366729e-05 9.4012416082763e-06 9.1260102008246e-06 2.89765817621286e-05 -1.947431178346e-06 -1.50643284062742e-05 1.1075030430702e-05 2.40789719264282e-05 1.90621471766268e-05 -1.947431178346e-06 9.72302662057453e-05 -5.17917800181177e-05 4.58610530691227e-05 -1.58895574136702e-05 -2.64737502331776e-05 -1.50643284062742e-05 -5.17917800181177e-05 0.000124872849914048 -9.76673662627942e-06 4.14561567892811e-05 2.70612506366729e-05 1.1075030430702e-05 4.58610530691227e-05 -9.76673662627942e-06 0.000281588762023158 0 0 0 371 0 0 0 0 387 0 0 0 0 0 0 0 0 0 0 205 689 689 0 30 0 +296 334 -0.649003923830353 0.746972456433294 0.144312356306783 0.241771922531768 -0.733399069776898 -0.664719348268064 0.142386770763511 -0.834605685692229 0.202286211352098 -0.0134289749456552 0.979234369969071 0.722550788162572 0.000117399480721372 1.814989060959e-05 -6.15305335077206e-06 -1.23345346608904e-05 -1.46392967849345e-05 -5.18643088276644e-05 1.814989060959e-05 9.24921750538497e-05 1.20034847270523e-05 1.35864101485613e-05 -2.03525514315276e-05 -1.90387637439251e-05 -6.15305335077206e-06 1.20034847270523e-05 3.0268671374828e-05 -5.19570590620897e-06 -1.29807681884727e-05 7.56708337126991e-06 -1.23345346608904e-05 1.35864101485613e-05 -5.19570590620897e-06 8.67835276084779e-05 -5.02144179162089e-05 4.37831844920387e-05 -1.46392967849345e-05 -2.03525514315276e-05 -1.29807681884727e-05 -5.02144179162089e-05 0.000112810736837178 -1.13824151911778e-05 -5.18643088276644e-05 -1.90387637439251e-05 7.56708337126991e-06 4.37831844920387e-05 -1.13824151911778e-05 0.000179808020377553 0 0 0 219 0 0 0 0 235 0 0 0 0 0 0 0 0 0 0 366 404 404 0 33 0 +297 441 0.465886386518083 0.876424821393459 0.121776053896348 0.413598625536596 -0.884843376322666 0.461228634700802 0.0657293382740139 -0.517971327749726 0.00144022047924926 -0.1383751385816 0.990378840034203 -0.0211908373674042 6.01468128742191e-05 2.03284491158353e-05 1.06766614729436e-05 1.40169708302901e-05 8.59787190738737e-06 5.88834552762468e-05 2.03284491158353e-05 5.04345378544752e-05 1.56729325585348e-05 1.00080190739042e-05 3.74464718867649e-06 5.21767198659035e-05 1.06766614729436e-05 1.56729325585348e-05 2.1648956967001e-05 2.94410867673688e-06 2.96445254028813e-06 -6.04024972678169e-07 1.40169708302901e-05 1.00080190739042e-05 2.94410867673688e-06 4.53437060886938e-05 2.57477421918491e-05 3.38813593025313e-05 8.59787190738737e-06 3.74464718867649e-06 2.96445254028813e-06 2.57477421918491e-05 9.7218637040014e-05 2.27389415415424e-05 5.88834552762468e-05 5.21767198659035e-05 -6.04024972678169e-07 3.38813593025313e-05 2.27389415415424e-05 0.000319783132400085 825 779 0 2588 0 845 799 0 2570 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 260 +297 439 0.229268390486129 0.964843815529966 0.128500648860136 0.339055196722306 -0.972556492672021 0.221699464252659 0.0705918983423799 -0.605621270001085 0.0396216315337541 -0.141158631275811 0.989193796548959 0.117609091273697 9.22097927230212e-05 -2.65137249007679e-05 -3.37276045140088e-06 1.12220614785505e-06 3.93941823455407e-05 -5.62529354760799e-06 -2.65137249007679e-05 7.08690418370262e-05 6.04882121531837e-06 -1.01699656998907e-06 -3.65630845970084e-05 4.05717971586325e-05 -3.37276045140088e-06 6.04882121531837e-06 1.46182650451945e-05 -1.66737023096474e-06 1.66193155181369e-06 1.69111623217247e-07 1.12220614785505e-06 -1.01699656998907e-06 -1.66737023096474e-06 2.75364806242859e-05 3.54660612963496e-05 -5.37653458815561e-06 3.93941823455407e-05 -3.65630845970084e-05 1.66193155181369e-06 3.54660612963496e-05 0.000255928500906833 -0.000123628464975024 -5.62529354760799e-06 4.05717971586325e-05 1.69111623217247e-07 -5.37653458815561e-06 -0.000123628464975024 0.000313633135938137 0 0 0 2277 0 0 0 0 2278 0 0 0 0 0 0 0 0 0 0 0 233 226 0 0 76 +297 442 0.568647080331021 0.815711427042557 0.106091308895695 0.520843315565234 -0.822361682763522 0.5667291647722 0.0503916314376935 -0.468381318985785 -0.019020009289003 -0.115900481400209 0.993078706678301 -0.0572498856318035 3.76653285035135e-05 -4.94419540040107e-06 3.80756832794458e-06 -4.69916100415246e-06 -1.70946835642638e-06 -8.6082113473144e-06 -4.94419540040107e-06 3.67012320558371e-05 4.19369934685656e-06 -4.08820120758408e-06 -1.38217249227115e-06 -2.94958160663636e-06 3.80756832794458e-06 4.19369934685656e-06 1.45316679666409e-05 -4.39877563854693e-06 1.13367306429652e-06 -1.69231706227167e-08 -4.69916100415246e-06 -4.08820120758408e-06 -4.39877563854693e-06 4.09392196705015e-05 2.3697497093422e-05 5.83632081437517e-06 -1.70946835642638e-06 -1.38217249227115e-06 1.13367306429652e-06 2.3697497093422e-05 8.20324993368641e-05 -1.57002141049048e-05 -8.6082113473144e-06 -2.94958160663636e-06 -1.69231706227167e-08 5.83632081437517e-06 -1.57002141049048e-05 0.000135458435002366 1305 1315 0 2530 0 1305 1315 0 2500 0 0 0 0 0 0 0 0 0 4 0 0 0 0 0 118 +297 438 0.130604770556395 0.982826938759192 0.130359511955003 0.268610342120249 -0.991433195667294 0.129685052739857 0.0155565299729131 -0.637700195596402 -0.00161630345203282 -0.131274504550944 0.991344739239613 0.216825267165562 2.58800958854373e-05 1.25050038989442e-05 6.63629747414774e-06 -1.85775469331613e-06 -7.49067214475952e-06 1.15580875763843e-06 1.25050038989442e-05 5.22712611066849e-05 8.40304252888677e-06 -3.99318282542547e-06 -1.36628507887122e-05 -7.59011894868786e-06 6.63629747414774e-06 8.40304252888677e-06 1.38286506985432e-05 -4.97366727708203e-06 8.78180658212165e-07 -1.96914329075156e-06 -1.85775469331613e-06 -3.99318282542547e-06 -4.97366727708203e-06 2.05620799732748e-05 2.14481820444179e-05 -1.03980238653803e-06 -7.49067214475952e-06 -1.36628507887122e-05 8.78180658212165e-07 2.14481820444179e-05 0.000255399815756714 -3.2131409469492e-05 1.15580875763843e-06 -7.59011894868786e-06 -1.96914329075156e-06 -1.03980238653803e-06 -3.2131409469492e-05 0.000105802400192001 0 0 0 2439 0 0 0 0 2446 0 0 0 0 0 0 0 0 0 0 0 812 794 0 3 92 +297 437 0.0578905594807803 0.992885008928514 0.104057878932961 0.236419646622466 -0.998295228152895 0.0567970660140868 0.01344361332942 -0.675434115128917 0.00743777992157146 -0.10465874228757 0.994480380446302 0.312195032292387 4.34331205322855e-05 1.23251305682263e-05 6.0105407187762e-06 -1.22190551854888e-06 -1.22677878866067e-05 1.55341482683132e-05 1.23251305682263e-05 7.18014901859369e-05 6.31985759830217e-06 -3.54254112649133e-06 -4.85702337620892e-05 7.22832019805362e-05 6.0105407187762e-06 6.31985759830217e-06 1.36661795495677e-05 -3.44211648192594e-06 -2.60187255115335e-06 -1.95671115891105e-06 -1.22190551854888e-06 -3.54254112649133e-06 -3.44211648192594e-06 2.00238151444482e-05 5.19034612789077e-06 -3.13660737602211e-06 -1.22677878866067e-05 -4.85702337620892e-05 -2.60187255115335e-06 5.19034612789077e-06 0.000185914451335167 -5.51963964697791e-05 1.55341482683132e-05 7.22832019805362e-05 -1.95671115891105e-06 -3.13660737602211e-06 -5.51963964697791e-05 0.000248493326799482 0 0 0 2330 0 0 0 0 2367 0 0 0 0 0 0 0 0 0 0 0 423 423 0 70 69 +297 299 0.997655705573695 0.0675561543057465 0.0109205838521338 0.2400718362782 -0.0674437978371591 0.997669399324387 -0.0103490958550756 -0.0207266094518593 -0.0115942774485404 0.00958830887775817 0.999886812125908 -0.0597797720718001 5.10929532933417e-05 9.88336528025814e-06 5.65853037838993e-06 1.17123254339545e-05 -2.07933851030305e-06 4.27320209573677e-06 9.88336528025814e-06 3.90451185901867e-05 2.49403890700803e-06 4.29306807718502e-06 -4.83236904013225e-07 1.73961179119135e-05 5.65853037838993e-06 2.49403890700803e-06 1.21919912591402e-05 2.57048789794885e-06 1.96641419660963e-06 3.12365741094658e-06 1.17123254339545e-05 4.29306807718502e-06 2.57048789794885e-06 7.72528911048558e-05 5.15540601720753e-06 8.33095798466587e-06 -2.07933851030305e-06 -4.83236904013225e-07 1.96641419660963e-06 5.15540601720753e-06 1.75084725820572e-05 1.11359604681082e-06 4.27320209573677e-06 1.73961179119135e-05 3.12365741094658e-06 8.33095798466587e-06 1.11359604681082e-06 0.000176403742548749 3271 3288 0 616 63 3271 3288 0 585 120 0 0 0 0 0 0 0 0 2206 0 0 0 0 0 2834 +297 436 0.0257485280668033 0.998205966215279 0.0540542534368405 0.210592648518968 -0.998912998647551 0.0235896716453926 0.040203837187763 -0.705026822405315 0.0388565880559608 -0.0550306860204713 0.997728314302428 0.405933470257193 4.07798056704033e-05 2.29813595975599e-06 5.85135487730176e-06 -3.60120428562756e-06 1.25334307581389e-05 -1.40910858132548e-06 2.29813595975599e-06 4.08701089785672e-05 4.64107054103431e-06 -9.99081977349738e-07 1.02049818952513e-06 -3.2230633674807e-07 5.85135487730176e-06 4.64107054103431e-06 1.61538099194925e-05 -4.57786657432608e-06 4.25431074776979e-06 -1.47985640285616e-06 -3.60120428562756e-06 -9.99081977349738e-07 -4.57786657432608e-06 3.01040126345946e-05 8.42546843834017e-06 6.17717889061501e-06 1.25334307581389e-05 1.02049818952513e-06 4.25431074776979e-06 8.42546843834017e-06 0.000299092968138181 2.60566939693002e-05 -1.40910858132548e-06 -3.2230633674807e-07 -1.47985640285616e-06 6.17717889061501e-06 2.60566939693002e-05 0.000105551746820522 0 0 0 2013 0 0 0 0 2041 0 0 0 0 0 0 0 0 0 0 0 639 611 0 69 91 +297 435 -0.0372295970769591 0.999143186350259 0.018079000839052 0.166233699862364 -0.996691998947425 -0.038433996306745 0.0716092672918748 -0.729241165483204 0.0722427597456889 -0.0153532113169941 0.997268901834697 0.521545818092432 5.11697766505701e-05 1.23628742453723e-05 3.41195416116279e-06 -1.209274164178e-05 2.15542127061891e-05 1.48926411059946e-05 1.23628742453723e-05 5.71945850594764e-05 1.06179933022072e-05 5.12890653444989e-06 1.44749508789361e-05 3.64212058192616e-05 3.41195416116279e-06 1.06179933022072e-05 1.81800092812209e-05 -1.90677295824382e-07 -1.99016177506541e-06 7.09154370280498e-06 -1.209274164178e-05 5.12890653444989e-06 -1.90677295824382e-07 3.83391830682647e-05 1.57626604883338e-05 1.13813554629135e-05 2.15542127061891e-05 1.44749508789361e-05 -1.99016177506541e-06 1.57626604883338e-05 0.000272766077813851 4.84126029423771e-05 1.48926411059946e-05 3.64212058192616e-05 7.09154370280498e-06 1.13813554629135e-05 4.84126029423771e-05 0.000180262165697506 0 0 0 1524 0 0 0 0 1539 0 0 0 0 0 0 0 0 0 0 0 288 268 0 60 56 +297 434 -0.115669678303988 0.991313744680045 0.0625906153466971 0.138021271342427 -0.990964280199547 -0.119477266406428 0.0609506208388497 -0.737299880862421 0.0678993438086533 -0.0549749253794283 0.99617640841865 0.634566208343964 5.51360717285399e-05 1.84431495976377e-05 -1.7381849463849e-06 -8.65043144651278e-06 1.33441587819781e-06 3.59144846540177e-05 1.84431495976377e-05 6.58917877038088e-05 5.77635795135838e-06 1.54747350410072e-06 3.74870995611527e-06 4.27721736996777e-05 -1.7381849463849e-06 5.77635795135838e-06 1.8332213284488e-05 -3.65838088585705e-06 2.68081214825836e-06 2.52038180488629e-06 -8.65043144651278e-06 1.54747350410072e-06 -3.65838088585705e-06 2.95242631636646e-05 -6.78735858236871e-06 3.04227899000369e-06 1.33441587819781e-06 3.74870995611527e-06 2.68081214825836e-06 -6.78735858236871e-06 0.000126237904834234 2.81395330971146e-05 3.59144846540177e-05 4.27721736996777e-05 2.52038180488629e-06 3.04227899000369e-06 2.81395330971146e-05 0.000224421046665855 0 0 0 1294 0 0 0 0 1313 0 0 0 0 0 0 0 0 0 0 0 856 856 0 66 0 +297 331 -0.585302942452109 0.798471003703516 0.140941554559336 0.196848153603279 -0.794158087007932 -0.599604361478893 0.0989320096601237 -0.778042191765171 0.163503511879118 -0.0540246789919956 0.985062401913202 0.572473480442994 5.17442944419258e-05 1.49918810709268e-05 7.37860466413996e-06 2.18706557683652e-05 -1.77168792264613e-05 2.19373206856475e-05 1.49918810709268e-05 5.74833170770557e-05 1.08644437798312e-05 1.75812439755399e-05 -1.31345727533462e-05 1.62642441386677e-05 7.37860466413996e-06 1.08644437798312e-05 2.1821183684593e-05 -1.41318921100064e-06 -6.45841904587143e-06 3.03890182734639e-06 2.18706557683652e-05 1.75812439755399e-05 -1.41318921100064e-06 0.000121771862486541 -9.69231737568055e-05 6.27032451850331e-05 -1.77168792264613e-05 -1.31345727533462e-05 -6.45841904587143e-06 -9.69231737568055e-05 0.0001515346944815 -5.77204143437821e-05 2.19373206856475e-05 1.62642441386677e-05 3.03890182734639e-06 6.27032451850331e-05 -5.77204143437821e-05 0.00019066745868257 0 0 0 489 0 0 0 0 513 0 0 0 0 0 0 0 0 0 0 215 612 612 0 30 0 +297 433 -0.229727259288576 0.973248733583023 -0.00350555541980046 0.152992198682768 -0.973016050685975 -0.229589538778964 0.0229871440316163 -0.754653444477934 0.021567369965465 0.00869173528729002 0.9997296145911 0.700184649728405 4.77495080074524e-05 6.07665096854124e-06 6.55021382821415e-06 -1.0324252485252e-05 1.93621231159819e-05 1.34668863506548e-05 6.07665096854124e-06 6.56965531909877e-05 -9.69079676105143e-07 9.46416623334668e-07 1.34764701042017e-06 -1.03171097833905e-05 6.55021382821415e-06 -9.69079676105143e-07 1.84979241244736e-05 -7.9509003059006e-06 -2.31579697283436e-06 4.80277142485546e-06 -1.0324252485252e-05 9.46416623334668e-07 -7.9509003059006e-06 4.05477529313777e-05 -2.24193436266022e-05 -1.64172043625026e-05 1.93621231159819e-05 1.34764701042017e-06 -2.31579697283436e-06 -2.24193436266022e-05 0.000194545077700074 4.61547101597973e-05 1.34668863506548e-05 -1.03171097833905e-05 4.80277142485546e-06 -1.64172043625026e-05 4.61547101597973e-05 0.000140432303078411 0 0 0 859 0 0 0 0 867 0 0 0 0 0 0 0 0 0 0 17 850 850 0 33 0 +297 332 -0.591403677884063 0.793624230925356 0.14283651449591 0.201142462002204 -0.7885470107127 -0.606224645069981 0.103369684172103 -0.783293544812829 0.168627701405399 -0.0515000951252759 0.984333499643703 0.66117411437251 0.000121168952589771 7.89166696625343e-05 1.78387211177315e-05 1.46395017908596e-05 -2.42405097254149e-05 0.000123358176517581 7.89166696625343e-05 0.000149472231531203 2.32883506325374e-05 5.57627920736151e-06 -1.6479357910102e-05 0.000113888456334763 1.78387211177315e-05 2.32883506325374e-05 2.81538974774057e-05 -1.08351917392211e-05 -8.21202826728994e-06 2.14614083189024e-05 1.46395017908596e-05 5.57627920736151e-06 -1.08351917392211e-05 7.75881469060364e-05 -4.80539698084918e-05 3.60997190039252e-05 -2.42405097254149e-05 -1.6479357910102e-05 -8.21202826728994e-06 -4.80539698084918e-05 0.000109198917441411 -1.20759423949347e-05 0.000123358176517581 0.000113888456334763 2.14614083189024e-05 3.60997190039252e-05 -1.20759423949347e-05 0.000443897991187515 0 0 0 404 0 0 0 0 424 0 0 0 0 0 0 0 0 0 0 229 681 681 0 27 0 +297 448 0.893884670445798 0.443748553959025 0.0636978555469599 0.991786588787527 -0.447381121719789 0.892085524952365 0.0635102204310921 -0.187708353893943 -0.0286413664260336 -0.0852680305257308 0.995946301313235 -0.263711245338784 9.27133505962736e-05 -5.5389015082154e-06 8.3108000597758e-06 3.78876267163663e-06 -8.04255239249877e-06 -2.06964249389127e-05 -5.5389015082154e-06 5.38707476809906e-05 4.06704344861689e-06 -1.00746136012562e-05 2.92326684640918e-06 6.60852939493285e-06 8.3108000597758e-06 4.06704344861689e-06 2.35568597829107e-05 1.15745509880002e-05 -1.14606057517518e-05 -9.63543616441359e-06 3.78876267163663e-06 -1.00746136012562e-05 1.15745509880002e-05 9.84836648324149e-05 -4.67521286660007e-05 2.30900535720784e-05 -8.04255239249877e-06 2.92326684640918e-06 -1.14606057517518e-05 -4.67521286660007e-05 5.94512528638017e-05 2.99178407140659e-06 -2.06964249389127e-05 6.60852939493285e-06 -9.63543616441359e-06 2.30900535720784e-05 2.99178407140659e-06 0.000312362223386035 2868 3026 0 2862 367 2868 3026 0 2806 389 0 0 0 0 0 0 0 0 78 0 0 0 0 0 1400 +298 440 0.383540979944236 0.912166611493183 0.14438971424745 0.295138027188539 -0.922941787257465 0.373035462627865 0.0949894781331632 -0.538223505470114 0.0327837465432306 -0.169695658456721 0.984951069578347 0.0843874690840717 7.17532988462867e-05 -1.04433008497689e-05 1.07812270687868e-05 1.56734070321938e-05 2.42301256034609e-05 -1.53176895237148e-05 -1.04433008497689e-05 6.49155584206871e-05 4.78208245117015e-07 5.21191347073923e-07 9.60400513965493e-06 8.14531157162381e-06 1.07812270687868e-05 4.78208245117015e-07 1.66967597132884e-05 -6.69719764286536e-07 8.07172638013092e-06 -3.22705440733509e-06 1.56734070321938e-05 5.21191347073923e-07 -6.69719764286536e-07 6.19620236366331e-05 7.33424748464348e-05 2.66863591466421e-05 2.42301256034609e-05 9.60400513965493e-06 8.07172638013092e-06 7.33424748464348e-05 0.000228500543621219 3.11393843759783e-05 -1.53176895237148e-05 8.14531157162381e-06 -3.22705440733509e-06 2.66863591466421e-05 3.11393843759783e-05 0.000157460485068583 313 193 0 2301 0 363 243 0 2274 0 0 0 0 0 0 0 0 0 13 0 173 139 0 0 238 +298 441 0.503903743152902 0.854993228714267 0.122750138448994 0.315087063542978 -0.863637008305266 0.496322231666035 0.0882913372850193 -0.493762128482954 0.0145648728804993 -0.150501897685043 0.988502424514566 0.023421615782573 4.17268225460165e-05 -6.50246568572351e-06 3.53575364143636e-06 6.58420012737567e-07 3.34954429517943e-06 -8.54136406773776e-06 -6.50246568572351e-06 5.40464469686755e-05 5.50857419688722e-06 6.88408290133035e-07 -6.8160112794075e-07 -8.65059909046557e-06 3.53575364143636e-06 5.50857419688722e-06 1.40913960304041e-05 -1.80684631142424e-06 4.01518123598087e-06 -3.11140849388239e-06 6.58420012737567e-07 6.88408290133035e-07 -1.80684631142424e-06 2.7500449837022e-05 3.25581148242985e-06 -8.88713673975404e-07 3.34954429517943e-06 -6.8160112794075e-07 4.01518123598087e-06 3.25581148242985e-06 5.21458722286132e-05 -3.78419897274441e-06 -8.54136406773776e-06 -8.65059909046557e-06 -3.11140849388239e-06 -8.88713673975404e-07 -3.78419897274441e-06 0.000120356085994199 777 731 0 2281 0 838 792 0 2237 0 0 0 0 0 0 0 0 0 238 0 2 2 0 0 215 +298 442 0.604955331134464 0.788349573146949 0.111955338644543 0.398186210685266 -0.796207392155183 0.600513841455714 0.0737354385458108 -0.44281472263912 -0.00910142897751698 -0.133746314861848 0.990973807550655 -0.0278319428498233 5.49636712107311e-05 -2.38222437712213e-06 5.69557509633639e-06 1.80177469507612e-06 8.624783247182e-06 -1.09131347718983e-05 -2.38222437712213e-06 5.88965905290726e-05 6.04654983302983e-06 3.95167853266941e-06 3.59511811712643e-06 2.8276003595753e-05 5.69557509633639e-06 6.04654983302983e-06 1.63884781075174e-05 1.28408415258902e-06 1.95011699504271e-06 5.58724080610315e-06 1.80177469507612e-06 3.95167853266941e-06 1.28408415258902e-06 3.77437739685111e-05 5.47595231475929e-06 2.08948931569442e-05 8.624783247182e-06 3.59511811712643e-06 1.95011699504271e-06 5.47595231475929e-06 5.32655786325098e-05 -1.76863485973254e-05 -1.09131347718983e-05 2.8276003595753e-05 5.58724080610315e-06 2.08948931569442e-05 -1.76863485973254e-05 0.000227644748101603 1306 1316 0 2223 0 1307 1317 0 2175 0 0 0 0 0 0 0 0 0 457 0 0 0 0 0 160 +298 300 0.997665247294249 0.0603228845799302 0.0320188059936959 0.238938135450319 -0.0612195626651649 0.997736985332355 0.0278041947732704 -0.0146270856923076 -0.0302691177339458 -0.0296994561542871 0.999100456818907 -0.0422636844750295 4.04854507758635e-05 -5.83232714294815e-06 2.74286508286103e-06 4.26253886305825e-06 -3.50448755197679e-07 -8.35179056507737e-06 -5.83232714294815e-06 3.57732144520844e-05 2.59921668157204e-06 2.77893791548858e-06 -3.43178768520006e-06 1.40291719678843e-05 2.74286508286103e-06 2.59921668157204e-06 9.75007458762229e-06 2.24531965756637e-07 2.75607588925326e-06 2.41051376512509e-06 4.26253886305825e-06 2.77893791548858e-06 2.24531965756637e-07 0.00010668003345072 4.40220803026836e-06 4.20072316520269e-05 -3.50448755197679e-07 -3.43178768520006e-06 2.75607588925326e-06 4.40220803026836e-06 1.68701692952635e-05 -2.45566534392948e-06 -8.35179056507737e-06 1.40291719678843e-05 2.41051376512509e-06 4.20072316520269e-05 -2.45566534392948e-06 0.000138861790835502 3380 3410 0 464 96 3380 3410 0 409 164 0 0 0 0 0 0 0 0 2238 0 0 0 0 0 3240 +298 447 0.881078157987213 0.46682187949908 0.0760171844967047 0.816843383824584 -0.471046375943712 0.880569084006731 0.0520903062175946 -0.188595746171853 -0.0426214878688538 -0.0817032503178053 0.995744941066411 -0.198856122753607 5.92482165255492e-05 4.19329761021795e-06 7.69516202717491e-06 8.20112824494731e-06 -5.57588421600327e-06 8.33695717834593e-06 4.19329761021795e-06 5.71111444669711e-05 3.68618421135788e-06 -9.3387969201871e-07 -4.54238968925446e-06 -2.11821350231795e-05 7.69516202717491e-06 3.68618421135788e-06 1.82577991336837e-05 6.62554323228974e-06 -3.46967377127168e-06 -1.07305359866466e-05 8.20112824494731e-06 -9.3387969201871e-07 6.62554323228974e-06 9.64444844764058e-05 -3.70163780236771e-07 1.19721767307288e-05 -5.57588421600327e-06 -4.54238968925446e-06 -3.46967377127168e-06 -3.70163780236771e-07 4.92549796980158e-05 2.19223659278485e-05 8.33695717834593e-06 -2.11821350231795e-05 -1.07305359866466e-05 1.19721767307288e-05 2.19223659278485e-05 0.000120230710184156 3034 3091 0 2606 0 3034 3091 0 2532 0 0 0 0 0 0 0 0 0 864 0 0 0 0 0 916 +298 438 0.174090081411556 0.975704933497385 0.133013256117508 0.198566972779086 -0.984599552311623 0.170275493518363 0.0396229465692335 -0.616211728738307 0.0160114066174114 -0.137862754418813 0.990321915238772 0.254415385097228 9.64085682629808e-05 0.000104783199018877 6.3045266698458e-06 -1.33443035315413e-06 -2.7417944992414e-05 0.000161217150519524 0.000104783199018877 0.000204498144209507 1.03474536957585e-05 -3.81095779795151e-06 -7.19204709694936e-05 0.000261454571972416 6.3045266698458e-06 1.03474536957585e-05 1.2722906394642e-05 -4.336427156121e-06 -1.91051663665907e-07 -9.72984291419495e-09 -1.33443035315413e-06 -3.81095779795151e-06 -4.336427156121e-06 2.01046689458072e-05 2.71233102152586e-05 -4.20229036755407e-06 -2.7417944992414e-05 -7.19204709694936e-05 -1.91051663665907e-07 2.71233102152586e-05 0.000349849047786207 -0.000133423444300563 0.000161217150519524 0.000261454571972416 -9.72984291419495e-09 -4.20229036755407e-06 -0.000133423444300563 0.000587155105261981 0 0 0 2341 0 0 0 0 2350 0 0 0 0 0 0 0 0 0 0 0 446 435 0 5 107 +298 329 -0.473001216062474 0.857572499884099 0.202087251072299 0.208275744062024 -0.859722287484395 -0.499415532408411 0.107059396560145 -0.725684722551207 0.192736706431391 -0.123099688999447 0.973498345433735 0.378496432162321 0.0001225256688568 -2.61181064042437e-05 -8.98583001705457e-06 -6.39676371164196e-06 -3.12198631219571e-05 -8.66999667371506e-05 -2.61181064042437e-05 0.000117689907765036 2.23768098117343e-05 -8.28410231316367e-06 3.93494313073307e-05 5.73184379912936e-05 -8.98583001705457e-06 2.23768098117343e-05 2.33043690484494e-05 2.111635664195e-06 2.79673480718033e-06 1.13372821977655e-05 -6.39676371164196e-06 -8.28410231316367e-06 2.111635664195e-06 8.82707279544202e-05 -7.47337946608089e-05 -3.56660317019255e-06 -3.12198631219571e-05 3.93494313073307e-05 2.79673480718033e-06 -7.47337946608089e-05 0.000195265748380752 0.000148022118983639 -8.66999667371506e-05 5.73184379912936e-05 1.13372821977655e-05 -3.56660317019255e-06 0.000148022118983639 0.00060674693766856 0 0 0 803 0 0 0 0 821 0 0 0 0 0 0 0 0 0 0 126 474 474 0 3 0 +298 331 -0.549546134723488 0.82363466105323 0.140089224861177 0.109106013105129 -0.815454635166612 -0.565267911354707 0.124522794611967 -0.75590499286844 0.181749233274206 -0.0458053872859712 0.982277497807936 0.602401475180895 4.82155274817397e-05 1.84518183368621e-05 7.72207874152205e-06 -1.06332800797517e-05 1.06738781669986e-05 2.30624788999475e-05 1.84518183368621e-05 8.57082386230506e-05 8.7925986580987e-06 3.41013209071924e-06 -7.20286916740401e-06 -1.81765060027759e-05 7.72207874152205e-06 8.7925986580987e-06 2.67113064306918e-05 -4.2018236223325e-06 -7.37897088937918e-06 -2.16978983787536e-06 -1.06332800797517e-05 3.41013209071924e-06 -4.2018236223325e-06 8.29197750888927e-05 -5.79228807190724e-05 7.83925451644962e-06 1.06738781669986e-05 -7.20286916740401e-06 -7.37897088937918e-06 -5.79228807190724e-05 0.000106975808229864 2.61416924174573e-05 2.30624788999475e-05 -1.81765060027759e-05 -2.16978983787536e-06 7.83925451644962e-06 2.61416924174573e-05 0.000254838909934768 0 0 0 413 0 0 0 0 440 0 0 0 0 0 0 0 0 0 0 237 463 463 0 38 0 +298 436 0.0700572265445562 0.995206804931709 0.0682304948428826 0.124920219749523 -0.996298361659591 0.0663902700661034 0.0546068365222283 -0.684877585836779 0.0498152543233522 -0.0718035337443064 0.996174027456312 0.474633181486436 5.96162033795661e-05 1.52548671366223e-05 1.76772946464156e-06 -2.35223005296327e-06 4.09975894752337e-05 5.29837464654389e-06 1.52548671366223e-05 7.946540655988e-05 1.98349339967383e-06 5.42827381979701e-07 1.24370593990924e-05 4.08258690290799e-07 1.76772946464156e-06 1.98349339967383e-06 1.28488634366137e-05 -2.37722271574463e-06 -1.78165845726336e-06 8.12216788098247e-07 -2.35223005296327e-06 5.42827381979701e-07 -2.37722271574463e-06 3.03460426858441e-05 1.16550548242517e-05 1.97968128623975e-05 4.09975894752337e-05 1.24370593990924e-05 -1.78165845726336e-06 1.16550548242517e-05 0.00026914190849682 5.35997555607492e-05 5.29837464654389e-06 4.08258690290799e-07 8.12216788098247e-07 1.97968128623975e-05 5.35997555607492e-05 0.000154214111075718 0 0 0 1643 0 0 0 0 1673 0 0 0 0 0 0 0 0 0 0 0 488 462 0 58 126 +298 435 0.00819119354010719 0.999720783646561 0.0221643653979888 0.0777824977959774 -0.99597404849884 0.00617780616223878 0.0894289071153853 -0.70333304053995 0.0892670099489107 -0.0228076622241049 0.995746559862826 0.57405807034249 5.57829592304045e-05 1.16791178285341e-05 5.07387564563937e-06 -1.18459980806743e-05 -1.51290879669364e-05 1.29795203256389e-05 1.16791178285341e-05 4.67697126235775e-05 8.25472191552152e-06 -1.91232517726186e-06 -3.12522496332544e-05 1.21848960670934e-05 5.07387564563937e-06 8.25472191552152e-06 1.5496110210928e-05 -4.02337679312646e-06 -8.52958140899629e-06 1.29488690323324e-06 -1.18459980806743e-05 -1.91232517726186e-06 -4.02337679312646e-06 3.78876295796572e-05 1.05503308565266e-05 8.21280367033307e-06 -1.51290879669364e-05 -3.12522496332544e-05 -8.52958140899629e-06 1.05503308565266e-05 0.000192519658471552 -4.84226884147444e-05 1.29795203256389e-05 1.21848960670934e-05 1.29488690323324e-06 8.21280367033307e-06 -4.84226884147444e-05 0.000157426496082851 0 0 0 1344 0 0 0 0 1362 0 0 0 0 0 0 0 0 0 0 0 347 306 0 51 94 +298 434 -0.0714012982475018 0.995078685062244 0.0687041857776333 0.0440772840993828 -0.993988581620495 -0.0767161723531857 0.0781110011941554 -0.718099329544444 0.0829973145146777 -0.0627139492798258 0.994574485068403 0.675957511778454 2.83064731287434e-05 4.51788236256822e-06 3.43906658868806e-06 -9.91349086080797e-06 1.56495658713461e-05 -4.15102835512464e-06 4.51788236256822e-06 4.73818116404066e-05 3.12777450524826e-06 -3.70656872717968e-06 6.9861346714656e-06 -1.57335747572268e-05 3.43906658868806e-06 3.12777450524826e-06 1.25866344926732e-05 -3.48569561124824e-06 -2.73905241472018e-06 -4.17888624573247e-06 -9.91349086080797e-06 -3.70656872717968e-06 -3.48569561124824e-06 2.7420213668512e-05 -2.78125938130071e-05 2.66153386088038e-06 1.56495658713461e-05 6.9861346714656e-06 -2.73905241472018e-06 -2.78125938130071e-05 0.00021401104406509 7.5849294847908e-06 -4.15102835512464e-06 -1.57335747572268e-05 -4.17888624573247e-06 2.66153386088038e-06 7.5849294847908e-06 7.23203449166629e-05 0 0 0 1188 0 0 0 0 1205 0 0 0 0 0 0 0 0 0 0 0 672 672 0 54 0 +299 441 0.524188991129889 0.843844030974804 0.114687196174742 0.246023987511566 -0.851599338466053 0.519077847638405 0.0730530958636343 -0.480762934530733 0.00211383594668939 -0.13596116901261 0.99071191181812 0.0586010252782288 5.29711174676809e-05 2.13299149004712e-06 3.48110172404543e-06 -1.42214810858903e-06 -8.37975269484838e-06 1.66931364176582e-05 2.13299149004712e-06 4.75516547814245e-05 7.36787789260725e-06 -2.66738366012671e-06 -1.3994923176795e-05 5.14346459822308e-05 3.48110172404543e-06 7.36787789260725e-06 1.47801130517975e-05 -9.03469617013463e-07 5.47738035226215e-07 2.93283993791644e-07 -1.42214810858903e-06 -2.66738366012671e-06 -9.03469617013463e-07 4.80513019492018e-05 4.85550210777715e-05 -4.17553019360054e-06 -8.37975269484838e-06 -1.3994923176795e-05 5.47738035226215e-07 4.85550210777715e-05 0.00014756832811026 -5.51828945536735e-05 1.66931364176582e-05 5.14346459822308e-05 2.93283993791644e-07 -4.17553019360054e-06 -5.51828945536735e-05 0.000317812425419271 726 680 0 2177 0 798 752 0 2138 0 0 0 0 0 0 0 0 0 398 0 22 22 0 0 230 +299 440 0.406398730831253 0.904379913307113 0.130142398876634 0.203358334482574 -0.913355229240836 0.39821640651981 0.0848876834226825 -0.529183732725793 0.0249458773581266 -0.153364487366103 0.987854765245259 0.125253888670379 3.92118332360395e-05 1.18547099342036e-06 8.55334296970583e-06 1.15264977844405e-06 -1.20733346404578e-06 3.73153635883441e-06 1.18547099342036e-06 4.48897417237005e-05 4.51017920741532e-06 -4.77615651757911e-06 -5.88711438991325e-06 1.90291576958127e-05 8.55334296970583e-06 4.51017920741532e-06 1.7572651145004e-05 -9.22267619531183e-10 4.08033854269928e-06 4.91236875376512e-06 1.15264977844405e-06 -4.77615651757911e-06 -9.22267619531183e-10 3.62796539498624e-05 2.53709495239782e-05 1.35527416298848e-05 -1.20733346404578e-06 -5.88711438991325e-06 4.08033854269928e-06 2.53709495239782e-05 0.000112874704046886 -2.0934229298092e-05 3.73153635883441e-06 1.90291576958127e-05 4.91236875376512e-06 1.35527416298848e-05 -2.0934229298092e-05 0.000205982307632543 225 106 0 2275 0 291 171 0 2243 0 0 0 0 0 0 0 0 0 128 0 250 204 0 0 310 +299 442 0.623894122643679 0.775673924794972 0.0953209637164753 0.290261909464864 -0.781447258498066 0.620718747108281 0.0636271889539524 -0.430052102679956 -0.00981355779166089 -0.114184935002343 0.993411040155071 -0.000362085225979404 5.22926213803636e-05 2.90911539501849e-05 9.11636378807287e-06 8.17174388872602e-06 1.30508400126823e-05 1.94271831311221e-05 2.90911539501849e-05 6.82351168597454e-05 1.01273302788355e-05 6.06817232843301e-07 7.03475192902182e-06 2.58987333455491e-05 9.11636378807287e-06 1.01273302788355e-05 1.83756603014876e-05 2.00700061305684e-06 4.77110896054465e-07 -2.74761965933832e-06 8.17174388872602e-06 6.06817232843301e-07 2.00700061305684e-06 3.60728876633192e-05 2.38272482173838e-06 2.41453515992592e-05 1.30508400126823e-05 7.03475192902182e-06 4.77110896054465e-07 2.38272482173838e-06 4.32544027563691e-05 7.71396077283851e-06 1.94271831311221e-05 2.58987333455491e-05 -2.74761965933832e-06 2.41453515992592e-05 7.71396077283851e-06 0.000221432361411634 1211 1221 0 1981 0 1279 1289 0 1937 0 0 0 0 0 0 0 0 0 677 0 3 3 0 0 143 +299 443 0.706533091510808 0.701380250048587 0.0942164287264265 0.382273033136089 -0.705370190907119 0.708705817438396 0.0137462034260063 -0.377746906472163 -0.0571304155405374 -0.0761696079204592 0.995456833041699 -0.027469539703031 5.58930143143579e-05 -2.97350306382868e-06 1.33712073951509e-05 1.04126787836183e-05 -7.18395737066595e-06 -3.31818710197889e-07 -2.97350306382868e-06 4.02987570395964e-05 1.04363116229092e-06 -1.96201350555071e-06 -5.98547059333925e-06 -3.18777943416244e-06 1.33712073951509e-05 1.04363116229092e-06 1.65680607391826e-05 5.12373265431953e-06 -3.57345283059726e-06 1.13117595210294e-06 1.04126787836183e-05 -1.96201350555071e-06 5.12373265431953e-06 6.40873744950877e-05 1.39248357831771e-05 3.42602116838091e-06 -7.18395737066595e-06 -5.98547059333925e-06 -3.57345283059726e-06 1.39248357831771e-05 7.204606073752e-05 3.76159585153203e-06 -3.31818710197889e-07 -3.18777943416244e-06 1.13117595210294e-06 3.42602116838091e-06 3.76159585153203e-06 0.000163742981510955 1708 1725 0 1895 0 1718 1735 0 1850 0 0 0 0 0 0 0 0 0 947 0 0 0 0 0 140 +299 438 0.198529082074771 0.973616414633276 0.112504580916483 0.0958329310243191 -0.980057431245941 0.196204191191627 0.03148566052107 -0.613537022230386 0.00858108560481317 -0.116511769858175 0.993152240320868 0.252039329474928 6.26751034628419e-05 4.63369100909886e-06 7.51062615190007e-06 -6.48189988831801e-07 1.89285744057197e-05 -1.36205313488552e-05 4.63369100909886e-06 5.34824209835389e-05 5.64780218822236e-06 3.29311738990801e-07 -4.36189125110917e-07 4.82230420882127e-05 7.51062615190007e-06 5.64780218822236e-06 1.67883821283205e-05 -3.90926483175054e-06 -5.09632941973823e-06 -2.05744142001425e-06 -6.48189988831801e-07 3.29311738990801e-07 -3.90926483175054e-06 2.31191062677439e-05 1.0465362915091e-05 1.32718487385864e-05 1.89285744057197e-05 -4.36189125110917e-07 -5.09632941973823e-06 1.0465362915091e-05 0.000191849047868519 1.41671572010055e-05 -1.36205313488552e-05 4.82230420882127e-05 -2.05744142001425e-06 1.32718487385864e-05 1.41671572010055e-05 0.000244866848097097 0 0 0 2471 0 0 0 0 2492 0 0 0 0 0 0 0 0 0 0 0 70 64 0 16 120 +299 327 -0.365908440688746 0.922284008225616 0.124511931974502 0.218894337183261 -0.911816228556742 -0.382060405024028 0.150402833262657 -0.700600659706385 0.186285207070474 -0.0584983340289958 0.980752653089729 0.23901023264591 0.000106270253390065 2.79609577041673e-06 3.87378700977324e-06 2.42836089743634e-06 -7.93114947025907e-06 -1.87262809399627e-06 2.79609577041673e-06 7.02085892084865e-05 5.16783180862099e-06 -2.60731018657095e-05 7.28221262939073e-05 7.94921099384595e-05 3.87378700977324e-06 5.16783180862099e-06 2.05653923979853e-05 -2.5977328120721e-06 1.17429194628021e-05 1.00705065441499e-05 2.42836089743634e-06 -2.60731018657095e-05 -2.5977328120721e-06 6.63847332775586e-05 -7.95396759417963e-05 -8.59761663035114e-05 -7.93114947025907e-06 7.28221262939073e-05 1.17429194628021e-05 -7.95396759417963e-05 0.000312157359578188 0.000316889112250055 -1.87262809399627e-06 7.94921099384595e-05 1.00705065441499e-05 -8.59761663035114e-05 0.000316889112250055 0.000564509852996942 0 0 0 1073 0 0 0 0 1073 0 0 0 0 0 0 0 0 0 0 12 245 245 0 0 0 +299 436 0.0937903925400231 0.994695373503383 0.0422430609467904 0.0120298023624991 -0.994757383662643 0.0918904090091456 0.044876501432101 -0.686041955192762 0.04075671620533 -0.0462305814704705 0.998099004819191 0.473678976072563 6.33718508696525e-05 -7.68323441398686e-06 2.90415817965989e-06 -6.44391896759783e-06 1.45689119890792e-06 -9.40973942718703e-06 -7.68323441398686e-06 6.22912679932115e-05 6.32885187815403e-06 -5.70197814643322e-08 4.74758615298515e-06 1.54531471315486e-05 2.90415817965989e-06 6.32885187815403e-06 1.41914696667103e-05 -2.82446575551256e-06 3.36179229618438e-06 1.91494374771721e-06 -6.44391896759783e-06 -5.70197814643322e-08 -2.82446575551256e-06 2.60215461230761e-05 2.37818367362299e-07 1.33380512097585e-05 1.45689119890792e-06 4.74758615298515e-06 3.36179229618438e-06 2.37818367362299e-07 0.000287230537255623 2.84797301604174e-05 -9.40973942718703e-06 1.54531471315486e-05 1.91494374771721e-06 1.33380512097585e-05 2.84797301604174e-05 0.000200680784116719 0 0 0 1605 0 0 0 0 1627 0 0 0 0 0 0 0 0 0 0 0 403 374 0 91 154 +299 449 0.945594980231918 0.321347780646698 0.0508501448733464 0.874156988927779 -0.323702419542924 0.944946462458646 0.0478845138739765 -0.0719236544293919 -0.03266308225283 -0.0617396708796883 0.997557685598889 -0.168428641494987 6.80037301464619e-05 -8.19515400013429e-06 7.94140647381259e-06 -8.33705186780045e-06 -6.98170408995357e-06 -7.61001048528781e-06 -8.19515400013429e-06 5.42704732360827e-05 5.47721976151244e-09 6.12950624336658e-06 5.78910211932007e-06 2.48555464983073e-05 7.94140647381259e-06 5.47721976151244e-09 2.18537075834307e-05 7.21286363099844e-06 -4.82267522918217e-06 -1.11164296908791e-05 -8.33705186780045e-06 6.12950624336658e-06 7.21286363099844e-06 8.68030329462022e-05 -5.07640164308789e-06 7.81647700235821e-05 -6.98170408995357e-06 5.78910211932007e-06 -4.82267522918217e-06 -5.07640164308789e-06 3.26512857379687e-05 3.37245955058847e-05 -7.61001048528781e-06 2.48555464983073e-05 -1.11164296908791e-05 7.81647700235821e-05 3.37245955058847e-05 0.000335484168949401 2971 3100 0 2192 828 2971 3100 0 2113 941 0 0 0 0 0 0 0 0 1414 0 0 0 0 0 2116 +299 448 0.922090365468262 0.383461453384168 0.0520256828797923 0.776226872589081 -0.386328990741224 0.919957496428981 0.0665440882196798 -0.121576978330657 -0.0223443241892591 -0.08145869218581 0.996426220371535 -0.174608870843348 7.03633747054876e-05 -1.3776877195149e-05 6.53064756495057e-06 -9.90598660639266e-06 -2.23459240636241e-06 -4.39804075070137e-05 -1.3776877195149e-05 4.24153327949984e-05 6.27293193873015e-07 8.04243340595066e-06 1.37496495826325e-06 3.26275777160587e-05 6.53064756495057e-06 6.27293193873015e-07 2.20332060111686e-05 1.40116676090758e-05 -9.87409153623155e-06 6.88339468759708e-06 -9.90598660639266e-06 8.04243340595066e-06 1.40116676090758e-05 0.000100691450989923 -1.59431385274629e-05 7.93437759862902e-05 -2.23459240636241e-06 1.37496495826325e-06 -9.87409153623155e-06 -1.59431385274629e-05 4.7099827187632e-05 2.42942905132738e-06 -4.39804075070137e-05 3.26275777160587e-05 6.88339468759708e-06 7.93437759862902e-05 2.42942905132738e-06 0.000359627591910973 3063 3221 0 1997 299 3063 3221 0 1930 336 0 0 0 0 0 0 0 0 1282 0 0 0 0 0 1508 +299 435 0.0312827057392075 0.999367257337515 0.0169256398203331 -0.0218450584020268 -0.996873508261392 0.0299664106781652 0.0731110303421653 -0.708145517170163 0.0725575692003228 -0.0191598327957484 0.997180174270918 0.608201157987658 8.11589188745565e-05 3.01750096233308e-05 1.57912948980835e-06 -1.57771443195936e-05 1.07072158226434e-05 4.18025879214248e-05 3.01750096233308e-05 0.000120645207985221 1.50293876862423e-05 -8.80416377238786e-06 1.53156835844696e-05 6.09401382071056e-05 1.57912948980835e-06 1.50293876862423e-05 1.67588140614873e-05 -4.21346483539547e-06 -3.16090952729278e-06 -2.25543763459091e-06 -1.57771443195936e-05 -8.80416377238786e-06 -4.21346483539547e-06 3.43814803534408e-05 -1.51359582056792e-06 2.61270335531391e-05 1.07072158226434e-05 1.53156835844696e-05 -3.16090952729278e-06 -1.51359582056792e-06 0.000233260905417784 3.39215385163442e-05 4.18025879214248e-05 6.09401382071056e-05 -2.25543763459091e-06 2.61270335531391e-05 3.39215385163442e-05 0.00045827529342047 0 0 0 1232 0 0 0 0 1243 0 0 0 0 0 0 0 0 0 0 0 424 385 0 43 121 +299 329 -0.452052737143753 0.869425669818755 0.199367318036459 0.126303941672205 -0.873555747219307 -0.476716525697484 0.0981922126598569 -0.726272244642264 0.180412525454748 -0.129770407979358 0.974992800933377 0.451010015621947 8.3899096786084e-05 2.36388501657438e-05 -4.45429473752209e-06 -2.96963484391462e-05 1.64632116671806e-05 7.6823765990534e-06 2.36388501657438e-05 0.000155772260768366 1.71948397016286e-05 -2.89235417646028e-05 2.07344017590593e-05 -8.30820533083754e-05 -4.45429473752209e-06 1.71948397016286e-05 2.4837784816797e-05 -1.79392999670435e-06 1.85069918835731e-06 -1.17400521549191e-05 -2.96963484391462e-05 -2.89235417646028e-05 -1.79392999670435e-06 6.23450154352655e-05 -3.62152877457658e-05 -2.48305445190949e-05 1.64632116671806e-05 2.07344017590593e-05 1.85069918835731e-06 -3.62152877457658e-05 0.000120627486119996 6.36628791645642e-05 7.6823765990534e-06 -8.30820533083754e-05 -1.17400521549191e-05 -2.48305445190949e-05 6.36628791645642e-05 0.000219322793952355 0 0 0 749 0 0 0 0 794 0 0 0 0 0 0 0 0 0 0 98 232 232 0 18 0 +300 303 0.99685426546623 -0.0072459961048207 0.0789244509783404 0.357173637526517 0.0100219861786518 0.999342873107369 -0.0348336297641248 0.0215751644245226 -0.0786201832535288 0.0355150321689018 0.996271824993171 -0.0258791832040919 8.67957369035698e-05 -1.32972608158878e-05 2.58569282315781e-06 7.2285738530605e-06 7.23513074900455e-06 -6.24930044388239e-06 -1.32972608158878e-05 7.26346052476875e-05 2.37461884556975e-06 1.27968218046944e-05 -1.85544456696606e-06 -2.38409571721197e-05 2.58569282315781e-06 2.37461884556975e-06 1.37089611070638e-05 2.63125520007635e-06 2.67060375015137e-07 1.77381694924697e-06 7.2285738530605e-06 1.27968218046944e-05 2.63125520007635e-06 8.66086948392779e-05 4.53425741692955e-06 -1.95345382998018e-06 7.23513074900455e-06 -1.85544456696606e-06 2.67060375015137e-07 4.53425741692955e-06 1.47174510507928e-05 -1.78722130263477e-07 -6.24930044388239e-06 -2.38409571721197e-05 1.77381694924697e-06 -1.95345382998018e-06 -1.78722130263477e-07 0.000169319308482999 2991 3024 0 381 532 2991 3024 0 333 617 0 0 0 0 0 0 0 0 2356 0 0 0 0 0 3021 +300 445 0.834799978047834 0.548552509476909 0.0468949997112943 0.467281655654723 -0.549400954379607 0.835533374399674 0.00652469087937075 -0.239630671935387 -0.0356032017958095 -0.0312109693998841 0.998878514841022 -0.0924205717361 0.00011084903866269 -3.33632583341202e-06 1.29239060949438e-05 -3.96734273227917e-06 -2.33406534542481e-05 -4.36082430449621e-05 -3.33632583341202e-06 3.68633121269728e-05 1.02102347976776e-05 1.23585028200606e-06 -4.22231975751478e-06 9.27550758844715e-06 1.29239060949438e-05 1.02102347976776e-05 2.71027145346144e-05 9.21135704686331e-06 -1.24955346977425e-05 -4.86786107876395e-06 -3.96734273227917e-06 1.23585028200606e-06 9.21135704686331e-06 0.000121211594349814 3.10057336468169e-05 1.06728790647155e-05 -2.33406534542481e-05 -4.22231975751478e-06 -1.24955346977425e-05 3.10057336468169e-05 8.6733804297075e-05 1.80508752568909e-06 -4.36082430449621e-05 9.27550758844715e-06 -4.86786107876395e-06 1.06728790647155e-05 1.80508752568909e-06 0.000202083459016235 2260 2268 0 2024 0 2260 2268 0 1976 0 0 0 0 0 0 0 0 0 1476 0 0 0 0 0 162 +300 440 0.438880685713627 0.891071493799956 0.115651790494792 0.0861031692986544 -0.898465850731888 0.433479602406942 0.0696745962725633 -0.527778262900263 0.0119523544191682 -0.134488018924492 0.990843132887141 0.144360496462078 4.70078327533169e-05 -5.38147048137609e-06 6.52280875831282e-06 -3.31628729002978e-06 -8.19641371051685e-06 -1.86352485390764e-05 -5.38147048137609e-06 5.42432641901505e-05 3.09041141798386e-06 -9.18559533208583e-06 -1.55907297371139e-05 -2.26950050261238e-05 6.52280875831282e-06 3.09041141798386e-06 1.69725456328925e-05 -1.0378829893955e-06 5.44730212521407e-06 -4.21441706931791e-07 -3.31628729002978e-06 -9.18559533208583e-06 -1.0378829893955e-06 3.9105651166039e-05 5.84143832254977e-05 -2.22292766118804e-05 -8.19641371051685e-06 -1.55907297371139e-05 5.44730212521407e-06 5.84143832254977e-05 0.000270134313948691 -0.000139115012879926 -1.86352485390764e-05 -2.26950050261238e-05 -4.21441706931791e-07 -2.22292766118804e-05 -0.000139115012879926 0.000192583478838325 134 33 0 2079 0 184 69 0 2046 0 0 0 0 0 0 0 0 0 340 0 168 158 0 0 235 +300 442 0.652363495298989 0.753992652576943 0.0769217125477054 0.219243633785601 -0.757799829452627 0.650604444719158 0.0495305460624488 -0.419659978142356 -0.0126999402697364 -0.0906031808032218 0.995806093145389 0.0233773150977892 4.20102103007135e-05 1.07374282611744e-06 6.43822580580969e-06 4.41252543595851e-06 5.07960268753455e-06 7.75644345837403e-06 1.07374282611744e-06 3.98571112835645e-05 1.711319049559e-06 -1.45631352433434e-06 -5.30306449975483e-06 1.39676618035698e-06 6.43822580580969e-06 1.711319049559e-06 1.67018115158971e-05 7.05321894447314e-07 -2.41195890789388e-06 -1.32892054899617e-06 4.41252543595851e-06 -1.45631352433434e-06 7.05321894447314e-07 2.74390594916248e-05 -1.11431032473959e-05 6.33076463874651e-06 5.07960268753455e-06 -5.30306449975483e-06 -2.41195890789388e-06 -1.11431032473959e-05 4.2475352535386e-05 -2.14001398827229e-05 7.75644345837403e-06 1.39676618035698e-06 -1.32892054899617e-06 6.33076463874651e-06 -2.14001398827229e-05 0.00017341926630603 1174 1184 0 1772 0 1251 1261 0 1738 0 0 0 0 0 0 0 0 0 933 0 26 26 0 0 209 +300 302 0.997977301111042 -0.00712428282088875 0.0631708086176499 0.239554915125311 0.00834596393230364 0.999782808970862 -0.0190965905955243 0.0136578874411988 -0.0630210389723976 0.0195851852332412 0.997820008401425 -0.0108479381105616 3.94682872471558e-05 -7.31851366240921e-06 2.36720611537611e-06 -1.576216050243e-07 5.44082104381109e-06 -1.70466461642426e-05 -7.31851366240921e-06 1.95416911159491e-05 5.23209831586071e-07 -2.42286263820485e-06 -1.69261069505168e-06 4.72926840423785e-06 2.36720611537611e-06 5.23209831586071e-07 9.92651441184422e-06 4.86715044835581e-06 1.38743138030658e-06 3.4033063287426e-06 -1.576216050243e-07 -2.42286263820485e-06 4.86715044835581e-06 8.19597866571809e-05 -7.96645824400046e-07 -8.26670541896416e-06 5.44082104381109e-06 -1.69261069505168e-06 1.38743138030658e-06 -7.96645824400046e-07 1.35118842530254e-05 -5.25921377683337e-06 -1.70466461642426e-05 4.72926840423785e-06 3.4033063287426e-06 -8.26670541896416e-06 -5.25921377683337e-06 9.75445843066866e-05 3447 3477 0 229 295 3447 3477 0 185 373 0 0 0 0 0 0 0 0 2419 0 0 0 0 0 3213 +300 441 0.556004607544463 0.825802586439415 0.0943873117495135 0.131865315179361 -0.831178307786731 0.552240236002025 0.0646014117896335 -0.474820309320195 0.00122354162736897 -0.114371368665413 0.993437312051186 0.0626730878224459 8.3427313289526e-05 -2.51519564625765e-06 2.01071469281833e-06 2.41763637110616e-07 1.60279977769652e-05 -2.06558315046027e-05 -2.51519564625765e-06 7.76942908498067e-05 7.09615418555322e-06 3.46005065942885e-06 7.37014281437132e-06 9.49188011322653e-06 2.01071469281833e-06 7.09615418555322e-06 1.65260351361394e-05 -1.02405847731295e-06 2.28909407262059e-06 -7.23545163010597e-06 2.41763637110616e-07 3.46005065942885e-06 -1.02405847731295e-06 3.47720599549444e-05 1.48108374986865e-05 3.85318882159748e-05 1.60279977769652e-05 7.37014281437132e-06 2.28909407262059e-06 1.48108374986865e-05 7.06584972333357e-05 3.50171187838164e-05 -2.06558315046027e-05 9.49188011322653e-06 -7.23545163010597e-06 3.85318882159748e-05 3.50171187838164e-05 0.000308892920351967 631 585 0 1848 0 696 650 0 1813 0 0 0 0 0 0 0 0 0 660 0 117 117 0 0 212 +300 438 0.234633420068604 0.966517172686887 0.103883170380273 0.0275509899906328 -0.9720622347077 0.23399846246094 0.0184318046047523 -0.613619327533297 -0.00649384647044942 -0.105305624100818 0.994418702303389 0.293699310750911 3.89356058697175e-05 1.31662098170026e-06 4.10166876376199e-06 -2.62665415980603e-06 -1.21932489209075e-05 3.02993345869717e-06 1.31662098170026e-06 3.58324570501282e-05 3.97730184245207e-06 -2.81908970259699e-06 -1.34271981493097e-05 -7.62071766017119e-06 4.10166876376199e-06 3.97730184245207e-06 1.34247391805187e-05 -3.42388587772401e-06 -1.64319719554908e-06 -2.0877534491467e-06 -2.62665415980603e-06 -2.81908970259699e-06 -3.42388587772401e-06 2.31264868330469e-05 2.79721038538982e-05 -2.71006633411285e-06 -1.21932489209075e-05 -1.34271981493097e-05 -1.64319719554908e-06 2.79721038538982e-05 0.000386209874200932 -5.56050650073838e-05 3.02993345869717e-06 -7.62071766017119e-06 -2.0877534491467e-06 -2.71006633411285e-06 -5.56050650073838e-05 0.000105774106225672 0 0 0 2456 0 0 0 0 2485 0 0 0 0 0 0 0 0 0 0 0 345 339 0 21 157 +300 448 0.936040867758574 0.349759365338731 0.0386766110669619 0.679594966976165 -0.351362925024314 0.934993749084671 0.0482781947772406 -0.0855574860033837 -0.0192766388184011 -0.0587798905276212 0.998084833902122 -0.129800223047484 6.29665649081487e-05 -1.19571772874138e-05 6.42158815747092e-06 -1.11443522311712e-05 -7.53080129524588e-06 -3.46621685063927e-05 -1.19571772874138e-05 4.04212152407132e-05 5.30384693187676e-07 -1.23687674992145e-06 -1.1663431979989e-06 3.0377622831659e-06 6.42158815747092e-06 5.30384693187676e-07 1.95487046874593e-05 9.39061643910387e-06 -7.62089239828996e-06 -1.17109921743296e-06 -1.11443522311712e-05 -1.23687674992145e-06 9.39061643910387e-06 9.85326628178673e-05 -9.25739056304039e-06 3.94474373988297e-05 -7.53080129524588e-06 -1.1663431979989e-06 -7.62089239828996e-06 -9.25739056304039e-06 4.34255320910751e-05 2.38441576547324e-06 -3.46621685063927e-05 3.0377622831659e-06 -1.17109921743296e-06 3.94474373988297e-05 2.38441576547324e-06 0.000330607411887112 3122 3280 0 1843 250 3122 3280 0 1781 305 0 0 0 0 0 0 0 0 1782 0 0 0 0 0 1569 +300 439 0.33080441786532 0.936792236769519 0.113968163313921 0.0309891860154921 -0.943436660365834 0.325442565826867 0.0633593262731561 -0.579627174645487 0.0222644334881817 -0.128481288429044 0.991461977851427 0.224852759960632 3.60231519407739e-05 -5.26296044914014e-06 2.04630119527419e-06 -1.52272832437104e-07 8.36923802904865e-06 4.58669178771435e-06 -5.26296044914014e-06 3.97933777111654e-05 6.85315267014453e-06 6.3525421862967e-07 4.36131463555878e-06 -8.32630873128674e-06 2.04630119527419e-06 6.85315267014453e-06 1.5166291993753e-05 -5.81115404332979e-07 4.24768178944627e-06 -2.0146987214301e-06 -1.52272832437104e-07 6.3525421862967e-07 -5.81115404332979e-07 2.55628761464207e-05 2.28716701812169e-05 6.54645577932559e-06 8.36923802904865e-06 4.36131463555878e-06 4.24768178944627e-06 2.28716701812169e-05 0.000183049082237716 -4.72333836256663e-05 4.58669178771435e-06 -8.32630873128674e-06 -2.0146987214301e-06 6.54645577932559e-06 -4.72333836256663e-05 0.000148422156309823 0 0 0 2355 0 0 0 0 2340 0 0 0 0 0 0 0 0 0 90 0 225 199 0 2 197 +300 436 0.130338518163969 0.990990516041654 0.0308166805207235 -0.0768953788524289 -0.991217229114342 0.129541206594221 0.0265985056158895 -0.695119225983823 0.0223668368283441 -0.0340128344836045 0.999171082298064 0.498128123909663 8.79615286995798e-05 2.63274128296119e-06 5.25307807814339e-06 -4.6262134999262e-06 8.49104646686714e-06 1.17441800623505e-05 2.63274128296119e-06 7.23945126410927e-05 7.11620694643164e-06 7.52108700377719e-06 -2.83400423144379e-05 5.2671174343299e-05 5.25307807814339e-06 7.11620694643164e-06 1.64323273922998e-05 8.15679556899028e-08 2.97607222803818e-06 -8.46219718562301e-06 -4.6262134999262e-06 7.52108700377719e-06 8.15679556899028e-08 2.79225066624591e-05 -2.45645391183195e-06 1.10712565119603e-05 8.49104646686714e-06 -2.83400423144379e-05 2.97607222803818e-06 -2.45645391183195e-06 0.000380411504460068 -9.96991919491276e-05 1.17441800623505e-05 5.2671174343299e-05 -8.46219718562301e-06 1.10712565119603e-05 -9.96991919491276e-05 0.00032296553802985 0 0 0 1491 0 0 0 0 1512 0 0 0 0 0 0 0 0 0 0 0 346 317 0 91 191 +301 303 0.997928814034915 -0.0144282401819904 0.0626889783304698 0.230643124399409 0.0160101144562179 0.99956409769674 -0.0248050565570936 0.0160624495666633 -0.0623037587466929 0.0257573383903036 0.997724812343104 0.00252672398900772 5.71556506945284e-05 -2.03687926365721e-05 -7.20745494858502e-07 -1.16720952646052e-06 6.53141360891603e-06 -3.9805905921256e-05 -2.03687926365721e-05 3.36680656801542e-05 2.43827621294541e-06 2.61952049099578e-06 -4.22508259761327e-06 2.65030016334505e-05 -7.20745494858502e-07 2.43827621294541e-06 1.21892085565513e-05 3.27221349243767e-06 1.52010102479603e-06 6.10974057013539e-06 -1.16720952646052e-06 2.61952049099578e-06 3.27221349243767e-06 7.38647440768112e-05 1.67362023432136e-06 1.10461216093135e-05 6.53141360891603e-06 -4.22508259761327e-06 1.52010102479603e-06 1.67362023432136e-06 1.46197650041151e-05 -4.58827458959596e-06 -3.9805905921256e-05 2.65030016334505e-05 6.10974057013539e-06 1.10461216093135e-05 -4.58827458959596e-06 0.000211364443172952 3244 3277 0 183 311 3244 3277 0 143 391 0 0 0 0 0 0 0 0 2564 0 0 0 0 0 3198 +300 329 -0.421321315925738 0.890288475878879 0.172843219317007 0.00311518385052268 -0.891154748632792 -0.441784822608622 0.103292712724056 -0.727885167384922 0.168319822765562 -0.110510634012892 0.979518165749997 0.42959733485332 5.39869954866574e-05 -1.15281262743708e-06 -3.79548089467597e-06 -4.14037605041322e-06 -7.0291692925576e-06 8.54994780255484e-06 -1.15281262743708e-06 0.000136806209011069 2.3625356291174e-05 8.39503866284568e-07 -1.6224665412132e-05 -0.000109169140251245 -3.79548089467597e-06 2.3625356291174e-05 2.18013480033308e-05 -7.00897957572343e-07 -2.84320683185882e-07 -1.92426411937677e-05 -4.14037605041322e-06 8.39503866284568e-07 -7.00897957572343e-07 6.85090945971729e-05 -5.34384593564713e-05 7.17525648879869e-06 -7.0291692925576e-06 -1.6224665412132e-05 -2.84320683185882e-07 -5.34384593564713e-05 0.000140308474927212 4.6187280319876e-05 8.54994780255484e-06 -0.000109169140251245 -1.92426411937677e-05 7.17525648879869e-06 4.6187280319876e-05 0.000327523392001229 0 0 0 703 0 0 0 0 733 0 0 0 0 0 0 0 0 0 0 91 376 376 0 88 0 +301 442 0.656979703006719 0.751173477752681 0.0641566532648428 0.108092028947621 -0.753886318769733 0.65522676335417 0.0483043161243203 -0.420477480615496 -0.00575223513278807 -0.0801017784157172 0.996770092290904 0.0330841417887466 5.45327848466755e-05 -1.22469528796349e-05 2.99264009368158e-06 -8.40706709154168e-07 9.54604094012077e-06 -2.26450248542346e-05 -1.22469528796349e-05 4.97817686913356e-05 3.74288353848932e-06 -3.49178013487941e-07 -1.31466239003321e-06 -9.03272528140479e-06 2.99264009368158e-06 3.74288353848932e-06 1.54812934724425e-05 1.6278787216519e-06 -1.77793169567023e-06 2.12160632450522e-06 -8.40706709154168e-07 -3.49178013487941e-07 1.6278787216519e-06 3.8098071513159e-05 5.53626002212279e-06 1.54675800813317e-05 9.54604094012077e-06 -1.31466239003321e-06 -1.77793169567023e-06 5.53626002212279e-06 5.3031280576574e-05 -5.20094014582545e-06 -2.26450248542346e-05 -9.03272528140479e-06 2.12160632450522e-06 1.54675800813317e-05 -5.20094014582545e-06 0.000151916026106724 1011 1021 0 1756 0 1082 1092 0 1732 0 0 0 0 0 0 0 0 0 1041 0 194 194 0 0 144 +301 438 0.240935233187921 0.965949468522744 0.0942965411312108 -0.0949795313130112 -0.9705023883677 0.240654606118614 0.0145077471195529 -0.621447626309766 -0.0086791463446847 -0.095010445817934 0.995438439886769 0.324095972277653 4.47077991569773e-05 1.29279983373941e-06 2.44045627712374e-06 -8.29148731047791e-07 -5.1671595744939e-06 2.62854454106561e-06 1.29279983373941e-06 5.86792769813926e-05 9.26046947603995e-06 -1.71764367095555e-06 -2.25307063145195e-05 3.39642455672664e-06 2.44045627712374e-06 9.26046947603995e-06 1.45886436361019e-05 -2.53769681985705e-06 -7.12472858950509e-06 -1.87858185662848e-06 -8.29148731047791e-07 -1.71764367095555e-06 -2.53769681985705e-06 2.43245746052491e-05 3.32139530904284e-05 1.28777082988113e-05 -5.1671595744939e-06 -2.25307063145195e-05 -7.12472858950509e-06 3.32139530904284e-05 0.000469467562516646 5.54395157073514e-05 2.62854454106561e-06 3.39642455672664e-06 -1.87858185662848e-06 1.28777082988113e-05 5.54395157073514e-05 0.000246973519188317 0 0 0 2236 0 0 0 0 2257 0 0 0 0 0 0 0 0 0 7 0 326 320 0 91 176 +301 327 -0.33035821686081 0.939476172522733 0.0908183341323842 0.0118584701069709 -0.930372070941463 -0.340333893461668 0.136310860071073 -0.70193052363518 0.15896936234583 -0.0394634289343571 0.986494490411428 0.283455857728534 4.96087508310353e-05 9.0974169045982e-07 6.53957440034992e-06 -4.0532875925296e-06 -1.17004269598573e-05 -7.64639883473813e-06 9.0974169045982e-07 3.95056738722045e-05 2.90669847801909e-06 -2.23941670732284e-06 1.04755517218525e-05 8.30304558488921e-06 6.53957440034992e-06 2.90669847801909e-06 1.66892175736579e-05 1.34030783098427e-06 -5.19482895580167e-07 5.97355325218823e-06 -4.0532875925296e-06 -2.23941670732284e-06 1.34030783098427e-06 4.77641985797513e-05 -1.87068611698919e-05 9.88001996708679e-06 -1.17004269598573e-05 1.04755517218525e-05 -5.19482895580167e-07 -1.87068611698919e-05 9.33469466089949e-05 2.21027847688114e-05 -7.64639883473813e-06 8.30304558488921e-06 5.97355325218823e-06 9.88001996708679e-06 2.21027847688114e-05 0.000157184141587266 0 0 0 1033 0 0 0 0 1077 0 0 0 0 0 0 0 0 0 0 2 245 245 0 72 0 +301 439 0.335998058545536 0.938208799217126 0.0828827709791896 -0.0704665646047188 -0.940615247981371 0.329723763745491 0.0807786784148591 -0.579041607748646 0.0484588476810374 -0.10510227729724 0.993280046808733 0.214099552630218 9.25111373783173e-05 -2.68091367742338e-05 -2.05699080765144e-06 -7.05604431958213e-06 2.00034855706069e-05 -4.37469317374411e-05 -2.68091367742338e-05 5.99296084457873e-05 6.5998382602505e-06 8.83911054353453e-07 -1.18206156022427e-05 1.25695281349579e-05 -2.05699080765144e-06 6.5998382602505e-06 1.49614803187567e-05 -5.97268670221724e-07 1.29446486895301e-06 2.302501204971e-07 -7.05604431958213e-06 8.83911054353453e-07 -5.97268670221724e-07 2.71475803786242e-05 2.50239585063803e-05 9.47806862988829e-06 2.00034855706069e-05 -1.18206156022427e-05 1.29446486895301e-06 2.50239585063803e-05 0.000204948340117808 -4.98670135512936e-05 -4.37469317374411e-05 1.25695281349579e-05 2.302501204971e-07 9.47806862988829e-06 -4.98670135512936e-05 0.00022796885725551 0 0 0 2204 0 0 0 0 2214 0 0 0 0 0 0 0 0 0 165 0 166 157 0 15 144 +301 440 0.445228332622938 0.890317347665454 0.0954293051203294 -0.0153954130409008 -0.894936449350896 0.438963556178654 0.0799984247982414 -0.530210938337647 0.0293339982445069 -0.121020728773793 0.992216458114887 0.154835281108053 7.34235976988369e-05 -6.01636267304677e-06 1.14208394990305e-05 6.311016678073e-06 8.4461190598904e-06 -1.79230084800559e-05 -6.01636267304677e-06 7.02043277289704e-05 9.09214246119704e-06 2.21936784102416e-06 -1.36948360408292e-05 4.29389760284912e-05 1.14208394990305e-05 9.09214246119704e-06 2.44635139148318e-05 8.88020517940787e-06 8.28338948301485e-06 1.28712246328182e-05 6.311016678073e-06 2.21936784102416e-06 8.88020517940787e-06 5.44610504893863e-05 6.1014820351665e-05 3.67164322167031e-06 8.4461190598904e-06 -1.36948360408292e-05 8.28338948301485e-06 6.1014820351665e-05 0.000236460095224632 -9.02244726914605e-05 -1.79230084800559e-05 4.29389760284912e-05 1.28712246328182e-05 3.67164322167031e-06 -9.02244726914605e-05 0.000292480171177953 40 0 0 1964 0 91 12 0 1939 0 0 0 0 0 0 0 0 0 436 0 306 272 0 0 121 +301 329 -0.418866562833986 0.895731716156839 0.149048633708483 -0.127431983781714 -0.893372366931119 -0.435898610029159 0.108987227593586 -0.7339137253109 0.162593408671852 -0.0875048252690664 0.982805315925335 0.441775359220896 7.57947885635064e-05 1.34144799861256e-05 -6.11473257312979e-08 -6.81097141964306e-06 -8.32000414146762e-06 5.81714108384166e-07 1.34144799861256e-05 8.86189106811982e-05 1.39467602925804e-05 -9.4604560439314e-06 1.68767608683966e-05 -2.11857420524833e-06 -6.11473257312979e-08 1.39467602925804e-05 2.18741196678219e-05 -1.2580608367879e-06 -3.46459474378997e-07 -1.81057779758296e-06 -6.81097141964306e-06 -9.4604560439314e-06 -1.2580608367879e-06 7.62229302118018e-05 -7.22965782775806e-05 -2.29500712559254e-05 -8.32000414146762e-06 1.68767608683966e-05 -3.46459474378997e-07 -7.22965782775806e-05 0.00016680349959328 6.13876896035007e-05 5.81714108384166e-07 -2.11857420524833e-06 -1.81057779758296e-06 -2.29500712559254e-05 6.13876896035007e-05 0.000168928752991236 0 0 0 613 0 0 0 0 642 0 0 0 0 0 0 0 0 0 0 44 448 448 0 173 0 +301 448 0.938435454984186 0.344323960741783 0.0279268130604783 0.563967643742447 -0.345316131963183 0.937277852362619 0.0476129864270416 -0.0835707578971398 -0.00978089129935371 -0.0543252936449199 0.998475386094111 -0.0985361505236159 9.83184155137863e-05 -2.29615953360644e-05 1.5429442854258e-07 -1.14120758554505e-06 5.49118845172328e-06 5.08530325456359e-06 -2.29615953360644e-05 8.69652234290498e-05 3.86138620541621e-06 2.93868018075806e-05 5.48698587146806e-06 0.000143380333238585 1.5429442854258e-07 3.86138620541621e-06 1.77749956230289e-05 9.52938161163702e-06 -7.2969297256357e-06 1.01069565986369e-05 -1.14120758554505e-06 2.93868018075806e-05 9.52938161163702e-06 0.000113509147163126 2.49106812573847e-06 0.000158816110961517 5.49118845172328e-06 5.48698587146806e-06 -7.2969297256357e-06 2.49106812573847e-06 4.52368730563632e-05 1.88231960255312e-05 5.08530325456359e-06 0.000143380333238585 1.01069565986369e-05 0.000158816110961517 1.88231960255312e-05 0.000914833572151941 3086 3244 0 1617 0 3086 3244 0 1574 94 0 0 0 0 0 0 0 0 2033 0 0 0 0 0 1754 +301 328 -0.376500147882491 0.916968331935688 0.131972409508747 -0.0624817876136373 -0.913572622090751 -0.391132639482398 0.111356735304889 -0.724193809487973 0.153729316692336 -0.078640552888538 0.98497865998746 0.392812166456988 6.36086991969653e-05 8.37951305673774e-06 8.60816796862087e-06 -5.06537124738136e-06 8.02163949393324e-07 1.57284613221872e-05 8.37951305673774e-06 5.91080603006783e-05 1.49110370217916e-05 7.25836867599426e-06 -2.26760306665193e-06 -1.9377858205742e-07 8.60816796862087e-06 1.49110370217916e-05 2.16130613339087e-05 3.47439428280436e-06 -8.3706952837471e-07 -9.02262093816545e-07 -5.06537124738136e-06 7.25836867599426e-06 3.47439428280436e-06 6.38007926240034e-05 -4.19031602283832e-05 2.90322256287372e-05 8.02163949393324e-07 -2.26760306665193e-06 -8.3706952837471e-07 -4.19031602283832e-05 0.000119091592017211 -2.90592062469097e-05 1.57284613221872e-05 -1.9377858205742e-07 -9.02262093816545e-07 2.90322256287372e-05 -2.90592062469097e-05 0.000142994329084332 0 0 0 772 0 0 0 0 810 0 0 0 0 0 0 0 0 0 0 20 227 227 0 123 0 +302 444 0.790799725591484 0.612062428588817 -0.00392141739586378 0.157977220701392 -0.611995346710297 0.790783948685826 0.0110653561079848 -0.318952282864517 0.00987368266539973 -0.00635059137498899 0.999931087815461 -0.03400288905558 8.56343676667426e-05 8.32223478443051e-07 8.56874564190128e-06 -3.50007845772984e-06 -1.13194693158277e-05 1.2276791117472e-05 8.32223478443051e-07 6.48442289567363e-05 4.59229535352046e-06 -2.53102769577756e-05 -2.20776587097998e-05 3.34598084463438e-05 8.56874564190128e-06 4.59229535352046e-06 1.95814272538448e-05 6.61974183978232e-06 -2.4830100054794e-06 1.19636585247383e-06 -3.50007845772984e-06 -2.53102769577756e-05 6.61974183978232e-06 6.74442664088735e-05 1.23264508965283e-05 -5.03128757268106e-05 -1.13194693158277e-05 -2.20776587097998e-05 -2.4830100054794e-06 1.23264508965283e-05 4.69848193906794e-05 -5.99749341863117e-05 1.2276791117472e-05 3.34598084463438e-05 1.19636585247383e-06 -5.03128757268106e-05 -5.99749341863117e-05 0.000267808049822554 1550 1564 0 1906 0 1618 1632 0 1867 0 0 0 0 0 0 0 0 0 1631 0 326 326 0 0 120 +302 445 0.831713017986967 0.555189445706812 -0.00425853105816363 0.239413798827208 -0.554992965843946 0.831582112477961 0.021307230473068 -0.255335312718417 0.0153708677292906 -0.0153580461795905 0.999763905551103 -0.0359117256371393 5.92822331352421e-05 -8.96377499141131e-06 -1.35955499080562e-06 -3.14483038123704e-06 9.10267621615396e-07 -9.93153368119999e-06 -8.96377499141131e-06 2.76528969073953e-05 2.54372501636015e-06 2.54605287556543e-06 -1.0058121424182e-07 1.73172158936896e-05 -1.35955499080562e-06 2.54372501636015e-06 1.3795856972022e-05 4.72137273722039e-06 -6.96178403842942e-07 1.72984701661049e-07 -3.14483038123704e-06 2.54605287556543e-06 4.72137273722039e-06 4.46717531437273e-05 -8.47897583132022e-06 2.14736008751951e-05 9.10267621615396e-07 -1.0058121424182e-07 -6.96178403842942e-07 -8.47897583132022e-06 2.4763993718497e-05 2.68383746914282e-06 -9.93153368119999e-06 1.73172158936896e-05 1.72984701661049e-07 2.14736008751951e-05 2.68383746914282e-06 0.000179012859670049 1946 1954 0 1877 0 2026 2034 0 1837 0 0 0 0 0 0 0 0 0 1772 0 289 289 0 0 136 +302 440 0.430544730679153 0.901056868757431 0.0522279058499414 -0.156786281178125 -0.900399966502174 0.424780715331519 0.0940278905715041 -0.535879166406265 0.0625390694470205 -0.0875092175002031 0.994198673125851 0.142437272143572 8.21620477000373e-05 -6.60711451760609e-06 4.63417504260565e-06 -3.68691180056262e-06 2.66207017263591e-06 -2.69964612279957e-05 -6.60711451760609e-06 5.21567301307678e-05 4.20651710763244e-06 -5.0269668198212e-06 -1.18894180603709e-05 -6.34410784675131e-06 4.63417504260565e-06 4.20651710763244e-06 1.64731116584849e-05 -1.4658181210461e-06 2.41373501628741e-06 -3.51989285468235e-06 -3.68691180056262e-06 -5.0269668198212e-06 -1.4658181210461e-06 3.87444823104352e-05 4.60849671985793e-05 -6.19320073872762e-06 2.66207017263591e-06 -1.18894180603709e-05 2.41373501628741e-06 4.60849671985793e-05 0.000179288193113605 -4.00956747424381e-05 -2.69964612279957e-05 -6.34410784675131e-06 -3.51989285468235e-06 -6.19320073872762e-06 -4.00956747424381e-05 0.000120477625633683 0 0 0 2013 0 2 0 0 2010 0 0 0 0 0 0 0 0 0 550 0 515 388 0 5 147 +302 442 0.646550408419503 0.762280877688783 0.0300072138425412 -0.0111328820600185 -0.762431548121446 0.644342328081289 0.0593388462300957 -0.430222191046521 0.025897949758781 -0.0612440017699905 0.997786785062565 0.0557016521336224 0.000116631206820574 -5.64539624242199e-05 -3.96160222701677e-06 1.08195267691818e-05 4.57260906009823e-05 -0.000138275980481078 -5.64539624242199e-05 0.0001060525549822 1.01646628064383e-05 -2.90349707856505e-05 -5.98310048764406e-05 0.000152737097519184 -3.96160222701677e-06 1.01646628064383e-05 1.86532065358695e-05 -2.1155457046223e-06 -9.51486493395398e-06 2.15675466015025e-05 1.08195267691818e-05 -2.90349707856505e-05 -2.1155457046223e-06 4.36225723692548e-05 2.81759303900959e-05 -7.33868358104042e-05 4.57260906009823e-05 -5.98310048764406e-05 -9.51486493395398e-06 2.81759303900959e-05 0.000127380085350572 -0.000252602218608691 -0.000138275980481078 0.000152737097519184 2.15675466015025e-05 -7.33868358104042e-05 -0.000252602218608691 0.000886218981472518 838 848 0 1806 0 888 898 0 1780 0 0 0 0 0 0 0 0 0 1198 0 388 388 0 0 48 +302 441 0.548900313206963 0.834590713487779 0.0465487606844433 -0.0907299951561696 -0.83491767733852 0.544730264803585 0.0786219477923803 -0.483770995258226 0.0402606287699261 -0.082019994921821 0.995817152997514 0.114107973083554 4.43579058934158e-05 -1.09814154777682e-05 9.03794041493954e-07 -9.55298053513508e-07 3.81789742790158e-06 -3.66990981264515e-06 -1.09814154777682e-05 4.97282837096206e-05 2.40742890395132e-06 3.52063060044442e-06 -9.59611846832416e-07 -4.04666650791548e-07 9.03794041493954e-07 2.40742890395132e-06 1.38454681472602e-05 -2.25771245850507e-06 3.63888900206389e-07 -4.01232917889553e-06 -9.55298053513508e-07 3.52063060044442e-06 -2.25771245850507e-06 2.73928570660027e-05 9.4058353877894e-06 2.62261522344056e-05 3.81789742790158e-06 -9.59611846832416e-07 3.63888900206389e-07 9.4058353877894e-06 5.73810777775165e-05 4.19208069908584e-05 -3.66990981264515e-06 -4.04666650791548e-07 -4.01232917889553e-06 2.62261522344056e-05 4.19208069908584e-05 0.000229189079148814 366 320 0 1956 0 410 364 0 1926 0 0 0 0 0 0 0 0 0 890 0 414 414 0 0 90 +302 439 0.320272266703852 0.946122342896197 0.0477303619616297 -0.208720177189245 -0.945481045505201 0.31610010429763 0.0783984480294015 -0.584919354148057 0.0590869509347683 -0.0702370011862639 0.995778838846053 0.199053931651165 0.000192143103856113 -3.78576254519331e-05 3.53380561461285e-06 -5.66274288208071e-06 6.37392191380025e-05 -0.000212819421805659 -3.78576254519331e-05 6.32721994696973e-05 1.3937329029151e-05 5.63699431191448e-06 -2.24065944051504e-05 2.7831782117074e-05 3.53380561461285e-06 1.3937329029151e-05 1.67039097896404e-05 -6.12842051335908e-07 -1.20148216070616e-06 -1.07010945579635e-05 -5.66274288208071e-06 5.63699431191448e-06 -6.12842051335908e-07 2.33816943459375e-05 9.80310241821688e-06 1.16469276181433e-05 6.37392191380025e-05 -2.24065944051504e-05 -1.20148216070616e-06 9.80310241821688e-06 0.000178125821232083 -0.000153463619029657 -0.000212819421805659 2.7831782117074e-05 -1.07010945579635e-05 1.16469276181433e-05 -0.000153463619029657 0.000559745356586444 0 0 0 2175 0 0 0 0 2181 0 0 0 0 0 0 0 0 0 236 0 153 153 0 114 94 +302 438 0.226639035294387 0.973076734339702 0.0419096261926873 -0.225507402911561 -0.973608926895586 0.225157354390282 0.0372803330617466 -0.617545379231955 0.0268403641937897 -0.0492527649046251 0.998425640695988 0.320697080237473 4.73808013463763e-05 -2.30308254152749e-06 -1.3114324912407e-06 -1.27778401250364e-06 1.05138446425993e-05 1.17047691573925e-05 -2.30308254152749e-06 5.26066996386138e-05 3.57132640182341e-06 1.12687579514589e-06 4.91648475171123e-06 -9.47284081799016e-06 -1.3114324912407e-06 3.57132640182341e-06 1.32429192184317e-05 -1.34033113909905e-06 1.17965039938114e-06 -4.69413847667809e-06 -1.27778401250364e-06 1.12687579514589e-06 -1.34033113909905e-06 2.17520302262604e-05 1.02500633311856e-05 7.1427169625494e-06 1.05138446425993e-05 4.91648475171123e-06 1.17965039938114e-06 1.02500633311856e-05 0.000176525477964167 4.56111376542041e-05 1.17047691573925e-05 -9.47284081799016e-06 -4.69413847667809e-06 7.1427169625494e-06 4.56111376542041e-05 0.000203179760554304 0 0 0 2080 0 0 0 0 2097 0 0 0 0 0 0 0 0 0 39 0 249 246 0 185 140 +302 305 0.997389622515855 0.0597913046355222 0.0404838336581631 0.305342806790459 -0.0600732551406236 0.998177218467933 0.00578312618137238 0.00398123440159099 -0.0400642598145676 -0.00820002570741795 0.999163457430219 -0.0236530647536211 4.78334057949307e-05 -1.03581357553761e-05 1.08837054332206e-05 -8.91317131802127e-06 -5.12362163520543e-07 -2.72627030626059e-06 -1.03581357553761e-05 5.23948225032984e-05 2.24125469569405e-06 -1.44947725165243e-05 -5.32514811402945e-06 8.33642910348221e-05 1.08837054332206e-05 2.24125469569405e-06 1.63736911738075e-05 3.3094133820563e-06 -2.10780930076999e-06 4.89345365725417e-06 -8.91317131802127e-06 -1.44947725165243e-05 3.3094133820563e-06 7.72043008915633e-05 5.02813534951768e-07 -5.29679052299092e-05 -5.12362163520543e-07 -5.32514811402945e-06 -2.10780930076999e-06 5.02813534951768e-07 2.13977540703267e-05 -2.49683185846511e-05 -2.72627030626059e-06 8.33642910348221e-05 4.89345365725417e-06 -5.29679052299092e-05 -2.49683185846511e-05 0.000583959904699303 3473 3526 0 507 241 3473 3526 0 464 329 0 0 0 0 0 0 0 0 2825 0 0 0 0 0 3150 +302 446 0.869961741278117 0.492967368453859 -0.0122369257587009 0.309202913621436 -0.492788518045381 0.870019258914607 0.0150321522183223 -0.199306487933964 0.0180567216012423 -0.00704718080894778 0.999812128375957 -0.0846587189504296 0.000114720224771602 -8.43580165690093e-06 -1.14054886710938e-06 -2.61816244621501e-05 -6.45978744753138e-06 -6.32509946945857e-05 -8.43580165690093e-06 3.7230882803296e-05 3.45007753202761e-06 1.70927757768155e-06 -5.09798074952233e-07 6.55256130236026e-06 -1.14054886710938e-06 3.45007753202761e-06 1.63112828690739e-05 6.37536610192272e-06 -2.87632959741812e-06 -1.71621181596892e-07 -2.61816244621501e-05 1.70927757768155e-06 6.37536610192272e-06 6.60799959597254e-05 -1.44406052067335e-06 3.12544090522949e-05 -6.45978744753138e-06 -5.09798074952233e-07 -2.87632959741812e-06 -1.44406052067335e-06 3.23451253437046e-05 1.42720177047102e-05 -6.32509946945857e-05 6.55256130236026e-06 -1.71621181596892e-07 3.12544090522949e-05 1.42720177047102e-05 0.000290436727027664 2251 2283 0 1726 0 2342 2374 0 1685 0 0 0 0 0 0 0 0 0 1912 0 309 309 0 0 482 +302 448 0.931922703066427 0.361771682702447 -0.0253243974065351 0.456744111844816 -0.359554427063443 0.930809226742454 0.0656871173838071 -0.10035724722718 0.0473359217555087 -0.0521098167887255 0.997518860726855 -0.101689527158325 0.000154244070952794 -5.4376410696386e-05 -6.57981387170858e-06 -2.18372641116439e-05 1.51416516808301e-05 -0.00024631666214738 -5.4376410696386e-05 6.25093253404651e-05 1.72236407212685e-06 3.6480769902263e-05 -4.66063160832618e-07 0.000200127460728031 -6.57981387170858e-06 1.72236407212685e-06 1.68571814053214e-05 1.25752570364756e-05 -2.90714915866501e-06 3.69772367774128e-05 -2.18372641116439e-05 3.6480769902263e-05 1.25752570364756e-05 0.000194063132657072 2.68945863053628e-05 0.000294512326757158 1.51416516808301e-05 -4.66063160832618e-07 -2.90714915866501e-06 2.68945863053628e-05 4.43981496769204e-05 -1.45725484149649e-05 -0.00024631666214738 0.000200127460728031 3.69772367774128e-05 0.000294512326757158 -1.45725484149649e-05 0.00164770462008084 3026 3054 0 1595 0 3129 3157 0 1546 0 0 0 0 0 0 0 0 0 2131 0 13 146 0 0 1866 +302 447 0.90535162981413 0.424606035010061 -0.00693840226086731 0.403099313493855 -0.423909337525917 0.904597633002522 0.0447660130520152 -0.144411608440233 0.0252843815672247 -0.03758772937103 0.998973404375458 -0.0615926758098751 6.45016800970212e-05 -1.32725585217004e-05 9.89911143233298e-06 7.3952519987147e-06 -2.17868977891297e-06 -1.29038487384458e-05 -1.32725585217004e-05 4.29339259242071e-05 -5.00210467093107e-07 -4.22431892309649e-06 1.22702697674832e-06 -6.54227336510162e-06 9.89911143233298e-06 -5.00210467093107e-07 2.15943528150068e-05 3.29603173432997e-06 -7.88014460152693e-06 -7.58931247913799e-06 7.3952519987147e-06 -4.22431892309649e-06 3.29603173432997e-06 8.85100107168043e-05 2.09992995574533e-05 1.40335804700176e-05 -2.17868977891297e-06 1.22702697674832e-06 -7.88014460152693e-06 2.09992995574533e-05 5.35971676306931e-05 1.95162447325235e-05 -1.29038487384458e-05 -6.54227336510162e-06 -7.58931247913799e-06 1.40335804700176e-05 1.95162447325235e-05 0.00015670651610924 2604 2639 0 1727 0 2706 2741 0 1684 0 0 0 0 0 0 0 0 0 2020 0 302 328 0 0 956 +302 449 0.954651647677227 0.297163735325777 -0.0182741892949318 0.560226511844753 -0.295871835550722 0.953758287132512 0.052962124710997 -0.0504630065736636 0.033167582290579 -0.0451535616899473 0.998429300126809 -0.0571197154247753 8.45901762301599e-05 -1.58716933002551e-05 -4.12788428403764e-06 -1.38770934802636e-05 -3.33462729195833e-06 -2.14058767730209e-05 -1.58716933002551e-05 5.66513931476506e-05 -1.62767347205473e-06 2.69890982987403e-05 8.70104801574515e-06 8.32356656849568e-05 -4.12788428403764e-06 -1.62767347205473e-06 1.54266924317925e-05 4.68513873885936e-06 -2.28774603489062e-06 -3.34286170674849e-06 -1.38770934802636e-05 2.69890982987403e-05 4.68513873885936e-06 0.000169601417589547 2.61479908513546e-05 0.000181674842534577 -3.33462729195833e-06 8.70104801574515e-06 -2.28774603489062e-06 2.61479908513546e-05 3.69619665330356e-05 5.27095302847688e-05 -2.14058767730209e-05 8.32356656849568e-05 -3.34286170674849e-06 0.000181674842534577 5.27095302847688e-05 0.000713126581368579 3150 3281 0 1527 114 3150 3281 0 1477 227 0 0 0 0 0 0 0 0 2213 0 0 0 0 0 2834 +302 329 -0.437293345191082 0.891484335882594 0.118449183735317 -0.267411151365009 -0.88632244757634 -0.449530073741157 0.111154090003729 -0.73574160250288 0.152338600406725 -0.0563772265923049 0.986719088265693 0.477408620048522 0.000115579230444649 4.7201487567076e-06 1.13590294857471e-07 -4.9541451969388e-07 -2.42962184119984e-05 3.79469723756652e-05 4.7201487567076e-06 0.000162238070916947 1.78068470512727e-05 5.33494158387852e-06 -2.80412449735725e-05 -8.27920734547423e-05 1.13590294857471e-07 1.78068470512727e-05 1.79000422724249e-05 -3.09243515286888e-06 -4.56387665040567e-06 -8.15813636416647e-06 -4.9541451969388e-07 5.33494158387852e-06 -3.09243515286888e-06 4.50141549874056e-05 -2.35107580206012e-05 2.81230370128703e-05 -2.42962184119984e-05 -2.80412449735725e-05 -4.56387665040567e-06 -2.35107580206012e-05 9.21957885259392e-05 5.83955701695489e-05 3.79469723756652e-05 -8.27920734547423e-05 -8.15813636416647e-06 2.81230370128703e-05 5.83955701695489e-05 0.000491377509162316 0 0 0 526 0 0 0 0 545 0 0 0 0 0 0 0 0 0 0 18 311 311 0 215 0 +302 328 -0.395786308775029 0.914558407473346 0.0832833543155809 -0.208742136552764 -0.904732643607736 -0.403869292839233 0.135456405873234 -0.72232383652043 0.157518384250201 -0.0217373784379559 0.987276782367463 0.364558771400493 4.98683098561988e-05 4.51243186038085e-07 2.7077943868148e-06 -1.22980242823866e-05 1.02579638320555e-05 5.90345332756558e-06 4.51243186038085e-07 4.53019082625954e-05 1.14412231924141e-05 -8.97234023193159e-06 2.53069157752547e-05 -2.78100304687785e-07 2.7077943868148e-06 1.14412231924141e-05 1.82969209890824e-05 -1.92991138752209e-06 6.05883592293157e-06 -4.2829125788389e-06 -1.22980242823866e-05 -8.97234023193159e-06 -1.92991138752209e-06 6.38136801816287e-05 -6.52474262746272e-05 -1.54724474982859e-05 1.02579638320555e-05 2.53069157752547e-05 6.05883592293157e-06 -6.52474262746272e-05 0.000181966799400261 4.51431754188162e-05 5.90345332756558e-06 -2.78100304687785e-07 -4.2829125788389e-06 -1.54724474982859e-05 4.51431754188162e-05 0.00014907432775655 0 0 0 702 0 0 0 0 728 0 0 0 0 0 0 0 0 0 0 15 179 179 0 203 0 +302 452 0.994332028804352 0.0991542897493153 -0.0383698230140525 0.853596809479257 -0.0997813422610511 0.994899564683631 -0.0147830960527565 0.0620671572888815 0.0367083128242618 0.0185278983328081 0.999154250730569 -0.051771553373699 6.87891891638724e-05 -1.50729663903545e-05 1.36010512038845e-06 2.07392773899659e-06 7.74734388720458e-06 8.23209095820977e-06 -1.50729663903545e-05 4.93095160085443e-05 -2.33380823759752e-07 -2.57868976741401e-05 -3.97700385714351e-06 2.04830942231409e-05 1.36010512038845e-06 -2.33380823759752e-07 1.70325026412577e-05 9.09195068509426e-06 -6.11628798636922e-06 -5.95211014525366e-06 2.07392773899659e-06 -2.57868976741401e-05 9.09195068509426e-06 0.000124347643903114 -7.94265658796745e-06 -4.46299212319052e-05 7.74734388720458e-06 -3.97700385714351e-06 -6.11628798636922e-06 -7.94265658796745e-06 3.08846182722479e-05 4.61432880377346e-06 8.23209095820977e-06 2.04830942231409e-05 -5.95211014525366e-06 -4.46299212319052e-05 4.61432880377346e-06 0.000276902472670866 3212 3274 0 1453 1467 3212 3274 0 1382 1584 0 0 0 0 0 0 0 0 2287 0 0 0 0 0 2207 +303 305 0.997967875867745 0.0621575455673423 0.0140199238608563 0.196750489599254 -0.0623892264001638 0.997911470547082 0.0167416062475826 -0.000908948726621612 -0.0129500256837406 -0.0175822774293822 0.999761551748809 -0.053753443574193 6.06640321286428e-05 -2.75372755125556e-05 -2.73741574600319e-06 1.27206745298892e-06 4.97405976679404e-06 -3.04795735014269e-05 -2.75372755125556e-05 5.28718834024122e-05 3.65823476527696e-06 -1.3147978702044e-05 -5.48195418886596e-06 2.51111001072078e-05 -2.73741574600319e-06 3.65823476527696e-06 1.49988222577097e-05 8.54753077416806e-06 -2.12939215401619e-06 1.6975236004597e-06 1.27206745298892e-06 -1.3147978702044e-05 8.54753077416806e-06 9.53676914869308e-05 -1.08864087528351e-06 -7.28648456722854e-05 4.97405976679404e-06 -5.48195418886596e-06 -2.12939215401619e-06 -1.08864087528351e-06 2.05940650195382e-05 -1.6994906129532e-05 -3.04795735014269e-05 2.51111001072078e-05 1.6975236004597e-06 -7.28648456722854e-05 -1.6994906129532e-05 0.000379985915608878 3373 3426 0 372 49 3373 3426 0 323 125 0 0 0 0 0 0 0 0 2955 0 0 0 0 0 3391 +303 445 0.830436969886714 0.556571261318844 -0.0245534135982136 0.102841612275291 -0.55559710050534 0.830621829825584 0.0371380899785985 -0.264608632296163 0.0410645949137738 -0.0171990375065316 0.999008454495465 -0.0487756416722169 8.67932948116948e-05 -1.64899943888111e-05 -2.82353118249135e-06 2.81384759466166e-06 9.4818528419232e-06 -2.19823737765278e-05 -1.64899943888111e-05 6.41778341834762e-05 6.00400249075069e-06 5.68429392954401e-06 6.03012542356373e-07 2.52690991965756e-05 -2.82353118249135e-06 6.00400249075069e-06 1.54646311601458e-05 1.21553208889689e-06 -5.55896509766206e-06 3.07725857145803e-06 2.81384759466166e-06 5.68429392954401e-06 1.21553208889689e-06 6.55764006301426e-05 1.39010590219932e-05 1.69810379415821e-05 9.4818528419232e-06 6.03012542356373e-07 -5.55896509766206e-06 1.39010590219932e-05 5.2256984221163e-05 -7.16840341415963e-06 -2.19823737765278e-05 2.52690991965756e-05 3.07725857145803e-06 1.69810379415821e-05 -7.16840341415963e-06 0.0003917131211488 1651 1696 0 1793 0 1720 1765 0 1762 0 0 0 0 0 0 0 0 0 1923 0 546 546 0 0 99 +302 451 0.985943639200079 0.159804143418684 -0.0487624452537598 0.760592777127111 -0.159989210586835 0.98711875708037 0.000109160010031073 0.0315374043186426 0.0481517685729895 0.00769383950488762 0.998810398432538 -0.094133236186863 6.77633026856455e-05 -7.09778263704096e-06 4.47457937325494e-06 2.18907600201851e-05 9.22824576795073e-06 1.48788934225929e-05 -7.09778263704096e-06 3.85820860041608e-05 1.25956628284075e-07 7.82940827861638e-07 1.28393338324148e-06 3.22616064318966e-06 4.47457937325494e-06 1.25956628284075e-07 1.83783785950236e-05 1.3538979486712e-05 -6.07513300026776e-06 -2.81968523337575e-06 2.18907600201851e-05 7.82940827861638e-07 1.3538979486712e-05 0.00014485463406601 4.49201395129218e-06 2.96611989326655e-05 9.22824576795073e-06 1.28393338324148e-06 -6.07513300026776e-06 4.49201395129218e-06 3.20215631715223e-05 1.21466658612862e-05 1.48788934225929e-05 3.22616064318966e-06 -2.81968523337575e-06 2.96611989326655e-05 1.21466658612862e-05 0.000181970525269288 3289 3367 0 1447 1049 3289 3367 0 1382 1165 0 0 0 0 0 0 0 0 2289 0 0 0 0 0 2443 +303 306 0.993020072839601 0.117860165522792 0.00448512213574722 0.290458880483497 -0.117930442754472 0.992782461186991 0.0218035646451311 -0.00554106928390616 -0.00188297885458933 -0.0221803097913476 0.999752213425003 -0.0371862141091228 6.34558005711799e-05 -1.3927843319602e-05 -3.73840660156416e-06 -8.02681070519577e-06 4.13455715659511e-06 7.32447922807249e-06 -1.3927843319602e-05 5.30757415998087e-05 1.00069846379029e-06 -8.4909735286236e-06 -2.87690229797185e-06 -2.60099622857806e-05 -3.73840660156416e-06 1.00069846379029e-06 1.25098155548993e-05 -8.30205025811682e-07 3.52987510535137e-06 9.2268900437393e-07 -8.02681070519577e-06 -8.4909735286236e-06 -8.30205025811682e-07 6.66030857317455e-05 8.9239450047495e-07 1.20929392275009e-05 4.13455715659511e-06 -2.87690229797185e-06 3.52987510535137e-06 8.9239450047495e-07 1.54520541244313e-05 4.58679308815419e-09 7.32447922807249e-06 -2.60099622857806e-05 9.2268900437393e-07 1.20929392275009e-05 4.58679308815419e-09 0.000127443367323475 3353 3426 0 639 64 3353 3426 0 591 148 0 0 0 0 0 0 0 0 2942 0 0 0 0 0 3386 +303 446 0.869702022310036 0.49342906597125 -0.0120892201805473 0.210109538207589 -0.492861775002114 0.869499207183231 0.0325330516474819 -0.207734693625044 0.0265643206500608 -0.022335746293156 0.999397544176455 -0.027127844559141 0.000100814894288346 -3.29928884611509e-05 9.39956726548118e-07 -5.84891209988254e-06 4.65745736835627e-06 -6.4321004852228e-05 -3.29928884611509e-05 8.1299520050455e-05 4.69876666368034e-06 9.85587311570159e-07 -4.75693614651448e-06 6.58640763234499e-05 9.39956726548118e-07 4.69876666368034e-06 1.76444486333801e-05 7.78824554872063e-06 -1.70895389111133e-06 1.22632509501082e-05 -5.84891209988254e-06 9.85587311570159e-07 7.78824554872063e-06 6.72386522613003e-05 9.3184589798835e-07 8.41710795215447e-05 4.65745736835627e-06 -4.75693614651448e-06 -1.70895389111133e-06 9.3184589798835e-07 3.12278241842693e-05 2.25260256672691e-05 -6.4321004852228e-05 6.58640763234499e-05 1.22632509501082e-05 8.41710795215447e-05 2.25260256672691e-05 0.000578295837521635 2025 2030 0 1571 0 2104 2109 0 1527 0 0 0 0 0 0 0 0 0 2031 0 519 519 0 0 488 +303 444 0.789040543504191 0.614110138968015 -0.0168451157103564 0.0305018378351649 -0.613917474787048 0.789218081079509 0.0154969238325618 -0.324919783989266 0.022811287944881 -0.00188619030409002 0.999738009394678 -0.0518801810452649 0.000101179528436698 -3.75383463144589e-05 9.41414067735392e-07 -2.37964425477351e-05 -1.48249803585357e-05 -0.000119184068305989 -3.75383463144589e-05 4.85926699349557e-05 5.34043684764198e-07 -5.46788333388739e-07 -3.99831927951705e-06 8.51085385851334e-05 9.41414067735392e-07 5.34043684764198e-07 1.46777570837174e-05 1.58740337278762e-06 -4.65401984978916e-07 8.38489500415531e-06 -2.37964425477351e-05 -5.46788333388739e-07 1.58740337278762e-06 0.000158332465124912 0.000109692561573853 -3.72857482787749e-05 -1.48249803585357e-05 -3.99831927951705e-06 -4.65401984978916e-07 0.000109692561573853 0.000132378842922434 -6.25046815049467e-05 -0.000119184068305989 8.51085385851334e-05 8.38489500415531e-06 -3.72857482787749e-05 -6.25046815049467e-05 0.000505343431965167 1450 1461 0 1753 0 1513 1524 0 1723 0 0 0 0 0 0 0 0 0 1769 0 538 538 0 0 78 +303 439 0.317976590348627 0.947622908168712 0.0300285181807905 -0.288640412776314 -0.94450799125011 0.313859606496317 0.096937102673126 -0.583635354863297 0.0824350802446664 -0.0591859047734312 0.994837416978878 0.22474580578781 6.63258241996802e-05 -1.73710228228415e-05 -2.56901120270085e-06 -8.58459393099679e-06 -3.32013126134569e-05 2.32172824108998e-05 -1.73710228228415e-05 0.000103421405501488 1.3129637472218e-05 -6.47596712363378e-07 -3.35083626163375e-05 5.81343379351663e-05 -2.56901120270085e-06 1.3129637472218e-05 1.55045432766385e-05 -5.06091691309776e-07 -4.12517588766986e-07 2.7397985903975e-06 -8.58459393099679e-06 -6.47596712363378e-07 -5.06091691309776e-07 3.07249025317714e-05 4.91505819260031e-05 1.0813126818981e-06 -3.32013126134569e-05 -3.35083626163375e-05 -4.12517588766986e-07 4.91505819260031e-05 0.000335146297906168 -0.000162217954226027 2.32172824108998e-05 5.81343379351663e-05 2.7397985903975e-06 1.0813126818981e-06 -0.000162217954226027 0.000491905855311369 0 0 0 2088 0 0 0 0 2075 0 0 0 0 0 0 0 0 0 296 0 193 188 0 161 96 +303 442 0.644593032810944 0.764500597913086 0.00621754309373313 -0.105896732691595 -0.762464475234184 0.642236938126178 0.0786106819215505 -0.433747651017629 0.0561047774921941 -0.0554125536033579 0.99688600293399 0.0502944605617703 5.55218322411337e-05 -1.08526516735852e-05 1.2435400421193e-06 -5.94015336834831e-06 2.14097423351555e-06 -2.99672335114696e-05 -1.08526516735852e-05 2.57561567442214e-05 1.46600283576374e-06 -6.78317496632473e-07 1.68912636967073e-06 -3.41948066212403e-06 1.2435400421193e-06 1.46600283576374e-06 1.65060211348573e-05 2.23715979394891e-06 -4.69375566642479e-06 6.10287503362098e-07 -5.94015336834831e-06 -6.78317496632473e-07 2.23715979394891e-06 6.15609812278077e-05 4.04673322759805e-05 -5.20212578673803e-07 2.14097423351555e-06 1.68912636967073e-06 -4.69375566642479e-06 4.04673322759805e-05 0.000109718659377024 -1.52877598506946e-05 -2.99672335114696e-05 -3.41948066212403e-06 6.10287503362098e-07 -5.20212578673803e-07 -1.52877598506946e-05 9.59402669940187e-05 737 747 0 1983 0 787 797 0 1956 0 0 0 0 0 0 0 0 0 1279 0 504 504 0 0 78 +303 441 0.545642914673212 0.837761603927407 0.0207196682381645 -0.214760860349499 -0.835291535143746 0.541708836393192 0.0940190825882561 -0.487249176269147 0.0675415500571717 -0.068607809748683 0.995354764622827 0.0857790069434693 4.85735313434177e-05 -1.28333965208221e-05 1.49406683996676e-06 -6.9967492812703e-06 -7.94349899370522e-06 -3.45001934935426e-05 -1.28333965208221e-05 3.11170345652647e-05 2.78875205555634e-06 -4.58864701403538e-06 -1.02854841380024e-05 -1.89096047977533e-06 1.49406683996676e-06 2.78875205555634e-06 1.23776222069141e-05 -2.53412305263798e-06 -9.02393530910619e-08 -1.01836539558492e-06 -6.9967492812703e-06 -4.58864701403538e-06 -2.53412305263798e-06 5.80431069310252e-05 7.43644763638999e-05 6.23630437260142e-06 -7.94349899370522e-06 -1.02854841380024e-05 -9.02393530910619e-08 7.43644763638999e-05 0.000189341358987795 -1.28390309369352e-05 -3.45001934935426e-05 -1.89096047977533e-06 -1.01836539558492e-06 6.23630437260142e-06 -1.28390309369352e-05 0.000170876528847281 252 206 0 2055 0 293 247 0 2028 0 0 0 0 0 0 0 0 0 992 0 538 538 0 0 236 +303 449 0.95265784766655 0.300417570024308 -0.0468220984154559 0.455553923923573 -0.297560295308111 0.95285382237271 0.0593924561360008 -0.0582516198573725 0.062457152796831 -0.042648291998704 0.997136012414609 -0.0823402621838652 6.61923944322135e-05 -1.79490187647431e-05 -3.68716760324304e-07 -8.68004056526016e-06 3.47177101969384e-06 -7.39632719796383e-06 -1.79490187647431e-05 4.34857355938014e-05 1.50274929415463e-06 -4.29597709637579e-07 -3.80512808219842e-08 -1.43365143479368e-05 -3.68716760324304e-07 1.50274929415463e-06 1.65114918450853e-05 5.23606403727692e-06 -2.90606953454527e-06 1.02852262526568e-06 -8.68004056526016e-06 -4.29597709637579e-07 5.23606403727692e-06 7.70032780762672e-05 -8.54493587310586e-06 7.5002865369801e-05 3.47177101969384e-06 -3.80512808219842e-08 -2.90606953454527e-06 -8.54493587310586e-06 2.71981034270102e-05 1.34941334361786e-05 -7.39632719796383e-06 -1.43365143479368e-05 1.02852262526568e-06 7.5002865369801e-05 1.34941334361786e-05 0.000220772646483715 3203 3248 0 1368 0 3203 3334 0 1310 0 0 0 0 0 0 0 0 0 2370 0 0 0 0 0 3115 +303 450 0.971736062953161 0.230339187676587 -0.0516999282086535 0.567811932233748 -0.229365411225464 0.973041511372589 0.0241189817181845 -0.0102314504489322 0.0558617229385556 -0.0115791090433631 0.998371369853973 -0.0712822415373949 5.32467706695539e-05 -8.2672948101155e-06 5.642575064553e-06 1.44782034361805e-05 5.79027117287404e-06 -5.16904879618489e-06 -8.2672948101155e-06 3.11220271187116e-05 1.02299598173775e-06 -2.4603494691766e-06 -1.9242869551176e-06 -9.95220716210093e-07 5.642575064553e-06 1.02299598173775e-06 1.99647456055345e-05 5.10718430656431e-06 -6.66481653260829e-06 -8.87506734896089e-06 1.44782034361805e-05 -2.4603494691766e-06 5.10718430656431e-06 9.80228527587263e-05 6.16401829871006e-06 -8.01552091392384e-06 5.79027117287404e-06 -1.9242869551176e-06 -6.66481653260829e-06 6.16401829871006e-06 3.36794104266566e-05 7.70508598842627e-06 -5.16904879618489e-06 -9.95220716210093e-07 -8.87506734896089e-06 -8.01552091392384e-06 7.70508598842627e-06 0.00019223531578617 3250 3349 0 1321 353 3250 3349 0 1239 456 0 0 0 0 0 0 0 0 2419 0 0 0 0 0 2915 +303 437 0.152267718586981 0.988299407531756 0.0088782289166268 -0.422112821903286 -0.987594175495714 0.151798037963239 0.0401883092136437 -0.658610977340901 0.0383703844554147 -0.0148874693246079 0.99915267945087 0.400837025469299 6.39587291393988e-05 -5.07217667424132e-06 -7.34778214194283e-07 -8.16612825589641e-06 1.21122104952425e-05 -1.448182911588e-06 -5.07217667424132e-06 3.20516157946495e-05 4.12719194106436e-06 -1.94202939107908e-06 -7.74663102641665e-06 -1.59885412014809e-05 -7.34778214194283e-07 4.12719194106436e-06 1.3077338225902e-05 5.66065246992789e-07 -1.89118290185651e-06 -2.91162274205409e-06 -8.16612825589641e-06 -1.94202939107908e-06 5.66065246992789e-07 2.47275529477883e-05 4.8956217449074e-06 9.79643453612697e-06 1.21122104952425e-05 -7.74663102641665e-06 -1.89118290185651e-06 4.8956217449074e-06 0.000266153944410126 -1.85403953448502e-05 -1.448182911588e-06 -1.59885412014809e-05 -2.91162274205409e-06 9.79643453612697e-06 -1.85403953448502e-05 0.000146387485420462 0 0 0 1532 0 0 0 0 1534 0 0 0 0 0 0 0 0 0 11 0 108 108 0 220 133 +304 444 0.803019648825862 0.595177079316555 -0.0303922334783912 -0.0542800588570453 -0.595203544066873 0.803522827571457 0.00915460003519468 -0.326887233976855 0.0298694614920272 0.0107382413730431 0.999496125776579 -0.0151418188625697 6.98036864843825e-05 -2.3443649950205e-05 3.97323327411119e-06 -1.4840271844881e-05 -1.25004585679855e-05 -9.59416998987137e-05 -2.3443649950205e-05 4.94601558747909e-05 2.04040761553595e-06 3.25133517064233e-06 3.84025767999459e-08 8.93766185826802e-05 3.97323327411119e-06 2.04040761553595e-06 1.29113232048651e-05 2.27154997424609e-07 8.92169112235322e-07 -2.76041330145743e-07 -1.4840271844881e-05 3.25133517064233e-06 2.27154997424609e-07 0.000201252046106312 0.000159680504767935 4.98252074871117e-05 -1.25004585679855e-05 3.84025767999459e-08 8.92169112235322e-07 0.000159680504767935 0.00017578866048546 2.21875553951594e-05 -9.59416998987137e-05 8.93766185826802e-05 -2.76041330145743e-07 4.98252074871117e-05 2.21875553951594e-05 0.000738632983990551 1370 1386 0 1596 0 1429 1445 0 1565 0 0 0 0 0 0 0 0 0 1926 0 605 605 0 0 78 +304 443 0.74165217043338 0.670265886682191 -0.0263761111916183 -0.107705781296985 -0.669756557675028 0.742118970166149 0.0261837272142602 -0.377756412248706 0.0371242716124224 -0.00175364468193958 0.999309117934774 0.00919414100289526 5.58084873415121e-05 -8.26879266507935e-06 7.81226591854841e-06 1.16955906454664e-05 7.94771909782662e-06 -1.50935544399761e-05 -8.26879266507935e-06 2.51011437911769e-05 -6.11749309773711e-08 -1.35243606838898e-05 -1.00321268447337e-05 -1.97479863903579e-07 7.81226591854841e-06 -6.11749309773711e-08 1.38284798773455e-05 3.9816243960576e-06 3.77218468492307e-06 -5.11367234926382e-06 1.16955906454664e-05 -1.35243606838898e-05 3.9816243960576e-06 0.000136194027127262 0.000112231322015986 -8.79697969473327e-05 7.94771909782662e-06 -1.00321268447337e-05 3.77218468492307e-06 0.000112231322015986 0.000155141595053538 -8.99963043938903e-05 -1.50935544399761e-05 -1.97479863903579e-07 -5.11367234926382e-06 -8.79697969473327e-05 -8.99963043938903e-05 0.00014853102866962 1125 1171 0 1701 0 1179 1225 0 1669 0 0 0 0 0 0 0 0 0 1680 0 565 565 0 0 118 +304 442 0.660203651438661 0.75093985943154 -0.0148481023702696 -0.213230695435661 -0.748350777717 0.659356071119504 0.0722543076100855 -0.440249087727605 0.064048826042482 -0.0365909687599378 0.997275713575634 0.0623441922939817 3.39361136102954e-05 -3.90625297059574e-06 -1.11491353890579e-06 -5.16835226060394e-06 -5.17471977624106e-07 5.23546305572804e-06 -3.90625297059574e-06 2.58059662051704e-05 4.26047274792956e-06 -6.56833003484808e-07 -2.25674688986326e-06 -1.39599226929476e-06 -1.11491353890579e-06 4.26047274792956e-06 1.40745952688538e-05 3.74933558816594e-06 1.47651459034614e-06 -6.14548203245523e-06 -5.16835226060394e-06 -6.56833003484808e-07 3.74933558816594e-06 3.67139712142707e-05 8.84435284838661e-06 -1.09955481669727e-05 -5.17471977624106e-07 -2.25674688986326e-06 1.47651459034614e-06 8.84435284838661e-06 4.28198600831345e-05 -1.42343993018446e-05 5.23546305572804e-06 -1.39599226929476e-06 -6.14548203245523e-06 -1.09955481669727e-05 -1.42343993018446e-05 0.000118952883163155 663 673 0 1757 0 703 713 0 1729 0 0 0 0 0 0 0 0 0 1439 0 584 584 0 0 170 +304 306 0.995365138101137 0.0949268167456028 -0.0153993933468388 0.18699221477978 -0.0947104550187419 0.99540329432973 0.0142201036446036 -0.00260997990924248 0.0166784760408974 -0.0126957118771317 0.999780299534296 -0.0293559455692883 5.63384089689348e-05 -7.52648481665445e-06 -2.47082879918544e-06 -1.58244630099633e-05 -8.10975045644208e-07 2.17108508695094e-05 -7.52648481665445e-06 2.65385722807671e-05 1.17596008802717e-07 5.5689147898684e-08 -1.28136523033598e-06 7.35391623458424e-07 -2.47082879918544e-06 1.17596008802717e-07 1.27280917185217e-05 1.67403965133198e-07 2.69242387652437e-06 -5.17926640805863e-07 -1.58244630099633e-05 5.5689147898684e-08 1.67403965133198e-07 9.48224748845179e-05 3.60918648117828e-06 2.93794619096257e-05 -8.10975045644208e-07 -1.28136523033598e-06 2.69242387652437e-06 3.60918648117828e-06 1.60449268727022e-05 5.01156492642962e-06 2.17108508695094e-05 7.35391623458424e-07 -5.17926640805863e-07 2.93794619096257e-05 5.01156492642962e-06 0.000119857703728486 3384 3437 0 442 0 3384 3457 0 410 27 0 0 0 0 0 0 0 0 3166 0 0 0 0 0 3523 +304 439 0.337489177034363 0.941320013923197 0.00420556444481182 -0.384418023146352 -0.937432917056435 0.335682755019139 0.092393798503052 -0.595968734740984 0.0855603962340651 -0.0351243415652426 0.995713663271665 0.212034835210819 6.51007568751405e-05 -3.25332284501837e-05 -5.20377942011943e-06 -4.79325753179058e-06 7.56175606334845e-08 2.93955932855314e-05 -3.25332284501837e-05 7.47472051081414e-05 7.16713391599554e-06 7.12954279272545e-06 7.95326890276486e-07 4.08337666999363e-05 -5.20377942011943e-06 7.16713391599554e-06 1.55302486134677e-05 1.842147176572e-06 1.09866850549514e-06 1.18452727771092e-06 -4.79325753179058e-06 7.12954279272545e-06 1.842147176572e-06 3.44143718372357e-05 3.00536608362604e-05 5.01674210096502e-05 7.56175606334845e-08 7.95326890276486e-07 1.09866850549514e-06 3.00536608362604e-05 0.000158557623823914 5.10843416685698e-05 2.93955932855314e-05 4.08337666999363e-05 1.18452727771092e-06 5.01674210096502e-05 5.10843416685698e-05 0.000459592391782612 0 0 0 1994 0 0 0 0 1990 0 0 0 0 0 0 0 0 0 432 0 111 88 0 175 121 +304 448 0.938798564299303 0.341889249886833 -0.0420594398605772 0.281565534589841 -0.338970949236497 0.93863205924899 0.0637852092863957 -0.100067503280278 0.0612858160039931 -0.0456245346477036 0.997076953196144 -0.0215352092254583 6.53134678830274e-05 -1.85535729159162e-05 4.02251976758259e-06 1.11567006814296e-05 -9.27050598087405e-07 2.66172702569172e-05 -1.85535729159162e-05 0.000134076465938499 6.1381255398369e-06 -3.0888619269439e-05 -1.61119445973304e-05 0.000154364863470218 4.02251976758259e-06 6.1381255398369e-06 1.92950517710686e-05 7.88642426249693e-06 -7.11098288522377e-06 4.12620634235415e-06 1.11567006814296e-05 -3.0888619269439e-05 7.88642426249693e-06 0.000138535934480337 2.88462636672818e-05 -3.39876831303489e-05 -9.27050598087405e-07 -1.61119445973304e-05 -7.11098288522377e-06 2.88462636672818e-05 4.61906585906278e-05 -4.83764522150013e-05 2.66172702569172e-05 0.000154364863470218 4.12620634235415e-06 -3.39876831303489e-05 -4.83764522150013e-05 0.000727816497419166 2697 2725 0 1281 0 2789 2817 0 1239 0 0 0 0 0 0 0 0 0 2493 0 343 477 0 0 1863 +304 449 0.957546902229019 0.278889561024934 -0.0729694647296337 0.349504473855908 -0.275573375098833 0.959854302360618 0.0523357733911542 -0.051919171102672 0.0846359555286496 -0.0300055160117593 0.995960051428078 -0.0803478493380962 4.86987880035433e-05 -1.04791220982375e-05 -7.34288935430739e-06 -1.67214491383973e-05 2.41678164489217e-06 4.61546947740104e-06 -1.04791220982375e-05 3.40721527488469e-05 1.44804376451792e-06 9.25949677764611e-06 2.43055404688435e-06 8.19794048459474e-06 -7.34288935430739e-06 1.44804376451792e-06 1.52704281945119e-05 6.55980579554625e-06 -2.71197889964493e-06 -1.62151178909434e-06 -1.67214491383973e-05 9.25949677764611e-06 6.55980579554625e-06 7.36184165988034e-05 -1.42225009126347e-06 4.93536453501963e-05 2.41678164489217e-06 2.43055404688435e-06 -2.71197889964493e-06 -1.42225009126347e-06 2.63811740204736e-05 2.04793157572669e-05 4.61546947740104e-06 8.19794048459474e-06 -1.62151178909434e-06 4.93536453501963e-05 2.04793157572669e-05 0.000194352138810858 3036 3050 0 1137 0 3137 3152 0 1094 0 0 0 0 0 0 0 0 0 2618 0 3 102 0 0 3110 +304 450 0.975712079351642 0.208025023234448 -0.0686405704784121 0.454369706302541 -0.206867946491505 0.978083370472469 0.0236341515524352 -0.00250632846199942 0.0720526954505001 -0.00886059329406387 0.997361468558313 -0.0353489397948803 6.53901037840553e-05 -4.06384032491952e-06 1.01632031705098e-05 1.52946382284272e-05 -4.13383288720431e-06 -7.46634993927599e-06 -4.06384032491952e-06 3.80316319210727e-05 5.49833388396424e-06 8.00565569440105e-07 -2.20647274261394e-06 4.15156323304052e-06 1.01632031705098e-05 5.49833388396424e-06 1.86005739237699e-05 7.32243483704858e-06 -1.4839411639234e-06 -9.64374619537748e-06 1.52946382284272e-05 8.00565569440105e-07 7.32243483704858e-06 7.15685177344932e-05 -4.552166451914e-06 5.88220504041318e-06 -4.13383288720431e-06 -2.20647274261394e-06 -1.4839411639234e-06 -4.552166451914e-06 2.39861848620914e-05 6.69507493234714e-07 -7.46634993927599e-06 4.15156323304052e-06 -9.64374619537748e-06 5.88220504041318e-06 6.69507493234714e-07 0.000276493503645244 3218 3317 0 1052 165 3218 3317 0 1005 279 0 0 0 0 0 0 0 0 2710 0 0 0 0 0 3112 +305 448 0.949506793251028 0.306622611322332 -0.0664787469498625 0.195106602837997 -0.303522333463951 0.951358952752289 0.0528236320851402 -0.0919146488771051 0.0794420710879814 -0.0299786131090518 0.996388598939846 -0.0629104807884965 5.65789818655845e-05 -3.8101047028865e-05 -5.1713156010238e-07 1.38011262683233e-05 8.7920383814672e-06 -1.52513703876012e-05 -3.8101047028865e-05 8.50735026252068e-05 1.80991896987073e-07 -1.71911904999213e-05 -1.10281530833314e-05 6.77218380993096e-05 -5.1713156010238e-07 1.80991896987073e-07 1.44343164556654e-05 4.63405861277187e-06 1.62409037838024e-07 -4.35503751309646e-06 1.38011262683233e-05 -1.71911904999213e-05 4.63405861277187e-06 0.000159828483617836 5.93936511191981e-05 -0.00010220623324654 8.7920383814672e-06 -1.10281530833314e-05 1.62409037838024e-07 5.93936511191981e-05 6.11145978534248e-05 -9.04783224632402e-05 -1.52513703876012e-05 6.77218380993096e-05 -4.35503751309646e-06 -0.00010220623324654 -9.04783224632402e-05 0.000637162988191102 2500 2528 0 1054 0 2591 2619 0 1029 0 0 0 0 0 0 0 0 0 2707 0 400 534 0 0 1863 +305 449 0.969010415678218 0.239746670410278 -0.0595008263330306 0.269815556615664 -0.237739582507203 0.970550062280199 0.0388904553483528 -0.0411656083825817 0.0670723878837533 -0.0235395546917743 0.997470392617487 -0.0234308431857531 4.88726646718699e-05 -1.30295817066911e-05 2.36395731188919e-06 -1.35802262823456e-05 -3.79933721339821e-06 -6.13614912525474e-06 -1.30295817066911e-05 2.92855474636073e-05 -3.51108804114034e-06 1.44519608710711e-07 3.44571910833951e-06 1.07722976757719e-05 2.36395731188919e-06 -3.51108804114034e-06 1.48171391755827e-05 5.09765288161445e-06 -1.09265368634755e-06 -1.48337833000893e-06 -1.35802262823456e-05 1.44519608710711e-07 5.09765288161445e-06 7.94325689547134e-05 1.33921260131833e-06 5.16389253464053e-05 -3.79933721339821e-06 3.44571910833951e-06 -1.09265368634755e-06 1.33921260131833e-06 2.44539548093704e-05 1.62574704898431e-05 -6.13614912525474e-06 1.07722976757719e-05 -1.48337833000893e-06 5.16389253464053e-05 1.62574704898431e-05 0.000235343931698088 3096 3110 0 911 0 3196 3210 0 880 0 0 0 0 0 0 0 0 0 2850 0 15 131 0 0 3126 +305 445 0.862803755168261 0.503363838923788 -0.0468457653524263 -0.0345973368944659 -0.503371124102183 0.863979851183029 0.0125031264032876 -0.265934405681799 0.0467674190826526 0.0127930611527779 0.998823881421889 -0.0165234300758425 4.49108315243799e-05 -5.98345728133943e-06 -4.45064822435851e-06 -5.67743008378078e-06 5.99362889512835e-06 -1.21463835106032e-06 -5.98345728133943e-06 2.693733135275e-05 2.91594311943665e-06 -5.30054178295619e-06 -4.30458926462411e-06 -3.97856257406417e-06 -4.45064822435851e-06 2.91594311943665e-06 1.32603665210246e-05 1.49023995038443e-06 -2.93754239681346e-06 -8.22552886256882e-07 -5.67743008378078e-06 -5.30054178295619e-06 1.49023995038443e-06 9.17464399744027e-05 4.1868988378178e-05 -3.86524642422917e-05 5.99362889512835e-06 -4.30458926462411e-06 -2.93754239681346e-06 4.1868988378178e-05 6.59411378856968e-05 -3.59161945203848e-05 -1.21463835106032e-06 -3.97856257406417e-06 -8.22552886256882e-07 -3.86524642422917e-05 -3.59161945203848e-05 0.000140875161653206 1571 1597 0 1387 0 1636 1662 0 1364 0 0 0 0 0 0 0 0 0 2251 0 622 622 0 0 106 +305 443 0.767795583360281 0.640371396692965 -0.0203572215674845 -0.228668883846395 -0.640285322854137 0.768053271764756 0.0113524036673643 -0.392205937659686 0.0229051852212389 0.00431810478742463 0.999728316324503 0.0313473334428854 3.64033205102161e-05 -7.21131205328422e-06 1.97935504113338e-06 1.13032039993967e-06 1.21962695371819e-06 6.13628348124612e-06 -7.21131205328422e-06 2.19982668815738e-05 2.588079999264e-06 -3.56803272860904e-06 -6.83007201508051e-07 -9.89268814425765e-06 1.97935504113338e-06 2.588079999264e-06 1.22468512533426e-05 -2.07009470369333e-07 3.54970766515935e-06 -4.37240077966542e-06 1.13032039993967e-06 -3.56803272860904e-06 -2.07009470369333e-07 9.0436346790618e-05 7.03091213624305e-05 -7.91492297296937e-06 1.21962695371819e-06 -6.83007201508051e-07 3.54970766515935e-06 7.03091213624305e-05 0.000103557464082602 -5.63668085664532e-06 6.13628348124612e-06 -9.89268814425765e-06 -4.37240077966542e-06 -7.91492297296937e-06 -5.63668085664532e-06 7.42854755434984e-05 1042 1086 0 1522 0 1087 1131 0 1500 0 0 0 0 0 0 0 0 0 1877 0 641 641 0 0 135 +305 442 0.689332357816104 0.724319556158452 -0.0134937405530982 -0.271664809618398 -0.722521894895165 0.688739338805523 0.0600019547917476 -0.450097241145663 0.0527542592099523 -0.0316117659765224 0.998107050564745 0.0664869863779134 3.40991137126804e-05 -7.36205060691244e-06 8.56366811631695e-07 8.53931475788472e-06 9.34502300920671e-06 8.8343238849212e-06 -7.36205060691244e-06 3.29453582038388e-05 6.65939331504316e-06 2.33226155474161e-06 6.97847507024173e-06 -1.86756433528147e-05 8.56366811631695e-07 6.65939331504316e-06 1.54892829922152e-05 1.59138923393292e-06 1.56832068741036e-06 -7.38360300763524e-06 8.53931475788472e-06 2.33226155474161e-06 1.59138923393292e-06 4.27835963498693e-05 1.75122114040808e-05 1.65951215423643e-05 9.34502300920671e-06 6.97847507024173e-06 1.56832068741036e-06 1.75122114040808e-05 6.29697217676456e-05 1.27845621833361e-05 8.8343238849212e-06 -1.86756433528147e-05 -7.38360300763524e-06 1.65951215423643e-05 1.27845621833361e-05 0.000110637709634774 652 661 0 1603 0 693 702 0 1583 0 0 0 0 0 0 0 0 0 1583 0 590 590 0 0 119 +306 448 0.966739787020938 0.251748732215265 -0.0451304777142661 0.111951663529518 -0.249695780908001 0.967204028486456 0.0465659132447098 -0.0861724407987751 0.0553732894765581 -0.0337482311770114 0.99789521278788 -0.0188695803330913 9.11910510339203e-05 -4.32175421744145e-05 3.51682811285674e-07 -3.28573080212857e-06 4.28062214607131e-07 2.44495523617569e-06 -4.32175421744145e-05 0.000171383816939438 1.27080833960934e-05 -1.29861434821148e-05 3.17972669427394e-06 -9.71928246180724e-05 3.51682811285674e-07 1.27080833960934e-05 2.18648587089081e-05 2.21224457881636e-06 -4.01021153574208e-06 -9.23542962389109e-06 -3.28573080212857e-06 -1.29861434821148e-05 2.21224457881636e-06 8.24019908791223e-05 6.53053213862278e-06 6.73395488971639e-05 4.28062214607131e-07 3.17972669427394e-06 -4.01021153574208e-06 6.53053213862278e-06 3.33287163297236e-05 1.35225154716908e-05 2.44495523617569e-06 -9.71928246180724e-05 -9.23542962389109e-06 6.73395488971639e-05 1.35225154716908e-05 0.000284105254695975 2504 2532 0 801 0 2603 2631 0 785 0 0 0 0 0 0 0 0 0 2977 0 390 524 0 0 1856 +305 439 0.376136226928215 0.926513647332809 0.00969536478227508 -0.463381090332882 -0.923760291289185 0.374163934763542 0.0816595013429785 -0.621479532592864 0.0720309865927576 -0.0396712897234168 0.996613127418134 0.246687156437977 4.76202297997831e-05 -4.04256431837379e-06 2.06102423149297e-06 4.33661142416092e-06 1.6829901697627e-05 1.66335532994929e-05 -4.04256431837379e-06 4.68849351955325e-05 6.8977058540575e-06 -2.11048721075177e-06 5.82964366917618e-06 -3.11811667563573e-05 2.06102423149297e-06 6.8977058540575e-06 1.60210427478276e-05 -8.38300205314453e-07 2.14636934849072e-06 -6.28799055808348e-06 4.33661142416092e-06 -2.11048721075177e-06 -8.38300205314453e-07 2.81394663942725e-05 3.17082477602475e-05 1.42029327583069e-05 1.6829901697627e-05 5.82964366917618e-06 2.14636934849072e-06 3.17082477602475e-05 0.00019305099590492 3.86711816567058e-05 1.66335532994929e-05 -3.11811667563573e-05 -6.28799055808348e-06 1.42029327583069e-05 3.86711816567058e-05 0.00012225686336328 0 0 0 1720 0 0 0 0 1722 0 0 0 0 0 0 0 0 0 569 0 12 0 0 174 38 +305 452 0.996506447062279 0.0363976269645498 -0.0751672383067454 0.558449413700875 -0.0379412339256315 0.999095304119838 -0.0192103111346183 0.0887733770027644 0.0744000250773753 0.0219951366678593 0.996985882664067 -0.0164412562012193 6.53124044912612e-05 -6.89763362457375e-06 3.01251772564681e-06 -3.58152555676078e-05 -2.55726635056721e-06 3.66316348954708e-05 -6.89763362457375e-06 4.49230086098678e-05 4.3532827916811e-06 7.97464154876402e-06 1.37488680345457e-06 5.86891047974644e-05 3.01251772564681e-06 4.3532827916811e-06 1.75077276329494e-05 8.2297713805253e-06 -4.45759527189022e-06 -1.5012607405198e-06 -3.58152555676078e-05 7.97464154876402e-06 8.2297713805253e-06 0.000205150227595779 1.26536741489505e-06 4.52655361891708e-05 -2.55726635056721e-06 1.37488680345457e-06 -4.45759527189022e-06 1.26536741489505e-06 2.74330423460234e-05 1.75585518126172e-05 3.66316348954708e-05 5.86891047974644e-05 -1.5012607405198e-06 4.52655361891708e-05 1.75585518126172e-05 0.000583430028325579 3292 3354 0 652 975 3292 3354 0 615 1091 0 0 0 0 0 0 0 0 3106 0 0 0 0 0 2718 +306 450 0.99216625576862 0.113700326921026 -0.051752841198612 0.290686903809646 -0.113775135744098 0.993505382384444 0.00150786589324796 0.02832059857625 0.0515881711295238 0.0043921328750098 0.998658785455933 0.00525627547026855 4.39484691559267e-05 -1.80807072882701e-05 2.00350643644211e-06 2.42942103507906e-06 -1.74030063976267e-06 2.87787025018659e-05 -1.80807072882701e-05 3.7158140477822e-05 4.63534649083968e-06 5.8584528805197e-06 2.58770806329169e-08 -6.1602775859008e-06 2.00350643644211e-06 4.63534649083968e-06 1.59702146186628e-05 -1.63638593488792e-06 -2.55922839946725e-06 -6.50411521218767e-06 2.42942103507906e-06 5.8584528805197e-06 -1.63638593488792e-06 9.03965386740453e-05 1.26241658783364e-05 3.62382943041694e-05 -1.74030063976267e-06 2.58770806329169e-08 -2.55922839946725e-06 1.26241658783364e-05 2.70601607776264e-05 1.26640026319905e-05 2.87787025018659e-05 -6.1602775859008e-06 -6.50411521218767e-06 3.62382943041694e-05 1.26640026319905e-05 0.000147619492423332 3322 3421 0 548 134 3322 3421 0 527 251 0 0 0 0 0 0 0 0 3220 0 0 0 0 0 3088 +306 308 0.989554668410371 0.141159723083607 -0.0292487744392916 0.122375357640333 -0.140843464744235 0.989951504453201 0.0126149621356135 -0.00274140469846747 0.0307355928213624 -0.00836369594156391 0.999492557212967 0.0201077540653259 8.79003836417264e-05 1.81986505358543e-05 -3.33323733949775e-06 6.50698636160719e-06 3.44402920303569e-06 9.34782558496811e-05 1.81986505358543e-05 6.12752627003503e-05 3.71581384057804e-06 1.17284033247636e-05 2.03588861823863e-06 6.49042159255813e-05 -3.33323733949775e-06 3.71581384057804e-06 1.26095231186659e-05 1.149953673445e-06 2.58357179274724e-06 -4.12658153993306e-06 6.50698636160719e-06 1.17284033247636e-05 1.149953673445e-06 9.10326050769613e-05 1.48375152900861e-05 4.00191713402196e-05 3.44402920303569e-06 2.03588861823863e-06 2.58357179274724e-06 1.48375152900861e-05 1.99796977069036e-05 8.56337082968172e-06 9.34782558496811e-05 6.49042159255813e-05 -4.12658153993306e-06 4.00191713402196e-05 8.56337082968172e-06 0.000371807088015587 3136 3143 0 489 0 3238 3245 0 470 0 0 0 0 0 0 0 0 0 3360 0 2 99 0 0 3484 +306 445 0.89006315463195 0.454506961690327 -0.0347994618011536 -0.101634248740447 -0.454707302546803 0.890637750165644 0.00238054415832221 -0.272339362656624 0.0320756882581234 0.0137047347623861 0.999391480085687 -0.00308494328161114 8.80602634991955e-05 -3.25278151066115e-05 2.42130405887482e-06 5.90814010449514e-06 9.634716308494e-06 -4.78135049927668e-05 -3.25278151066115e-05 6.22762557937344e-05 7.9720069992145e-06 -1.75278640279675e-05 -2.74500382468862e-05 3.85115128813592e-05 2.42130405887482e-06 7.9720069992145e-06 2.10624008745822e-05 2.44866386721984e-06 -6.9206940627487e-06 5.1072617188838e-06 5.90814010449514e-06 -1.75278640279675e-05 2.44866386721984e-06 0.000108549445476688 5.98292755757542e-05 -0.000135738850026735 9.634716308494e-06 -2.74500382468862e-05 -6.9206940627487e-06 5.98292755757542e-05 9.20985212636742e-05 -0.000141860941482751 -4.78135049927668e-05 3.85115128813592e-05 5.1072617188838e-06 -0.000135738850026735 -0.000141860941482751 0.000443248159751969 1597 1604 0 1063 0 1666 1673 0 1048 0 0 0 0 0 0 0 0 0 2455 0 610 610 0 0 105 +306 446 0.921599462355517 0.387109253993672 -0.0282994073875203 -0.0135716897431019 -0.387082637251814 0.922021153183475 0.0066351352960061 -0.204892192964449 0.0286611745084345 0.00483927212276951 0.999577469994757 0.0123807870721605 4.02315071082057e-05 -1.63991159133028e-05 5.22884157755886e-07 -5.31796794853234e-06 -2.27541491879825e-06 4.82381937436407e-06 -1.63991159133028e-05 3.44115276233689e-05 4.65516982617919e-06 8.0733520587522e-06 5.13270237902291e-06 1.86223313434518e-05 5.22884157755886e-07 4.65516982617919e-06 1.49066022060465e-05 2.98074054431146e-06 3.00880215923288e-07 -3.77331540622714e-06 -5.31796794853234e-06 8.0733520587522e-06 2.98074054431146e-06 4.60895548397382e-05 5.96966465883614e-07 4.07373353011655e-05 -2.27541491879825e-06 5.13270237902291e-06 3.00880215923288e-07 5.96966465883614e-07 2.39860631817927e-05 2.25110236696475e-05 4.82381937436407e-06 1.86223313434518e-05 -3.77331540622714e-06 4.07373353011655e-05 2.25110236696475e-05 0.000275825047837021 1895 1937 0 1033 0 1977 2019 0 1019 0 0 0 0 0 0 0 0 0 2614 0 618 618 0 0 476 +306 442 0.729385296647832 0.68403552277097 -0.00961730842804414 -0.314871142918574 -0.682603418254887 0.728644758179983 0.0559409488977261 -0.467466384213184 0.0452731975974547 -0.0342376979991347 0.998387759147227 0.0635646458603237 4.1666135614758e-05 -1.21634202729269e-05 5.50505802382176e-07 -1.88661099061157e-06 -6.30775957201825e-07 1.98676023008138e-07 -1.21634202729269e-05 3.15652823488112e-05 9.36593269287005e-06 2.74656088729415e-06 -9.51463502285855e-07 -1.16620063099941e-05 5.50505802382176e-07 9.36593269287005e-06 1.86957194227636e-05 4.16262920500821e-06 -5.10929034082104e-07 3.10287508807415e-06 -1.88661099061157e-06 2.74656088729415e-06 4.16262920500821e-06 2.70469126051114e-05 -1.36149257180141e-05 1.88055201632143e-05 -6.30775957201825e-07 -9.51463502285855e-07 -5.10929034082104e-07 -1.36149257180141e-05 2.36361533906932e-05 -1.13721710611537e-05 1.98676023008138e-07 -1.16620063099941e-05 3.10287508807415e-06 1.88055201632143e-05 -1.13721710611537e-05 0.000123582483820581 666 675 0 1451 0 706 715 0 1437 0 0 0 0 0 0 0 0 0 1754 0 568 568 0 0 58 +306 440 0.530975881461086 0.847322886113212 0.0104182520318629 -0.42442165995458 -0.844220344205014 0.527889819892782 0.0928673703942022 -0.587323735467344 0.0731889591194623 -0.0581056341703886 0.995623980999186 0.158558766456922 4.23316242699729e-05 -3.87637142167676e-06 1.40389460960712e-06 -7.05833566110858e-06 -4.42196282334985e-06 1.09475080250967e-05 -3.87637142167676e-06 3.96672309669723e-05 2.36633262850171e-06 -1.84289326713628e-06 -2.48875491379517e-06 -2.44624836693201e-05 1.40389460960712e-06 2.36633262850171e-06 1.66803481509402e-05 -4.36883882040996e-07 5.79410812262226e-06 -5.95060845613648e-06 -7.05833566110858e-06 -1.84289326713628e-06 -4.36883882040996e-07 3.85502257926989e-05 5.04658830227384e-05 -1.85603025847089e-05 -4.42196282334985e-06 -2.48875491379517e-06 5.79410812262226e-06 5.04658830227384e-05 0.000203101360924554 -6.47250490888853e-05 1.09475080250967e-05 -2.44624836693201e-05 -5.95060845613648e-06 -1.85603025847089e-05 -6.47250490888853e-05 0.000112670428735346 0 0 0 1522 0 0 0 0 1543 0 0 0 0 0 0 0 0 0 1052 0 361 246 0 94 56 +306 441 0.640304306634042 0.768090939723746 0.00683397543093186 -0.387962889797131 -0.766463664125206 0.638312985715738 0.0713441226901233 -0.529648683259839 0.050436558979197 -0.0509199428608471 0.997428349776256 0.128604968414746 4.69838220456559e-05 -1.18246657009671e-05 -3.46358380711445e-07 -5.26279501693291e-06 -2.58507075224222e-06 3.41231157334043e-05 -1.18246657009671e-05 4.28410010295838e-05 5.99931527060386e-06 -1.27993327856558e-06 -7.97763058498218e-06 -8.46536560467131e-06 -3.46358380711445e-07 5.99931527060386e-06 1.82506342455939e-05 2.06486102358743e-06 1.7083444986793e-06 -3.04045591997187e-06 -5.26279501693291e-06 -1.27993327856558e-06 2.06486102358743e-06 3.10962266929514e-05 9.24509609334856e-06 3.49093341048289e-06 -2.58507075224222e-06 -7.97763058498218e-06 1.7083444986793e-06 9.24509609334856e-06 5.36734331227155e-05 -1.07519526394648e-05 3.41231157334043e-05 -8.46536560467131e-06 -3.04045591997187e-06 3.49093341048289e-06 -1.07519526394648e-05 0.000170979976655213 219 173 0 1496 0 256 210 0 1480 0 0 0 0 0 0 0 0 0 1420 0 566 566 0 0 51 +306 443 0.803410697498434 0.595241823688208 -0.0147791230259614 -0.252670159556465 -0.595168806399892 0.803545664003177 0.00940519804258035 -0.404481255087602 0.0174740674602951 0.00123983629149823 0.999846548112441 0.0230883653487692 5.04823537674112e-05 -3.88982115946304e-06 -1.89137131105134e-06 1.13485132114414e-06 1.11076856624215e-05 2.82574380362401e-05 -3.88982115946304e-06 4.1518266348019e-05 4.62662052937198e-06 3.54042961859095e-06 2.85418136454742e-06 1.33654014155578e-05 -1.89137131105134e-06 4.62662052937198e-06 1.87670822720351e-05 7.56632153642583e-06 -1.83202051086684e-07 -4.82750595124707e-06 1.13485132114414e-06 3.54042961859095e-06 7.56632153642583e-06 8.89199549527762e-05 4.85933104548608e-05 -6.76771096236156e-06 1.11076856624215e-05 2.85418136454742e-06 -1.83202051086684e-07 4.85933104548608e-05 8.46708062424639e-05 -1.29749737852263e-06 2.82574380362401e-05 1.33654014155578e-05 -4.82750595124707e-06 -6.76771096236156e-06 -1.29749737852263e-06 0.000198820123198583 1078 1122 0 1284 0 1133 1177 0 1269 0 0 0 0 0 0 0 0 0 2042 0 591 591 0 0 105 +306 439 0.427371923553532 0.903996864386151 0.0119544191895589 -0.505120950623698 -0.901661757988815 0.425227785339958 0.0786600581959774 -0.652126640273904 0.0660250947645942 -0.0443959430002406 0.99682981852794 0.250719048094664 7.57635365904493e-05 -3.1735738000882e-05 -8.65142944396933e-06 -3.56636500311631e-06 1.5460677060631e-05 2.71610436903794e-05 -3.1735738000882e-05 8.28784064456907e-05 1.16380472788512e-05 -7.10929142181784e-06 -2.98113865377038e-05 -4.35918747422244e-05 -8.65142944396933e-06 1.16380472788512e-05 1.56840518041115e-05 -2.95544010171717e-06 -4.98074842889678e-06 -6.35457358239313e-06 -3.56636500311631e-06 -7.10929142181784e-06 -2.95544010171717e-06 3.01605526906233e-05 4.97361440799672e-05 -2.9630577721904e-06 1.5460677060631e-05 -2.98113865377038e-05 -4.98074842889678e-06 4.97361440799672e-05 0.00031327396364694 -5.98715810664364e-05 2.71610436903794e-05 -4.35918747422244e-05 -6.35457358239313e-06 -2.9630577721904e-06 -5.98715810664364e-05 0.000182226968200336 0 0 0 1560 0 0 0 0 1564 0 0 0 0 0 0 0 0 0 664 0 0 0 0 163 14 +307 451 0.997873364396565 -0.0286679027346262 -0.0585397299334175 0.292251980815104 0.0276409126733977 0.999450784593557 -0.0182786520811763 0.0925406631379327 0.0590315896318323 0.0166216884858638 0.998117723967177 -0.0455423065612602 4.36399258068209e-05 -2.00392273190124e-05 -7.69056227718813e-07 -5.12258226583119e-06 2.40212991386625e-06 1.15096015716974e-05 -2.00392273190124e-05 3.09808406467067e-05 1.68162654607657e-06 6.68745715052914e-06 2.0917980505801e-06 -1.93247087594229e-05 -7.69056227718813e-07 1.68162654607657e-06 1.2113829017408e-05 -2.7344389480285e-07 5.83618042008932e-07 1.2496119182148e-06 -5.12258226583119e-06 6.68745715052914e-06 -2.7344389480285e-07 0.000125714564242254 1.73376634966389e-05 -1.00035398980649e-05 2.40212991386625e-06 2.0917980505801e-06 5.83618042008932e-07 1.73376634966389e-05 2.36154750051232e-05 -4.86360924048857e-06 1.15096015716974e-05 -1.93247087594229e-05 1.2496119182148e-06 -1.00035398980649e-05 -4.86360924048857e-06 0.000131233009796277 3266 3344 0 87 615 3266 3344 0 80 731 0 0 0 0 0 0 0 0 3699 0 0 0 0 0 2851 +307 446 0.947564181595235 0.319113874445569 -0.0169840187850524 -0.0871308980579076 -0.318912697931706 0.947687389891829 0.0135389119921837 -0.218238203089504 0.0204159950938834 -0.00741256880909958 0.999764092657851 -0.000861738476585995 6.17850636626789e-05 -1.52635940796722e-06 8.36119090511708e-06 5.3706563330196e-06 1.82106147761808e-06 -1.05541318034971e-05 -1.52635940796722e-06 2.76951938393296e-05 6.80047957506895e-06 -8.63331464102398e-08 -5.20474638818541e-06 -1.07791963026279e-05 8.36119090511708e-06 6.80047957506895e-06 1.82616412397444e-05 2.4060844415789e-06 -2.59408412319748e-06 -4.82593144579555e-06 5.3706563330196e-06 -8.63331464102398e-08 2.4060844415789e-06 3.89677035582933e-05 8.91056141223415e-07 -5.54140229889823e-06 1.82106147761808e-06 -5.20474638818541e-06 -2.59408412319748e-06 8.91056141223415e-07 2.86601623006376e-05 -4.23310837224357e-06 -1.05541318034971e-05 -1.07791963026279e-05 -4.82593144579555e-06 -5.54140229889823e-06 -4.23310837224357e-06 0.000108478827110653 2080 2116 0 823 0 2161 2197 0 815 0 0 0 0 0 0 0 0 0 2870 0 605 605 0 0 571 +307 445 0.921305602870624 0.388438576704054 -0.0176481797170521 -0.141883973126485 -0.388213674249415 0.921448985202169 0.0148966706234295 -0.283798087870036 0.0220483388255372 -0.00687312141771309 0.999733279908702 -0.00857183866695374 7.87066576093636e-05 -4.28883564211408e-05 -7.56261918471577e-06 -2.56069577680324e-05 -1.43280074433359e-05 -1.32805270232219e-05 -4.28883564211408e-05 6.66673940949978e-05 1.37536180024046e-05 -6.40343402082755e-06 -1.56197768526399e-05 4.61641655895696e-05 -7.56261918471577e-06 1.37536180024046e-05 1.87686042371105e-05 3.90157860641558e-06 -1.9174698405877e-06 1.09961000825285e-05 -2.56069577680324e-05 -6.40343402082755e-06 3.90157860641558e-06 0.00014798437777405 8.47863922819793e-05 5.68034639259899e-05 -1.43280074433359e-05 -1.56197768526399e-05 -1.9174698405877e-06 8.47863922819793e-05 9.68344592600461e-05 -6.09435014309643e-06 -1.32805270232219e-05 4.61641655895696e-05 1.09961000825285e-05 5.68034639259899e-05 -6.09435014309643e-06 0.000511218038106109 1631 1664 0 937 0 1707 1740 0 932 0 0 0 0 0 0 0 0 0 2682 0 550 550 0 0 167 +307 443 0.843625541153907 0.536929790753879 -0.00153170289988119 -0.300092108061876 -0.536849629090157 0.843542685940121 0.0151067118423406 -0.429819240508133 0.00940330040671513 -0.0119221138193732 0.99988471392633 0.0363006721026558 6.38240227583255e-05 -2.34062673474944e-05 -9.13890742664927e-07 -8.0675770331445e-06 -1.29096362035574e-06 -2.06952896264595e-05 -2.34062673474944e-05 5.16096088759721e-05 2.08824030252651e-06 -1.36900986928271e-05 -1.35762782733219e-05 2.95170607064931e-05 -9.13890742664927e-07 2.08824030252651e-06 1.87026999121019e-05 2.51573506658187e-06 -3.66445301037517e-06 -3.66337024317615e-06 -8.0675770331445e-06 -1.36900986928271e-05 2.51573506658187e-06 5.06972275205863e-05 2.1116010454563e-05 -4.02256210665848e-05 -1.29096362035574e-06 -1.35762782733219e-05 -3.66445301037517e-06 2.1116010454563e-05 6.68089911412961e-05 -5.31835384589302e-05 -2.06952896264595e-05 2.95170607064931e-05 -3.66337024317615e-06 -4.02256210665848e-05 -5.31835384589302e-05 0.000289455067149923 1095 1106 0 1067 0 1149 1160 0 1064 0 0 0 0 0 0 0 0 0 2252 0 570 570 0 0 161 +307 311 0.951405353704169 0.307486567554623 0.0167291277872273 0.189776491196554 -0.307941232507093 0.949960579704217 0.0524127306104151 -0.027341067728445 0.000224198700861288 -0.0550173407345707 0.998485373930654 -0.0258506321479877 4.77206430106705e-05 -1.11760590808624e-05 -3.52830708542773e-06 2.31648257159076e-06 5.54426648136402e-06 8.10056308297923e-06 -1.11760590808624e-05 3.02869354352997e-05 3.92919766432853e-06 -3.58604145317616e-07 6.19583896251825e-07 -1.6221336504711e-05 -3.52830708542773e-06 3.92919766432853e-06 1.40593129821224e-05 -1.82373044297871e-06 1.33405993977107e-06 -1.32425894321246e-06 2.31648257159076e-06 -3.58604145317616e-07 -1.82373044297871e-06 9.01645176780855e-05 4.62122725038678e-05 1.41862471254451e-05 5.54426648136402e-06 6.19583896251825e-07 1.33405993977107e-06 4.62122725038678e-05 5.03193440371602e-05 1.74825463166597e-08 8.10056308297923e-06 -1.6221336504711e-05 -1.32425894321246e-06 1.41862471254451e-05 1.74825463166597e-08 0.000114518105958252 3046 3088 0 936 0 3173 3215 0 930 0 0 0 0 0 0 0 0 0 2886 0 252 394 0 0 3071 +307 450 0.998162253320955 0.0414505966742626 -0.0442036659178931 0.206539548968097 -0.041343592302753 0.999139430349757 0.00333258096183892 0.0384821951003221 0.0443037630539082 -0.00149891818024718 0.999016981749335 -0.0136541881654522 4.74716402809158e-05 -3.02862947066368e-05 -3.79715410374675e-06 -1.65786048904673e-06 2.86526427891549e-06 4.684335770294e-06 -3.02862947066368e-05 6.21685671036741e-05 6.40074063926179e-06 -5.16477443035707e-06 -1.7628951355608e-06 4.48716388879155e-05 -3.79715410374675e-06 6.40074063926179e-06 1.47195488536826e-05 1.6416680426162e-06 7.09702723969352e-07 -3.31178934705236e-06 -1.65786048904673e-06 -5.16477443035707e-06 1.6416680426162e-06 7.17123676530882e-05 4.09597193921721e-06 3.51268210980251e-05 2.86526427891549e-06 -1.7628951355608e-06 7.09702723969352e-07 4.09597193921721e-06 2.05277781606161e-05 2.50854282452771e-06 4.684335770294e-06 4.48716388879155e-05 -3.31178934705236e-06 3.51268210980251e-05 2.50854282452771e-06 0.000366292321740766 3231 3330 0 238 175 3231 3330 0 231 295 0 0 0 0 0 0 0 0 3547 0 0 0 0 0 3116 +307 442 0.776484853827826 0.630132140748683 -0.00218104824833502 -0.352888392801856 -0.628926253384359 0.775203970138326 0.0592500842673698 -0.49537484470132 0.0390261397001101 -0.0446350745183591 0.998240787857743 0.0749158303057759 4.68673187603352e-05 -1.60256592051843e-05 -3.24294738707089e-08 4.90368521605386e-06 8.20366518941094e-06 2.99988873946388e-05 -1.60256592051843e-05 4.11591935037242e-05 4.5106429406237e-06 2.71318454180197e-06 -2.47023597681655e-06 -2.27181930814819e-05 -3.24294738707089e-08 4.5106429406237e-06 1.63761698669745e-05 1.82661686201401e-06 -7.33430227005077e-07 -3.337653232255e-06 4.90368521605386e-06 2.71318454180197e-06 1.82661686201401e-06 2.6650021432784e-05 -1.06831829689505e-06 7.00092639881859e-06 8.20366518941094e-06 -2.47023597681655e-06 -7.33430227005077e-07 -1.06831829689505e-06 4.00286869641656e-05 7.83198319238131e-06 2.99988873946388e-05 -2.27181930814819e-05 -3.337653232255e-06 7.00092639881859e-06 7.83198319238131e-06 0.000125720025789715 695 705 0 1225 0 737 747 0 1223 0 0 0 0 0 0 0 0 0 1958 0 546 546 0 0 147 +307 439 0.493223242399248 0.869306768947066 0.0321958789286026 -0.505743215310253 -0.868291201732819 0.489720388994078 0.0790210705879531 -0.690058400495479 0.0529265731986301 -0.0669304270590108 0.996352897212202 0.253913207341708 5.53037463657331e-05 -1.71010565202594e-05 -5.32864915913753e-06 -1.03445065462532e-05 -6.2027929864552e-06 -8.05465736053989e-06 -1.71010565202594e-05 5.83534430213948e-05 1.0102539619169e-05 -1.30935465454407e-06 -3.89794539589014e-06 -1.88660166381405e-05 -5.32864915913753e-06 1.0102539619169e-05 1.6977514593422e-05 -5.91906563904002e-07 1.61146286458044e-06 9.58034136304384e-07 -1.03445065462532e-05 -1.30935465454407e-06 -5.91906563904002e-07 2.30868726714996e-05 6.32786013539274e-06 2.32500519230632e-05 -6.2027929864552e-06 -3.89794539589014e-06 1.61146286458044e-06 6.32786013539274e-06 7.86534631689245e-05 4.33375733229847e-06 -8.05465736053989e-06 -1.88660166381405e-05 9.58034136304384e-07 2.32500519230632e-05 4.33375733229847e-06 0.000157016397655095 0 0 0 1412 0 0 0 0 1419 0 0 0 0 0 0 0 0 0 843 0 0 0 0 164 93 +307 440 0.592625832512651 0.80508287625316 0.0252227080748095 -0.457961691191504 -0.802951545518716 0.587999207844609 0.0975999340328562 -0.626957621413591 0.0637451032456067 -0.0780928545902369 0.994906059823818 0.168033497549286 7.19290475375981e-05 -1.68939453707772e-05 -1.16364241596539e-05 -5.8801687881442e-06 2.87959571699059e-06 3.59403076650015e-05 -1.68939453707772e-05 8.86784681786524e-05 1.53881052788707e-05 -9.51529706603809e-06 -3.4465545648645e-05 -1.50726218911683e-05 -1.16364241596539e-05 1.53881052788707e-05 2.22033871266385e-05 -1.2989099050594e-06 -7.29832263961112e-06 -6.51876154719666e-06 -5.8801687881442e-06 -9.51529706603809e-06 -1.2989099050594e-06 3.08871918282035e-05 2.88798366956947e-05 -5.5183778474555e-07 2.87959571699059e-06 -3.4465545648645e-05 -7.29832263961112e-06 2.88798366956947e-05 0.000145877342571707 -4.91114750898785e-05 3.59403076650015e-05 -1.50726218911683e-05 -6.51876154719666e-06 -5.5183778474555e-07 -4.91114750898785e-05 0.00021092020033276 0 0 0 1225 0 0 0 0 1256 0 0 0 0 0 0 0 0 0 1244 0 366 246 0 79 113 +307 441 0.694036606640425 0.719747765037224 0.0166235786449778 -0.40856061529284 -0.718615430150829 0.691175408250516 0.0766056040957298 -0.559343968011673 0.0436469035807008 -0.0651130536348471 0.996922884707821 0.128423986939283 4.57524753655275e-05 -1.7300646715362e-05 -5.31352469403709e-06 -3.45232949474963e-07 6.73105773199079e-06 1.19362423613724e-05 -1.7300646715362e-05 3.21433692771954e-05 4.44706086638893e-06 -3.42214763713901e-07 7.82141123399583e-07 -2.03882303627384e-05 -5.31352469403709e-06 4.44706086638893e-06 1.43854197858853e-05 -1.28538062742103e-06 4.26455073951284e-06 -3.81957185070313e-06 -3.45232949474963e-07 -3.42214763713901e-07 -1.28538062742103e-06 2.46359825099698e-05 1.01436247609425e-05 -4.20806654813586e-07 6.73105773199079e-06 7.82141123399583e-07 4.26455073951284e-06 1.01436247609425e-05 5.21072437448705e-05 -6.68531372440267e-06 1.19362423613724e-05 -2.03882303627384e-05 -3.81957185070313e-06 -4.20806654813586e-07 -6.68531372440267e-06 7.46177367311224e-05 252 206 0 1397 0 294 248 0 1393 0 0 0 0 0 0 0 0 0 1612 0 538 538 0 0 113 +308 310 0.985223404713543 0.16919262834103 0.0266213696061564 0.114648586179998 -0.169912726082944 0.985072239967869 0.0276106421466044 0.00346266994329717 -0.0215524550739815 -0.0317259603438485 0.999264206864503 -0.0281964390205271 4.80089188387352e-05 -2.56808926622416e-05 3.92610415625041e-07 6.23046327568288e-06 3.07849914389446e-06 1.85691809426012e-05 -2.56808926622416e-05 4.58323799449081e-05 2.27945205613223e-08 3.68166354650633e-06 9.68815608023912e-07 -1.98973221646446e-05 3.92610415625041e-07 2.27945205613223e-08 1.42489863189274e-05 2.37974053209422e-06 1.92386535936313e-06 6.4222747237658e-07 6.23046327568288e-06 3.68166354650633e-06 2.37974053209422e-06 5.60934260612377e-05 1.13603731789337e-05 1.14555814205442e-05 3.07849914389446e-06 9.68815608023912e-07 1.92386535936313e-06 1.13603731789337e-05 2.60132095243508e-05 2.88563507643472e-06 1.85691809426012e-05 -1.98973221646446e-05 6.4222747237658e-07 1.14555814205442e-05 2.88563507643472e-06 9.8499166495629e-05 3104 3140 0 534 0 3230 3266 0 541 0 0 0 0 0 0 0 0 0 3351 0 3 125 0 0 3346 +308 449 0.998671699376983 0.0443596851089161 -0.0262117378387378 0.0557133966785107 -0.044083324501193 0.998966976147598 0.0110291009355705 -0.0220746254133597 0.0266739079328738 -0.0098589504290412 0.999595570084235 -0.0108456911603506 5.83489261206461e-05 -4.12278365640654e-05 2.21431371424977e-06 1.01921582034733e-05 3.02335934880106e-06 3.81657327764131e-05 -4.12278365640654e-05 6.80380728276248e-05 1.37830678548331e-06 -9.55725348637204e-06 -5.21292159598232e-06 -2.58803786117792e-05 2.21431371424977e-06 1.37830678548331e-06 1.45629403674021e-05 3.0204521523276e-06 1.29619935317262e-06 -1.45616701805513e-06 1.01921582034733e-05 -9.55725348637204e-06 3.0204521523276e-06 6.05149035324431e-05 3.22324367571868e-07 2.34505785334428e-05 3.02335934880106e-06 -5.21292159598232e-06 1.29619935317262e-06 3.22324367571868e-07 1.90027525847393e-05 5.81209939674486e-06 3.81657327764131e-05 -2.58803786117792e-05 -1.45616701805513e-06 2.34505785334428e-05 5.81209939674486e-06 0.0001346039669278 3197 3211 0 161 0 3238 3321 0 169 0 0 0 0 0 0 0 0 0 3624 0 0 0 0 0 3289 +308 452 0.987134168828445 -0.158760892466819 -0.0190029406807207 0.314502179758975 0.157846028505621 0.986544513655904 -0.0425975804528579 0.159140873346723 0.0255100767615164 0.039049988458055 0.998911574857879 0.0131916513827572 3.78427116504466e-05 -2.29136200289213e-05 3.8648103967018e-06 -6.20630654253064e-06 3.73323523236088e-07 2.58906699602009e-05 -2.29136200289213e-05 4.74019907355678e-05 1.49185208174544e-06 4.74637498247818e-06 8.00819277936844e-07 1.80503494393985e-05 3.8648103967018e-06 1.49185208174544e-06 1.81446713920223e-05 8.02490603457941e-06 -4.21709572295634e-06 -7.92024588480735e-06 -6.20630654253064e-06 4.74637498247818e-06 8.02490603457941e-06 0.000150302651481261 5.18181731281387e-06 7.56164030035965e-05 3.73323523236088e-07 8.00819277936844e-07 -4.21709572295634e-06 5.18181731281387e-06 2.58782590480965e-05 2.09891373376364e-05 2.58906699602009e-05 1.80503494393985e-05 -7.92024588480735e-06 7.56164030035965e-05 2.09891373376364e-05 0.000237028436746417 3039 3118 0 0 1110 3045 3124 0 0 1239 0 0 0 0 0 290 273 0 3787 0 0 0 0 0 2545 +308 444 0.919594411874991 0.392699833895408 0.0115307461513843 -0.239433137276806 -0.3924124793145 0.919544558522451 -0.0212191180306524 -0.370243364316197 -0.0189357790052534 0.014988173680293 0.999708352932591 0.0221224349764172 4.62410108856577e-05 -2.78363603422933e-05 1.91269175960464e-06 5.99990710003753e-07 3.55779809410497e-06 2.19487257408138e-05 -2.78363603422933e-05 4.99807251013583e-05 1.89573715380851e-06 -5.30709912533729e-06 -4.3910371127366e-06 -1.49969570837871e-05 1.91269175960464e-06 1.89573715380851e-06 1.59622825259726e-05 -6.15603188178623e-07 -7.76301515003059e-07 3.53194792956471e-06 5.99990710003753e-07 -5.30709912533729e-06 -6.15603188178623e-07 3.36302005223648e-05 2.38558858545775e-06 -7.79951319964388e-06 3.55779809410497e-06 -4.3910371127366e-06 -7.76301515003059e-07 2.38558858545775e-06 3.18779650533505e-05 -1.49254297287404e-05 2.19487257408138e-05 -1.49969570837871e-05 3.53194792956471e-06 -7.79951319964388e-06 -1.49254297287404e-05 0.000122222848841854 1446 1461 0 802 0 1515 1530 0 807 0 0 0 0 0 0 0 0 0 2684 0 490 490 0 0 208 +308 448 0.993468759124251 0.110932715235403 -0.0267162372841267 -0.0259486446729965 -0.110094774125228 0.993436708362513 0.0310265561764485 -0.0939972962288552 0.0299827509484318 -0.0278825961552432 0.999161446152326 -0.0267034810038964 2.96770599763524e-05 -1.60226785153518e-05 -2.82311009804001e-07 -7.52359611366857e-06 9.66048492425209e-08 4.4085765253e-06 -1.60226785153518e-05 2.16428985479e-05 5.77897407857869e-07 1.24555899231784e-06 -1.10092201459954e-06 -9.1550382125641e-06 -2.82311009804001e-07 5.77897407857869e-07 1.21064536319394e-05 -3.60839693099773e-07 5.94104996413163e-07 -1.67352439402374e-06 -7.52359611366857e-06 1.24555899231784e-06 -3.60839693099773e-07 3.90037616822601e-05 4.22657579998892e-07 -8.55632574173395e-07 9.66048492425209e-08 -1.10092201459954e-06 5.94104996413163e-07 4.22657579998892e-07 1.972230752669e-05 1.88732622891124e-06 4.4085765253e-06 -9.1550382125641e-06 -1.67352439402374e-06 -8.55632574173395e-07 1.88732622891124e-06 8.39721612950867e-05 2858 2886 0 341 0 2956 2984 0 348 0 0 0 0 0 0 0 0 0 3458 0 309 443 0 0 2024 +308 447 0.983730364834453 0.179349551277871 -0.0104071013783937 -0.069782625632468 -0.179186211886573 0.983701657476888 0.0149449170945825 -0.152361118860552 0.0129178470502542 -0.0128369596731604 0.999834157095033 -0.0172542695899765 5.15029705546984e-05 -4.16417551666052e-06 1.16455260834809e-05 -3.6359840754038e-06 -8.51878755916568e-06 3.32244936728876e-06 -4.16417551666052e-06 3.01527056416529e-05 4.91239423568917e-06 -5.53258381634996e-06 -6.93112854055642e-06 7.93414330517221e-06 1.16455260834809e-05 4.91239423568917e-06 2.03673692821943e-05 6.32739889368664e-06 -3.09929219087724e-06 4.79882666319784e-06 -3.6359840754038e-06 -5.53258381634996e-06 6.32739889368664e-06 4.95830786263943e-05 6.06309836072925e-07 -5.96056633430623e-06 -8.51878755916568e-06 -6.93112854055642e-06 -3.09929219087724e-06 6.06309836072925e-07 2.86912703865705e-05 -1.27039417654783e-05 3.32244936728876e-06 7.93414330517221e-06 4.79882666319784e-06 -5.96056633430623e-06 -1.27039417654783e-05 0.000154655670396607 2579 2616 0 538 0 2674 2711 0 545 0 0 0 0 0 0 0 0 0 3254 0 604 630 0 0 1100 +308 439 0.552183908653017 0.832730045259253 0.040664514594411 -0.514943960463673 -0.833015304826426 0.549050703363276 0.0680354838391584 -0.733969643187877 0.03432831119663 -0.0714422624138875 0.996853835921582 0.279833366298274 3.74191801701962e-05 -1.33130149255984e-05 -6.89554237022956e-06 -1.8106883744431e-06 5.973648929421e-06 1.08952984507759e-05 -1.33130149255984e-05 4.49674905885826e-05 1.38133069291054e-05 1.28175789671913e-06 -4.1942027829049e-06 -3.04919542503413e-05 -6.89554237022956e-06 1.38133069291054e-05 2.17452040546526e-05 2.00949633181664e-06 -1.81489722569868e-06 -8.65662343746563e-06 -1.8106883744431e-06 1.28175789671913e-06 2.00949633181664e-06 2.59432572948451e-05 7.33226337905048e-06 4.94467606733994e-06 5.973648929421e-06 -4.1942027829049e-06 -1.81489722569868e-06 7.33226337905048e-06 0.000128048966216615 -1.12332717661125e-05 1.08952984507759e-05 -3.04919542503413e-05 -8.65662343746563e-06 4.94467606733994e-06 -1.12332717661125e-05 9.93015119916425e-05 0 0 0 1394 0 0 0 0 1413 0 0 0 0 0 0 0 0 0 982 0 0 0 0 144 194 +308 311 0.970499697492354 0.239038957780836 0.0314756069091776 0.128211278971712 -0.240075661546368 0.970131640740342 0.0347602699576117 -0.0196501531629961 -0.0222264234712505 -0.041291358629909 0.998899899790851 -0.0383469753019032 8.00869610868051e-05 -6.18028767315716e-05 -1.63383993203119e-06 -2.09609840237671e-05 -1.78974391258364e-05 6.11271541370461e-05 -6.18028767315716e-05 0.000113521886623028 9.22062183961641e-06 7.66884322661838e-06 6.87201638655995e-06 -3.89509847154715e-05 -1.63383993203119e-06 9.22062183961641e-06 1.71849812695283e-05 -1.49431145277419e-06 -7.0491281867414e-08 -5.94202855151341e-06 -2.09609840237671e-05 7.66884322661838e-06 -1.49431145277419e-06 8.09833609594894e-05 4.27706172502726e-05 -2.05748118985327e-05 -1.78974391258364e-05 6.87201638655995e-06 -7.0491281867414e-08 4.27706172502726e-05 4.92946119132874e-05 -1.76216659529134e-05 6.11271541370461e-05 -3.89509847154715e-05 -5.94202855151341e-06 -2.05748118985327e-05 -1.76216659529134e-05 0.000213305400790974 2899 2932 0 697 0 3023 3056 0 702 0 0 0 0 0 0 0 0 0 3076 0 173 315 0 0 3110 +308 446 0.967335543891872 0.253477055866642 -0.00336566079634141 -0.137784054897142 -0.253498267036879 0.96728564617982 -0.00985430382047553 -0.230132822489595 0.000757715458181654 0.010385607525162 0.999945781041961 -0.006695258296786 4.37940120005198e-05 -1.72071356976228e-05 -1.18883627027539e-07 -1.22447870716685e-05 -3.10498812521222e-06 1.75701959465021e-06 -1.72071356976228e-05 3.24357792644499e-05 1.56739794339738e-06 5.17186619116116e-06 1.48360786017493e-06 -5.61398695655803e-07 -1.18883627027539e-07 1.56739794339738e-06 1.34215959291305e-05 8.79461137759542e-07 2.11051336520833e-06 3.67505274516098e-06 -1.22447870716685e-05 5.17186619116116e-06 8.79461137759542e-07 4.10992700234252e-05 2.47966073704456e-06 3.38408120396809e-05 -3.10498812521222e-06 1.48360786017493e-06 2.11051336520833e-06 2.47966073704456e-06 2.12914994302279e-05 1.08444606755312e-05 1.75701959465021e-06 -5.61398695655803e-07 3.67505274516098e-06 3.38408120396809e-05 1.08444606755312e-05 0.000183068111063617 2099 2137 0 634 0 2185 2223 0 635 0 0 0 0 0 0 0 0 0 3069 0 560 560 0 0 675 +308 438 0.467139454086076 0.883461551846232 0.0357269764409136 -0.567689069237054 -0.884181650426573 0.466842868174955 0.0167494920258056 -0.783822618819818 -0.00188135193514087 -0.0394134855554322 0.99922121558305 0.343057686920185 5.56537018960639e-05 -3.02665758051051e-05 -8.06785133064763e-06 -6.11086737039835e-06 1.68179552534499e-05 2.2766040525569e-05 -3.02665758051051e-05 7.55053221084251e-05 4.24709134985309e-06 -5.62460952770838e-06 -9.3794466769562e-07 -6.32244616780175e-05 -8.06785133064763e-06 4.24709134985309e-06 1.83257601619193e-05 3.48120312144421e-07 -5.76414445986628e-06 -7.64057540912277e-06 -6.11086737039835e-06 -5.62460952770838e-06 3.48120312144421e-07 2.6249428233855e-05 1.58824750786822e-05 1.17066409186854e-05 1.68179552534499e-05 -9.3794466769562e-07 -5.76414445986628e-06 1.58824750786822e-05 0.000253743530046981 4.84558295869417e-05 2.2766040525569e-05 -6.32244616780175e-05 -7.64057540912277e-06 1.17066409186854e-05 4.84558295869417e-05 0.000166149860401776 0 0 0 1143 0 0 0 0 1168 0 0 0 0 0 0 0 0 0 649 0 0 0 0 220 212 +308 445 0.946123657468281 0.323799741846303 0.00193699744699446 -0.197033233892737 -0.323782881642406 0.946111297382004 -0.00616915889577668 -0.304453219666403 -0.00383018722546288 0.00520962056285337 0.999979094541185 0.0187037868732045 4.58141916268397e-05 -1.92829212619678e-05 -3.08392047253601e-07 -3.29622801528637e-06 4.41081149771165e-07 -2.11293655679681e-05 -1.92829212619678e-05 4.18157009358326e-05 1.09237100058334e-06 -4.26977686809517e-06 -4.92192794303587e-06 -5.76244761850885e-06 -3.08392047253601e-07 1.09237100058334e-06 1.47559045306478e-05 1.86807291585141e-06 1.23833133924374e-06 -9.69457601382594e-07 -3.29622801528637e-06 -4.26977686809517e-06 1.86807291585141e-06 5.35406911058249e-05 1.69485627055321e-05 1.25323541237945e-06 4.41081149771165e-07 -4.92192794303587e-06 1.23833133924374e-06 1.69485627055321e-05 3.83720259650187e-05 -8.43832854502166e-06 -2.11293655679681e-05 -5.76244761850885e-06 -9.69457601382594e-07 1.25323541237945e-06 -8.43832854502166e-06 0.000193094597104799 1669 1678 0 670 0 1747 1756 0 677 0 0 0 0 0 0 0 0 0 2898 0 525 525 0 0 252 +308 443 0.878907939864124 0.476615498079404 0.0189341024166064 -0.329744409327148 -0.476608235838074 0.879100511642511 -0.00518458881641977 -0.456484053999351 -0.0191160345030052 -0.0044673728742741 0.999807291333926 0.0547145149593402 4.22099222805265e-05 -1.7220576307558e-05 2.45030826911608e-06 9.95744069032191e-07 -5.1848956191725e-06 -6.05867755466634e-06 -1.7220576307558e-05 3.76305721554275e-05 7.82386638088606e-06 7.17572257917812e-07 -1.85960186272031e-06 -5.91208249383572e-06 2.45030826911608e-06 7.82386638088606e-06 1.56990816807591e-05 4.21724928111668e-07 -7.73949388578553e-07 -2.59654477037205e-07 9.95744069032191e-07 7.17572257917812e-07 4.21724928111668e-07 2.68624957759734e-05 2.00279337632523e-06 5.38972120896249e-06 -5.1848956191725e-06 -1.85960186272031e-06 -7.73949388578553e-07 2.00279337632523e-06 3.22646037899549e-05 -4.1332152356593e-06 -6.05867755466634e-06 -5.91208249383572e-06 -2.59654477037205e-07 5.38972120896249e-06 -4.1332152356593e-06 0.000135766881970149 1111 1134 0 795 0 1165 1188 0 800 0 0 0 0 0 0 0 0 0 2423 0 535 535 0 0 226 +308 451 0.994829378815777 -0.0975169392930452 -0.0283717041421856 0.220136678871985 0.0964687869119704 0.994676513789364 -0.0362271454515817 0.103257349279779 0.0317534281101747 0.0333028447246438 0.998940759172684 0.0109103383545144 2.80488694788026e-05 -1.4262442953521e-05 8.18489903910408e-07 5.35707778413315e-06 5.5953397711878e-06 -9.84163006432573e-06 -1.4262442953521e-05 1.90291983663426e-05 8.64271977819331e-07 -7.74209352693721e-06 -3.00366935784065e-06 -2.77358412939517e-06 8.18489903910408e-07 8.64271977819331e-07 1.11478315911814e-05 2.76948296182753e-07 7.68651653716981e-07 1.12752429242636e-06 5.35707778413315e-06 -7.74209352693721e-06 2.76948296182753e-07 8.72276186460923e-05 9.95106479102445e-06 -1.42756195630079e-05 5.5953397711878e-06 -3.00366935784065e-06 7.68651653716981e-07 9.95106479102445e-06 1.96594582702825e-05 -4.44395730916452e-06 -9.84163006432573e-06 -2.77358412939517e-06 1.12752429242636e-06 -1.42756195630079e-05 -4.44395730916452e-06 0.000110290870357827 3336 3425 0 0 668 3344 3433 0 0 787 0 0 0 0 0 170 159 0 3786 0 0 0 0 0 2775 +308 441 0.743832354613738 0.667981452788345 0.0226761319575276 -0.451929837235561 -0.667980581281927 0.74182277639036 0.0591685005620129 -0.60625938728274 0.0227017897981941 -0.0591586608982213 0.997990421587646 0.129615425762411 5.42049161187475e-05 -3.73217377890807e-05 -6.95750850781023e-06 -7.0420963241879e-06 3.00631065831142e-06 -1.36085404306442e-05 -3.73217377890807e-05 7.52654907837789e-05 7.77030450297209e-06 1.94005850151118e-06 -1.33623437850253e-05 8.07395525760014e-05 -6.95750850781023e-06 7.77030450297209e-06 1.46033002994506e-05 -1.7444684135136e-06 8.6804355127479e-07 4.09421250852893e-06 -7.0420963241879e-06 1.94005850151118e-06 -1.7444684135136e-06 2.71222200756145e-05 1.20102247212804e-05 2.54400375656636e-05 3.00631065831142e-06 -1.33623437850253e-05 8.6804355127479e-07 1.20102247212804e-05 6.33048727695896e-05 -4.51170423879021e-05 -1.36085404306442e-05 8.07395525760014e-05 4.09421250852893e-06 2.54400375656636e-05 -4.51170423879021e-05 0.000535941029631265 250 204 0 1011 0 292 246 0 1017 0 0 0 0 0 0 0 0 0 1762 0 533 533 0 0 169 +308 442 0.81867955360702 0.574175920264104 0.00926288803126039 -0.383811483381291 -0.574031969909352 0.817816248769653 0.0407906946535913 -0.528001678074249 0.0158456942984392 -0.0387117015539566 0.999124776059026 0.0790209753375002 3.96670393706385e-05 -2.49753799382227e-05 -6.62091662816793e-07 2.90318586561148e-06 6.86713919258967e-06 2.42164841274487e-05 -2.49753799382227e-05 5.39118945320073e-05 5.43668224805762e-06 -2.22695654111579e-06 -2.56827810516516e-06 -1.62861603129747e-05 -6.62091662816793e-07 5.43668224805762e-06 1.61928437672192e-05 -1.07327864179078e-06 -1.16843732603841e-06 -9.40998166052945e-06 2.90318586561148e-06 -2.22695654111579e-06 -1.07327864179078e-06 2.46429727684563e-05 1.92011404353852e-06 -6.5383191307386e-06 6.86713919258967e-06 -2.56827810516516e-06 -1.16843732603841e-06 1.92011404353852e-06 4.50256460703856e-05 -1.49182540116645e-05 2.42164841274487e-05 -1.62861603129747e-05 -9.40998166052945e-06 -6.5383191307386e-06 -1.49182540116645e-05 0.000155350532317086 712 722 0 947 0 760 770 0 953 0 0 0 0 0 0 0 0 0 2082 0 516 516 0 0 245 +308 440 0.646895026332598 0.761837412500806 0.033624125568167 -0.483275138276284 -0.761797249427139 0.64360723846402 0.0737202371263305 -0.670523279434188 0.034522104098574 -0.0733040211093053 0.996711966827836 0.173956407131027 5.90815286147434e-05 -1.71678182923066e-05 4.11212800310367e-07 -8.07472296757473e-06 -2.93845741080264e-06 -1.39140598964227e-05 -1.71678182923066e-05 4.66907722441275e-05 5.84346801528179e-06 -7.64397164104777e-06 -1.50979151888155e-05 -2.42935017998194e-05 4.11212800310367e-07 5.84346801528179e-06 1.83115795223984e-05 -7.20697377624414e-07 -2.72628919862821e-08 -2.3197259051737e-06 -8.07472296757473e-06 -7.64397164104777e-06 -7.20697377624414e-07 3.51799557413085e-05 2.51473190367791e-05 2.52007756712073e-05 -2.93845741080264e-06 -1.50979151888155e-05 -2.72628919862821e-08 2.51473190367791e-05 0.000112041430245615 1.04379319589532e-05 -1.39140598964227e-05 -2.42935017998194e-05 -2.3197259051737e-06 2.52007756712073e-05 1.04379319589532e-05 0.000151897737487809 0 0 0 1085 0 0 0 0 1130 0 0 0 0 0 0 0 0 0 1346 0 366 246 0 58 177 +309 449 0.998374450052513 -0.0363722884419837 -0.0438806804395155 0.00421460987840671 0.0360157144625094 0.999311684365274 -0.00888964581941278 -0.0223095519624757 0.0441738134429973 0.00729480119898765 0.998997227264105 -0.0178922109710676 5.26263850871749e-05 -3.99665818296713e-05 -1.30541675956977e-06 4.5280893368787e-07 -1.33169972283187e-06 3.71839494082316e-05 -3.99665818296713e-05 0.000146311791734155 4.70658819885968e-06 1.58320947317363e-05 1.43859242149797e-05 -0.000103730263497681 -1.30541675956977e-06 4.70658819885968e-06 1.43930901183509e-05 9.01546905434441e-07 3.65408584769234e-06 -6.98111679605125e-06 4.5280893368787e-07 1.58320947317363e-05 9.01546905434441e-07 5.68694571000917e-05 8.36352874095995e-06 6.11374723522449e-06 -1.33169972283187e-06 1.43859242149797e-05 3.65408584769234e-06 8.36352874095995e-06 2.09256065598844e-05 -1.22542688195825e-05 3.71839494082316e-05 -0.000103730263497681 -6.98111679605125e-06 6.11374723522449e-06 -1.22542688195825e-05 0.00027866295455422 2926 2973 0 0 0 2946 3063 0 0 0 0 0 0 0 0 99 113 0 3700 0 0 0 0 0 3308 +309 447 0.995107868210506 0.0982241112778185 -0.010599744771677 -0.114833665148462 -0.0982012978905092 0.995163035377529 0.00265294379914865 -0.166334055003582 0.0108090572281506 -0.00159905655456627 0.999940301868053 0.00153057387578989 4.98566159313259e-05 -4.38747684923845e-05 -1.65098472884564e-06 -4.65395059212489e-06 -4.71714620057534e-06 3.17120554728322e-05 -4.38747684923845e-05 6.72010680869146e-05 2.66833057336822e-06 -2.14573826825273e-06 3.19399088972055e-06 -4.03672459849841e-05 -1.65098472884564e-06 2.66833057336822e-06 1.38255507677179e-05 8.34759555357549e-07 1.7406584617331e-06 -3.59901259797091e-07 -4.65395059212489e-06 -2.14573826825273e-06 8.34759555357549e-07 5.5622038691447e-05 1.27916831367534e-05 1.55842301354842e-05 -4.71714620057534e-06 3.19399088972055e-06 1.7406584617331e-06 1.27916831367534e-05 2.69951571489232e-05 -8.08806009451854e-08 3.17120554728322e-05 -4.03672459849841e-05 -3.59901259797091e-07 1.55842301354842e-05 -8.08806009451854e-08 0.000117848889988639 2329 2360 0 280 0 2436 2467 0 302 0 0 0 0 0 0 0 0 0 3398 0 523 549 0 0 1191 +309 451 0.982908216917037 -0.179352699825932 -0.0415216351089452 0.165324079155594 0.176844635784916 0.982541012331654 -0.0577852392950641 0.119593530671508 0.0511606480712659 0.0494547080816001 0.997465197356525 -0.00857555485096558 2.90418459545527e-05 -1.20964678377292e-05 8.85515460222588e-07 -1.98231581939266e-06 3.96298555448582e-07 1.48932068308878e-05 -1.20964678377292e-05 2.5611035778348e-05 4.80428963466825e-06 -2.54585462734003e-06 -2.69459504669042e-06 -3.05785685486431e-07 8.85515460222588e-07 4.80428963466825e-06 1.32743625996284e-05 -1.15068245897139e-06 3.45152293452812e-07 -1.22480509218135e-06 -1.98231581939266e-06 -2.54585462734003e-06 -1.15068245897139e-06 8.43880805574246e-05 9.11100804920431e-06 2.28488783059482e-05 3.96298555448582e-07 -2.69459504669042e-06 3.45152293452812e-07 9.11100804920431e-06 1.86083173886683e-05 1.79611566643955e-06 1.48932068308878e-05 -3.05785685486431e-07 -1.22480509218135e-06 2.28488783059482e-05 1.79611566643955e-06 7.48652374872396e-05 2969 3058 0 0 788 2989 3078 0 0 922 0 0 0 0 0 433 422 0 3752 0 0 0 0 0 2651 +309 445 0.969358543100868 0.245601336629546 -0.00489881242167997 -0.218379882793248 -0.245648139865099 0.96907625300507 -0.0234138258828006 -0.322448657785396 -0.00100314414665096 0.0238997763051027 0.999713856258073 0.0110832974179025 6.11325291698137e-05 -4.37107745579555e-05 -7.95568963675078e-06 -1.50021929623365e-06 6.17823336183364e-06 2.81220258231987e-05 -4.37107745579555e-05 8.26818963243513e-05 9.091355764627e-06 -8.82718314937575e-06 -7.93740431402034e-06 -3.78691215015367e-05 -7.95568963675078e-06 9.091355764627e-06 1.64796547847879e-05 -5.9666114474373e-07 1.21056416990618e-06 -3.95254490083702e-06 -1.50021929623365e-06 -8.82718314937575e-06 -5.9666114474373e-07 5.40371290939446e-05 1.63519853149866e-05 2.80991508248416e-05 6.17823336183364e-06 -7.93740431402034e-06 1.21056416990618e-06 1.63519853149866e-05 3.30192949708053e-05 1.25623878021314e-05 2.81220258231987e-05 -3.78691215015367e-05 -3.95254490083702e-06 2.80991508248416e-05 1.25623878021314e-05 0.000209215913476113 1711 1737 0 519 0 1793 1819 0 534 0 0 0 0 0 0 0 0 0 3025 0 441 441 0 0 377 +309 311 0.98675883843463 0.16137989051957 0.0162334748908206 0.0733311160769856 -0.161651480828366 0.986699825886131 0.0170953895034512 -0.0153115401927161 -0.0132587147618432 -0.0194931919441043 0.999722072353459 -0.0182113514605834 4.78677236085896e-05 -3.0240330600271e-05 -3.25590382306938e-06 7.64571958192682e-06 3.78144054534304e-06 4.01098702718329e-05 -3.0240330600271e-05 4.71414266387068e-05 5.5362122800801e-06 -1.03826175433657e-06 -3.06423050704797e-06 -1.14102695371087e-05 -3.25590382306938e-06 5.5362122800801e-06 1.59605762321771e-05 -2.09652615098674e-06 -2.56730152391776e-07 3.103639634926e-07 7.64571958192682e-06 -1.03826175433657e-06 -2.09652615098674e-06 7.97085356419578e-05 3.70594910247404e-05 2.7205854954249e-05 3.78144054534304e-06 -3.06423050704797e-06 -2.56730152391776e-07 3.70594910247404e-05 4.43522582574466e-05 4.12815119240131e-06 4.01098702718329e-05 -1.14102695371087e-05 3.103639634926e-07 2.7205854954249e-05 4.12815119240131e-06 0.000140586514261688 3133 3170 0 447 0 3264 3301 0 471 0 0 0 0 0 0 0 0 0 3349 0 77 219 0 0 3243 +309 450 0.993143318649031 -0.108517263804869 -0.04347817934429 0.0834941573708014 0.106919865302324 0.993559215638265 -0.0375263563913099 0.0538482538251914 0.0472704032828439 0.0326203690441901 0.998349347922308 -0.0261622604829862 5.05374149651379e-05 -3.41659928094109e-05 5.68702006874071e-08 -2.7113291921946e-06 -1.1125783742678e-06 1.97385060965281e-05 -3.41659928094109e-05 5.61787014083307e-05 -1.68676509204504e-07 4.46249095172468e-06 2.65108264251211e-06 1.24007688306597e-05 5.68702006874071e-08 -1.68676509204504e-07 1.61472525577409e-05 -5.30948514740046e-08 8.27921772703879e-07 -4.01836488902303e-06 -2.7113291921946e-06 4.46249095172468e-06 -5.30948514740046e-08 7.1833724193747e-05 6.79740328465529e-06 5.7106984193051e-05 -1.1125783742678e-06 2.65108264251211e-06 8.27921772703879e-07 6.79740328465529e-06 1.9813519727959e-05 1.15050619694024e-05 1.97385060965281e-05 1.24007688306597e-05 -4.01836488902303e-06 5.7106984193051e-05 1.15050619694024e-05 0.000249104955114976 2935 3034 0 0 332 2953 3052 0 0 454 0 0 0 0 0 274 274 0 3726 0 0 0 0 0 2942 +309 448 0.999216555194265 0.0294440881937833 -0.0264446874843251 -0.0626537903372817 -0.0292457638823296 0.999541383940388 0.00785538576222198 -0.0972620440694434 0.0266638541971324 -0.00707583641494095 0.999619413286068 -0.00914454284936971 4.11071264134419e-05 -2.01412967434342e-05 8.09811514680815e-07 -7.10105444965877e-06 -1.71814403395707e-06 -1.48850812353615e-06 -2.01412967434342e-05 4.63962589619014e-05 4.29500236615615e-06 7.12104284400144e-06 -1.08297632226123e-06 -2.21707321378355e-05 8.09811514680815e-07 4.29500236615615e-06 1.38985158064595e-05 -2.62997042691461e-06 -7.58508075144631e-07 -3.40378599416342e-06 -7.10105444965877e-06 7.12104284400144e-06 -2.62997042691461e-06 6.53547703143041e-05 1.43666447708212e-05 2.36903989703379e-05 -1.71814403395707e-06 -1.08297632226123e-06 -7.58508075144631e-07 1.43666447708212e-05 2.58616226507894e-05 3.16234909580673e-07 -1.48850812353615e-06 -2.21707321378355e-05 -3.40378599416342e-06 2.36903989703379e-05 3.16234909580673e-07 0.000179254744300999 2730 2758 0 102 0 2837 2865 0 121 0 0 0 0 0 0 0 0 0 3577 0 188 322 0 0 2172 +309 446 0.984790820608959 0.173657794876031 -0.00547813135356932 -0.167988217677458 -0.173743047578505 0.984408558162811 -0.0274434697869609 -0.244456528463869 0.000626946940243056 0.0279778643682629 0.999608346325162 0.00673154626399723 4.13864021158154e-05 -1.61322953606231e-05 -1.73708285792216e-06 -1.45675801059971e-05 -4.53363301825337e-06 -3.04003365159202e-05 -1.61322953606231e-05 2.93880389224074e-05 3.76317794182e-06 4.3754325075485e-06 1.44902611519727e-06 1.91161212624483e-05 -1.73708285792216e-06 3.76317794182e-06 1.2856853771092e-05 2.68118228188998e-08 1.56411052220467e-06 4.4539250917075e-07 -1.45675801059971e-05 4.3754325075485e-06 2.68118228188998e-08 6.14358077707406e-05 2.06289115068616e-05 4.75170568799544e-05 -4.53363301825337e-06 1.44902611519727e-06 1.56411052220467e-06 2.06289115068616e-05 3.13335725840982e-05 1.87765117308997e-05 -3.04003365159202e-05 1.91161212624483e-05 4.4539250917075e-07 4.75170568799544e-05 1.87765117308997e-05 0.000232383755865271 2193 2236 0 477 0 2287 2330 0 493 0 0 0 0 0 0 0 0 0 3192 0 465 465 0 0 770 +309 444 0.949067310980964 0.315062785934279 0.00258459797512118 -0.277133142924 -0.314738433910148 0.948404615338373 -0.0383197576279033 -0.401698989266231 -0.0145243742429727 0.0355545570103795 0.999262185829448 0.00332045030292125 3.7045132366973e-05 -2.0217016842816e-05 3.62201460893618e-06 4.52367738246533e-06 2.81054975361332e-06 -8.82984923781889e-06 -2.0217016842816e-05 3.0445052510138e-05 2.92174382668124e-06 -3.78824392728019e-06 -4.99369629369342e-06 1.00107004828386e-06 3.62201460893618e-06 2.92174382668124e-06 1.77540921725441e-05 5.98489985843021e-07 -2.2093883450137e-06 3.02790786668886e-06 4.52367738246533e-06 -3.78824392728019e-06 5.98489985843021e-07 7.03172392281548e-05 3.92704829767598e-05 -3.80711856578165e-05 2.81054975361332e-06 -4.99369629369342e-06 -2.2093883450137e-06 3.92704829767598e-05 6.60878070765702e-05 -4.40731783138027e-05 -8.82984923781889e-06 1.00107004828386e-06 3.02790786668886e-06 -3.80711856578165e-05 -4.40731783138027e-05 0.000173817179573504 1478 1490 0 599 0 1549 1561 0 615 0 0 0 0 0 0 0 0 0 2724 0 456 456 0 0 285 +309 441 0.795057550806591 0.606365197944014 0.0143086556930245 -0.444352397344168 -0.606373067504453 0.794081988833944 0.0417791576598675 -0.643084458884224 0.0139711814341027 -0.041893218208261 0.999024406287199 0.132117282870938 4.81830269704769e-05 -2.229832194061e-05 -5.11378855312511e-07 -4.19463065034038e-06 -1.95044502680659e-06 -2.83944650326211e-06 -2.229832194061e-05 4.8778172080696e-05 2.62394219490472e-06 1.00940681993119e-05 1.78606130783515e-05 1.35499654132788e-05 -5.11378855312511e-07 2.62394219490472e-06 1.22638886151659e-05 -2.87707777436757e-06 2.91457113839559e-07 -2.02155894858953e-06 -4.19463065034038e-06 1.00940681993119e-05 -2.87707777436757e-06 2.7236836671761e-05 1.9859101415521e-05 1.97924485760365e-05 -1.95044502680659e-06 1.78606130783515e-05 2.91457113839559e-07 1.9859101415521e-05 7.41767542024575e-05 2.08188267761531e-05 -2.83944650326211e-06 1.35499654132788e-05 -2.02155894858953e-06 1.97924485760365e-05 2.08188267761531e-05 0.000155269360251431 291 245 0 875 0 336 290 0 889 0 0 0 0 0 0 0 0 0 1833 0 478 478 0 0 353 +309 442 0.862918984134369 0.505262189500146 -0.00899703740277347 -0.391801010317755 -0.504950072902773 0.862813890208077 0.0240336168623944 -0.563915993217347 0.0199060467193356 -0.0161960095555326 0.999670665058491 0.046770692137357 7.11047990972921e-05 -1.91167471530176e-05 1.93172648212918e-06 -6.93425999325405e-06 5.41141347171028e-06 -4.62293179955719e-05 -1.91167471530176e-05 3.79981750343015e-05 1.69206098439997e-06 9.51664230100384e-07 -1.16085433583324e-06 -7.50004597121319e-06 1.93172648212918e-06 1.69206098439997e-06 1.85827689278208e-05 2.36535017724914e-06 -2.70019549697665e-06 4.99807080941776e-06 -6.93425999325405e-06 9.51664230100384e-07 2.36535017724914e-06 2.57220589941417e-05 -4.81633156827542e-06 2.95272995489291e-05 5.41141347171028e-06 -1.16085433583324e-06 -2.70019549697665e-06 -4.81633156827542e-06 3.56926310810979e-05 2.15670206392695e-06 -4.62293179955719e-05 -7.50004597121319e-06 4.99807080941776e-06 2.95272995489291e-05 2.15670206392695e-06 0.000226317586911304 749 759 0 795 0 799 809 0 811 0 0 0 0 0 0 0 0 0 2317 0 472 472 0 0 304 +309 443 0.914983886944484 0.403450466754996 0.00567516582479913 -0.344644639156561 -0.403298300641091 0.914891790125737 -0.0179859128356783 -0.487721091349337 -0.01244858754928 0.0141680357036358 0.999822133897989 0.0522745868221055 4.78659813676029e-05 -2.91941864398315e-05 1.26438590598335e-06 -5.107304920134e-06 -3.525765702895e-06 -2.52504495190246e-05 -2.91941864398315e-05 6.12980031121535e-05 3.7462031336197e-06 1.57646874435153e-05 1.13368495778869e-05 7.48577426063121e-05 1.26438590598335e-06 3.7462031336197e-06 1.20559192584898e-05 -1.66502619956931e-06 3.06403035087449e-06 3.10047545022208e-06 -5.107304920134e-06 1.57646874435153e-05 -1.66502619956931e-06 3.65081036847533e-05 1.68375895067327e-05 6.90434803866216e-05 -3.525765702895e-06 1.13368495778869e-05 3.06403035087449e-06 1.68375895067327e-05 3.93279498665916e-05 6.16506523143839e-05 -2.52504495190246e-05 7.48577426063121e-05 3.10047545022208e-06 6.90434803866216e-05 6.16506523143839e-05 0.000402032844115589 1181 1210 0 635 0 1243 1272 0 651 0 0 0 0 0 0 0 0 0 2606 0 482 482 0 0 273 +309 439 0.618070331090388 0.785819028386634 0.0218522413336674 -0.508283232580288 -0.785568823272058 0.616352715479565 0.0546896153206382 -0.784043967953065 0.0295074520887819 -0.050968468158779 0.998264256359395 0.262608414156077 5.33698084206101e-05 -2.28351018870402e-05 -5.67204751129086e-06 -5.34516545718882e-06 -6.62273173628487e-06 5.51691935314177e-06 -2.28351018870402e-05 6.73766027326445e-05 6.86622304331302e-06 3.07995769702115e-06 1.75572130065163e-05 -1.2136836691314e-06 -5.67204751129086e-06 6.86622304331302e-06 1.62549327977445e-05 1.37869577403022e-06 5.16489606360699e-06 6.93278037835324e-07 -5.34516545718882e-06 3.07995769702115e-06 1.37869577403022e-06 2.76259394904042e-05 1.86265787657039e-05 2.25896145818842e-05 -6.62273173628487e-06 1.75572130065163e-05 5.16489606360699e-06 1.86265787657039e-05 0.000119681379974837 4.52446591536495e-06 5.51691935314177e-06 -1.2136836691314e-06 6.93278037835324e-07 2.25896145818842e-05 4.52446591536495e-06 0.000213329358553305 0 0 0 1104 0 0 0 0 1134 0 0 0 0 0 0 0 0 0 1190 0 0 0 0 132 324 +309 438 0.538109498807135 0.842495089527582 0.0253020041784333 -0.566880792680869 -0.842806814086878 0.538205179632463 0.00344365293176354 -0.843191216074292 -0.010716409018867 -0.0231777638848153 0.99967392175601 0.309494311335154 6.08910310112776e-05 -2.88454812161395e-05 -1.07586796551792e-05 -5.8179437178714e-07 1.75569334597759e-05 -5.42116214651083e-06 -2.88454812161395e-05 4.54736738509137e-05 9.63430358283741e-06 -2.13859011717515e-07 1.91532233345601e-06 -1.54765536341064e-05 -1.07586796551792e-05 9.63430358283741e-06 1.48357119230097e-05 -2.33561910638763e-06 -3.85688486502151e-06 -3.61158497028216e-06 -5.8179437178714e-07 -2.13859011717515e-07 -2.33561910638763e-06 1.77640914033445e-05 1.22685826021218e-06 1.14823579609947e-05 1.75569334597759e-05 1.91532233345601e-06 -3.85688486502151e-06 1.22685826021218e-06 0.000139136846708508 -6.91318289466778e-06 -5.42116214651083e-06 -1.54765536341064e-05 -3.61158497028216e-06 1.14823579609947e-05 -6.91318289466778e-06 0.000190394855795967 0 0 0 1002 0 0 0 0 1035 0 0 0 0 0 0 0 0 0 775 0 0 0 0 207 303 +310 449 0.991036855412901 -0.125319954713283 -0.046269430123676 -0.0222424308205814 0.124171720010359 0.991895520446807 -0.0269195183319868 -0.0189951286419535 0.0492679932915688 0.0209328800746061 0.998566211810115 0.0011656694407486 2.7058829116226e-05 -1.22258519079332e-05 1.67608900723396e-06 -3.86306727044057e-06 6.90590694002295e-07 -4.70518862462504e-07 -1.22258519079332e-05 2.89062986231578e-05 1.05829328757646e-06 -1.62237176957706e-06 -1.17085020787133e-06 -4.75049450939795e-06 1.67608900723396e-06 1.05829328757646e-06 1.34245229509794e-05 1.00673096197874e-06 1.72367020709401e-06 -3.35874570819337e-06 -3.86306727044057e-06 -1.62237176957706e-06 1.00673096197874e-06 6.42237798028025e-05 8.35362717294214e-06 3.03839431221732e-05 6.90590694002295e-07 -1.17085020787133e-06 1.72367020709401e-06 8.35362717294214e-06 1.7660904155048e-05 1.06728582064763e-05 -4.70518862462504e-07 -4.75049450939795e-06 -3.35874570819337e-06 3.03839431221732e-05 1.06728582064763e-05 0.000112679817739572 2918 3035 0 0 26 2948 3065 0 0 153 0 0 0 0 0 340 354 0 3492 0 0 0 0 0 3121 +310 450 0.979131925472975 -0.197796101835734 -0.0466623468995391 0.0387397157483895 0.195287930249974 0.979295327923756 -0.0533224624842486 0.0568878508255016 0.0562431935283428 0.0430971322165455 0.997486511375689 -0.00786366159052938 4.78226878893353e-05 -3.84148941190505e-05 -2.12583732639763e-06 -6.07402133374614e-06 -1.07301576128272e-06 3.29468449032586e-05 -3.84148941190505e-05 6.19552176951061e-05 5.34679858583465e-06 -2.35889673311553e-07 -1.9669717143589e-06 -2.2800651275356e-05 -2.12583732639763e-06 5.34679858583465e-06 1.38137272265214e-05 3.09702757712577e-08 1.32764833173419e-06 -1.84506496587687e-06 -6.07402133374614e-06 -2.35889673311553e-07 3.09702757712577e-08 5.78906567192413e-05 5.31048831057578e-06 1.8318582158029e-05 -1.07301576128272e-06 -1.9669717143589e-06 1.32764833173419e-06 5.31048831057578e-06 1.84780660430739e-05 3.39062637713667e-06 3.29468449032586e-05 -2.2800651275356e-05 -1.84506496587687e-06 1.8318582158029e-05 3.39062637713667e-06 0.000143037150710583 2659 2758 0 0 466 2693 2792 0 0 599 0 0 0 0 0 512 512 0 3517 0 0 0 0 0 2736 +310 448 0.997392982265471 -0.0572617873234978 -0.0439127161549875 -0.0864648785766271 0.0569374532021796 0.998340685706774 -0.0086024232270304 -0.100442927639809 0.0443324412867101 0.00607971833606241 0.99899833417004 -0.00101648320867889 3.65824932862488e-05 -1.82995009777846e-05 4.76405017213447e-07 -6.20977611134639e-06 -3.22954104408678e-06 7.29075731113376e-06 -1.82995009777846e-05 4.63505687505005e-05 5.3611850406344e-06 -3.14452032820437e-06 -4.74134439344617e-06 -1.8487838335565e-05 4.76405017213447e-07 5.3611850406344e-06 1.81703297707851e-05 -9.34548397402603e-07 -2.89150601063328e-06 8.65176720534542e-07 -6.20977611134639e-06 -3.14452032820437e-06 -9.34548397402603e-07 4.94922020824467e-05 9.43331976396597e-06 -1.03814530585055e-05 -3.22954104408678e-06 -4.74134439344617e-06 -2.89150601063328e-06 9.43331976396597e-06 2.82956990664868e-05 -9.33048282545776e-06 7.29075731113376e-06 -1.8487838335565e-05 8.65176720534542e-07 -1.03814530585055e-05 -9.33048282545776e-06 0.000120441633284474 2827 2827 0 0 0 2979 2979 0 0 0 0 0 0 0 0 165 193 0 3469 0 40 174 0 0 2220 +310 447 0.9994953111967 0.010902488371747 -0.0298372023339282 -0.138302810516372 -0.0114296164324274 0.999780592584678 -0.0175536480321951 -0.176730901762021 0.029639277386931 0.0178858166806697 0.999400625774092 -0.00353088226299816 4.19150161912958e-05 -2.27390097974106e-05 -1.42899491371039e-07 -6.16891290347254e-06 -2.65135798510546e-06 -1.13578178560205e-05 -2.27390097974106e-05 3.21031827383007e-05 2.81575271384004e-06 -1.78211403326407e-07 -1.35638994855084e-06 -9.19735493728092e-06 -1.42899491371039e-07 2.81575271384004e-06 1.41575338655412e-05 3.00831442632452e-06 1.20996590623931e-06 -1.40906124146904e-06 -6.16891290347254e-06 -1.78211403326407e-07 3.00831442632452e-06 5.15980096017947e-05 4.64442585903477e-06 2.60462684812457e-05 -2.65135798510546e-06 -1.35638994855084e-06 1.20996590623931e-06 4.64442585903477e-06 2.11375603412947e-05 9.48507249968894e-06 -1.13578178560205e-05 -9.19735493728092e-06 -1.40906124146904e-06 2.60462684812457e-05 9.48507249968894e-06 0.000158788511860113 2594 2628 0 56 0 2700 2734 0 87 0 0 0 0 0 0 0 20 0 3423 0 396 422 0 0 1329 +310 313 0.979312244730177 0.202354851351504 -0.000203607592610252 0.0837382182230903 -0.202344464261848 0.979271229132706 0.0091966067385998 -0.0384314006304497 0.0020603650470038 -0.00896515071983248 0.999957689589137 0.00683715550669147 3.05384412143415e-05 -1.70407106425173e-05 1.04341432637624e-06 3.21419187545781e-06 3.18704921226706e-06 7.008760072968e-06 -1.70407106425173e-05 2.78536862911047e-05 1.13013582004558e-06 -5.69724989561581e-07 4.50269759071749e-07 -2.33650442708624e-05 1.04341432637624e-06 1.13013582004558e-06 1.26754546784199e-05 -3.04385659773653e-06 1.22236422559717e-07 -9.42687492109292e-07 3.21419187545781e-06 -5.69724989561581e-07 -3.04385659773653e-06 4.22675613973384e-05 2.19886910903844e-05 -7.99058013370766e-06 3.18704921226706e-06 4.50269759071749e-07 1.22236422559717e-07 2.19886910903844e-05 4.14977490697523e-05 -1.26565279082037e-05 7.008760072968e-06 -2.33650442708624e-05 -9.42687492109292e-07 -7.99058013370766e-06 -1.26565279082037e-05 0.000139229604107643 3241 3258 0 451 0 3392 3409 0 498 0 0 0 0 0 0 0 0 0 3292 0 92 146 0 0 2756 +310 446 0.995989746845855 0.0847558123399324 -0.0286509415644141 -0.195232556935608 -0.0858390901443439 0.995546628590458 -0.038968717009465 -0.268667004683009 0.0252205230144125 0.0412718133448328 0.99882959639876 0.00798965448012878 5.25278997311226e-05 -2.47006553457537e-05 -1.10362223385979e-06 2.50166051473222e-06 4.84783384837548e-06 4.74346083788414e-06 -2.47006553457537e-05 5.08932757112888e-05 5.32133933591524e-06 1.24461714917432e-06 -6.63456932872453e-06 -8.75602106930785e-06 -1.10362223385979e-06 5.32133933591524e-06 1.77626588123586e-05 6.14698405711117e-07 -3.4009343579376e-06 7.47542708559429e-06 2.50166051473222e-06 1.24461714917432e-06 6.14698405711117e-07 3.13821594451435e-05 4.12769106748438e-07 5.99925274789921e-06 4.84783384837548e-06 -6.63456932872453e-06 -3.4009343579376e-06 4.12769106748438e-07 2.67222408994589e-05 -1.03728974887561e-05 4.74346083788414e-06 -8.75602106930785e-06 7.47542708559429e-06 5.99925274789921e-06 -1.03728974887561e-05 0.000210328232186419 2024 2048 0 192 0 2124 2148 0 226 0 0 0 0 0 0 0 0 0 3046 0 383 383 0 0 984 +310 443 0.946936058755432 0.321405913058304 -0.00321553726259405 -0.339186084606924 -0.321274082311012 0.946149455248446 -0.0398016628834373 -0.515172623541418 -0.00975011097095551 0.0387226985659312 0.999202425913701 0.0182103144627842 4.1287989492062e-05 -2.35658311342984e-05 -5.67835676850855e-08 4.1898415128536e-06 -1.93477042531287e-07 1.44355306234094e-06 -2.35658311342984e-05 4.01902128359141e-05 6.09335225576856e-06 -3.75861443097185e-06 -5.36993102148548e-06 1.6788756974216e-07 -5.67835676850855e-08 6.09335225576856e-06 1.63433012548543e-05 -5.82190692416853e-07 1.514139610698e-06 -1.06999725025077e-05 4.1898415128536e-06 -3.75861443097185e-06 -5.82190692416853e-07 2.73362564813469e-05 4.47389959064256e-06 -8.7338761473307e-06 -1.93477042531287e-07 -5.36993102148548e-06 1.514139610698e-06 4.47389959064256e-06 3.19782121436143e-05 3.29335366408113e-06 1.44355306234094e-06 1.6788756974216e-07 -1.06999725025077e-05 -8.7338761473307e-06 3.29335366408113e-06 0.000187212508309573 1238 1276 0 467 0 1304 1342 0 496 0 0 0 0 0 0 0 0 0 2736 0 399 399 0 0 475 +310 451 0.962705245167951 -0.264937327806242 -0.0548345079398273 0.115662329144448 0.260025717452812 0.962030417427902 -0.0829704899747297 0.135065221508025 0.0747344444634851 0.0656177436246018 0.995042247611804 -0.0262164455461037 4.86091765061342e-05 -2.93089556630942e-05 -3.56807352997194e-06 -3.7423124547851e-06 3.17837636076322e-06 9.73275250578462e-06 -2.93089556630942e-05 4.43177087357001e-05 3.29527921676365e-06 -3.94028757222038e-06 -4.0230519173263e-06 -1.48853314810422e-05 -3.56807352997194e-06 3.29527921676365e-06 1.33748666142935e-05 2.5703663118622e-06 3.03715399075198e-06 -1.2122746084574e-06 -3.7423124547851e-06 -3.94028757222038e-06 2.5703663118622e-06 0.000107045394698934 1.10281633259112e-05 2.87902435858257e-05 3.17837636076322e-06 -4.0230519173263e-06 3.03715399075198e-06 1.10281633259112e-05 1.8285302104446e-05 6.31259318934189e-06 9.73275250578462e-06 -1.48853314810422e-05 -1.2122746084574e-06 2.87902435858257e-05 6.31259318934189e-06 0.000138551687120657 2605 2694 0 0 940 2638 2727 0 0 1061 0 0 0 0 0 686 675 0 3557 0 0 0 0 0 2525 +310 452 0.944374620847924 -0.325810872378811 -0.0447643936415773 0.185664539081381 0.321496760175241 0.94326903198219 -0.0829660563134466 0.196138128077367 0.0692561094428738 0.0639594304472824 0.995546474335426 0.00665674764744307 2.60664000262512e-05 -1.50149501928105e-05 1.91698114882635e-06 -4.57029372556925e-06 -1.66565494192375e-06 9.94796237470142e-06 -1.50149501928105e-05 2.26056881223978e-05 1.27724645144978e-06 2.84693847708129e-06 1.05524400331289e-06 -8.88087009771179e-06 1.91698114882635e-06 1.27724645144978e-06 1.36905656215116e-05 4.55991135449821e-06 -3.11020876255753e-07 -3.73846143503224e-06 -4.57029372556925e-06 2.84693847708129e-06 4.55991135449821e-06 0.000137294050422112 6.1694875109023e-06 2.64615369146361e-05 -1.66565494192375e-06 1.05524400331289e-06 -3.11020876255753e-07 6.1694875109023e-06 1.86103240355955e-05 5.13503218055486e-06 9.94796237470142e-06 -8.88087009771179e-06 -3.73846143503224e-06 2.64615369146361e-05 5.13503218055486e-06 7.84543068195625e-05 2515 2594 0 0 1352 2551 2630 0 0 1479 0 0 0 0 0 835 818 0 3593 0 0 0 0 0 2317 +310 444 0.973058157716547 0.230361559050321 -0.0095589650686791 -0.286869183350786 -0.230552559934024 0.971862384006962 -0.0482599591812263 -0.431327648629722 -0.00182724085640642 0.0491635908392638 0.99878906808527 0.018159368383515 7.0206215575881e-05 -3.81925346782344e-05 -3.64830045525566e-07 1.76729799391592e-05 1.27649053860162e-05 -5.45177504193353e-05 -3.81925346782344e-05 5.383089657803e-05 3.85327314915823e-07 -1.25620680023346e-05 -4.74230552009017e-06 -1.60195312690626e-05 -3.64830045525566e-07 3.85327314915823e-07 1.35950557861811e-05 -1.8918250628742e-07 1.14140092562232e-06 8.09127706129845e-06 1.76729799391592e-05 -1.25620680023346e-05 -1.8918250628742e-07 3.21853136421345e-05 8.38784289966457e-06 -3.27882000378895e-05 1.27649053860162e-05 -4.74230552009017e-06 1.14140092562232e-06 8.38784289966457e-06 3.03670070523322e-05 -5.07678327906982e-05 -5.45177504193353e-05 -1.60195312690626e-05 8.09127706129845e-06 -3.27882000378895e-05 -5.07678327906982e-05 0.000321252530096242 1478 1498 0 377 0 1555 1575 0 407 0 0 0 0 0 0 0 0 0 2614 0 383 383 0 0 393 +310 445 0.986902416982466 0.158489078464047 -0.0300804149204247 -0.230449430716481 -0.15958288159728 0.986440506771402 -0.0383201057108138 -0.343368627607327 0.0235992214972461 0.0426185242376689 0.998812664185095 -0.000774794032885844 4.09529164630787e-05 -1.54852466705092e-05 8.94659494247568e-07 -2.81437631972325e-07 -2.44750868404218e-06 -1.48553767723446e-05 -1.54852466705092e-05 3.26334557246153e-05 2.37038496137901e-06 1.71941507752934e-06 3.04077619485542e-06 -9.54562921674378e-07 8.94659494247568e-07 2.37038496137901e-06 1.58398281967972e-05 3.02546793097832e-06 1.06179761991672e-06 -3.71450232720645e-06 -2.81437631972325e-07 1.71941507752934e-06 3.02546793097832e-06 6.31749815705643e-05 2.29912678633508e-05 3.16712284851659e-05 -2.44750868404218e-06 3.04077619485542e-06 1.06179761991672e-06 2.29912678633508e-05 3.84796679969426e-05 2.15008310402515e-05 -1.48553767723446e-05 -9.54562921674378e-07 -3.71450232720645e-06 3.16712284851659e-05 2.15008310402515e-05 0.000171271117166547 1798 1828 0 340 0 1890 1920 0 365 0 0 0 0 0 0 0 0 0 2970 0 344 344 0 0 562 +310 442 0.904052215406673 0.427186696749952 -0.0141816056266973 -0.376693289140954 -0.427030204539313 0.904146521717074 0.0128168513305335 -0.597937433310572 0.0182974377823675 -0.0055311288884423 0.999817288500164 0.068270445952109 4.7644028733141e-05 -2.11909184881144e-05 -4.09421827482779e-06 -8.63550885851473e-06 -1.17145355668433e-05 -1.20599136600491e-05 -2.11909184881144e-05 4.76124219489018e-05 1.06400827153063e-05 -8.64348586287523e-06 -1.31723734171975e-05 -1.76978352702488e-05 -4.09421827482779e-06 1.06400827153063e-05 1.82110901864049e-05 -6.70620039473055e-07 -1.32138298152215e-06 -7.29993008165784e-06 -8.63550885851473e-06 -8.64348586287523e-06 -6.70620039473055e-07 3.80941591444875e-05 2.22169021042225e-05 1.08023156795679e-05 -1.17145355668433e-05 -1.31723734171975e-05 -1.32138298152215e-06 2.22169021042225e-05 6.21249891180766e-05 4.56965340327554e-07 -1.20599136600491e-05 -1.76978352702488e-05 -7.29993008165784e-06 1.08023156795679e-05 4.56965340327554e-07 0.00017847315448021 787 795 0 563 0 843 851 0 585 0 0 0 0 0 0 0 0 0 2545 0 404 404 0 0 502 +310 440 0.765669112266766 0.643227826562456 -0.00296203584737172 -0.45494678827652 -0.642404189532087 0.764906398068073 0.0472764155382911 -0.7586419986136 0.0326751861853201 -0.0342952668784622 0.998877453383292 0.149886891801861 4.72164069116961e-05 -1.90159912733866e-05 6.0129237327127e-07 1.30298373277298e-06 5.42038771415029e-06 -3.01365917914807e-05 -1.90159912733866e-05 5.07835218716798e-05 3.23857582177783e-06 -5.94964431762236e-06 -3.48105656488156e-06 -2.58411068080978e-05 6.0129237327127e-07 3.23857582177783e-06 1.68376573590598e-05 8.87059631738733e-07 1.47475313678671e-06 7.35240987933498e-08 1.30298373277298e-06 -5.94964431762236e-06 8.87059631738733e-07 2.49963045535249e-05 2.22667588395682e-06 2.48060084306152e-05 5.42038771415029e-06 -3.48105656488156e-06 1.47475313678671e-06 2.22667588395682e-06 5.45331861964135e-05 -1.53865421868935e-05 -3.01365917914807e-05 -2.58411068080978e-05 7.35240987933498e-08 2.48060084306152e-05 -1.53865421868935e-05 0.00024901300050217 0 0 0 675 0 1 0 0 730 0 0 0 0 0 0 0 0 0 1675 0 356 246 0 5 536 +310 438 0.610743890470878 0.791597144844561 0.0191274809223694 -0.534515160750451 -0.791583222549179 0.610977612967697 -0.0101172244687744 -0.900904767888541 -0.0196952286392677 -0.00896195995495066 0.999765863211289 0.323627990724709 6.66338986511501e-05 -7.48462225211107e-05 -7.97905034345773e-06 6.22593812319132e-06 2.22257582632652e-05 9.22578662022879e-05 -7.48462225211107e-05 0.000188112790675739 1.3810925710399e-05 -2.67790247776234e-05 -7.63471327171735e-05 -0.000274072827690294 -7.97905034345773e-06 1.3810925710399e-05 1.49929317733932e-05 -2.80814409050391e-06 -3.56040445080098e-06 -2.16606432012642e-05 6.22593812319132e-06 -2.67790247776234e-05 -2.80814409050391e-06 2.34045836506991e-05 1.69774350218122e-05 4.57110473851024e-05 2.22257582632652e-05 -7.63471327171735e-05 -3.56040445080098e-06 1.69774350218122e-05 0.000161540082380876 0.000118890254662077 9.22578662022879e-05 -0.000274072827690294 -2.16606432012642e-05 4.57110473851024e-05 0.000118890254662077 0.000560037559919201 0 0 0 736 0 0 0 0 780 0 0 0 0 0 0 0 0 0 900 0 0 0 0 177 502 +311 449 0.978565221993731 -0.199365389600089 -0.0516095701780705 -0.0539695252852571 0.197575265199053 0.979559333574778 -0.0377826228319497 -0.0131143366311779 0.0580871834907164 0.0267759861843108 0.997952366437383 -0.0246700765079159 6.56496817444788e-05 -6.52115678522207e-05 -2.70909434300266e-06 -1.89095249024244e-06 -5.64996318963246e-06 5.96194560249514e-05 -6.52115678522207e-05 8.48350999592105e-05 5.30435013878986e-06 -2.30432129777751e-06 6.99515889522896e-06 -7.25329088850156e-05 -2.70909434300266e-06 5.30435013878986e-06 1.45184978427337e-05 -3.26607260210013e-07 2.18334463737004e-06 -8.62667808823112e-06 -1.89095249024244e-06 -2.30432129777751e-06 -3.26607260210013e-07 4.96345049657804e-05 3.61261359111961e-06 1.61820695683544e-05 -5.64996318963246e-06 6.99515889522896e-06 2.18334463737004e-06 3.61261359111961e-06 1.86180236541858e-05 -5.55342542762906e-06 5.96194560249514e-05 -7.25329088850156e-05 -8.62667808823112e-06 1.61820695683544e-05 -5.55342542762906e-06 0.000224308070957613 2685 2802 0 0 146 2717 2834 0 0 281 0 0 0 0 0 523 537 0 3221 0 0 0 0 0 2810 +310 441 0.844147849164006 0.536064267753559 -0.00703630511151807 -0.421781515275651 -0.535683593710276 0.843926724477621 0.0288231008414734 -0.677766925081246 0.02138916037216 -0.0205617253729871 0.999559762729703 0.127279645223924 3.17942405888186e-05 -1.76947095395661e-05 -2.55872737551108e-06 4.03088438323109e-06 2.16484414726822e-06 7.59795062972978e-06 -1.76947095395661e-05 3.36282373639482e-05 6.40362794866016e-06 -6.23710265613708e-07 -2.85082907379646e-07 -1.45968542542131e-05 -2.55872737551108e-06 6.40362794866016e-06 1.68569895295349e-05 -1.79359603113684e-07 2.51606352642771e-06 -9.56630049609264e-06 4.03088438323109e-06 -6.23710265613708e-07 -1.79359603113684e-07 2.58291804182592e-05 7.91021458879489e-06 1.29006921592878e-05 2.16484414726822e-06 -2.85082907379646e-07 2.51606352642771e-06 7.91021458879489e-06 4.08627096964643e-05 2.10173862081474e-05 7.59795062972978e-06 -1.45968542542131e-05 -9.56630049609264e-06 1.29006921592878e-05 2.10173862081474e-05 0.000120355440013148 317 276 0 755 0 367 326 0 787 0 0 0 0 0 0 0 0 0 2013 0 415 415 0 0 585 +311 313 0.991733820636019 0.12825725941525 -0.00375558437173044 0.048214888160497 -0.128271617432981 0.991731524010544 -0.00386994119482717 -0.026947510805528 0.0032281833607797 0.00431968644855056 0.999985459464874 -0.00564328404466053 2.28615702754489e-05 -9.72367463025593e-06 2.032899255584e-06 5.04715963778236e-06 3.06421162131869e-06 1.02785549872864e-05 -9.72367463025593e-06 2.19188957810932e-05 -1.22901982189259e-06 1.73715180927144e-06 2.7881146485215e-06 -5.47589768112926e-06 2.032899255584e-06 -1.22901982189259e-06 1.73171493116121e-05 1.76023396848687e-06 -1.37118845429062e-06 -7.72768885966336e-06 5.04715963778236e-06 1.73715180927144e-06 1.76023396848687e-06 3.66835207857422e-05 8.21391494233674e-06 4.93626246557114e-06 3.06421162131869e-06 2.7881146485215e-06 -1.37118845429062e-06 8.21391494233674e-06 3.27571289829661e-05 9.5648238768121e-06 1.02785549872864e-05 -5.47589768112926e-06 -7.72768885966336e-06 4.93626246557114e-06 9.5648238768121e-06 9.07550853951908e-05 3365 3394 0 333 0 3472 3501 0 378 0 0 0 0 0 0 0 0 0 3515 0 14 68 0 0 3025 +310 439 0.68537130997603 0.728176290541431 0.00504552822424881 -0.482548974606793 -0.727774717506498 0.684725427391588 0.0386658717959908 -0.835559120325098 0.0247007696251901 -0.0301724870822572 0.999239457288989 0.252900016779197 4.19098870850952e-05 -2.4980961783677e-05 -4.00036298817393e-06 -1.99349361057216e-06 2.43280526658158e-07 2.82801025067169e-06 -2.4980961783677e-05 4.61475123896244e-05 6.92917533569855e-06 -3.46967384218085e-06 -1.18972849538637e-05 -4.42558368910338e-05 -4.00036298817393e-06 6.92917533569855e-06 1.77577138953824e-05 -3.28882546967325e-06 -1.4856690730457e-05 -1.11355169299733e-05 -1.99349361057216e-06 -3.46967384218085e-06 -3.28882546967325e-06 1.86456193240368e-05 9.58244531244302e-06 1.39736902352251e-05 2.43280526658158e-07 -1.18972849538637e-05 -1.4856690730457e-05 9.58244531244302e-06 0.000169364923840386 3.71579983036791e-05 2.82801025067169e-06 -4.42558368910338e-05 -1.11355169299733e-05 1.39736902352251e-05 3.71579983036791e-05 0.000146540606491643 0 0 0 874 0 0 0 0 922 0 0 0 0 0 0 0 0 0 1340 0 0 0 0 90 542 +311 314 0.981934756642019 0.189201512107287 0.00263087717228579 0.0647390099163466 -0.189214368109693 0.981917017315353 0.00607404374123796 -0.042965190480884 -0.00143408480548589 -0.00646211442461375 0.999978091998987 0.00197849875062607 2.38946839737718e-05 -1.37698177600286e-05 -1.42286326725024e-07 -6.23172905095197e-07 -1.51126116652335e-06 3.9737562426875e-06 -1.37698177600286e-05 2.45296204998324e-05 1.46133386969144e-06 1.63879115708947e-06 1.72497921961005e-06 3.84604228672503e-06 -1.42286326725024e-07 1.46133386969144e-06 1.55823362773163e-05 1.34298468749028e-06 1.69142456356933e-06 -1.52025552120115e-06 -6.23172905095197e-07 1.63879115708947e-06 1.34298468749028e-06 4.42006590148155e-05 1.84905857031405e-05 2.14500360120299e-07 -1.51126116652335e-06 1.72497921961005e-06 1.69142456356933e-06 1.84905857031405e-05 4.09372534189908e-05 -2.60711407215836e-06 3.9737562426875e-06 3.84604228672503e-06 -1.52025552120115e-06 2.14500360120299e-07 -2.60711407215836e-06 0.000144024313696132 3119 3147 0 429 0 3147 3175 0 479 0 0 0 0 0 0 0 0 0 3377 0 16 22 0 0 2520 +311 450 0.962106129587742 -0.269034106010098 -0.0444122191862019 -0.00271725844404662 0.265840836687529 0.961703934327119 -0.0667397351584188 0.0633794019822096 0.0606666709072646 0.0524041267753674 0.996781501903973 0.0114211583299053 2.4489654804536e-05 -4.46439405865731e-06 2.76894485057585e-06 -5.01565207735794e-06 -3.64742902131587e-06 4.31949982899529e-06 -4.46439405865731e-06 2.26229693227971e-05 4.72239998445035e-06 -1.24365641008396e-07 -1.41538937114648e-06 8.77119682356262e-07 2.76894485057585e-06 4.72239998445035e-06 1.62005269890508e-05 9.75127728713506e-06 3.49008639733882e-07 -1.00888624481951e-06 -5.01565207735794e-06 -1.24365641008396e-07 9.75127728713506e-06 8.14061717810866e-05 3.8600184719385e-06 2.10496147950822e-05 -3.64742902131587e-06 -1.41538937114648e-06 3.49008639733882e-07 3.8600184719385e-06 1.90449027978291e-05 2.08671261513522e-06 4.31949982899529e-06 8.77119682356262e-07 -1.00888624481951e-06 2.10496147950822e-05 2.08671261513522e-06 0.000121575795555361 2733 2832 0 0 575 2763 2862 0 0 711 0 0 0 0 0 652 652 0 3199 0 0 0 0 0 2655 +311 448 0.990465266004846 -0.132672302524965 -0.0371027893921055 -0.106749735267591 0.132240993075093 0.991120721711099 -0.0138576601698543 -0.097153831304598 0.0386118710821415 0.00881902135127141 0.999215366311959 0.0113193712198281 9.30456610766106e-05 -7.88439404374692e-05 -6.28039141314969e-06 -2.93022079538597e-05 -1.15327711450174e-05 -5.7481723745972e-06 -7.88439404374692e-05 0.000113560877985563 7.09088962810112e-06 2.38771535710667e-05 1.0339254016081e-05 9.52206972397104e-06 -6.28039141314969e-06 7.09088962810112e-06 1.38423426146434e-05 2.5132498549506e-06 3.80535814407788e-06 -5.07456170964994e-06 -2.93022079538597e-05 2.38771535710667e-05 2.5132498549506e-06 5.54318272355825e-05 4.53896020586643e-06 4.77655233439305e-05 -1.15327711450174e-05 1.0339254016081e-05 3.80535814407788e-06 4.53896020586643e-06 1.90672681709592e-05 7.24927356391765e-07 -5.7481723745972e-06 9.52206972397104e-06 -5.07456170964994e-06 4.77655233439305e-05 7.24927356391765e-07 0.000377097831869435 2732 2732 0 0 0 2847 2886 0 0 0 0 0 0 0 0 340 368 0 3194 0 0 22 0 0 2039 +311 443 0.968179605840189 0.250135987371357 -0.00776135663994555 -0.323257844478229 -0.250238829843189 0.967278861314812 -0.0418584817239359 -0.525275425849864 -0.00296291644293792 0.0424687211401246 0.9990934034668 0.0346065206961639 3.31078825368773e-05 -2.05823174643916e-05 3.38660578964896e-06 4.1575173308712e-06 1.66927264697519e-06 -1.25780941419473e-05 -2.05823174643916e-05 3.07468883347004e-05 -2.1120720425952e-06 -2.67608509606818e-06 9.81287347554186e-07 5.22078379065433e-06 3.38660578964896e-06 -2.1120720425952e-06 1.49065613355601e-05 1.62799398558841e-06 1.90493901145297e-06 2.01058939386208e-06 4.1575173308712e-06 -2.67608509606818e-06 1.62799398558841e-06 2.6242631970722e-05 4.64124207678804e-08 4.69280913746313e-06 1.66927264697519e-06 9.81287347554186e-07 1.90493901145297e-06 4.64124207678804e-08 2.65313871651398e-05 -6.64492782576953e-06 -1.25780941419473e-05 5.22078379065433e-06 2.01058939386208e-06 4.69280913746313e-06 -6.64492782576953e-06 0.000233948139601298 1330 1374 0 331 0 1403 1447 0 362 0 0 0 0 0 0 0 0 0 2596 0 308 308 0 0 565 +311 452 0.917642149415767 -0.395185490539456 -0.0419680078476637 0.154593403407538 0.390153698160676 0.915939786182595 -0.0939914884408673 0.227207314876617 0.0755842406005363 0.0698765780134624 0.994688034721424 0.0157842105150272 3.71808887267821e-05 -2.80015059630577e-05 -1.00699283616777e-06 1.18848985293454e-05 2.01564797386881e-06 2.30484221963588e-05 -2.80015059630577e-05 4.19561255501893e-05 3.64091172690132e-06 -2.78025986895383e-05 -4.37976261817669e-06 -1.02907692608199e-05 -1.00699283616777e-06 3.64091172690132e-06 1.57003284688841e-05 7.87922038999648e-06 9.82484132747419e-07 -2.47826173935361e-06 1.18848985293454e-05 -2.78025986895383e-05 7.87922038999648e-06 0.000223608604108316 2.32445737873698e-05 -7.3704229505777e-05 2.01564797386881e-06 -4.37976261817669e-06 9.82484132747419e-07 2.32445737873698e-05 2.09634026281421e-05 -1.69956535460276e-05 2.30484221963588e-05 -1.02907692608199e-05 -2.47826173935361e-06 -7.3704229505777e-05 -1.69956535460276e-05 0.000178368898871668 2320 2399 0 0 1534 2353 2432 0 0 1670 0 0 0 0 0 997 980 0 3401 0 0 0 0 0 2134 +311 440 0.810662101202076 0.585453820597127 -0.00841318149461881 -0.425478513557521 -0.584693446353363 0.810202649213333 0.0412945637962599 -0.777236318236899 0.0309924420796649 -0.0285568057724142 0.999111594056447 0.155555667211135 0.000125482726665458 -5.01169135118313e-05 -7.21805463897707e-06 -4.87834294171632e-06 7.08555775720025e-06 -7.00176616273264e-05 -5.01169135118313e-05 8.67457078443975e-05 1.36202724974679e-05 -7.5923928018107e-06 -5.22303171096149e-06 -6.33064501630055e-05 -7.21805463897707e-06 1.36202724974679e-05 2.39629040071583e-05 3.23652498312069e-06 -7.03580217215614e-06 -8.79203475226017e-06 -4.87834294171632e-06 -7.5923928018107e-06 3.23652498312069e-06 2.62654933199754e-05 -6.24872749084708e-06 3.63186461205904e-05 7.08555775720025e-06 -5.22303171096149e-06 -7.03580217215614e-06 -6.24872749084708e-06 6.67349340457673e-05 -2.27938968753373e-05 -7.00176616273264e-05 -6.33064501630055e-05 -8.79203475226017e-06 3.63186461205904e-05 -2.27938968753373e-05 0.000400977149675876 1 0 0 634 0 12 0 0 672 0 0 0 0 0 0 0 0 0 1806 0 342 246 0 0 476 +311 457 0.83254896990834 -0.55386753018768 -0.00964218379627264 0.590499030273384 0.55201460451411 0.830966625791064 -0.0690966223815879 0.620705072000602 0.0462827085172468 0.0522036955129847 0.997563373960319 -0.0298817624873727 3.453319498238e-05 -2.62447067813334e-05 -5.1040134706756e-06 -3.0243188326407e-06 4.45289134713845e-06 -5.5472151991762e-06 -2.62447067813334e-05 6.2322180178835e-05 9.46569802781104e-06 -7.60601771674499e-07 -8.50814541299771e-06 7.72931522897536e-05 -5.1040134706756e-06 9.46569802781104e-06 1.90055877708121e-05 5.1837103065034e-06 -2.34604155755936e-06 1.19827772913665e-06 -3.0243188326407e-06 -7.60601771674499e-07 5.1837103065034e-06 0.000185974853748385 -1.21116677118309e-05 6.93790413596606e-05 4.45289134713845e-06 -8.50814541299771e-06 -2.34604155755936e-06 -1.21116677118309e-05 2.16687647623635e-05 -3.45955220052545e-06 -5.5472151991762e-06 7.72931522897536e-05 1.19827772913665e-06 6.93790413596606e-05 -3.45955220052545e-06 0.000464174432758871 1878 1925 0 0 3351 1913 1960 0 0 3440 0 0 0 0 0 1450 1402 0 3820 0 0 0 0 0 310 +311 447 0.997590003279103 -0.0636855651463003 -0.0275378675571589 -0.159371359947003 0.0630386688694491 0.997728345310499 -0.0237544772862429 -0.178331102030157 0.0289881283419132 0.0219612785595699 0.999338476522976 -0.0210973096475979 0.000104500121884691 -8.19963969986874e-05 -1.44768607162352e-05 1.1876387544264e-05 1.36632653748507e-05 -2.13975614142094e-05 -8.19963969986874e-05 0.000130094580353029 1.99764003633673e-05 -1.34819041955946e-05 -1.0791710139315e-05 -7.65202595494678e-05 -1.44768607162352e-05 1.99764003633673e-05 2.24027704100231e-05 3.12561483944114e-07 -2.41049457589028e-06 -2.12404062169775e-05 1.1876387544264e-05 -1.34819041955946e-05 3.12561483944114e-07 6.28749297257542e-05 1.74125811709714e-05 -5.99795766751439e-06 1.36632653748507e-05 -1.0791710139315e-05 -2.41049457589028e-06 1.74125811709714e-05 3.5768127486732e-05 -2.57277927532511e-05 -2.13975614142094e-05 -7.65202595494678e-05 -2.12404062169775e-05 -5.99795766751439e-06 -2.57277927532511e-05 0.000583727508538949 2441 2441 0 0 0 2591 2591 0 0 0 0 0 0 0 0 159 193 0 3161 0 270 296 0 0 1271 +311 444 0.987837284579114 0.15547465250744 -0.00226530860010613 -0.285035338180231 -0.155374559240684 0.986427708571869 -0.0530954056620291 -0.446580087671336 -0.0060204265734347 0.052801592678091 0.998586874675674 0.0389233741515601 4.89834883075574e-05 -3.15054775350964e-05 -6.3223209936203e-06 3.58137698160011e-06 8.50877199621253e-06 -2.74712240576316e-05 -3.15054775350964e-05 4.15921351023885e-05 6.20915819619316e-06 2.89160575836268e-06 3.75246315922015e-07 2.59911668712147e-05 -6.3223209936203e-06 6.20915819619316e-06 1.44693634134743e-05 8.85703658115573e-08 1.82706342198448e-06 -2.31807072442378e-06 3.58137698160011e-06 2.89160575836268e-06 8.85703658115573e-08 3.0189046808193e-05 3.53344196644408e-06 1.50004275075715e-05 8.50877199621253e-06 3.75246315922015e-07 1.82706342198448e-06 3.53344196644408e-06 2.59658496698211e-05 -1.90468847438604e-06 -2.74712240576316e-05 2.59911668712147e-05 -2.31807072442378e-06 1.50004275075715e-05 -1.90468847438604e-06 0.000356400561149226 1615 1625 0 188 0 1701 1711 0 216 0 0 0 0 0 0 0 0 0 2445 0 283 283 0 0 464 +311 446 0.999881671393206 0.00906496997158136 -0.0124285772051245 -0.194530870801701 -0.00969277357010269 0.998630089189174 -0.0514197929453419 -0.26852236248707 0.0119454322838535 0.0515341758975288 0.998599787383371 0.0144290047959866 3.22609704000006e-05 -1.63417424326449e-05 2.41769300257961e-06 9.44080057766326e-06 2.51027569653834e-06 5.23322911575259e-06 -1.63417424326449e-05 5.65494276769497e-05 4.02361048089766e-06 8.44465808292005e-06 9.17217840908075e-06 -4.26004926228708e-05 2.41769300257961e-06 4.02361048089766e-06 1.50655446334458e-05 -4.60588267088859e-07 5.5429315873529e-07 -8.29216273738959e-06 9.44080057766326e-06 8.44465808292005e-06 -4.60588267088859e-07 4.22886132087005e-05 9.84142749085963e-06 -7.18938376243259e-06 2.51027569653834e-06 9.17217840908075e-06 5.5429315873529e-07 9.84142749085963e-06 2.67535633421792e-05 -7.86215865732595e-06 5.23322911575259e-06 -4.26004926228708e-05 -8.29216273738959e-06 -7.18938376243259e-06 -7.86215865732595e-06 0.000169744951292745 2168 2193 0 47 0 2274 2301 0 75 0 0 0 0 0 0 0 18 0 2873 0 228 228 0 0 970 +311 441 0.881838937956777 0.471439731563269 -0.0102306894594394 -0.393885463636091 -0.471245362569738 0.881841114200769 0.0168540072879554 -0.692446715567561 0.0169674912635532 -0.0100413549234745 0.99980561882374 0.103144740495049 5.641338577888e-05 -2.04574583957999e-05 -6.57781898399006e-06 -3.48092980499544e-06 7.51136493431802e-06 -4.29251352745174e-05 -2.04574583957999e-05 3.42191592154102e-05 4.64422505882069e-06 -1.05498628857663e-06 -9.14763687353863e-07 -1.13257900425531e-05 -6.57781898399006e-06 4.64422505882069e-06 1.68108299985198e-05 7.02941595444432e-07 -5.08654537724638e-07 4.47147649909109e-06 -3.48092980499544e-06 -1.05498628857663e-06 7.02941595444432e-07 2.05321776120122e-05 -1.66065394660278e-06 1.62685236151987e-05 7.51136493431802e-06 -9.14763687353863e-07 -5.08654537724638e-07 -1.66065394660278e-06 4.17080495796413e-05 -2.29910402840136e-05 -4.29251352745174e-05 -1.13257900425531e-05 4.47147649909109e-06 1.62685236151987e-05 -2.29910402840136e-05 0.000246972467761931 408 362 0 639 0 472 426 0 673 0 0 0 0 0 0 0 0 0 2155 0 344 344 0 0 540 +311 439 0.737893566869698 0.674916670703215 0.000756028572311454 -0.446974333504457 -0.674583100759092 0.737492709352267 0.0322822524384788 -0.859008197008403 0.0212302647784372 -0.0243308704969895 0.99947850632132 0.236240218890369 5.51197358415425e-05 -2.64700112350259e-05 -4.69299882573833e-06 2.76355494837671e-06 2.00442582522919e-05 -5.3826037558344e-06 -2.64700112350259e-05 5.36523229528692e-05 3.46460974790076e-06 -7.35863124309675e-06 -2.91795933097499e-06 -4.30293133990679e-05 -4.69299882573833e-06 3.46460974790076e-06 1.43405477667106e-05 -7.89210048502482e-08 1.57308431084927e-06 9.97795534231874e-08 2.76355494837671e-06 -7.35863124309675e-06 -7.89210048502482e-08 2.577302535461e-05 2.47358207104739e-05 1.32218165232898e-05 2.00442582522919e-05 -2.91795933097499e-06 1.57308431084927e-06 2.47358207104739e-05 0.000159379973465914 -6.46124462184655e-06 -5.3826037558344e-06 -4.30293133990679e-05 9.97795534231874e-08 1.32218165232898e-05 -6.46124462184655e-06 0.000132431030499092 0 0 0 718 0 0 0 0 779 0 0 0 0 0 0 0 0 0 1475 0 0 0 0 67 480 +311 442 0.933468211642946 0.358054040738834 -0.020842307039165 -0.362787657744811 -0.358066951890855 0.933690301612166 0.00323707259337335 -0.61621690879385 0.0206193068679136 0.00444123698719251 0.999777535053829 0.0547989159203691 3.6236616218907e-05 -1.38677006883142e-05 -2.4209678063241e-06 3.51860160141296e-06 7.55227445801567e-06 -4.9940337796001e-07 -1.38677006883142e-05 4.12385155910338e-05 2.29448945269883e-06 4.96303394693755e-07 5.24488441923395e-06 -2.08950940186416e-05 -2.4209678063241e-06 2.29448945269883e-06 1.43350847691874e-05 -1.67592671091489e-06 1.81222378581539e-06 -1.70990506443678e-06 3.51860160141296e-06 4.96303394693755e-07 -1.67592671091489e-06 2.59190113120444e-05 7.58132940979123e-06 7.33120875704404e-06 7.55227445801567e-06 5.24488441923395e-06 1.81222378581539e-06 7.58132940979123e-06 4.02319400259676e-05 -4.21936407978968e-06 -4.9940337796001e-07 -2.08950940186416e-05 -1.70990506443678e-06 7.33120875704404e-06 -4.21936407978968e-06 0.000124427805161502 866 875 0 444 0 932 941 0 478 0 0 0 0 0 0 0 0 0 2494 0 332 332 0 0 573 +311 438 0.669121208354099 0.742839963978479 0.0215776840092373 -0.489020237736491 -0.742779984239286 0.66942331657127 -0.012260434095375 -0.927092776483692 -0.0235521452151594 -0.00782375531145848 0.999691995220823 0.309748347681551 3.80394517253963e-05 -3.29541229361322e-05 -3.75645919035254e-06 5.51375005884423e-07 2.73269331027383e-06 2.62371060615728e-05 -3.29541229361322e-05 6.02297811113849e-05 6.70304481066312e-06 -5.96012169316038e-06 -7.63120500796256e-06 -7.60830343852098e-05 -3.75645919035254e-06 6.70304481066312e-06 1.49128131984619e-05 -1.48930786861111e-06 -1.95747653753367e-06 -1.2046871614396e-05 5.51375005884423e-07 -5.96012169316038e-06 -1.48930786861111e-06 2.0285495424604e-05 7.67845811345552e-06 9.3619159220855e-06 2.73269331027383e-06 -7.63120500796256e-06 -1.95747653753367e-06 7.67845811345552e-06 0.000133606426626671 7.40053527973057e-06 2.62371060615728e-05 -7.60830343852098e-05 -1.2046871614396e-05 9.3619159220855e-06 7.40053527973057e-06 0.000204021553364745 0 0 0 642 0 0 0 0 696 0 0 0 0 0 0 0 0 0 1031 0 0 0 0 156 536 +312 449 0.962883798729412 -0.267263575647253 -0.0377487917245429 -0.0689669456434728 0.266166494934627 0.963406243480598 -0.0316829133259104 -0.00269725298016414 0.0448351103336782 0.0204595003567284 0.998784872595956 0.0177076273134866 7.56312542981815e-05 -6.4563669594058e-05 -8.8615079679111e-06 -3.08139324480181e-05 -7.80547252809384e-06 -5.33863472176599e-06 -6.4563669594058e-05 8.50816599775608e-05 1.15188707026902e-05 1.84840597844389e-05 2.24892692303543e-06 -5.65533431213967e-06 -8.8615079679111e-06 1.15188707026902e-05 1.65775226213363e-05 7.07432192467826e-06 3.20943226918276e-06 -3.36912134345846e-06 -3.08139324480181e-05 1.84840597844389e-05 7.07432192467826e-06 9.48914324155901e-05 1.41517126132917e-05 6.5940470950144e-05 -7.80547252809384e-06 2.24892692303543e-06 3.20943226918276e-06 1.41517126132917e-05 2.06733801530688e-05 8.56389429944579e-06 -5.33863472176599e-06 -5.65533431213967e-06 -3.36912134345846e-06 6.5940470950144e-05 8.56389429944579e-06 0.000300914796166025 2499 2616 0 0 309 2527 2644 0 0 442 0 0 0 0 0 634 648 0 3123 0 0 0 0 0 2715 +312 314 0.992823473235832 0.11958897839363 -0.000165041531211952 0.0304415233688554 -0.119584286033235 0.992794999412422 0.0075952403260649 -0.0384585419237342 0.0010721594381308 -0.00752099650690879 0.999971142126453 -0.00533409063811507 2.02682267517161e-05 -5.66739475807092e-06 8.82892335909153e-07 2.4732019473581e-06 -8.9628184399949e-07 1.29830850125512e-05 -5.66739475807092e-06 1.95508096394129e-05 3.01246027677709e-06 9.92124871205587e-07 8.87868432584859e-07 1.21745560839056e-08 8.82892335909153e-07 3.01246027677709e-06 1.87760998574482e-05 1.01768966061844e-06 -2.054900108769e-06 -9.5234133703912e-06 2.4732019473581e-06 9.92124871205587e-07 1.01768966061844e-06 2.66012729644036e-05 3.35840800639816e-07 7.75630389632752e-06 -8.9628184399949e-07 8.87868432584859e-07 -2.054900108769e-06 3.35840800639816e-07 2.75562511725569e-05 1.29938944093733e-05 1.29830850125512e-05 1.21745560839056e-08 -9.5234133703912e-06 7.75630389632752e-06 1.29938944093733e-05 8.68973044613924e-05 3080 3115 0 279 0 3101 3136 0 333 0 0 0 0 0 0 0 0 0 3570 0 7 13 0 0 2728 +312 315 0.980431057029824 0.196808527994676 0.00462014284951841 0.0445849319259033 -0.196862013546293 0.980221550423536 0.02027460746297 -0.0634378444221311 -0.00053854793667615 -0.0207873854500122 0.999783773909275 -0.00706751787372808 2.20092851316113e-05 -1.66969645745818e-05 -1.82369559419922e-06 2.29661118500274e-06 1.50999709838461e-06 8.01564600316325e-06 -1.66969645745818e-05 2.0798304640217e-05 3.22040515603968e-06 -7.57523036472783e-07 -1.56138769840604e-06 -8.46186027377067e-06 -1.82369559419922e-06 3.22040515603968e-06 1.62889715020058e-05 -1.36178910313938e-06 -3.34118919004982e-06 -9.12584220884136e-07 2.29661118500274e-06 -7.57523036472783e-07 -1.36178910313938e-06 3.89188148629245e-05 1.94747539343124e-05 -1.06971132084138e-05 1.50999709838461e-06 -1.56138769840604e-06 -3.34118919004982e-06 1.94747539343124e-05 5.65063715571074e-05 -1.84365268232678e-05 8.01564600316325e-06 -8.46186027377067e-06 -9.12584220884136e-07 -1.06971132084138e-05 -1.84365268232678e-05 9.22972141545605e-05 2857 2896 0 323 0 2858 2897 0 370 0 0 0 0 0 0 0 0 0 3328 0 0 0 0 0 2410 +312 452 0.88875114593298 -0.457760616517224 -0.0240128833875816 0.130265134878434 0.453733857350876 0.885963212136178 -0.095889381241306 0.25762479052828 0.0651689135731887 0.0743263392554509 0.995102310316167 0.0548333868743729 4.28406999717871e-05 -1.63376991410588e-05 -2.30672174404645e-06 2.79531032368359e-05 4.89629315968543e-06 -6.85260978941227e-06 -1.63376991410588e-05 3.75034721214377e-05 8.3213062152886e-06 -1.08860755358658e-05 -1.46336941962614e-06 -1.64531196675964e-05 -2.30672174404645e-06 8.3213062152886e-06 1.78130980990073e-05 3.75682501370119e-06 -2.81772823480086e-06 7.83313326883407e-07 2.79531032368359e-05 -1.08860755358658e-05 3.75682501370119e-06 0.000284030184113506 4.11574136084025e-05 -7.94074444428717e-05 4.89629315968543e-06 -1.46336941962614e-06 -2.81772823480086e-06 4.11574136084025e-05 2.78184059284457e-05 -2.9974014217382e-05 -6.85260978941227e-06 -1.64531196675964e-05 7.83313326883407e-07 -7.94074444428717e-05 -2.9974014217382e-05 0.00020895971167224 2130 2209 0 0 1721 2171 2250 0 0 1854 0 0 0 0 0 1119 1104 0 3291 0 0 0 0 0 1947 +312 454 0.839272627736787 -0.543580769732212 -0.0118913039286853 0.254632627842007 0.539170031866244 0.834885043358045 -0.110736810114749 0.397383415086231 0.0701222722759491 0.0865269388940344 0.993778625135641 0.0654695347615478 7.72099896131225e-05 -2.31399637502658e-05 -1.19041188428004e-05 -8.92758909442289e-05 3.99658036729156e-06 -0.000206622411427802 -2.31399637502658e-05 3.9395631784879e-05 5.7189723036816e-06 1.22936378231335e-05 -2.19194947111566e-06 7.95393209402399e-05 -1.19041188428004e-05 5.7189723036816e-06 1.76491282552378e-05 2.34825274338402e-05 -8.3448390258996e-07 3.13292337634075e-05 -8.92758909442289e-05 1.22936378231335e-05 2.34825274338402e-05 0.000313831793655371 4.10582496857987e-06 0.000375011564924183 3.99658036729156e-06 -2.19194947111566e-06 -8.3448390258996e-07 4.10582496857987e-06 1.79608082398505e-05 1.92190237401057e-05 -0.000206622411427802 7.95393209402399e-05 3.13292337634075e-05 0.000375011564924183 1.92190237401057e-05 0.0012966787443574 1971 2035 0 0 2418 2011 2075 0 0 2542 0 0 0 0 0 1407 1374 0 3437 0 0 0 0 0 1237 +312 442 0.955545596637379 0.294251756494735 -0.0186685978766381 -0.345106032763964 -0.294337922348173 0.955699345664606 -0.00198699874289348 -0.629714807296601 0.0172568889049295 0.00739354421145905 0.999823752112999 0.0760384667700267 3.47747290108043e-05 -2.32246993036459e-05 1.6875609937932e-07 4.660048639442e-06 7.98782274390178e-06 -2.63728621607223e-06 -2.32246993036459e-05 4.23966965241542e-05 -1.92625251325745e-06 3.93284914776114e-06 1.06829648551846e-05 1.86269189280925e-06 1.6875609937932e-07 -1.92625251325745e-06 1.51849376068441e-05 -1.65642243249485e-06 -4.22427883999419e-06 6.56551087167651e-06 4.660048639442e-06 3.93284914776114e-06 -1.65642243249485e-06 3.11011082491394e-05 1.70868467268078e-05 2.32390466098567e-06 7.98782274390178e-06 1.06829648551846e-05 -4.22427883999419e-06 1.70868467268078e-05 7.30489011373523e-05 -4.41455458061971e-05 -2.63728621607223e-06 1.86269189280925e-06 6.56551087167651e-06 2.32390466098567e-06 -4.41455458061971e-05 0.000285830815690343 926 935 0 325 0 994 1003 0 343 0 0 0 0 0 0 0 0 0 2408 0 274 274 0 0 474 +312 447 0.990799032440325 -0.133073114090207 -0.0246743514940359 -0.165637063980973 0.132400340191083 0.990824366554676 -0.0271518794710574 -0.174229312971313 0.0280611338438411 0.0236351633770552 0.999326749276501 -0.0163633898981735 5.84389414523968e-05 -4.00491642821206e-05 -3.55448477761239e-06 -6.94847003699359e-06 -6.29901776976432e-06 -6.36552176810831e-06 -4.00491642821206e-05 5.19695525251664e-05 5.66761063273884e-06 -2.55731747251783e-06 4.04180932761924e-07 -1.19228725438652e-05 -3.55448477761239e-06 5.66761063273884e-06 1.91985154511621e-05 4.36163254822568e-06 2.59371680530782e-07 -7.7402201409041e-06 -6.94847003699359e-06 -2.55731747251783e-06 4.36163254822568e-06 4.2363390179532e-05 2.42182665105577e-06 5.99911236191167e-06 -6.29901776976432e-06 4.04180932761924e-07 2.59371680530782e-07 2.42182665105577e-06 2.46764790288908e-05 2.18412692758505e-06 -6.36552176810831e-06 -1.19228725438652e-05 -7.7402201409041e-06 5.99911236191167e-06 2.18412692758505e-06 0.000308991960664101 2525 2525 0 0 0 2667 2667 0 0 0 0 0 0 0 0 239 273 0 3003 0 121 147 0 0 1135 +312 451 0.915453526107014 -0.400950597224915 -0.0344014552485742 0.0500012726071327 0.396797215229665 0.913594829384594 -0.0888620149879451 0.170015114332391 0.0670582696184288 0.0676986433152065 0.995449688416779 0.0383909463667689 0.000114149565536696 -0.000102517853232446 -5.11865688916841e-06 -1.38776049915777e-05 2.84403426874145e-06 -8.02581952359472e-06 -0.000102517853232446 0.000124561522408642 7.72529590354624e-06 1.21456091525185e-05 -2.1845017833819e-06 3.59506173503942e-05 -5.11865688916841e-06 7.72529590354624e-06 1.81410394791534e-05 1.15468386336861e-05 -2.7676501423548e-06 3.63974705032451e-06 -1.38776049915777e-05 1.21456091525185e-05 1.15468386336861e-05 0.000115749954052107 5.52662103971536e-06 7.72086002069906e-05 2.84403426874145e-06 -2.1845017833819e-06 -2.7676501423548e-06 5.52662103971536e-06 2.16595118094782e-05 6.42542513104425e-06 -8.02581952359472e-06 3.59506173503942e-05 3.63974705032451e-06 7.72086002069906e-05 6.42542513104425e-06 0.00060608541728046 2236 2325 0 0 1231 2257 2346 0 0 1366 0 0 0 0 0 910 899 0 3209 0 0 0 0 0 2247 +312 441 0.912461723294343 0.409024066676947 -0.0106262129552576 -0.371409336005934 -0.408708131249488 0.912364980907602 0.0234052358249564 -0.709293860926772 0.0192682893187003 -0.0170133621757477 0.999669584679962 0.129645214156411 5.68404916941277e-05 -3.14461258576245e-05 -2.74780168056961e-06 2.09063958106204e-06 1.11649869116596e-05 -2.30884022320412e-05 -3.14461258576245e-05 4.44398449618168e-05 1.81963416648078e-06 -4.61905418050265e-07 7.1616984562685e-06 -2.25263785103417e-05 -2.74780168056961e-06 1.81963416648078e-06 1.34167516063099e-05 -1.47148369672224e-06 3.26065324295318e-06 -5.29103776709549e-06 2.09063958106204e-06 -4.61905418050265e-07 -1.47148369672224e-06 3.07510501602247e-05 2.34734286778068e-05 7.36905531368297e-06 1.11649869116596e-05 7.1616984562685e-06 3.26065324295318e-06 2.34734286778068e-05 8.14831575722708e-05 -3.4923031810502e-05 -2.30884022320412e-05 -2.25263785103417e-05 -5.29103776709549e-06 7.36905531368297e-06 -3.4923031810502e-05 0.000281718730872732 462 416 0 473 0 524 478 0 502 0 0 0 0 0 0 0 0 0 2236 0 290 290 0 0 497 +312 445 0.999787225542041 0.0148239641306219 -0.0143441183208329 -0.231247643734169 -0.0154879520420791 0.998758607228561 -0.0473430863844751 -0.356987166927228 0.0136244994216404 0.0475551740015705 0.998775689752804 0.0309794306063285 5.81205007798558e-05 -3.8326196708499e-05 -4.22272035038679e-06 2.77195268562416e-06 1.90651214426804e-06 1.25910735765897e-05 -3.8326196708499e-05 6.0862888205603e-05 7.38211288707932e-06 8.53034687488788e-06 4.84337092870139e-06 -1.20697798081571e-06 -4.22272035038679e-06 7.38211288707932e-06 1.64700676040276e-05 2.57121503911371e-06 4.5467661401944e-08 3.20989620948049e-06 2.77195268562416e-06 8.53034687488788e-06 2.57121503911371e-06 4.97806908223125e-05 1.87757216832214e-05 -8.64810314848807e-07 1.90651214426804e-06 4.84337092870139e-06 4.5467661401944e-08 1.87757216832214e-05 3.90701121174317e-05 -2.41112882435197e-05 1.25910735765897e-05 -1.20697798081571e-06 3.20989620948049e-06 -8.64810314848807e-07 -2.41112882435197e-05 0.000260278898909691 1990 2021 0 53 0 2092 2127 0 80 0 0 0 0 0 0 1 23 0 2748 0 122 122 0 0 610 +312 453 0.862331265084448 -0.505244060697311 -0.0333650773706262 0.18809430641696 0.499731834669605 0.85983442576621 -0.10465588222858 0.32602916018854 0.081565205054645 0.0735744479923843 0.993948649542324 0.0169218686218541 4.63110005932108e-05 -2.95843916762031e-05 6.07707290260491e-06 1.22652495570762e-06 -3.88284489279853e-06 3.53017755483861e-06 -2.95843916762031e-05 4.85010317027767e-05 4.49352716364119e-06 -1.43008642295448e-05 -2.74537636307342e-06 8.17460957269386e-06 6.07707290260491e-06 4.49352716364119e-06 2.087210356388e-05 1.33749972808633e-05 -5.72849353148707e-06 -3.54468840388376e-06 1.22652495570762e-06 -1.43008642295448e-05 1.33749972808633e-05 0.000187953339277875 1.83502272105059e-06 4.54872638251937e-06 -3.88284489279853e-06 -2.74537636307342e-06 -5.72849353148707e-06 1.83502272105059e-06 2.23312434364795e-05 2.03690777055286e-06 3.53017755483861e-06 8.17460957269386e-06 -3.54468840388376e-06 4.54872638251937e-06 2.03690777055286e-06 0.00028908473975491 2007 2075 0 0 2075 2036 2104 0 0 2209 0 0 0 0 0 1222 1195 0 3362 0 0 0 0 0 1570 +312 444 0.996119192135673 0.087960932833156 -0.003070725336844 -0.271422278846825 -0.0879832311792039 0.994228743514129 -0.0613853125884534 -0.445192214853588 -0.00234650596420782 0.0614172603218054 0.998109419875558 0.0123397541143044 5.37055283850483e-05 -1.73621700779896e-05 -1.77464946933196e-06 -3.14601514150728e-07 2.42435065151171e-06 -4.93274825908015e-05 -1.73621700779896e-05 4.74586546094312e-05 8.60974730154408e-07 -8.13791981163351e-06 -7.79238597779302e-06 3.6812961188296e-05 -1.77464946933196e-06 8.60974730154408e-07 1.34254272761784e-05 -7.97452240244091e-07 -1.05542724125251e-06 5.49324139352321e-06 -3.14601514150728e-07 -8.13791981163351e-06 -7.97452240244091e-07 3.73757677396938e-05 1.43279598596952e-05 -6.0415452272323e-06 2.42435065151171e-06 -7.79238597779302e-06 -1.05542724125251e-06 1.43279598596952e-05 4.00126889917211e-05 -2.10133680800634e-05 -4.93274825908015e-05 3.6812961188296e-05 5.49324139352321e-06 -6.0415452272323e-06 -2.10133680800634e-05 0.00042996406007959 1720 1731 0 112 0 1817 1828 0 140 0 0 0 0 0 0 0 0 0 2478 0 172 172 0 0 584 +312 440 0.849072701609897 0.528102327046381 -0.0135454623054289 -0.39369943186357 -0.526984204442055 0.848510014940686 0.0481497955751804 -0.790126594249381 0.0369214795132183 -0.0337444323341564 0.998748275411277 0.161800566230076 5.53618541787991e-05 -2.93066098048122e-05 -1.00713929298094e-05 -6.5940155874721e-06 -4.93776246564869e-06 -2.69641300337855e-07 -2.93066098048122e-05 5.21229092300047e-05 8.46100827784435e-06 -7.52303801399135e-06 -1.32316930152773e-05 -4.02802993960591e-05 -1.00713929298094e-05 8.46100827784435e-06 2.33928513501587e-05 1.12932940282278e-06 -6.3777326133068e-06 -7.52038511185933e-06 -6.5940155874721e-06 -7.52303801399135e-06 1.12932940282278e-06 3.09165735370743e-05 1.66338874766287e-05 1.50230899111578e-05 -4.93776246564869e-06 -1.32316930152773e-05 -6.3777326133068e-06 1.66338874766287e-05 0.000109584652484205 -5.15076128063363e-06 -2.69641300337855e-07 -4.02802993960591e-05 -7.52038511185933e-06 1.50230899111578e-05 -5.15076128063363e-06 0.000201382958358369 11 0 0 535 0 32 0 0 551 0 0 0 0 0 0 0 0 0 1882 0 310 246 0 0 524 +312 443 0.983071685037316 0.183220934449944 -0.000388917961419504 -0.308902948941054 -0.183068210348412 0.98216105063386 -0.0429616221484104 -0.53472982553416 -0.00748948848191899 0.0423055527925437 0.999076647592764 0.0566646360157368 3.37030513425801e-05 -2.28222064506486e-05 5.98362314998565e-07 4.56686831759174e-06 4.77548327568047e-06 2.46634939827858e-06 -2.28222064506486e-05 3.93268269202235e-05 1.24825451945796e-06 -2.23348763928392e-06 -1.59012117987277e-07 -2.320489489918e-05 5.98362314998565e-07 1.24825451945796e-06 1.34678229241666e-05 -4.27789985806678e-07 2.03730479265794e-06 1.7963663690708e-06 4.56686831759174e-06 -2.23348763928392e-06 -4.27789985806678e-07 2.90585650474607e-05 7.98235195127486e-06 -3.6089879613754e-06 4.77548327568047e-06 -1.59012117987277e-07 2.03730479265794e-06 7.98235195127486e-06 3.30530950526389e-05 -1.23417864316697e-05 2.46634939827858e-06 -2.320489489918e-05 1.7963663690708e-06 -3.6089879613754e-06 -1.23417864316697e-05 0.000124812750906055 1399 1422 0 186 0 1481 1504 0 212 0 0 0 0 0 0 0 0 0 2534 0 216 216 0 0 466 +312 439 0.782157869069795 0.62307272846846 0.00307292874407672 -0.413119645090205 -0.622825699224064 0.781687775553945 0.0324402517804794 -0.878497633580972 0.017810565354674 -0.0272872971984027 0.999468952580996 0.269378846102777 4.17743077489635e-05 -3.52822661481395e-05 -5.0578465929303e-06 2.5700341322596e-06 -3.96124504585774e-06 3.03950198671173e-05 -3.52822661481395e-05 8.82974215850206e-05 9.40295099463511e-06 -1.08936448266894e-05 4.61034200622171e-06 -9.20614321053727e-05 -5.0578465929303e-06 9.40295099463511e-06 1.44191955121394e-05 -2.24630481417616e-06 5.11999908788354e-06 -1.50014146410917e-05 2.5700341322596e-06 -1.08936448266894e-05 -2.24630481417616e-06 1.96501564159213e-05 1.59341953955984e-06 1.74378397392076e-05 -3.96124504585774e-06 4.61034200622171e-06 5.11999908788354e-06 1.59341953955984e-06 5.96477948503314e-05 -1.13292155185393e-05 3.03950198671173e-05 -9.20614321053727e-05 -1.50014146410917e-05 1.74378397392076e-05 -1.13292155185393e-05 0.000227252537251789 0 0 0 701 0 0 0 0 736 0 0 0 0 0 0 0 0 0 1466 0 0 0 0 42 508 +312 438 0.718552307560711 0.695310496325139 0.0150298037001945 -0.450632534374028 -0.69525729242121 0.718699867614922 -0.00937003870974188 -0.948399696502911 -0.0173170041954644 -0.00371671768940128 0.999843141385343 0.331599781155537 2.98245943280619e-05 -2.15098038587928e-05 -4.26021843397312e-06 -1.13472373297638e-06 8.50111400805572e-06 1.07966970075535e-05 -2.15098038587928e-05 4.11148529327774e-05 7.59207031234528e-06 9.59171338683839e-07 -5.10170116965505e-06 -3.37885486897944e-05 -4.26021843397312e-06 7.59207031234528e-06 1.62382692608241e-05 2.38718475153297e-06 8.53607654382484e-08 -1.14084393284864e-05 -1.13472373297638e-06 9.59171338683839e-07 2.38718475153297e-06 2.41100646400371e-05 1.21928903999287e-05 5.69205320579615e-06 8.50111400805572e-06 -5.10170116965505e-06 8.53607654382484e-08 1.21928903999287e-05 0.000137288472205684 3.92745398894862e-05 1.07966970075535e-05 -3.37885486897944e-05 -1.14084393284864e-05 5.69205320579615e-06 3.92745398894862e-05 0.000136225829294251 0 0 0 591 0 0 0 0 635 0 0 0 0 0 0 0 0 0 1096 0 0 0 0 135 524 +313 450 0.919753381588233 -0.391544779906464 -0.0273203657553791 -0.0418380307744011 0.389055282484565 0.91867494694026 -0.0683544368359954 0.0965940706280268 0.0518623584872915 0.0522400918099254 0.997286953980561 0.0423136458716394 2.25999360120023e-05 -1.2399595967943e-05 -8.21464329310319e-07 -4.83638290280326e-06 -1.8886968774886e-06 1.33504098809191e-05 -1.2399595967943e-05 2.36901886229772e-05 2.99016301934357e-06 -4.13356598164293e-06 -4.98929296787272e-07 -8.87530065988879e-06 -8.21464329310319e-07 2.99016301934357e-06 1.71368714550994e-05 7.88123487952159e-06 2.0121279137081e-06 -1.44712967654265e-06 -4.83638290280326e-06 -4.13356598164293e-06 7.88123487952159e-06 0.00013451043443006 2.60588142252616e-05 1.46501644693833e-05 -1.8886968774886e-06 -4.98929296787272e-07 2.0121279137081e-06 2.60588142252616e-05 2.40508375152308e-05 5.19365645999621e-06 1.33504098809191e-05 -8.87530065988879e-06 -1.44712967654265e-06 1.46501644693833e-05 5.19365645999621e-06 7.46717664629973e-05 2399 2498 0 0 906 2435 2534 0 0 1023 0 0 0 0 0 907 907 0 2919 0 0 0 0 0 2357 +313 449 0.945543805580016 -0.323486308553047 -0.0361042920991913 -0.0781513830797203 0.322131571923726 0.945903481139022 -0.0387021283526988 0.0168886990146842 0.0466707842146459 0.0249642253595512 0.998598330337572 0.0375274237317893 3.9766547253188e-05 -1.90618704685012e-05 2.83929939893816e-06 -2.82840573557062e-05 -8.36911492238064e-06 -3.55156111937448e-05 -1.90618704685012e-05 2.72634577398025e-05 1.66296674338568e-06 4.48842849675121e-06 1.4189726866264e-06 -8.1802883723691e-06 2.83929939893816e-06 1.66296674338568e-06 1.62588449494662e-05 2.38540029298149e-06 1.08716146513023e-06 7.565640320987e-07 -2.82840573557062e-05 4.48842849675121e-06 2.38540029298149e-06 0.000121316298053585 2.30700956813196e-05 0.000126372264951656 -8.36911492238064e-06 1.4189726866264e-06 1.08716146513023e-06 2.30700956813196e-05 2.5696167678702e-05 3.46088221168445e-05 -3.55156111937448e-05 -8.1802883723691e-06 7.565640320987e-07 0.000126372264951656 3.46088221168445e-05 0.000321942975324732 2648 2765 0 0 485 2648 2765 0 0 597 0 0 0 0 0 634 648 0 2970 0 0 0 0 0 2498 +313 452 0.859710959927592 -0.510218418911885 -0.0239631046284381 0.0754575290782533 0.506007949206627 0.857138307829675 -0.0962801983306259 0.265840688415641 0.0696636255163396 0.0706476202991816 0.995065773216013 0.0183026855580306 2.13616991516028e-05 -1.31820731343808e-05 -2.83128402491522e-07 -2.49407933852989e-06 2.07581794044808e-07 -5.84021676402591e-07 -1.31820731343808e-05 1.99007259212483e-05 4.04819155028663e-06 3.64534358716001e-06 2.02169685530311e-07 -3.94135367766096e-06 -2.83128402491522e-07 4.04819155028663e-06 1.40490928898985e-05 3.51674165960863e-06 1.70751838298805e-06 -3.80004153450223e-06 -2.49407933852989e-06 3.64534358716001e-06 3.51674165960863e-06 0.000103880416636098 1.48759313828217e-06 4.024355516525e-05 2.07581794044808e-07 2.02169685530311e-07 1.70751838298805e-06 1.48759313828217e-06 1.54722067586717e-05 8.25817686663358e-06 -5.84021676402591e-07 -3.94135367766096e-06 -3.80004153450223e-06 4.024355516525e-05 8.25817686663358e-06 0.000128204366410553 2106 2185 0 0 1785 2136 2215 0 0 1898 0 0 0 0 0 1260 1243 0 3083 0 0 0 0 0 1904 +313 447 0.981403245938358 -0.191495334371069 -0.0133118659761776 -0.163495490721765 0.191192292297412 0.981323693565337 -0.0211970708671383 -0.163098720890905 0.0171223896613792 0.0182577479826536 0.999686690123904 0.048411472519208 9.22016139012984e-05 -6.7572393914335e-05 -4.19491540712435e-06 -4.22357651996859e-06 -3.70679864880162e-06 2.03166012689305e-05 -6.7572393914335e-05 9.79147426800577e-05 6.5226563025317e-06 1.23583785968555e-05 8.22211942082527e-06 -2.83493992435342e-05 -4.19491540712435e-06 6.5226563025317e-06 2.05121729720563e-05 8.74529832259836e-06 -5.0404789495992e-08 -3.01987597780819e-06 -4.22357651996859e-06 1.23583785968555e-05 8.74529832259836e-06 8.85425944049975e-05 2.22683359697939e-05 1.89946776364759e-06 -3.70679864880162e-06 8.22211942082527e-06 -5.0404789495992e-08 2.22683359697939e-05 3.70760557688964e-05 -6.33705219954647e-06 2.03166012689305e-05 -2.83493992435342e-05 -3.01987597780819e-06 1.89946776364759e-06 -6.33705219954647e-06 0.000291044715114507 2578 2578 0 0 0 2686 2686 0 0 0 0 0 0 0 0 292 326 0 2886 0 16 42 0 0 1178 +313 315 0.990773308771714 0.135437866263933 0.00498347342956164 0.0291311418043298 -0.135522108957692 0.9904336663614 0.0259790400433513 -0.0511790960259596 -0.00141725410899859 -0.0264147102915728 0.999650066008602 -0.00113639777218396 2.20227047105835e-05 -1.15603940555697e-05 -3.66063518656352e-06 -1.41201108097538e-06 -4.18261062058023e-07 1.02839572430997e-05 -1.15603940555697e-05 2.09138603536619e-05 3.98525579042177e-06 -2.73221051728415e-06 -1.61588106177061e-06 -9.75964803189072e-06 -3.66063518656352e-06 3.98525579042177e-06 1.99094409274865e-05 9.07474295881924e-07 -1.86070865141093e-06 -1.12556396324468e-06 -1.41201108097538e-06 -2.73221051728415e-06 9.07474295881924e-07 3.04052236939482e-05 1.73130373052762e-06 -2.82948766142001e-06 -4.18261062058023e-07 -1.61588106177061e-06 -1.86070865141093e-06 1.73130373052762e-06 3.38986912372891e-05 -7.67265696799985e-06 1.02839572430997e-05 -9.75964803189072e-06 -1.12556396324468e-06 -2.82948766142001e-06 -7.67265696799985e-06 7.33169035211438e-05 2855 2894 0 233 0 2856 2895 0 269 0 0 0 0 0 0 0 0 0 3451 0 0 0 0 0 2599 +313 444 0.999570610725699 0.0281318034906135 0.00819730478989787 -0.263387961738153 -0.0276775393581968 0.998311420129362 -0.0510711489431362 -0.44941885949068 -0.00962018651214433 0.0508223383136003 0.998661375011475 0.0544549232797368 5.1590701556288e-05 -3.22672183377034e-05 -4.13343838909979e-06 -1.67844620016674e-05 -1.38604060803823e-05 -3.0041202312976e-05 -3.22672183377034e-05 6.036331613951e-05 4.07583106035783e-06 -8.2609035111906e-06 -7.20975265580171e-06 1.22212250009516e-05 -4.13343838909979e-06 4.07583106035783e-06 1.86087493437348e-05 1.2981291470914e-05 6.92793471773367e-06 -3.12677037710575e-06 -1.67844620016674e-05 -8.2609035111906e-06 1.2981291470914e-05 0.000120047303283193 6.73981883919664e-05 4.42598707585317e-05 -1.38604060803823e-05 -7.20975265580171e-06 6.92793471773367e-06 6.73981883919664e-05 7.4664735707823e-05 3.70538656861461e-05 -3.0041202312976e-05 1.22212250009516e-05 -3.12677037710575e-06 4.42598707585317e-05 3.70538656861461e-05 0.000271019219269388 1730 1747 0 67 0 1816 1833 0 74 0 0 0 0 0 0 0 1 0 2422 0 109 109 0 0 407 +313 440 0.879997758293555 0.474758981831039 -0.0144171623099868 -0.351901768620902 -0.473736717001573 0.879486747250696 0.0455695553518109 -0.791079764833398 0.0343142588859146 -0.0332711674148157 0.998857127449149 0.160796957220114 6.93387561410705e-05 -5.34014603317598e-05 -9.28353036455065e-06 -2.11687807901134e-06 -5.62839138262217e-06 1.47638425657339e-05 -5.34014603317598e-05 6.68997559790295e-05 1.10424384435469e-05 -3.93846324626961e-06 -1.12768584156129e-05 -2.82231715688492e-05 -9.28353036455065e-06 1.10424384435469e-05 1.91554226424794e-05 -1.98219827845719e-07 -7.26466050102679e-06 -6.33265195958057e-06 -2.11687807901134e-06 -3.93846324626961e-06 -1.98219827845719e-07 2.62684392039243e-05 1.1572625994983e-05 2.92786399412553e-06 -5.62839138262217e-06 -1.12768584156129e-05 -7.26466050102679e-06 1.1572625994983e-05 0.000106099683701639 -2.44951604941354e-05 1.47638425657339e-05 -2.82231715688492e-05 -6.33265195958057e-06 2.92786399412553e-06 -2.44951604941354e-05 0.000179443392730527 29 0 0 488 0 76 7 0 492 0 0 0 0 0 0 0 0 0 1886 0 261 230 0 0 473 +313 441 0.935283064990299 0.353670370396416 -0.0127615612686304 -0.332811782008042 -0.353296697783229 0.935185596133531 0.0246848965935992 -0.699798742544359 0.0206647448040542 -0.0185787482902646 0.999613824651375 0.112942584155866 3.83097562620952e-05 -2.96210875253136e-05 -4.9116582768678e-06 -1.04783064123933e-06 -8.81040200642249e-06 1.88128501103895e-05 -2.96210875253136e-05 3.76206297372251e-05 5.504829855736e-06 2.98647654064637e-07 4.39621245622794e-06 -2.07308019117624e-05 -4.9116582768678e-06 5.504829855736e-06 1.33053874735146e-05 -2.48988995092449e-06 3.0867851017813e-06 -5.24095720453787e-06 -1.04783064123933e-06 2.98647654064637e-07 -2.48988995092449e-06 2.68408135150846e-05 1.756096679588e-05 4.41827265647749e-06 -8.81040200642249e-06 4.39621245622794e-06 3.0867851017813e-06 1.756096679588e-05 7.19796736172403e-05 -1.18541624096395e-05 1.88128501103895e-05 -2.07308019117624e-05 -5.24095720453787e-06 4.41827265647749e-06 -1.18541624096395e-05 0.000169016886954745 521 480 0 417 0 575 534 0 443 0 0 0 0 0 0 0 0 0 2263 0 224 224 0 0 497 +313 453 0.830859881989662 -0.555682482665379 -0.0298133352539849 0.149808565731987 0.550307051386621 0.828419579353281 -0.104322335759394 0.35305995290988 0.082668045182456 0.070270754962315 0.994096582482174 0.00930557169613703 3.99865072889264e-05 -2.77046033126727e-05 -4.00145123998124e-06 2.013241048091e-06 2.99461184959244e-06 -2.48874022185341e-05 -2.77046033126727e-05 4.06190285444883e-05 6.30784955878496e-06 -1.24735690337799e-05 -2.65536606337807e-06 1.51044676097176e-05 -4.00145123998124e-06 6.30784955878496e-06 1.63250669785443e-05 4.59770308805924e-06 -2.52782341213896e-07 -3.75597811116378e-06 2.013241048091e-06 -1.24735690337799e-05 4.59770308805924e-06 0.000112922687021216 -2.77228577353976e-06 2.55916174372179e-05 2.99461184959244e-06 -2.65536606337807e-06 -2.52782341213896e-07 -2.77228577353976e-06 1.84583479915791e-05 -7.19228227595481e-07 -2.48874022185341e-05 1.51044676097176e-05 -3.75597811116378e-06 2.55916174372179e-05 -7.19228227595481e-07 0.000493774718384205 1971 2039 0 0 2212 1986 2054 0 0 2314 0 0 0 0 0 1262 1235 0 3214 0 0 0 0 0 1444 +313 446 0.992983302962591 -0.117820367108502 -0.0101252719431053 -0.193842691492079 0.11719159721425 0.991898034929549 -0.0490348635694351 -0.255900906505148 0.0158205429703595 0.0475042039962566 0.998745743932261 0.0202482294294308 4.6750066478456e-05 -2.79275953809833e-05 -1.15252559310542e-08 1.01039955688941e-05 4.5888939628889e-06 2.49262318936867e-05 -2.79275953809833e-05 5.88020451020543e-05 1.99621660510543e-06 -4.46389947849674e-06 5.09341205258338e-07 -3.68855185801367e-05 -1.15252559310542e-08 1.99621660510543e-06 1.61497823499338e-05 4.94292614691631e-06 1.49778986224364e-07 -4.19909112754723e-06 1.01039955688941e-05 -4.46389947849674e-06 4.94292614691631e-06 4.33164033348959e-05 3.21236034524612e-06 4.75841105713037e-06 4.5888939628889e-06 5.09341205258338e-07 1.49778986224364e-07 3.21236034524612e-06 2.23560652922744e-05 -2.92483036344384e-06 2.49262318936867e-05 -3.68855185801367e-05 -4.19909112754723e-06 4.75841105713037e-06 -2.92483036344384e-06 0.000168432460542723 2344 2344 0 0 0 2454 2454 0 0 0 0 0 0 0 0 83 113 0 2724 0 14 14 0 0 813 +313 454 0.805247655712713 -0.592799284923497 -0.0128538229088182 0.226730762522494 0.587767142168635 0.800893752158617 -0.114450794406189 0.444376131206825 0.0781408955419409 0.0846061791329836 0.993345757979779 0.0259916329374656 3.99332950163403e-05 -2.97918728690637e-05 2.90828953881155e-07 -6.25433932259695e-06 1.46549916477761e-06 -2.33317194751582e-06 -2.97918728690637e-05 4.22607074752951e-05 3.31205755999323e-06 1.12860134154853e-05 1.23346607015447e-06 6.41991348091878e-06 2.90828953881155e-07 3.31205755999323e-06 1.48081416105197e-05 4.39142440024621e-06 1.45798978582171e-06 3.32905880189202e-06 -6.25433932259695e-06 1.12860134154853e-05 4.39142440024621e-06 0.000209908738366847 9.27850551731911e-06 0.000105564112481564 1.46549916477761e-06 1.23346607015447e-06 1.45798978582171e-06 9.27850551731911e-06 1.59304400752192e-05 8.66916662195655e-06 -2.33317194751582e-06 6.41991348091878e-06 3.32905880189202e-06 0.000105564112481564 8.66916662195655e-06 0.000179168863246424 1727 1791 0 0 2599 1761 1825 0 0 2691 0 0 0 0 0 1479 1446 0 3346 0 0 0 0 0 1102 +313 445 0.998906681107469 -0.0440797322342829 -0.0155698312455644 -0.222619810230679 0.0432297269148777 0.997749418417228 -0.0512570849634288 -0.345572736499186 0.0177941886504141 0.0505279650712058 0.998564114915029 0.0111397278663509 3.30529015721286e-05 -2.27371725136687e-05 -4.46965293919817e-07 4.564132802079e-06 5.48489714837255e-06 6.8374532285221e-06 -2.27371725136687e-05 3.38811077309853e-05 1.37018847215667e-06 -2.24441029544365e-06 -2.53961653815236e-06 1.14927661438101e-05 -4.46965293919817e-07 1.37018847215667e-06 1.30605933362041e-05 1.14284489335259e-06 2.7442492764918e-07 1.85110612642723e-06 4.564132802079e-06 -2.24441029544365e-06 1.14284489335259e-06 6.10906262788578e-05 2.80150802793711e-05 -5.94741269652968e-06 5.48489714837255e-06 -2.53961653815236e-06 2.7442492764918e-07 2.80150802793711e-05 4.55356106931054e-05 -1.99624125330529e-05 6.8374532285221e-06 1.14927661438101e-05 1.85110612642723e-06 -5.94741269652968e-06 -1.99624125330529e-05 0.000236376636944839 2112 2116 0 7 0 2222 2226 0 13 0 0 0 0 0 0 34 68 0 2723 0 25 25 0 0 495 +313 443 0.99236383033008 0.123267436230625 0.00437806095671968 -0.287760697189658 -0.123021387363625 0.991705366865481 -0.0372317550127531 -0.530937803955545 -0.00893120953403191 0.0364088518815087 0.999297067443375 0.0570679651226157 2.98269931653012e-05 -1.96833980568655e-05 -2.40388204226784e-06 2.64804888235932e-06 4.51496201412981e-06 -2.01409746745612e-05 -1.96833980568655e-05 2.57120107849635e-05 5.37012233854293e-06 1.97848266049728e-06 8.56725692401635e-07 -1.8132128909269e-05 -2.40388204226784e-06 5.37012233854293e-06 1.60414906738434e-05 4.58192274422655e-06 4.1345433778581e-06 4.94098724751448e-07 2.64804888235932e-06 1.97848266049728e-06 4.58192274422655e-06 4.73244663412673e-05 1.6774589523038e-05 -3.25584026249713e-06 4.51496201412981e-06 8.56725692401635e-07 4.1345433778581e-06 1.6774589523038e-05 4.25281597017446e-05 -2.80496044504388e-05 -2.01409746745612e-05 -1.8132128909269e-05 4.94098724751448e-07 -3.25584026249713e-06 -2.80496044504388e-05 0.000313136379099665 1493 1537 0 192 0 1571 1615 0 217 0 0 0 0 0 0 0 0 0 2550 0 142 142 0 0 454 +313 438 0.75932058918249 0.650070939051182 0.0289830475393921 -0.403283644424713 -0.65018522123476 0.759747280177747 -0.00657634780278816 -0.95608222308658 -0.0262948841310011 -0.0138507928881751 0.999558269739642 0.33788854380294 4.44123770647584e-05 -3.97663958061791e-05 -1.01017190376262e-05 -5.46814692662305e-07 1.56100634890358e-05 4.05355768773297e-05 -3.97663958061791e-05 6.26736320143991e-05 1.02455559062558e-05 -4.77361537646038e-06 -2.34886802760205e-05 -5.65533411180561e-05 -1.01017190376262e-05 1.02455559062558e-05 1.79059327593514e-05 2.24200677380441e-06 -6.75753228723892e-06 -9.74872630540706e-06 -5.46814692662305e-07 -4.77361537646038e-06 2.24200677380441e-06 2.28748454124742e-05 2.11587785891682e-06 1.5879806737665e-05 1.56100634890358e-05 -2.34886802760205e-05 -6.75753228723892e-06 2.11587785891682e-06 0.000114261291014588 7.11308457137902e-05 4.05355768773297e-05 -5.65533411180561e-05 -9.74872630540706e-06 1.5879806737665e-05 7.11308457137902e-05 0.000194935967999267 0 0 0 560 0 0 0 0 595 0 0 0 0 0 0 0 0 0 1069 0 0 0 0 103 600 +314 316 0.987332988228173 0.158443132693 0.00832730801973133 0.0286376296851416 -0.158573956160688 0.987172582715039 0.0185631991657736 -0.064911092487348 -0.00527927873627258 -0.0196485530802754 0.999793010366584 0.00375834711402067 2.31324967478894e-05 -1.37855597921171e-05 -1.09385483202026e-06 -1.2092241198779e-06 1.07139804418641e-06 4.65709626829636e-06 -1.37855597921171e-05 2.52799769131859e-05 -1.41568316312934e-06 -3.33395564300657e-06 -2.9655428610114e-07 -3.75280127669343e-06 -1.09385483202026e-06 -1.41568316312934e-06 1.62676926957366e-05 1.5487388312486e-06 -1.26209387935365e-06 -1.23780773029361e-06 -1.2092241198779e-06 -3.33395564300657e-06 1.5487388312486e-06 2.94599122027526e-05 3.99371700171384e-06 -5.80035846700952e-08 1.07139804418641e-06 -2.9655428610114e-07 -1.26209387935365e-06 3.99371700171384e-06 3.66596943972094e-05 -4.24045065375507e-06 4.65709626829636e-06 -3.75280127669343e-06 -1.23780773029361e-06 -5.80035846700952e-08 -4.24045065375507e-06 0.000110264846673227 2359 2388 0 300 0 2359 2388 0 327 0 0 0 0 0 0 0 0 0 3268 0 0 0 0 0 2395 +313 439 0.818590828444074 0.57432846003936 -0.0074749967265476 -0.371989096349232 -0.57367416225197 0.818163433291615 0.0388143271096945 -0.879586792427095 0.0284079417020106 -0.0274848396992857 0.999218480831374 0.264567911852776 4.14907176471366e-05 -2.64006253098399e-05 -7.83660416001466e-06 -3.23201047521494e-07 7.76340784277112e-06 2.75318045024655e-05 -2.64006253098399e-05 5.69251579661521e-05 8.70073181653831e-06 -1.00990559581349e-06 2.31386870029826e-06 -3.59316833929836e-05 -7.83660416001466e-06 8.70073181653831e-06 1.65281818685069e-05 -1.36463046232083e-06 2.55027618224911e-06 -1.0227913165665e-05 -3.23201047521494e-07 -1.00990559581349e-06 -1.36463046232083e-06 2.08402675657127e-05 1.12570659473438e-05 2.15540500758489e-06 7.76340784277112e-06 2.31386870029826e-06 2.55027618224911e-06 1.12570659473438e-05 0.000113968101039228 -8.81701342730238e-06 2.75318045024655e-05 -3.59316833929836e-05 -1.0227913165665e-05 2.15540500758489e-06 -8.81701342730238e-06 0.000128215684539861 0 0 0 712 0 0 0 0 743 0 0 0 0 0 0 0 0 0 1524 0 0 0 0 14 531 +314 447 0.967527919692594 -0.251446472212597 -0.0257758846048231 -0.163198451212055 0.250348134085293 0.967350069752406 -0.0394924589007423 -0.142569743370701 0.0348645432399983 0.0317571119885651 0.998887355742784 -0.00129209046222952 4.05340861232039e-05 -2.48326661697796e-05 2.64541402515977e-06 -1.75431854897083e-05 -1.05258841322798e-05 4.46691776956016e-06 -2.48326661697796e-05 5.35492828915523e-05 -2.43252504960306e-06 8.40179625117914e-06 9.4089628108341e-06 -4.12779339297005e-05 2.64541402515977e-06 -2.43252504960306e-06 1.77617303531208e-05 8.53067433338687e-06 1.15960914224713e-06 2.95663460595517e-06 -1.75431854897083e-05 8.40179625117914e-06 8.53067433338687e-06 0.000127005361892443 4.14435120415034e-05 4.21491204238917e-05 -1.05258841322798e-05 9.4089628108341e-06 1.15960914224713e-06 4.14435120415034e-05 4.39175498428969e-05 1.83601528363693e-05 4.46691776956016e-06 -4.12779339297005e-05 2.95663460595517e-06 4.21491204238917e-05 1.83601528363693e-05 0.000120378668768598 2720 2720 0 0 0 2759 2775 0 0 0 0 0 0 0 0 266 300 0 2806 0 29 31 0 0 1139 +314 452 0.827423517307814 -0.561429036768632 -0.0129522074956971 0.0616560468665144 0.557156594405093 0.823578678268211 -0.106276479114174 0.308068929506429 0.0703338632301943 0.0807192503374097 0.994252256878546 0.0429052806596544 2.21275219310793e-05 -1.54763309638385e-05 4.2541518278651e-07 -9.5755941777227e-06 -3.95286256006438e-06 3.87178644039871e-06 -1.54763309638385e-05 2.654358564008e-05 3.61344199381802e-06 -8.08875016227901e-06 1.6658837544934e-06 7.96427781669959e-06 4.2541518278651e-07 3.61344199381802e-06 1.53887481061277e-05 8.44453473211309e-06 -2.7694075740059e-07 -4.39918355457937e-06 -9.5755941777227e-06 -8.08875016227901e-06 8.44453473211309e-06 0.000182071283819373 1.16737483238559e-05 6.17724402312602e-05 -3.95286256006438e-06 1.6658837544934e-06 -2.7694075740059e-07 1.16737483238559e-05 2.1249505071802e-05 1.04988848172466e-05 3.87178644039871e-06 7.96427781669959e-06 -4.39918355457937e-06 6.17724402312602e-05 1.04988848172466e-05 0.000157015663706602 2068 2147 0 0 1923 2083 2162 0 0 1956 0 0 0 0 0 1301 1284 0 3005 0 0 0 0 0 1903 +314 444 0.999404302983715 -0.0322016321937268 0.0124134629211701 -0.228330615489813 0.032942959281379 0.997338559228258 -0.0650427529421141 -0.416931826080629 -0.0102859424177237 0.0654129433718086 0.997805264682451 0.0309454473291015 6.47740307572282e-05 -4.36425988334747e-05 -5.32015208298239e-06 -9.90367170779981e-07 -5.00889113581315e-07 -2.36698399930346e-05 -4.36425988334747e-05 5.71740474758398e-05 5.56793873458168e-06 2.05817550146884e-06 5.63042885840429e-06 -9.62976593808138e-06 -5.32015208298239e-06 5.56793873458168e-06 2.00008633777082e-05 1.06959057919776e-05 8.54195522543158e-07 -2.10887925338849e-06 -9.90367170779981e-07 2.05817550146884e-06 1.06959057919776e-05 7.66753421818625e-05 2.80379740667456e-05 3.2709423399577e-05 -5.00889113581315e-07 5.63042885840429e-06 8.54195522543158e-07 2.80379740667456e-05 5.28638392172125e-05 2.37049039104804e-05 -2.36698399930346e-05 -9.62976593808138e-06 -2.10887925338849e-06 3.2709423399577e-05 2.37049039104804e-05 0.000234199247869334 1866 1868 0 8 0 1896 1904 0 16 0 0 0 0 0 0 14 28 0 2442 0 53 53 0 0 401 +314 445 0.994435973340035 -0.105062252263943 -0.00768232233666377 -0.211625922410715 0.104434972498705 0.992794753940424 -0.0587529834780117 -0.336154736531736 0.0137996900853453 0.0576237771896319 0.998242990887463 0.0529384191903767 3.72715147816159e-05 -2.37181452008726e-05 -2.89968530564374e-06 -4.33500044401545e-06 3.91629940917301e-06 -8.0584419928295e-06 -2.37181452008726e-05 4.0277292453153e-05 2.24262405095876e-06 9.8990430134432e-06 5.13445719432053e-06 1.63123899929151e-05 -2.89968530564374e-06 2.24262405095876e-06 1.45390117612375e-05 2.23727035060125e-06 -1.39484295238412e-06 2.39625471327537e-06 -4.33500044401545e-06 9.8990430134432e-06 2.23727035060125e-06 4.88148224317592e-05 1.13557787390787e-05 5.20716707103928e-05 3.91629940917301e-06 5.13445719432053e-06 -1.39484295238412e-06 1.13557787390787e-05 3.27358779249517e-05 2.82293736095401e-05 -8.0584419928295e-06 1.63123899929151e-05 2.39625471327537e-06 5.20716707103928e-05 2.82293736095401e-05 0.000244080211805055 2115 2115 0 0 0 2153 2153 0 0 0 0 0 0 0 0 99 132 0 2605 0 26 26 0 0 480 +314 442 0.984244562019338 0.176393824030406 -0.0121598100023138 -0.286048648103416 -0.176501408157038 0.984264366131303 -0.00842083622496402 -0.61290827756624 0.0104830841809493 0.0104343858504067 0.999890608285716 0.0651703285006104 3.73673313110759e-05 -3.11643921259854e-05 -8.06258739149372e-06 3.69548809172258e-07 -2.89213257967601e-06 2.23279120634359e-05 -3.11643921259854e-05 4.31294586808288e-05 8.02777417154094e-06 -6.02261495134494e-06 -4.25864878934542e-06 -1.49085705859961e-05 -8.06258739149372e-06 8.02777417154094e-06 1.58356877117928e-05 2.03834560966458e-07 -4.83515159206141e-07 -2.54370199779536e-06 3.69548809172258e-07 -6.02261495134494e-06 2.03834560966458e-07 2.57510689378901e-05 -8.02972330542833e-07 2.36452634558145e-06 -2.89213257967601e-06 -4.25864878934542e-06 -4.83515159206141e-07 -8.02972330542833e-07 4.2369621435059e-05 -3.56332056210215e-05 2.23279120634359e-05 -1.49085705859961e-05 -2.54370199779536e-06 2.36452634558145e-06 -3.56332056210215e-05 0.000205488255792389 1059 1068 0 267 0 1097 1106 0 276 0 0 0 0 0 0 0 0 0 2499 0 147 147 0 0 411 +314 443 0.998005614763682 0.0623512163468885 0.0098548830651911 -0.262868150232626 -0.061788929667371 0.996853407300077 -0.0496529206068298 -0.520369153915899 -0.0129197937570909 0.0489449708784362 0.998717912503317 0.0572264142755237 2.838313740084e-05 -1.56032100955608e-05 -7.34099813882213e-07 2.9632339053873e-06 -1.77277027250093e-06 -2.56976184536735e-06 -1.56032100955608e-05 3.38238979387478e-05 3.26866928626759e-06 -1.35039761866491e-05 -1.09056288595552e-05 3.21111792035851e-06 -7.34099813882213e-07 3.26866928626759e-06 1.59567582849292e-05 3.02281633782144e-06 1.78154851446949e-06 -8.28162596260895e-06 2.9632339053873e-06 -1.35039761866491e-05 3.02281633782144e-06 7.11079401420863e-05 4.35157462924942e-05 -1.12516615236535e-05 -1.77277027250093e-06 -1.09056288595552e-05 1.78154851446949e-06 4.35157462924942e-05 7.58952030797373e-05 -3.1879582545422e-07 -2.56976184536735e-06 3.21111792035851e-06 -8.28162596260895e-06 -1.12516615236535e-05 -3.1879582545422e-07 0.000143950883719709 1578 1621 0 115 0 1619 1662 0 128 0 0 0 0 0 0 0 0 0 2593 0 102 102 0 0 473 +314 440 0.906350825093911 0.422048788167777 -0.0200749161317669 -0.321801348990993 -0.421198187157931 0.906245961587933 0.0361986773299179 -0.788289748910687 0.0334704195739984 -0.0243531827832316 0.999142959491717 0.155718080234732 5.18999479010764e-05 -3.03453096405229e-05 -5.21516196800187e-06 -1.1366794695068e-06 1.71911737034261e-06 -3.3432396642394e-06 -3.03453096405229e-05 4.62493281702913e-05 1.05097441046333e-05 -3.31095583213249e-06 -2.43019847793379e-05 8.70007227495417e-06 -5.21516196800187e-06 1.05097441046333e-05 2.24010271491385e-05 9.25341117658974e-06 -3.51526480127367e-06 8.33957046109979e-07 -1.1366794695068e-06 -3.31095583213249e-06 9.25341117658974e-06 4.22362599559447e-05 1.42402430677709e-05 5.09133747257073e-06 1.71911737034261e-06 -2.43019847793379e-05 -3.51526480127367e-06 1.42402430677709e-05 0.000119452939118963 -9.20970508819733e-05 -3.3432396642394e-06 8.70007227495417e-06 8.33957046109979e-07 5.09133747257073e-06 -9.20970508819733e-05 0.000304161090114959 69 2 0 467 0 100 22 0 485 0 0 0 0 0 0 0 0 0 2025 0 213 185 0 0 438 +314 441 0.955027768079719 0.296261666969527 -0.0122876719156447 -0.309912235449511 -0.296078945740452 0.955049831984226 0.0147335099729738 -0.705286611040142 0.0161003132234191 -0.0104327901990809 0.999815951464453 0.135423833309021 3.23544107780806e-05 -2.3081137944831e-05 2.7349153432487e-07 4.67529111402011e-06 2.89026418993572e-06 -7.11838294821301e-06 -2.3081137944831e-05 3.05248240860957e-05 1.52868754494331e-06 -2.64471283763898e-06 -4.85846529211422e-07 -1.04117407689597e-05 2.7349153432487e-07 1.52868754494331e-06 1.41992347636424e-05 2.50353641631083e-06 5.89730576852983e-07 -1.35631793593255e-06 4.67529111402011e-06 -2.64471283763898e-06 2.50353641631083e-06 2.90019253566891e-05 5.91859472212432e-06 3.72473291129972e-06 2.89026418993572e-06 -4.85846529211422e-07 5.89730576852983e-07 5.91859472212432e-06 5.79201107531608e-05 -2.50615074630702e-05 -7.11838294821301e-06 -1.04117407689597e-05 -1.35631793593255e-06 3.72473291129972e-06 -2.50615074630702e-05 0.000199543362294182 534 493 0 357 0 570 529 0 363 0 0 0 0 0 0 0 0 0 2188 0 182 182 0 0 406 +314 455 0.740775362453244 -0.671743282761051 -0.00358112380003608 0.268168171285055 0.667514572647373 0.736689065075155 -0.108229001206186 0.5815076332611 0.0753402793043598 0.0777829252734863 0.994119539517376 0.0329121072197484 9.4378311777216e-05 -6.50552933649976e-05 -1.80397163747805e-06 -6.69560353694674e-05 1.99587047296841e-06 -6.99034852736179e-05 -6.50552933649976e-05 9.26145955516977e-05 -3.5759745467179e-06 2.82193598924208e-05 4.22853164043529e-06 7.55245521101096e-05 -1.80397163747805e-06 -3.5759745467179e-06 1.84592824859812e-05 1.77123607542487e-06 -4.61777708272962e-06 -1.56019892135322e-05 -6.69560353694674e-05 2.82193598924208e-05 1.77123607542487e-06 0.000507413939898758 1.43442915291678e-05 0.00044605767774119 1.99587047296841e-06 4.22853164043529e-06 -4.61777708272962e-06 1.43442915291678e-05 2.53335422886537e-05 3.79676971329514e-05 -6.99034852736179e-05 7.55245521101096e-05 -1.56019892135322e-05 0.00044605767774119 3.79676971329514e-05 0.000839742705299446 1726 1782 0 0 3059 1730 1786 0 0 3082 0 0 0 0 0 1533 1492 0 3373 0 0 0 0 0 737 +314 456 0.7282632929911 -0.685297149987268 0.000626339433544134 0.345903141835055 0.681445128675067 0.724072382932439 -0.106544454945159 0.686505622940553 0.0725610962346936 0.0780192315641893 0.994307742512022 -0.000386676863480803 5.08701664365289e-05 -4.93672659052995e-05 2.88034618814396e-06 2.21864290425498e-05 1.6148635931647e-06 -3.11783211622677e-05 -4.93672659052995e-05 6.40372397065705e-05 -2.14149232396187e-06 -1.41846349182172e-05 -7.54100176345745e-07 5.95650348597248e-05 2.88034618814396e-06 -2.14149232396187e-06 1.55176041162343e-05 4.29984111270814e-06 -1.44993029370233e-06 -1.46163492577584e-05 2.21864290425498e-05 -1.41846349182172e-05 4.29984111270814e-06 0.000242948470530299 -4.21833362306971e-06 2.1493171843579e-05 1.6148635931647e-06 -7.54100176345745e-07 -1.44993029370233e-06 -4.21833362306971e-06 1.91128777178583e-05 1.54559382381689e-05 -3.11783211622677e-05 5.95650348597248e-05 -1.46163492577584e-05 2.1493171843579e-05 1.54559382381689e-05 0.000502840420047088 1641 1694 0 0 3362 1654 1707 0 0 3384 0 0 0 0 0 1690 1644 0 3559 0 0 0 0 0 431 +314 439 0.851856938648587 0.523739108962097 -0.00609112632001087 -0.339034735113343 -0.523380629114284 0.851609675258177 0.0288734839359532 -0.88243023113165 0.0203094348565886 -0.0214081001084184 0.999564515229284 0.249072215659784 4.20675091410916e-05 -3.64028868633087e-05 -8.54785706620649e-06 -2.8842784435806e-06 -1.16067160714242e-05 3.21300229302349e-05 -3.64028868633087e-05 8.12030005615755e-05 8.12662871530514e-06 -1.08138514900827e-05 -6.70050811325124e-06 -5.1173886035987e-05 -8.54785706620649e-06 8.12662871530514e-06 2.30134821266036e-05 9.34640118729477e-06 -8.18389393497413e-06 -7.92021833884127e-06 -2.8842784435806e-06 -1.08138514900827e-05 9.34640118729477e-06 4.11346534809255e-05 1.53038959359014e-05 1.30860568771371e-05 -1.16067160714242e-05 -6.70050811325124e-06 -8.18389393497413e-06 1.53038959359014e-05 0.00015750416054852 -1.12516147859983e-05 3.21300229302349e-05 -5.1173886035987e-05 -7.92021833884127e-06 1.30860568771371e-05 -1.12516147859983e-05 0.000244358043906237 0 0 0 691 0 0 0 0 719 0 0 0 0 0 0 0 0 0 1572 0 0 0 0 8 487 +314 438 0.796240750596788 0.604441659905366 0.0255136602608992 -0.364942315418329 -0.604174203695738 0.796648685132901 -0.0180112205206034 -0.957783204323495 -0.031212155928168 -0.00107342762500286 0.99951220556602 0.324195086504175 4.08910356619331e-05 -2.58281963740736e-05 -2.34959606009305e-06 2.9852834770347e-06 1.1691080666995e-05 1.02012869495522e-05 -2.58281963740736e-05 6.56587519648954e-05 5.98475492789934e-06 -6.36027413610983e-06 -1.88726273006258e-05 -6.13216739384818e-05 -2.34959606009305e-06 5.98475492789934e-06 1.76113210998229e-05 4.98430388844687e-06 -5.26269614146312e-06 -5.49040579509821e-06 2.9852834770347e-06 -6.36027413610983e-06 4.98430388844687e-06 2.9569447097903e-05 4.51582860340713e-06 6.6038255711006e-06 1.1691080666995e-05 -1.88726273006258e-05 -5.26269614146312e-06 4.51582860340713e-06 0.000153678049179329 -1.43812563143916e-06 1.02012869495522e-05 -6.13216739384818e-05 -5.49040579509821e-06 6.6038255711006e-06 -1.43812563143916e-06 0.000125824617045746 0 0 0 539 0 0 0 0 560 0 0 0 0 0 0 0 0 0 1176 0 0 0 0 70 549 +315 449 0.892395322996544 -0.44915482244064 -0.0434802595692607 -0.115747392714279 0.445675740985257 0.892366160482263 -0.0711039346547495 0.0612986828470644 0.0707369874332782 0.0440747218307888 0.996520796323089 -0.017603565327786 3.5919500180585e-05 -2.05344077596756e-05 -1.91780525465293e-06 -4.35461531251789e-06 3.53439523734694e-06 1.95472522097535e-05 -2.05344077596756e-05 4.40836913404977e-05 2.62318879257599e-06 -2.24724602736584e-06 -6.19379996211391e-07 -2.89800865285397e-05 -1.91780525465293e-06 2.62318879257599e-06 1.67802107563809e-05 3.02298093803836e-06 6.9175511019153e-07 -3.01688712307527e-08 -4.35461531251789e-06 -2.24724602736584e-06 3.02298093803836e-06 6.90827545169174e-05 8.10835976770809e-06 -1.84502225826195e-05 3.53439523734694e-06 -6.19379996211391e-07 6.9175511019153e-07 8.10835976770809e-06 2.32028790143355e-05 -1.03140952425789e-05 1.95472522097535e-05 -2.89800865285397e-05 -3.01688712307527e-08 -1.84502225826195e-05 -1.03140952425789e-05 0.000105053901265618 2401 2518 0 0 613 2436 2553 0 0 613 0 0 0 0 0 789 803 0 2644 0 0 0 0 0 2429 +315 448 0.920528290185285 -0.389389660597009 -0.0316758455088578 -0.139997329738342 0.387675872213797 0.920480755730831 -0.0492198784280371 -0.0319374713112867 0.0483227179681259 0.0330283294967327 0.998285552524341 -0.0108277841118131 4.75800456931839e-05 -4.28112164466066e-05 3.04280931654285e-06 1.69881634368083e-05 -2.26569921164578e-07 1.55536247098725e-05 -4.28112164466066e-05 7.71537350527706e-05 1.44130845455009e-06 -4.50021313175391e-06 7.24812350592707e-06 -5.32284885290439e-05 3.04280931654285e-06 1.44130845455009e-06 1.63603503358213e-05 3.2853867883853e-06 -1.91317021850005e-06 -4.29519988427539e-06 1.69881634368083e-05 -4.50021313175391e-06 3.2853867883853e-06 5.99173404898683e-05 6.17500119976793e-06 -2.68470215032709e-06 -2.26569921164578e-07 7.24812350592707e-06 -1.91317021850005e-06 6.17500119976793e-06 2.71974660414178e-05 -6.92144191881909e-06 1.55536247098725e-05 -5.32284885290439e-05 -4.29519988427539e-06 -2.68470215032709e-06 -6.92144191881909e-06 0.000139951123100931 2583 2717 0 0 172 2616 2750 0 0 172 0 0 0 0 0 547 572 0 2634 0 0 0 0 0 1701 +315 450 0.857512584733748 -0.51377587713538 -0.0265803517098257 -0.0791296624013415 0.509076141056159 0.854857569158124 -0.100299646362458 0.15654733711202 0.0742539536362696 0.0724767861237983 0.994602164607813 -0.00604926713722667 1.8977654416112e-05 -9.10188849674556e-06 2.44967921717015e-06 1.21355729664811e-05 1.36351813635029e-06 -6.93165423418532e-06 -9.10188849674556e-06 1.99455217611629e-05 4.7960768995636e-06 3.81026708235018e-07 -2.54827112419345e-07 -1.00798090316675e-05 2.44967921717015e-06 4.7960768995636e-06 1.88681248320719e-05 1.02879143651238e-05 -2.7157577320207e-06 -1.48605161039649e-06 1.21355729664811e-05 3.81026708235018e-07 1.02879143651238e-05 6.68833081214593e-05 -5.22558306196899e-06 -2.90913088649559e-05 1.36351813635029e-06 -2.54827112419345e-07 -2.7157577320207e-06 -5.22558306196899e-06 2.22208169893463e-05 -1.22791387795381e-05 -6.93165423418532e-06 -1.00798090316675e-05 -1.48605161039649e-06 -2.90913088649559e-05 -1.22791387795381e-05 0.000130315297081426 2243 2342 0 0 1053 2292 2391 0 0 1053 0 0 0 0 0 1141 1141 0 2574 0 0 0 0 0 2169 +315 446 0.967165657064652 -0.254146198174725 -0.000549315968884503 -0.178243791434271 0.253571694640555 0.965120171203789 -0.0651494498264337 -0.221491996611454 0.0170876409084979 0.0628710194676601 0.997875366686281 0.0496853533851697 4.77366064138476e-05 -4.56722835883498e-05 -2.05017789406243e-06 4.06692360252268e-06 8.4752212803291e-07 2.99481707442385e-05 -4.56722835883498e-05 5.59148369800057e-05 2.80525131489828e-06 -2.53139712055155e-06 2.02738377326862e-06 -3.2961679022103e-05 -2.05017789406243e-06 2.80525131489828e-06 1.35774312484097e-05 1.54295236209647e-06 2.92199426832087e-06 -4.3250696956896e-06 4.06692360252268e-06 -2.53139712055155e-06 1.54295236209647e-06 6.2143622714565e-05 1.73391826233951e-05 1.89653718428664e-05 8.4752212803291e-07 2.02738377326862e-06 2.92199426832087e-06 1.73391826233951e-05 3.0312936472025e-05 5.21093059527427e-06 2.99481707442385e-05 -3.2961679022103e-05 -4.3250696956896e-06 1.89653718428664e-05 5.21093059527427e-06 0.000232734347557021 2368 2368 0 0 0 2396 2396 0 0 0 0 0 0 0 0 217 241 0 2333 0 0 0 0 0 765 +315 445 0.983781688583345 -0.179264848115183 -0.00614031256073442 -0.199859288659708 0.178251412420614 0.980890836008677 -0.0779718013403196 -0.313090678880752 0.020000579445593 0.0756127109978097 0.996936655338443 0.00938098961335032 2.88955473895366e-05 -1.40567318102235e-05 -2.77468828632049e-07 1.0767097326722e-05 3.90177849035359e-06 8.65906205909273e-06 -1.40567318102235e-05 4.23152673027678e-05 8.67723454912494e-07 5.2848649070306e-06 1.10683473571567e-05 -6.2113694256296e-06 -2.77468828632049e-07 8.67723454912494e-07 1.3728624227693e-05 -8.80429807209456e-07 1.18590016249078e-07 -6.4570618799726e-06 1.0767097326722e-05 5.2848649070306e-06 -8.80429807209456e-07 4.25789404694992e-05 9.1037074203299e-06 -4.64256946025603e-08 3.90177849035359e-06 1.10683473571567e-05 1.18590016249078e-07 9.1037074203299e-06 3.18512967267794e-05 1.77540235663975e-06 8.65906205909273e-06 -6.2113694256296e-06 -6.4570618799726e-06 -4.64256946025603e-08 1.77540235663975e-06 0.000118506293661338 2082 2082 0 0 0 2088 2088 0 0 0 0 0 0 0 0 135 171 0 2390 0 0 0 0 0 352 +315 454 0.717392782318229 -0.696651257642561 0.00496196561338926 0.125904936696645 0.691003987326479 0.710634830935824 -0.132331502521961 0.515657232539705 0.0886627620628737 0.0983624028064103 0.991193095384311 0.0594636135734745 0.000127189590521022 -6.27957749341543e-05 -1.1452943710454e-05 -4.97525017051172e-05 -7.84764842475852e-07 -0.000544338496955517 -6.27957749341543e-05 5.31661678298156e-05 8.66819734442734e-06 9.95650379635506e-06 -1.59288428739803e-06 0.000244119315228063 -1.1452943710454e-05 8.66819734442734e-06 1.7428837311559e-05 1.45877011796976e-05 -1.56831804419163e-06 5.52805385081992e-05 -4.97525017051172e-05 9.95650379635506e-06 1.45877011796976e-05 0.000313882891160289 6.65134880514033e-06 0.0002222277357228 -7.84764842475852e-07 -1.59288428739803e-06 -1.56831804419163e-06 6.65134880514033e-06 2.11263730427797e-05 3.19481647710548e-05 -0.000544338496955517 0.000244119315228063 5.52805385081992e-05 0.0002222277357228 3.19481647710548e-05 0.00328754985779365 1686 1750 0 0 2682 1715 1779 0 0 2682 0 0 0 0 0 1539 1506 0 2998 0 0 0 0 0 974 +315 443 0.999909058391842 -0.0129107592560357 0.0038970811349255 -0.235739858339398 0.0131070861039539 0.998375149463868 -0.0554550739505734 -0.503042595665942 -0.00317478185125255 0.0555011101549574 0.998453578055467 0.0672231193018509 3.18882359807017e-05 -1.86130520959487e-05 -7.96932488190466e-07 -1.09702363234249e-08 3.60877827124802e-06 -1.89212516890686e-05 -1.86130520959487e-05 2.46231744383537e-05 3.81506499886999e-06 9.16245214999872e-06 5.74563922597302e-06 2.3111394993113e-06 -7.96932488190466e-07 3.81506499886999e-06 1.5433618507681e-05 2.97386082471255e-06 -2.23161106210192e-06 -3.00372579433909e-06 -1.09702363234249e-08 9.16245214999872e-06 2.97386082471255e-06 8.05192713602085e-05 5.12483616261264e-05 4.05661373892679e-05 3.60877827124802e-06 5.74563922597302e-06 -2.23161106210192e-06 5.12483616261264e-05 8.94365057725977e-05 3.98873694843483e-05 -1.89212516890686e-05 2.3111394993113e-06 -3.00372579433909e-06 4.05661373892679e-05 3.98873694843483e-05 0.000216646305324845 1640 1654 0 35 0 1640 1681 0 65 0 0 0 0 0 0 1 42 0 2395 0 20 20 0 0 415 +315 442 0.994736206520558 0.100275919973471 -0.0210859979740846 -0.2367052307909 -0.10069751040388 0.994716390263247 -0.0199828511508407 -0.587264838632919 0.018970789007036 0.0220009730496238 0.999577944109073 0.085171853588639 2.7750998496986e-05 -1.30705873741034e-05 -1.39025756322275e-06 -7.40528328593101e-06 -7.85602799930509e-06 -2.0315007578846e-05 -1.30705873741034e-05 2.63423263106851e-05 1.89820008785866e-07 -9.94081992648109e-06 -6.20501327187457e-06 -2.57532142203574e-05 -1.39025756322275e-06 1.89820008785866e-07 1.3068213854374e-05 2.62254246995261e-06 2.58866898722957e-06 4.10135645439959e-08 -7.40528328593101e-06 -9.94081992648109e-06 2.62254246995261e-06 6.57244309675235e-05 5.13301032929157e-05 2.91567396881522e-05 -7.85602799930509e-06 -6.20501327187457e-06 2.58866898722957e-06 5.13301032929157e-05 0.000100219523382963 1.65152210438405e-05 -2.0315007578846e-05 -2.57532142203574e-05 4.10135645439959e-08 2.91567396881522e-05 1.65152210438405e-05 0.000198938436612039 1177 1186 0 187 0 1177 1186 0 209 0 0 0 0 0 0 0 0 0 2303 0 27 27 0 0 441 +315 452 0.782787818957208 -0.622148771060901 -0.0131961039563614 0.0174575275262496 0.616476421383044 0.778193611955655 -0.119881292077482 0.337610067870974 0.0848531223407417 0.085706528215888 0.992700528180683 0.0449268863901381 2.78749542696312e-05 -2.17204262211951e-05 -1.16727799988742e-06 3.12425532366281e-06 1.03548690510708e-06 1.17783561663146e-05 -2.17204262211951e-05 3.59898953092966e-05 6.27580191995229e-06 -1.45737504356314e-06 -1.1752400692324e-06 -1.74898065199715e-05 -1.16727799988742e-06 6.27580191995229e-06 1.50753506239699e-05 7.43591277629715e-06 1.61805290988223e-06 -1.97265300994055e-06 3.12425532366281e-06 -1.45737504356314e-06 7.43591277629715e-06 0.000152644019991838 8.59185884686049e-06 -2.19210048247295e-05 1.03548690510708e-06 -1.1752400692324e-06 1.61805290988223e-06 8.59185884686049e-06 1.90924048244206e-05 -6.51219679294118e-06 1.17783561663146e-05 -1.74898065199715e-05 -1.97265300994055e-06 -2.19210048247295e-05 -6.51219679294118e-06 0.000113744491553676 1902 1981 0 0 1921 1921 2000 0 0 1921 0 0 0 0 0 1310 1295 0 2760 0 0 0 0 0 1727 +315 444 0.994002569881637 -0.108560468847189 0.0131725347742857 -0.223762442866423 0.109266263395336 0.990847053932683 -0.0792653732505195 -0.416262321850452 -0.00444688119050298 0.0802292983678749 0.996766514752114 0.0164356551318687 4.3798288652415e-05 -2.70054370040823e-05 -4.44171379848027e-06 -3.4028330380919e-06 1.07636133000965e-06 -4.41340241072145e-05 -2.70054370040823e-05 4.45462417833287e-05 3.51898208645212e-06 5.03934572425146e-06 5.89228952788211e-06 5.52783892941644e-06 -4.44171379848027e-06 3.51898208645212e-06 1.41444916534405e-05 -2.40388636322879e-07 -4.19902709829807e-06 1.90447835619837e-06 -3.4028330380919e-06 5.03934572425146e-06 -2.40388636322879e-07 6.53850523961233e-05 3.43911542292783e-05 4.24589940839204e-06 1.07636133000965e-06 5.89228952788211e-06 -4.19902709829807e-06 3.43911542292783e-05 6.96373968655202e-05 -1.21095248367879e-05 -4.41340241072145e-05 5.52783892941644e-06 1.90447835619837e-06 4.24589940839204e-06 -1.21095248367879e-05 0.000311281986054473 1850 1850 0 0 0 1876 1876 0 0 0 0 0 0 0 0 114 128 0 2128 0 7 7 0 0 303 +315 440 0.936175292753291 0.351195001348839 -0.0154237565423943 -0.253683507227954 -0.350990090765051 0.936266632089038 0.0145172249893356 -0.75966877836467 0.0195391254418199 -0.00817708164560366 0.999775653790754 0.151289556297285 4.07942238999409e-05 -3.48961452507753e-05 -3.39066999693419e-06 -3.79869305109422e-07 9.75042123422619e-07 1.22191932835446e-05 -3.48961452507753e-05 6.06424400872712e-05 7.68455132590354e-06 -9.58622829871322e-07 -4.06908506505655e-06 -4.79954046995217e-05 -3.39066999693419e-06 7.68455132590354e-06 2.13510802175626e-05 9.81338953199177e-06 -3.98223360473271e-06 -4.95265628230688e-06 -3.79869305109422e-07 -9.58622829871322e-07 9.81338953199177e-06 4.37903206468383e-05 1.55085493944145e-05 4.86528771887294e-06 9.75042123422619e-07 -4.06908506505655e-06 -3.98223360473271e-06 1.55085493944145e-05 0.000123059367877062 -3.61342280395583e-05 1.22191932835446e-05 -4.79954046995217e-05 -4.95265628230688e-06 4.86528771887294e-06 -3.61342280395583e-05 0.0001737724725474 154 56 0 424 0 154 56 0 433 0 0 0 0 0 0 0 0 0 1982 0 63 59 0 0 558 +315 441 0.97466725284475 0.222990045343836 -0.0172969913459433 -0.254676286134783 -0.223028710224808 0.97481182555542 -0.000314917080202198 -0.675691184279331 0.0167910883365615 0.00416466503608998 0.999850346260685 0.111584479706177 2.74464316310916e-05 -2.05641124204231e-05 -5.08470126093023e-06 -9.57302003446242e-07 -1.40645552913053e-07 6.71168641147524e-06 -2.05641124204231e-05 3.5917335779655e-05 1.87770429883728e-06 -4.88593369974919e-06 2.44919273731899e-06 -1.57109680752799e-05 -5.08470126093023e-06 1.87770429883728e-06 1.31439695604323e-05 1.0814924386059e-06 -3.13290264254348e-07 4.19444379856842e-06 -9.57302003446242e-07 -4.88593369974919e-06 1.0814924386059e-06 3.26940144235182e-05 1.63138791729545e-05 3.51971289555955e-06 -1.40645552913053e-07 2.44919273731899e-06 -3.13290264254348e-07 1.63138791729545e-05 7.69377056821198e-05 -2.56813148656985e-05 6.71168641147524e-06 -1.57109680752799e-05 4.19444379856842e-06 3.51971289555955e-06 -2.56813148656985e-05 0.000119577189197506 663 622 0 323 0 663 622 0 339 0 0 0 0 0 0 0 0 0 2216 0 45 45 0 0 516 +316 449 0.851872751479103 -0.52288839348618 -0.0300090527152004 -0.121383868004079 0.519973707095992 0.85121014704044 -0.0711943080888078 0.114449904643509 0.0627706875561669 0.0450445727345018 0.997010946404749 -0.00967729813285599 5.19388084688016e-05 -4.67373275567745e-05 -9.91878090744024e-07 -4.73991622726936e-06 -2.09819645918802e-06 4.59298485417342e-05 -4.67373275567745e-05 7.75774288139844e-05 1.97050707529787e-06 5.69208011206857e-06 6.70030710177778e-06 -7.60296511916533e-05 -9.91878090744024e-07 1.97050707529787e-06 1.18544249452295e-05 6.76045351291711e-07 3.3331989907927e-06 -9.91536947637816e-07 -4.73991622726936e-06 5.69208011206857e-06 6.76045351291711e-07 4.89043488145932e-05 3.99251406148209e-06 -2.40592570026018e-05 -2.09819645918802e-06 6.70030710177778e-06 3.3331989907927e-06 3.99251406148209e-06 1.92784687883271e-05 -2.59395194531004e-05 4.59298485417342e-05 -7.60296511916533e-05 -9.91536947637816e-07 -2.40592570026018e-05 -2.59395194531004e-05 0.000287711615428747 2173 2290 0 0 522 2200 2317 0 0 522 0 0 0 0 0 958 972 0 2498 0 0 0 0 0 2224 +315 439 0.888618653052915 0.458567282489977 -0.00854030890433994 -0.273258121006868 -0.458455992245378 0.888632022686806 0.0122976188696151 -0.858646594362419 0.0132284776421706 -0.00701253772285427 0.999887909564845 0.233805972746577 3.45310481929454e-05 -2.5942231610798e-05 -8.2846885939166e-06 -8.34036383804447e-07 6.33753384540067e-06 2.58735236933347e-05 -2.5942231610798e-05 5.80295667673894e-05 4.41693395107097e-06 -1.01196132517009e-05 -1.30749174051296e-05 -3.43920729934396e-05 -8.2846885939166e-06 4.41693395107097e-06 2.25299709592149e-05 1.34454760236565e-05 4.63651766697366e-06 -6.46240381283621e-06 -8.34036383804447e-07 -1.01196132517009e-05 1.34454760236565e-05 5.33885617214286e-05 4.08995976235093e-05 7.60398380522282e-06 6.33753384540067e-06 -1.30749174051296e-05 4.63651766697366e-06 4.08995976235093e-05 0.000181977682391836 5.59603700380102e-06 2.58735236933347e-05 -3.43920729934396e-05 -6.46240381283621e-06 7.60398380522282e-06 5.59603700380102e-06 0.000121891389363265 0 0 0 685 0 0 0 0 690 0 0 0 0 0 0 0 0 0 1668 0 0 0 0 2 573 +316 450 0.81304340942278 -0.581803448330579 -0.0215676124044733 -0.103314826401195 0.576625796647821 0.809817385458583 -0.108159571232929 0.2037201736468 0.0803934390012496 0.0755019848724057 0.993899564969157 -0.0218465593728272 6.20059477068528e-05 -4.9861467274856e-05 -2.90478907009535e-06 5.4202834464084e-07 4.22146460261368e-06 4.81086315079723e-05 -4.9861467274856e-05 9.72578670507429e-05 9.47193992806184e-06 1.46966254526879e-05 -4.47761939108705e-06 -7.62938592470324e-05 -2.90478907009535e-06 9.47193992806184e-06 1.67313288756115e-05 1.20247086118902e-05 -2.50190921769395e-06 -9.29005561465511e-06 5.4202834464084e-07 1.46966254526879e-05 1.20247086118902e-05 0.000131307053539686 9.15635717467685e-06 1.6172698440171e-05 4.22146460261368e-06 -4.47761939108705e-06 -2.50190921769395e-06 9.15635717467685e-06 2.50375170628383e-05 1.05802165630286e-05 4.81086315079723e-05 -7.62938592470324e-05 -9.29005561465511e-06 1.6172698440171e-05 1.05802165630286e-05 0.000232450246668194 1978 2077 0 0 919 2009 2108 0 0 919 0 0 0 0 0 1067 1067 0 2481 0 0 0 0 0 2045 +316 451 0.77039318740109 -0.637415266849458 -0.0140040848762834 -0.0543525108595218 0.631493884506058 0.765893234443785 -0.120925709692713 0.307355866200683 0.0878055273740628 0.0843168489714314 0.992562772998309 0.0536680063553962 4.24000192770129e-05 -2.44753446902479e-05 -4.20924945402013e-07 8.97783981390431e-06 3.08440063998932e-06 -1.39158498764741e-05 -2.44753446902479e-05 4.33981418460904e-05 5.35428644096731e-06 -1.17890808794895e-05 -7.34351189826774e-06 -5.28244657266738e-06 -4.20924945402013e-07 5.35428644096731e-06 1.76602683840662e-05 9.44905254093552e-06 -4.60884249008601e-06 3.21032081430443e-06 8.97783981390431e-06 -1.17890808794895e-05 9.44905254093552e-06 0.000112246176779663 3.00758476232631e-07 5.46701797266858e-07 3.08440063998932e-06 -7.34351189826774e-06 -4.60884249008601e-06 3.00758476232631e-07 2.74759836505984e-05 -7.72566164987219e-06 -1.39158498764741e-05 -5.28244657266738e-06 3.21032081430443e-06 5.46701797266858e-07 -7.72566164987219e-06 0.00027250913663156 1807 1896 0 0 1443 1845 1934 0 0 1443 0 0 0 0 0 1440 1429 0 2569 0 0 0 0 0 1753 +316 442 0.999644124745539 0.0185282935782342 -0.019191826354064 -0.208218536342163 -0.019108655735935 0.999351741190661 -0.0305115823116243 -0.570113552723222 0.0186140575289564 0.0308674539972488 0.99935014741883 0.0899670772925565 4.33301675783722e-05 -4.12278955239861e-05 -7.11679591043202e-06 -3.29894119590158e-06 8.26948192784569e-06 -9.97825224618912e-06 -4.12278955239861e-05 5.55790999063109e-05 8.59048837567268e-06 -2.09604999477121e-06 -1.35022848989385e-05 3.75438299219016e-06 -7.11679591043202e-06 8.59048837567268e-06 1.50669391182965e-05 4.46288011123451e-06 1.8631778169259e-07 4.72137139374847e-06 -3.29894119590158e-06 -2.09604999477121e-06 4.46288011123451e-06 4.34561120740247e-05 1.74533646951306e-05 2.93318573328838e-06 8.26948192784569e-06 -1.35022848989385e-05 1.8631778169259e-07 1.74533646951306e-05 6.7374410042615e-05 -6.27599397287908e-05 -9.97825224618912e-06 3.75438299219016e-06 4.72137139374847e-06 2.93318573328838e-06 -6.27599397287908e-05 0.000391214723008249 964 971 0 68 0 964 971 0 84 0 0 0 0 0 0 0 0 0 2218 0 4 4 0 0 447 +316 444 0.981826904428629 -0.189327463866284 0.0130782707594185 -0.192778361420578 0.189744392289967 0.978007004629407 -0.0865988711838991 -0.373369298273384 0.00360490424377933 0.0875066301589508 0.996157414439916 0.0199795771986669 3.58143946995532e-05 -3.22756151296868e-05 -1.53946245721628e-06 -2.59065475111908e-06 1.36575324441217e-06 9.02303169240636e-06 -3.22756151296868e-05 5.2356986497011e-05 3.93200601189775e-06 2.32252281108236e-06 -2.84600373535006e-06 8.03728562285594e-06 -1.53946245721628e-06 3.93200601189775e-06 1.72269906669871e-05 4.58679360728443e-06 -3.37227469183101e-06 1.18245924313477e-06 -2.59065475111908e-06 2.32252281108236e-06 4.58679360728443e-06 5.94571420204495e-05 1.73720677672286e-05 -7.94203092728657e-06 1.36575324441217e-06 -2.84600373535006e-06 -3.37227469183101e-06 1.73720677672286e-05 5.61648757067188e-05 -1.94555439944998e-05 9.02303169240636e-06 8.03728562285594e-06 1.18245924313477e-06 -7.94203092728657e-06 -1.94555439944998e-05 0.000191356446332389 1611 1611 0 0 0 1634 1634 0 0 0 0 0 0 0 0 217 236 0 2209 0 0 0 0 0 347 +316 445 0.965235420478997 -0.261368428057066 -0.00266980668077566 -0.181889385042524 0.260330364052409 0.962216895278077 -0.0797919043121482 -0.276577065734381 0.0234240176971146 0.0763229405644003 0.996807967533631 0.00268276766357132 2.88666971926624e-05 -1.07488739191942e-05 -6.31717529499247e-07 3.65508792774959e-06 2.49318559040537e-06 6.56196137551291e-06 -1.07488739191942e-05 3.38227532359549e-05 3.0423711362849e-06 1.31346207851023e-06 9.05026927972224e-07 -9.3765154559591e-06 -6.31717529499247e-07 3.0423711362849e-06 1.38883490162921e-05 -1.00333956836851e-06 -5.58310421599896e-07 -2.86065189599029e-06 3.65508792774959e-06 1.31346207851023e-06 -1.00333956836851e-06 4.3722003159646e-05 1.23179438631365e-05 1.04554611798281e-05 2.49318559040537e-06 9.05026927972224e-07 -5.58310421599896e-07 1.23179438631365e-05 3.74882942331057e-05 1.09901454048609e-05 6.56196137551291e-06 -9.3765154559591e-06 -2.86065189599029e-06 1.04554611798281e-05 1.09901454048609e-05 0.000128404280411687 1840 1840 0 0 0 1860 1860 0 0 0 0 0 0 0 0 275 306 0 2348 0 0 0 0 0 422 +316 453 0.691058473873701 -0.722782238001327 -0.00490123628737243 0.0391479138737121 0.715727196844437 0.685227837435381 -0.134897703838261 0.500694537338949 0.100860127823415 0.0897142532345019 0.990847408727509 0.0358410114209054 2.73634537249992e-05 -2.12489924418867e-05 3.88637836119408e-06 7.41010080168574e-06 -1.48785330837888e-06 5.12899905227699e-06 -2.12489924418867e-05 2.94783536091566e-05 -3.33700483885061e-07 -1.20196502999955e-05 3.49603130301256e-06 3.13361322019574e-06 3.88637836119408e-06 -3.33700483885061e-07 1.46903867729285e-05 9.32179093299405e-06 -1.83715540419493e-06 -7.06139915852468e-06 7.41010080168574e-06 -1.20196502999955e-05 9.32179093299405e-06 0.000135652867264235 -6.26380860015591e-06 -2.77479246375404e-05 -1.48785330837888e-06 3.49603130301256e-06 -1.83715540419493e-06 -6.26380860015591e-06 2.04812349898571e-05 5.83142638309161e-06 5.12899905227699e-06 3.13361322019574e-06 -7.06139915852468e-06 -2.77479246375404e-05 5.83142638309161e-06 0.000212503169273617 1515 1583 0 0 2239 1559 1627 0 0 2239 0 0 0 0 0 1754 1727 0 2756 0 0 0 0 0 1105 +316 443 0.995268355141109 -0.0955799123042057 0.0174751714907461 -0.210713268514557 0.0966124813598223 0.992619710432109 -0.0732948764046524 -0.478201837328757 -0.0103406818057916 0.0746363907594387 0.997157198978273 0.00718724822317506 3.8231429097918e-05 -2.72638529795098e-05 -2.41844421678575e-06 1.59998881492967e-06 6.92859144336204e-07 -1.07463359561259e-05 -2.72638529795098e-05 4.29548032935705e-05 4.18758602728436e-06 1.28925333795091e-06 3.26536004472878e-06 -1.4016009901151e-05 -2.41844421678575e-06 4.18758602728436e-06 1.26948781646783e-05 -4.22783438629391e-07 1.33019415819981e-06 -2.20854290742034e-06 1.59998881492967e-06 1.28925333795091e-06 -4.22783438629391e-07 5.70604341563877e-05 3.17993152874419e-05 9.60446028724838e-06 6.92859144336204e-07 3.26536004472878e-06 1.33019415819981e-06 3.17993152874419e-05 6.35054719384985e-05 3.11337160211025e-06 -1.07463359561259e-05 -1.4016009901151e-05 -2.20854290742034e-06 9.60446028724838e-06 3.11337160211025e-06 0.00018948334918236 1394 1394 0 0 0 1410 1410 0 0 0 0 0 0 0 0 96 120 0 2292 0 5 5 0 0 268 +316 441 0.989830337382111 0.140939910592614 -0.0192832777338818 -0.204960695006133 -0.141110435170076 0.98996327842884 -0.00778154538209188 -0.639142809410333 0.0179930065338631 0.0104234814034437 0.999783777999676 0.0995329006868825 4.54253190602662e-05 -3.15380395670066e-05 -7.83620698283912e-06 -4.42985802741394e-06 -5.24497993239328e-06 -2.08451436143686e-05 -3.15380395670066e-05 4.62296761349757e-05 1.00701255711107e-05 2.99258566042676e-06 7.2490126689623e-08 -8.9905257804472e-06 -7.83620698283912e-06 1.00701255711107e-05 1.49569962159871e-05 2.45478782054911e-07 -1.3143950885794e-06 -3.32221864164831e-06 -4.42985802741394e-06 2.99258566042676e-06 2.45478782054911e-07 3.18178678957068e-05 1.35554623621308e-05 1.9904476574815e-05 -5.24497993239328e-06 7.2490126689623e-08 -1.3143950885794e-06 1.35554623621308e-05 7.59682499288494e-05 2.23148669098938e-06 -2.08451436143686e-05 -8.9905257804472e-06 -3.32221864164831e-06 1.9904476574815e-05 2.23148669098938e-06 0.000239346994505162 552 511 0 228 0 552 511 0 238 0 0 0 0 0 0 0 0 0 2220 0 16 16 0 0 527 +317 448 0.839727984383642 -0.540776339969771 -0.0491717639696209 -0.15883516004094 0.537184668355956 0.840536189689853 -0.0702249663934719 0.0600023563829011 0.0793066474281159 0.032555551762501 0.996318519211177 -0.030974661390274 3.25074933078487e-05 -2.15484582607528e-05 3.19250393728519e-06 1.34952446950476e-06 -4.22274243059415e-06 1.22162867471884e-05 -2.15484582607528e-05 4.20664622390676e-05 -6.86396008598778e-07 6.7956205552242e-07 5.32306600093805e-06 -2.26955111125779e-05 3.19250393728519e-06 -6.86396008598778e-07 1.83249838334029e-05 8.84109269668726e-06 -5.56835389901317e-06 1.47126578712548e-06 1.34952446950476e-06 6.7956205552242e-07 8.84109269668726e-06 5.22613923527605e-05 -8.11950550973961e-06 2.9591034384348e-05 -4.22274243059415e-06 5.32306600093805e-06 -5.56835389901317e-06 -8.11950550973961e-06 2.93819281422329e-05 1.54508254509661e-06 1.22162867471884e-05 -2.26955111125779e-05 1.47126578712548e-06 2.9591034384348e-05 1.54508254509661e-06 0.000218011313299865 2083 2192 0 0 0 2082 2191 0 0 0 0 0 0 0 0 1043 1068 0 2283 0 0 0 0 0 1571 +316 439 0.923501372925422 0.383452214664921 -0.0104696357829338 -0.202275677088733 -0.383392853047248 0.92355678325448 0.00726555826677751 -0.812795031879641 0.0124552975537052 -0.00269576950125412 0.999918795897769 0.218235896997355 4.04629157478666e-05 -3.92181770339821e-05 -4.86927285676107e-06 7.61135097262919e-06 9.94597439221827e-06 4.0102234241575e-05 -3.92181770339821e-05 6.59403677143661e-05 6.57289255982906e-06 -1.00697636962051e-05 -2.51269692707843e-05 -4.80549228605456e-05 -4.86927285676107e-06 6.57289255982906e-06 1.58024332380298e-05 3.54086627880032e-06 4.30849211257505e-06 -6.64495343489472e-06 7.61135097262919e-06 -1.00697636962051e-05 3.54086627880032e-06 4.42533696888967e-05 5.62017221461632e-05 1.82071958980699e-05 9.94597439221827e-06 -2.51269692707843e-05 4.30849211257505e-06 5.62017221461632e-05 0.000215802052470581 3.09214553935737e-05 4.0102234241575e-05 -4.80549228605456e-05 -6.64495343489472e-06 1.82071958980699e-05 3.09214553935737e-05 0.000168676515511481 0 0 0 588 0 0 0 0 597 0 0 0 0 0 0 0 0 0 1777 0 0 0 0 1 680 +316 438 0.882109289369202 0.470687981761586 0.0183309965295641 -0.219689420698127 -0.469920548528671 0.882024419129495 -0.0347505702081145 -0.902353604677364 -0.0325250623223753 0.0220396888472045 0.99922788813986 0.306906924031382 2.74517611979972e-05 -2.50926847692387e-05 -3.26745026768797e-06 4.53057862043079e-07 7.81515505997091e-06 2.82445815731978e-05 -2.50926847692387e-05 4.42746602541579e-05 4.21391145008457e-06 -4.23666931173367e-06 -1.01520161891425e-05 -5.20651682088392e-05 -3.26745026768797e-06 4.21391145008457e-06 1.45013421514148e-05 2.75089359828937e-06 1.79671133879639e-06 -5.78840911772803e-06 4.53057862043079e-07 -4.23666931173367e-06 2.75089359828937e-06 3.00354452112171e-05 1.04677883309059e-05 1.53942913843274e-05 7.81515505997091e-06 -1.01520161891425e-05 1.79671133879639e-06 1.04677883309059e-05 9.75195975328159e-05 2.78047726196938e-05 2.82445815731978e-05 -5.20651682088392e-05 -5.78840911772803e-06 1.53942913843274e-05 2.78047726196938e-05 0.000160590530209347 0 0 0 450 0 0 0 0 456 0 0 0 0 0 0 0 0 0 1298 0 0 0 0 18 653 +317 446 0.90980137105847 -0.414754666068275 -0.0154929724301765 -0.169016111573698 0.412064699315608 0.90710575213433 -0.0858011539709578 -0.132463054515546 0.049640193372569 0.0716779004952306 0.996191813750008 0.0103544441237023 2.95268100819231e-05 -2.134160063363e-05 -1.37667027168964e-06 -4.97862872346344e-06 2.79255351321137e-07 1.12085025592035e-05 -2.134160063363e-05 3.79794386990466e-05 2.62113613375716e-06 4.88343872981624e-06 4.75585107745138e-06 -8.81812880895095e-06 -1.37667027168964e-06 2.62113613375716e-06 1.15328916106039e-05 -3.57303161157766e-07 2.30696327437132e-06 -1.56371168265879e-06 -4.97862872346344e-06 4.88343872981624e-06 -3.57303161157766e-07 3.1430187024105e-05 1.42244905414081e-06 1.16859576515502e-05 2.79255351321137e-07 4.75585107745138e-06 2.30696327437132e-06 1.42244905414081e-06 1.91131425982712e-05 3.56462195417465e-06 1.12085025592035e-05 -8.81812880895095e-06 -1.56371168265879e-06 1.16859576515502e-05 3.56462195417465e-06 0.000212715266304761 1746 1746 0 0 0 1745 1745 0 0 0 0 0 0 0 0 637 667 0 2072 0 0 0 0 0 717 +317 450 0.757651667337809 -0.651789539885504 -0.0336800634809441 -0.132240493844104 0.644589766104675 0.755376860189953 -0.117939953038352 0.259168726532318 0.102313168328219 0.0676475778236779 0.992449404655588 -0.0081757676593136 3.91448989858242e-05 -1.90847862604637e-05 -2.4181276717065e-06 1.25605597627409e-05 3.75388740145556e-06 1.18108603265771e-05 -1.90847862604637e-05 4.49089769702273e-05 1.39326507660827e-06 3.24256284622326e-06 3.68359632437715e-06 -8.83208850318556e-06 -2.4181276717065e-06 1.39326507660827e-06 1.7162212665159e-05 2.90764407630938e-06 -2.77752911776271e-06 -3.12657304205019e-06 1.25605597627409e-05 3.24256284622326e-06 2.90764407630938e-06 6.7533850782886e-05 2.86470322198988e-07 1.21691463116703e-05 3.75388740145556e-06 3.68359632437715e-06 -2.77752911776271e-06 2.86470322198988e-07 2.44626023366209e-05 2.48916564306157e-06 1.18108603265771e-05 -8.83208850318556e-06 -3.12657304205019e-06 1.21691463116703e-05 2.48916564306157e-06 0.000138088831633013 1636 1735 0 0 823 1636 1735 0 0 823 0 0 0 0 0 1417 1417 0 2202 0 0 0 0 0 1649 +317 442 0.996904869646855 -0.0697967329197376 -0.0361814448041891 -0.165776965308706 0.0683314193091839 0.996849718886925 -0.0402672955418024 -0.509681965419649 0.03887798875431 0.0376703335370047 0.998533648888023 0.0727765273153465 2.81245127680255e-05 -2.16250634178239e-05 -2.17178398434333e-06 -4.2235338095927e-06 -3.1785972679631e-06 9.36924781693329e-06 -2.16250634178239e-05 3.3428703380446e-05 1.89144977950531e-06 -6.22493312517381e-06 -1.065249346304e-05 -1.11254640510562e-05 -2.17178398434333e-06 1.89144977950531e-06 1.27739100124505e-05 1.24300336120488e-06 1.08504252574612e-06 -1.70980803096479e-06 -4.2235338095927e-06 -6.22493312517381e-06 1.24300336120488e-06 4.75286592523305e-05 3.23331371414722e-05 4.64344617731551e-06 -3.1785972679631e-06 -1.065249346304e-05 1.08504252574612e-06 3.23331371414722e-05 7.39189017514952e-05 -1.72352246209147e-05 9.36924781693329e-06 -1.11254640510562e-05 -1.70980803096479e-06 4.64344617731551e-06 -1.72352246209147e-05 0.000261646861086293 864 870 0 15 0 864 870 0 16 0 0 0 0 0 0 0 0 0 2252 0 0 0 0 0 468 +317 441 0.997836959818603 0.0539899480150393 -0.0375031616440778 -0.16616186636138 -0.0548112556738358 0.998271067801147 -0.0212273748403945 -0.598874151786674 0.0362922563562239 0.0232370545571199 0.999071024214036 0.0932446783335327 5.60063491876262e-05 -4.96387153077958e-05 -4.285937712622e-06 4.2312186231259e-06 1.72011697657662e-05 8.20455555302708e-06 -4.96387153077958e-05 5.85272585267723e-05 2.69591996064626e-06 -9.96829190864811e-06 -2.54887163574818e-05 3.73554020116442e-06 -4.285937712622e-06 2.69591996064626e-06 1.18754732222851e-05 -1.30834063757615e-06 1.94116722744544e-07 1.3058425011081e-06 4.2312186231259e-06 -9.96829190864811e-06 -1.30834063757615e-06 3.17001670211229e-05 2.54890394387646e-05 -6.98022161027633e-06 1.72011697657662e-05 -2.54887163574818e-05 1.94116722744544e-07 2.54890394387646e-05 9.86740824596639e-05 -5.66365942600671e-05 8.20455555302708e-06 3.73554020116442e-06 1.3058425011081e-06 -6.98022161027633e-06 -5.66365942600671e-05 0.000205647361623294 440 399 0 143 0 440 399 0 142 0 0 0 0 0 0 0 0 0 2146 0 0 0 0 0 803 +317 443 0.982986663145238 -0.183622817282566 -0.00445881730997792 -0.173135226434744 0.182856875998512 0.980600862140945 -0.0706067423728078 -0.419360506317227 0.0173373290519326 0.0685901606766512 0.997494264083607 0.0462266610114871 3.48579035496573e-05 -2.72428073067273e-05 -1.95997178489227e-06 2.9209991918445e-06 4.58093606113138e-06 1.54367453450223e-05 -2.72428073067273e-05 4.13775854454499e-05 2.60589400718259e-06 6.86327121071238e-06 7.49337314104238e-06 -2.12705324785042e-05 -1.95997178489227e-06 2.60589400718259e-06 1.26385694705158e-05 4.24345653924502e-08 4.67733796607419e-07 -4.3699252199829e-07 2.9209991918445e-06 6.86327121071238e-06 4.24345653924502e-08 4.66553471917702e-05 2.13716752303883e-05 2.19475903477951e-05 4.58093606113138e-06 7.49337314104238e-06 4.67733796607419e-07 2.13716752303883e-05 4.87506650031578e-05 9.62474310156819e-06 1.54367453450223e-05 -2.12705324785042e-05 -4.3699252199829e-07 2.19475903477951e-05 9.62474310156819e-06 0.000214316094576984 1130 1130 0 0 0 1128 1128 0 0 0 0 0 0 0 0 250 267 0 2157 0 0 0 0 0 362 +317 449 0.802319787515252 -0.59515136663039 -0.0455829941914605 -0.145661887435475 0.589846374574063 0.802231742828581 -0.0922251874492582 0.164841734571011 0.0914560712217304 0.0471071289317797 0.994694277373953 -0.0135136865975261 4.95129311088936e-05 -3.99307853211996e-05 -2.9773453032102e-06 -1.75084605579823e-05 -4.35338849027699e-06 2.2466866139244e-05 -3.99307853211996e-05 6.75070643356749e-05 3.98679529353224e-06 2.60091841613041e-05 1.32082937300574e-05 -4.05551973498261e-05 -2.9773453032102e-06 3.98679529353224e-06 1.18981269829525e-05 -1.80466373799937e-06 2.15918468551518e-06 -2.11051608418606e-06 -1.75084605579823e-05 2.60091841613041e-05 -1.80466373799937e-06 0.000105410086825001 2.76102061524208e-05 3.90120903451416e-06 -4.35338849027699e-06 1.32082937300574e-05 2.15918468551518e-06 2.76102061524208e-05 2.92994122554035e-05 -7.35180068398783e-06 2.2466866139244e-05 -4.05551973498261e-05 -2.11051608418606e-06 3.90120903451416e-06 -7.35180068398783e-06 0.000213041440001247 1849 1966 0 0 383 1849 1966 0 0 383 0 0 0 0 0 1181 1194 0 2308 0 0 0 0 0 1854 +317 445 0.938435698165255 -0.345261875347531 -0.0115185867447956 -0.171521621919807 0.342874148711709 0.934976987185939 -0.0908589653139752 -0.225179698734909 0.0421397502877281 0.0813158709245092 0.995797153330675 -0.0170752756924633 4.52661787394002e-05 -3.07350196132427e-05 -5.18939787706933e-06 -1.21053200460036e-06 1.23032268838993e-06 2.85534402995356e-05 -3.07350196132427e-05 5.11582229743294e-05 7.75067252502945e-06 1.02819134088973e-05 3.49624377326346e-06 -1.43150606256559e-05 -5.18939787706933e-06 7.75067252502945e-06 1.42999152246054e-05 1.68327066730235e-06 1.4753114704298e-06 -6.78908710452854e-06 -1.21053200460036e-06 1.02819134088973e-05 1.68327066730235e-06 4.69848936271835e-05 1.04313021747597e-05 -7.85786701468456e-06 1.23032268838993e-06 3.49624377326346e-06 1.4753114704298e-06 1.04313021747597e-05 3.37172392833668e-05 -9.34092584678916e-06 2.85534402995356e-05 -1.43150606256559e-05 -6.78908710452854e-06 -7.85786701468456e-06 -9.34092584678916e-06 0.000170882210537783 1527 1527 0 0 0 1526 1526 0 0 0 0 0 0 0 0 440 465 0 2147 0 0 0 0 0 269 +317 444 0.961136167317942 -0.276074271757819 -0.000514146640108749 -0.174085955621573 0.274947346804067 0.957377660041548 -0.0884984324085731 -0.32806307972091 0.0249243727861309 0.0849176808842558 0.99607618338883 0.0353110024273834 3.73920630518256e-05 -2.46871401424053e-05 -5.79138968527973e-06 -8.97409422689659e-06 -8.18357686901477e-07 -2.35063165745968e-05 -2.46871401424053e-05 3.32493034606792e-05 5.32437405242767e-06 5.72174758037597e-06 1.32743415372801e-06 8.511443851415e-06 -5.79138968527973e-06 5.32437405242767e-06 1.73673231493182e-05 5.69221249589417e-06 -6.03806854753275e-06 -7.28571563991144e-07 -8.97409422689659e-06 5.72174758037597e-06 5.69221249589417e-06 5.46383206911664e-05 1.15163310325783e-05 6.8674485062028e-05 -8.18357686901477e-07 1.32743415372801e-06 -6.03806854753275e-06 1.15163310325783e-05 5.3843760184398e-05 4.9484764608096e-05 -2.35063165745968e-05 8.511443851415e-06 -7.28571563991144e-07 6.8674485062028e-05 4.9484764608096e-05 0.000479784968354734 1309 1309 0 0 0 1308 1308 0 0 0 0 0 0 0 0 394 403 0 1911 0 0 0 0 0 296 +317 454 0.58828470772959 -0.808596416103837 0.00964046241322302 0.0175656196492777 0.800522978297124 0.580641863962668 -0.148384591626828 0.665809958624943 0.114385592929409 0.095009797799958 0.988882740496667 0.0489459833248329 4.11367447559214e-05 -1.21199124601488e-05 -3.92929524190216e-06 -3.16219013056079e-06 4.37947778604611e-06 -1.95974387662642e-07 -1.21199124601488e-05 4.60559540908058e-05 2.09811247117899e-06 -1.72532487746485e-05 1.28292995002793e-06 -1.58446692347231e-05 -3.92929524190216e-06 2.09811247117899e-06 1.50413217248584e-05 2.46558134359245e-06 -1.46629186371407e-06 -3.13099141812001e-06 -3.16219013056079e-06 -1.72532487746485e-05 2.46558134359245e-06 0.000166419854808879 -6.50846654103526e-07 3.23325000045162e-05 4.37947778604611e-06 1.28292995002793e-06 -1.46629186371407e-06 -6.50846654103526e-07 2.3106665305836e-05 5.11836919276258e-06 -1.95974387662642e-07 -1.58446692347231e-05 -3.13099141812001e-06 3.23325000045162e-05 5.11836919276258e-06 0.000181730157442479 899 963 0 0 2530 899 963 0 0 2530 0 0 0 0 0 2124 2091 0 2674 0 0 0 0 0 574 +317 438 0.920407262871395 0.39093868500217 0.00417313100207638 -0.151018871651412 -0.390425430773804 0.919652647214976 -0.0425087223470225 -0.846858307140933 -0.0204561349887017 0.0374960403144219 0.999087380313686 0.308353128031502 4.49208750653231e-05 -3.95743958980202e-05 -7.19100890908195e-06 -1.02007434367985e-06 1.0495222044833e-05 4.17795599022925e-05 -3.95743958980202e-05 5.20277713750665e-05 5.97180719861998e-06 1.37498092814056e-06 7.99912383776411e-07 -4.24759716538605e-05 -7.19100890908195e-06 5.97180719861998e-06 1.33721142035219e-05 1.42932671838082e-06 3.3658302656204e-06 -7.43796470140901e-06 -1.02007434367985e-06 1.37498092814056e-06 1.42932671838082e-06 2.43007297240481e-05 1.23709708912317e-05 1.66015308817615e-06 1.0495222044833e-05 7.99912383776411e-07 3.3658302656204e-06 1.23709708912317e-05 9.67583332955391e-05 1.37231816757383e-05 4.17795599022925e-05 -4.24759716538605e-05 -7.43796470140901e-06 1.66015308817615e-06 1.37231816757383e-05 0.000144053383604093 0 0 0 341 0 0 0 0 343 0 0 0 0 0 0 0 0 0 1216 0 0 0 0 0 802 +317 451 0.709963098542047 -0.703785738302558 -0.02525932046788 -0.101370360822962 0.694824193364213 0.705866423096127 -0.137738640407295 0.363117106917096 0.11476819692034 0.0802385649635089 0.99014647081543 -0.0101226730330902 0.000203505313339404 -0.000138429306623872 -8.05025840942701e-06 -3.42394836459317e-05 1.42454046415345e-06 0.000103539061750245 -0.000138429306623872 0.00012284499670909 6.88397402783839e-06 2.27550353384442e-05 3.59141506423648e-06 -8.05061186763783e-05 -8.05025840942701e-06 6.88397402783839e-06 1.88741150200059e-05 8.20961821780452e-06 -7.10300239940246e-06 -5.53471265084613e-06 -3.42394836459317e-05 2.27550353384442e-05 8.20961821780452e-06 0.000269872141879092 3.45767756289418e-05 0.000107704451445422 1.42454046415345e-06 3.59141506423648e-06 -7.10300239940246e-06 3.45767756289418e-05 3.8486522669626e-05 2.84336778112728e-05 0.000103539061750245 -8.05061186763783e-05 -5.53471265084613e-06 0.000107704451445422 2.84336778112728e-05 0.000387156101038562 1444 1533 0 0 1295 1445 1534 0 0 1295 0 0 0 0 0 1614 1603 0 2326 0 0 0 0 0 1454 +317 437 0.888552935371824 0.458774056188965 -0.000215429892962591 -0.156385324456189 -0.457812318007488 0.886659656438912 -0.0651347459060165 -0.929573535670844 -0.0296911185832599 0.0579742961281542 0.997876454510136 0.385701956011183 4.01443125748792e-05 -2.50849876716562e-05 -3.48097255668191e-06 5.985587883512e-06 7.35971352392404e-06 5.03982698662521e-05 -2.50849876716562e-05 5.33202347871582e-05 4.82564634551135e-06 -6.751173831107e-08 1.74182610212222e-06 -5.40705998251517e-06 -3.48097255668191e-06 4.82564634551135e-06 1.25669642763046e-05 -2.58909480715688e-06 -1.07757884809102e-06 -5.01779100126034e-06 5.985587883512e-06 -6.751173831107e-08 -2.58909480715688e-06 2.37333681053207e-05 3.98199194190332e-06 1.68886856176182e-05 7.35971352392404e-06 1.74182610212222e-06 -1.07757884809102e-06 3.98199194190332e-06 0.0001398515874861 -4.2884281285897e-06 5.03982698662521e-05 -5.40705998251517e-06 -5.01779100126034e-06 1.68886856176182e-05 -4.2884281285897e-06 0.000261074650682747 0 0 0 199 0 0 0 0 199 0 0 0 0 0 0 0 0 0 1022 0 0 0 0 7 844 +317 439 0.953157092477122 0.301151045342336 -0.0282772868178053 -0.141138752640373 -0.30142898690799 0.953469487325988 -0.00604173732799579 -0.760196298042399 0.025142054653133 0.0142823187030607 0.999581858809114 0.224281478053412 6.14267903070756e-05 -5.8485712189349e-05 -1.18749858040816e-05 3.55800744812651e-06 -1.69297373710424e-06 8.01233458555025e-05 -5.8485712189349e-05 7.92755689150031e-05 1.28105652740324e-05 -2.40286871920356e-06 3.77375417480941e-06 -7.82124346407287e-05 -1.18749858040816e-05 1.28105652740324e-05 1.54381934245574e-05 1.63995705949918e-06 3.17063908995475e-06 -9.99271337552458e-06 3.55800744812651e-06 -2.40286871920356e-06 1.63995705949918e-06 3.22904711114639e-05 2.2706208346785e-05 1.35664838132731e-05 -1.69297373710424e-06 3.77375417480941e-06 3.17063908995475e-06 2.2706208346785e-05 0.000163419470279517 -7.24237688766464e-05 8.01233458555025e-05 -7.82124346407287e-05 -9.99271337552458e-06 1.35664838132731e-05 -7.24237688766464e-05 0.000324540454084607 0 0 0 427 0 0 0 0 427 0 0 0 0 0 0 0 0 0 1897 0 0 0 0 0 732 +317 456 0.538165415042597 -0.842830208791816 0.0039019482278291 0.123505158181259 0.835011178336912 0.532531866777858 -0.13844183947959 0.901207140325743 0.114605052700269 0.0777627803903233 0.990362878889114 0.00596405277614778 6.05209661155732e-05 -4.80666660380039e-05 2.68422952250201e-06 -1.00760927513523e-05 8.48370046386865e-07 1.25409344980475e-05 -4.80666660380039e-05 5.04783735628643e-05 -6.85961517140153e-07 -1.49742591189345e-05 3.10238607906633e-07 -4.30841876392803e-05 2.68422952250201e-06 -6.85961517140153e-07 1.2706790232191e-05 6.13609552047025e-06 2.63926682662213e-06 4.917155057412e-06 -1.00760927513523e-05 -1.49742591189345e-05 6.13609552047025e-06 0.000493199889485301 4.30061267106295e-06 9.00750523066285e-05 8.48370046386865e-07 3.10238607906633e-07 2.63926682662213e-06 4.30061267106295e-06 1.83129062902911e-05 3.99140178534874e-06 1.25409344980475e-05 -4.30841876392803e-05 4.917155057412e-06 9.00750523066285e-05 3.99140178534874e-06 0.000265113782978288 595 648 0 0 3227 595 648 0 0 3227 0 0 0 0 0 2623 2577 0 3101 0 0 0 0 0 41 +318 446 0.85980381120334 -0.510589573208826 -0.00597444312393707 -0.174488511074727 0.508086594794016 0.856636901048802 -0.0895613306741661 -0.0717218627232415 0.0508470100481188 0.0739696389874589 0.99596338992818 -0.010257515449802 4.05498789994316e-05 -3.34731474241572e-05 -2.45610508361431e-06 -2.97118208794465e-06 9.73796924279357e-07 -2.76261409090697e-06 -3.34731474241572e-05 5.33795185681413e-05 6.4602416373351e-06 1.36619090321748e-05 2.96711175967306e-06 6.59742113118951e-05 -2.45610508361431e-06 6.4602416373351e-06 1.37311235824963e-05 -2.78140673612273e-06 1.2926629302177e-07 -3.64529860636842e-06 -2.97118208794465e-06 1.36619090321748e-05 -2.78140673612273e-06 4.5647215886088e-05 8.57001331176553e-06 6.96910763540151e-05 9.73796924279357e-07 2.96711175967306e-06 1.2926629302177e-07 8.57001331176553e-06 3.12445711699765e-05 3.38500558650645e-05 -2.76261409090697e-06 6.59742113118951e-05 -3.64529860636842e-06 6.96910763540151e-05 3.38500558650645e-05 0.000404222833680798 1437 1437 0 0 0 1391 1391 0 0 0 0 0 0 0 0 910 947 0 2011 0 0 0 0 0 579 +318 447 0.816711173600573 -0.576091074219375 -0.0331953780026933 -0.179720417534373 0.572615151121305 0.81621270995501 -0.0768680740894717 0.0206200550613012 0.0713775008129374 0.0437708386104871 0.996488517778822 -0.0125915754469625 1.87344932267086e-05 -1.25383732647666e-05 1.86084550231749e-06 2.93492482563259e-06 -7.26968644652e-08 1.59550409545698e-06 -1.25383732647666e-05 4.45527913581274e-05 4.79036401972386e-06 9.12445598472513e-06 -1.07470218274945e-06 4.31935083287777e-06 1.86084550231749e-06 4.79036401972386e-06 1.20218961148964e-05 4.67533410801613e-06 2.51538400434023e-06 -1.37935925626474e-06 2.93492482563259e-06 9.12445598472513e-06 4.67533410801613e-06 5.66399709963819e-05 -6.26596795165518e-07 8.91644846958058e-06 -7.26968644652e-08 -1.07470218274945e-06 2.51538400434023e-06 -6.26596795165518e-07 1.90289083639671e-05 1.42801395138467e-07 1.59550409545698e-06 4.31935083287777e-06 -1.37935925626474e-06 8.91644846958058e-06 1.42801395138467e-07 0.000120250881158945 1614 1614 0 0 0 1565 1565 0 0 0 0 0 0 0 0 1213 1247 0 2091 0 0 0 0 0 1071 +318 449 0.731209396342174 -0.680864066572269 -0.0419158866253216 -0.180859356433604 0.675670630374262 0.731343157168989 -0.0927706080164551 0.228429453109178 0.0938190702925657 0.0395134067471814 0.994804841532585 -0.034841185822106 0.000144855692795959 -9.3110805327645e-05 -2.28525499993921e-07 2.88205617525186e-06 -1.14110012238746e-05 0.000165258223744602 -9.3110805327645e-05 9.0679002623847e-05 4.07149479909803e-06 2.60122350904605e-06 1.13286021905983e-05 -0.000132669095888 -2.28525499993921e-07 4.07149479909803e-06 1.36423767477624e-05 3.17254096920891e-07 1.55641024993653e-06 -9.36635567284082e-06 2.88205617525186e-06 2.60122350904605e-06 3.17254096920891e-07 6.27500429393049e-05 2.75190538745012e-06 2.58058661469929e-07 -1.14110012238746e-05 1.13286021905983e-05 1.55641024993653e-06 2.75190538745012e-06 2.82853979274264e-05 -6.21710634008092e-05 0.000165258223744602 -0.000132669095888 -9.36635567284082e-06 2.58058661469929e-07 -6.21710634008092e-05 0.0010329270570082 1412 1529 0 0 378 1346 1463 0 0 378 0 0 0 0 0 1622 1636 0 2071 0 0 0 0 0 1232 +318 444 0.925027566995338 -0.379796882668878 0.00885032280135661 -0.153075771339135 0.379153182503934 0.921498571419156 -0.0841620286684747 -0.259901749186512 0.0238089163093269 0.0812078246689125 0.99641277827852 0.0396231982358854 0.000106415992575083 -0.000102365978694476 -3.97160972307412e-06 -1.9961246048719e-05 -1.05018351618179e-06 -7.56032749572002e-06 -0.000102365978694476 0.000121199279288773 1.8757767959451e-06 2.2150701829866e-05 9.42602689317166e-06 2.53411457920044e-05 -3.97160972307412e-06 1.8757767959451e-06 1.87170531234284e-05 5.65580472810379e-06 -7.44134936661228e-06 9.52717268841154e-06 -1.9961246048719e-05 2.2150701829866e-05 5.65580472810379e-06 7.07377778244217e-05 2.09652175647384e-05 4.22049083199892e-05 -1.05018351618179e-06 9.42602689317166e-06 -7.44134936661228e-06 2.09652175647384e-05 6.67669695447378e-05 1.28058073267242e-05 -7.56032749572002e-06 2.53411457920044e-05 9.52717268841154e-06 4.22049083199892e-05 1.28058073267242e-05 0.000310333645640984 1082 1082 0 0 0 1052 1052 0 0 0 0 0 0 0 0 600 616 0 1759 0 0 0 0 0 233 +318 445 0.894345403076215 -0.44713132759471 -0.0148282122939432 -0.163557910443173 0.444441651909549 0.891779656486597 -0.0848567164375204 -0.165159018365186 0.0511655943418394 0.0693009390992526 0.996282822192377 -0.00639210615919291 8.4862119854794e-05 -6.33226381233774e-05 -4.95554089536523e-06 -5.53043669680007e-06 2.15291354122938e-06 1.83518765052042e-05 -6.33226381233774e-05 9.88706610093117e-05 5.03084501670024e-07 2.44976185488114e-05 2.63279160636021e-05 -2.92155300497215e-05 -4.95554089536523e-06 5.03084501670024e-07 1.60332817354532e-05 -2.27695451456246e-06 -5.22615070604807e-06 -1.5237811576196e-05 -5.53043669680007e-06 2.44976185488114e-05 -2.27695451456246e-06 6.35368624873324e-05 2.40254658421738e-05 4.7905217322062e-05 2.15291354122938e-06 2.63279160636021e-05 -5.22615070604807e-06 2.40254658421738e-05 5.25782808144713e-05 2.58311166979407e-05 1.83518765052042e-05 -2.92155300497215e-05 -1.5237811576196e-05 4.7905217322062e-05 2.58311166979407e-05 0.000634375814591158 1245 1245 0 0 0 1208 1208 0 0 0 0 0 0 0 0 677 677 0 1870 0 0 0 0 0 243 +318 442 0.983091245922242 -0.179991273271172 -0.0336859575680424 -0.133971934699145 0.178275162304774 0.982786824789565 -0.0484564085055032 -0.467171623251599 0.041827845943346 0.0416317014577578 0.998257097514198 0.0574598680983198 2.55485108827008e-05 -2.1753858512458e-05 -2.46347087728218e-06 -4.73978956677923e-08 -7.55813701216811e-07 2.32091620694409e-05 -2.1753858512458e-05 3.4036946525506e-05 2.14031835562982e-06 -6.64741993100432e-06 -5.1796564112673e-06 -2.40885311764283e-05 -2.46347087728218e-06 2.14031835562982e-06 1.14588192272343e-05 9.59659051881084e-07 1.92202684923441e-06 -2.63611216865617e-06 -4.73978956677923e-08 -6.64741993100432e-06 9.59659051881084e-07 4.99244166213424e-05 3.73288117400759e-05 -1.78980798392268e-05 -7.55813701216811e-07 -5.1796564112673e-06 1.92202684923441e-06 3.73288117400759e-05 8.41107579870091e-05 -3.15460540156755e-05 2.32091620694409e-05 -2.40885311764283e-05 -2.63611216865617e-06 -1.78980798392268e-05 -3.15460540156755e-05 0.000116688489874723 698 698 0 0 0 678 678 0 0 0 0 0 0 0 0 130 137 0 2049 0 0 0 0 0 449 +318 450 0.6811293209488 -0.731148977661232 -0.0385229880559937 -0.178755984338826 0.722314335667554 0.679637250551723 -0.127887482388365 0.316341852063149 0.119686459689335 0.0592822075114445 0.991040247033189 0.0115617828137447 6.34105569199442e-05 -2.31737754188375e-05 -2.13200286405777e-07 -5.5730229172154e-06 -4.00800282811854e-06 2.11744901390062e-05 -2.31737754188375e-05 5.87120716708957e-05 4.8168037571989e-06 1.40230255459366e-05 1.24604610698875e-07 -4.98210287052442e-05 -2.13200286405777e-07 4.8168037571989e-06 1.33500694280208e-05 1.89177349165233e-06 8.16091091613708e-07 3.44554679016745e-07 -5.5730229172154e-06 1.40230255459366e-05 1.89177349165233e-06 7.57262234699679e-05 2.32008336273992e-06 7.46256170070493e-06 -4.00800282811854e-06 1.24604610698875e-07 8.16091091613708e-07 2.32008336273992e-06 2.41274937783411e-05 1.41543024879348e-06 2.11744901390062e-05 -4.98210287052442e-05 3.44554679016745e-07 7.46256170070493e-06 1.41543024879348e-06 0.000191620030952961 1144 1243 0 0 790 1081 1180 0 0 790 0 0 0 0 0 1679 1679 0 1971 0 0 0 0 0 1148 +318 441 0.997827709522087 -0.0583891707944858 -0.0305051937190737 -0.122540204616882 0.0575940256502409 0.997992933396817 -0.026325521826086 -0.557745091796502 0.0319810931536938 0.0245114182361752 0.999187870251008 0.0983076183216728 2.74275164506277e-05 -1.95346753740766e-05 -3.99557610970931e-06 -1.75757041682302e-06 -2.80348851477772e-06 1.03360429662214e-05 -1.95346753740766e-05 3.9750832892276e-05 5.02974804044097e-06 -5.64265816311591e-06 -1.77123212236555e-05 -8.86037384706375e-06 -3.99557610970931e-06 5.02974804044097e-06 1.29136421094757e-05 3.31165782999038e-06 -1.0339427254914e-06 -1.32253945710347e-06 -1.75757041682302e-06 -5.64265816311591e-06 3.31165782999038e-06 4.7341493430956e-05 3.50801014179095e-05 6.88240430521653e-07 -2.80348851477772e-06 -1.77123212236555e-05 -1.0339427254914e-06 3.50801014179095e-05 0.00010879693714423 -3.26168999936508e-05 1.03360429662214e-05 -8.86037384706375e-06 -1.32253945710347e-06 6.88240430521653e-07 -3.26168999936508e-05 0.000131293392027653 407 366 0 130 0 407 366 0 122 0 0 0 0 0 0 0 0 0 1889 0 0 0 0 0 650 +318 437 0.934222280497641 0.356661179870608 -0.0046404089360033 -0.0720422378176863 -0.356254360017247 0.932354950362149 -0.0616204308967103 -0.857790516529925 -0.0176511073445686 0.0592203453932862 0.998088868338391 0.37674513257405 3.7421264988411e-05 -3.63735645364762e-05 -6.43605421240068e-06 7.70971266724821e-07 9.76338232919119e-06 4.24001635842698e-05 -3.63735645364762e-05 9.04701521790181e-05 9.78817736380474e-06 2.44569602461015e-07 -1.30203682517607e-05 -7.18931776345008e-05 -6.43605421240068e-06 9.78817736380474e-06 1.22821220395512e-05 -5.96439616978834e-07 -2.64117270333837e-06 -5.38339481715156e-06 7.70971266724821e-07 2.44569602461015e-07 -5.96439616978834e-07 2.42903980464473e-05 -3.11290673306501e-06 1.46348353862276e-05 9.76338232919119e-06 -1.30203682517607e-05 -2.64117270333837e-06 -3.11290673306501e-06 0.000139433631003592 -7.4546012215585e-06 4.24001635842698e-05 -7.18931776345008e-05 -5.38339481715156e-06 1.46348353862276e-05 -7.4546012215585e-06 0.000257586914661158 0 0 0 144 0 0 0 0 139 0 0 0 0 0 0 0 0 0 1017 0 0 0 0 0 1285 +318 443 0.956830308686074 -0.290623838049633 0.00368037185803418 -0.147844979200109 0.290082852771601 0.954107396152396 -0.0743707949075792 -0.364124660455135 0.0181024558445012 0.0722278434164866 0.997223866405032 0.024704593902706 3.71437884564739e-05 -2.55393146860282e-05 -3.38225285611593e-06 -1.12287693329532e-06 2.71125780338299e-06 1.22161289773633e-05 -2.55393146860282e-05 7.07440491305815e-05 1.25593217264949e-05 6.53770302075564e-06 -1.74940286072646e-05 -1.91935682280258e-05 -3.38225285611593e-06 1.25593217264949e-05 1.57339630389127e-05 3.45617565716567e-06 -1.19302799475081e-06 -4.30086671480656e-06 -1.12287693329532e-06 6.53770302075564e-06 3.45617565716567e-06 4.646283106295e-05 9.39642444535112e-06 2.04056983282276e-06 2.71125780338299e-06 -1.74940286072646e-05 -1.19302799475081e-06 9.39642444535112e-06 4.87662205019028e-05 6.32982089801875e-06 1.22161289773633e-05 -1.91935682280258e-05 -4.30086671480656e-06 2.04056983282276e-06 6.32982089801875e-06 0.000116699790749939 925 925 0 0 0 900 900 0 0 0 0 0 0 0 0 436 445 0 1960 0 0 0 0 0 345 +318 454 0.495190762406465 -0.868702948800126 0.0118867814511967 -0.0692326369257322 0.859046493869368 0.487551803038159 -0.155988335220892 0.752679486166426 0.12971210505596 0.087455280573591 0.987687371439843 0.0349474656461377 4.77243980223736e-05 -3.35111434202077e-05 5.33460489882912e-06 8.98620940272852e-06 1.62151566076015e-06 9.76040455461801e-06 -3.35111434202077e-05 6.07194081145323e-05 -1.38060258940495e-06 2.39108166342369e-05 1.44359181260514e-06 -1.74649633042665e-05 5.33460489882912e-06 -1.38060258940495e-06 1.40244662436914e-05 -2.71450328812986e-06 1.77936020157425e-06 2.07267661413893e-06 8.98620940272852e-06 2.39108166342369e-05 -2.71450328812986e-06 0.000223828509784777 6.08284657196071e-06 6.04939984651194e-05 1.62151566076015e-06 1.44359181260514e-06 1.77936020157425e-06 6.08284657196071e-06 2.05972672135479e-05 8.77959973309721e-06 9.76040455461801e-06 -1.74649633042665e-05 2.07267661413893e-06 6.04939984651194e-05 8.77959973309721e-06 0.000205830104295228 113 168 0 0 2545 35 75 0 0 2522 0 0 0 0 0 2867 2834 0 2389 0 0 0 0 0 199 +318 440 0.996117900987434 0.0777978502631924 -0.0411900695169924 -0.0862178171683408 -0.0779123805599736 0.996959511825027 -0.00118014282268301 -0.593793077430154 0.0409730190230914 0.00438477776289607 0.999150632005056 0.159499911113378 3.59777393497812e-05 -1.26917933305176e-05 -2.02366597057869e-06 -9.20310723665722e-06 -1.73267796098179e-05 -2.17161020934733e-05 -1.26917933305176e-05 5.14985422524374e-05 2.19161232764689e-06 -3.74044742909636e-06 7.05122629180437e-06 -4.04116173320004e-05 -2.02366597057869e-06 2.19161232764689e-06 1.26618818974704e-05 1.88074241517491e-06 1.84112226316427e-06 -4.62355349608202e-06 -9.20310723665722e-06 -3.74044742909636e-06 1.88074241517491e-06 7.56347079297564e-05 0.000104048950162242 5.87056982820811e-05 -1.73267796098179e-05 7.05122629180437e-06 1.84112226316427e-06 0.000104048950162242 0.000276896386734471 7.35243100584459e-05 -2.17161020934733e-05 -4.04116173320004e-05 -4.62355349608202e-06 5.87056982820811e-05 7.35243100584459e-05 0.000306770458906955 28 0 0 286 0 28 0 0 286 0 0 0 0 0 0 0 0 0 1844 0 0 0 0 0 885 +318 439 0.980008990216617 0.196021137301805 -0.0340307629287677 -0.0797382121960037 -0.196306648074666 0.98052861132175 -0.00522898662558548 -0.683539248933837 0.032343144811481 0.0118049189047662 0.999407106675431 0.211007098039131 3.36745500184721e-05 -2.5040037389434e-05 -5.05509923659682e-06 2.34002120146401e-06 4.69127452463996e-06 1.24309995931527e-05 -2.5040037389434e-05 4.61196430114933e-05 4.85253368536784e-06 4.13653580292713e-07 6.06715527980685e-06 -3.65634235659405e-06 -5.05509923659682e-06 4.85253368536784e-06 1.22890752261402e-05 9.80186063985068e-07 -6.31194503897022e-07 -3.07597270069573e-06 2.34002120146401e-06 4.13653580292713e-07 9.80186063985068e-07 3.3338887525593e-05 3.02204362233464e-05 5.25260161335304e-06 4.69127452463996e-06 6.06715527980685e-06 -6.31194503897022e-07 3.02204362233464e-05 0.00019358976761717 -5.05770845864451e-06 1.24309995931527e-05 -3.65634235659405e-06 -3.07597270069573e-06 5.25260161335304e-06 -5.05770845864451e-06 0.000105010412900375 0 0 0 320 0 0 0 0 307 0 0 0 0 0 0 0 0 0 2086 0 0 0 0 0 1015 +318 453 0.536649766295173 -0.843793475019765 0.00442717171634109 -0.101022422777721 0.835636213226257 0.53071885361899 -0.141596672129771 0.641257980402769 0.117128764529543 0.0796873260149616 0.989914532973614 0.0497729026974531 5.64766287351027e-05 -4.32907139036187e-05 2.18195154184613e-06 9.59738553217833e-06 4.28517386191509e-06 -1.79933606102501e-05 -4.32907139036187e-05 5.52641411988793e-05 2.65123712242684e-06 1.39588439527658e-05 5.13935120457816e-07 2.42029394086556e-05 2.18195154184613e-06 2.65123712242684e-06 1.37271557765762e-05 1.00746329478251e-05 -1.11582787035609e-06 8.88854811882203e-07 9.59738553217833e-06 1.39588439527658e-05 1.00746329478251e-05 0.000142841970010318 -4.21357402713295e-06 4.92394015885688e-05 4.28517386191509e-06 5.13935120457816e-07 -1.11582787035609e-06 -4.21357402713295e-06 2.15238730684841e-05 9.95588170019621e-06 -1.79933606102501e-05 2.42029394086556e-05 8.88854811882203e-07 4.92394015885688e-05 9.95588170019621e-06 0.000363892199214912 334 402 0 0 2158 233 301 0 0 2158 0 0 0 0 0 2713 2686 0 2246 0 0 0 0 0 436 +318 438 0.957604477885012 0.288086121417097 0.000224903150783724 -0.0875461356828456 -0.287911684448286 0.95705123236663 -0.0340558450734195 -0.782771509800133 -0.0100262601564037 0.0325472774954848 0.999419906163024 0.265925022584375 0.000113236272265556 -6.95938299696403e-05 -9.76828088544577e-06 2.18433975065571e-05 6.86475864757032e-05 0.00015373495864195 -6.95938299696403e-05 9.20019871279384e-05 1.14881668558252e-05 -6.92883557843386e-06 -1.14621405550438e-05 -0.000108212519901241 -9.76828088544577e-06 1.14881668558252e-05 1.35507386852593e-05 -1.58192420324108e-06 -3.09548383615448e-06 -8.70032996938013e-06 2.18433975065571e-05 -6.92883557843386e-06 -1.58192420324108e-06 2.77787237012131e-05 2.6408618210038e-05 5.02175994153186e-05 6.86475864757032e-05 -1.14621405550438e-05 -3.09548383615448e-06 2.6408618210038e-05 0.000210882195273408 6.57987203400752e-05 0.00015373495864195 -0.000108212519901241 -8.70032996938013e-06 5.02175994153186e-05 6.57987203400752e-05 0.000512897776199214 0 0 0 267 0 0 0 0 257 0 0 0 0 0 0 0 0 0 1443 0 0 0 0 0 1095 +319 445 0.834443213718388 -0.5508141202331 0.0175592719429092 -0.169010704600235 0.549812064651149 0.82990760589024 -0.0946575894979966 -0.0987592403386743 0.0375661635434095 0.0886406827442461 0.995355018432752 0.0100706192487813 2.93265476651059e-05 -2.19637564767097e-05 -2.40709608902092e-06 -2.05750301729346e-07 -1.88790984659655e-06 1.22531407440961e-06 -2.19637564767097e-05 7.81863802038144e-05 4.62286519757271e-06 5.8624548003481e-05 4.18360419746899e-05 7.4400495710307e-05 -2.40709608902092e-06 4.62286519757271e-06 1.57034209322572e-05 -3.28297327402909e-06 -4.28773652639026e-06 -1.42650292697291e-05 -2.05750301729346e-07 5.8624548003481e-05 -3.28297327402909e-06 0.000116595611088042 5.87022324717025e-05 0.00011149365588015 -1.88790984659655e-06 4.18360419746899e-05 -4.28773652639026e-06 5.87022324717025e-05 7.56892904038591e-05 9.14878608024224e-05 1.22531407440961e-06 7.4400495710307e-05 -1.42650292697291e-05 0.00011149365588015 9.14878608024224e-05 0.000261186429895482 928 928 0 0 0 837 837 0 0 0 0 0 0 0 0 746 776 0 1747 0 0 0 0 0 384 +319 444 0.872682425939977 -0.4868070211483 0.0380040473664978 -0.152115413547104 0.488157092270447 0.867997931695701 -0.0910068340183731 -0.180386319607875 0.0113153312624364 0.0979720099452086 0.995124840683679 -0.0107742292334562 2.89430361375543e-05 -2.13058574125798e-05 -2.3632421859723e-06 -4.0086342363135e-06 -2.86278248486996e-06 6.41938675291256e-07 -2.13058574125798e-05 5.94456420118673e-05 8.05421783349779e-06 2.15932612249834e-05 1.06560523369824e-05 1.32888602750346e-05 -2.3632421859723e-06 8.05421783349779e-06 1.61625201937948e-05 3.65225715277029e-06 -2.38260135193634e-06 -9.8746859890314e-07 -4.0086342363135e-06 2.15932612249834e-05 3.65225715277029e-06 6.97486816834533e-05 1.78237165580956e-05 3.29578226909307e-05 -2.86278248486996e-06 1.06560523369824e-05 -2.38260135193634e-06 1.78237165580956e-05 5.41774079072448e-05 2.11700767714966e-05 6.41938675291256e-07 1.32888602750346e-05 -9.8746859890314e-07 3.29578226909307e-05 2.11700767714966e-05 0.000151848305051199 814 814 0 0 0 736 736 0 0 0 0 0 0 0 0 624 640 0 1704 0 0 0 0 0 193 +319 448 0.695988965086038 -0.717576732900412 -0.0261341324408541 -0.225750087026118 0.713969210971313 0.695448576555693 -0.0812357258332881 0.191748403560106 0.0764678119437543 0.0378802028325069 0.996352228867835 -0.00900647311362775 3.38429626386861e-05 -9.52033992730726e-06 3.16715369359348e-06 2.90556589501692e-06 -5.64732785505222e-06 5.34790067902912e-06 -9.52033992730726e-06 6.19231163027043e-05 1.40510992712769e-05 2.35962308710018e-05 -3.29583649621239e-06 -5.75972347159709e-07 3.16715369359348e-06 1.40510992712769e-05 1.92099315104885e-05 9.20815942642861e-06 -5.34598880811867e-06 -1.54417241950926e-06 2.90556589501692e-06 2.35962308710018e-05 9.20815942642861e-06 0.000102809019220246 9.10118533004807e-06 1.38971999477845e-05 -5.64732785505222e-06 -3.29583649621239e-06 -5.34598880811867e-06 9.10118533004807e-06 4.19106872092461e-05 3.58198694198416e-06 5.34790067902912e-06 -5.75972347159709e-07 -1.54417241950926e-06 1.38971999477845e-05 3.58198694198416e-06 0.000123027155110514 1113 1246 0 0 7 979 1112 0 0 7 0 0 0 0 0 1341 1366 0 1770 0 0 0 0 0 1195 +319 449 0.646187067620173 -0.762927439337191 -0.0195958145234918 -0.235895766251815 0.757742141884773 0.644431505855465 -0.102639566799232 0.300176757554078 0.0909347021346546 0.051475786222793 0.994525577036824 -0.0274803119047844 5.14192900921289e-05 -2.4681155489919e-05 -2.09437144420033e-06 -1.15073863052716e-06 3.35137728665127e-06 2.34508531285663e-05 -2.4681155489919e-05 7.22377657019071e-05 5.38298559428307e-06 4.19059328946801e-06 2.23082625754848e-06 -2.85089139214578e-05 -2.09437144420033e-06 5.38298559428307e-06 1.38103878582902e-05 1.34593613547471e-06 -5.49586911960596e-07 -3.90978570497627e-07 -1.15073863052716e-06 4.19059328946801e-06 1.34593613547471e-06 6.57004163736702e-05 8.76322299490605e-06 -2.19283414485966e-05 3.35137728665127e-06 2.23082625754848e-06 -5.49586911960596e-07 8.76322299490605e-06 2.88406046513779e-05 -1.3368380394538e-05 2.34508531285663e-05 -2.85089139214578e-05 -3.90978570497627e-07 -2.19283414485966e-05 -1.3368380394538e-05 0.000133542279553105 773 890 0 0 438 624 741 0 0 438 0 0 0 0 0 1604 1618 0 1745 0 0 0 0 0 1042 +319 442 0.954343329511625 -0.297756712344968 -0.0238694296157538 -0.101276159384065 0.296475450896496 0.953929120998058 -0.0460601685579901 -0.376883800899421 0.0364844683719632 0.0368805147115262 0.998653449001318 0.068293118189951 2.01900161479766e-05 -1.25617941149468e-05 -1.88727669065608e-06 -5.85513998531961e-07 -2.20583566565782e-06 -2.95253271574689e-07 -1.25617941149468e-05 3.13119736816484e-05 5.69841297534658e-06 -8.96475480604232e-06 -1.8845917013881e-05 7.05808988478639e-06 -1.88727669065608e-06 5.69841297534658e-06 1.33493242765011e-05 -1.9324695640616e-06 -1.23288405708618e-07 -1.0418033027903e-06 -5.85513998531961e-07 -8.96475480604232e-06 -1.9324695640616e-06 4.27984945965775e-05 2.93680242351284e-05 -1.09502409119625e-05 -2.20583566565782e-06 -1.8845917013881e-05 -1.23288405708618e-07 2.93680242351284e-05 9.1625007787038e-05 -3.50489467571345e-05 -2.95253271574689e-07 7.05808988478639e-06 -1.0418033027903e-06 -1.09502409119625e-05 -3.50489467571345e-05 0.000146659569629472 546 546 0 0 0 492 492 0 0 0 0 0 0 0 0 292 293 0 1851 0 0 0 0 0 376 +319 437 0.970413498813097 0.241081671628089 0.0133142377299583 0.00190009469517912 -0.239914284904498 0.968985551707138 -0.059229523732477 -0.78500801984052 -0.0271804565834848 0.0542828535342349 0.998155596383697 0.349266128084175 7.14272916678922e-05 -7.46125131925478e-05 -1.08128254369309e-05 3.83617541659792e-06 -1.02171828832825e-05 7.18646351042886e-05 -7.46125131925478e-05 0.000128177089223392 1.58710692191252e-05 2.27380263149045e-06 2.15932081760928e-05 -6.1802604782269e-05 -1.08128254369309e-05 1.58710692191252e-05 1.37297561648077e-05 3.54709544842317e-07 2.94494055213643e-06 -1.57250221190201e-05 3.83617541659792e-06 2.27380263149045e-06 3.54709544842317e-07 2.7026735697167e-05 5.71997230509556e-06 5.36753689909863e-06 -1.02171828832825e-05 2.15932081760928e-05 2.94494055213643e-06 5.71997230509556e-06 0.000152320060066918 -5.65440993750851e-05 7.18646351042886e-05 -6.1802604782269e-05 -1.57250221190201e-05 5.36753689909863e-06 -5.65440993750851e-05 0.000308617757388659 0 0 0 103 0 0 0 0 90 0 0 0 0 0 0 0 0 0 1070 0 0 0 0 0 1016 +319 450 0.58916436359265 -0.807954680480924 0.00972558283274928 -0.243512527402127 0.802969264260039 0.584101351675738 -0.118600049006175 0.380794218156975 0.0901427386213632 0.0776842664864932 0.992894476474865 0.00840332113404872 3.16555135520065e-05 -9.54108994104486e-06 -4.7888892280504e-07 -6.81931904301435e-06 -2.18397867371337e-06 -4.23483774286272e-05 -9.54108994104486e-06 6.12078755714444e-05 5.3801111000571e-06 1.49000296907666e-05 3.90451205736975e-06 1.60800392907479e-05 -4.7888892280504e-07 5.3801111000571e-06 1.42332276329272e-05 5.52377233794726e-06 -4.94232723933775e-07 4.96480953952955e-06 -6.81931904301435e-06 1.49000296907666e-05 5.52377233794726e-06 0.000137125836421984 1.5554258453281e-05 8.52386190596707e-05 -2.18397867371337e-06 3.90451205736975e-06 -4.94232723933775e-07 1.5554258453281e-05 3.02705870850441e-05 8.77718302994176e-06 -4.23483774286272e-05 1.60800392907479e-05 4.96480953952955e-06 8.52386190596707e-05 8.77718302994176e-06 0.000446730271728332 453 552 0 0 857 292 391 0 0 857 0 0 0 0 0 2001 2001 0 1604 0 0 0 0 0 910 +319 441 0.983826758605131 -0.177320632111174 -0.0253436871866718 -0.0796040612870073 0.176600805545453 0.983875989301509 -0.028287685601228 -0.449535954038101 0.0299510355951066 0.0233544664608389 0.999278491894582 0.0756466880422169 2.25733027957513e-05 -1.6255906060982e-05 -4.12243007898434e-06 4.41568606475052e-06 5.47144314123908e-06 -8.90337570790518e-07 -1.6255906060982e-05 3.45174548320395e-05 7.83339521883203e-06 -8.20270017929628e-07 -7.57880427024266e-06 1.10597732276557e-05 -4.12243007898434e-06 7.83339521883203e-06 1.34836828763549e-05 1.25974914046457e-06 6.84536072769845e-07 -3.25809680559923e-06 4.41568606475052e-06 -8.20270017929628e-07 1.25974914046457e-06 3.20797805383484e-05 7.4787394336886e-06 2.59696938182555e-06 5.47144314123908e-06 -7.57880427024266e-06 6.84536072769845e-07 7.4787394336886e-06 5.6827631676293e-05 -1.49751056044937e-05 -8.90337570790518e-07 1.10597732276557e-05 -3.25809680559923e-06 2.59696938182555e-06 -1.49751056044937e-05 0.000175063201978698 452 428 0 0 0 411 408 0 0 0 0 0 0 0 0 10 1 0 1993 0 0 0 0 0 788 +320 445 0.761574322455868 -0.647359460105971 0.0305005047038862 -0.195880509521725 0.647540196224433 0.758183470179703 -0.0764821536038739 -0.030576735938877 0.026386467166121 0.0779971471117346 0.996604334424109 -0.0368554921127926 3.82360334669956e-05 -2.62284543640209e-05 4.52004646073254e-06 9.14496499475904e-06 -4.29426202631966e-06 -6.32215473883803e-06 -2.62284543640209e-05 9.8089543165245e-05 -6.45125755231119e-06 2.14874475006574e-05 3.63131761255765e-05 7.54256979901888e-05 4.52004646073254e-06 -6.45125755231119e-06 1.25290326622376e-05 1.98247127955413e-07 -2.49572241300811e-06 -1.39228752702778e-05 9.14496499475904e-06 2.14874475006574e-05 1.98247127955413e-07 6.04869832803588e-05 1.35272515551668e-05 2.81116905274901e-05 -4.29426202631966e-06 3.63131761255765e-05 -2.49572241300811e-06 1.35272515551668e-05 4.41010044523894e-05 4.04200939191311e-05 -6.32215473883803e-06 7.54256979901888e-05 -1.39228752702778e-05 2.81116905274901e-05 4.04200939191311e-05 0.00025456735252453 542 542 0 0 0 139 139 0 0 0 0 0 0 0 0 1476 1502 0 1690 0 0 0 0 0 373 +319 438 0.985485958468465 0.168750253321028 0.018460164289087 -0.0160935816028083 -0.16798254397202 0.985083770931744 -0.0373072267474308 -0.712767688470776 -0.0244804122142473 0.0336647627495699 0.999133321017188 0.274776673714039 3.22870283885469e-05 -3.28818752387131e-05 -5.73704868909955e-06 2.31322126582004e-06 9.48258722366784e-06 4.89210510081605e-05 -3.28818752387131e-05 7.11851003636214e-05 9.65253752226953e-06 5.85151213204613e-06 -6.28893869451277e-07 -4.79315224413796e-05 -5.73704868909955e-06 9.65253752226953e-06 1.38123858468419e-05 1.96674568435109e-06 1.71858647948374e-06 -1.03835372313795e-05 2.31322126582004e-06 5.85151213204613e-06 1.96674568435109e-06 3.2251914156444e-05 1.73445213189801e-05 1.35958982160636e-05 9.48258722366784e-06 -6.28893869451277e-07 1.71858647948374e-06 1.73445213189801e-05 0.000120675480903652 3.19707410476702e-05 4.89210510081605e-05 -4.79315224413796e-05 -1.03835372313795e-05 1.35958982160636e-05 3.19707410476702e-05 0.0002331988150505 0 0 0 189 0 0 0 0 170 0 0 0 0 0 0 0 0 0 1291 0 0 0 0 0 1233 +320 446 0.711957847583794 -0.701873234125349 0.022135638284761 -0.231266649457306 0.700967652778491 0.708449316244428 -0.0821213496663027 0.0426748331899196 0.0419567994735536 0.0739833057603196 0.996376483788488 -0.0357755367763976 2.61022850791902e-05 -1.8337395524961e-05 2.99673534667142e-06 -8.43538532785698e-06 -7.77620268278767e-06 -2.53094881666344e-05 -1.8337395524961e-05 4.85776723067925e-05 -1.15875749922436e-07 6.18788233459851e-06 1.40391770805889e-05 3.26765257431431e-05 2.99673534667142e-06 -1.15875749922436e-07 1.11129223926183e-05 -2.29609579314519e-06 -6.60071626512528e-07 -4.5966233108121e-06 -8.43538532785698e-06 6.18788233459851e-06 -2.29609579314519e-06 5.06498415147516e-05 1.08405350257254e-05 6.62111789207837e-05 -7.77620268278767e-06 1.40391770805889e-05 -6.60071626512528e-07 1.08405350257254e-05 3.72077028739636e-05 5.20249538869017e-05 -2.53094881666344e-05 3.26765257431431e-05 -4.5966233108121e-06 6.62111789207837e-05 5.20249538869017e-05 0.000283248707912869 587 587 0 0 0 147 147 0 0 0 0 0 0 0 0 1840 1876 0 1621 0 0 0 0 0 581 +320 448 0.604660242286091 -0.796403444722027 -0.0112935660185089 -0.28585825022171 0.793752089075347 0.603699350955062 -0.0741937648657818 0.239733272742458 0.0659060883913467 0.0358977282195591 0.997179893811356 -0.0120596647341768 2.98328856248731e-05 -3.50102691776441e-06 4.81731010215978e-06 1.04568660132016e-06 -4.85432672120116e-06 -4.80071064910282e-07 -3.50102691776441e-06 5.05686214653816e-05 4.05498586942312e-06 1.93800227834101e-05 5.69557251759907e-06 -1.47958533369864e-05 4.81731010215978e-06 4.05498586942312e-06 1.51898474662669e-05 8.11395197017767e-06 -5.43158486103246e-06 -2.56078703783434e-06 1.04568660132016e-06 1.93800227834101e-05 8.11395197017767e-06 0.000100014950503547 3.31840482207108e-06 5.96035303081892e-06 -4.85432672120116e-06 5.69557251759907e-06 -5.43158486103246e-06 3.31840482207108e-06 3.96890288096423e-05 1.41658752684128e-05 -4.80071064910282e-07 -1.47958533369864e-05 -2.56078703783434e-06 5.96035303081892e-06 1.41658752684128e-05 9.59279552466263e-05 475 609 0 0 39 102 152 0 0 32 0 0 0 0 0 2431 2459 0 1533 0 0 0 0 0 776 +320 443 0.85928304418201 -0.510894308430861 0.0248928824014084 -0.136108192879932 0.511446809669187 0.857470568558537 -0.0562706400808649 -0.234868470951378 0.00740343572327893 0.0610837921944264 0.998105184572568 0.0358101485014375 3.60996835448291e-05 -1.0598291107918e-05 -1.67398241326548e-06 8.16604252421417e-07 1.11856900756653e-06 -3.08453391839579e-05 -1.0598291107918e-05 5.11907256717238e-05 8.45182365031305e-06 1.39931489892869e-05 7.85838039810263e-06 -1.7290603606614e-05 -1.67398241326548e-06 8.45182365031305e-06 1.24309363933157e-05 3.6868598627668e-07 1.93632708298834e-06 5.63614651623889e-06 8.16604252421417e-07 1.39931489892869e-05 3.6868598627668e-07 6.56967746115546e-05 3.16022430064401e-05 -2.23372259345191e-05 1.11856900756653e-06 7.85838039810263e-06 1.93632708298834e-06 3.16022430064401e-05 6.68356267629858e-05 -4.27437241761212e-05 -3.08453391839579e-05 -1.7290603606614e-05 5.63614651623889e-06 -2.23372259345191e-05 -4.27437241761212e-05 0.000321102768954732 409 409 0 0 0 160 160 0 0 0 0 0 0 0 0 993 993 0 1713 0 0 0 0 0 264 +320 447 0.656562162394293 -0.754267166008764 -0.0026775349181386 -0.260390678181091 0.752385136778106 0.655166598395747 -0.0683617897800897 0.129235813301384 0.0533172848851178 0.0428692270475479 0.997657003435963 -0.0241961494277762 4.93486567572995e-05 -2.77123658011356e-06 -3.6578113915888e-06 -1.25302941801551e-05 3.14499050343491e-06 -3.30269753069595e-05 -2.77123658011356e-06 5.07899394318168e-05 1.03583062570702e-05 -2.25730782018773e-06 -8.14391760558589e-06 -4.42990797409575e-05 -3.6578113915888e-06 1.03583062570702e-05 2.04298721221637e-05 9.62135651921697e-06 -8.18853181667192e-06 1.31011901367318e-05 -1.25302941801551e-05 -2.25730782018773e-06 9.62135651921697e-06 5.22622174384674e-05 -1.98834935526078e-05 5.60650153417929e-05 3.14499050343491e-06 -8.14391760558589e-06 -8.18853181667192e-06 -1.98834935526078e-05 3.8352574322086e-05 -5.64185439660829e-06 -3.30269753069595e-05 -4.42990797409575e-05 1.31011901367318e-05 5.60650153417929e-05 -5.64185439660829e-06 0.000291067421153285 652 652 0 0 0 184 184 0 0 0 0 0 0 0 0 2013 2048 0 1565 0 0 0 0 0 816 +320 442 0.912136618836044 -0.409673023930674 -0.0132212723233254 -0.0965009430747925 0.408893683060418 0.911697679739364 -0.0401658649993542 -0.31389066664528 0.0285086746734547 0.0312306615581066 0.999105550603642 0.0639596899295719 2.33808349418675e-05 -1.32371199670349e-05 -1.3986752607413e-06 -1.24438100480242e-06 -7.57651759336626e-07 2.44486594321559e-07 -1.32371199670349e-05 4.51810848506983e-05 5.69305529514028e-06 -8.81202576348905e-06 -2.14795296124276e-05 1.33545041221873e-05 -1.3986752607413e-06 5.69305529514028e-06 1.29173102918787e-05 -5.76316008030789e-07 -4.06828528206419e-06 3.78974557527407e-06 -1.24438100480242e-06 -8.81202576348905e-06 -5.76316008030789e-07 7.69462800306319e-05 8.04031401440426e-05 -1.41621015623809e-05 -7.57651759336626e-07 -2.14795296124276e-05 -4.06828528206419e-06 8.04031401440426e-05 0.000175750581283711 -4.79753513402283e-05 2.44486594321559e-07 1.33545041221873e-05 3.78974557527407e-06 -1.41621015623809e-05 -4.79753513402283e-05 0.000176871108888673 354 354 0 0 0 165 165 0 0 0 0 0 0 0 0 613 620 0 1834 0 0 0 0 0 352 +320 436 0.98773335163743 0.156146669061198 -0.00102166735340885 0.0934128534363041 -0.155617901601298 0.98380671211422 -0.0889236858222665 -0.746199154780517 -0.0128800141419598 0.0879918799668532 0.996037918101315 0.443153417032292 5.1771412825088e-05 -3.41951308098402e-05 -3.37455197060693e-06 1.15981306717644e-06 2.61709222313749e-05 6.16151418678737e-05 -3.41951308098402e-05 8.12348160056033e-05 1.05872614741187e-05 1.86757025269985e-06 -1.0917764438906e-05 -5.27489787967384e-05 -3.37455197060693e-06 1.05872614741187e-05 1.34825397862254e-05 3.18619102230701e-06 1.99967452865304e-06 -5.24330084387059e-06 1.15981306717644e-06 1.86757025269985e-06 3.18619102230701e-06 3.28134596419351e-05 2.07893947587902e-05 2.4605176125088e-05 2.61709222313749e-05 -1.0917764438906e-05 1.99967452865304e-06 2.07893947587902e-05 0.000148462484280745 3.0722807511522e-05 6.16151418678737e-05 -5.27489787967384e-05 -5.24330084387059e-06 2.4605176125088e-05 3.0722807511522e-05 0.00027940215838288 0 0 0 30 0 0 0 0 21 0 0 0 0 0 0 0 0 0 965 0 0 0 0 0 1096 +320 449 0.549955966494674 -0.835181285380976 -0.00454482852145456 -0.309069983452148 0.831158603223994 0.547825134071001 -0.0951997834389819 0.346815861167871 0.081998848794655 0.0485782155854842 0.995447811674164 -0.0382996583013018 4.24788496126266e-05 -1.92751074601075e-05 4.70451858257824e-07 -5.9016838572945e-06 -1.77445516489441e-06 2.12457167894493e-05 -1.92751074601075e-05 6.62692787807019e-05 2.0276762031105e-06 2.08233197891426e-05 1.35827833917102e-05 -1.78017050339348e-05 4.70451858257824e-07 2.0276762031105e-06 1.50969668423789e-05 6.57904153824669e-06 -1.73740431622436e-06 2.15474497251581e-06 -5.9016838572945e-06 2.08233197891426e-05 6.57904153824669e-06 0.00010104421113657 4.7757575062213e-06 2.4440002819712e-05 -1.77445516489441e-06 1.35827833917102e-05 -1.73740431622436e-06 4.7757575062213e-06 3.01335947084665e-05 1.96195501039263e-06 2.12457167894493e-05 -1.78017050339348e-05 2.15474497251581e-06 2.4440002819712e-05 1.96195501039263e-06 0.000105946958171772 69 180 0 0 507 0 11 0 0 169 0 0 0 0 0 2806 2820 0 1448 0 0 0 0 0 640 +320 451 0.426808284582286 -0.903719248550329 0.0335590228039409 -0.329598407713464 0.899289077032296 0.420213774782246 -0.121241657088876 0.560565723997165 0.0954664555869083 0.0819262063254788 0.992055569297803 0.00968423745240655 0.000174850422110577 -4.39688109256016e-05 -4.02018801067739e-06 -0.00040422808412947 -0.000107571880739681 -0.000309866670220593 -4.39688109256016e-05 5.41155708729324e-05 7.11467335134354e-06 0.000166322584129857 4.23813294302533e-05 8.07209350239822e-05 -4.02018801067739e-06 7.11467335134354e-06 1.42149775768745e-05 1.49263652297379e-05 -6.71823480310923e-07 7.19129631382862e-06 -0.00040422808412947 0.000166322584129857 1.49263652297379e-05 0.00245722477664102 0.000599597643067011 0.00162552488123621 -0.000107571880739681 4.23813294302533e-05 -6.71823480310923e-07 0.000599597643067011 0.000191947735225685 0.000431288355964967 -0.000309866670220593 8.07209350239822e-05 7.19129631382862e-06 0.00162552488123621 0.000431288355964967 0.00149154758722153 0 0 0 0 756 0 0 0 0 190 0 0 0 0 0 3163 3241 0 1349 577 0 0 0 0 395 +320 450 0.488351283890921 -0.872428994306322 0.0195108537934039 -0.326429144633178 0.868730893071697 0.483922317819317 -0.105479029855379 0.426145198810209 0.082581226346797 0.0684605010939782 0.994230104575908 0.00182431920366505 4.87593685522368e-05 -2.74578431200562e-05 -6.30662090287799e-06 1.84847096544468e-06 7.94568548109939e-06 -1.80110272036276e-05 -2.74578431200562e-05 5.378706913136e-05 1.30206506774552e-05 -2.63414427347484e-06 -6.37895840194992e-06 -5.51109129605284e-06 -6.30662090287799e-06 1.30206506774552e-05 1.72251258541002e-05 8.24142379980938e-06 -3.87654298077672e-06 -1.46081651870693e-08 1.84847096544468e-06 -2.63414427347484e-06 8.24142379980938e-06 8.7559151175141e-05 -9.79522420704133e-06 2.86378885244782e-05 7.94568548109939e-06 -6.37895840194992e-06 -3.87654298077672e-06 -9.79522420704133e-06 3.53394359223405e-05 8.40335961208649e-06 -1.80110272036276e-05 -5.51109129605284e-06 -1.46081651870693e-08 2.86378885244782e-05 8.40335961208649e-06 0.000250350020494577 0 0 0 0 770 0 0 0 0 222 0 0 0 0 0 3130 3229 0 1335 49 0 0 0 0 504 +320 438 0.998433421909726 0.0500229406891591 0.0250680557372116 0.0343468682907419 -0.0492643373012569 0.998334610470252 -0.0300171718767319 -0.615259778548346 -0.0265278548681017 0.0287351864796132 0.999234988365639 0.276337270700951 3.60481463258639e-05 -2.14222863169043e-05 -4.26623443287715e-06 2.41992502913401e-06 5.81171688600645e-06 4.28136545529666e-05 -2.14222863169043e-05 4.57956009643749e-05 3.30604427460781e-06 4.49470824964261e-06 1.80033100184662e-05 -1.17331612273484e-05 -4.26623443287715e-06 3.30604427460781e-06 1.23808841617025e-05 1.15550494515759e-07 -2.3644525738852e-06 -9.0207075416451e-06 2.41992502913401e-06 4.49470824964261e-06 1.15550494515759e-07 2.78156898329462e-05 1.26733383502957e-05 1.06906233972789e-05 5.81171688600645e-06 1.80033100184662e-05 -2.3644525738852e-06 1.26733383502957e-05 0.000148591757443054 3.65451034007813e-05 4.28136545529666e-05 -1.17331612273484e-05 -9.0207075416451e-06 1.06906233972789e-05 3.65451034007813e-05 0.000208064012414973 0 0 0 131 0 0 0 0 74 0 0 0 0 0 0 0 0 0 1584 0 0 0 0 0 1126 +321 443 0.798915711673967 -0.60035450479487 0.0361684145766116 -0.153068329915463 0.601421026847118 0.796926616184063 -0.0565748785555741 -0.171642857296201 0.00514141095778016 0.0669510043981927 0.99774301746664 0.000217665884715674 2.20108292815311e-05 -4.93310090856556e-06 -5.00569485399243e-07 3.68837797672707e-07 -7.81300386028319e-07 8.09077483453647e-06 -4.93310090856556e-06 4.27167197899608e-05 6.62233947464167e-06 -2.30425464569965e-06 -4.88085322164932e-06 -2.2655336617612e-05 -5.00569485399243e-07 6.62233947464167e-06 1.30255003932763e-05 -1.57350054131458e-06 3.46396174974635e-07 -2.89771886817047e-06 3.68837797672707e-07 -2.30425464569965e-06 -1.57350054131458e-06 2.7437135116121e-05 -5.12256693336084e-06 9.45504060392174e-07 -7.81300386028319e-07 -4.88085322164932e-06 3.46396174974635e-07 -5.12256693336084e-06 3.46335805250324e-05 4.9326122992622e-06 8.09077483453647e-06 -2.2655336617612e-05 -2.89771886817047e-06 9.45504060392174e-07 4.9326122992622e-06 8.29141257689188e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1509 1537 0 1512 0 0 0 0 0 407 +321 444 0.737757543109457 -0.673752888685812 0.0420814991726928 -0.193240089083888 0.674959411727016 0.735100142261008 -0.0636990845221971 -0.0806545340689034 0.011983326175069 0.0753977840216094 0.997081528290647 -0.00322726846997643 1.87255365889755e-05 -9.23625921375891e-06 3.29182897668408e-07 -2.22380301933373e-06 -2.37739527117096e-06 -9.59560759060664e-06 -9.23625921375891e-06 4.45180631778247e-05 5.28624329965212e-06 -2.32987291971856e-06 2.42075130680322e-07 1.05351710785165e-05 3.29182897668408e-07 5.28624329965212e-06 1.25199920985905e-05 -2.06046008124483e-06 -4.87321044603005e-06 -2.7972244409597e-06 -2.22380301933373e-06 -2.32987291971856e-06 -2.06046008124483e-06 4.14510989274244e-05 7.99089192759098e-06 1.12005754437865e-05 -2.37739527117096e-06 2.42075130680322e-07 -4.87321044603005e-06 7.99089192759098e-06 6.47075510764882e-05 2.08721211843127e-05 -9.59560759060664e-06 1.05351710785165e-05 -2.7972244409597e-06 1.12005754437865e-05 2.08721211843127e-05 9.76841508127573e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1870 1877 0 1431 0 0 0 0 0 328 +321 446 0.632694426511208 -0.773531871579474 0.0366906842728415 -0.278978597941235 0.77367288510391 0.629334362699907 -0.0732702311999545 0.0908298170460947 0.0335861506672894 0.0747442544672047 0.996636978496933 -0.0247230918592584 2.59105276531814e-05 -2.1283563443925e-05 2.4301699389784e-06 -1.06582530731652e-06 -5.6771387417757e-06 -9.93073804827492e-06 -2.1283563443925e-05 8.71181565751718e-05 -4.68636341245697e-06 -1.24977265817454e-06 2.74901862691204e-05 6.14104325009934e-05 2.4301699389784e-06 -4.68636341245697e-06 1.64952176232399e-05 5.37445449177079e-07 -5.56878043517431e-06 -1.0640038584834e-05 -1.06582530731652e-06 -1.24977265817454e-06 5.37445449177079e-07 3.94094849431951e-05 -9.16023970875464e-06 2.51287542388832e-05 -5.6771387417757e-06 2.74901862691204e-05 -5.56878043517431e-06 -9.16023970875464e-06 4.43075570359609e-05 3.99694021730026e-05 -9.93073804827492e-06 6.14104325009934e-05 -1.0640038584834e-05 2.51287542388832e-05 3.99694021730026e-05 0.000203462525299277 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2567 2599 0 1280 0 0 0 0 0 361 +321 442 0.862014569296288 -0.506835891244951 -0.00694706174377022 -0.10335359859237 0.506146495537821 0.861419168459407 -0.0421039340856187 -0.254706074917157 0.0273241171077579 0.0327779736505998 0.999089083649522 0.0282657908215709 1.64496575323599e-05 -6.68171619172431e-06 -1.39470723870854e-06 2.63913209368533e-06 6.03634167162313e-06 5.29263568726752e-06 -6.68171619172431e-06 5.20689972085103e-05 6.38877388422129e-06 -5.09729322531161e-06 -2.04305793420936e-05 -2.14031402009688e-06 -1.39470723870854e-06 6.38877388422129e-06 1.12403933848361e-05 -7.84495462278518e-07 1.4515463977274e-07 2.64945543904263e-06 2.63913209368533e-06 -5.09729322531161e-06 -7.84495462278518e-07 3.78460707539426e-05 2.29948183843166e-05 -1.35321303793216e-05 6.03634167162313e-06 -2.04305793420936e-05 1.4515463977274e-07 2.29948183843166e-05 7.72095294718922e-05 -2.79561228250059e-05 5.29263568726752e-06 -2.14031402009688e-06 2.64945543904263e-06 -1.35321303793216e-05 -2.79561228250059e-05 8.98201406250714e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1037 1044 0 1660 0 0 0 0 0 540 +321 447 0.570969537814206 -0.82084146804058 0.0145969597251425 -0.314698041593412 0.819817245318235 0.569134420219783 -0.0631323688761338 0.182856870647703 0.0435140341390246 0.0480134987902096 0.99789840803905 -0.0380053895147207 5.77251692375315e-05 -9.34650482147703e-06 4.65788611493871e-06 3.55741691981867e-06 -1.61213420592027e-05 1.38417357382907e-06 -9.34650482147703e-06 7.27465033818499e-05 2.20609276345602e-06 9.0078984793529e-06 8.02005203516765e-06 7.74781339644187e-06 4.65788611493871e-06 2.20609276345602e-06 1.75971871422518e-05 1.21816251754391e-05 -1.0330278799456e-05 -6.27334242651783e-06 3.55741691981867e-06 9.0078984793529e-06 1.21816251754391e-05 8.58029137650911e-05 -1.60604113395456e-05 4.23599840796918e-05 -1.61213420592027e-05 8.02005203516765e-06 -1.0330278799456e-05 -1.60604113395456e-05 5.69082772680456e-05 3.88039218992485e-05 1.38417357382907e-06 7.74781339644187e-06 -6.27334242651783e-06 4.23599840796918e-05 3.88039218992485e-05 0.000188383076822137 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2868 2905 0 1282 0 0 0 0 0 304 +321 441 0.917907681326209 -0.396418854085905 -0.0172505271676197 -0.0660626653946765 0.396125386916119 0.918017319689811 -0.018135010065904 -0.32127780734598 0.0230253426228165 0.00981289329164103 0.999686721289399 0.0719759908356929 2.38521915211674e-05 -7.15948920712194e-06 -2.25467585300448e-06 1.98993071039891e-06 3.35759272724199e-06 3.29088595527086e-06 -7.15948920712194e-06 7.77574252264928e-05 5.25149508031578e-06 1.70948902341375e-06 -2.67282094000725e-05 -2.17125035213312e-06 -2.25467585300448e-06 5.25149508031578e-06 1.1344555402334e-05 1.01361522002461e-06 -2.05645087205094e-06 -1.65321616167169e-06 1.98993071039891e-06 1.70948902341375e-06 1.01361522002461e-06 3.18470969914721e-05 6.4820807723442e-06 -2.1314478806453e-06 3.35759272724199e-06 -2.67282094000725e-05 -2.05645087205094e-06 6.4820807723442e-06 8.4541629870316e-05 -7.36528737678956e-06 3.29088595527086e-06 -2.17125035213312e-06 -1.65321616167169e-06 -2.1314478806453e-06 -7.36528737678956e-06 9.89029328012084e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 594 553 0 1763 0 0 0 0 0 598 +321 438 0.997942831512927 -0.0590123286970457 0.0250529458091126 0.0574472585587776 0.0595316382980618 0.9980156021638 -0.0205144309981349 -0.548956317319848 -0.0237926264525638 0.0219636722653644 0.99947561652454 0.27125889855557 4.11356699732725e-05 -1.38630206967237e-05 -4.4003388915837e-06 1.80838029847617e-06 3.00130315009249e-07 4.17612686637939e-05 -1.38630206967237e-05 6.04582019737556e-05 6.55752972194305e-06 1.22122258837991e-05 1.86081953958102e-05 -7.08868727406688e-06 -4.4003388915837e-06 6.55752972194305e-06 1.18958560694977e-05 -6.98622180447134e-07 4.14123337450158e-06 -3.16865511938475e-06 1.80838029847617e-06 1.22122258837991e-05 -6.98622180447134e-07 3.18528587100309e-05 2.47332642714069e-05 1.30135233661139e-05 3.00130315009249e-07 1.86081953958102e-05 4.14123337450158e-06 2.47332642714069e-05 0.00016229090422982 5.99527404027124e-06 4.17612686637939e-05 -7.08868727406688e-06 -3.16865511938475e-06 1.30135233661139e-05 5.99527404027124e-06 0.000173314575646857 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1532 0 0 0 0 0 841 +321 436 0.998797705499224 0.0480022719982406 0.00994612349071073 0.134717549729933 -0.0469799004616054 0.995233068075143 -0.0854636130897567 -0.667024034699065 -0.0140011585986012 0.08489359276615 0.996291646790814 0.451279503508406 5.25903738055618e-05 -3.12524989969219e-05 -1.0736143502516e-05 -2.23645115789626e-07 6.44461417136369e-07 2.93097405798398e-05 -3.12524989969219e-05 7.39160152754376e-05 1.05657749790406e-05 -1.99012297120063e-06 -4.99294423177483e-06 -2.28228448209113e-05 -1.0736143502516e-05 1.05657749790406e-05 1.40075923188851e-05 9.37500855532302e-07 2.58006775424104e-06 -3.08164511398727e-06 -2.23645115789626e-07 -1.99012297120063e-06 9.37500855532302e-07 2.78120056525382e-05 5.82970175539649e-06 1.34818905779107e-05 6.44461417136369e-07 -4.99294423177483e-06 2.58006775424104e-06 5.82970175539649e-06 0.000118265757301637 -3.80601679647635e-06 2.93097405798398e-05 -2.28228448209113e-05 -3.08164511398727e-06 1.34818905779107e-05 -3.80601679647635e-06 0.000158666539436902 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 942 0 0 0 0 0 1044 +321 448 0.515024517424207 -0.85714367128182 -0.00738059845043595 -0.353264394245919 0.854724918166493 0.51418371751814 -0.071136621402109 0.280674530327613 0.0647692883799423 0.0303287227022411 0.997439275275446 -0.0279348900704137 2.99932702066839e-05 -6.17872432892578e-07 6.16879334994211e-07 -2.85152489846584e-06 6.34253611639288e-07 7.786894651463e-06 -6.17872432892578e-07 4.15025933668092e-05 6.46669003198492e-06 1.08553837386677e-07 -1.74968133447806e-06 -1.70594073257847e-05 6.16879334994211e-07 6.46669003198492e-06 1.1518414174424e-05 5.23163373615284e-07 2.64125309888609e-07 1.54935341152878e-06 -2.85152489846584e-06 1.08553837386677e-07 5.23163373615284e-07 5.84843782787394e-05 -1.51478149866539e-06 2.02104343640833e-05 6.34253611639288e-07 -1.74968133447806e-06 2.64125309888609e-07 -1.51478149866539e-06 3.02951324751696e-05 8.54460356647841e-06 7.786894651463e-06 -1.70594073257847e-05 1.54935341152878e-06 2.02104343640833e-05 8.54460356647841e-06 0.000119647222110388 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3079 3241 0 1176 102 0 0 0 0 204 +321 437 0.999428144358324 0.0151179995528045 0.0302461626326278 0.0942347687861155 -0.0137605490916562 0.998910345692522 -0.0445956114112374 -0.610822535825348 -0.0308874012046026 0.0441539053535174 0.998547145150823 0.361823666360166 2.64656848350649e-05 -1.02065743857221e-05 -3.47521349476974e-06 -6.73065748540863e-07 -2.99599978786562e-07 1.66844823911503e-05 -1.02065743857221e-05 6.16952926645799e-05 4.86873585919812e-06 3.42962664827718e-06 4.13411341672447e-06 5.64745484426651e-06 -3.47521349476974e-06 4.86873585919812e-06 1.06997415177674e-05 -3.18801498946269e-06 1.16864362307543e-07 -2.74506952214353e-06 -6.73065748540863e-07 3.42962664827718e-06 -3.18801498946269e-06 1.95167441466584e-05 6.24787435691063e-07 2.85450522709972e-06 -2.99599978786562e-07 4.13411341672447e-06 1.16864362307543e-07 6.24787435691063e-07 0.000121755312278507 -2.27189367231759e-06 1.66844823911503e-05 5.64745484426651e-06 -2.74506952214353e-06 2.85450522709972e-06 -2.27189367231759e-06 9.15126638251561e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1371 0 0 0 0 0 1014 +321 451 0.326928430526075 -0.94408895834737 0.0425892009825816 -0.434303080656026 0.939636972661582 0.319909836219785 -0.121408633536533 0.574373398314163 0.100995846058814 0.0797103218937626 0.991688511409937 -0.0216443129619042 3.42257436641478e-05 -8.4312571118236e-06 1.1807454057426e-08 -2.18294352920246e-05 -2.84754166860593e-07 -2.35649928788102e-05 -8.4312571118236e-06 5.33292562930857e-05 7.67395447339922e-06 6.28894643753307e-05 1.07922639196804e-05 1.30398514698373e-05 1.1807454057426e-08 7.67395447339922e-06 1.35939687334886e-05 -2.57166045660857e-06 -3.80488933231855e-06 -3.56082421613791e-06 -2.18294352920246e-05 6.28894643753307e-05 -2.57166045660857e-06 0.000354389653908072 7.34330493963797e-05 0.000134540766579507 -2.84754166860593e-07 1.07922639196804e-05 -3.80488933231855e-06 7.34330493963797e-05 6.13617803860242e-05 4.98358010969711e-05 -2.35649928788102e-05 1.30398514698373e-05 -3.56082421613791e-06 0.000134540766579507 4.98358010969711e-05 0.00027738942359996 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3173 3251 0 869 1450 0 0 0 0 125 +321 449 0.455554866570846 -0.890190586152893 0.00552121982790079 -0.384438012352014 0.886974742706726 0.45336359551033 -0.087961673848801 0.370712217533125 0.0757995339296737 0.0449685511298184 0.996108558373699 -0.0286367166287823 4.55232272460793e-05 -4.18432969818378e-06 -9.50487442897284e-07 -1.04273968317204e-05 1.25919586399713e-06 2.2355690288351e-05 -4.18432969818378e-06 4.20893991456196e-05 6.30890667630802e-06 4.59147402374419e-06 4.48067351404824e-07 -8.14091637839194e-06 -9.50487442897284e-07 6.30890667630802e-06 1.31085882995565e-05 2.7783717105933e-06 -8.43399320025157e-07 8.0684991812117e-07 -1.04273968317204e-05 4.59147402374419e-06 2.7783717105933e-06 8.06355408211664e-05 -1.70478510671959e-06 3.97522661082952e-05 1.25919586399713e-06 4.48067351404824e-07 -8.43399320025157e-07 -1.70478510671959e-06 3.22003655928017e-05 1.22414159238124e-05 2.2355690288351e-05 -8.14091637839194e-06 8.0684991812117e-07 3.97522661082952e-05 1.22414159238124e-05 0.00016164177588151 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3023 3154 0 1044 546 0 0 0 0 202 +321 450 0.391251872413529 -0.919803950395503 0.0297096814142257 -0.416991015296765 0.916187480699849 0.386264863779096 -0.106770572811895 0.459731764110585 0.0867321886139852 0.0689938246986133 0.993839715251753 -0.0554871419528595 3.96131053712836e-05 -1.07253375680853e-05 -4.75806126425313e-06 -8.36721388611207e-06 1.02692001709721e-06 3.91970936695442e-06 -1.07253375680853e-05 5.66986961506703e-05 8.97341580915226e-06 2.75467283709951e-05 -4.97475492233642e-06 7.78231673981585e-06 -4.75806126425313e-06 8.97341580915226e-06 1.41341290444064e-05 6.78504512784911e-06 -7.35805744919265e-07 -2.16115245624032e-06 -8.36721388611207e-06 2.75467283709951e-05 6.78504512784911e-06 0.000113446794592492 -1.41032408174711e-05 2.72252526628573e-05 1.02692001709721e-06 -4.97475492233642e-06 -7.35805744919265e-07 -1.41032408174711e-05 3.27640200020279e-05 1.23718055554044e-06 3.91970936695442e-06 7.78231673981585e-06 -2.16115245624032e-06 2.72252526628573e-05 1.23718055554044e-06 0.000142650398669512 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3108 3207 0 921 947 0 0 0 0 137 +322 442 0.808388933923754 -0.588522989642657 0.0121664362771714 -0.120561457315871 0.588634186361424 0.808050971878377 -0.0237365012804083 -0.203996818713032 0.00413837603913791 0.02634990528408 0.999644214876112 0.0397173231165377 4.41433761915303e-05 2.17500271514575e-06 1.58771391882297e-07 2.325471455889e-06 8.5815239756331e-06 -1.59192941107623e-05 2.17500271514575e-06 4.76098279265704e-05 1.25842471838592e-07 -1.43591340690179e-05 -2.41085730944778e-05 1.75845692056551e-05 1.58771391882297e-07 1.25842471838592e-07 1.17047997943585e-05 -1.33814427061853e-06 1.91950772004129e-06 4.40690035326307e-06 2.325471455889e-06 -1.43591340690179e-05 -1.33814427061853e-06 6.11034809192463e-05 6.34432806813262e-05 -2.28624369839162e-05 8.5815239756331e-06 -2.41085730944778e-05 1.91950772004129e-06 6.34432806813262e-05 0.000139254382656491 -6.08972879540008e-05 -1.59192941107623e-05 1.75845692056551e-05 4.40690035326307e-06 -2.28624369839162e-05 -6.08972879540008e-05 0.000236025159446784 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1102 1112 0 1343 0 0 0 0 0 382 +322 443 0.735842082068221 -0.675224805927357 0.0510675211643194 -0.179926256982426 0.677027384845799 0.735063857519328 -0.0362635566052671 -0.139076507468949 -0.0130518361299673 0.0612583613000552 0.998036603910131 -0.0167422246379745 4.34987030785825e-05 1.15131534961731e-05 -9.90896277115473e-07 1.50035649798788e-06 -2.75225918511384e-07 1.54004365892091e-05 1.15131534961731e-05 4.69633105896421e-05 6.14798578993669e-06 6.30591879101224e-06 3.50208442992033e-06 -1.84310992434224e-05 -9.90896277115473e-07 6.14798578993669e-06 1.29978854018935e-05 9.17500988938898e-07 -3.58095317588217e-07 -5.34893725107786e-06 1.50035649798788e-06 6.30591879101224e-06 9.17500988938898e-07 6.97157814896321e-05 3.91822353362838e-05 -3.2592365923764e-06 -2.75225918511384e-07 3.50208442992033e-06 -3.58095317588217e-07 3.91822353362838e-05 7.88747285331577e-05 1.25909988218249e-05 1.54004365892091e-05 -1.84310992434224e-05 -5.34893725107786e-06 -3.2592365923764e-06 1.25909988218249e-05 0.000129249220148905 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1557 1562 0 1203 0 0 0 0 0 367 +322 444 0.667521973196462 -0.740420588515109 0.0786877843304873 -0.226786738138751 0.744226537944989 0.666761955990668 -0.0394379799421114 -0.058743402577477 -0.0232653286741823 0.0848872555006812 0.996118907729014 -0.0162978391323681 5.31569390210583e-05 -3.02611884026073e-06 -1.65965953667901e-06 -4.55700528038593e-07 -9.38869188296494e-07 -1.78853858041709e-05 -3.02611884026073e-06 6.35521592278988e-05 -1.11132380970436e-08 1.45409254184059e-05 2.37165678130623e-05 3.74784341727897e-05 -1.65965953667901e-06 -1.11132380970436e-08 1.71042309180147e-05 5.91891159516639e-06 -7.34043637728797e-06 -9.48272900329891e-06 -4.55700528038593e-07 1.45409254184059e-05 5.91891159516639e-06 0.000104037867414858 3.3789865585664e-05 2.58882188612493e-07 -9.38869188296494e-07 2.37165678130623e-05 -7.34043637728797e-06 3.3789865585664e-05 8.58911614544514e-05 2.75298033219186e-05 -1.78853858041709e-05 3.74784341727897e-05 -9.48272900329891e-06 2.58882188612493e-07 2.75298033219186e-05 0.000265795886656446 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1880 1893 0 1119 0 0 0 0 0 328 +322 447 0.488007891740087 -0.872434542074817 0.0265756917896715 -0.37370413341439 0.872184740665699 0.486237022889648 -0.0535475090113458 0.198302073491355 0.0337946112465179 0.0493105198321463 0.998211599253675 -0.0494719923472726 3.78220749430733e-05 1.37801768404947e-05 1.34497346035468e-06 1.89276239763703e-06 -7.54200925635778e-06 8.30469576346675e-06 1.37801768404947e-05 5.96912869997228e-05 3.97658857155607e-06 1.58133750838113e-05 1.55874701349304e-06 -8.97531050333869e-06 1.34497346035468e-06 3.97658857155607e-06 1.75259554913582e-05 4.23750536446063e-06 -6.33168208786478e-06 2.96028646847358e-06 1.89276239763703e-06 1.58133750838113e-05 4.23750536446063e-06 6.1388935427489e-05 -1.72680461603877e-05 1.23378838995095e-05 -7.54200925635778e-06 1.55874701349304e-06 -6.33168208786478e-06 -1.72680461603877e-05 5.08868965529561e-05 7.93725013596688e-06 8.30469576346675e-06 -8.97531050333869e-06 2.96028646847358e-06 1.23378838995095e-05 7.93725013596688e-06 0.000161295232331067 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3054 3088 0 1003 0 0 0 0 0 147 +322 445 0.612317589519766 -0.788153377619923 0.0623010666923946 -0.275277689330163 0.790610040903666 0.610241380105584 -0.0504105269674365 0.0610934436291072 0.00171253817656838 0.080123101245138 0.996783505009917 -0.043815416644325 6.07545750889719e-05 -1.69066030582926e-05 -1.05603798517093e-06 -9.60673879847149e-06 -7.99580069872058e-06 2.44322311372595e-05 -1.69066030582926e-05 7.07285238517835e-05 -1.30337445515059e-07 2.47344497400833e-05 2.28508720354892e-05 3.28605491992299e-05 -1.05603798517093e-06 -1.30337445515059e-07 1.62199350988106e-05 7.53805842568598e-06 -4.72653114181579e-06 -8.52436113086658e-07 -9.60673879847149e-06 2.47344497400833e-05 7.53805842568598e-06 7.82548725994356e-05 1.25702913948086e-06 6.63297867909782e-05 -7.99580069872058e-06 2.28508720354892e-05 -4.72653114181579e-06 1.25702913948086e-06 4.70429228329365e-05 3.65689649520445e-05 2.44322311372595e-05 3.28605491992299e-05 -8.52436113086658e-07 6.63297867909782e-05 3.65689649520445e-05 0.000307687377861478 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2230 2230 0 1060 0 0 0 0 0 317 +322 441 0.874238872170284 -0.485494167535317 0.00134449827788328 -0.0768832662216235 0.485494743377566 0.874226830718458 -0.00472256336235742 -0.258168778333568 0.00111738049986018 0.00478139531405258 0.999987944787171 0.0512210853691059 3.83711083772342e-05 -1.26057196073034e-06 -2.29238078936803e-06 6.72684807227582e-06 7.22477269872876e-06 3.36883202146965e-05 -1.26057196073034e-06 4.1998063837399e-05 -1.35264827254287e-06 -7.41459870224721e-06 -1.1841851018904e-05 -5.36090724001399e-06 -2.29238078936803e-06 -1.35264827254287e-06 1.18739722078425e-05 -1.58010736248422e-06 2.18369794740188e-06 9.97598685912587e-07 6.72684807227582e-06 -7.41459870224721e-06 -1.58010736248422e-06 3.44377408265982e-05 2.20091913765734e-05 -2.1768082117184e-06 7.22477269872876e-06 -1.1841851018904e-05 2.18369794740188e-06 2.20091913765734e-05 8.48274653607921e-05 -4.65012656964292e-05 3.36883202146965e-05 -5.36090724001399e-06 9.97598685912587e-07 -2.1768082117184e-06 -4.65012656964292e-05 0.000217912886031725 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 638 592 0 1386 0 0 0 0 0 731 +322 436 0.998303922152938 -0.0475175530139337 0.0336357127117775 0.16138418942508 0.0497852220045972 0.996293763096216 -0.0701439183788139 -0.571226594396375 -0.0301779834318697 0.0716995102573841 0.996969643241376 0.418776470801707 8.03754100001271e-05 -1.45534499814842e-05 -1.27125616830872e-05 2.00353028017772e-06 1.57723581175061e-05 0.000121572990570732 -1.45534499814842e-05 5.59143728010291e-05 8.38288518007646e-06 1.94576210444763e-06 -2.20054865444989e-06 -3.3463153156108e-05 -1.27125616830872e-05 8.38288518007646e-06 1.73133065970232e-05 2.1421685118364e-06 -1.30227225666775e-06 -1.25604317379354e-05 2.00353028017772e-06 1.94576210444763e-06 2.1421685118364e-06 4.36991280632961e-05 2.8852060528255e-05 2.45846117299496e-05 1.57723581175061e-05 -2.20054865444989e-06 -1.30227225666775e-06 2.8852060528255e-05 0.000215554279946496 3.3260215225256e-05 0.000121572990570732 -3.3463153156108e-05 -1.25604317379354e-05 2.45846117299496e-05 3.3260215225256e-05 0.00047071416889205 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 932 0 0 0 0 0 1007 +322 449 0.366815321595182 -0.930106031427785 0.0186893056232405 -0.464249845465797 0.927694380315385 0.364215793940098 -0.0820365295209314 0.395916264007175 0.0694957306190642 0.04743021975745 0.996454072037182 -0.0629997674214169 5.882928812821e-05 5.65488175353859e-06 -2.65828047399169e-06 -2.11340189462591e-06 2.9331161837418e-06 2.02791317619663e-05 5.65488175353859e-06 4.22625927894751e-05 3.34544623357129e-06 -3.7258630313999e-06 6.7173239431404e-06 1.01758898129098e-05 -2.65828047399169e-06 3.34544623357129e-06 1.27813589730316e-05 3.22997565823232e-07 1.33596668169369e-06 -8.38433635341802e-07 -2.11340189462591e-06 -3.7258630313999e-06 3.22997565823232e-07 5.06589370795187e-05 -7.6952603443372e-06 1.93665915800391e-05 2.9331161837418e-06 6.7173239431404e-06 1.33596668169369e-06 -7.6952603443372e-06 2.61904961271647e-05 4.41099421107214e-06 2.02791317619663e-05 1.01758898129098e-05 -8.38433635341802e-07 1.93665915800391e-05 4.41099421107214e-06 0.000151876387866516 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3152 3283 0 766 647 0 0 0 0 59 +322 448 0.427784875212442 -0.903870989234356 0.00416357538438976 -0.421930859774868 0.90230515482204 0.426762887738309 -0.060982335399967 0.292983482324106 0.0533433043694311 0.0298441362710632 0.99813016155669 -0.0493553116049399 3.06931799687632e-05 1.14234285964566e-05 4.484353659896e-06 2.90615400300242e-06 -4.214431374127e-06 3.48064773167786e-06 1.14234285964566e-05 3.52796295545666e-05 6.842509043994e-06 4.64029741844095e-06 -4.07827788513915e-06 -1.33888270856848e-05 4.484353659896e-06 6.842509043994e-06 1.4836935339408e-05 8.71172593345426e-06 -2.7951748279886e-06 -5.55518137131294e-06 2.90615400300242e-06 4.64029741844095e-06 8.71172593345426e-06 8.01777308233616e-05 -1.39566880516636e-05 1.31998539396327e-05 -4.214431374127e-06 -4.07827788513915e-06 -2.7951748279886e-06 -1.39566880516636e-05 3.79863024896387e-05 2.7137551334222e-05 3.48064773167786e-06 -1.33888270856848e-05 -5.55518137131294e-06 1.31998539396327e-05 2.7137551334222e-05 0.000155771172600244 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3210 3372 0 902 159 0 0 0 0 123 +322 438 0.986263672808377 -0.156892371472146 0.0516599600500918 0.0756338634259333 0.157166651317647 0.987571285070761 -0.00126515504321721 -0.441812166713834 -0.0508193999583631 0.00936699938787179 0.998663931415539 0.260712820293869 3.16906564339006e-05 -1.44158806813879e-06 -5.68638661740658e-06 3.50680293193432e-06 2.56863210557845e-06 2.89216459832134e-05 -1.44158806813879e-06 4.64246635534134e-05 2.46867304549666e-06 1.15821655690551e-05 1.91902069468384e-05 -1.58995639475593e-05 -5.68638661740658e-06 2.46867304549666e-06 1.20590672377481e-05 1.35732814115581e-06 3.61634445751997e-06 -5.23723115336157e-06 3.50680293193432e-06 1.15821655690551e-05 1.35732814115581e-06 4.04860983015191e-05 2.99349614533993e-05 1.4806342717309e-05 2.56863210557845e-06 1.91902069468384e-05 3.61634445751997e-06 2.99349614533993e-05 0.000129931697243227 4.07776174558496e-05 2.89216459832134e-05 -1.58995639475593e-05 -5.23723115336157e-06 1.4806342717309e-05 4.07776174558496e-05 0.000136425727150514 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1599 0 0 0 0 0 975 +323 442 0.748017300875551 -0.663245178809026 0.0239989661743722 -0.149344399043908 0.66332521386988 0.748310279854913 0.0056022948814522 -0.151540652190945 -0.0216743681645627 0.0117285058743387 0.999696285836165 0.000884389568124021 1.62313878643554e-05 -3.27545281747618e-06 -2.29211806956925e-06 1.47853352723216e-06 5.21387884892307e-06 2.49413425081454e-06 -3.27545281747618e-06 5.65309758049523e-05 6.55311661420693e-06 1.28734659511606e-06 -1.39163505547253e-05 5.82871307652872e-06 -2.29211806956925e-06 6.55311661420693e-06 2.10011917509091e-05 3.86410752355845e-06 -1.16040389805555e-05 -1.6726211995191e-06 1.47853352723216e-06 1.28734659511606e-06 3.86410752355845e-06 4.13800236671045e-05 1.38039598462461e-05 -1.24074713383928e-05 5.21387884892307e-06 -1.39163505547253e-05 -1.16040389805555e-05 1.38039598462461e-05 0.000100805344128934 -2.43635266929547e-05 2.49413425081454e-06 5.82871307652872e-06 -1.6726211995191e-06 -1.24074713383928e-05 -2.43635266929547e-05 7.4900104706216e-05 0 0 0 0 82 0 0 0 0 18 0 0 0 0 0 1232 1242 0 1382 0 0 0 0 0 742 +322 437 0.995267520966171 -0.0838593311414485 0.0490935259516136 0.116481823735109 0.0849662032378947 0.99616445702471 -0.0209073878808893 -0.512037025704852 -0.0471519460594114 0.0249797346097605 0.998575338590753 0.326676035427318 5.08629456699141e-05 -1.63452272926917e-05 -6.09397537173683e-06 -6.2220601165239e-06 5.03243790547964e-06 6.04447791694593e-05 -1.63452272926917e-05 5.26668627223039e-05 7.90957437858732e-06 9.98720874000008e-06 -1.74199763815108e-07 1.44009539617181e-05 -6.09397537173683e-06 7.90957437858732e-06 1.41038815168075e-05 5.39503595249456e-06 3.84371200766159e-06 -2.63976467282793e-06 -6.2220601165239e-06 9.98720874000008e-06 5.39503595249456e-06 4.11833593749731e-05 8.34464237433854e-06 5.8253062254817e-06 5.03243790547964e-06 -1.74199763815108e-07 3.84371200766159e-06 8.34464237433854e-06 0.000103113659361441 -1.24397853772735e-05 6.04447791694593e-05 1.44009539617181e-05 -2.63976467282793e-06 5.8253062254817e-06 -1.24397853772735e-05 0.000335170483401246 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1254 0 0 0 0 0 963 +323 443 0.667247282715034 -0.742007218720809 0.0648563880863886 -0.216158323703738 0.743627432694571 0.668593016503838 -0.00127264542592926 -0.0780236614050479 -0.0424182160573106 0.0490781585688349 0.997893796602628 -0.0353337330924968 1.79407404474653e-05 7.00776054418259e-06 -5.02380014355654e-07 1.67828529384101e-06 -5.94191762668591e-07 -1.52707667247382e-06 7.00776054418259e-06 4.301248724908e-05 2.05436964539042e-06 3.37534982364634e-06 3.0460637420313e-06 -9.62131281115357e-06 -5.02380014355654e-07 2.05436964539042e-06 1.21656040499547e-05 6.24228608502355e-07 1.15908930113428e-07 -1.1507048815526e-06 1.67828529384101e-06 3.37534982364634e-06 6.24228608502355e-07 4.05843856163292e-05 2.96985068075955e-06 -2.0348612360344e-06 -5.94191762668591e-07 3.0460637420313e-06 1.15908930113428e-07 2.96985068075955e-06 4.56421187523502e-05 6.93940231977631e-06 -1.52707667247382e-06 -9.62131281115357e-06 -1.1507048815526e-06 -2.0348612360344e-06 6.93940231977631e-06 8.27243796591711e-05 0 0 0 0 87 0 0 0 0 29 0 0 0 0 0 1705 1709 0 1172 0 0 0 0 0 468 +322 450 0.303110122791343 -0.951476864983559 0.0530662685938522 -0.505394192514595 0.950204439080578 0.297537821340022 -0.092643234096169 0.490429225775963 0.0723586719957016 0.0785049060459976 0.994284266351292 -0.0540265257586949 5.78518119250602e-05 5.81328133148192e-06 3.62602789258081e-07 6.54331882332305e-06 -5.85291428197124e-07 1.1931082206275e-05 5.81328133148192e-06 4.9852872503218e-05 8.93384034685954e-06 1.78114250739055e-05 1.48966815146816e-07 1.36210275769038e-05 3.62602789258081e-07 8.93384034685954e-06 2.08499153541008e-05 1.14966096431247e-05 -1.11183641799817e-05 -6.90179808082162e-06 6.54331882332305e-06 1.78114250739055e-05 1.14966096431247e-05 0.000107981802364714 -2.90019285185376e-05 2.70789885711145e-05 -5.85291428197124e-07 1.48966815146816e-07 -1.11183641799817e-05 -2.90019285185376e-05 5.40545202642057e-05 1.1105083760976e-05 1.1931082206275e-05 1.36210275769038e-05 -6.90179808082162e-06 2.70789885711145e-05 1.1105083760976e-05 0.000159960730849528 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3058 3157 0 624 1088 0 0 0 0 79 +323 444 0.593006453664558 -0.80205030233009 0.0711242465295406 -0.267937508000186 0.804524846955766 0.593805227341049 -0.0116242252751362 -0.00811041856771503 -0.0329107359836586 0.0641144641610292 0.997399728765934 -0.0506879811533871 1.63030076181717e-05 7.48062690936076e-06 -1.72992566568227e-07 -6.01865808664662e-08 -7.27007249866315e-07 5.84025052157106e-06 7.48062690936076e-06 4.30000767223622e-05 -5.76781287189158e-06 -1.48401487537991e-05 1.4135127285823e-05 -7.34616384784391e-06 -1.72992566568227e-07 -5.76781287189158e-06 1.82072602519788e-05 3.99894246565592e-06 -1.64529927251672e-05 5.95583084757997e-07 -6.01865808664662e-08 -1.48401487537991e-05 3.99894246565592e-06 6.53113622958471e-05 1.02964434121754e-06 1.01370101614115e-05 -7.27007249866315e-07 1.4135127285823e-05 -1.64529927251672e-05 1.02964434121754e-06 0.000100016880097339 2.86071152929648e-06 5.84025052157106e-06 -7.34616384784391e-06 5.95583084757997e-07 1.01370101614115e-05 2.86071152929648e-06 0.000109076724987486 0 0 0 0 93 0 0 0 0 28 0 0 0 0 0 2050 2057 0 1004 0 0 0 0 0 374 +323 441 0.82341615973837 -0.567389429214119 0.00742047827246816 -0.0952587374275551 0.567091997946838 0.823300350651568 0.0241495027209313 -0.224377308872812 -0.0198114549283594 -0.0156769969408055 0.999680818071718 0.0362842999910934 1.59070394620774e-05 1.90578501612978e-06 -5.78943901303118e-06 4.97669799912897e-06 3.19241459168683e-06 -9.5132118136654e-08 1.90578501612978e-06 4.42674131145951e-05 -1.94074881949813e-06 6.51181543878109e-07 -3.52488018832085e-06 1.99074693101861e-06 -5.78943901303118e-06 -1.94074881949813e-06 1.19918067567839e-05 7.41870451414423e-07 -5.16327138553987e-07 -3.5026721600848e-06 4.97669799912897e-06 6.51181543878109e-07 7.41870451414423e-07 3.49615489339871e-05 7.24617516810154e-06 -1.24939127844258e-05 3.19241459168683e-06 -3.52488018832085e-06 -5.16327138553987e-07 7.24617516810154e-06 6.6113246706302e-05 -3.25402591759392e-05 -9.5132118136654e-08 1.99074693101861e-06 -3.5026721600848e-06 -1.24939127844258e-05 -3.25402591759392e-05 8.02495247983846e-05 0 0 0 0 67 0 0 0 0 34 0 0 0 0 0 712 666 0 1484 0 0 0 0 0 554 +323 438 0.966441991865685 -0.250808985994483 0.055540335820975 0.0697933424546904 0.249241981303872 0.967856319075985 0.0336538315857873 -0.367898809950943 -0.0621957483627934 -0.0186814926893784 0.997889117445665 0.259468873874569 4.58540973932374e-05 2.377370483525e-06 -8.93524100266581e-06 -5.41054858697598e-06 -1.38380888491914e-05 3.86762186427625e-06 2.377370483525e-06 5.08281779333454e-05 -1.30471236440097e-06 7.89886910318463e-06 1.58535111326907e-05 1.55469472520525e-05 -8.93524100266581e-06 -1.30471236440097e-06 1.48471468262576e-05 6.5121532685429e-06 7.40288870620798e-06 -2.7538170525569e-07 -5.41054858697598e-06 7.89886910318463e-06 6.5121532685429e-06 4.84570030816604e-05 2.70561190326167e-05 3.97529556604427e-06 -1.38380888491914e-05 1.58535111326907e-05 7.40288870620798e-06 2.70561190326167e-05 0.000132237115049887 2.37539157031052e-06 3.86762186427625e-06 1.55469472520525e-05 -2.7538170525569e-07 3.97529556604427e-06 2.37539157031052e-06 9.18759998759177e-05 0 0 0 0 72 0 0 0 0 22 0 0 0 0 0 0 0 0 1551 0 0 0 0 0 790 +323 440 0.89281679354741 -0.450312482212771 -0.00984080906705109 -0.0383334336707943 0.450372105557231 0.892190182940621 0.0340828989425341 -0.2651569217869 -0.00656808158200353 -0.0348618104485882 0.999370559140392 0.092717149175974 2.95513330949201e-05 9.7336886349574e-06 -4.65102558894011e-06 6.89607259286306e-06 1.99929935285317e-05 -1.08374377648705e-05 9.7336886349574e-06 4.80517800313915e-05 -7.34748271014756e-07 -4.58541419371031e-06 -1.96196074405095e-05 -1.32450159638824e-05 -4.65102558894011e-06 -7.34748271014756e-07 1.50945476811188e-05 4.84614622810736e-06 -8.33461836261148e-06 -3.35377879718047e-07 6.89607259286306e-06 -4.58541419371031e-06 4.84614622810736e-06 5.39382257153257e-05 4.33606121545845e-05 -1.73670304401667e-05 1.99929935285317e-05 -1.96196074405095e-05 -8.33461836261148e-06 4.33606121545845e-05 0.000194535120148205 -5.34493326589719e-05 -1.08374377648705e-05 -1.32450159638824e-05 -3.35377879718047e-07 -1.73670304401667e-05 -5.34493326589719e-05 0.000118802076592531 0 0 0 0 82 0 0 0 0 20 0 0 0 0 0 208 92 0 1519 0 0 0 0 0 784 +323 446 0.47069516993758 -0.879448681088234 0.0708242495872643 -0.387641260799865 0.882109419554273 0.4707273734813 -0.0172832806208875 0.152191099661028 -0.0181391546400797 0.0706098944027162 0.997339066657564 -0.0667954645977419 4.35388711676817e-05 -1.58014657847367e-05 2.27114837400374e-06 2.27442002244992e-06 -1.14023638680767e-05 -3.31170926574232e-05 -1.58014657847367e-05 0.000119454754096032 -1.37484228168387e-05 -7.02525526693574e-06 4.63072440947059e-05 7.48043348011088e-05 2.27114837400374e-06 -1.37484228168387e-05 1.97459820817729e-05 9.57917562005476e-06 -1.55002170656995e-05 -5.48571597529925e-06 2.27442002244992e-06 -7.02525526693574e-06 9.57917562005476e-06 5.96600196184717e-05 -2.81997941222927e-05 4.2116899242183e-06 -1.14023638680767e-05 4.63072440947059e-05 -1.55002170656995e-05 -2.81997941222927e-05 7.57249297983066e-05 2.98497520583772e-05 -3.31170926574232e-05 7.48043348011088e-05 -5.48571597529925e-06 4.2116899242183e-06 2.98497520583772e-05 0.000266302498297983 0 0 0 0 71 0 0 0 0 13 0 0 0 0 0 2603 2635 0 882 0 0 0 0 0 340 +323 445 0.532491254929729 -0.844115355303329 0.0626285107957769 -0.319946942752936 0.846271792653342 0.532384119748841 -0.0197788270266583 0.0818429280728829 -0.0166468129880997 0.0635327945268146 0.997840902968481 -0.0587683402577984 4.35126869180549e-05 -3.71903677436712e-05 2.84551209166627e-06 -1.5509052541111e-05 -2.86317273666708e-05 -7.54173397821797e-05 -3.71903677436712e-05 0.000103212416994554 -4.61452817348128e-06 2.46214506362001e-05 4.81743950581963e-05 0.000127264576952782 2.84551209166627e-06 -4.61452817348128e-06 1.77186922674944e-05 1.67529779114241e-06 -1.47930616715294e-05 -2.67876190939968e-05 -1.5509052541111e-05 2.46214506362001e-05 1.67529779114241e-06 6.8184045590335e-05 4.12343465987291e-06 5.27240948492484e-05 -2.86317273666708e-05 4.81743950581963e-05 -1.47930616715294e-05 4.12343465987291e-06 0.000104249401306542 0.000105719328528727 -7.54173397821797e-05 0.000127264576952782 -2.67876190939968e-05 5.27240948492484e-05 0.000105719328528727 0.000418747927868259 0 0 0 0 70 0 0 0 0 40 0 0 0 0 0 2292 2329 0 1082 0 0 0 0 0 284 +323 448 0.336980158718241 -0.941272552464583 0.0212215599577015 -0.490333506886612 0.941314122007002 0.336362032238165 -0.0280768049962739 0.314752422200559 0.0192897988692565 0.0294374802831482 0.999380477302895 -0.0886064304811612 2.7915822981481e-05 7.26606781129126e-06 7.25169454396366e-07 -3.53142626830699e-06 4.25520769673991e-08 -1.4995023276803e-05 7.26606781129126e-06 4.64258870989411e-05 7.46076020950106e-06 1.56630201665736e-05 1.97632648469317e-06 -1.04016046998648e-05 7.25169454396366e-07 7.46076020950106e-06 1.71136966679428e-05 1.25737524494001e-06 -5.08788073674878e-06 -6.47715198677488e-06 -3.53142626830699e-06 1.56630201665736e-05 1.25737524494001e-06 7.41022153275188e-05 -2.00382350458574e-06 1.51795060876344e-05 4.25520769673991e-08 1.97632648469317e-06 -5.08788073674878e-06 -2.00382350458574e-06 5.60566481229603e-05 1.95510695030627e-05 -1.4995023276803e-05 -1.04016046998648e-05 -6.47715198677488e-06 1.51795060876344e-05 1.95510695030627e-05 0.000177706742269185 0 0 0 0 62 0 0 0 0 16 0 0 0 0 0 3173 3335 0 701 294 0 0 0 0 133 +323 436 0.988734642290832 -0.142965359512601 0.044325084472031 0.175425284231116 0.144777444481719 0.988623551536014 -0.0407794668633663 -0.49660414338529 -0.0379907712920198 0.0467373440382583 0.998184512987898 0.438483107095175 3.47376069908644e-05 3.51080486667053e-06 -1.35808412939181e-06 1.07648397683602e-06 -2.14118678179859e-06 7.48705984229458e-06 3.51080486667053e-06 4.70310432201267e-05 8.48513183751288e-07 -6.15294225031036e-06 6.17570464253774e-06 -2.0827082357253e-06 -1.35808412939181e-06 8.48513183751288e-07 1.58654595095862e-05 3.39103657664061e-06 -1.09530686789913e-06 1.84354482035999e-06 1.07648397683602e-06 -6.15294225031036e-06 3.39103657664061e-06 4.23613247500503e-05 1.90305813224408e-06 4.81161773163472e-06 -2.14118678179859e-06 6.17570464253774e-06 -1.09530686789913e-06 1.90305813224408e-06 9.63953900826696e-05 9.04948295139071e-06 7.48705984229458e-06 -2.0827082357253e-06 1.84354482035999e-06 4.81161773163472e-06 9.04948295139071e-06 0.000105677127956934 0 0 0 0 35 0 0 0 0 11 0 0 0 0 0 0 0 0 979 0 0 0 0 0 971 +323 447 0.403152646932351 -0.914170855781918 0.0419474636944243 -0.444454740046665 0.915123163226092 0.402934449077649 -0.013907763068233 0.227266309175032 -0.00418800650781879 0.0439940471592193 0.999023014958135 -0.0804634686224012 4.01252445722238e-05 9.35377060136328e-06 -1.53021339957875e-06 -5.74380693209161e-06 -5.1449913911091e-06 -9.49788515250411e-06 9.35377060136328e-06 4.9630401999408e-05 -5.22060652664691e-06 -4.01880960155743e-06 1.34173342446285e-05 1.44397250248593e-05 -1.53021339957875e-06 -5.22060652664691e-06 1.85890975626258e-05 1.60105166043493e-05 -8.82458078290102e-06 -2.84068807571648e-06 -5.74380693209161e-06 -4.01880960155743e-06 1.60105166043493e-05 0.000109304785329421 -1.37043854626263e-05 3.71844860845653e-05 -5.1449913911091e-06 1.34173342446285e-05 -8.82458078290102e-06 -1.37043854626263e-05 5.55253730371819e-05 2.54276251656919e-05 -9.49788515250411e-06 1.44397250248593e-05 -2.84068807571648e-06 3.71844860845653e-05 2.54276251656919e-05 0.000157437079517582 0 0 0 0 66 0 0 0 0 23 0 0 0 0 0 3103 3163 0 829 0 0 0 0 0 214 +324 442 0.681259647183073 -0.730260961819008 0.0510315663405754 -0.176935044389701 0.730683459593321 0.682586047575769 0.0133405221646407 -0.132570655523699 -0.0445754977171323 0.0281995620190767 0.998607935931416 -0.022568179354039 2.62903908162851e-05 1.43324722905542e-05 -1.51965389454761e-06 6.21395193049321e-06 2.8504810227074e-06 8.75799043363225e-06 1.43324722905542e-05 4.36679609452432e-05 -1.94343896025465e-06 -2.92807077144195e-07 3.63265654510639e-06 -1.49026944892331e-05 -1.51965389454761e-06 -1.94343896025465e-06 1.34800869672614e-05 -2.24141406408733e-06 1.05126560015195e-06 2.37597414000147e-06 6.21395193049321e-06 -2.92807077144195e-07 -2.24141406408733e-06 5.95857690721406e-05 6.18651261359593e-05 -4.98924787934157e-05 2.8504810227074e-06 3.63265654510639e-06 1.05126560015195e-06 6.18651261359593e-05 0.000140576823784903 -0.000102377334598161 8.75799043363225e-06 -1.49026944892331e-05 2.37597414000147e-06 -4.98924787934157e-05 -0.000102377334598161 0.000234289873516661 0 0 0 0 55 0 0 0 0 55 0 0 0 0 0 1272 1282 0 1023 0 0 0 0 0 340 +323 435 0.996890056594733 -0.078793248716687 0.00135610442806751 0.19807785628117 0.0786206782604343 0.99323611698811 -0.0854447474117107 -0.52625008352537 0.00538553733798127 0.0852856369329096 0.996341987532659 0.53273173764608 6.64837256817763e-05 -1.60844566942317e-05 -1.22693851095767e-06 2.65288564196085e-06 9.6232621502869e-06 3.42969368808268e-05 -1.60844566942317e-05 0.000119185641239473 -5.4355815091037e-06 -1.64308583951939e-05 1.81585624532161e-05 5.07771141945962e-05 -1.22693851095767e-06 -5.4355815091037e-06 1.45768481429959e-05 5.20190714499013e-06 -1.96305330055866e-06 -1.43870512693372e-05 2.65288564196085e-06 -1.64308583951939e-05 5.20190714499013e-06 4.47339497580488e-05 1.18473183658478e-05 -4.51053202654024e-06 9.6232621502869e-06 1.81585624532161e-05 -1.96305330055866e-06 1.18473183658478e-05 0.000114507699413278 2.98466371672148e-05 3.42969368808268e-05 5.07771141945962e-05 -1.43870512693372e-05 -4.51053202654024e-06 2.98466371672148e-05 0.000321315746231061 22 17 0 0 43 18 16 0 0 17 0 0 0 0 0 0 0 0 758 0 22 17 0 0 928 +323 437 0.982477917956236 -0.177973415702185 0.0553407989793814 0.120096797065862 0.177865363754182 0.984030560297243 0.00691149605266868 -0.447897088276732 -0.0556870999870834 0.00305281908912608 0.998443602408588 0.336233758377209 3.49800009294707e-05 -2.12834194152357e-05 -3.97810804662981e-06 -4.89972109267082e-08 -1.298513537576e-06 -4.32356220558856e-06 -2.12834194152357e-05 8.38778982572614e-05 -7.57992023994081e-07 -1.58860602061594e-06 1.41214222786167e-05 2.20317070173922e-05 -3.97810804662981e-06 -7.57992023994081e-07 1.36238771539465e-05 5.30408711320843e-06 -3.41449447271682e-06 -2.1553228418907e-06 -4.89972109267082e-08 -1.58860602061594e-06 5.30408711320843e-06 4.42779690968612e-05 1.50147965621189e-06 6.11582130320963e-06 -1.298513537576e-06 1.41214222786167e-05 -3.41449447271682e-06 1.50147965621189e-06 0.000140029399364663 1.42960891137072e-05 -4.32356220558856e-06 2.20317070173922e-05 -2.1553228418907e-06 6.11582130320963e-06 1.42960891137072e-05 0.000100813528026321 0 0 0 0 52 0 0 0 0 16 0 0 0 0 0 0 0 0 1314 0 0 0 0 0 1065 +323 450 0.204130834460658 -0.976640336311799 0.0671137535172243 -0.584715845740168 0.978385776693184 0.201220401310014 -0.04766153649551 0.498799151646263 0.0330435226159548 0.07539233107825 0.996606302422234 -0.0739338314799525 3.85673005026041e-05 6.04075593338729e-06 -2.94996427369303e-06 -6.62399494798243e-06 -5.24484328595361e-07 4.62633813462502e-06 6.04075593338729e-06 3.85643766102652e-05 7.68059747224844e-06 1.45613253981766e-05 5.52767259676522e-07 1.76924946488004e-05 -2.94996427369303e-06 7.68059747224844e-06 1.77576694877588e-05 1.12104727806773e-05 -5.69644245150576e-06 -4.82690066876768e-06 -6.62399494798243e-06 1.45613253981766e-05 1.12104727806773e-05 0.00012730012662944 -1.70272068485636e-05 1.20301622783284e-05 -5.24484328595361e-07 5.52767259676522e-07 -5.69644245150576e-06 -1.70272068485636e-05 5.12306913601956e-05 1.49996487262691e-05 4.62633813462502e-06 1.76924946488004e-05 -4.82690066876768e-06 1.20301622783284e-05 1.49996487262691e-05 0.000119624500737839 0 0 0 0 36 0 0 0 0 10 0 0 0 0 0 3149 3248 0 375 1274 0 0 0 0 68 +323 449 0.276027557538812 -0.960507978673793 0.0351170953118576 -0.545919341140958 0.960585310036389 0.274429343108603 -0.0443215273120771 0.396275635068383 0.0329340192119432 0.0459669288180605 0.998399915782039 -0.104302612265572 4.28622421090005e-05 1.32100951708233e-05 -3.08833089109194e-07 -1.10344689684657e-05 -4.73144390160951e-06 -1.05367928249504e-05 1.32100951708233e-05 3.30855621797802e-05 3.90827372579439e-06 3.98684733903222e-06 1.86554279754767e-06 1.6976078393239e-05 -3.08833089109194e-07 3.90827372579439e-06 1.35261178352106e-05 3.46332936405044e-06 -1.11817265709966e-06 -3.03651166290041e-06 -1.10344689684657e-05 3.98684733903222e-06 3.46332936405044e-06 7.23609729493656e-05 -4.94468569382014e-06 3.15437479182765e-05 -4.73144390160951e-06 1.86554279754767e-06 -1.11817265709966e-06 -4.94468569382014e-06 3.95426300869624e-05 2.10088226559618e-05 -1.05367928249504e-05 1.6976078393239e-05 -3.03651166290041e-06 3.15437479182765e-05 2.10088226559618e-05 0.000158017012199265 0 0 0 0 43 0 0 0 0 10 0 0 0 0 0 3062 3193 0 554 780 0 0 0 0 108 +324 441 0.765175218588374 -0.642682282518153 0.0382931925476377 -0.120236305588634 0.641805152983607 0.766131990262883 0.0335845068375646 -0.174629751254849 -0.050921807331654 -0.00112126405934888 0.998702013768365 0.00471714458309431 3.00494936599115e-05 1.47296077218784e-05 -3.73064100042388e-06 -1.09675732759294e-06 -4.96578448278178e-07 -9.9364123394204e-06 1.47296077218784e-05 4.70158190213379e-05 -3.38434566076635e-06 2.33033476075238e-06 8.16406667695054e-06 1.25222292956576e-05 -3.73064100042388e-06 -3.38434566076635e-06 1.30342502470372e-05 2.87776040325046e-07 -9.81715813770762e-07 8.02216313952261e-07 -1.09675732759294e-06 2.33033476075238e-06 2.87776040325046e-07 4.55968601800947e-05 3.16115591020872e-05 -9.50091688653805e-06 -4.96578448278178e-07 8.16406667695054e-06 -9.81715813770762e-07 3.16115591020872e-05 0.000106722882572623 -4.00503103376387e-05 -9.9364123394204e-06 1.25222292956576e-05 8.02216313952261e-07 -9.50091688653805e-06 -4.00503103376387e-05 0.000198982909228763 0 0 0 0 102 0 0 0 0 102 0 0 0 0 0 786 740 0 1220 0 0 0 0 0 473 +324 446 0.384169647439694 -0.917693744028705 0.101251539033437 -0.449844147927394 0.922632289882727 0.38564321551963 -0.00538219188022809 0.180945275831907 -0.0341077652715185 0.0954856140696501 0.994846298607943 -0.0791407107826972 3.98146400098615e-05 -2.57227661919278e-06 2.90158170593551e-06 -1.03665160325578e-05 -1.27124558344888e-05 -4.10974612054252e-05 -2.57227661919278e-06 6.62469697979468e-05 -5.60369973041245e-07 1.98821285801517e-05 1.94659631794498e-05 2.4524383437932e-05 2.90158170593551e-06 -5.60369973041245e-07 1.34063825256896e-05 3.84083962252501e-07 5.61669293842437e-07 -9.31013028717469e-07 -1.03665160325578e-05 1.98821285801517e-05 3.84083962252501e-07 6.14739049843241e-05 -2.96617620433025e-06 4.85890699678834e-05 -1.27124558344888e-05 1.94659631794498e-05 5.61669293842437e-07 -2.96617620433025e-06 3.91048217257927e-05 3.78917806411238e-05 -4.10974612054252e-05 2.4524383437932e-05 -9.31013028717469e-07 4.85890699678834e-05 3.78917806411238e-05 0.000280708095686136 0 0 0 0 25 0 0 0 0 25 0 0 0 0 0 2646 2678 0 638 0 0 0 0 0 210 +324 440 0.846173702445693 -0.532788218378669 0.0112596468075274 -0.0637618115623967 0.532118144757612 0.845881561306525 0.0365330571038437 -0.204043339003714 -0.0289887100275944 -0.0249218498213719 0.999269010873657 0.0480980262758861 2.58909688487396e-05 6.67512430326987e-06 -6.08021130980835e-06 3.26866404047423e-06 3.67697791140745e-06 1.84656135411619e-06 6.67512430326987e-06 4.56034973581841e-05 -4.37766575682456e-06 -1.16445668596723e-05 -5.99688702920741e-06 -4.39385871402576e-06 -6.08021130980835e-06 -4.37766575682456e-06 1.7525582277028e-05 5.14938288542052e-06 4.66309508178004e-07 -3.71775612114227e-06 3.26866404047423e-06 -1.16445668596723e-05 5.14938288542052e-06 4.31951470068744e-05 -4.69955267017483e-07 -3.48389588014578e-06 3.67697791140745e-06 -5.99688702920741e-06 4.66309508178004e-07 -4.69955267017483e-07 5.54550004345886e-05 -7.04396377460579e-06 1.84656135411619e-06 -4.39385871402576e-06 -3.71775612114227e-06 -3.48389588014578e-06 -7.04396377460579e-06 9.2149906029326e-05 0 0 0 0 136 0 0 0 0 136 0 0 0 0 0 285 165 0 1402 0 0 0 0 0 671 +324 445 0.451249413441044 -0.88708927123724 0.0971935786196665 -0.387467484621758 0.89160463500073 0.452757484294624 -0.00719967085490043 0.112239109934564 -0.0376183693736103 0.0899070924398449 0.995239455113534 -0.0951006388313029 3.59395187485148e-05 -1.92564600327849e-05 6.18718974554492e-06 -9.4807177480311e-06 -2.89984414125844e-05 -3.47729248460079e-05 -1.92564600327849e-05 8.66904219153829e-05 -2.85432886311003e-06 2.7389342194177e-05 3.61817919977579e-05 5.59270268416532e-05 6.18718974554492e-06 -2.85432886311003e-06 1.83923682305865e-05 8.26226793823809e-06 -1.43857314152347e-05 -6.54642454077643e-06 -9.4807177480311e-06 2.7389342194177e-05 8.26226793823809e-06 0.000101552333597712 9.71004283125606e-06 5.67811501583988e-05 -2.89984414125844e-05 3.61817919977579e-05 -1.43857314152347e-05 9.71004283125606e-06 0.000102245022813739 6.04245505822899e-05 -3.47729248460079e-05 5.59270268416532e-05 -6.54642454077643e-06 5.67811501583988e-05 6.04245505822899e-05 0.00014834197433614 0 0 0 0 76 0 0 0 0 76 0 0 0 0 0 2335 2365 0 839 0 0 0 0 0 405 +324 438 0.936639931648881 -0.340665355803758 0.0815644150097173 0.0626534549675659 0.338523245294333 0.940140359675158 0.0392188284534118 -0.302510258809192 -0.0900424946132176 -0.00912247033232952 0.995896144032531 0.225423724338008 3.40582981261899e-05 -4.85263671147248e-06 -5.41382957297953e-06 -4.09968740742753e-06 1.00098692357479e-05 8.75939632122487e-06 -4.85263671147248e-06 6.1855321543522e-05 -3.93295897829648e-07 7.9227493710487e-06 -7.51032316159583e-06 1.63989353580549e-05 -5.41382957297953e-06 -3.93295897829648e-07 1.25724539413337e-05 1.49464944766022e-06 -1.41577826792493e-06 -1.92086324749382e-06 -4.09968740742753e-06 7.9227493710487e-06 1.49464944766022e-06 3.43279231762925e-05 8.39430659199405e-06 1.01248694204859e-05 1.00098692357479e-05 -7.51032316159583e-06 -1.41577826792493e-06 8.39430659199405e-06 0.000126858871477552 -3.13895347133629e-06 8.75939632122487e-06 1.63989353580549e-05 -1.92086324749382e-06 1.01248694204859e-05 -3.13895347133629e-06 0.000111904746566445 0 0 0 0 115 0 0 0 0 115 0 0 0 0 0 0 0 0 1500 0 0 0 0 0 897 +324 448 0.250119823577962 -0.967055867116184 0.0473605714650383 -0.570698322866574 0.96816826483767 0.249328337982728 -0.022036125793495 0.319524624587945 0.00950183216781939 0.0513646741928373 0.99863476077619 -0.0825643478802332 3.58608131919875e-05 1.96161656726884e-05 -9.22195868784094e-07 -1.15749960272587e-06 6.77384887304994e-07 -2.17658061084927e-05 1.96161656726884e-05 5.56717084094526e-05 1.64683213672767e-06 -1.96872117365161e-06 -9.47220844296521e-06 -2.81744822280268e-05 -9.22195868784094e-07 1.64683213672767e-06 1.85959142704669e-05 4.09766083734724e-06 -1.29326385186891e-05 7.70648025508683e-06 -1.15749960272587e-06 -1.96872117365161e-06 4.09766083734724e-06 5.77309914658274e-05 -6.58344706662561e-06 1.69984711367993e-05 6.77384887304994e-07 -9.47220844296521e-06 -1.29326385186891e-05 -6.58344706662561e-06 7.65084489800408e-05 -1.12404975152698e-05 -2.17658061084927e-05 -2.81744822280268e-05 7.70648025508683e-06 1.69984711367993e-05 -1.12404975152698e-05 0.000256856868214983 0 0 0 0 44 0 0 0 0 44 0 0 0 0 0 3110 3272 0 421 335 0 0 0 0 53 +324 437 0.958864877177345 -0.269583675554071 0.0888976332105222 0.120190432801212 0.26873437837845 0.962971770303542 0.0216148901456805 -0.350733086834259 -0.0914329327607015 0.00316409121540538 0.995806209728358 0.306280889679834 4.37216422535157e-05 3.94814715543312e-06 -5.93573870037587e-06 -9.19458711268922e-06 -6.51493150464131e-06 -1.11487413405397e-05 3.94814715543312e-06 4.9887235955343e-05 -5.36150474866883e-07 8.11131829406806e-06 5.22458640203852e-06 1.42999388758991e-05 -5.93573870037587e-06 -5.36150474866883e-07 1.46574905720248e-05 7.08096460625625e-06 -8.66326871311475e-10 1.21737595372876e-06 -9.19458711268922e-06 8.11131829406806e-06 7.08096460625625e-06 4.30368972796175e-05 1.24322992037759e-05 1.92747856091206e-05 -6.51493150464131e-06 5.22458640203852e-06 -8.66326871311475e-10 1.24322992037759e-05 0.000116495887289698 2.01455026544519e-05 -1.11487413405397e-05 1.42999388758991e-05 1.21737595372876e-06 1.92747856091206e-05 2.01455026544519e-05 0.000120394438327692 0 0 0 0 81 0 0 0 0 81 0 0 0 0 0 0 0 0 1263 0 0 0 0 0 974 +324 447 0.314488952708958 -0.94662353035005 0.0707148528360954 -0.511399178360622 0.94919658651943 0.314462506048824 -0.0117971364896309 0.238458232596692 -0.0110697228458766 0.0708323660278343 0.997426807920769 -0.108828638475547 3.27269005797043e-05 2.44132315857824e-06 3.51166479601014e-07 -1.27072299262089e-05 -5.50388776779341e-06 -1.6739197067584e-05 2.44132315857824e-06 4.90941749037534e-05 4.66900394010269e-06 2.74886970680772e-05 8.35500514069471e-06 1.98937340609942e-05 3.51166479601014e-07 4.66900394010269e-06 1.77430221265156e-05 6.42413223750654e-06 -7.81909665467418e-06 -1.1162810284221e-05 -1.27072299262089e-05 2.74886970680772e-05 6.42413223750654e-06 8.99305118608983e-05 8.68031303435691e-06 2.31403232261682e-05 -5.50388776779341e-06 8.35500514069471e-06 -7.81909665467418e-06 8.68031303435691e-06 6.88965570235871e-05 4.20651306594972e-05 -1.6739197067584e-05 1.98937340609942e-05 -1.1162810284221e-05 2.31403232261682e-05 4.20651306594972e-05 0.000175326436267339 0 0 0 0 85 0 0 0 0 85 0 0 0 0 0 3044 3107 0 593 0 0 0 0 0 149 +324 449 0.183764443888193 -0.980915295379119 0.0635280446240773 -0.629620040060231 0.982730201926948 0.181907081070733 -0.0339288089526578 0.401143268719337 0.0217250864919609 0.0686658368304175 0.997403139893441 -0.107270129789626 3.32653717098773e-05 1.52664323799238e-05 -1.88983212155115e-06 -1.55249547248312e-05 -2.83632609764817e-06 -1.40400197006181e-05 1.52664323799238e-05 5.32102538811294e-05 -5.78670156991277e-06 -2.10733819975914e-06 1.09420717854126e-05 -3.11274101104056e-06 -1.88983212155115e-06 -5.78670156991277e-06 1.94021188440869e-05 9.92612914638041e-07 -7.54619524837701e-06 -3.39937386480469e-07 -1.55249547248312e-05 -2.10733819975914e-06 9.92612914638041e-07 7.35591607311612e-05 4.30097888563541e-06 5.41516464263767e-05 -2.83632609764817e-06 1.09420717854126e-05 -7.54619524837701e-06 4.30097888563541e-06 6.16462576992937e-05 1.81721804205774e-05 -1.40400197006181e-05 -3.11274101104056e-06 -3.39937386480469e-07 5.41516464263767e-05 1.81721804205774e-05 0.000150601275880606 0 0 0 0 64 0 0 0 0 64 0 0 0 0 0 3114 3245 0 254 924 0 0 0 0 1 +324 436 0.968912800256823 -0.234569153061877 0.078646665093409 0.181876520213346 0.237318958993194 0.971041679745394 -0.0275275843406494 -0.395294742369779 -0.0699120676340517 0.0453361735160586 0.996522420304758 0.401764192453942 4.55622504113052e-05 2.59530401712232e-06 -9.5434070416575e-06 -8.55076119776829e-06 -5.9968079676521e-06 2.25687557155081e-05 2.59530401712232e-06 6.18824515426662e-05 -6.26881990702576e-07 2.68923888862409e-06 1.30827128313819e-05 1.17105092215919e-05 -9.5434070416575e-06 -6.26881990702576e-07 1.9024323648846e-05 9.04280205792811e-06 -3.5729129489003e-07 -6.97891757487298e-06 -8.55076119776829e-06 2.68923888862409e-06 9.04280205792811e-06 4.58352347792985e-05 1.11730781106373e-05 7.40733858957565e-06 -5.9968079676521e-06 1.30827128313819e-05 -3.5729129489003e-07 1.11730781106373e-05 9.08021120722644e-05 2.65980874421366e-05 2.25687557155081e-05 1.17105092215919e-05 -6.97891757487298e-06 7.40733858957565e-06 2.65980874421366e-05 0.000130486626989737 0 0 0 0 82 0 0 0 0 82 0 0 0 0 0 0 0 0 887 0 0 0 0 0 938 +324 435 0.984154828507777 -0.168367389869953 0.0556030174829307 0.220392048902068 0.172048283333117 0.982610632477323 -0.0698264501792995 -0.432189041541108 -0.0428796190159773 0.0782864418075949 0.996008318892042 0.504013913230047 5.70129463723919e-05 4.27029742184652e-06 -8.17644264147173e-06 1.30491652447257e-06 -1.33863273993175e-05 3.01011243860369e-05 4.27029742184652e-06 7.54918255912389e-05 -3.34342584925782e-06 1.25754272561507e-05 1.75472649221481e-05 6.0664759498662e-05 -8.17644264147173e-06 -3.34342584925782e-06 1.86546580358329e-05 3.210829065539e-06 -1.59162894094305e-06 -1.70931321145727e-05 1.30491652447257e-06 1.25754272561507e-05 3.210829065539e-06 5.39242520387429e-05 1.13696434917035e-05 1.68162934958897e-06 -1.33863273993175e-05 1.75472649221481e-05 -1.59162894094305e-06 1.13696434917035e-05 9.56783148485398e-05 1.20907192494361e-05 3.01011243860369e-05 6.0664759498662e-05 -1.70931321145727e-05 1.68162934958897e-06 1.20907192494361e-05 0.00029384002577622 19 15 0 0 61 19 15 0 0 61 0 0 0 0 0 0 0 0 664 0 0 0 0 0 958 +324 434 0.994039009833653 -0.094300426049238 0.0547163282381291 0.256299006466492 0.0958763362110187 0.995029072692289 -0.0269234591364958 -0.467591091478861 -0.0519054436806217 0.0320089697437305 0.99813889352748 0.597881526177642 5.51056617521942e-05 1.16665937133497e-05 -1.30361071154659e-05 -9.3005354106079e-06 2.49197725951755e-06 1.33729181021999e-05 1.16665937133497e-05 8.38892810756112e-05 -7.89611322304701e-06 -7.90834920809721e-06 1.79715405632308e-06 -2.89551796839878e-05 -1.30361071154659e-05 -7.89611322304701e-06 1.99067600297608e-05 1.22620923472535e-05 5.72701078031739e-06 2.6447342515712e-07 -9.3005354106079e-06 -7.90834920809721e-06 1.22620923472535e-05 5.90686166094539e-05 2.59302905704223e-05 2.96789392645822e-05 2.49197725951755e-06 1.79715405632308e-06 5.72701078031739e-06 2.59302905704223e-05 7.54395996340703e-05 1.15927194278605e-05 1.33729181021999e-05 -2.89551796839878e-05 2.6447342515712e-07 2.96789392645822e-05 1.15927194278605e-05 0.000170412591631422 67 65 0 0 27 67 65 0 0 27 0 0 0 0 0 0 0 0 633 0 0 0 0 0 1024 +325 440 0.791055599700142 -0.611226362915564 0.0251668722740811 -0.081608939920836 0.61058011931215 0.791418603076604 0.0291292396920662 -0.170438146652612 -0.0377220901304379 -0.00767645629759455 0.999258783266328 0.0123836831907517 2.44294262841921e-05 2.96433899578586e-06 -3.92210786010726e-06 -1.90732695382503e-06 -1.96059027881088e-06 -2.30918507153943e-05 2.96433899578586e-06 3.67533199923225e-05 1.26030748431854e-07 9.79686363903289e-06 -1.9411280572574e-06 1.37909180298316e-05 -3.92210786010726e-06 1.26030748431854e-07 2.05047458183315e-05 7.3895659361167e-06 -7.63806260064329e-06 -8.05424527251099e-08 -1.90732695382503e-06 9.79686363903289e-06 7.3895659361167e-06 5.5981047238264e-05 -1.43114862879187e-05 1.00044279438775e-05 -1.96059027881088e-06 -1.9411280572574e-06 -7.63806260064329e-06 -1.43114862879187e-05 8.40380247822613e-05 -4.18595319955964e-06 -2.30918507153943e-05 1.37909180298316e-05 -8.05424527251099e-08 1.00044279438775e-05 -4.18595319955964e-06 0.000160097267774204 0 0 0 0 187 0 0 0 0 187 0 0 0 0 0 354 234 0 1256 0 0 0 0 0 733 +325 441 0.700544351323453 -0.71220759712961 0.0446984386714913 -0.146444504969166 0.711912148516111 0.701823168708419 0.0250066522999184 -0.139830725593354 -0.0491803276115255 0.0143030924957195 0.998687497128647 -0.0333690699416823 2.13922198988024e-05 1.00135000905275e-05 -2.54398190978207e-06 2.33276571050295e-06 2.53199702468875e-06 -6.47317835645362e-07 1.00135000905275e-05 3.1480367917961e-05 -1.97498277114751e-06 -4.82869128859988e-06 -1.99568044259454e-06 3.86192407815209e-06 -2.54398190978207e-06 -1.97498277114751e-06 1.26662785438848e-05 7.36165310146889e-07 -1.10584600957853e-06 -1.10330950058115e-06 2.33276571050295e-06 -4.82869128859988e-06 7.36165310146889e-07 5.12227215590308e-05 2.70312748002869e-05 -1.64706152756912e-05 2.53199702468875e-06 -1.99568044259454e-06 -1.10584600957853e-06 2.70312748002869e-05 0.000101839295339371 -2.97172841266787e-05 -6.47317835645362e-07 3.86192407815209e-06 -1.10330950058115e-06 -1.64706152756912e-05 -2.97172841266787e-05 0.000111133523223704 0 0 0 0 176 0 0 0 0 176 0 0 0 0 0 845 799 0 1045 0 0 0 0 0 665 +325 446 0.295800881582095 -0.949034939316868 0.108786591136427 -0.517418123839589 0.954970265860007 0.296544498072682 -0.00965152765566464 0.196328051644561 -0.0231004281025811 0.106742890248717 0.994018272268084 -0.130741852202641 4.05772897882602e-05 -1.01882203262132e-05 3.19480546219334e-06 -1.1656962238936e-05 -1.61835544292545e-05 -9.15195000366542e-06 -1.01882203262132e-05 6.80984962537991e-05 -2.13709325773184e-06 1.65313191051115e-05 2.16209437552705e-05 5.73864125426451e-06 3.19480546219334e-06 -2.13709325773184e-06 1.33981450326365e-05 -1.33887530825162e-06 1.08152843144175e-06 2.46663862998506e-06 -1.1656962238936e-05 1.65313191051115e-05 -1.33887530825162e-06 5.28322031598367e-05 3.89155612582235e-06 1.85668127524407e-05 -1.61835544292545e-05 2.16209437552705e-05 1.08152843144175e-06 3.89155612582235e-06 4.26641021556415e-05 6.91993481648442e-06 -9.15195000366542e-06 5.73864125426451e-06 2.46663862998506e-06 1.85668127524407e-05 6.91993481648442e-06 0.000180853010999729 0 0 0 0 37 0 0 0 0 37 0 0 0 0 0 2663 2697 0 510 0 0 0 0 0 296 +325 436 0.941933108714802 -0.323340184762587 0.0906263958489195 0.170938289837395 0.32740365459378 0.944277317435134 -0.0338702633019574 -0.330885488165485 -0.0746248327670199 0.0615749356086004 0.995308827268849 0.33909086129917 3.68332984263758e-05 7.87086617359155e-06 -7.66710014014828e-06 -1.2794364299363e-06 9.93013541519088e-06 1.87826891825578e-05 7.87086617359155e-06 4.48295210368727e-05 -4.38047753486513e-06 -6.86168465224391e-06 -1.49180844493786e-05 5.41564934693702e-06 -7.66710014014828e-06 -4.38047753486513e-06 1.72234032354884e-05 7.20609485985477e-06 3.40508584490431e-06 -1.5837359133072e-06 -1.2794364299363e-06 -6.86168465224391e-06 7.20609485985477e-06 3.97054787913356e-05 2.24864487237837e-05 5.94262484741004e-06 9.93013541519088e-06 -1.49180844493786e-05 3.40508584490431e-06 2.24864487237837e-05 8.88955156110474e-05 9.9654084113347e-06 1.87826891825578e-05 5.41564934693702e-06 -1.5837359133072e-06 5.94262484741004e-06 9.9654084113347e-06 0.000102253898073895 45 33 0 0 199 45 33 0 0 199 0 0 0 0 0 0 0 0 847 0 0 0 0 0 1233 +325 442 0.608689299240218 -0.791287527049521 0.0579774656768051 -0.22152103153189 0.792294154391809 0.610081103858498 0.00842731459986606 -0.0719915369644056 -0.0420393851884198 0.0408055909239151 0.998282321711814 -0.0688796150178255 2.49737699352251e-05 1.18503103151375e-05 -4.58720927622275e-07 6.78288191554801e-06 7.44661141176997e-06 -1.38315302791675e-05 1.18503103151375e-05 3.34094458926402e-05 -6.74891824373745e-07 -1.5163551780805e-06 -6.45142154430211e-06 -7.33264439127839e-06 -4.58720927622275e-07 -6.74891824373745e-07 1.15332284007236e-05 -1.28781422462053e-06 2.27948520818004e-07 2.36851943218193e-07 6.78288191554801e-06 -1.5163551780805e-06 -1.28781422462053e-06 4.14972427389638e-05 2.73748613272061e-05 -2.09913358761466e-05 7.44661141176997e-06 -6.45142154430211e-06 2.27948520818004e-07 2.73748613272061e-05 7.26215209824204e-05 -2.61335510246018e-05 -1.38315302791675e-05 -7.33264439127839e-06 2.36851943218193e-07 -2.09913358761466e-05 -2.61335510246018e-05 0.000119874977456127 0 0 0 0 160 0 0 0 0 160 0 0 0 0 0 1307 1317 0 937 0 0 0 0 0 556 +325 435 0.964256157468648 -0.259334417089485 0.054366560463707 0.196334963057586 0.263254514969948 0.960946702409847 -0.0853140989261367 -0.356739934801746 -0.0301184848844404 0.0965768877138743 0.994869730983794 0.436097204413667 5.2855986540628e-05 2.73187667557392e-06 -4.29436244605145e-06 9.88395764751248e-06 6.96758374569029e-06 5.56040679548374e-06 2.73187667557392e-06 7.14764638095345e-05 -6.36102654713982e-06 5.3675112332623e-06 2.3912371610994e-05 4.558830055152e-05 -4.29436244605145e-06 -6.36102654713982e-06 1.81890900447843e-05 -2.18368169580498e-07 -6.43515581473916e-06 -7.97562784004755e-06 9.88395764751248e-06 5.3675112332623e-06 -2.18368169580498e-07 5.07913642027757e-05 1.57606220335015e-05 1.46361680151704e-05 6.96758374569029e-06 2.3912371610994e-05 -6.43515581473916e-06 1.57606220335015e-05 0.000110181298535457 1.53224919623601e-05 5.56040679548374e-06 4.558830055152e-05 -7.97562784004755e-06 1.46361680151704e-05 1.53224919623601e-05 0.000169893678330765 122 87 0 0 151 122 87 0 0 151 0 0 0 0 0 0 0 0 627 0 0 0 0 0 1138 +325 437 0.928340722020492 -0.359378131007683 0.095030851789811 0.105783007570228 0.359306135630087 0.933037083218148 0.0184635380776241 -0.285734727373611 -0.0953027005758271 0.0170047138521981 0.995303086988963 0.244567632754847 3.55114925966784e-05 1.02923826044092e-05 -4.04248878840286e-06 1.74510821598107e-06 -1.24310471209822e-06 -2.36011852491928e-06 1.02923826044092e-05 3.70139331799608e-05 -2.56720405340914e-06 4.47400051044147e-06 8.08508555187148e-06 1.17343888585736e-05 -4.04248878840286e-06 -2.56720405340914e-06 1.39536215309045e-05 4.9002509220835e-06 -2.19309264690017e-07 -1.42752149043183e-06 1.74510821598107e-06 4.47400051044147e-06 4.9002509220835e-06 4.18525662024574e-05 1.47251735584275e-05 5.39070160320157e-06 -1.24310471209822e-06 8.08508555187148e-06 -2.19309264690017e-07 1.47251735584275e-05 0.000166736757470449 5.92167109504761e-07 -2.36011852491928e-06 1.17343888585736e-05 -1.42752149043183e-06 5.39070160320157e-06 5.92167109504761e-07 0.000217370136411325 6 6 0 0 171 6 6 0 0 171 0 0 0 0 0 0 0 0 1164 0 0 0 0 0 1041 +325 444 0.429434657543686 -0.894935079874244 0.121148989722647 -0.374295172802866 0.901298767409127 0.433168854135821 0.00502749176518506 0.0611951427840318 -0.0569772478023141 0.107032455905396 0.992621602936251 -0.132419907966043 2.19743275940449e-05 8.24511912983777e-06 1.949425693726e-06 5.5039517420577e-06 -9.52221689461559e-07 -4.72453333078525e-06 8.24511912983777e-06 3.32019717212816e-05 -3.07961868688711e-06 6.02774374814502e-06 2.24012704779684e-05 1.80305119001148e-07 1.949425693726e-06 -3.07961868688711e-06 1.47190862908227e-05 1.43587435562547e-06 -1.00752775845398e-05 -1.38158097919641e-06 5.5039517420577e-06 6.02774374814502e-06 1.43587435562547e-06 0.000109559777344565 5.63308166057426e-05 2.10800265848599e-06 -9.52221689461559e-07 2.24012704779684e-05 -1.00752775845398e-05 5.63308166057426e-05 0.000119488273545755 7.96886043978457e-06 -4.72453333078525e-06 1.80305119001148e-07 -1.38158097919641e-06 2.10800265848599e-06 7.96886043978457e-06 0.000124738636475106 0 0 0 0 110 0 0 0 0 110 0 0 0 0 0 2022 2031 0 630 0 0 0 0 0 251 +325 448 0.158418112141589 -0.985179161926425 0.0657702109730647 -0.65018596834558 0.987171281138203 0.156690655924486 -0.0306740939868247 0.323274648564339 0.019913900709131 0.0697857954880566 0.997363213331355 -0.139501717623137 4.85031997474174e-05 7.92912193047783e-06 -1.59331503635518e-06 7.87464979454509e-06 -2.38185560649195e-06 -4.01336437708245e-06 7.92912193047783e-06 5.31832764233992e-05 2.67390765382763e-06 3.26445638088643e-06 -8.09748683514826e-06 5.70794375106312e-06 -1.59331503635518e-06 2.67390765382763e-06 1.55072864414999e-05 3.38014791424083e-06 -7.94742194094389e-07 -1.01993262175633e-05 7.87464979454509e-06 3.26445638088643e-06 3.38014791424083e-06 6.84258171844105e-05 -2.95080868616168e-06 -3.94887659939704e-05 -2.38185560649195e-06 -8.09748683514826e-06 -7.94742194094389e-07 -2.95080868616168e-06 4.63385416606416e-05 6.19658447052703e-06 -4.01336437708245e-06 5.70794375106312e-06 -1.01993262175633e-05 -3.94887659939704e-05 6.19658447052703e-06 0.000173032360100627 0 0 0 0 56 0 0 0 0 56 0 0 0 0 0 3064 3221 0 164 363 0 0 0 0 119 +325 438 0.899541252963974 -0.4284335268912 0.0852657448895599 0.0463006350549717 0.426804345183142 0.903569193873315 0.0374267660360419 -0.243405172797967 -0.0930783817478206 0.00272487039969083 0.995655055695752 0.166333918714773 4.22573104274597e-05 4.42460267775354e-06 -8.08538553527107e-06 1.1052981177765e-06 1.14537905708102e-05 1.2636776064523e-05 4.42460267775354e-06 3.81928421189836e-05 -4.54674639910443e-06 -1.01626784190117e-06 -1.85111579834057e-06 1.27001968863127e-05 -8.08538553527107e-06 -4.54674639910443e-06 1.48763238532256e-05 5.58841209610883e-06 -1.46561730534431e-06 -1.89624246837512e-06 1.1052981177765e-06 -1.01626784190117e-06 5.58841209610883e-06 5.12476171779417e-05 2.06604797996944e-05 1.33431247201903e-05 1.14537905708102e-05 -1.85111579834057e-06 -1.46561730534431e-06 2.06604797996944e-05 0.000106638877785951 1.12915944225637e-05 1.2636776064523e-05 1.27001968863127e-05 -1.89624246837512e-06 1.33431247201903e-05 1.12915944225637e-05 0.000149700611207483 0 0 0 0 231 0 0 0 0 231 0 0 0 0 0 0 0 0 1355 0 0 0 0 0 1168 +325 433 0.990360099246878 -0.0693584515354243 0.119901121847638 0.28415841763915 0.0792935109282883 0.993621928715598 -0.0801748208614176 -0.377751170388664 -0.113575582518336 0.0889093244609539 0.989543187071447 0.62462360065489 5.07114434909167e-05 2.50420946197807e-05 -1.26460007472176e-06 2.39486974367899e-06 3.12193839854703e-06 4.34340671159909e-05 2.50420946197807e-05 6.60210140713529e-05 -2.45760964645811e-06 -2.70673049720783e-05 -5.96657057009677e-06 5.55342777047079e-05 -1.26460007472176e-06 -2.45760964645811e-06 2.36935210942499e-05 6.32575367349793e-06 3.71333607349638e-06 -2.77875529229763e-06 2.39486974367899e-06 -2.70673049720783e-05 6.32575367349793e-06 9.17267366920414e-05 4.24003498870216e-05 -1.53738352790394e-06 3.12193839854703e-06 -5.96657057009677e-06 3.71333607349638e-06 4.24003498870216e-05 7.89329937192842e-05 -7.28118330992303e-06 4.34340671159909e-05 5.55342777047079e-05 -2.77875529229763e-06 -1.53738352790394e-06 -7.28118330992303e-06 0.000269651767432045 267 265 0 0 29 267 265 0 0 29 0 0 0 0 0 0 0 0 354 0 0 0 0 0 1393 +325 447 0.224923168737381 -0.970795762721129 0.083457505641123 -0.588204682716086 0.974368800162904 0.224435386661504 -0.0153035447920841 0.261516355126076 -0.00387420110960186 0.0847605114236799 0.996393820870522 -0.142735523686263 4.02844564554359e-05 4.77008352158641e-06 -1.1156205400735e-06 -1.21721729394993e-05 -3.69446016039559e-06 -1.06920677087416e-05 4.77008352158641e-06 5.24299600338335e-05 9.49652906204274e-06 2.11029839869275e-05 -1.38718972776183e-05 2.38090236069468e-05 -1.1156205400735e-06 9.49652906204274e-06 2.10415082115283e-05 4.05619705029569e-06 -1.87374982210554e-05 -6.73277134482711e-06 -1.21721729394993e-05 2.11029839869275e-05 4.05619705029569e-06 9.00490964523714e-05 2.22152560533808e-05 2.38287172483561e-05 -3.69446016039559e-06 -1.38718972776183e-05 -1.87374982210554e-05 2.22152560533808e-05 0.000127337320995512 2.22050553866315e-05 -1.06920677087416e-05 2.38090236069468e-05 -6.73277134482711e-06 2.38287172483561e-05 2.22050553866315e-05 0.000145005796482093 0 0 0 0 77 0 0 0 0 77 0 0 0 0 0 3024 3087 0 338 0 0 0 0 0 199 +325 434 0.981227778648468 -0.187079866307643 0.0468312932867306 0.240445473463944 0.1890215160041 0.981110299274757 -0.0411515144861984 -0.388033899439115 -0.0382480443435332 0.0492311312008032 0.998054799509819 0.526507481874962 4.67768333961708e-05 9.05027506145435e-06 -1.19716310585541e-05 -1.50240669524936e-06 1.32711666762484e-05 1.40755845425581e-05 9.05027506145435e-06 7.74960381892496e-05 -8.690258069282e-06 2.09080792660021e-06 -4.53544627929698e-06 2.5423038944289e-05 -1.19716310585541e-05 -8.690258069282e-06 1.86549441468834e-05 1.11625110475861e-05 -1.59847205230124e-06 -5.46421384698768e-06 -1.50240669524936e-06 2.09080792660021e-06 1.11625110475861e-05 6.67908570134821e-05 1.21090684803794e-05 1.70026457997509e-05 1.32711666762484e-05 -4.53544627929698e-06 -1.59847205230124e-06 1.21090684803794e-05 6.8140493574846e-05 -9.87692744441714e-07 1.40755845425581e-05 2.5423038944289e-05 -5.46421384698768e-06 1.70026457997509e-05 -9.87692744441714e-07 0.000177373005521458 161 158 0 0 82 161 158 0 0 82 0 0 0 0 0 0 0 0 565 0 0 0 0 0 1192 +326 440 0.734299800578666 -0.678026195280676 0.0329284281942149 -0.127008245680257 0.677099828593582 0.735027518650725 0.0356422354054946 -0.118793116181985 -0.0483696701319481 -0.00387625326427357 0.998821980971563 -0.0370902099393862 2.6597249283003e-05 4.89040682074749e-06 4.24722117399414e-07 6.09840905362105e-06 -2.33537252367465e-06 -8.5828822882188e-06 4.89040682074749e-06 2.43881138873542e-05 -1.30111672629016e-06 -3.16960554305608e-06 2.38277092148e-06 -1.34611582815125e-06 4.24722117399414e-07 -1.30111672629016e-06 1.52540582570026e-05 6.23064896770604e-06 -6.37770351487615e-06 -1.4410881818955e-07 6.09840905362105e-06 -3.16960554305608e-06 6.23064896770604e-06 4.33206685399135e-05 -3.21520854335555e-06 -8.60684086593014e-06 -2.33537252367465e-06 2.38277092148e-06 -6.37770351487615e-06 -3.21520854335555e-06 0.00011632868862578 -2.55614011672254e-05 -8.5828822882188e-06 -1.34611582815125e-06 -1.4410881818955e-07 -8.60684086593014e-06 -2.55614011672254e-05 0.000102411444256974 0 0 0 0 390 0 0 0 0 323 0 0 0 0 0 366 246 0 1020 0 0 0 0 0 942 +326 441 0.633636270157772 -0.771924767857303 0.0513539668282415 -0.187016293291139 0.771569175048027 0.635396863797354 0.0308518004692484 -0.0992828047112525 -0.0564454183814224 0.0200743180441236 0.9982038551813 -0.086649437238517 2.16444338685216e-05 4.14898673600295e-06 -2.34657638916101e-06 6.21852142687969e-06 5.1269833164778e-06 -7.60440092869212e-06 4.14898673600295e-06 4.11905249578069e-05 -7.01519534568376e-06 -7.50741926183933e-06 -1.14056918447008e-05 7.80627434747204e-06 -2.34657638916101e-06 -7.01519534568376e-06 2.04405684635975e-05 5.49153118749371e-06 -4.59997224452047e-06 -6.35076502470513e-06 6.21852142687969e-06 -7.50741926183933e-06 5.49153118749371e-06 5.9410804182507e-05 3.6210870416627e-05 -1.9036363585016e-05 5.1269833164778e-06 -1.14056918447008e-05 -4.59997224452047e-06 3.6210870416627e-05 0.000163321742711853 -3.6824595935743e-05 -7.60440092869212e-06 7.80627434747204e-06 -6.35076502470513e-06 -1.9036363585016e-05 -3.6824595935743e-05 0.000103834290684995 0 0 0 0 276 0 0 0 0 194 0 0 0 0 0 845 799 0 1020 0 0 0 0 0 782 +325 449 0.0907654353565713 -0.991989924887181 0.0878500123327126 -0.713568397600879 0.995611948486601 0.0883709707626313 -0.0307801812402679 0.405257775666931 0.0227702388051962 0.090258298503771 0.995658051630156 -0.117302292763066 3.67573014522296e-05 1.04611491976397e-05 -4.71866188390354e-06 -5.14026373646704e-06 8.80896136030085e-06 -2.94610786224006e-05 1.04611491976397e-05 4.94837395927565e-05 1.94430056960159e-06 -7.6293640706786e-06 -7.02163904981856e-06 -1.53764138793245e-05 -4.71866188390354e-06 1.94430056960159e-06 1.7188024157662e-05 -7.18627629798949e-07 -1.90724856091919e-06 1.40280385798862e-05 -5.14026373646704e-06 -7.6293640706786e-06 -7.18627629798949e-07 5.67592488093901e-05 5.5694275932197e-07 3.36424384326871e-05 8.80896136030085e-06 -7.02163904981856e-06 -1.90724856091919e-06 5.5694275932197e-07 4.69047962997086e-05 -2.58428666986368e-05 -2.94610786224006e-05 -1.53764138793245e-05 1.40280385798862e-05 3.36424384326871e-05 -2.58428666986368e-05 0.000279706894516488 0 0 0 0 69 0 0 0 0 69 0 0 0 0 0 3111 3238 0 25 1103 0 0 0 0 26 +326 437 0.89111619637675 -0.44049076796966 0.108994531461597 0.0814560035007421 0.439459130600349 0.89759523585693 0.0346188546738317 -0.214666934486779 -0.113082258055894 0.0170492199364415 0.993439342392146 0.199427111005993 3.21460295482419e-05 7.04298994399997e-06 -3.13038040183252e-06 5.84125797312028e-06 1.154493309827e-06 7.11809874761639e-07 7.04298994399997e-06 3.82466442279231e-05 -4.91487934698332e-06 -2.74870373411104e-06 -4.79732030906048e-06 1.68100303963728e-05 -3.13038040183252e-06 -4.91487934698332e-06 1.52454412223247e-05 7.54103840830757e-06 -2.54249486989608e-06 -3.36438105873693e-06 5.84125797312028e-06 -2.74870373411104e-06 7.54103840830757e-06 5.64763150138052e-05 3.04441151271983e-07 6.63233954544481e-06 1.154493309827e-06 -4.79732030906048e-06 -2.54249486989608e-06 3.04441151271983e-07 0.000110587706181393 -1.37323413728821e-06 7.11809874761639e-07 1.68100303963728e-05 -3.36438105873693e-06 6.63233954544481e-06 -1.37323413728821e-06 8.43002691075829e-05 12 12 0 0 252 12 12 0 0 187 0 0 0 0 0 0 0 0 1153 0 0 0 0 0 1135 +326 444 0.347680426498803 -0.928857694216207 0.127834678100123 -0.433336126389908 0.935539790471871 0.352734075011095 0.0185465029025618 0.0785862449611851 -0.0623187088558356 0.113146171925604 0.991622066265734 -0.178285721824858 2.15730648627444e-05 7.1665851703641e-06 9.23096456958293e-07 -1.62274608267756e-06 -3.16546583067023e-06 -5.10031728239973e-06 7.1665851703641e-06 2.47665284505356e-05 -3.14913184251981e-07 4.44435407113075e-06 8.41882293029212e-06 4.4121745051146e-06 9.23096456958293e-07 -3.14913184251981e-07 1.56483812881515e-05 3.15179270620583e-06 -4.2472440315971e-06 -1.41926885380861e-06 -1.62274608267756e-06 4.44435407113075e-06 3.15179270620583e-06 9.5188172035021e-05 4.29486698166466e-05 8.41836908048311e-06 -3.16546583067023e-06 8.41882293029212e-06 -4.2472440315971e-06 4.29486698166466e-05 9.90016329389622e-05 1.9115384737126e-05 -5.10031728239973e-06 4.4121745051146e-06 -1.41926885380861e-06 8.41836908048311e-06 1.9115384737126e-05 8.1434146571198e-05 0 0 0 0 204 0 0 0 0 143 0 0 0 0 0 1999 2008 0 537 0 0 0 0 0 461 +326 446 0.209757661157913 -0.970831065103513 0.116141149535984 -0.587807568404852 0.977395461752718 0.211410210854053 0.00195808371536065 0.201598642599886 -0.0264543934111799 0.113105109418729 0.993230788534379 -0.184464832061061 4.11425255395676e-05 -2.56727392452694e-06 5.85512813589796e-06 6.66931327290806e-06 -1.63013917798581e-05 -6.6559958968815e-06 -2.56727392452694e-06 5.7834718386871e-05 -5.51546883524183e-06 1.59813043385725e-06 2.79524931927293e-05 3.01087567843396e-05 5.85512813589796e-06 -5.51546883524183e-06 1.72813823111111e-05 4.49815806986257e-07 -7.33646609086496e-06 2.1349231024668e-06 6.66931327290806e-06 1.59813043385725e-06 4.49815806986257e-07 3.96566533713471e-05 -1.59810563358141e-05 9.34119033281576e-06 -1.63013917798581e-05 2.79524931927293e-05 -7.33646609086496e-06 -1.59810563358141e-05 6.586475219894e-05 4.71282979366313e-06 -6.6559958968815e-06 3.01087567843396e-05 2.1349231024668e-06 9.34119033281576e-06 4.71282979366313e-06 0.000109805066620621 0 0 0 0 143 0 0 0 0 81 0 0 0 0 0 2699 2743 0 335 0 0 0 0 0 394 +326 435 0.936433220335678 -0.342406360054868 0.0764899238182935 0.186446541283255 0.347823525842776 0.93458955467292 -0.0745731799414075 -0.281725089391147 -0.0459523527368505 0.0964377980371283 0.994277693799724 0.384045005223329 4.34897324690031e-05 1.84610507639049e-05 -9.32947539825985e-06 3.86670132727204e-06 5.58713003192706e-06 3.81559380917592e-05 1.84610507639049e-05 4.28104822688216e-05 -3.24215972344492e-06 -1.33982581859018e-06 -5.45611875866462e-06 2.23521364095653e-05 -9.32947539825985e-06 -3.24215972344492e-06 1.71519472959885e-05 2.42022040725942e-06 1.60702831459886e-06 -5.74359262441381e-06 3.86670132727204e-06 -1.33982581859018e-06 2.42022040725942e-06 4.22189555651408e-05 6.53767058715679e-06 1.32039873703673e-05 5.58713003192706e-06 -5.45611875866462e-06 1.60702831459886e-06 6.53767058715679e-06 9.09228848133897e-05 -2.12196208857307e-06 3.81559380917592e-05 2.23521364095653e-05 -5.74359262441381e-06 1.32039873703673e-05 -2.12196208857307e-06 0.000156359495929222 101 94 0 0 234 101 94 0 0 161 0 0 0 0 0 0 0 0 612 0 0 0 0 0 1275 +326 442 0.535826740727334 -0.841310181239467 0.0713223868384742 -0.264478919876108 0.842677384959699 0.538147194701518 0.0171003424635513 -0.0464638571331075 -0.0527686346138086 0.0509389416625635 0.997306720835317 -0.116841944316337 1.98535086911191e-05 6.16827774135746e-07 4.57119405267716e-07 5.0105837819225e-06 1.02520847258385e-05 -2.81067550100181e-06 6.16827774135746e-07 3.36885366098952e-05 1.23522963370318e-06 -8.11892830922674e-06 -1.83622005834701e-05 4.68013835931406e-06 4.57119405267716e-07 1.23522963370318e-06 1.49285304003333e-05 3.21915057181801e-06 1.48228928683575e-06 -3.50191794613542e-06 5.0105837819225e-06 -8.11892830922674e-06 3.21915057181801e-06 5.63996908947919e-05 4.22289249010972e-05 -2.05889607879501e-05 1.02520847258385e-05 -1.83622005834701e-05 1.48228928683575e-06 4.22289249010972e-05 0.000112358274462996 -3.2967957214508e-05 -2.81067550100181e-06 4.68013835931406e-06 -3.50191794613542e-06 -2.05889607879501e-05 -3.2967957214508e-05 8.18864283367025e-05 0 0 0 0 257 0 0 0 0 197 0 0 0 0 0 1307 1317 0 758 0 0 0 0 0 636 +326 443 0.435953234480578 -0.892597164688531 0.114956856846021 -0.364722556264042 0.897153153341848 0.441126213837368 0.0228884886850764 0.0366119890695467 -0.0711406831194341 0.0931555959430437 0.993106760700881 -0.153238572099749 1.81419547481525e-05 8.2129097181462e-06 -1.33327366622813e-06 1.89131307626594e-07 -1.05841776621797e-06 4.34614083753796e-06 8.2129097181462e-06 2.2860643507108e-05 -2.2675825393436e-06 -1.64836481122381e-06 9.99792405825231e-06 -1.32327922354954e-06 -1.33327366622813e-06 -2.2675825393436e-06 1.65434977421928e-05 5.62689253496152e-06 -7.86090015835344e-06 1.17169391284308e-06 1.89131307626594e-07 -1.64836481122381e-06 5.62689253496152e-06 4.55816592248445e-05 -1.5952954150204e-05 1.36710091398328e-05 -1.05841776621797e-06 9.99792405825231e-06 -7.86090015835344e-06 -1.5952954150204e-05 6.4606316492043e-05 6.62434837654554e-07 4.34614083753796e-06 -1.32327922354954e-06 1.17169391284308e-06 1.36710091398328e-05 6.62434837654554e-07 7.60664711484742e-05 0 0 0 0 259 0 0 0 0 172 0 0 0 0 0 1688 1706 0 614 0 0 0 0 0 579 +326 433 0.976666731257086 -0.153838500362032 0.149852633817229 0.278149354758596 0.165047052132704 0.98411459408846 -0.065405934626828 -0.298296986296944 -0.137410213004361 0.0886125358426541 0.98654257478004 0.581071333225944 5.30976463297252e-05 3.49615387711451e-05 -5.07616581687448e-06 -1.86679725435169e-06 -6.02329109266322e-06 7.28558296323355e-05 3.49615387711451e-05 5.88442790633825e-05 1.38454392053565e-06 3.76958893402438e-06 -4.86417509042608e-06 8.89537616593484e-05 -5.07616581687448e-06 1.38454392053565e-06 2.6491714052601e-05 1.28474865763556e-05 -2.20120269002868e-06 -9.24404244202157e-06 -1.86679725435169e-06 3.76958893402438e-06 1.28474865763556e-05 7.23798127111863e-05 1.40835786460712e-05 1.35118517548538e-05 -6.02329109266322e-06 -4.86417509042608e-06 -2.20120269002868e-06 1.40835786460712e-05 0.00012599349790408 -1.75384173998495e-05 7.28558296323355e-05 8.89537616593484e-05 -9.24404244202157e-06 1.35118517548538e-05 -1.75384173998495e-05 0.000485692913361283 211 209 0 0 134 211 209 0 0 71 0 0 0 0 0 0 0 0 328 0 0 0 0 0 1513 +326 436 0.908094791267407 -0.40591368427071 0.102946252941929 0.149591970478353 0.410077411542423 0.911780609595059 -0.0221954163990792 -0.24881646606888 -0.0848549740184469 0.062371474956433 0.994439255307275 0.287027050680459 3.14948838919786e-05 7.28749943255471e-06 -3.21330134886759e-06 -6.97339701937182e-07 3.94859194512974e-06 1.33462810649235e-05 7.28749943255471e-06 2.79791928594406e-05 5.49449034361298e-07 2.01759981486192e-07 1.01799024284574e-05 1.02625296064436e-05 -3.21330134886759e-06 5.49449034361298e-07 1.6987427886889e-05 3.95718365564627e-06 -2.27275932113204e-06 -4.44091271114811e-06 -6.97339701937182e-07 2.01759981486192e-07 3.95718365564627e-06 5.09513207935634e-05 2.19812317083898e-05 -1.48638911857735e-06 3.94859194512974e-06 1.01799024284574e-05 -2.27275932113204e-06 2.19812317083898e-05 0.000112470360479528 1.47613132760625e-06 1.33462810649235e-05 1.02625296064436e-05 -4.44091271114811e-06 -1.48638911857735e-06 1.47613132760625e-06 0.000106712606717721 63 41 0 0 271 63 41 0 0 209 0 0 0 0 0 0 0 0 847 0 0 0 0 0 1283 +326 445 0.28027609164529 -0.952961533958044 0.115367357811352 -0.511679313049918 0.959250952365242 0.282535263196871 0.00338163224658596 0.150280399440726 -0.0358179122565465 0.109718457182946 0.993317138337488 -0.184546109231382 3.3322943802463e-05 -4.18058185090611e-06 4.11305501493294e-06 -6.90311501657507e-06 -2.22626498049473e-05 -2.76335077236688e-05 -4.18058185090611e-06 4.50416462576925e-05 -5.25889633215895e-06 6.44292236706332e-06 2.63360856782074e-05 2.89479782983969e-05 4.11305501493294e-06 -5.25889633215895e-06 1.79285657821196e-05 8.33395256463743e-07 -8.31137720155323e-06 -1.4249861889186e-05 -6.90311501657507e-06 6.44292236706332e-06 8.33395256463743e-07 7.12739504594562e-05 1.66407646334806e-05 3.21554233557197e-06 -2.22626498049473e-05 2.63360856782074e-05 -8.31137720155323e-06 1.66407646334806e-05 9.01914089889071e-05 3.58728961313517e-05 -2.76335077236688e-05 2.89479782983969e-05 -1.4249861889186e-05 3.21554233557197e-06 3.58728961313517e-05 0.000177516802337016 0 0 0 0 172 0 0 0 0 125 0 0 0 0 0 2271 2308 0 488 0 0 0 0 0 433 +326 447 0.136002542474082 -0.986297752581741 0.0933812170235153 -0.668029134384637 0.990649004270883 0.136421793057477 -0.00190911395437649 0.263129443297965 -0.0108562782616134 0.0927676540136166 0.995628597214401 -0.199918770345676 8.70578349870828e-05 -7.65655425391347e-06 -2.82255796798951e-06 -3.02353952580767e-05 -1.31899700749489e-05 -4.4996571105598e-05 -7.65655425391347e-06 6.86732882720131e-05 -1.75206838888676e-06 3.17637213786587e-05 9.76708572713441e-06 6.06362943864494e-05 -2.82255796798951e-06 -1.75206838888676e-06 2.08565613281311e-05 -5.57554582645861e-06 -1.86639182505596e-05 -1.67124295022505e-05 -3.02353952580767e-05 3.17637213786587e-05 -5.57554582645861e-06 9.70544385202021e-05 3.91123402074186e-05 6.28749070932307e-05 -1.31899700749489e-05 9.76708572713441e-06 -1.86639182505596e-05 3.91123402074186e-05 0.00011932439173351 6.43206334765338e-05 -4.4996571105598e-05 6.06362943864494e-05 -1.67124295022505e-05 6.28749070932307e-05 6.43206334765338e-05 0.000306001393349653 0 0 0 0 135 0 0 0 0 70 0 0 0 0 0 3016 3076 0 159 0 0 0 0 0 297 +326 434 0.959053682900469 -0.270832058835897 0.082861506272553 0.240327205808809 0.273507157908081 0.961603790825644 -0.0226270643874828 -0.308199712615945 -0.0735518041117354 0.04436378451463 0.996304163764986 0.50231395883213 5.90156509163674e-05 -3.55441356003298e-06 -6.37579993328521e-06 2.31044529240469e-07 -1.04239318210655e-05 1.74599955625316e-05 -3.55441356003298e-06 5.54061127299438e-05 -6.05899104558795e-06 -2.44254020004062e-06 3.91116573640194e-06 1.95292801592738e-05 -6.37579993328521e-06 -6.05899104558795e-06 1.70031814081522e-05 9.89153193964364e-06 1.64101799960916e-06 -3.07971973357396e-06 2.31044529240469e-07 -2.44254020004062e-06 9.89153193964364e-06 6.13212177579755e-05 6.51961907720318e-07 9.43629550689952e-06 -1.04239318210655e-05 3.91116573640194e-06 1.64101799960916e-06 6.51961907720318e-07 0.000105881342107546 -3.00825857723763e-05 1.74599955625316e-05 1.95292801592738e-05 -3.07971973357396e-06 9.43629550689952e-06 -3.00825857723763e-05 0.000157512856676894 95 93 0 0 191 95 93 0 0 127 0 0 0 0 0 0 0 0 542 0 0 0 0 0 1383 +326 448 0.0685228615691158 -0.994390660669804 0.0805719021436823 -0.729258150211424 0.997629315661853 0.0677833200288946 -0.0118815006595774 0.321773491908984 0.00635342226228392 0.0811950460221051 0.996677981359589 -0.165110693422535 4.44565183048026e-05 1.30898701044617e-05 -3.59994649899006e-07 -1.03843179961271e-05 -4.12242542105163e-06 -1.96405820369224e-05 1.30898701044617e-05 5.33317699349152e-05 -2.08924394999057e-06 9.5778381481167e-06 2.90617123979974e-06 -5.29171138062959e-06 -3.59994649899006e-07 -2.08924394999057e-06 1.5815746134222e-05 2.18610067699454e-06 -9.19473946873089e-07 2.75533246017391e-06 -1.03843179961271e-05 9.5778381481167e-06 2.18610067699454e-06 6.74808167133878e-05 -1.96258221438988e-06 1.61978316019867e-05 -4.12242542105163e-06 2.90617123979974e-06 -9.19473946873089e-07 -1.96258221438988e-06 4.80707536432362e-05 1.11321473288334e-05 -1.96405820369224e-05 -5.29171138062959e-06 2.75533246017391e-06 1.61978316019867e-05 1.11321473288334e-05 0.000118289566669273 0 0 0 0 165 0 0 0 0 102 0 0 0 0 0 3089 3223 0 4 394 0 0 0 0 190 +326 431 0.991683854411168 0.0992648973693103 0.0819122277225466 0.307513836489286 -0.097006443579029 0.99479725957461 -0.0311153056709301 -0.299469194820378 -0.0845747172880803 0.0229105323619298 0.99615371539865 0.655364774271089 6.63444658348438e-05 1.38691087055505e-05 -9.81631035173243e-06 7.61374225811964e-06 1.11691241346481e-05 3.8795528063174e-05 1.38691087055505e-05 6.24737544195191e-05 -4.88328907253099e-06 -3.36148417674365e-06 1.2081555514947e-05 2.1748541477235e-05 -9.81631035173243e-06 -4.88328907253099e-06 1.94063698730607e-05 4.79017681200808e-06 -7.83608649727415e-07 -1.02592362017298e-05 7.61374225811964e-06 -3.36148417674365e-06 4.79017681200808e-06 6.08077293741153e-05 -5.47652006712675e-06 1.30278316537841e-05 1.11691241346481e-05 1.2081555514947e-05 -7.83608649727415e-07 -5.47652006712675e-06 0.000105388159782005 -8.53404548774892e-06 3.8795528063174e-05 2.1748541477235e-05 -1.02592362017298e-05 1.30278316537841e-05 -8.53404548774892e-06 0.000211499326231771 268 268 0 0 0 219 219 0 0 0 0 0 0 0 0 0 0 0 234 0 238 203 0 0 1339 +326 432 0.992036537006701 -0.0330439310378232 0.121538503632878 0.280623310319599 0.0409334224066784 0.997173741614366 -0.0629998727370304 -0.294470599766433 -0.119113240967695 0.0674731624897868 0.990585386612279 0.617281454455311 4.79312739601736e-05 2.49315908863728e-05 -7.41967555904628e-06 5.21951688946046e-06 -1.93553836402911e-06 5.58635639033471e-05 2.49315908863728e-05 3.29728394670037e-05 -1.67835941585763e-06 8.74120220278146e-07 1.4666043915816e-06 1.52768985420068e-05 -7.41967555904628e-06 -1.67835941585763e-06 2.26757324808775e-05 7.61036401392685e-06 3.79986254264226e-06 -6.31162260574579e-06 5.21951688946046e-06 8.74120220278146e-07 7.61036401392685e-06 8.74029323717797e-05 3.02324782117028e-05 1.66881561634627e-05 -1.93553836402911e-06 1.4666043915816e-06 3.79986254264226e-06 3.02324782117028e-05 7.99054665260885e-05 -1.18489532519546e-05 5.58635639033471e-05 1.52768985420068e-05 -6.31162260574579e-06 1.66881561634627e-05 -1.18489532519546e-05 0.000266407992181518 216 185 0 0 108 204 185 0 0 54 0 0 0 0 0 0 0 0 346 0 26 0 0 0 1561 +327 440 0.690544114690164 -0.721473236110577 0.0512366591700526 -0.166343232078321 0.721751299583116 0.691962343181241 0.0162227361813584 -0.089579807712256 -0.047158108707421 0.0257776103480744 0.998554769448267 -0.1036168423204 3.61025811000614e-05 7.59925813594352e-06 -2.93391418070439e-06 2.12677021649086e-06 -8.69366605864514e-06 5.8911581649024e-06 7.59925813594352e-06 2.79623555788491e-05 -2.0683476672241e-06 -2.61376973512911e-06 8.93585350386567e-06 8.45214711383573e-06 -2.93391418070439e-06 -2.0683476672241e-06 1.8549183833396e-05 4.50154582506511e-06 -5.22823063572689e-06 -4.93991925522594e-06 2.12677021649086e-06 -2.61376973512911e-06 4.50154582506511e-06 4.20018192525152e-05 4.68115564437691e-06 -4.01107968709234e-07 -8.69366605864514e-06 8.93585350386567e-06 -5.22823063572689e-06 4.68115564437691e-06 0.000103105280251124 -5.8970056582286e-06 5.8911581649024e-06 8.45214711383573e-06 -4.93991925522594e-06 -4.01107968709234e-07 -5.8970056582286e-06 9.79818929473393e-05 0 0 0 0 496 0 0 0 0 455 0 0 0 0 0 366 246 0 966 0 0 0 0 0 760 +327 441 0.586117198592431 -0.807273937735388 0.0691044062803635 -0.243962565820753 0.808700251894702 0.588113814739242 0.0112269095615137 -0.0552429696974237 -0.0497044474831572 0.0493044659849188 0.997546258343109 -0.158435451682049 3.12659544095068e-05 1.10501202922077e-05 -1.73952062473054e-06 3.3707335552015e-06 1.96656235184837e-06 2.80490360659034e-06 1.10501202922077e-05 3.43500440492167e-05 -2.8689834194395e-06 -9.97705369521625e-06 -2.05052468762629e-05 4.51796168973222e-06 -1.73952062473054e-06 -2.8689834194395e-06 1.44748102968576e-05 2.17987415757558e-06 -5.30188181205559e-06 1.17077089276959e-06 3.3707335552015e-06 -9.97705369521625e-06 2.17987415757558e-06 6.02700034301612e-05 5.10201321510722e-05 -8.75831807293379e-06 1.96656235184837e-06 -2.05052468762629e-05 -5.30188181205559e-06 5.10201321510722e-05 0.000181743205870528 -2.37972293040826e-05 2.80490360659034e-06 4.51796168973222e-06 1.17077089276959e-06 -8.75831807293379e-06 -2.37972293040826e-05 0.000150625088165339 0 0 0 0 414 0 0 0 0 377 0 0 0 0 0 845 799 0 773 0 0 0 0 0 672 +327 436 0.880554455443023 -0.457184905179774 0.124923230326476 0.104682426017267 0.464584025210044 0.884766577786701 -0.0367394386353756 -0.190621433237579 -0.0937311822131438 0.0903884135681713 0.991485955610848 0.20394497471837 2.87927350467392e-05 7.00710141243615e-06 -1.58159539459825e-07 5.72728744124238e-06 -4.04250608124587e-06 6.43024429961419e-06 7.00710141243615e-06 3.55776186814576e-05 -2.02057560427351e-06 -4.39538210412077e-06 6.24117079670263e-06 2.31225046272746e-05 -1.58159539459825e-07 -2.02057560427351e-06 1.6917226986711e-05 6.79181918225128e-06 5.93294013252434e-07 -4.16879784291898e-06 5.72728744124238e-06 -4.39538210412077e-06 6.79181918225128e-06 4.56835117188218e-05 5.43154497554847e-06 -1.82994892925792e-06 -4.04250608124587e-06 6.24117079670263e-06 5.93294013252434e-07 5.43154497554847e-06 0.000112139549401407 6.01543979011805e-06 6.43024429961419e-06 2.31225046272746e-05 -4.16879784291898e-06 -1.82994892925792e-06 6.01543979011805e-06 0.000104722800056896 303 284 0 0 397 303 284 0 0 343 0 0 0 0 0 0 0 0 905 0 0 0 0 0 1177 +327 442 0.483161382793193 -0.870501193627746 0.0937163276597964 -0.32293927587123 0.874278209531309 0.485422767761724 0.00153260473545479 -0.00603653011403005 -0.046826173408656 0.0811936477269986 0.995597760670787 -0.182199615982749 2.17187910711224e-05 8.11824872385401e-06 5.05336916612876e-07 8.53338825562116e-06 1.46842197281733e-05 -4.27659271887356e-06 8.11824872385401e-06 2.5161933876541e-05 6.10632815502524e-07 -8.17066220893043e-06 -9.50283019905438e-06 2.01282012065663e-05 5.05336916612876e-07 6.10632815502524e-07 1.41136981033387e-05 -1.05231292770603e-06 -1.03023741372067e-06 -2.39757144900311e-06 8.53338825562116e-06 -8.17066220893043e-06 -1.05231292770603e-06 7.35282493230083e-05 6.57276716683585e-05 -2.59440507552977e-05 1.46842197281733e-05 -9.50283019905438e-06 -1.03023741372067e-06 6.57276716683585e-05 0.000123783151277252 -3.95509868195677e-05 -4.27659271887356e-06 2.01282012065663e-05 -2.39757144900311e-06 -2.59440507552977e-05 -3.95509868195677e-05 9.14148955090923e-05 0 0 0 0 632 0 0 0 0 578 0 0 0 0 0 1307 1317 0 619 0 0 0 0 0 505 +327 439 0.771480556419316 -0.634432000127259 0.0481018532020242 -0.107693542854944 0.634601726272168 0.772719370926262 0.0136170043587298 -0.0999712147740716 -0.0458082970577061 0.0200202649794579 0.998749612721239 -0.0656722855999431 4.53761342146472e-05 -1.28800769107318e-05 -2.5172614442152e-06 -1.35368756063302e-06 1.52091641597301e-05 -3.87695862915994e-05 -1.28800769107318e-05 6.6267429264802e-05 -2.29817440956922e-06 2.99736789041601e-06 -2.71842654604971e-05 5.20589695472548e-05 -2.5172614442152e-06 -2.29817440956922e-06 1.47817275264713e-05 3.84865652293893e-06 -3.78782762084296e-06 1.07821813799438e-06 -1.35368756063302e-06 2.99736789041601e-06 3.84865652293893e-06 4.69208911732042e-05 -8.68259872860981e-06 8.92930872998745e-06 1.52091641597301e-05 -2.71842654604971e-05 -3.78782762084296e-06 -8.68259872860981e-06 0.000112511826306335 -4.64514878240274e-05 -3.87695862915994e-05 5.20589695472548e-05 1.07821813799438e-06 8.92930872998745e-06 -4.64514878240274e-05 0.000161095233568323 50 23 0 0 509 50 23 0 0 458 0 0 0 0 0 0 0 0 1329 0 0 0 0 0 1096 +327 446 0.150749223361192 -0.978202739437436 0.142807815658296 -0.66792268903541 0.988378916578549 0.15199411798362 -0.00221480504677314 0.228687417451098 -0.0195394196180766 0.141482114259993 0.989747959040841 -0.229963537640684 3.85622890285386e-05 1.24534630314393e-05 3.95319369738089e-07 -6.27291278294688e-06 -9.45790718418169e-06 2.54016473995346e-06 1.24534630314393e-05 6.488726467951e-05 -4.14923809303045e-06 1.020314931111e-05 1.53984366987149e-05 3.7509707317923e-05 3.95319369738089e-07 -4.14923809303045e-06 1.90484009345061e-05 1.18161405650191e-06 -7.48658742046152e-06 -5.79293216883198e-06 -6.27291278294688e-06 1.020314931111e-05 1.18161405650191e-06 6.76638545696239e-05 -9.96225731250501e-06 1.0228026973286e-05 -9.45790718418169e-06 1.53984366987149e-05 -7.48658742046152e-06 -9.96225731250501e-06 7.43481143075894e-05 1.01594810756611e-05 2.54016473995346e-06 3.7509707317923e-05 -5.79293216883198e-06 1.0228026973286e-05 1.01594810756611e-05 0.000161290222337588 0 0 0 0 256 0 0 0 0 222 0 0 0 0 0 2588 2626 0 188 0 0 0 0 0 238 +327 435 0.911683115851645 -0.39702201916983 0.105865067729383 0.15577458983566 0.406277970483785 0.909519007261475 -0.0878258853054043 -0.229218760112744 -0.0614174809855673 0.123080021629882 0.990494422652129 0.297921706076966 6.05831729789479e-05 -3.08731779642713e-05 -1.39912463349441e-06 -2.93324428573697e-06 -1.52349575920732e-05 -3.30705107063801e-05 -3.08731779642713e-05 0.000105665695961 -9.18327068260592e-06 -1.95182475697457e-06 2.77554668275964e-05 8.59866781380086e-05 -1.39912463349441e-06 -9.18327068260592e-06 1.71555378362102e-05 6.71995667278742e-06 -1.29670820827726e-06 -5.15014964608871e-06 -2.93324428573697e-06 -1.95182475697457e-06 6.71995667278742e-06 4.48183712592129e-05 2.11545703446207e-06 1.63572245001631e-05 -1.52349575920732e-05 2.77554668275964e-05 -1.29670820827726e-06 2.11545703446207e-06 6.84975057160039e-05 4.34928121144321e-05 -3.30705107063801e-05 8.59866781380086e-05 -5.15014964608871e-06 1.63572245001631e-05 4.34928121144321e-05 0.000210720170569077 358 361 0 0 418 358 361 0 0 362 0 0 0 0 0 0 0 0 683 0 0 0 0 0 1289 +327 416 0.957609051495795 0.234528828419816 0.167275620259953 0.304748326612444 -0.248399249442637 0.966325042317281 0.0671842650241855 -0.217189119499316 -0.14588597386198 -0.105887398827876 0.983618392162229 0.6171471385469 0.000170641775164861 4.16505023353228e-05 -3.40296354073238e-05 1.94545593638904e-06 -3.86242331159002e-06 6.27325424465691e-05 4.16505023353228e-05 8.39564275832315e-05 -1.96438620428498e-05 8.86440245197227e-06 6.23120458777906e-06 9.9149566769932e-05 -3.40296354073238e-05 -1.96438620428498e-05 2.77700354941691e-05 -9.01101848892256e-07 6.04428599392127e-06 -1.54488595659841e-05 1.94545593638904e-06 8.86440245197227e-06 -9.01101848892256e-07 7.81222320024011e-05 -1.93357869679858e-07 5.11913234209403e-05 -3.86242331159002e-06 6.23120458777906e-06 6.04428599392127e-06 -1.93357869679858e-07 5.84844253427544e-05 1.43307514988778e-06 6.27325424465691e-05 9.9149566769932e-05 -1.54488595659841e-05 5.11913234209403e-05 1.43307514988778e-06 0.000620576199416978 684 684 0 0 0 644 644 0 0 0 0 0 0 0 0 0 0 0 83 0 436 436 0 0 609 +327 434 0.940239643579721 -0.325852975033803 0.0988395229789139 0.193877297925433 0.331382119198992 0.942400077952996 -0.0454750937258208 -0.241289571101292 -0.0783281795796657 0.0755111365018902 0.994063762818024 0.400549801244645 7.91229708738948e-05 1.1158829634566e-05 -1.63127465453886e-05 4.82136738901302e-07 6.53389900686136e-06 7.71152661108024e-05 1.1158829634566e-05 4.57533935510684e-05 -4.27747739949955e-06 3.87446235346755e-06 7.07174482009765e-07 2.14170755020575e-05 -1.63127465453886e-05 -4.27747739949955e-06 1.70770887134501e-05 4.77366871137922e-06 -1.65582618898919e-07 -1.40306389304863e-05 4.82136738901302e-07 3.87446235346755e-06 4.77366871137922e-06 5.04348273525937e-05 1.4916525626507e-06 1.87175160001794e-05 6.53389900686136e-06 7.07174482009765e-07 -1.65582618898919e-07 1.4916525626507e-06 7.19489429216279e-05 -2.70724611232103e-05 7.71152661108024e-05 2.14170755020575e-05 -1.40306389304863e-05 1.87175160001794e-05 -2.70724611232103e-05 0.000311035708829602 474 472 0 0 315 474 472 0 0 275 0 0 0 0 0 0 0 0 635 0 0 0 0 0 1337 +327 444 0.289216707014637 -0.945020238406089 0.152612074838486 -0.50554614149529 0.955793236381657 0.293912076496081 0.00865913256856474 0.120891522876864 -0.0530375873384898 0.143361223113713 0.988248235028352 -0.243700535804836 4.62743618168807e-05 8.9738948381087e-06 4.15319691049928e-07 -1.76858727554919e-05 -1.94788707850644e-05 4.41891645306461e-07 8.9738948381087e-06 3.23753290931573e-05 -5.41411772840709e-07 5.36203185202335e-06 1.10490243248574e-05 1.17806091055574e-05 4.15319691049928e-07 -5.41411772840709e-07 2.33442457713138e-05 1.3219200735194e-05 -1.74917692734738e-05 8.79339807659326e-07 -1.76858727554919e-05 5.36203185202335e-06 1.3219200735194e-05 0.000142983218616299 4.52442351697404e-05 5.54318779583909e-06 -1.94788707850644e-05 1.10490243248574e-05 -1.74917692734738e-05 4.52442351697404e-05 0.000173594361984127 -2.2493199759271e-06 4.41891645306461e-07 1.17806091055574e-05 8.79339807659326e-07 5.54318779583909e-06 -2.2493199759271e-06 0.000116379011956955 0 0 0 0 401 0 0 0 0 350 0 0 0 0 0 1875 1889 0 370 0 0 0 0 0 319 +327 433 0.963221474009775 -0.211383215864235 0.165896136354441 0.231347593332274 0.226303466815578 0.971034384645029 -0.0766744073619182 -0.231200931455159 -0.144883169877276 0.111397306466293 0.983157925868661 0.478843761161776 5.47047347010828e-05 2.47545938956064e-05 -5.55404619393717e-06 -5.19472185950714e-06 5.40746865132964e-08 4.30669519497594e-05 2.47545938956064e-05 4.80795275431328e-05 -5.06347126793699e-06 -2.50076442609276e-06 4.20999323199652e-06 6.29319333790701e-05 -5.55404619393717e-06 -5.06347126793699e-06 1.85330868060349e-05 5.76676248149193e-06 3.17785831014837e-06 -1.17175081477185e-05 -5.19472185950714e-06 -2.50076442609276e-06 5.76676248149193e-06 6.48756475542612e-05 -2.38492378410529e-06 1.48289312494674e-06 5.40746865132964e-08 4.20999323199652e-06 3.17785831014837e-06 -2.38492378410529e-06 8.19761505259421e-05 3.68805522424145e-06 4.30669519497594e-05 6.29319333790701e-05 -1.17175081477185e-05 1.48289312494674e-06 3.68805522424145e-06 0.000295727212044046 472 469 0 0 261 472 469 0 0 218 0 0 0 0 0 0 0 0 403 0 0 0 0 0 1481 +327 414 0.957253222804636 0.233528365534503 0.170677385499434 0.31274764079513 -0.247462323276014 0.966699634435175 0.0652243462346446 -0.216827180902338 -0.149762031199421 -0.104672437984805 0.983165812433152 0.61610010478524 8.5696561202529e-05 3.57366846251596e-05 -1.80074435794578e-05 2.30099145846361e-05 1.26173915435246e-06 5.8261683658132e-05 3.57366846251596e-05 6.62011204914936e-05 -1.29797594264012e-05 1.6042874430966e-05 -2.64730169377379e-06 2.23719318261738e-05 -1.80074435794578e-05 -1.29797594264012e-05 2.68603890448907e-05 1.14693616944254e-06 9.61582464323772e-06 -1.25348766193414e-05 2.30099145846361e-05 1.6042874430966e-05 1.14693616944254e-06 9.64440861560209e-05 -9.0048742337252e-06 4.20601744808734e-05 1.26173915435246e-06 -2.64730169377379e-06 9.61582464323772e-06 -9.0048742337252e-06 6.40159057674069e-05 2.32413197861847e-06 5.8261683658132e-05 2.23719318261738e-05 -1.25348766193414e-05 4.20601744808734e-05 2.32413197861847e-06 0.00028754213690117 672 672 0 0 0 629 629 0 0 0 0 0 0 0 0 0 0 0 82 0 430 430 0 0 669 +327 432 0.983311241076598 -0.0912797644932625 0.157375372172568 0.256632611500491 0.103605871296027 0.992011176250112 -0.0719697827415073 -0.23475557531045 -0.149548743242432 0.08707370894204 0.984912860412375 0.532996171262742 5.92694898500548e-05 9.57655512350694e-06 -6.85885385928249e-06 1.02132567519454e-06 5.42462988476592e-06 4.7002138293237e-05 9.57655512350694e-06 5.99829106457132e-05 -3.34927567145653e-06 -7.46655383130444e-06 -4.16954753135351e-06 3.74443360605594e-05 -6.85885385928249e-06 -3.34927567145653e-06 1.92891643124952e-05 3.60285092897233e-06 3.06454868604453e-06 -1.12464573733151e-05 1.02132567519454e-06 -7.46655383130444e-06 3.60285092897233e-06 5.81846958580118e-05 1.42891631252515e-05 -6.7690392612835e-06 5.42462988476592e-06 -4.16954753135351e-06 3.06454868604453e-06 1.42891631252515e-05 6.68686720645908e-05 1.6864307085259e-05 4.7002138293237e-05 3.74443360605594e-05 -1.12464573733151e-05 -6.7690392612835e-06 1.6864307085259e-05 0.000332426343818255 580 541 0 0 231 580 541 0 0 192 0 0 0 0 0 0 0 0 356 0 0 0 0 0 1550 +327 430 0.977591765906076 0.163482836823674 0.132618631031706 0.294936287074849 -0.16865208422082 0.985259089298502 0.0286531227383495 -0.231740947963756 -0.125979417845191 -0.0503774653865159 0.99075289414698 0.600633575374645 6.01983689863671e-05 1.7391730283392e-05 -8.00900083650317e-06 -9.76116352190767e-06 8.35284947849091e-06 4.15258200553473e-05 1.7391730283392e-05 6.34465351554894e-05 -6.92860349279808e-06 -4.51521476212775e-06 -1.18338978513914e-06 5.06201123625422e-06 -8.00900083650317e-06 -6.92860349279808e-06 1.75923204684639e-05 6.16403779852761e-06 1.81689759358008e-06 -4.55999911194389e-06 -9.76116352190767e-06 -4.51521476212775e-06 6.16403779852761e-06 8.01716161267245e-05 7.95314372158725e-06 1.42741473884528e-05 8.35284947849091e-06 -1.18338978513914e-06 1.81689759358008e-06 7.95314372158725e-06 6.16791425950469e-05 1.62198875919811e-05 4.15258200553473e-05 5.06201123625422e-06 -4.55999911194389e-06 1.42741473884528e-05 1.62198875919811e-05 0.000208122219686079 649 649 0 0 0 617 617 0 0 0 0 0 0 0 0 0 0 0 132 0 323 293 0 0 915 +327 384 0.957992306279682 0.23483719351924 0.164627560417274 0.301546620823803 -0.248011708190782 0.966616633575174 0.0643620718753514 -0.214666920676024 -0.144017129915947 -0.102487932147176 0.984253671598419 0.611238134712826 6.53579604805182e-05 1.99776245757189e-07 -1.06855129956433e-05 1.7774563846043e-07 -1.87226530495833e-05 -6.63008640016691e-05 1.99776245757189e-07 7.17463217595186e-05 -3.59590322862233e-06 1.51892337878295e-06 8.42664687711432e-06 9.88328341542245e-05 -1.06855129956433e-05 -3.59590322862233e-06 1.54351901174692e-05 2.57318109515522e-06 6.46354484096117e-06 1.05031716401555e-05 1.7774563846043e-07 1.51892337878295e-06 2.57318109515522e-06 8.06019769095667e-05 -1.33230654075849e-05 3.05351774150887e-06 -1.87226530495833e-05 8.42664687711432e-06 6.46354484096117e-06 -1.33230654075849e-05 7.80121323210377e-05 4.19085186006288e-05 -6.63008640016691e-05 9.88328341542245e-05 1.05031716401555e-05 3.05351774150887e-06 4.19085186006288e-05 0.000540492420577301 697 697 0 0 0 655 655 0 0 0 0 0 0 0 0 0 0 0 102 0 482 462 0 0 992 +327 382 0.958042141940496 0.234955812842105 0.164167659049435 0.29411663448319 -0.248666616234677 0.966172634142621 0.0683765676551901 -0.205888446033173 -0.142548827552042 -0.106330649605909 0.984059766842403 0.624502356941894 4.39264586912016e-05 9.15754184492191e-06 -6.76853273032304e-06 9.29453414336663e-06 -2.10728272088013e-08 2.03983574308929e-05 9.15754184492191e-06 4.89269302529876e-05 -3.91005466498486e-06 1.42804071915427e-05 -1.22161624371468e-05 4.27668422497398e-05 -6.76853273032304e-06 -3.91005466498486e-06 1.68244344264903e-05 7.5414003404177e-06 3.17229812716026e-06 8.44411191148818e-07 9.29453414336663e-06 1.42804071915427e-05 7.5414003404177e-06 0.000125417628014372 -3.46402836929277e-05 2.87241929931492e-05 -2.10728272088013e-08 -1.22161624371468e-05 3.17229812716026e-06 -3.46402836929277e-05 8.92253685344132e-05 -4.76151209026855e-06 2.03983574308929e-05 4.27668422497398e-05 8.44411191148818e-07 2.87241929931492e-05 -4.76151209026855e-06 0.00022965050505187 586 586 0 0 0 540 540 0 0 0 0 0 0 0 0 0 0 0 98 0 465 444 0 0 938 +327 383 0.958152195471527 0.234516417327399 0.164153648503508 0.3028131047729 -0.247985037082124 0.966461953281613 0.066743645708534 -0.214692399534189 -0.142995775100069 -0.104658219280714 0.98417420482378 0.615191532839294 0.000122306362088817 3.22204929535701e-05 -2.1700093647822e-05 -2.0654671021465e-05 -4.06866312303123e-06 7.14644832500924e-05 3.22204929535701e-05 7.29742150418575e-05 -1.2585491811277e-05 1.3718181308229e-05 9.50384400920144e-06 3.8760514323381e-05 -2.1700093647822e-05 -1.2585491811277e-05 1.97639297173548e-05 5.71517127135164e-06 2.56727674298275e-06 -1.53767877303424e-05 -2.0654671021465e-05 1.3718181308229e-05 5.71517127135164e-06 8.18507239443914e-05 -6.51961731647125e-06 1.8063888461989e-05 -4.06866312303123e-06 9.50384400920144e-06 2.56727674298275e-06 -6.51961731647125e-06 6.9106877132146e-05 5.6925114893105e-07 7.14644832500924e-05 3.8760514323381e-05 -1.53767877303424e-05 1.8063888461989e-05 5.6925114893105e-07 0.000370137721342338 685 685 0 0 0 646 646 0 0 0 0 0 0 0 0 0 0 0 113 0 481 460 0 0 914 +327 418 0.957097198351746 0.234106393944759 0.170760502521573 0.312852352671371 -0.248334161414178 0.966350437308872 0.0670595003535611 -0.224384141253986 -0.149315428479295 -0.10658812610762 0.983027911196275 0.598616217773056 6.77182158077659e-05 1.73545914548983e-05 -1.36759649978609e-05 2.17240466420284e-06 1.49203906787201e-05 -3.69758793426773e-06 1.73545914548983e-05 6.25416090465303e-05 -1.22805948112989e-05 1.084485520801e-05 3.84349049473499e-06 2.2209441913842e-05 -1.36759649978609e-05 -1.22805948112989e-05 2.2455728109797e-05 1.11450509725331e-07 3.6307200985668e-06 -5.90890136768096e-06 2.17240466420284e-06 1.084485520801e-05 1.11450509725331e-07 7.98896775825618e-05 7.27289551508927e-06 3.58334271105473e-05 1.49203906787201e-05 3.84349049473499e-06 3.6307200985668e-06 7.27289551508927e-06 7.44249965736266e-05 -3.04398252069769e-06 -3.69758793426773e-06 2.2209441913842e-05 -5.90890136768096e-06 3.58334271105473e-05 -3.04398252069769e-06 0.000323234289000832 670 670 0 0 0 629 629 0 0 0 0 0 0 0 0 0 0 0 90 0 403 403 0 0 641 +328 439 0.73872241344612 -0.671960064306771 0.0525249259797576 -0.150451626432682 0.673466239500726 0.739011021565432 -0.0174909764612063 -0.0562007891607336 -0.0270632615382889 0.048294740724593 0.998466423017447 -0.136432440310281 2.99166075589586e-05 1.34308423587371e-06 -1.76242541641376e-06 -6.56972663892394e-07 5.30869830512768e-06 -1.66517729551698e-05 1.34308423587371e-06 2.75241024786757e-05 -1.19289478907096e-06 1.06682798209504e-06 -9.1373343175186e-06 2.06411344269778e-05 -1.76242541641376e-06 -1.19289478907096e-06 1.46721939639896e-05 2.90817058027487e-06 -2.07801766863842e-06 1.33896282851072e-06 -6.56972663892394e-07 1.06682798209504e-06 2.90817058027487e-06 4.10707461860412e-05 9.8293421496673e-06 1.59364884771331e-06 5.30869830512768e-06 -9.1373343175186e-06 -2.07801766863842e-06 9.8293421496673e-06 0.000123368507878517 -4.10697159574045e-05 -1.66517729551698e-05 2.06411344269778e-05 1.33896282851072e-06 1.59364884771331e-06 -4.10697159574045e-05 0.000103469981224001 412 386 0 0 607 412 386 0 0 579 0 0 0 0 0 0 0 0 1223 0 0 0 0 0 978 +328 433 0.952024580787349 -0.259796478087438 0.161725036868245 0.175158238714299 0.278848441378885 0.954161053304311 -0.108720886207637 -0.186097544748872 -0.126066428192594 0.148601730577307 0.980828619766058 0.368277706288286 8.37665178093533e-05 3.9504104610215e-05 -9.63787143824922e-06 -6.28191324645216e-07 1.09489049131623e-05 9.08288726862411e-05 3.9504104610215e-05 6.27489373053279e-05 -3.97766767098665e-06 4.53529605768212e-06 -5.980902899726e-07 8.93933237951041e-05 -9.63787143824922e-06 -3.97766767098665e-06 2.00185507612688e-05 4.67616283663412e-06 -4.33873424728339e-06 -1.656465704346e-05 -6.28191324645216e-07 4.53529605768212e-06 4.67616283663412e-06 6.12871099785883e-05 6.41714151429184e-06 6.12253279206081e-06 1.09489049131623e-05 -5.980902899726e-07 -4.33873424728339e-06 6.41714151429184e-06 7.25367995069676e-05 -3.46225022521991e-06 9.08288726862411e-05 8.93933237951041e-05 -1.656465704346e-05 6.12253279206081e-06 -3.46225022521991e-06 0.000396525979485075 815 812 0 0 350 815 812 0 0 315 0 0 0 0 0 0 0 0 452 0 0 0 0 0 1634 +328 435 0.890271905289324 -0.440018808568779 0.117470774059893 0.110595086039321 0.452319051589969 0.884366622011842 -0.115339297033209 -0.166907268376656 -0.0531357715787502 0.155817604836797 0.986355647726344 0.219417948403854 5.38990285754484e-05 2.73261135272819e-06 -8.46076543979416e-06 -2.77162023751807e-06 1.13686807312354e-05 3.2222808674915e-06 2.73261135272819e-06 4.13595853489881e-05 -1.26403711318119e-06 1.18988020362635e-05 -2.22606911216439e-06 4.12758093429736e-05 -8.46076543979416e-06 -1.26403711318119e-06 1.63820057206465e-05 2.23352607103965e-06 -4.02292989073997e-06 -1.45165917365103e-06 -2.77162023751807e-06 1.18988020362635e-05 2.23352607103965e-06 4.94398637039191e-05 1.13678233120901e-05 4.26994243374524e-05 1.13686807312354e-05 -2.22606911216439e-06 -4.02292989073997e-06 1.13678233120901e-05 7.1019284729002e-05 2.10425856201979e-05 3.2222808674915e-06 4.12758093429736e-05 -1.45165917365103e-06 4.26994243374524e-05 2.10425856201979e-05 0.000205897852578128 795 793 0 0 476 795 793 0 0 440 0 0 0 0 0 0 0 0 649 0 0 0 0 0 1370 +328 440 0.654001263168097 -0.754777045191276 0.0509309319260994 -0.225231689569911 0.756219457489906 0.654092912972985 -0.0171637208142166 -0.0221875087464547 -0.0203587791433288 0.0497400568037724 0.998554678954012 -0.193463494216188 4.62919687597703e-05 9.95283123138381e-06 -1.69634035291087e-06 7.52776271324339e-07 -2.16698418430609e-05 -1.20716521977481e-05 9.95283123138381e-06 2.14636511566468e-05 -2.51496765647629e-06 -1.1023518619075e-06 1.14006630935436e-06 6.08095796994249e-06 -1.69634035291087e-06 -2.51496765647629e-06 1.4157905238546e-05 2.69707034647808e-06 1.03881748564866e-06 -4.03900696104597e-06 7.52776271324339e-07 -1.1023518619075e-06 2.69707034647808e-06 5.42542548490521e-05 5.57925879237154e-05 -8.09594276096299e-06 -2.16698418430609e-05 1.14006630935436e-06 1.03881748564866e-06 5.57925879237154e-05 0.000197686109722561 4.00939680949626e-06 -1.20716521977481e-05 6.08095796994249e-06 -4.03900696104597e-06 -8.09594276096299e-06 4.00939680949626e-06 8.65925358751238e-05 255 213 0 0 754 255 213 0 0 729 0 0 0 0 0 366 246 0 791 0 0 0 0 0 574 +328 434 0.922530604808393 -0.373349531556253 0.0977108513860489 0.146022855777797 0.380956808502761 0.921476143728672 -0.0758526637259825 -0.183077776815237 -0.0617186620662721 0.107200017843575 0.992319990188188 0.298271014193941 5.1443178828412e-05 3.69159258210248e-06 -5.44753660637153e-06 1.68293039141672e-06 8.69500031995631e-06 8.97193934867516e-06 3.69159258210248e-06 2.99328750574642e-05 -1.35864864915701e-07 3.26718450257053e-08 -2.90659093677839e-06 1.85429831292797e-05 -5.44753660637153e-06 -1.35864864915701e-07 1.70824845817519e-05 4.12112077986824e-06 -1.01672457848204e-06 -3.77776805344419e-06 1.68293039141672e-06 3.26718450257053e-08 4.12112077986824e-06 6.16559494380416e-05 6.40086982082403e-06 2.26941221666734e-05 8.69500031995631e-06 -2.90659093677839e-06 -1.01672457848204e-06 6.40086982082403e-06 9.12347015721024e-05 -4.76485836279177e-06 8.97193934867516e-06 1.85429831292797e-05 -3.77776805344419e-06 2.26941221666734e-05 -4.76485836279177e-06 0.000138968129781039 766 770 0 0 381 766 770 0 0 345 0 0 0 0 0 0 0 0 664 0 0 0 0 0 1422 +328 441 0.546121965353901 -0.83481616875213 0.0695180792888242 -0.308423644480439 0.837504961929238 0.545924333198412 -0.0234959819070062 0.021405328285639 -0.0183367854843094 0.0710534081651544 0.9973039534095 -0.235428178389139 2.92992381393592e-05 9.50103937753171e-06 -1.27892166026778e-06 9.96506676595999e-06 1.23791850288151e-05 3.36028777012911e-07 9.50103937753171e-06 2.25155769519879e-05 -2.70695762860863e-06 -5.30194754325119e-06 -1.07963323691523e-05 1.02007493576455e-05 -1.27892166026778e-06 -2.70695762860863e-06 1.41932552426876e-05 4.8863623348861e-06 2.34888360126205e-08 -3.37274266901319e-06 9.96506676595999e-06 -5.30194754325119e-06 4.8863623348861e-06 5.73012763607569e-05 4.65821945878058e-05 -9.53202514427795e-07 1.23791850288151e-05 -1.07963323691523e-05 2.34888360126205e-08 4.65821945878058e-05 0.000144649202455184 2.1499901443536e-06 3.36028777012911e-07 1.02007493576455e-05 -3.37274266901319e-06 -9.53202514427795e-07 2.1499901443536e-06 9.90305749075561e-05 0 0 0 0 637 0 0 0 0 614 0 0 0 0 0 845 799 0 662 0 0 0 0 0 504 +329 435 0.869262493683684 -0.480261408509099 0.117182321924769 0.0667653002757863 0.493292631776201 0.858181524284527 -0.142080437823071 -0.111655183236304 -0.0323279524581004 0.181310371665668 0.982894425976831 0.127408851598232 3.83960029756538e-05 1.11412924892122e-05 -4.88772857775917e-06 5.82331023658204e-07 -1.16080343303277e-06 -6.01066830475817e-06 1.11412924892122e-05 3.53602173030871e-05 5.08919217209186e-07 1.29536107689373e-05 1.36938822655941e-06 2.32566168860811e-05 -4.88772857775917e-06 5.08919217209186e-07 1.78073886902572e-05 3.19461468451371e-06 -3.23231392858643e-06 -3.99059777756139e-06 5.82331023658204e-07 1.29536107689373e-05 3.19461468451371e-06 6.03624292397823e-05 2.69998146906104e-06 3.4750899499118e-05 -1.16080343303277e-06 1.36938822655941e-06 -3.23231392858643e-06 2.69998146906104e-06 8.84101398691207e-05 1.17602872240641e-05 -6.01066830475817e-06 2.32566168860811e-05 -3.99059777756139e-06 3.4750899499118e-05 1.17602872240641e-05 0.000143773134779953 1065 1063 0 0 544 1065 1063 0 0 508 0 0 0 0 0 0 0 0 622 0 0 0 0 0 1284 +329 438 0.76758536750407 -0.633124166169158 0.0998323284625218 -0.136532006201928 0.63818344982813 0.769396001644573 -0.0274167288130858 -0.026974602610416 -0.0594524007850611 0.0847560196443391 0.994626477213904 -0.147455401426276 6.47815243588886e-05 2.65448449600602e-05 -7.48723560211351e-06 5.68173127435213e-06 -8.64090936817683e-06 2.87719437515818e-05 2.65448449600602e-05 3.8702235188618e-05 -4.10303703173679e-06 1.04270499699388e-05 7.65664857918164e-06 5.25868861711646e-05 -7.48723560211351e-06 -4.10303703173679e-06 1.58377688904956e-05 -3.88025427424683e-07 -2.99556545894246e-06 -6.42884786683261e-06 5.68173127435213e-06 1.04270499699388e-05 -3.88025427424683e-07 4.54107431353445e-05 1.04777383903399e-05 2.86658450493875e-05 -8.64090936817683e-06 7.65664857918164e-06 -2.99556545894246e-06 1.04777383903399e-05 0.000130896937527148 8.39226971990619e-06 2.87719437515818e-05 5.25868861711646e-05 -6.42884786683261e-06 2.86658450493875e-05 8.39226971990619e-06 0.000203636088452806 899 899 0 0 398 899 899 0 0 371 0 0 0 0 0 0 0 0 1061 0 0 0 0 0 852 +329 439 0.707065323050812 -0.705050628904521 0.0544264606638224 -0.18972775017773 0.70709741189688 0.705840055914836 -0.0424625194127218 -0.0151031741073352 -0.00847815002138913 0.0685085844802036 0.997614502112281 -0.211996411636981 4.69380572293309e-05 1.21456178543596e-05 -5.45944435991639e-06 5.73593965091447e-06 1.21407444283244e-06 -1.23165026746183e-05 1.21456178543596e-05 3.66467442515478e-05 -3.70463349845709e-06 5.59277232361011e-07 2.59713018881993e-06 3.33414364563614e-05 -5.45944435991639e-06 -3.70463349845709e-06 1.6293964413247e-05 3.84365195988933e-06 -3.67412593167774e-06 -1.00104521270292e-06 5.73593965091447e-06 5.59277232361011e-07 3.84365195988933e-06 5.19181343484109e-05 3.05875434192921e-05 8.03562714688649e-06 1.21407444283244e-06 2.59713018881993e-06 -3.67412593167774e-06 3.05875434192921e-05 0.000182031470917984 -1.55197128166394e-05 -1.23165026746183e-05 3.33414364563614e-05 -1.00104521270292e-06 8.03562714688649e-06 -1.55197128166394e-05 0.000155696443043407 379 355 0 0 585 379 355 0 0 558 0 0 0 0 0 0 0 0 1052 0 0 0 0 0 790 +329 433 0.938441006964916 -0.305227821688451 0.161754299213335 0.133557528752028 0.327016029933317 0.935854713514046 -0.131287742612153 -0.143924301253846 -0.11130585165806 0.176102050132491 0.978058830196736 0.278523368125165 7.48305843294903e-05 4.30667009330975e-05 -1.53709548900143e-05 2.73841946223738e-06 2.26194638452543e-05 8.09251007335866e-05 4.30667009330975e-05 5.20402661975167e-05 -1.02226928747135e-05 -1.61023215107272e-06 2.01377329804886e-05 7.85043205627363e-05 -1.53709548900143e-05 -1.02226928747135e-05 2.3120742575934e-05 1.25339056023695e-06 -7.45079519001204e-06 -2.74153637296662e-05 2.73841946223738e-06 -1.61023215107272e-06 1.25339056023695e-06 5.07272493096556e-05 1.02017414366764e-05 6.36952495855856e-06 2.26194638452543e-05 2.01377329804886e-05 -7.45079519001204e-06 1.02017414366764e-05 8.94480185179611e-05 7.40984660218402e-05 8.09251007335866e-05 7.85043205627363e-05 -2.74153637296662e-05 6.36952495855856e-06 7.40984660218402e-05 0.000289239321178489 1196 1177 0 0 389 1196 1177 0 0 353 0 0 0 0 0 0 0 0 405 0 0 0 0 0 1645 +329 432 0.970924479639503 -0.184300509710256 0.152770995144041 0.155810641687616 0.205297075584354 0.969285709378928 -0.135419069374665 -0.144136378343088 -0.123120938890478 0.162845128003045 0.978939578672963 0.332778918332824 7.67096704561356e-05 2.85867349945443e-06 -9.02274166942399e-06 1.09748836076101e-05 -3.09531575634574e-06 1.06585802997038e-05 2.85867349945443e-06 5.42223879299586e-05 -2.69033541376461e-06 -4.21355500388159e-06 1.1325709572065e-05 4.1012513709796e-05 -9.02274166942399e-06 -2.69033541376461e-06 1.82121014265545e-05 -1.29132996215671e-06 1.33702033588758e-06 -6.68853384266165e-06 1.09748836076101e-05 -4.21355500388159e-06 -1.29132996215671e-06 5.20884622554223e-05 8.11760530923103e-06 2.88376368804843e-07 -3.09531575634574e-06 1.1325709572065e-05 1.33702033588758e-06 8.11760530923103e-06 7.81911167861568e-05 3.51871674895519e-05 1.06585802997038e-05 4.1012513709796e-05 -6.68853384266165e-06 2.88376368804843e-07 3.51871674895519e-05 0.000168312381253779 1397 1372 0 0 274 1397 1372 0 0 240 0 0 0 0 0 0 0 0 352 0 0 0 0 0 1701 +329 441 0.507557807360431 -0.859600413885087 0.05892538193393 -0.374136300220765 0.861415303887826 0.504768246103598 -0.0563266540222489 0.0830550647845341 0.0186747534205127 0.0793482587968047 0.996672015966435 -0.338050661215479 3.88738896848333e-05 1.31074431121517e-05 -1.8411098527111e-06 9.61523412781564e-06 1.30230970139198e-05 -1.00002621893253e-05 1.31074431121517e-05 2.87287034883786e-05 -4.17738298498521e-06 -7.02470234243987e-06 -1.49697323586377e-05 1.32216142000546e-05 -1.8411098527111e-06 -4.17738298498521e-06 1.47885631967726e-05 5.50349131779862e-06 -5.30758686144108e-06 -1.49962840196051e-06 9.61523412781564e-06 -7.02470234243987e-06 5.50349131779862e-06 6.25689700203137e-05 4.40299833419486e-05 -1.61595729233064e-05 1.30230970139198e-05 -1.49697323586377e-05 -5.30758686144108e-06 4.40299833419486e-05 0.000174250389883711 -4.93255916182812e-05 -1.00002621893253e-05 1.32216142000546e-05 -1.49962840196051e-06 -1.61595729233064e-05 -4.93255916182812e-05 0.000120895311710045 0 0 0 0 632 0 0 0 0 604 0 0 0 0 0 807 768 0 564 0 0 0 0 0 364 +329 434 0.904375477812807 -0.41526352246533 0.0982914138698976 0.105630910367393 0.42440855427334 0.899287279352109 -0.105639804312086 -0.136305745543676 -0.0445238609115474 0.1372537653588 0.989534754167008 0.218484635150716 5.00812773758121e-05 1.16070286846368e-05 -6.63689616447445e-06 -5.94165162003282e-06 1.27161499527869e-05 -9.8273807024331e-07 1.16070286846368e-05 3.58483735081642e-05 -2.20010740138266e-06 -4.18865683243419e-06 1.17948185196037e-05 1.89749479291275e-05 -6.63689616447445e-06 -2.20010740138266e-06 1.66211862119836e-05 9.03460916353585e-07 -2.73065414569178e-06 -1.95355019617254e-06 -5.94165162003282e-06 -4.18865683243419e-06 9.03460916353585e-07 4.95091589864202e-05 8.73297113143709e-06 1.39831546922738e-05 1.27161499527869e-05 1.17948185196037e-05 -2.73065414569178e-06 8.73297113143709e-06 0.000123221606288305 2.60883427955602e-05 -9.8273807024331e-07 1.89749479291275e-05 -1.95355019617254e-06 1.39831546922738e-05 2.60883427955602e-05 0.000112457165379582 1272 1276 0 0 442 1272 1276 0 0 409 0 0 0 0 0 0 0 0 629 0 0 0 0 0 1379 +329 440 0.618838403071741 -0.784232509936703 0.0449266206385094 -0.267903030375974 0.785429125871583 0.616893411462441 -0.0504341860926926 0.0167200943268643 0.0118371920749181 0.0664972875582935 0.997716388374558 -0.284499478042079 4.84336863581623e-05 1.50165205687139e-05 -7.77381486808538e-06 9.84366455140839e-06 2.27533701883687e-05 -4.78384270579235e-06 1.50165205687139e-05 3.30306597442601e-05 -7.15051007305269e-06 -9.4828192767848e-06 -1.42533937947436e-05 1.35898965144347e-05 -7.77381486808538e-06 -7.15051007305269e-06 1.94979922166432e-05 1.06472175701988e-06 -1.72731427310055e-06 -2.26253914694662e-06 9.84366455140839e-06 -9.4828192767848e-06 1.06472175701988e-06 6.40550241941003e-05 6.43210451859999e-05 -1.39849535698333e-05 2.27533701883687e-05 -1.42533937947436e-05 -1.72731427310055e-06 6.43210451859999e-05 0.000202504305011523 -5.61684173399302e-05 -4.78384270579235e-06 1.35898965144347e-05 -2.26253914694662e-06 -1.39849535698333e-05 -5.61684173399302e-05 8.59688543518946e-05 107 102 0 0 781 107 102 0 0 752 0 0 0 0 0 366 246 0 710 0 0 0 0 0 541 +329 415 0.980355653721639 0.145148512075319 0.133546627281783 0.192864076169604 -0.145488064422763 0.989333332632071 -0.00726498820626298 -0.138224979899273 -0.133176632058843 -0.0123071680511838 0.991015902136804 0.404446755575645 7.60447311309424e-05 3.87886055000588e-05 -1.2671221868698e-05 6.57386218446255e-06 1.2410050657168e-05 3.96772397008298e-05 3.87886055000588e-05 6.18012405689438e-05 -1.32333060839783e-05 1.52241444056235e-05 1.27299114819032e-05 5.64047580632256e-05 -1.2671221868698e-05 -1.32333060839783e-05 2.17266694149124e-05 1.00461221348994e-06 -4.00001243722461e-06 -1.12116649427478e-05 6.57386218446255e-06 1.52241444056235e-05 1.00461221348994e-06 9.37851926434537e-05 -1.66260415986503e-05 4.74071689788524e-05 1.2410050657168e-05 1.27299114819032e-05 -4.00001243722461e-06 -1.66260415986503e-05 8.03197833252511e-05 1.23065480961745e-05 3.96772397008298e-05 5.64047580632256e-05 -1.12116649427478e-05 4.74071689788524e-05 1.23065480961745e-05 0.000200938639231939 1277 1275 0 10 0 1253 1251 0 10 0 0 0 0 0 0 0 0 0 130 0 264 268 0 0 1139 +329 431 0.992674448069265 -0.0533895448746244 0.108383562630412 0.185037904001774 0.0655466488033802 0.991555717374973 -0.111896810372986 -0.144436450293666 -0.101494221416918 0.11818128379351 0.987791530222795 0.388582223562678 8.13742084689052e-05 2.46047241895477e-05 -1.82905008716178e-05 7.95610877389893e-06 1.28107026423132e-05 1.62156864160613e-05 2.46047241895477e-05 7.85091813789273e-05 -1.47977635483167e-05 1.40185708026975e-05 2.11638365273934e-05 7.82211898941846e-05 -1.82905008716178e-05 -1.47977635483167e-05 1.94887899602528e-05 -1.03570376372956e-06 -1.8022723954232e-06 -1.44945825065757e-05 7.95610877389893e-06 1.40185708026975e-05 -1.03570376372956e-06 6.04632884526154e-05 -2.95278580947505e-06 2.37954792818798e-05 1.28107026423132e-05 2.11638365273934e-05 -1.8022723954232e-06 -2.95278580947505e-06 9.27065816821277e-05 4.74461060428668e-05 1.62156864160613e-05 7.82211898941846e-05 -1.44945825065757e-05 2.37954792818798e-05 4.74461060428668e-05 0.000239636766822288 1294 1266 0 0 178 1294 1266 0 0 145 0 0 0 0 0 0 0 0 314 0 0 0 0 0 1709 +329 430 0.991485800960053 0.0696319373143015 0.110033175908267 0.188486379359307 -0.0656621570649646 0.997067572241265 -0.039303148913112 -0.135673481743394 -0.112447265970225 0.0317434984015235 0.993150523679595 0.388755627731127 9.66762102447251e-05 2.99226664316717e-05 -1.01004105954259e-05 -5.81466471912732e-06 9.37223937622216e-06 1.48558420604214e-05 2.99226664316717e-05 6.4308949549858e-05 -8.3770590138213e-06 9.97296834036778e-06 4.9085916365098e-06 2.37448739848518e-05 -1.01004105954259e-05 -8.3770590138213e-06 1.65060758379182e-05 2.21229550065417e-06 1.02627149370549e-06 -3.18495392964122e-06 -5.81466471912732e-06 9.97296834036778e-06 2.21229550065417e-06 5.61973595652632e-05 3.76590482491053e-07 9.77442432112888e-06 9.37223937622216e-06 4.9085916365098e-06 1.02627149370549e-06 3.76590482491053e-07 5.72587289094744e-05 1.35734044706813e-05 1.48558420604214e-05 2.37448739848518e-05 -3.18495392964122e-06 9.77442432112888e-06 1.35734044706813e-05 0.000164007576101615 1332 1329 0 0 4 1299 1296 0 0 4 0 0 0 0 0 0 0 0 212 0 149 121 0 0 1419 +329 417 0.978720921822061 0.144780591676333 0.145409550792326 0.196813176420788 -0.145554766806781 0.98933568683222 -0.00535804255708591 -0.134813690256589 -0.144634598376733 -0.0159210249064229 0.989357040667488 0.429041656182425 0.000136233512512394 0.000151866214847158 -2.26788593926957e-05 4.43348363181266e-05 -5.40604961817434e-06 0.000235677491867764 0.000151866214847158 0.000335894537069651 -2.85980051319896e-05 0.000104585406035577 -5.12200254997629e-05 0.000545449230353149 -2.26788593926957e-05 -2.85980051319896e-05 2.16816619241101e-05 -1.13691516721633e-06 7.78069735933523e-07 -2.93334006411735e-05 4.43348363181266e-05 0.000104585406035577 -1.13691516721633e-06 0.000103380899169881 -3.31500133863652e-05 0.00018846472175549 -5.40604961817434e-06 -5.12200254997629e-05 7.78069735933523e-07 -3.31500133863652e-05 8.53126457390872e-05 -9.81994873567084e-05 0.000235677491867764 0.000545449230353149 -2.93334006411735e-05 0.00018846472175549 -9.81994873567084e-05 0.00115354097608328 1383 1381 0 12 0 1360 1358 0 12 0 0 0 0 0 0 0 0 0 123 0 289 292 0 0 1075 +329 384 0.979906912459054 0.14390204620295 0.138110984405903 0.189373760939355 -0.145136270040593 0.989411011901237 -0.0011457081976471 -0.122427402668773 -0.136813398589714 -0.0189222257457718 0.990416096062235 0.417565150160195 7.83559448844796e-05 1.30701370525503e-05 -9.97076757042478e-06 -1.90103190311076e-06 -6.9010811271575e-06 -5.53623686745007e-06 1.30701370525503e-05 4.82670212350851e-05 -4.67628165719894e-06 7.08239957045483e-06 4.72849245360871e-06 3.794083592274e-05 -9.97076757042478e-06 -4.67628165719894e-06 1.53104087960739e-05 4.20096733030254e-06 4.85695397239862e-06 -7.58394234945639e-07 -1.90103190311076e-06 7.08239957045483e-06 4.20096733030254e-06 7.46909126218933e-05 -2.69957294624378e-05 7.27918193859671e-06 -6.9010811271575e-06 4.72849245360871e-06 4.85695397239862e-06 -2.69957294624378e-05 6.99639447666107e-05 8.28867901156641e-06 -5.53623686745007e-06 3.794083592274e-05 -7.58394234945639e-07 7.27918193859671e-06 8.28867901156641e-06 0.000151610142367649 1319 1316 0 9 0 1297 1294 0 9 0 0 0 0 0 0 0 0 0 169 0 334 317 0 0 1548 +329 382 0.979895654613237 0.14377016413641 0.13832803755669 0.18402657829958 -0.145266165112991 0.989392345097778 0.000727141860102156 -0.116160408973474 -0.136756160166409 -0.0208069066924675 0.990386200070675 0.417825496032111 6.66886146636778e-05 1.86467154644159e-05 -1.01937226723348e-05 1.0551397815031e-05 -8.12344762704673e-07 7.02815108892604e-06 1.86467154644159e-05 6.13933254532753e-05 -9.23074777103641e-06 2.30672027717162e-05 -1.08260065796155e-06 7.67833836757637e-05 -1.01937226723348e-05 -9.23074777103641e-06 1.56260797148905e-05 5.01120056547313e-06 -3.85412355714213e-07 -1.42669003780646e-06 1.0551397815031e-05 2.30672027717162e-05 5.01120056547313e-06 0.000133442124765731 -5.70011517073816e-05 5.52492048055196e-05 -8.12344762704673e-07 -1.08260065796155e-06 -3.85412355714213e-07 -5.70011517073816e-05 9.31217749294796e-05 -1.34503534417422e-05 7.02815108892604e-06 7.67833836757637e-05 -1.42669003780646e-06 5.52492048055196e-05 -1.34503534417422e-05 0.000236623087616305 1257 1254 0 6 0 1234 1231 0 6 0 0 0 0 0 0 0 0 0 165 0 296 281 0 0 1550 +329 425 0.979793747612585 0.144218396840076 0.138583065892497 0.192373154965961 -0.145328934831664 0.989381110800414 -0.002125627444671 -0.136428402561966 -0.137418022253195 -0.0180574528718205 0.990348532364138 0.414870824254572 0.00010254989746144 5.85143497134075e-05 -1.63018108785087e-05 1.81148255664859e-05 -6.22653063298021e-06 8.90945426741692e-05 5.85143497134075e-05 0.000118557989649229 -1.66649243314135e-05 2.08231382058263e-05 1.2582883121378e-05 0.00015821258044425 -1.63018108785087e-05 -1.66649243314135e-05 2.00087683843882e-05 -1.88545254239e-06 -6.73730193657219e-07 -1.67679389279047e-05 1.81148255664859e-05 2.08231382058263e-05 -1.88545254239e-06 6.7391445814214e-05 -8.04495410998406e-06 3.74723020716535e-05 -6.22653063298021e-06 1.2582883121378e-05 -6.73730193657219e-07 -8.04495410998406e-06 6.75517391711634e-05 6.76283782199335e-06 8.90945426741692e-05 0.00015821258044425 -1.67679389279047e-05 3.74723020716535e-05 6.76283782199335e-06 0.00047012039466856 1483 1481 0 13 0 1451 1449 0 13 0 0 0 0 0 0 0 0 0 146 0 246 249 0 0 1051 +329 426 0.979177500961813 0.143980590758553 0.143111883136923 0.194609230380725 -0.145658187822415 0.989334172592508 0.00125986546422603 -0.126947372459869 -0.141404080317608 -0.0220790494703864 0.989705714666747 0.415610872040361 6.64234305172998e-05 2.54486429189677e-05 -8.60309115660672e-06 -4.48588107814268e-06 5.58726007004335e-07 7.62382068674186e-06 2.54486429189677e-05 7.43600120140801e-05 -9.11524077958422e-06 1.30629300775462e-05 4.35903278494429e-06 2.75649748617782e-05 -8.60309115660672e-06 -9.11524077958422e-06 1.88732045419478e-05 3.226654002174e-06 3.43896648765274e-06 -6.46719878882045e-06 -4.48588107814268e-06 1.30629300775462e-05 3.226654002174e-06 7.4016806183608e-05 1.25899231188353e-05 1.29931871932254e-05 5.58726007004335e-07 4.35903278494429e-06 3.43896648765274e-06 1.25899231188353e-05 6.34205331592849e-05 6.33957604506466e-06 7.62382068674186e-06 2.75649748617782e-05 -6.46719878882045e-06 1.29931871932254e-05 6.33957604506466e-06 0.000135988321499111 1287 1283 0 7 0 1253 1249 0 7 0 0 0 0 0 0 0 0 0 163 0 230 233 0 0 1232 +329 387 0.979716615875353 0.143871554343071 0.139485943480535 0.187177912722163 -0.145472567901122 0.98936143525594 0.00129708001326672 -0.122131606670982 -0.137815400322315 -0.0215621492253413 0.990223201684744 0.424174506115621 8.20121393105372e-05 5.10114431547444e-05 -1.17444388239798e-05 1.04261358641943e-05 -3.50179483400437e-06 4.51420586115559e-05 5.10114431547444e-05 7.10147994929808e-05 -1.30197843408808e-05 1.44595905370123e-05 3.50817153585044e-06 6.65408610368102e-05 -1.17444388239798e-05 -1.30197843408808e-05 1.86252380776386e-05 -1.52168748078238e-07 -1.97279160711839e-06 -1.23156008418331e-05 1.04261358641943e-05 1.44595905370123e-05 -1.52168748078238e-07 0.000102662876259431 -3.55857748625092e-05 -1.44494283536461e-05 -3.50179483400437e-06 3.50817153585044e-06 -1.97279160711839e-06 -3.55857748625092e-05 8.38282245632234e-05 1.20787363022417e-05 4.51420586115559e-05 6.65408610368102e-05 -1.23156008418331e-05 -1.44494283536461e-05 1.20787363022417e-05 0.000228375781312545 1281 1278 0 7 0 1254 1251 0 7 0 0 0 0 0 0 0 0 0 150 0 335 317 0 0 1498 +329 424 0.979984271543697 0.144354795084575 0.137085814959314 0.192979881622034 -0.14585156855926 0.989306089504973 0.000883864911006751 -0.13389676100546 -0.13549224138589 -0.0208603548499964 0.990558780749411 0.404969462117652 0.000161020919753807 6.24032431749464e-05 -2.71531788122779e-05 3.47835431516643e-05 -2.54760850984887e-05 6.9897995986208e-05 6.24032431749464e-05 9.41934875360377e-05 -1.6919172011106e-05 1.36787930614625e-05 -2.16897403277313e-06 6.480314823016e-05 -2.71531788122779e-05 -1.6919172011106e-05 2.27150196827218e-05 -2.09144689658639e-06 5.17540933653254e-06 -1.27911952739312e-05 3.47835431516643e-05 1.36787930614625e-05 -2.09144689658639e-06 9.8451852754611e-05 -3.03999310962428e-05 5.76687255636199e-06 -2.54760850984887e-05 -2.16897403277313e-06 5.17540933653254e-06 -3.03999310962428e-05 7.87399593188989e-05 -7.46491409146539e-06 6.9897995986208e-05 6.480314823016e-05 -1.27911952739312e-05 5.76687255636199e-06 -7.46491409146539e-06 0.000215759662383422 1343 1341 0 9 0 1313 1311 0 9 0 0 0 0 0 0 0 0 0 160 0 244 247 0 0 1053 +330 435 0.84647491869473 -0.520518836516824 0.11198371690528 0.021438489231914 0.531722463094921 0.837271538683728 -0.127466045480561 -0.0810025062437945 -0.0274123012718644 0.167441068263896 0.985500915472749 0.0352204820183337 7.02027714573426e-05 1.06914399131411e-05 -9.52423349331934e-06 -1.68787586549128e-06 2.90860475716537e-06 1.43961021199436e-05 1.06914399131411e-05 3.75760776896902e-05 -3.72269019533465e-06 1.1561600221053e-05 8.32857941151802e-06 3.33332573350396e-05 -9.52423349331934e-06 -3.72269019533465e-06 1.98947690176805e-05 2.35785122081716e-06 -2.39129354507024e-06 -1.22138058071091e-05 -1.68787586549128e-06 1.1561600221053e-05 2.35785122081716e-06 5.53887284980287e-05 1.0373022524857e-05 2.79220464142297e-05 2.90860475716537e-06 8.32857941151802e-06 -2.39129354507024e-06 1.0373022524857e-05 9.0691197521322e-05 3.16165839067637e-05 1.43961021199436e-05 3.33332573350396e-05 -1.22138058071091e-05 2.79220464142297e-05 3.16165839067637e-05 0.000144508824517564 1480 1461 0 0 509 1480 1461 0 0 467 0 0 0 0 0 0 0 0 661 0 0 0 0 0 1171 +330 433 0.923584821322178 -0.348332155195456 0.160174241000759 0.0852179214476845 0.367812271936749 0.922911900422094 -0.113788209723177 -0.104497757213614 -0.108190620831971 0.164007114833985 0.980508264038516 0.200681616739844 5.9227637584132e-05 3.94362020370244e-05 -4.58464968944749e-06 1.28653527036784e-07 -1.06323424002913e-06 6.69062917765332e-05 3.94362020370244e-05 5.39006600500872e-05 -1.59882057423402e-06 4.25156332874223e-06 -1.29973826039805e-06 6.88738268669235e-05 -4.58464968944749e-06 -1.59882057423402e-06 1.9188379315017e-05 2.89745296833431e-06 2.98744805836305e-08 -1.27874052719963e-05 1.28653527036784e-07 4.25156332874223e-06 2.89745296833431e-06 4.59588545211093e-05 3.34099740994663e-06 1.21426932823737e-05 -1.06323424002913e-06 -1.29973826039805e-06 2.98744805836305e-08 3.34099740994663e-06 7.95367207732649e-05 -5.91818393618906e-06 6.69062917765332e-05 6.88738268669235e-05 -1.27874052719963e-05 1.21426932823737e-05 -5.91818393618906e-06 0.000224550437384887 1446 1439 0 0 393 1446 1439 0 0 362 0 0 0 0 0 0 0 0 423 0 0 0 0 0 1546 +330 434 0.884818297942299 -0.455969507142709 0.0958560805714864 0.0636732139151011 0.463932382594297 0.881226881107066 -0.0905865795506797 -0.104553730831345 -0.0431662368856913 0.124623402980128 0.99126468888122 0.130336942519494 7.66385810808532e-05 2.46279542145067e-05 -5.17931425844424e-06 -1.7716197379786e-05 7.29728522393325e-06 2.26726458380352e-05 2.46279542145067e-05 3.9510999132537e-05 -2.9289231407812e-06 6.5370074948192e-07 -1.63806146399712e-05 2.38440669995597e-05 -5.17931425844424e-06 -2.9289231407812e-06 1.62860069034565e-05 4.64047213106183e-06 -2.10725753620306e-06 -3.23605750730322e-06 -1.7716197379786e-05 6.5370074948192e-07 4.64047213106183e-06 5.53970347431943e-05 -2.40207068932547e-05 1.27287311233891e-05 7.29728522393325e-06 -1.63806146399712e-05 -2.10725753620306e-06 -2.40207068932547e-05 0.000215628524808978 -3.4404289767319e-05 2.26726458380352e-05 2.38440669995597e-05 -3.23605750730322e-06 1.27287311233891e-05 -3.4404289767319e-05 0.000116183387717976 1396 1400 0 0 469 1396 1400 0 0 432 0 0 0 0 0 0 0 0 610 0 0 0 0 0 1155 +330 438 0.738021333513481 -0.668308982438647 0.0932073777702411 -0.187864287274223 0.67155463144591 0.740939661276946 -0.00477444555441246 0.00535263797074677 -0.0658702380634167 0.066117488901389 0.995635269262215 -0.234073597157716 8.33907423151982e-05 2.85271041141744e-05 -1.08344378797146e-05 -8.45559008423717e-06 -4.26984900512426e-05 2.53998452254098e-05 2.85271041141744e-05 4.42411496936095e-05 -6.97272066533523e-06 8.3866481495713e-06 3.91726556347644e-06 4.74333299560426e-05 -1.08344378797146e-05 -6.97272066533523e-06 1.49721559712739e-05 3.58472607135578e-06 2.88295993170032e-06 -9.94657764915845e-06 -8.45559008423717e-06 8.3866481495713e-06 3.58472607135578e-06 4.01491132128162e-05 2.49209301816614e-05 1.17112906560932e-05 -4.26984900512426e-05 3.91726556347644e-06 2.88295993170032e-06 2.49209301816614e-05 0.000204297202323887 2.53482621766829e-05 2.53998452254098e-05 4.74333299560426e-05 -9.94657764915845e-06 1.17112906560932e-05 2.53482621766829e-05 0.000194805773845862 546 540 0 0 616 546 540 0 0 595 0 0 0 0 0 0 0 0 981 0 0 0 0 0 854 +330 431 0.989450855610971 -0.099959435095373 0.104857597083531 0.142577725671799 0.109647408510618 0.989787302387033 -0.0910963327489405 -0.105479819868944 -0.0946807801912504 0.101632708164321 0.990306186234117 0.301788735188969 8.9840132971098e-05 3.57722699825665e-05 -1.86779799258431e-05 5.4679513171873e-06 2.56169705562143e-05 3.73014537279455e-05 3.57722699825665e-05 9.19307794153314e-05 -1.13611414087654e-05 1.85621054735058e-05 2.00264979159948e-05 8.76824661407878e-05 -1.86779799258431e-05 -1.13611414087654e-05 1.96864844123872e-05 1.87543315237353e-06 -9.54796725887055e-06 -1.79699041564709e-05 5.4679513171873e-06 1.85621054735058e-05 1.87543315237353e-06 6.06038199000446e-05 -1.24332505139851e-05 1.2422984029469e-05 2.56169705562143e-05 2.00264979159948e-05 -9.54796725887055e-06 -1.24332505139851e-05 9.73672160183179e-05 3.29860668937934e-05 3.73014537279455e-05 8.76824661407878e-05 -1.79699041564709e-05 1.2422984029469e-05 3.29860668937934e-05 0.000190644605576064 1664 1653 0 0 242 1664 1653 0 0 211 0 0 0 0 0 0 0 0 322 0 0 0 0 0 1818 +330 432 0.961481648472327 -0.230513029499085 0.149722352646796 0.105966499595362 0.247772945129157 0.962664944557185 -0.109017302217292 -0.0978061523545219 -0.119002551707774 0.14191528371485 0.982699570028995 0.253128597548342 6.66147653734619e-05 3.31875454456529e-05 -1.20290079498059e-05 -1.05848605822199e-06 1.38154663161927e-05 5.0584375092957e-05 3.31875454456529e-05 7.9791095835244e-05 -1.25640081179713e-05 9.00970864453486e-06 1.45014279034459e-05 0.000103124943163989 -1.20290079498059e-05 -1.25640081179713e-05 2.08588890574436e-05 2.17405330901379e-07 -1.00504708130356e-06 -2.32760370114187e-05 -1.05848605822199e-06 9.00970864453486e-06 2.17405330901379e-07 6.17592189797794e-05 9.72720451262389e-07 1.79869977204561e-05 1.38154663161927e-05 1.45014279034459e-05 -1.00504708130356e-06 9.72720451262389e-07 8.12429838831986e-05 4.46243382758109e-05 5.0584375092957e-05 0.000103124943163989 -2.32760370114187e-05 1.79869977204561e-05 4.46243382758109e-05 0.000291425300735742 1598 1581 0 0 339 1598 1581 0 0 301 0 0 0 0 0 0 0 0 383 0 0 0 0 0 1827 +330 430 0.993744085679053 0.0242189474593956 0.109023551409147 0.141938207325219 -0.0225649161370653 0.999611188530023 -0.0163797535183785 -0.0819192740008775 -0.109377862191721 0.0138171758892568 0.993904205098668 0.329119016208248 8.45524429254393e-05 4.1937299690361e-05 -1.68481855919467e-05 -4.97445711084752e-06 -1.44123910136858e-05 4.78247011843045e-05 4.1937299690361e-05 7.15100584289198e-05 -1.23443515174424e-05 2.63313350822823e-05 -1.77562927768797e-05 5.92966118299408e-05 -1.68481855919467e-05 -1.23443515174424e-05 1.67155710193538e-05 2.90631362084208e-06 5.8246963444123e-06 -9.18121784908397e-06 -4.97445711084752e-06 2.63313350822823e-05 2.90631362084208e-06 8.49701303644005e-05 -2.22168593879303e-05 2.23789536743174e-05 -1.44123910136858e-05 -1.77562927768797e-05 5.8246963444123e-06 -2.22168593879303e-05 8.01028993553845e-05 -2.00153566016826e-05 4.78247011843045e-05 5.92966118299408e-05 -9.18121784908397e-06 2.23789536743174e-05 -2.00153566016826e-05 0.000184357151766506 1828 1823 0 14 44 1786 1788 0 14 17 0 0 0 0 0 0 0 0 257 0 90 62 0 0 1657 +330 416 0.986486440911629 0.100270738771392 0.129577316084823 0.137025241542396 -0.103379262222665 0.99448851791645 0.0174732903209398 -0.0752330332613941 -0.127111093299539 -0.0306327713173616 0.991415353563588 0.340054054682892 0.000136314978063338 6.67639075165093e-05 -2.68096820758192e-05 8.43038793363094e-06 1.42099781215127e-05 7.45313602377965e-05 6.67639075165093e-05 7.28127403706056e-05 -1.95417387737722e-05 2.25503435561749e-05 1.23198557551492e-05 7.76989350448832e-05 -2.68096820758192e-05 -1.95417387737722e-05 2.15744875759726e-05 3.58084247265197e-06 -6.61165147344835e-06 -1.5504881249512e-05 8.43038793363094e-06 2.25503435561749e-05 3.58084247265197e-06 0.000115842267088804 -6.78505986000185e-05 1.31119037377991e-05 1.42099781215127e-05 1.23198557551492e-05 -6.61165147344835e-06 -6.78505986000185e-05 0.000116462465317161 2.58222165191695e-05 7.45313602377965e-05 7.76989350448832e-05 -1.5504881249512e-05 1.31119037377991e-05 2.58222165191695e-05 0.000172510384807978 1763 1761 0 40 0 1731 1729 0 40 0 0 0 0 0 0 0 0 0 175 0 220 223 0 0 1421 +330 384 0.986177289115001 0.0992848289468531 0.132653221501712 0.137970701296137 -0.102669728448173 0.994535773580522 0.0189082502884544 -0.0679453152224632 -0.13005107186858 -0.032266357240732 0.990982139544526 0.343603029871192 8.26681165876175e-05 4.47729301896928e-05 -1.39970015713336e-05 2.12359065232697e-05 -1.52302789138613e-05 4.71790571488169e-05 4.47729301896928e-05 6.16825571816102e-05 -1.23553703474631e-05 2.78653008525329e-05 -1.04629076373572e-05 6.53173752655932e-05 -1.39970015713336e-05 -1.23553703474631e-05 1.75396812074228e-05 1.05101609583281e-06 7.02251453069136e-07 -1.26729631807695e-05 2.12359065232697e-05 2.78653008525329e-05 1.05101609583281e-06 0.000192809796633769 -0.000113705390789141 4.64342410303419e-06 -1.52302789138613e-05 -1.04629076373572e-05 7.02251453069136e-07 -0.000113705390789141 0.000131035278827839 -1.60043660329521e-06 4.71790571488169e-05 6.53173752655932e-05 -1.26729631807695e-05 4.64342410303419e-06 -1.60043660329521e-06 0.00017086833791586 1851 1848 0 37 0 1816 1813 0 37 0 0 0 0 0 0 0 0 0 198 0 265 246 0 0 1835 +330 417 0.986051148982061 0.0991930918491205 0.133655759773264 0.149645137898852 -0.102697912415278 0.994520027500176 0.0195717573710785 -0.0859730664609836 -0.130981946758705 -0.0330249213543422 0.990834539261142 0.340291560060793 7.01373160737077e-05 2.77911271614198e-05 -1.28716783151534e-05 1.82843637416231e-06 1.22711219571235e-06 2.83285499707311e-05 2.77911271614198e-05 5.71615087367054e-05 -1.29212864108344e-05 4.21818900867961e-06 1.57507086560727e-05 5.97612257061644e-05 -1.28716783151534e-05 -1.29212864108344e-05 1.88727831724277e-05 5.92174765831915e-06 2.1128462014729e-06 -6.73727206363407e-06 1.82843637416231e-06 4.21818900867961e-06 5.92174765831915e-06 6.20927765301593e-05 -1.98920708342258e-05 -5.50101068462738e-06 1.22711219571235e-06 1.57507086560727e-05 2.1128462014729e-06 -1.98920708342258e-05 8.55372602250847e-05 2.39216909235915e-05 2.83285499707311e-05 5.97612257061644e-05 -6.73727206363407e-06 -5.50101068462738e-06 2.39216909235915e-05 0.000174534636906858 1838 1841 0 40 0 1802 1805 0 40 0 0 0 0 0 0 0 0 0 170 0 221 225 0 0 1353 +330 379 0.986012390795456 0.0998957789983127 0.133418134210272 0.134518434800525 -0.10348032937685 0.994426536505485 0.0201912091208985 -0.070175401065828 -0.130657516545695 -0.0337149348512719 0.99085413484432 0.346487688620345 4.90821283812911e-05 1.4636340932628e-05 -7.48681498872571e-06 2.43666009480633e-08 1.23867519607812e-06 5.68461442547433e-06 1.4636340932628e-05 4.20972425587743e-05 -7.65763454846492e-06 9.55892997820214e-06 3.42556391876668e-06 4.5290620356319e-05 -7.48681498872571e-06 -7.65763454846492e-06 1.60448919068326e-05 6.27064326337219e-07 3.39668912866838e-06 -7.35035702976672e-06 2.43666009480633e-08 9.55892997820214e-06 6.27064326337219e-07 9.19234262338805e-05 -4.65575167735093e-05 2.32921364226364e-05 1.23867519607812e-06 3.42556391876668e-06 3.39668912866838e-06 -4.65575167735093e-05 7.89590339562885e-05 -4.1308369723598e-06 5.68461442547433e-06 4.5290620356319e-05 -7.35035702976672e-06 2.32921364226364e-05 -4.1308369723598e-06 0.00013102471827627 1758 1755 0 38 0 1723 1720 0 38 0 0 0 0 0 0 0 0 0 198 0 272 250 0 0 1818 +330 383 0.986083217015722 0.0994384299380861 0.133236210436103 0.137440862680267 -0.103207837033137 0.994423670656243 0.0216726928069592 -0.0726963855636477 -0.130338142900942 -0.0351220997380819 0.990847317509172 0.345984761616508 5.58867605734615e-05 2.03883690151333e-05 -5.98412398730078e-06 6.21271779002584e-06 -6.60190250020435e-06 2.52629270236891e-05 2.03883690151333e-05 4.38211440962531e-05 -6.33558837730058e-06 1.03538791074285e-05 5.13948967747748e-06 4.37532073546389e-05 -5.98412398730078e-06 -6.33558837730058e-06 1.41293346424997e-05 3.76486422323144e-06 1.31494513777025e-06 -7.57662690550113e-06 6.21271779002584e-06 1.03538791074285e-05 3.76486422323144e-06 0.00011728783105283 -5.26462208609611e-05 -1.35622232875736e-05 -6.60190250020435e-06 5.13948967747748e-06 1.31494513777025e-06 -5.26462208609611e-05 9.54405901800282e-05 2.15321456671737e-05 2.52629270236891e-05 4.37532073546389e-05 -7.57662690550113e-06 -1.35622232875736e-05 2.15321456671737e-05 0.000134031039342277 1775 1774 0 40 0 1740 1739 0 40 0 0 0 0 0 0 0 0 0 195 0 267 247 0 0 1805 +330 415 0.98590818826968 0.0991916563596539 0.134707310905628 0.154944589203121 -0.102647553684905 0.99453747423774 0.0189391673344222 -0.0924943063486928 -0.132092861371467 -0.0324996560819512 0.990704420263306 0.340125156519141 6.87698081293207e-05 3.06973109171087e-05 -1.46927004727462e-05 1.7869277416797e-06 8.62800865978525e-06 3.45705008598945e-05 3.06973109171087e-05 4.90307297531246e-05 -1.03389657289051e-05 1.11844672504196e-05 6.91956746875445e-06 4.57094536387902e-05 -1.46927004727462e-05 -1.03389657289051e-05 1.95545057589255e-05 4.11565912303053e-06 -1.7645627849671e-06 -1.0070843121181e-05 1.7869277416797e-06 1.11844672504196e-05 4.11565912303053e-06 7.46881875891546e-05 -3.57737580363909e-05 8.3260247096771e-06 8.62800865978525e-06 6.91956746875445e-06 -1.7645627849671e-06 -3.57737580363909e-05 8.61219176408542e-05 1.07708687029352e-05 3.45705008598945e-05 4.57094536387902e-05 -1.0070843121181e-05 8.3260247096771e-06 1.07708687029352e-05 0.000175103864878452 1782 1782 0 44 0 1753 1753 0 44 0 0 0 0 0 0 0 0 0 154 0 177 181 0 0 1437 +330 413 0.986371863520166 0.0996278390233368 0.130938308173335 0.144599846245429 -0.103148575502098 0.994457356496311 0.0203700142920471 -0.0812530755708198 -0.128183143305363 -0.0335985089239131 0.991181225594213 0.339752728529988 0.00014187257173397 8.90779878140446e-05 -1.98532834480511e-05 2.46997894957889e-05 -2.05805514224224e-05 0.000153836078172954 8.90779878140446e-05 0.00011731935647461 -2.02108259459893e-05 2.68371924364305e-05 -3.28818209360822e-06 0.000182284213323907 -1.98532834480511e-05 -2.02108259459893e-05 1.74617840350662e-05 2.75222100573097e-06 1.48586913313503e-06 -2.68463105109513e-05 2.46997894957889e-05 2.68371924364305e-05 2.75222100573097e-06 7.59457333497629e-05 -2.78905660818468e-05 4.05226308558273e-05 -2.05805514224224e-05 -3.28818209360822e-06 1.48586913313503e-06 -2.78905660818468e-05 7.27123260946055e-05 -1.88944749712374e-05 0.000153836078172954 0.000182284213323907 -2.68463105109513e-05 4.05226308558273e-05 -1.88944749712374e-05 0.000405636614338053 2059 2059 0 41 0 2038 2038 0 41 0 0 0 0 0 0 0 0 0 165 0 173 180 0 0 1394 +330 418 0.986238234461164 0.0994258020884447 0.132093356252293 0.148833457374763 -0.103270709909295 0.994397280212452 0.0225656726225505 -0.0804991009468273 -0.129109664091253 -0.0358965038011686 0.990980391154687 0.333876661739432 8.19546794181401e-05 3.82840168647179e-05 -1.67226913923942e-05 2.43993118753018e-06 6.98252024022773e-06 4.85675943869981e-05 3.82840168647179e-05 4.91908778494902e-05 -1.32939939152072e-05 1.04289055495333e-05 4.38177402672785e-06 4.36071880696239e-05 -1.67226913923942e-05 -1.32939939152072e-05 1.89467310715176e-05 6.38750907275662e-06 -1.59837585429678e-06 -7.95732101068279e-06 2.43993118753018e-06 1.04289055495333e-05 6.38750907275662e-06 7.00572994945665e-05 -1.82622551731175e-05 9.98883618273768e-06 6.98252024022773e-06 4.38177402672785e-06 -1.59837585429678e-06 -1.82622551731175e-05 6.82371341893178e-05 -2.45083683616008e-07 4.85675943869981e-05 4.36071880696239e-05 -7.95732101068279e-06 9.98883618273768e-06 -2.45083683616008e-07 0.000167099592739592 1737 1738 0 44 0 1701 1703 0 44 0 0 0 0 0 0 0 0 0 184 0 161 169 0 0 1349 +330 385 0.985879110077842 0.100140472269484 0.134217234831328 0.148544226792955 -0.103266905108387 0.994516475275389 0.0165204937925903 -0.0852538860182553 -0.131826881255147 -0.0301474081715223 0.990814214249615 0.342323435077368 6.32839396740774e-05 5.92873612175249e-06 -9.31277033748999e-06 -3.73294721133503e-06 3.1890127142763e-06 -1.51648819918725e-06 5.92873612175249e-06 4.99625545302664e-05 -5.18010133885507e-06 2.87157314547772e-05 -1.17953423958042e-05 3.04290346178648e-05 -9.31277033748999e-06 -5.18010133885507e-06 1.49217114184314e-05 2.2727062713597e-06 1.94510119964793e-06 -5.36454143774178e-07 -3.73294721133503e-06 2.87157314547772e-05 2.2727062713597e-06 0.000110706268012435 -6.37470872886309e-05 2.46168442230409e-05 3.1890127142763e-06 -1.17953423958042e-05 1.94510119964793e-06 -6.37470872886309e-05 9.1233041575292e-05 -9.34593643327415e-06 -1.51648819918725e-06 3.04290346178648e-05 -5.36454143774178e-07 2.46168442230409e-05 -9.34593643327415e-06 9.77160177118946e-05 1352 1351 0 44 0 1327 1326 0 44 0 0 0 0 0 0 0 0 0 186 0 219 202 0 0 1845 +330 419 0.986434646029789 0.0991649658648738 0.130816660472217 0.145730859982174 -0.102994839273141 0.994419943434714 0.0228262827109583 -0.0824671996910479 -0.127823128561246 -0.035990077025745 0.991143764627764 0.335910351914715 7.58272594314754e-05 2.80008627014699e-05 -1.20378637583339e-05 1.12775176767433e-05 1.0475676476173e-05 2.56878927406533e-05 2.80008627014699e-05 6.835067706496e-05 -9.68169416892688e-06 9.3457811249017e-06 1.28762386540796e-05 6.21023672454819e-05 -1.20378637583339e-05 -9.68169416892688e-06 2.02935324531266e-05 -5.52018215611112e-08 -9.8237091186803e-07 -5.81988247889052e-06 1.12775176767433e-05 9.3457811249017e-06 -5.52018215611112e-08 9.67380415456893e-05 -3.50588467480072e-05 6.24218814864783e-06 1.0475676476173e-05 1.28762386540796e-05 -9.8237091186803e-07 -3.50588467480072e-05 7.39085596650305e-05 1.74513612295558e-05 2.56878927406533e-05 6.21023672454819e-05 -5.81988247889052e-06 6.24218814864783e-06 1.74513612295558e-05 0.000169594710293803 1281 1282 0 44 0 1262 1263 0 44 0 0 0 0 0 0 0 0 0 171 0 184 189 0 0 1360 +330 425 0.986703808182811 0.0996230079458677 0.128416709214016 0.142261785292656 -0.102913598250407 0.994504357651699 0.0192321061492159 -0.0848958530333143 -0.125795016644911 -0.0321922179974979 0.99153379916557 0.336776343804818 0.000110403383026986 8.1752123027377e-05 -2.18060431266301e-05 1.59041712064784e-05 -5.22620313095386e-06 9.58744828121514e-05 8.1752123027377e-05 0.000102077855216462 -2.07606378419683e-05 2.92966005835277e-05 -4.95870984951692e-06 0.000109143712908538 -2.18060431266301e-05 -2.07606378419683e-05 1.9221014045342e-05 1.59747886763769e-06 3.87427924817151e-06 -1.91223784110755e-05 1.59041712064784e-05 2.92966005835277e-05 1.59747886763769e-06 6.57316349244353e-05 -1.36927265482482e-05 3.50037856569148e-05 -5.22620313095386e-06 -4.95870984951692e-06 3.87427924817151e-06 -1.36927265482482e-05 6.5991393864345e-05 -7.60363916546732e-06 9.58744828121514e-05 0.000109143712908538 -1.91223784110755e-05 3.50037856569148e-05 -7.60363916546732e-06 0.000238728704019574 1661 1662 0 44 0 1640 1641 0 44 0 0 0 0 0 0 0 0 0 182 0 184 187 0 0 1270 +330 424 0.986029010903753 0.0997082905331239 0.133435551691177 0.148897818239222 -0.103388253488623 0.99442099727719 0.0209224571886334 -0.0873178175831156 -0.130604971944942 -0.034425818410026 0.990836618383708 0.339606321686329 6.46808941850743e-05 3.13140061333414e-05 -1.42436274919223e-05 5.98036075670113e-06 4.26679590563666e-06 2.91470578571348e-05 3.13140061333414e-05 6.67083214700526e-05 -1.18368355317513e-05 2.70063570864142e-05 -3.97635912337101e-06 7.95344033128562e-05 -1.42436274919223e-05 -1.18368355317513e-05 1.7644827718619e-05 2.52885330393426e-06 2.21097552960142e-06 -8.93258939106248e-06 5.98036075670113e-06 2.70063570864142e-05 2.52885330393426e-06 7.47736631183211e-05 -2.10839200229656e-05 3.8028206661537e-05 4.26679590563666e-06 -3.97635912337101e-06 2.21097552960142e-06 -2.10839200229656e-05 6.01186827543833e-05 -4.38179076920233e-06 2.91470578571348e-05 7.95344033128562e-05 -8.93258939106248e-06 3.8028206661537e-05 -4.38179076920233e-06 0.000204996794147809 1914 1915 0 41 0 1892 1893 0 41 0 0 0 0 0 0 0 0 0 191 0 180 184 0 0 1331 +330 426 0.986006860154734 0.0998155769876253 0.1335189960958 0.152097334872193 -0.10314049603612 0.994500196042099 0.0182043442521389 -0.0830988494335372 -0.130967590667408 -0.0317208238047929 0.990879043845372 0.337439681022793 6.73096891347058e-05 2.67090030848165e-05 -1.15147535510137e-05 -1.05379420909704e-05 1.37144527632474e-05 1.79042149829571e-05 2.67090030848165e-05 5.03627103374085e-05 -8.38446649296265e-06 2.03469400695176e-05 6.26860342265644e-06 4.90479891290516e-05 -1.15147535510137e-05 -8.38446649296265e-06 1.85121827486904e-05 6.49733400531564e-06 1.16797849129735e-06 -5.69353467720585e-06 -1.05379420909704e-05 2.03469400695176e-05 6.49733400531564e-06 0.000100897666808856 -1.7112369396227e-05 2.7969229134504e-05 1.37144527632474e-05 6.26860342265644e-06 1.16797849129735e-06 -1.7112369396227e-05 6.78359903448246e-05 7.41886870940616e-06 1.79042149829571e-05 4.90479891290516e-05 -5.69353467720585e-06 2.7969229134504e-05 7.41886870940616e-06 0.000191026079814882 1780 1777 0 43 0 1747 1745 0 43 0 0 0 0 0 0 0 0 0 193 0 163 172 0 0 1335 +330 394 0.986176511337072 0.0981928602138857 0.133469287441184 0.154494584788637 -0.101864094043289 0.994577802861074 0.0209451760741828 -0.0914764949363821 -0.130688923906278 -0.0342513687179779 0.990831594626031 0.338411546443555 6.70929593379553e-05 1.96715044672379e-05 -3.33013615822621e-06 -6.49846266937116e-06 -6.71375328709162e-06 2.22543806843519e-05 1.96715044672379e-05 4.34381704987281e-05 -1.90084195214466e-06 1.32088563166878e-05 2.46060278534985e-06 2.84240812747767e-05 -3.33013615822621e-06 -1.90084195214466e-06 1.43717977469814e-05 2.48312069071137e-06 6.28440967423189e-06 -2.3619691422776e-06 -6.49846266937116e-06 1.32088563166878e-05 2.48312069071137e-06 0.00011180161469405 -4.7000342331279e-05 1.24832877379986e-05 -6.71375328709162e-06 2.46060278534985e-06 6.28440967423189e-06 -4.7000342331279e-05 0.000103067335913496 1.98427436530592e-06 2.22543806843519e-05 2.84240812747767e-05 -2.3619691422776e-06 1.24832877379986e-05 1.98427436530592e-06 9.38203375597961e-05 2045 2050 0 39 0 2024 2030 0 39 0 0 0 0 0 0 0 0 0 106 0 214 194 0 0 1574 +330 386 0.986564130267312 0.0999385874033569 0.12924200407655 0.14314703898207 -0.103155592364307 0.99449457522803 0.0184245381486084 -0.0789519384698516 -0.126689149629597 -0.0315090239430254 0.991441899849047 0.336503711370068 5.40727056538884e-05 1.85207157139075e-05 -9.02725681188783e-06 -1.78109763826181e-06 5.50682355479241e-06 1.16062986856608e-05 1.85207157139075e-05 4.07933501240203e-05 -8.15686025751863e-06 4.51710384275995e-06 4.02374212645783e-06 2.64833130525531e-05 -9.02725681188783e-06 -8.15686025751863e-06 1.60714838568157e-05 4.62067788467107e-06 2.40334720445316e-06 -4.62324743239315e-06 -1.78109763826181e-06 4.51710384275995e-06 4.62067788467107e-06 6.48330256378518e-05 -9.53683966256844e-06 3.33111745124124e-06 5.50682355479241e-06 4.02374212645783e-06 2.40334720445316e-06 -9.53683966256844e-06 6.00317272054456e-05 5.66076513839683e-06 1.16062986856608e-05 2.64833130525531e-05 -4.62324743239315e-06 3.33111745124124e-06 5.66076513839683e-06 9.0434136594781e-05 1821 1821 0 43 0 1799 1799 0 43 0 0 0 0 0 0 0 0 0 194 0 215 195 0 0 1831 +330 422 0.985729827842069 0.0989429104097953 0.136187396561075 0.151187407494735 -0.102248016634894 0.994605447586543 0.0174741730964057 -0.0826828114511826 -0.133723780969111 -0.0311497048270422 0.990528972969753 0.346950938414346 0.000105235553207413 3.8883009935803e-05 -1.77031841878841e-05 4.86968620079716e-07 1.85474883692827e-05 6.8571989650867e-05 3.8883009935803e-05 6.75489657418199e-05 -1.43401725224616e-05 9.91052593975429e-06 1.00414315709792e-05 7.01632448179458e-05 -1.77031841878841e-05 -1.43401725224616e-05 2.27373399696428e-05 2.79557206624945e-06 -9.3581350953188e-07 -1.03547139026618e-05 4.86968620079716e-07 9.91052593975429e-06 2.79557206624945e-06 0.000121138781048894 -4.90110991896852e-05 -1.81267072654182e-06 1.85474883692827e-05 1.00414315709792e-05 -9.3581350953188e-07 -4.90110991896852e-05 9.00839352489259e-05 9.33379491927856e-06 6.8571989650867e-05 7.01632448179458e-05 -1.03547139026618e-05 -1.81267072654182e-06 9.33379491927856e-06 0.000215093990517915 1513 1514 0 42 0 1481 1482 0 42 0 0 0 0 0 0 0 0 0 160 0 221 224 0 0 1340 +330 378 0.986920600078121 0.100189122190855 0.12629279051501 0.132843069423663 -0.103007709118425 0.994552320280976 0.0159716650948485 -0.070619453559845 -0.124004600735684 -0.028771896328779 0.991864424696253 0.337980981442942 6.42159043263807e-05 3.45855013296883e-05 -1.13068723197838e-05 8.56700595647373e-06 5.02556728017427e-07 3.2622966072992e-05 3.45855013296883e-05 5.6683429863674e-05 -8.12004910881646e-06 1.05875339186436e-05 -2.05709372223079e-06 5.97682226962512e-05 -1.13068723197838e-05 -8.12004910881646e-06 1.58551431805356e-05 1.58594960698947e-06 2.15838201303537e-06 -4.92673048652504e-06 8.56700595647373e-06 1.05875339186436e-05 1.58594960698947e-06 6.73740006069612e-05 -2.71586936074134e-05 1.49567833198798e-05 5.02556728017427e-07 -2.05709372223079e-06 2.15838201303537e-06 -2.71586936074134e-05 7.34287106999102e-05 -5.6648425717384e-06 3.2622966072992e-05 5.97682226962512e-05 -4.92673048652504e-06 1.49567833198798e-05 -5.6648425717384e-06 0.000146839464492025 1896 1894 0 40 0 1874 1872 0 40 0 0 0 0 0 0 0 0 0 203 0 218 195 0 0 1747 +330 423 0.986071675046654 0.0994767177934268 0.133293039157087 0.146427903961585 -0.103042505877486 0.994473675559989 0.0201084708691037 -0.0777408187022983 -0.130556093895206 -0.033563242323296 0.990872653327144 0.340878121893493 5.48552440199005e-05 3.0957121389227e-05 -9.65065237080098e-06 -2.84568159605246e-06 1.89125077572237e-05 2.6052735281165e-05 3.0957121389227e-05 5.54668169822563e-05 -1.20824360813692e-05 1.67537032792646e-05 6.9759285391141e-06 4.64585606491251e-05 -9.65065237080098e-06 -1.20824360813692e-05 1.96613634401587e-05 6.62582156818308e-06 -5.22879997299818e-06 -4.8012620368087e-06 -2.84568159605246e-06 1.67537032792646e-05 6.62582156818308e-06 7.85735049370263e-05 -2.95813918953328e-05 3.4709610274553e-06 1.89125077572237e-05 6.9759285391141e-06 -5.22879997299818e-06 -2.95813918953328e-05 7.16459813588529e-05 1.15089007256271e-05 2.6052735281165e-05 4.64585606491251e-05 -4.8012620368087e-06 3.4709610274553e-06 1.15089007256271e-05 0.000158232768926564 1482 1482 0 41 0 1446 1448 0 41 0 0 0 0 0 0 0 0 0 179 0 160 168 0 0 1363 +331 434 0.865053516320238 -0.496064658599727 0.0748483025213536 0.0237067356345672 0.499431242797776 0.865647321768655 -0.0349735333105314 -0.0807091697388375 -0.0474430987548249 0.0676355587179618 0.996581448541688 0.0459130471817832 6.32146135391957e-05 9.72427817227746e-06 -1.26298775082396e-05 1.93991049895532e-07 2.09862173148804e-05 6.23423179744935e-06 9.72427817227746e-06 3.15733905704961e-05 -2.73275086253944e-06 3.65292246298018e-06 2.52569299055397e-06 8.11767521570335e-06 -1.26298775082396e-05 -2.73275086253944e-06 1.68768285828714e-05 4.72718600686034e-06 -1.82175341700963e-06 -6.32406180080501e-06 1.93991049895532e-07 3.65292246298018e-06 4.72718600686034e-06 4.24404295272145e-05 2.83839594155527e-06 6.8651737178435e-06 2.09862173148804e-05 2.52569299055397e-06 -1.82175341700963e-06 2.83839594155527e-06 8.85279650099363e-05 1.87789279204507e-05 6.23423179744935e-06 8.11767521570335e-06 -6.32406180080501e-06 6.8651737178435e-06 1.87789279204507e-05 7.49344081531898e-05 1713 1719 0 0 608 1710 1716 0 0 577 0 0 0 0 0 0 0 0 790 0 0 0 0 0 1298 +330 388 0.98610789571712 0.0992560347113353 0.133189555062461 0.150560630590191 -0.102788983007296 0.994504101758465 0.0199001647710381 -0.0869038193217388 -0.130482347375727 -0.033314128518857 0.990890773932399 0.337664296327347 8.41963354739977e-05 5.94540208929185e-05 -7.45788297871477e-06 -2.64488120941656e-05 8.55253640083727e-06 6.77708350473351e-05 5.94540208929185e-05 0.000114263742328187 -4.04699812418595e-06 -2.18872353357661e-05 1.33445277583869e-05 0.000130798956198761 -7.45788297871477e-06 -4.04699812418595e-06 1.74067386455074e-05 7.33975694648301e-06 1.67674446027961e-06 -7.08434317367819e-06 -2.64488120941656e-05 -2.18872353357661e-05 7.33975694648301e-06 8.48158507348952e-05 -3.6461450768169e-05 -2.51793596019254e-05 8.55253640083727e-06 1.33445277583869e-05 1.67674446027961e-06 -3.6461450768169e-05 6.8744048924191e-05 9.35309215088302e-06 6.77708350473351e-05 0.000130798956198761 -7.08434317367819e-06 -2.51793596019254e-05 9.35309215088302e-06 0.000291947639049392 1349 1347 0 45 0 1323 1321 0 45 0 0 0 0 0 0 0 0 0 200 0 220 203 0 0 1750 +331 431 0.985679413364428 -0.143553279294505 0.088479093990339 0.0803946719772437 0.147563547682934 0.988220895192824 -0.0405519629552037 -0.0484903554026114 -0.081615522204934 0.0530275240614473 0.995252223422349 0.222610271052559 8.36466206914078e-05 2.24584286899703e-07 -1.04091655153886e-05 -6.01422564158406e-06 4.27146894481164e-06 -2.79078585486015e-05 2.24584286899703e-07 9.23650090045692e-05 -3.21903860022393e-06 1.03097924455882e-05 1.91099608224176e-05 5.68253702277699e-05 -1.04091655153886e-05 -3.21903860022393e-06 2.09814273131279e-05 2.67851059915178e-06 6.27474651439375e-06 8.17247834986173e-07 -6.01422564158406e-06 1.03097924455882e-05 2.67851059915178e-06 6.9649095495332e-05 -2.60352920106361e-05 1.28245180654966e-05 4.27146894481164e-06 1.91099608224176e-05 6.27474651439375e-06 -2.60352920106361e-05 8.19208556027427e-05 2.69286606129311e-05 -2.79078585486015e-05 5.68253702277699e-05 8.17247834986173e-07 1.28245180654966e-05 2.69286606129311e-05 0.000130038958158163 1829 1808 0 0 323 1798 1779 0 0 291 0 0 0 0 0 0 0 0 459 0 0 0 0 0 1844 +330 421 0.985995809211511 0.0994314199355778 0.133886731780754 0.15589388515996 -0.10288478784453 0.994509709410937 0.0191091160852564 -0.0882640602690472 -0.131251608171187 -0.0326164163722596 0.990812386244494 0.337975786517256 5.95649494243363e-05 2.76659393560332e-05 -1.3483159377878e-05 1.23412962515417e-05 3.11427801913037e-06 3.37814733362518e-05 2.76659393560332e-05 5.05062324287952e-05 -7.95988615279613e-06 3.10711280057886e-05 -1.77709104603415e-05 5.5365986615749e-05 -1.3483159377878e-05 -7.95988615279613e-06 1.88183053696441e-05 4.51985407206891e-06 -1.90035164964579e-06 -1.08283802715051e-05 1.23412962515417e-05 3.10711280057886e-05 4.51985407206891e-06 9.71360407695763e-05 -5.22644965960627e-05 4.89397949889539e-05 3.11427801913037e-06 -1.77709104603415e-05 -1.90035164964579e-06 -5.22644965960627e-05 0.000104913623265444 -3.39484919283777e-05 3.37814733362518e-05 5.5365986615749e-05 -1.08283802715051e-05 4.89397949889539e-05 -3.39484919283777e-05 0.000192318002897479 1762 1760 0 43 0 1729 1727 0 43 0 0 0 0 0 0 0 0 0 176 0 162 170 0 0 1347 +331 432 0.953059038505314 -0.27420655046528 0.128410423273419 0.0659733685676791 0.28366133451109 0.956923165009322 -0.0619217536244663 -0.0749752473284817 -0.105899558198861 0.0954401590027687 0.98978606760391 0.166769076004404 6.76991708354039e-05 3.4424320910869e-05 -1.11363634162274e-05 -1.21673686388327e-06 2.45261352368676e-05 3.41947457760006e-05 3.4424320910869e-05 7.63392624015531e-05 -7.09290293127804e-06 1.2523207741423e-06 3.7051815800492e-05 7.28705437710477e-05 -1.11363634162274e-05 -7.09290293127804e-06 1.98359149782896e-05 3.76978790289836e-06 -7.90865439853028e-06 -1.11284386192946e-05 -1.21673686388327e-06 1.2523207741423e-06 3.76978790289836e-06 5.32671023529021e-05 -6.46710288703628e-06 1.09037827468086e-05 2.45261352368676e-05 3.7051815800492e-05 -7.90865439853028e-06 -6.46710288703628e-06 0.000119666904369337 6.39047848679745e-05 3.41947457760006e-05 7.28705437710477e-05 -1.11284386192946e-05 1.09037827468086e-05 6.39047848679745e-05 0.000180280564337254 1832 1815 0 0 453 1776 1759 0 0 414 0 0 0 0 0 0 0 0 527 0 0 0 0 0 1881 +331 435 0.824053274865851 -0.558621396088897 0.0942249224704307 -0.0251471166079385 0.565383852673796 0.821449332062002 -0.0745794475081848 -0.0546811192801508 -0.0357393245403684 0.114730687641027 0.992753529328813 -0.0457529261691006 7.06856646017539e-05 -9.92842417434521e-09 -5.75388430917877e-06 -4.49544739448747e-06 -2.71199942167156e-05 -2.06892920876797e-05 -9.92842417434521e-09 4.42492597510271e-05 -2.69204063074535e-06 1.67129769506071e-06 1.46622957332867e-05 1.60378571074699e-05 -5.75388430917877e-06 -2.69204063074535e-06 1.47426063920115e-05 2.54722514178125e-06 -6.94219604010808e-07 -2.79554734843581e-06 -4.49544739448747e-06 1.67129769506071e-06 2.54722514178125e-06 5.42040189491717e-05 1.20335940737125e-06 1.30101499330999e-05 -2.71199942167156e-05 1.46622957332867e-05 -6.94219604010808e-07 1.20335940737125e-06 0.0001198654828022 3.20008661149396e-05 -2.06892920876797e-05 1.60378571074699e-05 -2.79554734843581e-06 1.30101499330999e-05 3.20008661149396e-05 7.21528377841608e-05 1422 1398 0 0 603 1417 1393 0 0 577 0 0 0 0 0 0 0 0 855 0 0 0 0 0 1055 +331 433 0.909712753227304 -0.390819811314577 0.140294624628448 0.0433198726872774 0.402468057339014 0.913030916615217 -0.0662873149745646 -0.0792164379632187 -0.10218693378979 0.116766520838874 0.987888359165056 0.118262335224225 4.92863098615938e-05 1.8445057484267e-05 -3.36436086754965e-06 -5.99015721434962e-06 9.55336513317428e-06 8.89166383624611e-06 1.8445057484267e-05 4.31469091182551e-05 1.96074951827225e-06 5.8720241573203e-07 -9.99408472803143e-06 2.32892191377713e-05 -3.36436086754965e-06 1.96074951827225e-06 2.34223663026927e-05 1.14974133195818e-05 -7.94757979763385e-06 -4.37628045693097e-07 -5.99015721434962e-06 5.8720241573203e-07 1.14974133195818e-05 5.26779657152595e-05 -1.12583963764509e-05 5.77207082329865e-06 9.55336513317428e-06 -9.99408472803143e-06 -7.94757979763385e-06 -1.12583963764509e-05 0.000105605715055277 -6.43464574083111e-06 8.89166383624611e-06 2.32892191377713e-05 -4.37628045693097e-07 5.77207082329865e-06 -6.43464574083111e-06 7.85716289577929e-05 1582 1583 0 0 538 1546 1547 0 0 506 0 0 0 0 0 0 0 0 649 0 0 0 0 0 1598 +331 430 0.996569753641898 -0.0169146548493494 0.0810100029468889 0.0894331860553975 0.0148587793111528 0.999553740023247 0.0259140402662496 -0.051716011793836 -0.0814121784717129 -0.0246214389682189 0.996376355570336 0.24042955325537 6.32754868157909e-05 6.31400056168525e-06 -9.38078971632153e-06 -1.77092728398149e-05 2.04869975571867e-06 -1.41097914065322e-05 6.31400056168525e-06 4.18642021398478e-05 -3.01169786760749e-06 6.63630365345384e-06 6.10321948639039e-06 3.01264775699661e-05 -9.38078971632153e-06 -3.01169786760749e-06 1.47468547707339e-05 5.71568606509298e-06 6.52617681709823e-07 1.36967758918322e-06 -1.77092728398149e-05 6.63630365345384e-06 5.71568606509298e-06 6.59195935579377e-05 -8.95005859010476e-06 1.56054591853518e-05 2.04869975571867e-06 6.10321948639039e-06 6.52617681709823e-07 -8.95005859010476e-06 5.80758317602342e-05 8.6334643829491e-06 -1.41097914065322e-05 3.01264775699661e-05 1.36967758918322e-06 1.56054591853518e-05 8.6334643829491e-06 9.18050445631676e-05 2147 2121 0 22 84 2121 2117 0 22 57 0 0 0 0 0 0 0 0 364 0 41 13 0 0 1732 +331 418 0.992605033933439 0.0582313469503627 0.106509890819317 0.0997186526947207 -0.0659029790379336 0.995368811728994 0.0699837551945891 -0.0464396887424089 -0.101941375132583 -0.0764855468017127 0.991845712379965 0.250597873773572 9.23787317413468e-05 6.89698591577725e-05 -1.5056175336588e-05 1.78185621711547e-05 3.87821573433474e-06 6.02027296816363e-05 6.89698591577725e-05 0.000267377613256709 -1.01603390329827e-05 4.96247901435946e-05 -1.42372160139116e-05 0.000347194688600156 -1.5056175336588e-05 -1.01603390329827e-05 1.93382110050303e-05 3.29503608838382e-06 -9.14199792930577e-07 -3.0315202601935e-06 1.78185621711547e-05 4.96247901435946e-05 3.29503608838382e-06 6.58982734816485e-05 -4.40582058655714e-06 6.1213425112766e-05 3.87821573433474e-06 -1.42372160139116e-05 -9.14199792930577e-07 -4.40582058655714e-06 6.32338604541146e-05 -2.27364422122142e-05 6.02027296816363e-05 0.000347194688600156 -3.0315202601935e-06 6.1213425112766e-05 -2.27364422122142e-05 0.0005668891718263 1944 1962 0 75 1 1914 1940 0 75 3 0 0 0 0 0 0 0 0 260 0 108 109 0 0 1467 +331 415 0.992892475444436 0.0591081712852942 0.103299352820475 0.0999464050165386 -0.0657465073595541 0.995903116613239 0.0620836459146584 -0.0527937379039039 -0.0992064966413025 -0.0684339565372695 0.992710866575366 0.243402148090648 9.44251716948135e-05 4.94538217426483e-05 -1.83023671476384e-05 3.60693162902685e-06 1.05253673543132e-05 2.6255263416387e-05 4.94538217426483e-05 0.000126369459949859 -1.87681354746335e-05 2.29092088165768e-05 9.05777695103447e-06 0.000108172648179611 -1.83023671476384e-05 -1.87681354746335e-05 2.13660476113232e-05 5.01355515126089e-06 -5.03805828199354e-06 -9.43844675672985e-06 3.60693162902685e-06 2.29092088165768e-05 5.01355515126089e-06 7.04122622833461e-05 -1.56858635465406e-05 2.51397815267625e-05 1.05253673543132e-05 9.05777695103447e-06 -5.03805828199354e-06 -1.56858635465406e-05 7.40198675806627e-05 4.18816810420199e-06 2.6255263416387e-05 0.000108172648179611 -9.43844675672985e-06 2.51397815267625e-05 4.18816810420199e-06 0.000224443010651858 1230 1248 0 77 1 1210 1229 0 77 9 0 0 0 0 0 0 0 0 229 0 117 120 0 0 1505 +331 419 0.993223279727464 0.0584871401760101 0.100432918116779 0.100349471958752 -0.0657362149096754 0.995346769419663 0.0704525276706908 -0.0503160305990998 -0.0958450137292954 -0.0765771704875038 0.992446306005196 0.241999844145522 7.78267327826839e-05 2.98294656142876e-05 -1.12402589421549e-05 6.96066163917016e-07 -5.70770271798589e-06 1.71747691604868e-05 2.98294656142876e-05 9.04560099627735e-05 -6.02555778996847e-06 9.96728871931975e-06 -7.12841262700175e-06 5.70095014151011e-05 -1.12402589421549e-05 -6.02555778996847e-06 1.6668239036995e-05 3.15229203760566e-06 8.00876778384173e-07 -5.87076483886617e-07 6.96066163917016e-07 9.96728871931975e-06 3.15229203760566e-06 6.56993683844164e-05 -1.69950503421721e-05 8.21487598011133e-06 -5.70770271798589e-06 -7.12841262700175e-06 8.00876778384173e-07 -1.69950503421721e-05 6.3694582093394e-05 6.16659145508309e-07 1.71747691604868e-05 5.70095014151011e-05 -5.87076483886617e-07 8.21487598011133e-06 6.16659145508309e-07 0.000125464152039598 1838 1854 0 76 1 1822 1839 0 76 10 0 0 0 0 0 0 0 0 243 0 114 119 0 0 1494 +331 425 0.993175170923547 0.0598292216737874 0.100117651265361 0.0906318529048393 -0.066970328087021 0.995327690888283 0.0695540286893282 -0.0428628993417907 -0.0954885072503512 -0.075784246284488 0.992541532127594 0.249733890365926 0.000152281499924585 1.86012495173128e-05 -2.28503506691556e-05 -1.18704027141182e-05 1.5594041274188e-05 -1.20522244344626e-05 1.86012495173128e-05 0.000109327464076869 -4.15643168253735e-06 1.32312653110695e-05 6.62740121692099e-06 0.000128392456716343 -2.28503506691556e-05 -4.15643168253735e-06 1.81655275640242e-05 5.51726716635163e-06 -1.25449988400752e-06 7.51029284353039e-06 -1.18704027141182e-05 1.32312653110695e-05 5.51726716635163e-06 6.39646786153115e-05 -1.46992854132351e-05 2.47856990224067e-05 1.5594041274188e-05 6.62740121692099e-06 -1.25449988400752e-06 -1.46992854132351e-05 6.25961300201395e-05 3.99243598914285e-06 -1.20522244344626e-05 0.000128392456716343 7.51029284353039e-06 2.47856990224067e-05 3.99243598914285e-06 0.000255748760600428 2016 2032 0 77 1 1994 2010 0 76 1 0 0 0 0 0 0 0 0 271 0 119 122 0 0 1399 +331 424 0.992996214308205 0.0589388425985994 0.102394976452513 0.0958011995209067 -0.0661876073820831 0.995425672598795 0.0688979750084988 -0.0466021857649475 -0.0978658214015928 -0.0751927068562772 0.992354945489273 0.247801736463792 0.000103099149722566 3.41791504788263e-05 -1.45314764907128e-05 -2.10902930475993e-06 -7.51149380187658e-06 1.86257355970153e-05 3.41791504788263e-05 8.12956573873067e-05 -9.24314472482531e-06 1.73804078739985e-05 1.07796128840838e-05 8.79994450621613e-05 -1.45314764907128e-05 -9.24314472482531e-06 1.91717855816222e-05 3.20169416806155e-06 3.43869163022364e-06 -2.44441580213509e-06 -2.10902930475993e-06 1.73804078739985e-05 3.20169416806155e-06 5.8114403779185e-05 -6.80402453686883e-06 2.08056209477302e-05 -7.51149380187658e-06 1.07796128840838e-05 3.43869163022364e-06 -6.80402453686883e-06 7.47953826605148e-05 1.23519608258973e-05 1.86257355970153e-05 8.79994450621613e-05 -2.44441580213509e-06 2.08056209477302e-05 1.23519608258973e-05 0.0001901450431547 1883 1901 0 74 0 1850 1870 0 74 0 0 0 0 0 0 0 0 0 266 0 117 119 0 0 1487 +331 426 0.993037098122497 0.0592259991583961 0.101831246560865 0.0966470005566899 -0.0660804217292698 0.995674712613161 0.0653088395761366 -0.0434366109421209 -0.0975228158767571 -0.0715831522523936 0.992655606289049 0.246742642306553 8.53721203535017e-05 2.74698038081381e-05 -1.51579944785682e-05 -9.10967313122193e-06 1.55333297180129e-05 1.1965644115604e-05 2.74698038081381e-05 9.081242150614e-05 -7.93653409673486e-06 1.50036470561835e-05 4.3528956308668e-07 9.18756915616011e-05 -1.51579944785682e-05 -7.93653409673486e-06 1.95274817323867e-05 7.16343175236151e-06 -4.16934754720458e-06 8.94891347694432e-07 -9.10967313122193e-06 1.50036470561835e-05 7.16343175236151e-06 6.38055156706844e-05 -5.48700200631275e-06 1.88886306007596e-05 1.55333297180129e-05 4.3528956308668e-07 -4.16934754720458e-06 -5.48700200631275e-06 6.55858048178217e-05 3.56966658044216e-06 1.1965644115604e-05 9.18756915616011e-05 8.94891347694432e-07 1.88886306007596e-05 3.56966658044216e-06 0.000179540779521275 2001 2016 0 76 0 1971 1995 0 76 1 0 0 0 0 0 0 0 0 289 0 108 110 0 0 1428 +331 420 0.993157340642723 0.0598052840461831 0.100308647322298 0.0949590184164917 -0.0666277260182589 0.995585951712374 0.0661011261523026 -0.0439609569070235 -0.0959126834840395 -0.0723321557339622 0.992758186263789 0.246363628641059 8.07176368952766e-05 4.72319952870166e-05 -1.45640021686719e-05 -1.75008511131411e-06 1.43220511460249e-05 4.04405430183601e-05 4.72319952870166e-05 0.000104637604776117 -1.36871247304415e-05 2.58293417548899e-05 6.86181296558403e-06 0.000109463135187091 -1.45640021686719e-05 -1.36871247304415e-05 1.82074112909536e-05 2.79580447142178e-06 -4.20041348650802e-06 -7.1509424112003e-06 -1.75008511131411e-06 2.58293417548899e-05 2.79580447142178e-06 6.25973080113605e-05 -1.6704336691136e-07 3.72126663305946e-05 1.43220511460249e-05 6.86181296558403e-06 -4.20041348650802e-06 -1.6704336691136e-07 5.06395338034214e-05 -6.35917654962101e-06 4.04405430183601e-05 0.000109463135187091 -7.1509424112003e-06 3.72126663305946e-05 -6.35917654962101e-06 0.000205723824864822 1580 1597 0 78 0 1545 1571 0 78 0 0 0 0 0 0 0 0 0 265 0 103 104 0 0 1439 +331 421 0.993093372372559 0.0585280688261992 0.101685883529491 0.0983080713379431 -0.0659093586499977 0.995309805646195 0.0708120556605969 -0.0473496541765961 -0.0970644641052713 -0.0770250345278027 0.992293118924014 0.246643752973379 9.18818432982901e-05 4.46052855825041e-05 -1.19859890920249e-05 -9.64287631293224e-06 8.96236390934419e-06 2.5455596662555e-05 4.46052855825041e-05 8.5665404514601e-05 -8.45817296615764e-06 1.08877580330271e-05 -4.92794861091365e-06 8.04633675819394e-05 -1.19859890920249e-05 -8.45817296615764e-06 1.74291976981588e-05 5.45967451493283e-06 5.36474464963826e-07 3.24187138132184e-07 -9.64287631293224e-06 1.08877580330271e-05 5.45967451493283e-06 5.86174262764104e-05 -5.41490901044492e-06 1.99839195008661e-05 8.96236390934419e-06 -4.92794861091365e-06 5.36474464963826e-07 -5.41490901044492e-06 5.19932945683877e-05 -1.53001012769002e-05 2.5455596662555e-05 8.04633675819394e-05 3.24187138132184e-07 1.99839195008661e-05 -1.53001012769002e-05 0.000158795162420314 1939 1956 0 77 0 1900 1922 0 76 0 0 0 0 0 0 0 0 0 257 0 107 110 0 0 1475 +331 427 0.991752758029791 0.0580798563050875 0.11425058963473 0.103473890855293 -0.0662287667243514 0.995424876845557 0.0688699137154903 -0.0439966048471135 -0.109727924424344 -0.0758686025216493 0.991061924277659 0.254528341995809 0.000100642710658439 2.31102757991925e-05 -1.28415839391331e-05 4.38561672788876e-06 -1.30938473299305e-05 2.11606973241831e-06 2.31102757991925e-05 8.05787463045774e-05 -8.87933536044824e-06 1.0217850351974e-05 -7.18607301905284e-06 4.680061943647e-05 -1.28415839391331e-05 -8.87933536044824e-06 1.93416372823551e-05 7.31077489659202e-06 2.50894158315775e-06 -1.56588629299966e-06 4.38561672788876e-06 1.0217850351974e-05 7.31077489659202e-06 9.18446030508601e-05 -3.51109275751086e-05 1.02920830995705e-05 -1.30938473299305e-05 -7.18607301905284e-06 2.50894158315775e-06 -3.51109275751086e-05 8.83005455510344e-05 -5.98942852457567e-06 2.11606973241831e-06 4.680061943647e-05 -1.56588629299966e-06 1.02920830995705e-05 -5.98942852457567e-06 0.000140497168948877 1460 1476 0 76 1 1442 1461 0 76 10 0 0 0 0 0 0 0 0 292 0 121 122 0 0 1601 +331 386 0.992529103257209 0.0590983944062575 0.106739678498876 0.0961968379808761 -0.0665124375525335 0.995514186616609 0.0672874423342932 -0.0392707681176421 -0.102284284414867 -0.0738842610010612 0.992007581189814 0.255835142308331 6.96582869932498e-05 2.18735796028235e-05 -9.20892921278241e-06 -2.09366809731928e-06 9.98876825326742e-06 -9.71676863528189e-06 2.18735796028235e-05 5.88305063949874e-05 -5.60424854684085e-06 2.09553080597514e-05 8.18366623851183e-07 3.99081975040753e-05 -9.20892921278241e-06 -5.60424854684085e-06 1.45409754299482e-05 3.25350353564161e-06 1.72634218058588e-06 2.99693820930408e-06 -2.09366809731928e-06 2.09553080597514e-05 3.25350353564161e-06 6.4610757066067e-05 -1.02703514890272e-05 2.22796768597068e-05 9.98876825326742e-06 8.18366623851183e-07 1.72634218058588e-06 -1.02703514890272e-05 5.08655513396291e-05 -4.75693860430274e-06 -9.71676863528189e-06 3.99081975040753e-05 2.99693820930408e-06 2.22796768597068e-05 -4.75693860430274e-06 0.00010440217386824 2085 2101 0 74 0 2043 2060 0 74 3 0 0 0 0 0 0 0 0 289 0 151 131 0 0 1948 +331 394 0.992748859343849 0.0598677509612403 0.104237971326809 0.0929639278895606 -0.0664499692497522 0.995931955353181 0.0608600188391088 -0.04873542144191 -0.100170374154202 -0.0673453242714934 0.992688522871386 0.250517985729193 6.9097806307903e-05 2.78255161142026e-05 -1.84139890317268e-06 -3.33433107390502e-06 -2.90298061330085e-07 -1.55291468434112e-06 2.78255161142026e-05 0.000128457747188232 -1.38105726318084e-06 3.39611113589241e-05 3.9535309962513e-06 0.000114842448286417 -1.84139890317268e-06 -1.38105726318084e-06 1.77250133241275e-05 7.95012016267075e-06 3.89189431270028e-06 3.81029661893799e-06 -3.33433107390502e-06 3.39611113589241e-05 7.95012016267075e-06 8.0055081449796e-05 -1.89138528952247e-05 3.63221151662846e-05 -2.90298061330085e-07 3.9535309962513e-06 3.89189431270028e-06 -1.89138528952247e-05 6.25097683800507e-05 6.58207039886952e-06 -1.55291468434112e-06 0.000114842448286417 3.81029661893799e-06 3.63221151662846e-05 6.58207039886952e-06 0.000195618863671268 1453 1471 0 77 0 1410 1431 0 77 0 0 0 0 0 0 0 0 0 107 0 155 135 0 0 1667 +331 388 0.993419567141145 0.0600732000764654 0.0975129440314079 0.093508113445384 -0.0664569316924623 0.995760756492224 0.0635923899539674 -0.0459289862423462 -0.0932793645514533 -0.0696543355621674 0.993200500244674 0.238870550181638 5.85327504514821e-05 2.36993543366761e-05 -2.63643119433226e-06 -4.98602662539137e-06 4.27198512443855e-06 4.30744023836845e-06 2.36993543366761e-05 6.42234352979541e-05 2.66686916969702e-06 1.26379181802698e-05 -5.70075675548752e-06 4.78187861930468e-05 -2.63643119433226e-06 2.66686916969702e-06 1.63360918074016e-05 6.34049991474605e-06 -6.35206021017538e-07 3.28443254263063e-07 -4.98602662539137e-06 1.26379181802698e-05 6.34049991474605e-06 6.54161063985796e-05 -2.12391527565575e-05 1.89217414755759e-05 4.27198512443855e-06 -5.70075675548752e-06 -6.35206021017538e-07 -2.12391527565575e-05 5.88595914546438e-05 2.40580496932982e-06 4.30744023836845e-06 4.78187861930468e-05 3.28443254263063e-07 1.89217414755759e-05 2.40580496932982e-06 0.000127743711623475 1952 1972 0 81 0 1935 1955 0 80 3 0 0 0 0 0 0 0 0 299 0 161 144 0 0 1903 +331 412 0.992686439088945 0.0593862751745521 0.10510425286259 0.0985863271345563 -0.0665813887607848 0.995574188206481 0.0663246141918004 -0.0453243769578401 -0.100700309431481 -0.0728375322062624 0.99224701641401 0.251565798591163 0.000107415778978876 6.38751746980334e-05 -1.43449522884832e-05 2.1177513079624e-05 -1.37382349761565e-05 7.2684443667588e-05 6.38751746980334e-05 0.000137222594445606 -1.58000945176173e-05 2.41992144300717e-05 1.21092424524863e-05 0.000173400005744042 -1.43449522884832e-05 -1.58000945176173e-05 1.56332898165815e-05 1.88358501340479e-06 1.47902635062027e-06 -1.30432938313887e-05 2.1177513079624e-05 2.41992144300717e-05 1.88358501340479e-06 6.35612961835397e-05 -1.6659828829329e-05 2.75813455043256e-05 -1.37382349761565e-05 1.21092424524863e-05 1.47902635062027e-06 -1.6659828829329e-05 6.76095147137881e-05 1.70891889554518e-05 7.2684443667588e-05 0.000173400005744042 -1.30432938313887e-05 2.75813455043256e-05 1.70891889554518e-05 0.000328964992755128 2102 2118 0 76 0 2073 2098 0 76 7 0 0 0 0 0 0 0 0 215 0 101 102 0 0 1477 +332 435 0.819443953941134 -0.563902522234448 0.102594111755736 -0.0486187110485563 0.571078834938425 0.818520565782153 -0.062394292022879 -0.0566810834831805 -0.0487910917554883 0.109717951171594 0.992764524223149 -0.123402993278875 7.15597985966604e-05 4.41496779342661e-06 -1.23718214037976e-05 -6.11333717961103e-06 -1.6605025868281e-06 5.85075797799078e-06 4.41496779342661e-06 4.02450395875713e-05 -4.47823937258557e-06 5.6032669162252e-06 8.59138691577684e-06 1.6120340053273e-05 -1.23718214037976e-05 -4.47823937258557e-06 1.93168539705793e-05 7.72631810339086e-07 -2.97370018761047e-06 -4.27807079624322e-06 -6.11333717961103e-06 5.6032669162252e-06 7.72631810339086e-07 4.54005435351548e-05 6.08456601889584e-07 1.53546648217617e-05 -1.6605025868281e-06 8.59138691577684e-06 -2.97370018761047e-06 6.08456601889584e-07 8.6894558345051e-05 1.60977721663837e-05 5.85075797799078e-06 1.6120340053273e-05 -4.27807079624322e-06 1.53546648217617e-05 1.60977721663837e-05 8.2327841701278e-05 1332 1326 0 0 739 1294 1288 0 0 739 0 0 0 0 0 11 11 0 851 0 0 0 0 0 1136 +332 417 0.993130739543425 0.0515011016668977 0.10506650608555 0.0727227951291761 -0.0597197098443794 0.995268934407052 0.0766374873045503 -0.0388188618760217 -0.10062251452847 -0.0823855857013097 0.991507803720485 0.166666460944094 8.90385370553309e-05 4.53252250289455e-05 -1.67194112512029e-05 4.5176306355611e-06 1.35358804002046e-05 3.43489476678788e-05 4.53252250289455e-05 0.000126371929666837 -1.17953599975353e-05 2.81507499958932e-05 1.19423466836651e-05 0.000120961972883427 -1.67194112512029e-05 -1.17953599975353e-05 1.77122549210545e-05 3.21408708642551e-06 -8.93345364890092e-08 -5.61920954337505e-06 4.5176306355611e-06 2.81507499958932e-05 3.21408708642551e-06 6.08223688028668e-05 -2.01855951614575e-06 3.25524717880352e-05 1.35358804002046e-05 1.19423466836651e-05 -8.93345364890092e-08 -2.01855951614575e-06 4.95642044640938e-05 1.35943007835058e-05 3.43489476678788e-05 0.000120961972883427 -5.61920954337505e-06 3.25524717880352e-05 1.35943007835058e-05 0.000194829008856104 1910 1941 0 99 4 1876 1908 0 100 6 0 0 0 0 0 0 0 0 257 0 144 146 0 0 1637 +332 433 0.907229282594303 -0.396081222733664 0.141614596003491 0.011324407732156 0.407183934886861 0.911410394231308 -0.059433462436438 -0.06813158709152 -0.10552853629933 0.11158296592642 0.988136108914953 0.0339451435110402 5.77854417878731e-05 2.43064440030408e-05 -5.38561700088085e-06 -4.94217745087409e-06 -7.88777645643239e-06 8.66959682838327e-06 2.43064440030408e-05 4.86505425929908e-05 -2.38601860615283e-06 8.07347245529641e-07 -5.57962458807747e-07 3.47499294054915e-05 -5.38561700088085e-06 -2.38601860615283e-06 1.95555457289628e-05 6.09623932663493e-06 2.89985095729446e-06 -3.05144663996993e-06 -4.94217745087409e-06 8.07347245529641e-07 6.09623932663493e-06 4.75651116042825e-05 -8.35067727412178e-07 1.99293765153067e-06 -7.88777645643239e-06 -5.57962458807747e-07 2.89985095729446e-06 -8.35067727412178e-07 7.92508774878293e-05 1.02300435214971e-05 8.66959682838327e-06 3.47499294054915e-05 -3.05144663996993e-06 1.99293765153067e-06 1.02300435214971e-05 9.35622672771726e-05 1744 1749 0 0 430 1678 1683 0 0 402 0 0 0 0 0 11 11 0 720 0 0 0 0 0 1643 +332 434 0.860743080207191 -0.501868805803284 0.0851413626683392 -0.00232879917965846 0.505298911285786 0.862621490041406 -0.0236045582916755 -0.0790910880219072 -0.0615983776477613 0.063339298072607 0.996089239571853 -0.0213035483402284 4.86363384322444e-05 2.21100134517576e-05 -1.22920832599187e-05 6.91093969816547e-06 -4.62205112927683e-06 1.93928369044078e-05 2.21100134517576e-05 4.32186923548014e-05 -8.60676131610234e-06 6.38608494036033e-06 -9.43895783852757e-06 2.49940357615214e-05 -1.22920832599187e-05 -8.60676131610234e-06 1.99305024942381e-05 6.25082752727415e-07 1.22488522311959e-07 -7.45272719805815e-06 6.91093969816547e-06 6.38608494036033e-06 6.25082752727415e-07 4.17192371763949e-05 -1.55379339757985e-05 1.10674054508783e-05 -4.62205112927683e-06 -9.43895783852757e-06 1.22488522311959e-07 -1.55379339757985e-05 0.000119681636434459 -3.01603210625395e-05 1.93928369044078e-05 2.49940357615214e-05 -7.45272719805815e-06 1.10674054508783e-05 -3.01603210625395e-05 8.14593046176097e-05 1594 1600 0 0 564 1541 1547 0 0 539 0 0 0 0 0 11 11 0 836 0 0 0 0 0 1367 +332 432 0.949437810407218 -0.279725744142395 0.142552980442819 0.0451451760499479 0.28909331723168 0.956021804160443 -0.0494708389032912 -0.0642644133270682 -0.122445490325821 0.0881805989648264 0.988550091732874 0.104611785549918 7.85714564240756e-05 3.2158691361757e-05 -9.89511264164711e-06 1.21567720964273e-05 -2.05336189742622e-05 1.24104795353309e-05 3.2158691361757e-05 7.87244153933045e-05 -8.16658021638004e-06 6.4204453467126e-06 -6.01517434093486e-06 6.31228282088663e-05 -9.89511264164711e-06 -8.16658021638004e-06 1.70028777769511e-05 2.53283129987847e-06 4.61810236963501e-06 -8.45142568826117e-06 1.21567720964273e-05 6.4204453467126e-06 2.53283129987847e-06 6.16977822420039e-05 -3.38402678885852e-05 1.56533636699154e-05 -2.05336189742622e-05 -6.01517434093486e-06 4.61810236963501e-06 -3.38402678885852e-05 0.000114788595202852 -9.48064537087462e-06 1.24104795353309e-05 6.31228282088663e-05 -8.45142568826117e-06 1.56533636699154e-05 -9.48064537087462e-06 0.000149000538725487 1872 1898 0 0 368 1831 1857 0 0 335 0 0 0 0 0 12 12 0 552 0 0 0 0 0 1861 +332 334 0.99911439605258 0.0211193745592642 -0.0363922466840761 0.0195084413677037 -0.0223623191445316 0.999168469119607 -0.0340924771710506 0.0236859900061765 0.0356419736121228 0.0348760997734265 0.998755879773244 0.0722051836228228 4.21855077881172e-05 3.8623181300046e-06 -4.5857362409852e-06 1.68770395724231e-06 4.6126565498136e-06 7.48212597024478e-06 3.8623181300046e-06 5.36322743816409e-05 -6.55373349860232e-06 1.69438405586243e-05 6.32409700247946e-06 3.33917283508262e-05 -4.5857362409852e-06 -6.55373349860232e-06 1.71351894755752e-05 -1.65309307892917e-07 -2.03852992928761e-06 -8.02918609334063e-06 1.68770395724231e-06 1.69438405586243e-05 -1.65309307892917e-07 6.02297509131793e-05 -2.93485433626623e-05 1.8999296414188e-05 4.6126565498136e-06 6.32409700247946e-06 -2.03852992928761e-06 -2.93485433626623e-05 6.80069679811376e-05 3.86229494673303e-07 7.48212597024478e-06 3.33917283508262e-05 -8.02918609334063e-06 1.8999296414188e-05 3.86229494673303e-07 7.14449098859119e-05 2583 2548 0 37 63 2547 2545 0 28 34 0 0 0 0 0 0 1 0 528 0 110 76 0 0 3233 +332 431 0.984395793279102 -0.149727842566358 0.0924472570433129 0.066155958838804 0.152889343959719 0.987844328854532 -0.0280790037840922 -0.0511705144271595 -0.087119289930389 0.0417750536847559 0.995321593361493 0.145138385440233 6.84551487658477e-05 2.2927719297203e-05 -1.24281553680078e-05 6.92057286978157e-06 -6.95254538854564e-06 1.28541937542266e-05 2.2927719297203e-05 6.28237884379865e-05 -9.14320509848461e-06 1.02519449123263e-05 2.45060621216925e-06 4.89641187528405e-05 -1.24281553680078e-05 -9.14320509848461e-06 1.86004986778244e-05 2.11549971822167e-06 5.3633993097284e-06 -5.1946979725385e-06 6.92057286978157e-06 1.02519449123263e-05 2.11549971822167e-06 5.82379739310429e-05 -1.87383938377098e-05 1.58647959143141e-05 -6.95254538854564e-06 2.45060621216925e-06 5.3633993097284e-06 -1.87383938377098e-05 6.92748406078661e-05 4.32031253475901e-06 1.28541937542266e-05 4.89641187528405e-05 -5.1946979725385e-06 1.58647959143141e-05 4.32031253475901e-06 0.000125793965244345 1533 1545 0 0 310 1520 1534 0 0 267 0 0 0 0 0 11 11 0 460 0 0 0 0 0 1892 +332 384 0.992894041485966 0.0508551248322569 0.107588004256794 0.0710879646162374 -0.0594410545968885 0.995167029467486 0.0781622958290565 -0.0314611173920241 -0.103093081291006 -0.0840020222325319 0.991118296093242 0.171119741443716 6.60873943734623e-05 3.26967185186398e-05 -1.11806208094511e-05 -6.71955339119651e-06 1.39905543765727e-05 1.06442780909665e-05 3.26967185186398e-05 5.43647011846844e-05 -1.02669850276651e-05 -4.91909977415706e-07 3.12663706000979e-06 4.26926410952638e-05 -1.11806208094511e-05 -1.02669850276651e-05 1.56571075181723e-05 4.50347555275805e-06 -4.42367409801679e-07 -2.74043494938512e-06 -6.71955339119651e-06 -4.91909977415706e-07 4.50347555275805e-06 6.62551871571473e-05 -2.11594395230323e-05 1.58804140507778e-06 1.39905543765727e-05 3.12663706000979e-06 -4.42367409801679e-07 -2.11594395230323e-05 5.50963886087044e-05 3.84126565803175e-06 1.06442780909665e-05 4.26926410952638e-05 -2.74043494938512e-06 1.58804140507778e-06 3.84126565803175e-06 0.000109478661827543 1986 2017 0 98 1 1952 1985 0 99 5 0 0 0 0 0 0 0 0 321 0 188 167 0 0 2116 +332 383 0.992383995738556 0.0512970685536228 0.111993820185685 0.0691949095922025 -0.0603580671888661 0.995039833996353 0.0790735890530745 -0.0320699112987511 -0.107382068927745 -0.085231094785384 0.990557798290681 0.179375077966995 7.22207617918242e-05 1.1088098295992e-05 -1.08983655298177e-05 -1.40122545639186e-05 5.77104967502246e-06 -5.34626836838011e-06 1.1088098295992e-05 6.54018967832596e-05 -5.4958606024943e-06 1.79719815158751e-05 -3.79715513649955e-07 5.03318540162565e-05 -1.08983655298177e-05 -5.4958606024943e-06 1.50359961837093e-05 5.0923988284269e-06 3.12875147288087e-06 8.22588702251236e-08 -1.40122545639186e-05 1.79719815158751e-05 5.0923988284269e-06 9.15415651080402e-05 -2.42548863965568e-05 2.22674010019888e-05 5.77104967502246e-06 -3.79715513649955e-07 3.12875147288087e-06 -2.42548863965568e-05 5.42006778108527e-05 1.35277014072283e-06 -5.34626836838011e-06 5.03318540162565e-05 8.22588702251236e-08 2.22674010019888e-05 1.35277014072283e-06 0.0001130194959912 1888 1918 0 90 3 1854 1886 0 91 4 0 0 0 0 0 0 0 0 290 0 192 170 0 0 2050 +332 418 0.99301707568746 0.0510084244514147 0.10637306063149 0.0735321053525256 -0.0598641419974672 0.994849976787363 0.0817912476313415 -0.0368836541538804 -0.101653194224448 -0.0875880375460523 0.99095659026155 0.173774145105255 0.00010024127197664 0.000100869640145984 -1.69238438345349e-05 1.64481642566024e-05 -3.09373903437352e-06 0.000105442345434025 0.000100869640145984 0.000218853587319026 -2.11064846383838e-05 5.38147323228582e-05 -2.91807299514913e-05 0.000233166684315375 -1.69238438345349e-05 -2.11064846383838e-05 1.85650074746587e-05 2.82017462136469e-06 4.06096998094377e-06 -1.50060422789875e-05 1.64481642566024e-05 5.38147323228582e-05 2.82017462136469e-06 6.26735443799219e-05 -1.83603723496879e-05 6.59705041130919e-05 -3.09373903437352e-06 -2.91807299514913e-05 4.06096998094377e-06 -1.83603723496879e-05 5.90625894561445e-05 -3.55934582990224e-05 0.000105442345434025 0.000233166684315375 -1.50060422789875e-05 6.59705041130919e-05 -3.55934582990224e-05 0.000325763009349472 1642 1658 0 86 4 1651 1675 0 87 11 0 0 0 0 0 0 0 0 264 0 102 103 0 0 1512 +332 419 0.992868673282443 0.0508947072814596 0.10780318355733 0.0808319480901875 -0.0596964436159003 0.995001080979685 0.0800573761053399 -0.0425433234883718 -0.103189787449992 -0.0859219274690271 0.990943636210472 0.169692972112539 5.39641179173806e-05 2.17575797995803e-05 -7.63561012273524e-06 -2.41550622227004e-07 2.33343397890176e-06 6.34763155393443e-06 2.17575797995803e-05 5.60280691720062e-05 -6.93817500232734e-06 1.57977410709353e-05 -4.76077766419984e-06 4.90559635209487e-05 -7.63561012273524e-06 -6.93817500232734e-06 1.45395414740779e-05 4.32313514824053e-06 3.89825920354749e-07 -1.45458077469236e-06 -2.41550622227004e-07 1.57977410709353e-05 4.32313514824053e-06 6.81330600282656e-05 -2.30879005567614e-05 3.45542492221717e-05 2.33343397890176e-06 -4.76077766419984e-06 3.89825920354749e-07 -2.30879005567614e-05 6.88173382120609e-05 -2.0001157135652e-05 6.34763155393443e-06 4.90559635209487e-05 -1.45458077469236e-06 3.45542492221717e-05 -2.0001157135652e-05 0.000122477446088499 2073 2086 0 89 5 2048 2062 0 91 2 0 0 0 0 0 0 0 0 245 0 130 132 0 0 1605 +332 415 0.992586452299215 0.0510983367108317 0.110277353511244 0.0838215098117393 -0.0596196634831121 0.995368710227229 0.0754097236882839 -0.0464912410330335 -0.105913315679464 -0.0814253688107664 0.991035962453337 0.173272701783605 0.000103734911297821 5.94367251043981e-05 -1.70940315597668e-05 -7.35437103120062e-08 -5.08479355746824e-07 4.56316171062795e-05 5.94367251043981e-05 0.000145103753352681 -1.469258083959e-05 3.84386756355633e-05 -2.98578524533842e-06 0.000183941851528759 -1.70940315597668e-05 -1.469258083959e-05 1.77882806939978e-05 2.59212905803114e-06 3.22370287829715e-06 -8.40983617139978e-06 -7.35437103120062e-08 3.84386756355633e-05 2.59212905803114e-06 7.51204530304528e-05 -2.0226584345168e-05 7.08149611483659e-05 -5.08479355746824e-07 -2.98578524533842e-06 3.22370287829715e-06 -2.0226584345168e-05 5.22763849483332e-05 -1.471308523202e-05 4.56316171062795e-05 0.000183941851528759 -8.40983617139978e-06 7.08149611483659e-05 -1.471308523202e-05 0.000338773558314148 1896 1918 0 95 3 1876 1899 0 97 3 0 0 0 0 0 0 0 0 238 0 136 137 0 0 1664 +332 379 0.993058002215404 0.0513514036907984 0.105824560357862 0.071878962762236 -0.0595866664629786 0.995311555777226 0.0761861937371069 -0.0377691209265492 -0.101416139818965 -0.0819630421306024 0.991461964126167 0.173856524887408 7.61634241778156e-05 1.68709901051019e-05 -9.91319615710059e-06 3.608486599704e-06 -3.29016215055278e-06 -4.59088376195209e-06 1.68709901051019e-05 8.65465687393349e-05 -9.5983664178311e-06 1.46186706682542e-05 8.21883311259639e-06 7.15361647808062e-05 -9.91319615710059e-06 -9.5983664178311e-06 1.59237860081827e-05 2.24045161517963e-07 3.45096708895453e-06 -1.80107971112472e-06 3.608486599704e-06 1.46186706682542e-05 2.24045161517963e-07 7.71545224666408e-05 -2.31666760108162e-05 -1.75137533551292e-05 -3.29016215055278e-06 8.21883311259639e-06 3.45096708895453e-06 -2.31666760108162e-05 5.90365651696679e-05 3.02162323820927e-05 -4.59088376195209e-06 7.15361647808062e-05 -1.80107971112472e-06 -1.75137533551292e-05 3.02162323820927e-05 0.000148838419779676 1877 1907 0 97 3 1843 1875 0 97 6 0 0 0 0 0 0 0 0 302 0 196 172 0 0 2099 +332 385 0.992316426249459 0.0507750538640289 0.112827319832595 0.0769440726933433 -0.0599290828875766 0.995049353680024 0.0792798131003123 -0.0370746099985752 -0.108243314896374 -0.0854322986116577 0.990446720997234 0.17493249320945 5.68587965911152e-05 1.89356990026444e-05 -6.74750215654024e-06 3.62953229237222e-06 -7.19626816339125e-06 9.21348664782594e-06 1.89356990026444e-05 4.72033446518965e-05 -5.93094024453292e-06 1.06325653838828e-05 -2.20861932275906e-06 2.73462092130824e-05 -6.74750215654024e-06 -5.93094024453292e-06 1.3750565828433e-05 3.34690263062893e-06 4.22976864520477e-06 -4.99201606605745e-07 3.62953229237222e-06 1.06325653838828e-05 3.34690263062893e-06 6.6360646155808e-05 -2.29000916560869e-05 1.66734204734508e-05 -7.19626816339125e-06 -2.20861932275906e-06 4.22976864520477e-06 -2.29000916560869e-05 5.946033600219e-05 -4.35825241759689e-06 9.21348664782594e-06 2.73462092130824e-05 -4.99201606605745e-07 1.66734204734508e-05 -4.35825241759689e-06 8.36768916091049e-05 2116 2118 0 90 5 2093 2096 0 90 5 0 0 0 0 0 0 0 0 296 0 177 157 0 0 2122 +332 421 0.993533683748602 0.052144805961372 0.100855036900412 0.0713061661471278 -0.0600957177195204 0.995181590526972 0.0774732636977582 -0.0389906334813038 -0.0963292477324948 -0.0830332529018196 0.991880111174649 0.16653368810502 9.15669777332682e-05 1.5477076819368e-05 -1.38181266307319e-05 -6.80225215971364e-06 1.47863469662248e-06 -6.24041967679987e-06 1.5477076819368e-05 8.00155141516926e-05 -7.87318849619513e-06 2.93892849969202e-05 -7.15690668481644e-06 6.88064960115151e-05 -1.38181266307319e-05 -7.87318849619513e-06 1.62869966827975e-05 6.28494827626411e-06 3.59847177363579e-06 1.19744964557284e-06 -6.80225215971364e-06 2.93892849969202e-05 6.28494827626411e-06 6.53726374654625e-05 -1.05335947699433e-05 3.26378168956326e-05 1.47863469662248e-06 -7.15690668481644e-06 3.59847177363579e-06 -1.05335947699433e-05 5.20469031000237e-05 -1.06454983199747e-06 -6.24041967679987e-06 6.88064960115151e-05 1.19744964557284e-06 3.26378168956326e-05 -1.06454983199747e-06 0.0001405898994 1456 1460 0 81 3 1466 1475 0 82 2 0 0 0 0 0 0 0 0 266 0 104 107 0 0 1616 +332 422 0.991988740989992 0.0514596546686873 0.115370020761334 0.0767577453871975 -0.0607927003627359 0.995027705707045 0.0788930444207908 -0.0344538938559212 -0.110736558243869 -0.0852746669108341 0.990184652401535 0.177219628801124 6.58283761644021e-05 3.27908675811809e-05 -1.06457380029229e-05 -6.20257404624629e-06 1.06643613374688e-05 2.19221029659236e-05 3.27908675811809e-05 0.00011728402956285 -8.76611324778083e-06 1.50388326597801e-05 8.234523849037e-06 0.000106125614743671 -1.06457380029229e-05 -8.76611324778083e-06 1.71972428689874e-05 5.61689373864303e-06 8.45196187877333e-07 -2.73179247782342e-06 -6.20257404624629e-06 1.50388326597801e-05 5.61689373864303e-06 6.64113084351592e-05 -1.74408748308454e-05 2.07556062359253e-05 1.06643613374688e-05 8.234523849037e-06 8.45196187877333e-07 -1.74408748308454e-05 5.54830104675783e-05 1.15240085825199e-05 2.19221029659236e-05 0.000106125614743671 -2.73179247782342e-06 2.07556062359253e-05 1.15240085825199e-05 0.000169322727765762 2016 2041 0 88 9 1983 2009 0 88 9 0 0 0 0 0 0 0 0 255 0 143 144 0 0 1598 +332 425 0.992537623109352 0.0509451002188964 0.110786567218794 0.0739171360221179 -0.0605331116700011 0.994542419998971 0.0849771570137379 -0.0348080557540774 -0.105852770884776 -0.0910492810859969 0.990204635067792 0.176246371295952 8.38009695068288e-05 3.45179129881628e-05 -1.46732076746291e-05 -2.17573617510003e-06 8.19159892302098e-06 2.83938247693559e-05 3.45179129881628e-05 8.3290931358002e-05 -1.2405564163647e-05 1.88381622298843e-05 1.23904841867651e-06 7.57788172641284e-05 -1.46732076746291e-05 -1.2405564163647e-05 1.89582314867844e-05 5.38238455460712e-06 -2.45522713994954e-06 -9.89689095360302e-06 -2.17573617510003e-06 1.88381622298843e-05 5.38238455460712e-06 8.68728205800964e-05 -4.82966241385443e-05 2.52694675017349e-05 8.19159892302098e-06 1.23904841867651e-06 -2.45522713994954e-06 -4.82966241385443e-05 0.000108691133996455 -5.09037731649919e-06 2.83938247693559e-05 7.57788172641284e-05 -9.89689095360302e-06 2.52694675017349e-05 -5.09037731649919e-06 0.000136235113702473 1851 1873 0 82 8 1825 1847 0 82 10 0 0 0 0 0 0 0 0 280 0 117 120 0 0 1524 +332 424 0.992873082903103 0.0514454602570211 0.107500724953047 0.0762306274413546 -0.0600836985200727 0.995084129122638 0.0787243617972846 -0.0419463321716355 -0.102922254243854 -0.0846223409460174 0.991083280554253 0.174938679184402 7.77273462165432e-05 4.99299808059555e-05 -1.39194123315239e-05 -9.90634078104828e-06 2.02571041493122e-05 3.78043808373224e-05 4.99299808059555e-05 9.33575465450799e-05 -1.51170847399325e-05 1.05850744013721e-05 1.0252173769633e-05 8.28438246466046e-05 -1.39194123315239e-05 -1.51170847399325e-05 1.92056128384232e-05 4.98299717291696e-06 -3.81603174602118e-06 -6.30233807693357e-06 -9.90634078104828e-06 1.05850744013721e-05 4.98299717291696e-06 5.74974625611992e-05 -9.11981946724767e-06 1.52551730538789e-05 2.02571041493122e-05 1.0252173769633e-05 -3.81603174602118e-06 -9.11981946724767e-06 6.45438943015906e-05 8.17926248903207e-06 3.78043808373224e-05 8.28438246466046e-05 -6.30233807693357e-06 1.52551730538789e-05 8.17926248903207e-06 0.000145811840963428 1661 1689 0 101 4 1635 1663 0 102 12 0 0 0 0 0 0 0 0 276 0 115 119 0 0 1572 +332 420 0.993062433005789 0.0516586144524463 0.105633288813122 0.0713720211856057 -0.0599708951176229 0.995218924770374 0.0770894514034971 -0.0329459793756871 -0.10114591386415 -0.0828895610541797 0.991412540155122 0.172477415755256 9.59513830800744e-05 4.38781623777444e-05 -1.80452795617749e-05 9.39915238516906e-06 5.75738140447106e-06 3.95113272717383e-05 4.38781623777444e-05 8.20834702511262e-05 -1.40276043514844e-05 1.19220113233059e-05 7.0777476934794e-06 7.78613196285886e-05 -1.80452795617749e-05 -1.40276043514844e-05 1.71092800491142e-05 1.98726754425828e-06 -4.73527916560021e-07 -4.82773254562666e-06 9.39915238516906e-06 1.19220113233059e-05 1.98726754425828e-06 5.24680276280649e-05 -9.52657545538197e-06 1.67119593894828e-05 5.75738140447106e-06 7.0777476934794e-06 -4.73527916560021e-07 -9.52657545538197e-06 5.80543490664062e-05 1.06514779708823e-05 3.95113272717383e-05 7.78613196285886e-05 -4.82773254562666e-06 1.67119593894828e-05 1.06514779708823e-05 0.000152390744429754 1974 1994 0 93 9 1980 2008 0 94 11 0 0 0 0 0 0 0 0 270 0 100 101 0 0 1585 +332 426 0.992248212883097 0.0512308642415498 0.113220504235605 0.07669423983646 -0.0603672957043794 0.995061172482013 0.0787975420178964 -0.0324697490176532 -0.108624461515999 -0.0850215359058282 0.990440338835497 0.18115268380326 7.1236731773834e-05 3.44120267104122e-05 -1.02635772515965e-05 7.50384522460514e-06 -9.66653618123877e-06 1.68948014303639e-05 3.44120267104122e-05 8.70383163260816e-05 -1.0193646921069e-05 2.98846568517077e-05 -5.85267571715947e-06 7.83288697256948e-05 -1.02635772515965e-05 -1.0193646921069e-05 1.51242592345626e-05 -2.76970359113997e-07 4.4618699286841e-06 -4.64639676486843e-06 7.50384522460514e-06 2.98846568517077e-05 -2.76970359113997e-07 5.89964561680725e-05 1.4655778708739e-06 3.30528159848046e-05 -9.66653618123877e-06 -5.85267571715947e-06 4.4618699286841e-06 1.4655778708739e-06 4.93622456522765e-05 2.1895421278952e-06 1.68948014303639e-05 7.83288697256948e-05 -4.64639676486843e-06 3.30528159848046e-05 2.1895421278952e-06 0.000143714253727065 1819 1826 0 87 7 1822 1836 0 88 12 0 0 0 0 0 0 0 0 297 0 112 115 0 0 1497 +332 394 0.992399470500298 0.0519410134122459 0.111559051969961 0.0778792467765731 -0.0605861396614892 0.995299366014409 0.0755545610286682 -0.0424924551630584 -0.107110273231124 -0.0817392386618882 0.990881469314735 0.17821023940015 5.72187499086415e-05 1.69950747715618e-05 -3.06872326346817e-06 1.80706656957295e-06 -9.51926615449007e-06 -1.24703706489246e-05 1.69950747715618e-05 5.93263474117942e-05 -2.07375060595476e-06 1.28409113564132e-05 -2.30351553459831e-06 4.23989803382277e-05 -3.06872326346817e-06 -2.07375060595476e-06 1.38635073350557e-05 4.30896101274224e-06 6.0032951451521e-06 1.57261790242734e-06 1.80706656957295e-06 1.28409113564132e-05 4.30896101274224e-06 6.88623990303009e-05 -1.57378873298278e-05 2.0567805027383e-05 -9.51926615449007e-06 -2.30351553459831e-06 6.0032951451521e-06 -1.57378873298278e-05 5.75968880785366e-05 -1.66785577864524e-06 -1.24703706489246e-05 4.23989803382277e-05 1.57261790242734e-06 2.0567805027383e-05 -1.66785577864524e-06 0.000105329421581945 1549 1574 0 94 5 1524 1549 0 94 8 0 0 0 0 0 0 0 0 115 0 150 130 0 0 1770 +332 378 0.992907213193921 0.0515867092333499 0.107117120097377 0.0734097261869833 -0.0600264473541216 0.995213174489004 0.0771204443812474 -0.0339909812110248 -0.102625979193988 -0.0830033056811114 0.991250906501721 0.177278929859359 7.14967954805233e-05 1.88854072186137e-05 -1.07345506482789e-05 -1.10000788899332e-05 9.885176671636e-06 -1.70011694346864e-06 1.88854072186137e-05 6.30197897760542e-05 -8.13494311462325e-06 1.0216060769642e-05 3.66273890159521e-07 5.17130653059389e-05 -1.07345506482789e-05 -8.13494311462325e-06 1.60691399320696e-05 4.2149529311766e-06 1.77940791565036e-06 1.12359087478909e-07 -1.10000788899332e-05 1.0216060769642e-05 4.2149529311766e-06 5.30050107636938e-05 -1.62590988524777e-05 1.6080307646594e-05 9.885176671636e-06 3.66273890159521e-07 1.77940791565036e-06 -1.62590988524777e-05 6.73749112023555e-05 6.7997896248911e-06 -1.70011694346864e-06 5.17130653059389e-05 1.12359087478909e-07 1.6080307646594e-05 6.7997896248911e-06 9.54742911905391e-05 1881 1906 0 96 0 1855 1880 0 96 3 0 0 0 0 0 0 0 0 323 0 156 133 0 0 2070 +332 412 0.992292711382936 0.0508905076047936 0.112983765081658 0.0779264019410914 -0.060165874539353 0.994956302570877 0.0802622172345338 -0.034806038816223 -0.108329324179632 -0.0864413801961485 0.990349759081391 0.17795076178904 9.39579938771552e-05 5.30465092971609e-05 -1.50145733382498e-05 9.27449152144336e-06 -4.39800700128331e-06 3.7082949461064e-05 5.30465092971609e-05 8.26374877635569e-05 -1.61305238561753e-05 1.72641648125281e-05 -6.82705686726703e-06 6.26928891588513e-05 -1.50145733382498e-05 -1.61305238561753e-05 1.87788275098075e-05 1.74470278001763e-06 3.27201032801339e-06 -7.19117375621351e-06 9.27449152144336e-06 1.72641648125281e-05 1.74470278001763e-06 5.94610412324439e-05 -2.37625516450085e-05 2.16886639003171e-05 -4.39800700128331e-06 -6.82705686726703e-06 3.27201032801339e-06 -2.37625516450085e-05 5.98966878961963e-05 -1.33518239861202e-05 3.7082949461064e-05 6.26928891588513e-05 -7.19117375621351e-06 2.16886639003171e-05 -1.33518239861202e-05 0.000113492483367867 1938 1955 0 85 3 1946 1969 0 86 3 0 0 0 0 0 0 0 0 226 0 102 104 0 0 1605 +332 392 0.992229066638462 0.0516663912959467 0.113190385317045 0.0746659274024492 -0.0606138410306216 0.995180205524998 0.0770864502149254 -0.0357076677695827 -0.10866205222285 -0.0833483205690298 0.990578424893779 0.177365958943584 4.65449890103103e-05 -2.53191360172689e-06 -4.21682111520141e-06 -9.0384628814232e-06 -6.86382704183652e-07 -1.75392774191107e-05 -2.53191360172689e-06 4.93458708677652e-05 -4.23260187106847e-07 9.35897454438054e-06 2.36349357917604e-06 4.52146579633776e-05 -4.21682111520141e-06 -4.23260187106847e-07 1.44680471482764e-05 2.89133981539305e-06 3.03422495754716e-06 1.62940571631801e-06 -9.0384628814232e-06 9.35897454438054e-06 2.89133981539305e-06 6.27239040030576e-05 -1.26157329319126e-05 2.36813474747893e-05 -6.86382704183652e-07 2.36349357917604e-06 3.03422495754716e-06 -1.26157329319126e-05 5.65049013188849e-05 7.89585624681422e-06 -1.75392774191107e-05 4.52146579633776e-05 1.62940571631801e-06 2.36813474747893e-05 7.89585624681422e-06 0.000116929035183583 1640 1647 0 87 2 1621 1628 0 89 4 0 0 0 0 0 0 0 0 98 0 181 164 0 0 1673 +332 388 0.992225622063574 0.0511442623352141 0.1134573900226 0.0837772645409333 -0.0601978863333958 0.995145144447253 0.0778611325633473 -0.0398443716799328 -0.108924420593112 -0.0840857057605059 0.990487286483382 0.173917362282112 5.73669009970761e-05 1.21841797773577e-05 -7.49968512957493e-06 -4.53173442225389e-06 -8.03249148664496e-06 -1.46193792196108e-05 1.21841797773577e-05 5.45403314446523e-05 -1.31067304543771e-07 7.61236970573685e-06 -2.47708800127269e-06 3.98001993101258e-05 -7.49968512957493e-06 -1.31067304543771e-07 1.53178053929379e-05 4.39726986514327e-06 7.19732878444954e-06 7.45565672511296e-06 -4.53173442225389e-06 7.61236970573685e-06 4.39726986514327e-06 6.49513760638194e-05 -3.74250874664565e-05 1.87507641899917e-05 -8.03249148664496e-06 -2.47708800127269e-06 7.19732878444954e-06 -3.74250874664565e-05 8.10031561124441e-05 8.79852846962868e-07 -1.46193792196108e-05 3.98001993101258e-05 7.45565672511296e-06 1.87507641899917e-05 8.79852846962868e-07 0.000106699847988353 2112 2124 0 91 3 2091 2104 0 90 7 0 0 0 0 0 0 0 0 312 0 179 159 0 0 2052 +332 427 0.9919431498675 0.0513460697452175 0.115811780716217 0.0840091569003992 -0.060671989886213 0.995066720557357 0.0784928740872339 -0.0389267377298768 -0.111210148251808 -0.0848869999525625 0.990164885342267 0.180300334603624 9.87656525860415e-05 4.39406857091494e-05 -1.69825572294037e-05 5.84447061930864e-06 -4.49919482384842e-06 3.49061878142199e-05 4.39406857091494e-05 9.93313030536825e-05 -1.24505409986899e-05 1.83943844933274e-05 -1.0778153080781e-05 0.000107820425738485 -1.69825572294037e-05 -1.24505409986899e-05 1.68806279009043e-05 2.31296467395948e-07 3.33035391853523e-06 -4.98115224708295e-06 5.84447061930864e-06 1.83943844933274e-05 2.31296467395948e-07 5.93861849250802e-05 -6.04073897765353e-06 3.52223493050944e-05 -4.49919482384842e-06 -1.0778153080781e-05 3.33035391853523e-06 -6.04073897765353e-06 5.62256223153036e-05 -7.52438744863105e-06 3.49061878142199e-05 0.000107820425738485 -4.98115224708295e-06 3.52223493050944e-05 -7.52438744863105e-06 0.000213161100655203 1600 1617 0 84 4 1581 1600 0 85 6 0 0 0 0 0 0 0 0 295 0 143 144 0 0 1695 +332 376 0.99266467569759 0.0510005630538032 0.109616532468387 0.0793546480947667 -0.0596761788110398 0.995214218510724 0.0773783752517509 -0.0415654711148094 -0.105145590990353 -0.0833522755675154 0.990957518187842 0.173444464855691 6.00186216039883e-05 2.84002540218483e-05 -6.19690499311941e-06 2.76274483294897e-06 2.71704646639652e-06 1.12124265798135e-05 2.84002540218483e-05 7.44278607638798e-05 -6.4123301359626e-06 1.71756858925495e-06 1.46943303890193e-06 5.59527364658123e-05 -6.19690499311941e-06 -6.4123301359626e-06 1.32929389644681e-05 3.30529798219114e-06 3.05069981166733e-06 8.100064887557e-07 2.76274483294897e-06 1.71756858925495e-06 3.30529798219114e-06 6.60742168687494e-05 -2.18092679302051e-05 1.42018999475598e-05 2.71704646639652e-06 1.46943303890193e-06 3.05069981166733e-06 -2.18092679302051e-05 5.58116971193146e-05 7.42412912197829e-06 1.12124265798135e-05 5.59527364658123e-05 8.100064887557e-07 1.42018999475598e-05 7.42412912197829e-06 0.000112374730367033 1901 1930 0 97 2 1866 1897 0 97 5 0 0 0 0 0 0 0 0 288 0 188 168 0 0 1949 +332 386 0.992498274356376 0.0510910090242098 0.111071527388903 0.075670372684691 -0.0601554938335954 0.994990011709316 0.0798510686236035 -0.0317482841260532 -0.106435388669615 -0.0859336103953703 0.990599274501635 0.178998420173637 6.93672041538588e-05 8.60285830983281e-06 -8.77888344850945e-06 -1.02468601180761e-05 -3.73249485562493e-06 2.706567825564e-06 8.60285830983281e-06 5.34681066975724e-05 -4.26818710015356e-06 5.92116921764429e-06 4.07197587805197e-06 3.56769152563785e-05 -8.77888344850945e-06 -4.26818710015356e-06 1.38940907452439e-05 3.5970186142797e-06 5.75716161276721e-06 -1.00760490411493e-06 -1.02468601180761e-05 5.92116921764429e-06 3.5970186142797e-06 5.77845824248683e-05 -1.17391765313323e-05 1.68044122710346e-06 -3.73249485562493e-06 4.07197587805197e-06 5.75716161276721e-06 -1.17391765313323e-05 5.54412871592192e-05 5.85181215528409e-06 2.706567825564e-06 3.56769152563785e-05 -1.00760490411493e-06 1.68044122710346e-06 5.85181215528409e-06 9.20810776815318e-05 1852 1874 0 84 4 1825 1847 0 86 6 0 0 0 0 0 0 0 0 289 0 151 129 0 0 2022 +332 393 0.992256226884804 0.0511528029805849 0.113185559836765 0.0712656621430297 -0.0603187914882468 0.995040387740508 0.0790965875282617 -0.0341134889192346 -0.108578191188332 -0.085311297683531 0.990420495994415 0.18156110642867 5.99115839819859e-05 -2.44738961559618e-06 -6.00466016979056e-06 -4.25162045880635e-06 -7.31442384551809e-06 -1.41637488298933e-05 -2.44738961559618e-06 5.21217554844292e-05 1.00529910105469e-06 1.00264584387071e-05 4.55510324076819e-06 4.05703583358867e-05 -6.00466016979056e-06 1.00529910105469e-06 1.43037483571327e-05 2.20506935444772e-06 4.60062808246647e-06 3.97136484140647e-06 -4.25162045880635e-06 1.00264584387071e-05 2.20506935444772e-06 6.57285511924123e-05 -3.06567585349927e-05 1.68129220563203e-05 -7.31442384551809e-06 4.55510324076819e-06 4.60062808246647e-06 -3.06567585349927e-05 7.4528074882618e-05 1.19319099602929e-05 -1.41637488298933e-05 4.05703583358867e-05 3.97136484140647e-06 1.68129220563203e-05 1.19319099602929e-05 9.24541538915801e-05 1967 1980 0 86 3 1969 1991 0 85 6 0 0 0 0 0 0 0 0 107 0 149 130 0 0 1778 +332 395 0.992351381492097 0.0518606240847893 0.112023262406795 0.0771785586861159 -0.0607071325626579 0.995176699103647 0.0770583001187277 -0.0338575986203424 -0.107486648969746 -0.0832695216192828 0.990713281965348 0.174909245083458 8.16977939447716e-05 -7.62862691588939e-06 -9.01363530378044e-06 -3.66523945525686e-06 -3.77818946383714e-06 -3.60496953137659e-05 -7.62862691588939e-06 7.02322563882034e-05 1.82403961828474e-07 1.80657746564818e-05 1.58683290109939e-06 6.47581789569414e-05 -9.01363530378044e-06 1.82403961828474e-07 1.60696938014259e-05 5.57894688899675e-06 4.62113963181845e-06 2.22684885714455e-06 -3.66523945525686e-06 1.80657746564818e-05 5.57894688899675e-06 6.11765723439356e-05 -1.58119227063912e-05 2.58815932107803e-05 -3.77818946383714e-06 1.58683290109939e-06 4.62113963181845e-06 -1.58119227063912e-05 6.19190678561291e-05 1.5283206269793e-05 -3.60496953137659e-05 6.47581789569414e-05 2.22684885714455e-06 2.58815932107803e-05 1.5283206269793e-05 0.000137542550805799 2103 2134 0 91 1 2069 2101 0 91 2 0 0 0 0 0 0 0 0 113 0 183 167 0 0 1764 +333 433 0.895685394711809 -0.415291527438235 0.158998807976563 0.00181533945704589 0.422171935609956 0.906453402800554 -0.0106341588590637 -0.0693871970054189 -0.139708734455986 0.0766496952982501 0.987221501856292 -0.00352339151593267 5.82038393450876e-05 2.43274601818957e-05 -6.10694314237754e-06 -8.40676713174702e-06 1.47820666162642e-06 7.79134295504126e-06 2.43274601818957e-05 4.89115818117582e-05 -2.06586844815482e-06 9.67842643895195e-07 1.15518970793841e-06 4.00738811191075e-05 -6.10694314237754e-06 -2.06586844815482e-06 1.96060634132894e-05 9.93352212531367e-06 1.71369743361644e-06 -2.64892523162014e-06 -8.40676713174702e-06 9.67842643895195e-07 9.93352212531367e-06 5.27970997389205e-05 -2.46684786027124e-05 6.61292455746595e-06 1.47820666162642e-06 1.15518970793841e-06 1.71369743361644e-06 -2.46684786027124e-05 7.64016517290618e-05 -1.23362251687917e-06 7.79134295504126e-06 4.00738811191075e-05 -2.64892523162014e-06 6.61292455746595e-06 -1.23362251687917e-06 0.000100527386494655 1472 1456 0 0 572 1435 1419 0 0 551 0 0 0 0 0 117 117 0 771 0 0 0 0 0 1612 +333 430 0.994276522439759 -0.04755837619341 0.0956681649188784 0.0516675706507463 0.0396719066829407 0.995783461736041 0.0827129805600399 -0.0388614907052608 -0.0991984714864079 -0.0784442361606739 0.991970848900273 0.113389062971004 6.22421785585194e-05 1.61161529035482e-05 -6.76997252391233e-06 6.51742566045376e-07 -6.08583619846475e-06 4.61709420020066e-06 1.61161529035482e-05 6.97421507594568e-05 -8.78841405676211e-06 8.20265848881385e-06 3.05089259075914e-06 5.14294996441042e-05 -6.76997252391233e-06 -8.78841405676211e-06 1.49994982952524e-05 1.67212390124893e-06 2.67049406610933e-06 -2.58811353852049e-06 6.51742566045376e-07 8.20265848881385e-06 1.67212390124893e-06 9.35363867435038e-05 -4.23812357636957e-05 2.83751726303325e-06 -6.08583619846475e-06 3.05089259075914e-06 2.67049406610933e-06 -4.23812357636957e-05 9.9275193779257e-05 2.02864315586819e-05 4.61709420020066e-06 5.14294996441042e-05 -2.58811353852049e-06 2.83751726303325e-06 2.02864315586819e-05 0.000114231467544415 1803 1778 0 0 113 1817 1799 0 0 117 0 0 0 0 0 44 50 0 367 0 31 6 0 0 1851 +333 416 0.993126858693252 0.0283759449114019 0.113551082304215 0.0512290399547422 -0.0417825240730313 0.992194948129428 0.117487895497915 -0.0260480132266746 -0.109330980166466 -0.12142483542022 0.986561070648448 0.120743335940037 8.7746657858346e-05 3.76238013434929e-05 -1.79293754749136e-05 -8.377014692804e-06 9.45207569592111e-06 1.61218096640274e-05 3.76238013434929e-05 0.00010698218805446 -1.42921990233591e-05 4.78522305487657e-05 -2.30603652721152e-05 0.000100859552700037 -1.79293754749136e-05 -1.42921990233591e-05 1.99774822884579e-05 9.09658324662987e-06 -3.46370133190876e-06 -8.37612648687986e-06 -8.377014692804e-06 4.78522305487657e-05 9.09658324662987e-06 0.000110684666975298 -5.57541353072164e-05 5.95554615337599e-05 9.45207569592111e-06 -2.30603652721152e-05 -3.46370133190876e-06 -5.57541353072164e-05 8.92572912655333e-05 -3.93415253456215e-05 1.61218096640274e-05 0.000100859552700037 -8.37612648687986e-06 5.95554615337599e-05 -3.93415253456215e-05 0.0001749136905464 2072 2085 0 49 12 2031 2060 0 59 13 0 0 0 0 0 4 3 0 308 0 97 97 0 0 1668 +333 335 0.999508223058641 -0.00895119927197132 -0.0300530875244235 0.0401621240280057 0.00958766732794204 0.999731370930218 0.0211012467213531 0.00944443316788587 0.0298561329271878 -0.0213790086201434 0.999325547215248 0.0497074122024961 5.72828467041724e-05 -1.96012689386337e-06 -2.66376793936088e-06 1.36292171903838e-06 -1.05410244803778e-05 6.53752804666901e-07 -1.96012689386337e-06 3.39598621703724e-05 -4.18806763637524e-06 6.49054789271145e-06 2.00058474785826e-06 1.48562115585061e-05 -2.66376793936088e-06 -4.18806763637524e-06 1.45937396915814e-05 2.87872758721472e-06 -8.68216695283724e-07 -4.24992220924994e-06 1.36292171903838e-06 6.49054789271145e-06 2.87872758721472e-06 4.81612513602161e-05 -1.03378245406019e-05 8.22053536185783e-06 -1.05410244803778e-05 2.00058474785826e-06 -8.68216695283724e-07 -1.03378245406019e-05 6.15854092796676e-05 4.61667507773977e-07 6.53752804666901e-07 1.48562115585061e-05 -4.24992220924994e-06 8.22053536185783e-06 4.61667507773977e-07 4.27275008854258e-05 2694 2648 0 6 101 2671 2670 0 15 83 0 0 0 0 0 10 20 0 478 0 47 14 0 0 3158 +333 380 0.992960439221301 0.0286388142432114 0.114932086295276 0.0602320228187211 -0.0420581923068828 0.992347842857909 0.116089910134916 -0.0358119022958755 -0.110727930538411 -0.120106523944366 0.986566646661381 0.122473602198069 7.66234953750698e-05 4.50734799422935e-06 -1.23467787178347e-05 -4.52706000347368e-06 -1.1403836833058e-06 -1.82053787315299e-05 4.50734799422935e-06 7.94407210861645e-05 -6.90176823860117e-06 2.34949437832321e-05 5.00623376708514e-06 7.03799848482715e-05 -1.23467787178347e-05 -6.90176823860117e-06 1.43462874174971e-05 1.00707489262948e-06 2.57223616542079e-06 2.46733438970195e-06 -4.52706000347368e-06 2.34949437832321e-05 1.00707489262948e-06 6.55559805030808e-05 -1.34769075672983e-05 2.58137177673369e-05 -1.1403836833058e-06 5.00623376708514e-06 2.57223616542079e-06 -1.34769075672983e-05 6.09071664931521e-05 6.82637414299907e-06 -1.82053787315299e-05 7.03799848482715e-05 2.46733438970195e-06 2.58137177673369e-05 6.82637414299907e-06 0.000120508967915069 1992 2007 0 48 18 1942 1974 0 58 9 0 0 0 0 0 1 0 0 362 0 147 121 0 0 2147 +333 432 0.941662275002694 -0.299366680128301 0.153791256792151 0.0257518420826819 0.303752072041999 0.95273639637847 -0.00529506807872752 -0.0516201360798138 -0.144937360838888 0.0517005787658678 0.988089171880925 0.0548625435471342 6.9383658829338e-05 1.14398760937494e-05 -5.9188826454185e-06 -1.51340097165737e-06 4.06917254145913e-06 -3.73533976090176e-06 1.14398760937494e-05 4.76199664404415e-05 -1.36290352657678e-06 1.15929894736546e-06 -7.83193380851699e-07 1.1595723464406e-05 -5.9188826454185e-06 -1.36290352657678e-06 1.6773974227553e-05 5.65281345079682e-06 -2.80361166280586e-06 6.86861779184896e-07 -1.51340097165737e-06 1.15929894736546e-06 5.65281345079682e-06 6.58409959684351e-05 -4.82801183683776e-05 4.61711363736833e-06 4.06917254145913e-06 -7.83193380851699e-07 -2.80361166280586e-06 -4.82801183683776e-05 0.000147746403084676 -8.58501235251912e-06 -3.73533976090176e-06 1.1595723464406e-05 6.86861779184896e-07 4.61711363736833e-06 -8.58501235251912e-06 7.52515047251648e-05 1696 1689 0 0 477 1683 1676 0 0 450 0 0 0 0 0 115 115 0 606 0 0 0 0 0 1819 +333 414 0.992909731269958 0.0286009812784599 0.115378721692208 0.0511773414459413 -0.0420139592861158 0.992412646047522 0.115550712633285 -0.0233113460472457 -0.111198438723408 -0.119578943944428 0.98657781415893 0.123304455062407 6.32880833881279e-05 3.8687362557911e-06 -1.0270620318594e-05 -6.73116081269854e-06 1.78303632275366e-06 -1.20322797257641e-05 3.8687362557911e-06 5.47836604999347e-05 -2.15147300122601e-06 1.12733293236517e-05 -2.29367470444993e-06 3.56949364457697e-05 -1.0270620318594e-05 -2.15147300122601e-06 1.5227565363042e-05 4.35772106051439e-06 2.59540260288855e-06 1.8714763918643e-06 -6.73116081269854e-06 1.12733293236517e-05 4.35772106051439e-06 8.25069512354279e-05 -3.16294768274556e-05 1.51769487440651e-05 1.78303632275366e-06 -2.29367470444993e-06 2.59540260288855e-06 -3.16294768274556e-05 6.57315378910999e-05 -3.15751329059625e-06 -1.20322797257641e-05 3.56949364457697e-05 1.8714763918643e-06 1.51769487440651e-05 -3.15751329059625e-06 8.73023658398317e-05 2058 2073 0 50 14 2014 2045 0 61 15 0 0 0 0 0 3 2 0 300 0 91 92 0 0 1688 +333 431 0.980712210788756 -0.172059837990552 0.0927306408933751 0.0524595096749043 0.172162714553886 0.985044010908818 0.00694955323063664 -0.0546826047613572 -0.0925395014427255 0.00914924714571322 0.995666978436766 0.0856960148279963 8.62112707857956e-05 -1.67119794735873e-05 -1.12551024165864e-05 -1.72452225446648e-05 -3.9584149571231e-06 -3.50244882583662e-05 -1.67119794735873e-05 0.000114198526975194 -1.09108202451901e-05 1.15860671834923e-05 3.72058829581048e-05 7.91302410201524e-05 -1.12551024165864e-05 -1.09108202451901e-05 1.8193545871638e-05 5.1775604819268e-06 -4.49904386066991e-06 -3.42217780507813e-06 -1.72452225446648e-05 1.15860671834923e-05 5.1775604819268e-06 6.40107062271257e-05 -2.94703865282693e-05 2.43784854305523e-05 -3.9584149571231e-06 3.72058829581048e-05 -4.49904386066991e-06 -2.94703865282693e-05 0.000119249460498036 2.66295159182307e-05 -3.50244882583662e-05 7.91302410201524e-05 -3.42217780507813e-06 2.43784854305523e-05 2.66295159182307e-05 0.000134225653806657 1661 1660 0 0 374 1648 1647 0 0 339 0 0 0 0 0 85 85 0 462 0 0 0 0 0 1943 +333 434 0.849068437891833 -0.519880872642971 0.0938438385612241 -0.0191082682738985 0.52108308980814 0.853404722197328 0.0131450997449048 -0.0828416071797983 -0.0869206609036324 0.0377393480506002 0.995500145814551 -0.0629894047309088 6.66021771414537e-05 1.56859102173993e-05 -1.51923195050218e-05 -2.61424969812822e-06 -1.7897254310103e-06 1.72040364203575e-05 1.56859102173993e-05 5.00009333681285e-05 -9.27604521715654e-06 6.56749337593894e-06 -7.26808030478654e-06 2.05774345375735e-05 -1.51923195050218e-05 -9.27604521715654e-06 1.962191529641e-05 1.78094311419339e-06 6.32490688896019e-06 -5.15902532455403e-06 -2.61424969812822e-06 6.56749337593894e-06 1.78094311419339e-06 5.27777733126189e-05 -5.12812297280025e-06 1.3206238572126e-05 -1.7897254310103e-06 -7.26808030478654e-06 6.32490688896019e-06 -5.12812297280025e-06 6.93270470396361e-05 2.41687794214327e-06 1.72040364203575e-05 2.05774345375735e-05 -5.15902532455403e-06 1.3206238572126e-05 2.41687794214327e-06 8.00734644294539e-05 1588 1594 0 0 575 1563 1569 0 0 562 0 0 0 0 0 105 105 0 840 0 0 0 0 0 1268 +333 381 0.992015025650424 0.0279031402970804 0.122994323630602 0.062473952111674 -0.0427877998079204 0.991840218774908 0.120092400293026 -0.0274756196893771 -0.118639761763858 -0.124396122054124 0.985114314050156 0.130026107282221 6.70044931495613e-05 -5.73179978098998e-06 -9.2330760854371e-06 -3.68509370384215e-06 -5.17285867649351e-06 -2.69274141753753e-05 -5.73179978098998e-06 6.13006425851889e-05 -2.86828785360478e-06 3.27139697239591e-06 1.01788365288627e-05 3.76646717736e-05 -9.2330760854371e-06 -2.86828785360478e-06 1.57871147268951e-05 5.34649586246991e-06 4.23910203329863e-06 4.33505451037438e-06 -3.68509370384215e-06 3.27139697239591e-06 5.34649586246991e-06 7.17780190649811e-05 -2.47816944444261e-05 4.77042936183994e-06 -5.17285867649351e-06 1.01788365288627e-05 4.23910203329863e-06 -2.47816944444261e-05 7.19496427574539e-05 1.02503248800631e-05 -2.69274141753753e-05 3.76646717736e-05 4.33505451037438e-06 4.77042936183994e-06 1.02503248800631e-05 8.56791596228858e-05 1950 1964 0 42 6 1931 1962 0 52 11 0 0 0 0 0 0 0 0 357 0 121 99 0 0 2139 +333 384 0.992628053519458 0.0286667860823324 0.117761465437051 0.0585757883423936 -0.042237199124642 0.992535383523068 0.114409490274283 -0.0258034842524127 -0.11360266887832 -0.11853998409999 0.986429270547715 0.121074529895078 8.15370216299194e-05 3.5800289618994e-06 -1.20268968935997e-05 -1.3298919965113e-05 -8.58299994110703e-06 -2.49224663126538e-05 3.5800289618994e-06 5.57810441908213e-05 -4.64207781565302e-06 1.10037457819549e-05 8.66120078806955e-06 3.64291193546807e-05 -1.20268968935997e-05 -4.64207781565302e-06 1.45057834021429e-05 7.26065441208419e-06 6.26088037795845e-06 2.57496539837316e-06 -1.3298919965113e-05 1.10037457819549e-05 7.26065441208419e-06 5.95279764952469e-05 -1.91325177889193e-06 1.3713591305887e-05 -8.58299994110703e-06 8.66120078806955e-06 6.26088037795845e-06 -1.91325177889193e-06 6.2408731273431e-05 1.33394332235693e-05 -2.49224663126538e-05 3.64291193546807e-05 2.57496539837316e-06 1.3713591305887e-05 1.33394332235693e-05 9.05119475358813e-05 1906 1922 0 46 21 1854 1884 0 58 8 0 0 0 0 0 2 1 0 369 0 141 118 0 0 2158 +333 418 0.990501635397528 0.0271272777202818 0.134798446127206 0.0734007791255729 -0.0434121929959059 0.991899005918783 0.119380666594789 -0.0309605358605345 -0.130467972215823 -0.124098641655808 0.983655242127583 0.141854205365458 7.70421973751899e-05 4.84593428631935e-05 -1.40463915762634e-05 9.72141885406218e-06 -8.37213766192926e-06 3.57737541885672e-05 4.84593428631935e-05 0.000141588968236087 -1.70615639110993e-05 2.43942533679229e-05 1.45618113959299e-05 0.000116137466941436 -1.40463915762634e-05 -1.70615639110993e-05 1.79812824396551e-05 4.66871625992854e-06 4.7160256630139e-06 -9.94681266082824e-06 9.72141885406218e-06 2.43942533679229e-05 4.66871625992854e-06 8.18357207112239e-05 -3.68543036233086e-05 2.48416375634184e-05 -8.37213766192926e-06 1.45618113959299e-05 4.7160256630139e-06 -3.68543036233086e-05 9.48787068734317e-05 4.68922676376138e-06 3.57737541885672e-05 0.000116137466941436 -9.94681266082824e-06 2.48416375634184e-05 4.68922676376138e-06 0.000171942898338813 1675 1689 0 45 17 1658 1681 0 55 19 0 0 0 0 0 1 1 0 324 0 76 76 0 0 1562 +333 417 0.99347258883596 0.0284282708136939 0.110471936029554 0.0541178337992068 -0.0411138023579431 0.992594383555236 0.114306802029773 -0.0304916792255185 -0.106404278519459 -0.118102595878097 0.987284106202266 0.115196719863647 9.31740275017693e-05 1.77777557515527e-05 -1.66098897353263e-05 -6.00686347059078e-07 4.72938668686045e-07 -1.48364929097355e-05 1.77777557515527e-05 0.000143138039253203 -9.88245595400291e-06 3.0895648260585e-05 -8.82884748584982e-06 0.000143098285514081 -1.66098897353263e-05 -9.88245595400291e-06 1.77562928260679e-05 5.83428623121812e-06 1.5795284738753e-06 -8.89938506199288e-07 -6.00686347059078e-07 3.0895648260585e-05 5.83428623121812e-06 7.87113130690658e-05 -3.02680263856307e-05 3.26701161994034e-05 4.72938668686045e-07 -8.82884748584982e-06 1.5795284738753e-06 -3.02680263856307e-05 8.49160536977458e-05 -2.00064374626345e-06 -1.48364929097355e-05 0.000143098285514081 -8.89938506199288e-07 3.26701161994034e-05 -2.00064374626345e-06 0.000224950755437517 2042 2054 0 51 8 2002 2030 0 58 8 0 0 0 0 0 4 3 0 310 0 96 96 0 0 1719 +333 415 0.992554395287549 0.0277116457344455 0.118607913252261 0.0750734501928061 -0.041524167377531 0.992425379907828 0.115618375868227 -0.0464846059446229 -0.114505527896998 -0.119682621986203 0.986186875838214 0.125068760686773 8.68732729231286e-05 5.23828147139886e-05 -2.06744605839294e-05 2.60038985345985e-05 -9.19438912371101e-06 4.34700805464967e-05 5.23828147139886e-05 0.000124976518740015 -1.50291138314371e-05 6.65139669962649e-05 -2.76351148464351e-05 0.000129739141818592 -2.06744605839294e-05 -1.50291138314371e-05 2.21128966665292e-05 -1.3905073351756e-06 4.87824187220866e-06 -3.96096177854499e-06 2.60038985345985e-05 6.65139669962649e-05 -1.3905073351756e-06 0.000109988766622127 -4.81258397838942e-05 8.83766021130914e-05 -9.19438912371101e-06 -2.76351148464351e-05 4.87824187220866e-06 -4.81258397838942e-05 9.21864352089917e-05 -3.87038410260983e-05 4.34700805464967e-05 0.000129739141818592 -3.96096177854499e-06 8.83766021130914e-05 -3.87038410260983e-05 0.000219975397395735 1744 1757 0 47 12 1719 1748 0 56 6 0 0 0 0 0 2 1 0 281 0 76 77 0 0 1699 +333 379 0.992754885087056 0.0282499039139321 0.116789045139688 0.0736455433273015 -0.0416680401535588 0.992595262973505 0.114098283739585 -0.0429562550465818 -0.112700987420466 -0.118137999184899 0.986580914361838 0.122609640582501 8.88325663526838e-05 -1.32327951119404e-05 -9.05973686241653e-06 -1.7813152163542e-07 -1.46012463320459e-05 -4.16186204360076e-05 -1.32327951119404e-05 6.41265722727409e-05 -5.42138813094458e-06 1.40270708774088e-05 5.79758626727235e-06 5.28620572706319e-05 -9.05973686241653e-06 -5.42138813094458e-06 1.6386667376541e-05 6.8445197558849e-06 4.05415656830327e-06 2.51104228579258e-06 -1.7813152163542e-07 1.40270708774088e-05 6.8445197558849e-06 8.39559281995985e-05 -3.08717766783781e-05 1.13734383018842e-05 -1.46012463320459e-05 5.79758626727235e-06 4.05415656830327e-06 -3.08717766783781e-05 7.84676403329402e-05 1.02367938370783e-05 -4.16186204360076e-05 5.28620572706319e-05 2.51104228579258e-06 1.13734383018842e-05 1.02367938370783e-05 0.000105132284422999 1965 1980 0 50 19 1915 1945 0 62 8 0 0 0 0 0 1 0 0 354 0 143 117 0 0 2160 +333 382 0.992420775925291 0.0282263246858499 0.119600493755554 0.0535975459613981 -0.0424093337263848 0.992136713431272 0.117754788754761 -0.0197808089211267 -0.115336255898687 -0.121934476078438 0.985814146590902 0.123169591631499 9.50381923441253e-05 -2.30047208765834e-06 -1.92164114572377e-05 4.4508476288767e-06 -2.30889946438296e-05 -2.78381272220088e-05 -2.30047208765834e-06 6.26262772302966e-05 -1.78367766478158e-06 3.14865131219995e-05 -7.04856149528611e-06 3.83943211919973e-05 -1.92164114572377e-05 -1.78367766478158e-06 1.8915531444009e-05 5.30993661772008e-06 1.04927617047154e-05 5.42541260539885e-06 4.4508476288767e-06 3.14865131219995e-05 5.30993661772008e-06 0.000112272195547152 -4.49808769059891e-05 2.17769253308423e-05 -2.30889946438296e-05 -7.04856149528611e-06 1.04927617047154e-05 -4.49808769059891e-05 8.40075356839785e-05 -1.58279332495623e-07 -2.78381272220088e-05 3.83943211919973e-05 5.42541260539885e-06 2.17769253308423e-05 -1.58279332495623e-07 0.000102456080479077 1676 1698 0 40 8 1657 1693 0 51 12 0 0 0 0 0 4 2 0 372 0 123 100 0 0 2133 +333 422 0.992873694408726 0.0279855532977795 0.115838835274641 0.0588142243679848 -0.0419366207497202 0.991910781354892 0.119809522459702 -0.0318114169915307 -0.111548853832132 -0.123813612492912 0.986015741542797 0.121478706242502 0.000196289530672313 5.66571594489631e-05 -3.37106217678505e-05 -4.34802619443218e-06 -8.5484847808978e-06 3.60674197543119e-05 5.66571594489631e-05 0.00021545714647881 -8.964387539185e-06 6.99253280161311e-05 -3.97249467443463e-05 0.00023098513930092 -3.37106217678505e-05 -8.964387539185e-06 2.17069698085228e-05 7.93746996353575e-06 3.0925524436034e-06 4.54937475206373e-07 -4.34802619443218e-06 6.99253280161311e-05 7.93746996353575e-06 9.38894852471759e-05 -3.18408612671686e-05 8.81485263354439e-05 -8.5484847808978e-06 -3.97249467443463e-05 3.0925524436034e-06 -3.18408612671686e-05 6.58461389618715e-05 -5.42167162002172e-05 3.60674197543119e-05 0.00023098513930092 4.54937475206373e-07 8.81485263354439e-05 -5.42167162002172e-05 0.000338469174409044 2142 2149 0 37 12 2102 2125 0 47 12 0 0 0 0 0 3 2 0 313 0 99 100 0 0 1638 +333 425 0.992584660652195 0.0284952032098994 0.118168163360495 0.0594045824117797 -0.0425106912254868 0.992122467079901 0.117838242717808 -0.0339879782909735 -0.113879465091374 -0.121987842465207 0.985976893096986 0.129453714310824 7.24002419145922e-05 3.86907577346702e-06 -1.22006736146584e-05 -1.69312060040631e-05 1.79373504688583e-05 -1.09649943847793e-05 3.86907577346702e-06 5.98793318555266e-05 -2.64789229283713e-06 1.23024952030057e-05 -1.12674898619343e-06 3.77000166867755e-05 -1.22006736146584e-05 -2.64789229283713e-06 1.66838751921527e-05 9.57494280647469e-06 -3.26874501371066e-06 1.45297883477475e-06 -1.69312060040631e-05 1.23024952030057e-05 9.57494280647469e-06 6.50285317403096e-05 -1.02758753873158e-05 6.8495814110265e-06 1.79373504688583e-05 -1.12674898619343e-06 -3.26874501371066e-06 -1.02758753873158e-05 5.56351783516542e-05 -6.48303146891412e-06 -1.09649943847793e-05 3.77000166867755e-05 1.45297883477475e-06 6.8495814110265e-06 -6.48303146891412e-06 7.83859625428017e-05 2028 2038 0 40 13 1995 2017 0 53 13 0 0 0 0 0 2 1 0 334 0 78 79 0 0 1533 +333 419 0.99267847856595 0.0279993063198359 0.117496710752252 0.0703876551005488 -0.0418268907140773 0.992259806282041 0.116923000518798 -0.0429309699552309 -0.113313500542446 -0.120981468344264 0.986166078767711 0.12329592702193 6.86122294820636e-05 7.43215671416181e-06 -8.55305223775438e-06 2.89600032163236e-06 -4.76492818623224e-06 -9.03090392313647e-06 7.43215671416181e-06 7.06237090019568e-05 -6.30159226928247e-06 1.68952886606965e-05 -1.17019899343465e-06 5.85189172776009e-05 -8.55305223775438e-06 -6.30159226928247e-06 1.55179913351107e-05 2.61406885267614e-06 1.46911084723686e-06 9.64524408355901e-07 2.89600032163236e-06 1.68952886606965e-05 2.61406885267614e-06 7.38007414880552e-05 -1.6522213459272e-05 1.86153413187328e-05 -4.76492818623224e-06 -1.17019899343465e-06 1.46911084723686e-06 -1.6522213459272e-05 5.39475741979294e-05 -6.23783615630381e-06 -9.03090392313647e-06 5.85189172776009e-05 9.64524408355901e-07 1.86153413187328e-05 -6.23783615630381e-06 0.000122862325671436 1990 1997 0 38 10 1969 1993 0 48 9 0 0 0 0 0 0 0 0 293 0 74 75 0 0 1656 +333 383 0.991661157712866 0.0270243256259428 0.126007277996317 0.0606458773821325 -0.0429955189812097 0.991122619971282 0.125806746753896 -0.0228364750473882 -0.121488821012942 -0.130175412446919 0.984019729661535 0.133594356863513 4.84881584643599e-05 1.44328187916348e-05 -4.05018622037189e-06 6.79516106785135e-06 -3.04426788867572e-06 -6.75305291318254e-06 1.44328187916348e-05 5.32673742009135e-05 -2.67192693908581e-06 1.54924191043547e-05 -1.16693617255137e-05 2.16772701538162e-05 -4.05018622037189e-06 -2.67192693908581e-06 1.45249294272376e-05 2.51337636572595e-06 4.32284563004631e-06 1.15743398654133e-06 6.79516106785135e-06 1.54924191043547e-05 2.51337636572595e-06 7.37734030236226e-05 -1.71231216013352e-05 7.25098313135256e-06 -3.04426788867572e-06 -1.16693617255137e-05 4.32284563004631e-06 -1.71231216013352e-05 5.3158711585671e-05 -4.0331904067172e-06 -6.75305291318254e-06 2.16772701538162e-05 1.15743398654133e-06 7.25098313135256e-06 -4.0331904067172e-06 7.76414022642639e-05 2071 2086 0 42 18 2025 2053 0 52 11 0 0 0 0 0 2 2 0 351 0 146 122 0 0 2071 +333 423 0.992471364054832 0.0294007863991539 0.118895690797656 0.0636684094707182 -0.0429835863362289 0.992625689586779 0.113343070710328 -0.0361991938391374 -0.114686541655142 -0.117600315184449 0.986416323380601 0.126885785505332 7.77547963596604e-05 5.28070949461523e-06 -1.39059052954047e-05 -1.33594213921548e-05 8.16620372497275e-06 -2.78926622513158e-05 5.28070949461523e-06 6.69688739876131e-05 -8.12591970209473e-06 1.79556483156648e-05 6.31746451421246e-06 4.87326178286355e-05 -1.39059052954047e-05 -8.12591970209473e-06 1.65192180991995e-05 6.71534090279703e-06 3.31131768101171e-07 2.01557684894812e-06 -1.33594213921548e-05 1.79556483156648e-05 6.71534090279703e-06 6.42186197781385e-05 -1.74011097412667e-05 2.11357965607258e-05 8.16620372497275e-06 6.31746451421246e-06 3.31131768101171e-07 -1.74011097412667e-05 6.26415306091567e-05 4.95722193936812e-06 -2.78926622513158e-05 4.87326178286355e-05 2.01557684894812e-06 2.11357965607258e-05 4.95722193936812e-06 0.000108745360516692 1807 1818 0 41 8 1792 1813 0 52 6 0 0 0 0 0 2 1 0 324 0 83 84 0 0 1638 +333 426 0.991751998428461 0.0265182050379462 0.125398398772552 0.0689562845624156 -0.0421136760640293 0.991462651449107 0.123402791985761 -0.0258803287719225 -0.121055408394373 -0.127665953108385 0.9844018450386 0.132077864066447 5.53289839137175e-05 3.9825572986981e-06 -8.5819186369948e-06 1.84010579786878e-06 -4.11461536599002e-06 -1.23173303511288e-05 3.9825572986981e-06 4.90299895185477e-05 -1.57958555474847e-06 1.48473626267535e-05 -4.12161232126599e-06 2.96743677784976e-05 -8.5819186369948e-06 -1.57958555474847e-06 1.80867827921442e-05 6.15102641412319e-06 3.54935110728182e-06 5.11743099893058e-06 1.84010579786878e-06 1.48473626267535e-05 6.15102641412319e-06 6.41262487926811e-05 -1.28165111563177e-05 1.2014547936963e-05 -4.11461536599002e-06 -4.12161232126599e-06 3.54935110728182e-06 -1.28165111563177e-05 6.87825641596274e-05 -4.4233690618208e-06 -1.23173303511288e-05 2.96743677784976e-05 5.11743099893058e-06 1.2014547936963e-05 -4.4233690618208e-06 7.67931342623112e-05 1716 1725 0 43 25 1695 1715 0 49 24 0 0 0 0 0 1 0 0 343 0 90 91 0 0 1551 +333 385 0.992844125966866 0.0287492566190035 0.11590522756522 0.0572922583100848 -0.0420102630241292 0.992632698980613 0.113646217337436 -0.0327620003049957 -0.111784074598014 -0.117702188417713 0.98673730825785 0.118239003765218 9.58606124804764e-05 2.08981918240789e-06 -1.61161485606047e-05 -1.43736426327805e-05 -1.02265200760417e-05 -2.95847152244358e-05 2.08981918240789e-06 7.58299362518395e-05 -2.40833814962102e-06 3.10496454860213e-05 -2.74669705550891e-06 6.43037004220109e-05 -1.61161485606047e-05 -2.40833814962102e-06 1.64282005552112e-05 2.97606919368235e-06 5.8161859347285e-06 5.09085280602115e-06 -1.43736426327805e-05 3.10496454860213e-05 2.97606919368235e-06 7.2848988142136e-05 -1.73094920973508e-05 3.71178812568864e-05 -1.02265200760417e-05 -2.74669705550891e-06 5.8161859347285e-06 -1.73094920973508e-05 5.83394882380249e-05 -6.326747183655e-06 -2.95847152244358e-05 6.43037004220109e-05 5.09085280602115e-06 3.71178812568864e-05 -6.326747183655e-06 0.000140758445013916 2016 2030 0 41 5 1997 2030 0 53 5 0 0 0 0 0 2 0 0 356 0 122 99 0 0 2146 +333 413 0.991897945060997 0.028244774858074 0.123857576582892 0.0746152746690308 -0.0424672704237735 0.992602697313021 0.113738367447705 -0.0446505895670465 -0.119728850017548 -0.118076746144751 0.985760054218745 0.132615583954257 0.000115990663642896 6.37814750233375e-05 -1.84447167474733e-05 -7.65912655532288e-06 1.15730705766262e-06 4.25082501720502e-05 6.37814750233375e-05 0.000103042447888177 -1.64137297000072e-05 1.46024836274144e-05 4.06565447543085e-06 9.13790152392222e-05 -1.84447167474733e-05 -1.64137297000072e-05 1.94960320806973e-05 8.60294509207271e-06 1.4942040500494e-06 -7.6670377068211e-06 -7.65912655532288e-06 1.46024836274144e-05 8.60294509207271e-06 7.06326802551635e-05 -8.94715909539102e-06 2.63278696232817e-05 1.15730705766262e-06 4.06565447543085e-06 1.4942040500494e-06 -8.94715909539102e-06 5.33215012580391e-05 -8.7685377673103e-06 4.25082501720502e-05 9.13790152392222e-05 -7.6670377068211e-06 2.63278696232817e-05 -8.7685377673103e-06 0.000162902682420867 1629 1640 0 41 14 1599 1618 0 53 17 0 0 0 0 0 2 1 0 298 0 74 75 0 0 1604 +333 394 0.99226508255639 0.0293656552071545 0.120613698366375 0.0610811742107188 -0.0434165172542983 0.992349671642658 0.115573073075935 -0.028197278152781 -0.1162970849543 -0.119915751613217 0.985948883333294 0.130013745565696 8.51223421465952e-05 -3.68941651848402e-06 -1.19132350344192e-05 -2.06184915179083e-05 -6.48761596971424e-06 -2.72970252587799e-05 -3.68941651848402e-06 0.000108600467471652 2.0206138845638e-06 4.23564638902744e-05 -2.74182497765929e-06 9.80910234936167e-05 -1.19132350344192e-05 2.0206138845638e-06 1.67405653835374e-05 1.19245161072278e-05 3.01818707200945e-06 5.76503420936023e-06 -2.06184915179083e-05 4.23564638902744e-05 1.19245161072278e-05 0.00010659521853997 -2.75150743590992e-05 6.1152906989283e-05 -6.48761596971424e-06 -2.74182497765929e-06 3.01818707200945e-06 -2.75150743590992e-05 6.89675045724687e-05 -4.68265769483666e-06 -2.72970252587799e-05 9.80910234936167e-05 5.76503420936023e-06 6.1152906989283e-05 -4.68265769483666e-06 0.000168523186680234 1722 1739 0 52 8 1695 1718 0 61 11 0 0 0 0 0 2 1 0 163 0 112 91 0 0 1811 +333 388 0.992137471562069 0.0284682978552519 0.121872037562559 0.0654075879677616 -0.0425330598744609 0.992522854461655 0.114408575679463 -0.0353571679999277 -0.117703765191011 -0.118692625670311 0.985929959110355 0.126774849063269 0.00010554090809596 -6.8319933022807e-06 -1.29767634226023e-05 -1.26955730526325e-05 -1.59010628478593e-05 -3.70752493491062e-05 -6.8319933022807e-06 7.86587080272178e-05 6.39105122383835e-06 2.34102678027918e-05 -3.74466842458956e-06 6.93888772712374e-05 -1.29767634226023e-05 6.39105122383835e-06 1.82540591292102e-05 1.08065544514955e-05 5.01501968813304e-06 1.03229002078134e-05 -1.26955730526325e-05 2.34102678027918e-05 1.08065544514955e-05 0.000103005974258689 -6.04203725690373e-05 2.79749429851479e-05 -1.59010628478593e-05 -3.74466842458956e-06 5.01501968813304e-06 -6.04203725690373e-05 0.000100972398033643 4.49564236391406e-06 -3.70752493491062e-05 6.93888772712374e-05 1.03229002078134e-05 2.79749429851479e-05 4.49564236391406e-06 0.00014042003078896 2019 2034 0 46 5 1999 2033 0 56 6 0 0 0 0 0 1 0 0 366 0 123 99 0 0 2060 +333 420 0.99274596619758 0.0292085352868644 0.116628933223401 0.0646036886174214 -0.0423949291418446 0.992776913333928 0.112234889113037 -0.0358031544964627 -0.112508295611881 -0.116365208793495 0.986813569830166 0.11957079373824 0.000108916308800847 2.98901407199567e-05 -1.41907443314323e-05 8.35790078828318e-06 -1.28236474164143e-05 4.76692659017494e-06 2.98901407199567e-05 0.00010515541415353 -1.08590031401079e-05 2.67250145970859e-05 5.64370438248754e-06 9.54491396844898e-05 -1.41907443314323e-05 -1.08590031401079e-05 1.69936887009622e-05 2.2829344620587e-06 7.78680816119001e-06 -3.00949945853994e-06 8.35790078828318e-06 2.67250145970859e-05 2.2829344620587e-06 6.54198798974154e-05 -6.48970245734511e-06 2.99141982717098e-05 -1.28236474164143e-05 5.64370438248754e-06 7.78680816119001e-06 -6.48970245734511e-06 5.3102257829912e-05 1.49177674929689e-05 4.76692659017494e-06 9.54491396844898e-05 -3.00949945853994e-06 2.99141982717098e-05 1.49177674929689e-05 0.000187696924750212 1557 1569 0 50 10 1539 1561 0 60 13 0 0 0 0 0 1 1 0 325 0 81 82 0 0 1643 +333 387 0.992551074875425 0.0276727661627827 0.11864477138306 0.0554434621565954 -0.0421420068749588 0.991728523443604 0.121237729461249 -0.0174375013294298 -0.114308420600539 -0.125334567463522 0.985507397830449 0.123076582626234 6.31044192008995e-05 2.38803158692443e-05 -8.57551960482275e-06 1.46184975320286e-05 -3.66313747547607e-06 2.37894305998264e-06 2.38803158692443e-05 6.63869982129647e-05 -8.18768640599378e-06 1.76654873675744e-05 3.95943887466309e-06 4.07423363342746e-05 -8.57551960482275e-06 -8.18768640599378e-06 1.56797476367384e-05 2.9442449221813e-07 3.93599178176373e-06 -2.05393159768583e-06 1.46184975320286e-05 1.76654873675744e-05 2.9442449221813e-07 5.93202942841957e-05 -1.36363205732784e-05 6.48048976457121e-06 -3.66313747547607e-06 3.95943887466309e-06 3.93599178176373e-06 -1.36363205732784e-05 6.24631445215847e-05 5.9041826955174e-06 2.37894305998264e-06 4.07423363342746e-05 -2.05393159768583e-06 6.48048976457121e-06 5.9041826955174e-06 8.35199114820761e-05 1904 1917 0 37 16 1858 1884 0 49 9 0 0 0 0 0 2 2 0 363 0 147 123 0 0 2056 +333 421 0.99267568472859 0.02812168536896 0.117491088005151 0.0630699596086379 -0.0420452626643534 0.992150982606578 0.117765120474135 -0.0330354095280004 -0.113257144746415 -0.121842515259704 0.98606653966103 0.125925270120514 8.85945003338167e-05 -2.39290560943047e-06 -1.23545471503871e-05 -2.19849571334519e-05 5.61574879252719e-06 -2.04931096984698e-05 -2.39290560943047e-06 6.4018190534466e-05 7.80600736770675e-07 3.15661456341758e-05 -7.48541742488124e-06 4.09755065028389e-05 -1.23545471503871e-05 7.80600736770675e-07 1.96114816639851e-05 1.57376427395558e-05 -3.98800111284383e-06 8.58261442370386e-06 -2.19849571334519e-05 3.15661456341758e-05 1.57376427395558e-05 8.99833885814328e-05 -2.70952452566713e-05 2.54297493331135e-05 5.61574879252719e-06 -7.48541742488124e-06 -3.98800111284383e-06 -2.70952452566713e-05 7.78372340164685e-05 -4.90549244026861e-06 -2.04931096984698e-05 4.09755065028389e-05 8.58261442370386e-06 2.54297493331135e-05 -4.90549244026861e-06 8.90589286248337e-05 1634 1643 0 42 11 1613 1635 0 52 12 0 0 0 0 0 2 1 0 319 0 89 89 0 0 1648 +333 378 0.992622862033657 0.0286480141680219 0.117809783347312 0.0724702084530373 -0.042198601386403 0.992562644419125 0.114187017408919 -0.0404869964502984 -0.113662358805117 -0.118316052114419 0.986449278981395 0.130141347288854 7.9368062362422e-05 2.26832459395116e-05 -9.34764245907015e-06 1.09138262368476e-05 -1.27835628363905e-06 5.68130970961249e-06 2.26832459395116e-05 6.53427418438326e-05 -8.68947229372167e-06 2.15094919800578e-05 6.05895287024305e-06 5.120378039088e-05 -9.34764245907015e-06 -8.68947229372167e-06 1.36633495547723e-05 2.48938423268479e-06 3.59687906849996e-06 -4.03204996671557e-06 1.09138262368476e-05 2.15094919800578e-05 2.48938423268479e-06 5.33934624289363e-05 -8.52454966955495e-06 2.33966945264407e-05 -1.27835628363905e-06 6.05895287024305e-06 3.59687906849996e-06 -8.52454966955495e-06 5.44829670628106e-05 2.09706924236432e-06 5.68130970961249e-06 5.120378039088e-05 -4.03204996671557e-06 2.33966945264407e-05 2.09706924236432e-06 9.64671655251078e-05 1913 1931 0 48 8 1882 1905 0 60 6 0 0 0 0 0 1 0 0 370 0 115 91 0 0 2119 +333 427 0.992867014109375 0.0279750080891089 0.11589862473709 0.0641557078842334 -0.0417350376802442 0.992129529321376 0.118055849826994 -0.0342248095932985 -0.111683834655527 -0.122050792586363 0.986220221403758 0.122145344456644 6.44856170602153e-05 -8.12279093986646e-06 -8.16824503985013e-06 -2.26858441424191e-05 8.5043130754105e-06 -2.66535467170237e-05 -8.12279093986646e-06 7.97756508769301e-05 -1.3799789565823e-06 3.17836713391467e-05 -5.57051574559216e-06 7.12593095957227e-05 -8.16824503985013e-06 -1.3799789565823e-06 1.57781833175458e-05 6.30135759592385e-06 -2.59118101615642e-07 4.47119632395368e-06 -2.26858441424191e-05 3.17836713391467e-05 6.30135759592385e-06 8.43177670354592e-05 -3.10912772837079e-05 4.78722595569822e-05 8.5043130754105e-06 -5.57051574559216e-06 -2.59118101615642e-07 -3.10912772837079e-05 7.77100930157118e-05 -7.1702473345827e-06 -2.66535467170237e-05 7.12593095957227e-05 4.47119632395368e-06 4.78722595569822e-05 -7.1702473345827e-06 0.000154140830871243 1716 1730 0 49 14 1693 1724 0 61 10 0 0 0 0 0 2 1 0 351 0 81 81 0 0 1742 +333 386 0.991994408754133 0.0284421001594805 0.123037148613969 0.0647716124235656 -0.0429588961250022 0.992203035689792 0.116994312732211 -0.027245068623477 -0.118750268396577 -0.12134324417321 0.985481704979479 0.131032055065462 9.76820644409272e-05 2.82884890428808e-05 -1.5181707233873e-05 -1.29873064471003e-05 5.65762008622457e-06 1.67336224909943e-05 2.82884890428808e-05 8.4993511063043e-05 -8.12749975904975e-06 9.05261082288832e-06 1.88545692391745e-05 7.55635877128581e-05 -1.5181707233873e-05 -8.12749975904975e-06 1.75459469255151e-05 4.92269490153232e-06 1.51343286165891e-07 -3.83104827877761e-06 -1.29873064471003e-05 9.05261082288832e-06 4.92269490153232e-06 5.56823484460735e-05 9.85864551834752e-06 3.08813942045564e-06 5.65762008622457e-06 1.88545692391745e-05 1.51343286165891e-07 9.85864551834752e-06 4.13310385430348e-05 1.76366565626706e-05 1.67336224909943e-05 7.55635877128581e-05 -3.83104827877761e-06 3.08813942045564e-06 1.76366565626706e-05 0.000131833086486365 1942 1960 0 45 10 1911 1936 0 56 10 0 0 0 0 0 2 1 0 347 0 112 89 0 0 2068 +333 392 0.990870234954883 0.0284908391534318 0.131774237105697 0.071780087048741 -0.0441902541154641 0.992054208017934 0.117795032981532 -0.0275208795445568 -0.127371107091309 -0.122542729030501 0.984256003608863 0.143389086445583 8.30794473077875e-05 6.32332288330661e-06 -8.97321801087724e-06 -1.28595184092928e-05 -5.69679875500531e-06 -1.94934454845253e-05 6.32332288330661e-06 7.6900802701301e-05 -1.27540487924828e-06 2.6949099464997e-05 -7.33401038299594e-07 5.48297418936097e-05 -8.97321801087724e-06 -1.27540487924828e-06 1.67400932599978e-05 7.64589937294787e-06 5.10120484487827e-06 6.06510967759129e-07 -1.28595184092928e-05 2.6949099464997e-05 7.64589937294787e-06 8.15993257734441e-05 -1.72193955754938e-05 2.33889659314825e-05 -5.69679875500531e-06 -7.33401038299594e-07 5.10120484487827e-06 -1.72193955754938e-05 6.23893591941516e-05 8.42720542845902e-06 -1.94934454845253e-05 5.48297418936097e-05 6.06510967759129e-07 2.33889659314825e-05 8.42720542845902e-06 0.00010124340201105 1735 1750 0 36 8 1711 1741 0 46 9 0 0 0 0 0 1 0 0 150 0 125 103 0 0 1686 +333 376 0.99191881295554 0.027447389829163 0.123869727118611 0.0744170909822156 -0.0425285642346988 0.991765388734041 0.120800392935418 -0.0298932753984052 -0.119534052591755 -0.125092184011561 0.984918045204884 0.129613607349853 7.80896159915708e-05 2.28959752365694e-05 -1.01641777461331e-05 -8.89546943474487e-06 -1.59361433139256e-05 -3.72670286101584e-06 2.28959752365694e-05 7.49801791865787e-05 -6.27547248979525e-06 1.75106585016193e-05 -6.10051497518151e-06 5.67520789383983e-05 -1.01641777461331e-05 -6.27547248979525e-06 1.38090369609341e-05 6.20044007189556e-06 6.14192442723768e-06 -3.98438747023263e-07 -8.89546943474487e-06 1.75106585016193e-05 6.20044007189556e-06 5.90847080697795e-05 9.23809163534291e-07 2.04338659689329e-05 -1.59361433139256e-05 -6.10051497518151e-06 6.14192442723768e-06 9.23809163534291e-07 5.86031878431968e-05 2.56613522506269e-07 -3.72670286101584e-06 5.67520789383983e-05 -3.98438747023263e-07 2.04338659689329e-05 2.56613522506269e-07 9.54079585997714e-05 2069 2082 0 48 24 2019 2044 0 54 11 0 0 0 0 0 2 1 0 332 0 139 117 0 0 1994 +333 377 0.992242873005965 0.028023874776648 0.12111458793792 0.0692799982695393 -0.0423657386230547 0.992167049367197 0.117514638836671 -0.033765717913545 -0.116872687826508 -0.121734171835574 0.985657935719951 0.128988905581344 0.000109811966980471 1.31218217496422e-07 -1.47329225016489e-05 -1.59029087545928e-05 9.33754533100415e-06 -1.4355669513774e-05 1.31218217496422e-07 6.15882937250513e-05 -2.68451213990579e-06 1.71958385115275e-05 -3.72772829174692e-06 4.50404760507352e-05 -1.47329225016489e-05 -2.68451213990579e-06 1.4723715533063e-05 5.81553445319596e-06 2.03624629709075e-06 3.06249146620707e-06 -1.59029087545928e-05 1.71958385115275e-05 5.81553445319596e-06 6.01798761123555e-05 -1.22032856373209e-05 1.68113703119345e-05 9.33754533100415e-06 -3.72772829174692e-06 2.03624629709075e-06 -1.22032856373209e-05 5.46818087119671e-05 1.54649266057727e-06 -1.4355669513774e-05 4.50404760507352e-05 3.06249146620707e-06 1.68113703119345e-05 1.54649266057727e-06 8.86224534180662e-05 1739 1749 0 45 11 1718 1738 0 54 12 0 0 0 0 0 2 1 0 352 0 129 105 0 0 2046 +334 433 0.894536733218125 -0.411555313737893 0.174431237619724 -0.0219738782524057 0.421132121936083 0.906773411964993 -0.0202414235412661 -0.0652563176244237 -0.149839143073687 0.0915652941210203 0.984461288276728 -0.0473883845980173 0.000126376051473332 4.34191425159029e-05 -1.79780391013051e-05 -1.57255450168747e-05 2.75815677362284e-06 1.8588387368604e-05 4.34191425159029e-05 5.85777263115535e-05 -6.05444084532917e-06 -1.84257929399777e-07 -2.97113992917448e-06 2.94763302233279e-05 -1.79780391013051e-05 -6.05444084532917e-06 2.02399826501053e-05 8.85175482135279e-06 1.82040216217535e-06 -5.07130512049401e-06 -1.57255450168747e-05 -1.84257929399777e-07 8.85175482135279e-06 5.46546163604937e-05 -1.39842406578658e-05 1.82113336145442e-06 2.75815677362284e-06 -2.97113992917448e-06 1.82040216217535e-06 -1.39842406578658e-05 8.39775582874244e-05 8.43378378717494e-06 1.8588387368604e-05 2.94763302233279e-05 -5.07130512049401e-06 1.82113336145442e-06 8.43378378717494e-06 8.80013107413576e-05 1384 1365 0 0 549 1369 1350 0 0 520 0 0 0 0 0 118 118 0 779 0 0 0 0 0 1535 +333 395 0.991306118129536 0.0301018324065149 0.128086142282139 0.0660936240928344 -0.0441989569416331 0.993093395863218 0.108682838103046 -0.0274721575039364 -0.123929949423947 -0.113399236234779 0.985790028787645 0.13446090584861 0.000124915009853982 3.75626616339693e-05 -1.35337276427686e-05 -3.02636213137422e-05 3.07691241330078e-06 1.25968228957119e-05 3.75626616339693e-05 0.000161736253203842 -3.68890098879376e-07 5.52336738639668e-05 -1.94870464841033e-05 0.000158096810951162 -1.35337276427686e-05 -3.68890098879376e-07 1.68827770135351e-05 1.29387261235617e-05 4.69495018176884e-06 2.43423340566249e-06 -3.02636213137422e-05 5.52336738639668e-05 1.29387261235617e-05 0.000114511556512331 -3.40778797372061e-05 7.69616669115832e-05 3.07691241330078e-06 -1.94870464841033e-05 4.69495018176884e-06 -3.40778797372061e-05 7.18533819290411e-05 -2.07667415859019e-05 1.25968228957119e-05 0.000158096810951162 2.43423340566249e-06 7.69616669115832e-05 -2.07667415859019e-05 0.000244410367832984 2146 2159 0 44 13 2099 2125 0 56 7 0 0 0 0 0 2 1 0 152 0 137 118 0 0 1785 +333 412 0.992106569111476 0.0277885984670184 0.122279799317368 0.0694613599768146 -0.0420276746025053 0.992423138525999 0.115455570180533 -0.04083267676925 -0.118144953736344 -0.119683365232788 0.985757405243903 0.128890971642563 8.82980945420681e-05 3.14697942888494e-05 -1.20926213594481e-05 -3.51562248473234e-07 -6.56725852403019e-07 1.6054570696304e-05 3.14697942888494e-05 9.34083464377844e-05 -1.09243199615756e-05 2.54692571747576e-05 -8.08640400991796e-06 7.28168436106472e-05 -1.20926213594481e-05 -1.09243199615756e-05 1.80047604400476e-05 4.24501307929792e-06 4.18866431495148e-06 -5.2663199491442e-06 -3.51562248473234e-07 2.54692571747576e-05 4.24501307929792e-06 7.47545159629342e-05 -2.49907685995749e-05 2.19326036409949e-05 -6.56725852403019e-07 -8.08640400991796e-06 4.18866431495148e-06 -2.49907685995749e-05 6.68354160595554e-05 1.78517437695169e-06 1.6054570696304e-05 7.28168436106472e-05 -5.2663199491442e-06 2.19326036409949e-05 1.78517437695169e-06 0.000124304689241107 1761 1767 0 42 8 1751 1769 0 56 11 0 0 0 0 0 2 1 0 274 0 77 77 0 0 1624 +333 393 0.991676347062545 0.0295452445259693 0.125319995222579 0.0692491611209442 -0.0439812114417647 0.992502236122365 0.114039310468894 -0.0314753045638558 -0.121011056175877 -0.11860181203509 0.985540427615829 0.136755770588548 7.71559426359151e-05 2.02362809116853e-05 -7.12391131179253e-06 -6.80049432115474e-06 1.25238303662756e-06 -3.84418215535779e-07 2.02362809116853e-05 9.6435215651012e-05 -4.5633141481773e-06 2.51904280576102e-05 1.04895635658166e-05 7.77589906235358e-05 -7.12391131179253e-06 -4.5633141481773e-06 1.55953166273406e-05 4.22088311604023e-06 2.37678446993672e-06 -1.91025064664247e-06 -6.80049432115474e-06 2.51904280576102e-05 4.22088311604023e-06 8.37816019465951e-05 -2.25954971794113e-05 3.30414903122879e-05 1.25238303662756e-06 1.04895635658166e-05 2.37678446993672e-06 -2.25954971794113e-05 6.55283909843653e-05 8.87599835507419e-06 -3.84418215535779e-07 7.77589906235358e-05 -1.91025064664247e-06 3.30414903122879e-05 8.87599835507419e-06 0.000136831236877133 1742 1749 0 42 9 1724 1741 0 53 6 0 0 0 0 0 2 0 0 150 0 120 100 0 0 1787 +333 428 0.992447742845128 0.0274053891201833 0.119567647667674 0.0691982572186915 -0.041678671915821 0.992071932722717 0.118558713771478 -0.0343465166350131 -0.115370559628283 -0.122646748636013 0.98572177059253 0.126089356322331 7.09090494471839e-05 2.0525850353967e-06 -4.94414365232074e-06 -2.99073509697165e-06 -1.78709054567016e-05 -3.31379408900615e-05 2.0525850353967e-06 8.94966951389355e-05 -6.44429736738463e-06 1.43848196479767e-05 8.30559146166431e-06 7.03285605032679e-05 -4.94414365232074e-06 -6.44429736738463e-06 1.57682293940798e-05 5.91396144756246e-06 3.45682671105812e-06 1.52485888492916e-06 -2.99073509697165e-06 1.43848196479767e-05 5.91396144756246e-06 6.1081860238645e-05 -9.15749299084716e-06 2.369211644902e-05 -1.78709054567016e-05 8.30559146166431e-06 3.45682671105812e-06 -9.15749299084716e-06 7.66369306007614e-05 1.97563654356175e-05 -3.31379408900615e-05 7.03285605032679e-05 1.52485888492916e-06 2.369211644902e-05 1.97563654356175e-05 0.000136912572084807 1880 1895 0 45 16 1857 1887 0 52 18 0 0 0 0 0 1 1 0 344 0 79 80 0 0 1691 +333 373 0.991755262010013 0.0273681314694323 0.125189798527364 0.0791830046267034 -0.0426833233271922 0.991692764833944 0.121340817888105 -0.0431700845483996 -0.120828945974036 -0.125683911284936 0.984684680625693 0.132639650938259 5.36246911512257e-05 1.30725091274805e-05 -7.67169853424172e-06 9.40107129261101e-06 -1.61318109841546e-05 -4.73353308671557e-06 1.30725091274805e-05 5.92598137931942e-05 -5.05624018688808e-06 1.65386584613195e-05 -1.15383683028452e-05 4.00948756804005e-05 -7.67169853424172e-06 -5.05624018688808e-06 1.396813327055e-05 2.34301136088574e-06 4.05891209948306e-06 -5.32234678987996e-07 9.40107129261101e-06 1.65386584613195e-05 2.34301136088574e-06 0.00010446012926191 -7.20932121725757e-05 3.00146004970472e-05 -1.61318109841546e-05 -1.15383683028452e-05 4.05891209948306e-06 -7.20932121725757e-05 0.000114383261656333 -2.71253136324514e-05 -4.73353308671557e-06 4.00948756804005e-05 -5.32234678987996e-07 3.00146004970472e-05 -2.71253136324514e-05 0.00010258096156576 2007 2024 0 43 6 1984 2020 0 52 10 0 0 0 0 0 3 1 0 359 0 125 99 0 0 2110 +334 431 0.978800897864106 -0.170158267635752 0.113995466118701 0.0220172242323599 0.170565538604189 0.985326551402254 0.00624372824547463 -0.0383611433844043 -0.11338518148807 0.0133323312642818 0.993461649769118 0.0521470718912206 6.3467202130586e-05 1.43713417910059e-05 -8.19480075177832e-06 -7.94279630458713e-06 5.04966210954303e-06 -7.85080001600012e-06 1.43713417910059e-05 5.9081808347599e-05 -4.61530785094215e-06 4.74564830881101e-06 1.03942457497185e-05 2.79160524170827e-05 -8.19480075177832e-06 -4.61530785094215e-06 1.62482859881221e-05 4.9417120666154e-06 2.48061743594824e-06 1.13563196926186e-06 -7.94279630458713e-06 4.74564830881101e-06 4.9417120666154e-06 5.97179470348536e-05 -1.9081254579037e-05 1.4120955251543e-05 5.04966210954303e-06 1.03942457497185e-05 2.48061743594824e-06 -1.9081254579037e-05 7.39391708461792e-05 1.05006437193966e-05 -7.85080001600012e-06 2.79160524170827e-05 1.13563196926186e-06 1.4120955251543e-05 1.05006437193966e-05 8.95045113842799e-05 1765 1783 0 0 322 1745 1763 0 0 287 0 0 0 0 0 76 76 0 469 0 0 0 0 0 2031 +334 432 0.940345046471241 -0.297612015015439 0.164858369807088 -0.00617219930964422 0.304133233255192 0.952507591848828 -0.0152402066944399 -0.0461230914459596 -0.152493180197489 0.0644699619109242 0.986199500103534 0.0148374039100671 9.62016491143866e-05 1.32270337455757e-07 -1.29257627652652e-05 1.0641043170543e-07 -2.03935864345163e-05 -1.16350303786042e-05 1.32270337455757e-07 7.56856717692318e-05 3.86528823877141e-07 9.68703204870748e-06 2.68091552988268e-06 5.05118938192129e-05 -1.29257627652652e-05 3.86528823877141e-07 1.81411175619087e-05 3.79725657575996e-06 5.23491349471102e-06 1.44580142949979e-06 1.0641043170543e-07 9.68703204870748e-06 3.79725657575996e-06 5.87094295121426e-05 -2.80256964203722e-05 1.74984042566396e-05 -2.03935864345163e-05 2.68091552988268e-06 5.23491349471102e-06 -2.80256964203722e-05 0.000109656055748484 -2.13056907902358e-06 -1.16350303786042e-05 5.05118938192129e-05 1.44580142949979e-06 1.74984042566396e-05 -2.13056907902358e-06 0.000121414690276336 1638 1638 0 0 459 1580 1580 0 0 431 0 0 0 0 0 115 115 0 625 0 0 0 0 0 1904 +334 384 0.990292007475886 0.0273944247521986 0.136276503557565 0.031958678552501 -0.0425950631153919 0.993028460043517 0.109909681747322 -0.0178822319608144 -0.132315533961719 -0.114647385648771 0.984555014428512 0.0905873984942806 8.05504035142625e-05 2.22318528057341e-05 -9.67851496910555e-06 4.02112513659541e-06 -1.40325946193774e-05 -1.9414994930155e-06 2.22318528057341e-05 7.88139827004694e-05 -7.11493071514036e-06 2.59454119540613e-05 -6.54745676558974e-06 7.63120352309476e-05 -9.67851496910555e-06 -7.11493071514036e-06 1.44880117528864e-05 2.417984767212e-06 6.53187197064161e-06 6.31218170889054e-07 4.02112513659541e-06 2.59454119540613e-05 2.417984767212e-06 6.85255547155908e-05 -1.85681843852984e-05 4.10187612981321e-05 -1.40325946193774e-05 -6.54745676558974e-06 6.53187197064161e-06 -1.85681843852984e-05 5.84162221617843e-05 -2.42953643528891e-06 -1.9414994930155e-06 7.63120352309476e-05 6.31218170889054e-07 4.10187612981321e-05 -2.42953643528891e-06 0.000162933159617604 1918 1932 0 59 8 1869 1887 0 60 1 0 0 0 0 0 0 5 0 373 0 148 127 0 0 2212 +334 430 0.99227876956342 -0.0473658589258226 0.114626868062964 0.0297203647569247 0.0388557986506782 0.996398276529139 0.0753704281597179 -0.0318069369097225 -0.117783998849262 -0.0703345572103806 0.990545294106785 0.0807251369326864 0.000109357362137618 3.35678789671872e-05 -2.0395121059565e-05 -1.01436683311708e-05 3.10381447939342e-06 1.124670968643e-05 3.35678789671872e-05 0.000113464350347264 -1.26023826417818e-05 3.86269969821261e-05 1.3555153264731e-06 9.77797579456177e-05 -2.0395121059565e-05 -1.26023826417818e-05 1.84251421520098e-05 2.80304120383895e-06 6.90688249905025e-07 -7.79516209529611e-06 -1.01436683311708e-05 3.86269969821261e-05 2.80304120383895e-06 7.87594007926097e-05 -1.08355322971177e-05 4.50971083802203e-05 3.10381447939342e-06 1.3555153264731e-06 6.90688249905025e-07 -1.08355322971177e-05 5.84850909599064e-05 -1.52867512722759e-06 1.124670968643e-05 9.77797579456177e-05 -7.79516209529611e-06 4.50971083802203e-05 -1.52867512722759e-06 0.00017058817157357 1801 1778 0 0 115 1788 1779 0 0 77 0 0 0 0 0 37 46 0 374 0 39 14 0 0 1904 +334 382 0.990034853543098 0.0269522904638678 0.13821925628742 0.0330029618650193 -0.0429290705173773 0.992559013033287 0.113946042278361 -0.0177170051123818 -0.134119661774142 -0.118744177478894 0.98382505387922 0.0908744402786079 6.71378441286159e-05 1.85745674704453e-05 -9.14213730646102e-06 9.3545161968963e-07 -4.33349969115793e-06 -3.19329747476937e-06 1.85745674704453e-05 6.44597439963473e-05 -7.15518610937903e-06 6.38867393357941e-06 1.40451889642332e-05 4.41901340003734e-05 -9.14213730646102e-06 -7.15518610937903e-06 1.46955598062106e-05 2.20670218640091e-06 1.80694168987717e-06 1.84386407804632e-06 9.3545161968963e-07 6.38867393357941e-06 2.20670218640091e-06 5.60298282735439e-05 -1.67529105016306e-05 -5.7368741106775e-07 -4.33349969115793e-06 1.40451889642332e-05 1.80694168987717e-06 -1.67529105016306e-05 6.57542460767069e-05 2.34301939934574e-05 -3.19329747476937e-06 4.41901340003734e-05 1.84386407804632e-06 -5.7368741106775e-07 2.34301939934574e-05 9.0476861947749e-05 1756 1766 0 54 5 1739 1759 0 53 1 0 0 0 0 0 0 7 0 367 0 147 133 0 0 2205 +334 380 0.99083162590709 0.0273699716069976 0.132301072393785 0.0344648148670354 -0.04202625356288 0.993121033264439 0.109290472133856 -0.0273172032822253 -0.12839970059849 -0.113848574615604 0.985165985478698 0.0852851822211312 7.6366663990798e-05 1.75947569575859e-05 -1.19753747539712e-05 7.70130555723533e-06 -4.59560404639519e-06 -1.18395717246735e-05 1.75947569575859e-05 5.25948926694491e-05 -9.09808798059981e-06 1.13675739492374e-05 7.48279104944985e-06 3.17889776057834e-05 -1.19753747539712e-05 -9.09808798059981e-06 1.65697219339352e-05 1.60631220177813e-06 3.20348002650548e-06 4.86385026175205e-07 7.70130555723533e-06 1.13675739492374e-05 1.60631220177813e-06 6.45812189436593e-05 -2.9279058771416e-05 1.04415224847392e-05 -4.59560404639519e-06 7.48279104944985e-06 3.20348002650548e-06 -2.9279058771416e-05 7.20829341762642e-05 7.72239333507741e-06 -1.18395717246735e-05 3.17889776057834e-05 4.86385026175205e-07 1.04415224847392e-05 7.72239333507741e-06 8.92390330881359e-05 1879 1891 0 53 7 1832 1846 0 52 0 0 0 0 0 0 0 3 0 346 0 152 130 0 0 2176 +334 381 0.989708371326743 0.026936987844813 0.140540878080414 0.0408570471784673 -0.0430808981628331 0.992646400133382 0.113124535427648 -0.0238220323801087 -0.136460162462343 -0.118014926971489 0.98359092160952 0.0949937628699096 7.1655966085815e-05 1.53061354731948e-05 -9.35199860124535e-06 -5.85082864830113e-06 4.8648270247761e-06 6.77819326387851e-06 1.53061354731948e-05 8.96436985554196e-05 -8.45882208253482e-06 2.88763730851309e-05 -3.17114192203029e-06 8.60413595668942e-05 -9.35199860124535e-06 -8.45882208253482e-06 1.55660169257566e-05 4.53633285015171e-07 3.74424929310772e-06 -5.67901567058074e-06 -5.85082864830113e-06 2.88763730851309e-05 4.53633285015171e-07 7.97211493199608e-05 -1.86244146933046e-05 4.09913645078467e-05 4.8648270247761e-06 -3.17114192203029e-06 3.74424929310772e-06 -1.86244146933046e-05 5.78140167904687e-05 -1.4104040798584e-05 6.77819326387851e-06 8.60413595668942e-05 -5.67901567058074e-06 4.09913645078467e-05 -1.4104040798584e-05 0.000155797438880636 1687 1695 0 54 5 1669 1685 0 46 0 0 0 0 0 0 0 6 0 350 0 145 131 0 0 2186 +334 385 0.990854701033508 0.0272850972454919 0.132145695760784 0.0362656865348766 -0.0422537329116013 0.992828594995749 0.111830241946449 -0.0307605336618071 -0.128146726430419 -0.116391169884448 0.984901777883509 0.0835402165337141 0.000130738066420581 9.92387419432249e-06 -2.26333712339958e-05 1.42337837580609e-05 -1.88969908577127e-05 -2.50759250715736e-05 9.92387419432249e-06 7.77256726838367e-05 -6.97527252550503e-06 1.85738786594233e-05 5.01377676123849e-06 5.64600785364303e-05 -2.26333712339958e-05 -6.97527252550503e-06 1.71492100455532e-05 -3.80131605301977e-07 7.92063346989427e-06 2.81589135591156e-06 1.42337837580609e-05 1.85738786594233e-05 -3.80131605301977e-07 6.79488281336478e-05 -2.19391828547696e-05 2.44812813069077e-05 -1.88969908577127e-05 5.01377676123849e-06 7.92063346989427e-06 -2.19391828547696e-05 6.89803462023434e-05 -8.72393358085281e-06 -2.50759250715736e-05 5.64600785364303e-05 2.81589135591156e-06 2.44812813069077e-05 -8.72393358085281e-06 0.000115388894483044 1691 1698 0 54 5 1677 1691 0 46 0 0 0 0 0 0 0 7 0 344 0 150 139 0 0 2167 +334 383 0.990189614081139 0.0268990451351835 0.137116627498859 0.0306049731075718 -0.0427121467145646 0.992593967912898 0.113722853402309 -0.0190767841615987 -0.133042101189357 -0.118463733833376 0.984005153989234 0.0944072369595893 0.000105443938987985 4.20160366596978e-05 -1.21826987745252e-05 9.5475191264804e-07 -8.25915485410143e-06 1.43171248611369e-05 4.20160366596978e-05 8.66525815480376e-05 -8.63641723990334e-06 2.00763733767956e-05 -1.19996670322809e-05 5.9009445071078e-05 -1.21826987745252e-05 -8.63641723990334e-06 1.48013210210564e-05 1.61082038268856e-06 4.52288731208731e-06 -1.1952741734741e-06 9.5475191264804e-07 2.00763733767956e-05 1.61082038268856e-06 6.86816428217818e-05 -1.18330620409704e-05 1.2418959426524e-05 -8.25915485410143e-06 -1.19996670322809e-05 4.52288731208731e-06 -1.18330620409704e-05 4.87737093959888e-05 -5.01176120235654e-06 1.43171248611369e-05 5.9009445071078e-05 -1.1952741734741e-06 1.2418959426524e-05 -5.01176120235654e-06 0.000116812762131069 1774 1783 0 55 7 1728 1740 0 54 0 0 0 0 0 0 0 2 0 342 0 151 130 0 0 2144 +334 415 0.991166329764094 0.0277565546041583 0.12968762631216 0.0383482356941873 -0.0420634114948459 0.993160543658612 0.108916499820484 -0.0372488261566595 -0.125777486679419 -0.113409471369179 0.985554826302612 0.0796442378246196 0.000124222386243318 2.60792466894655e-05 -2.23895667724765e-05 3.09921976261858e-06 -1.11520630701423e-05 8.15327894738727e-06 2.60792466894655e-05 7.61342195043291e-05 -9.93220102921591e-06 5.58535033425105e-06 1.04485908168709e-05 5.30845564732577e-05 -2.23895667724765e-05 -9.93220102921591e-06 1.86906919129108e-05 4.944497681993e-06 4.15521828967639e-06 -8.73880527527949e-07 3.09921976261858e-06 5.58535033425105e-06 4.944497681993e-06 5.10006406920239e-05 -1.31346339150543e-05 7.38098871680414e-06 -1.11520630701423e-05 1.04485908168709e-05 4.15521828967639e-06 -1.31346339150543e-05 6.0637956951874e-05 1.39405978573496e-06 8.15327894738727e-06 5.30845564732577e-05 -8.73880527527949e-07 7.38098871680414e-06 1.39405978573496e-06 0.000109842852800502 1783 1796 0 60 9 1769 1785 0 58 6 0 0 0 0 0 0 3 0 284 0 106 117 0 0 1723 +334 419 0.991344243397205 0.0281639452490051 0.128231756095104 0.0392203145302385 -0.0420130893903428 0.993412720653569 0.106611757154421 -0.0417027024557443 -0.124384450005225 -0.111076363965001 0.985997236286802 0.079728548877931 0.000153067239901328 0.000120886859574519 -2.56047328388181e-05 1.94856341509968e-05 -1.38026878413863e-05 0.000108914170105484 0.000120886859574519 0.000171954765504986 -2.51057109302079e-05 3.55449330291027e-05 -2.40824193617221e-05 0.000146659797895691 -2.56047328388181e-05 -2.51057109302079e-05 1.82603376268488e-05 -3.05481732178591e-06 6.48754376203382e-06 -2.06054556047907e-05 1.94856341509968e-05 3.55449330291027e-05 -3.05481732178591e-06 5.98569434673877e-05 -1.23822499540845e-05 3.53082184512151e-05 -1.38026878413863e-05 -2.40824193617221e-05 6.48754376203382e-06 -1.23822499540845e-05 5.21933805712031e-05 -2.94391443287752e-05 0.000108914170105484 0.000146659797895691 -2.06054556047907e-05 3.53082184512151e-05 -2.94391443287752e-05 0.000202766184119299 1670 1682 0 63 6 1662 1676 0 58 4 0 0 0 0 0 0 3 0 293 0 105 117 0 0 1692 +334 379 0.990640272421736 0.0278289397066413 0.133631585977989 0.0438707195639605 -0.0424464720165904 0.993264261796008 0.107816525876952 -0.0346754016763566 -0.129731059001048 -0.112479581941056 0.985148819202882 0.0883938903858386 0.000105961637372194 -4.79594587179139e-06 -1.12408646021334e-05 1.39154272576021e-05 -2.58121846445381e-05 -2.6630634718518e-05 -4.79594587179139e-06 6.9815670189025e-05 -3.7420337882924e-06 1.24832934691385e-05 1.53951191619166e-05 5.33392125273649e-05 -1.12408646021334e-05 -3.7420337882924e-06 1.4970774349424e-05 1.51504550029112e-06 6.07831446254974e-06 2.74442806131362e-06 1.39154272576021e-05 1.24832934691385e-05 1.51504550029112e-06 6.62959440266896e-05 -1.92836890240703e-05 1.53185477129081e-05 -2.58121846445381e-05 1.53951191619166e-05 6.07831446254974e-06 -1.92836890240703e-05 6.80418253748161e-05 1.7832744563423e-05 -2.6630634718518e-05 5.33392125273649e-05 2.74442806131362e-06 1.53185477129081e-05 1.7832744563423e-05 0.000114077995249268 1805 1815 0 58 7 1764 1777 0 55 0 0 0 0 0 0 0 4 0 345 0 152 129 0 0 2197 +334 425 0.98915774867505 0.0255938196893585 0.144609490109798 0.0405000850177647 -0.0433637090101524 0.991692566413363 0.121100959787113 -0.0242045025193752 -0.140308720245714 -0.126058756594636 0.982050229320692 0.102098567284872 0.000142446680542103 9.7263649055303e-05 -2.47276298389778e-05 -1.55951958220953e-05 2.82383688229899e-05 9.3987629863512e-05 9.7263649055303e-05 0.000184413181437071 -2.36867386440616e-05 -6.10271452692678e-06 3.80272316193821e-05 0.000167279042513832 -2.47276298389778e-05 -2.36867386440616e-05 1.95740235449038e-05 6.93077751700894e-06 -5.23758944442998e-07 -1.66023496574389e-05 -1.55951958220953e-05 -6.10271452692678e-06 6.93077751700894e-06 5.22365548101448e-05 -9.50776680438847e-06 -9.00781715770497e-06 2.82383688229899e-05 3.80272316193821e-05 -5.23758944442998e-07 -9.50776680438847e-06 5.94357993638909e-05 4.09031563172516e-05 9.3987629863512e-05 0.000167279042513832 -1.66023496574389e-05 -9.00781715770497e-06 4.09031563172516e-05 0.000224154914222589 1787 1800 0 54 5 1763 1782 0 51 2 0 0 0 0 0 0 5 0 319 0 117 120 0 0 1569 +334 424 0.991316278814359 0.0292469850084681 0.128205496081748 0.0318202956771368 -0.0432871621945331 0.993193481869338 0.108133848361209 -0.0293027486291749 -0.124170274006289 -0.112744496274431 0.985834885573151 0.0839989962606321 0.00011377064948232 1.3881371119706e-05 -1.86262773179681e-05 -1.35763913814475e-05 8.3071971601716e-06 -7.8096435534984e-06 1.3881371119706e-05 8.04677709708671e-05 -5.06703041290809e-06 5.96820637907242e-06 1.97480810143301e-05 6.02668901968039e-05 -1.86262773179681e-05 -5.06703041290809e-06 1.78155609260119e-05 4.84945565327884e-06 3.79474547841006e-06 5.06228742516183e-06 -1.35763913814475e-05 5.96820637907242e-06 4.84945565327884e-06 5.89176244047396e-05 -1.21349568576951e-05 3.43315921586266e-06 8.3071971601716e-06 1.97480810143301e-05 3.79474547841006e-06 -1.21349568576951e-05 6.69832073257899e-05 2.52356426829637e-05 -7.8096435534984e-06 6.02668901968039e-05 5.06228742516183e-06 3.43315921586266e-06 2.52356426829637e-05 0.000137950250927468 1772 1786 0 57 2 1750 1771 0 53 1 0 0 0 0 0 0 3 0 315 0 118 122 0 0 1682 +334 387 0.990177287408997 0.0264884571439555 0.137285473148087 0.0316726759040842 -0.0426771652951228 0.992290483201006 0.116354013730024 -0.019604045639823 -0.133145030180379 -0.121070056524504 0.98367395124168 0.0963003182801524 9.77736999134388e-05 3.23265153062059e-05 -1.20996154703741e-05 -4.90211857969618e-06 -1.88332978855434e-05 1.07477865449576e-05 3.23265153062059e-05 8.73603967405497e-05 -6.60168416179948e-06 1.75250868839648e-05 -6.51208176210161e-07 6.86940041627871e-05 -1.20996154703741e-05 -6.60168416179948e-06 1.4382319047014e-05 2.98513434869748e-06 4.64734556815469e-06 -1.33716707065283e-06 -4.90211857969618e-06 1.75250868839648e-05 2.98513434869748e-06 7.16334149442952e-05 -9.46747627411198e-06 1.54641921296732e-05 -1.88332978855434e-05 -6.51208176210161e-07 4.64734556815469e-06 -9.46747627411198e-06 5.78116862835403e-05 4.18720850977845e-06 1.07477865449576e-05 6.86940041627871e-05 -1.33716707065283e-06 1.54641921296732e-05 4.18720850977845e-06 0.000127567127612401 1880 1893 0 57 7 1832 1849 0 53 0 0 0 0 0 0 0 2 0 343 0 151 128 0 0 2073 +334 423 0.991364937836986 0.0294877590389639 0.127773362225189 0.0314850595114751 -0.0432285587154787 0.993411135536717 0.10613956615246 -0.0317506360677055 -0.123801662908266 -0.110746502692004 0.986107681950931 0.0816795910285909 0.000101338466593512 -1.3504188007531e-05 -1.95800374051736e-05 3.72625900454697e-06 -1.40362276308656e-05 -3.26846569299861e-05 -1.3504188007531e-05 6.52840602923924e-05 2.73281057848491e-08 8.51459610101526e-06 1.34005725986505e-05 5.13617508362532e-05 -1.95800374051736e-05 2.73281057848491e-08 1.7634098498981e-05 5.96599984160821e-06 2.90420412724918e-06 8.73563743592422e-06 3.72625900454697e-06 8.51459610101526e-06 5.96599984160821e-06 5.64474901848766e-05 -1.03400653943748e-05 1.59214894419693e-05 -1.40362276308656e-05 1.34005725986505e-05 2.90420412724918e-06 -1.03400653943748e-05 5.73314690658585e-05 1.18625495299019e-05 -3.26846569299861e-05 5.13617508362532e-05 8.73563743592422e-06 1.59214894419693e-05 1.18625495299019e-05 0.000123339665205984 1710 1723 0 61 6 1667 1684 0 56 3 0 0 0 0 0 0 4 0 311 0 111 113 0 0 1664 +334 378 0.989985340806157 0.0267079921581165 0.138620734898499 0.0477768101359168 -0.0426590218285115 0.992632366916857 0.113407195563918 -0.0304596124357132 -0.134570549696256 -0.118184886106136 0.983830828877875 0.0970972425667862 7.89127333063411e-05 1.78679638485736e-05 -8.51925940166675e-06 -5.42380197311268e-06 8.05968346036585e-06 -3.84697414708228e-07 1.78679638485736e-05 7.43131405517168e-05 -5.77029062026327e-06 2.10080217546222e-05 2.84819845425789e-06 5.46274319494643e-05 -8.51925940166675e-06 -5.77029062026327e-06 1.29317849932778e-05 2.41377885087247e-06 3.7505524679055e-06 2.3651071326705e-08 -5.42380197311268e-06 2.10080217546222e-05 2.41377885087247e-06 5.89934561888802e-05 -1.33350205513489e-05 2.74994953387193e-05 8.05968346036585e-06 2.84819845425789e-06 3.7505524679055e-06 -1.33350205513489e-05 4.7102566511532e-05 -3.0066752957106e-06 -3.84697414708228e-07 5.46274319494643e-05 2.3651071326705e-08 2.74994953387193e-05 -3.0066752957106e-06 0.000102777221786474 1731 1743 0 56 5 1710 1727 0 48 2 0 0 0 0 0 0 5 0 370 0 154 131 0 0 2206 +334 420 0.990693196072558 0.0279142992972679 0.133220805996218 0.0381722085344711 -0.0426980249374285 0.99307596219316 0.109439535728966 -0.0305985115487593 -0.12924345214355 -0.114109268724637 0.985025484375479 0.0893874299910123 9.10397609174748e-05 8.00182899567859e-06 -1.47265617669477e-05 -1.52372460251784e-06 -2.08621635678277e-07 -4.21922381290808e-06 8.00182899567859e-06 5.80689032556383e-05 -7.22708208483895e-06 7.95356326926951e-06 7.63104221961782e-06 3.3359201699714e-05 -1.47265617669477e-05 -7.22708208483895e-06 1.69432854977632e-05 5.16409439351987e-06 2.50482071211524e-06 1.21928133142921e-06 -1.52372460251784e-06 7.95356326926951e-06 5.16409439351987e-06 4.12994195351481e-05 -5.0367329085392e-06 4.79199591706914e-06 -2.08621635678277e-07 7.63104221961782e-06 2.50482071211524e-06 -5.0367329085392e-06 5.24131011235531e-05 5.32825414711312e-06 -4.21922381290808e-06 3.3359201699714e-05 1.21928133142921e-06 4.79199591706914e-06 5.32825414711312e-06 8.59351586995782e-05 1773 1785 0 59 5 1730 1747 0 56 2 0 0 0 0 0 0 3 0 318 0 108 110 0 0 1690 +334 386 0.988887979481866 0.0265066418356798 0.146280422390923 0.0482166611685663 -0.0438209846005849 0.992230170336538 0.116443163743346 -0.0215959051189983 -0.142057331190288 -0.121559397055594 0.982366035468742 0.105933384991547 7.93675618286679e-05 3.30618260662205e-05 -1.13289514762851e-05 -1.37690309967168e-05 4.34920912938133e-06 2.97142101247117e-05 3.30618260662205e-05 7.80550354146511e-05 -1.21269988617468e-05 3.89399702489939e-06 1.1801190049324e-05 5.61240201422957e-05 -1.13289514762851e-05 -1.21269988617468e-05 1.62579122383274e-05 4.89177671853623e-06 2.99702457865631e-06 -6.21037617908869e-06 -1.37690309967168e-05 3.89399702489939e-06 4.89177671853623e-06 4.65418536443089e-05 -2.05317994627993e-06 -8.94446913937348e-06 4.34920912938133e-06 1.1801190049324e-05 2.99702457865631e-06 -2.05317994627993e-06 5.40571552276728e-05 1.43324702049816e-05 2.97142101247117e-05 5.61240201422957e-05 -6.21037617908869e-06 -8.94446913937348e-06 1.43324702049816e-05 9.91490463525748e-05 1698 1714 0 56 6 1677 1696 0 52 4 0 0 0 0 0 0 6 0 337 0 152 130 0 0 2170 +334 426 0.990277087975465 0.0278954502594418 0.136283281754056 0.0350361821014676 -0.0436324204598541 0.992535051987134 0.113887586951831 -0.0176504532747049 -0.132088988623756 -0.118726637414353 0.984101867010034 0.0896330947339835 0.000128854530574726 2.98351786492794e-05 -2.27722194525916e-05 2.2666851299778e-05 -3.03675301798536e-05 1.64204765036494e-05 2.98351786492794e-05 0.000119718411209369 -8.39524560403917e-06 9.09484342090706e-06 8.59928417107551e-06 0.000101661972705554 -2.27722194525916e-05 -8.39524560403917e-06 1.87365062769766e-05 -1.2853012292672e-06 9.9480391464819e-06 -3.58355303794014e-06 2.2666851299778e-05 9.09484342090706e-06 -1.2853012292672e-06 6.09068466790739e-05 -1.73317220348336e-05 2.87848843599027e-06 -3.03675301798536e-05 8.59928417107551e-06 9.9480391464819e-06 -1.73317220348336e-05 7.13304684733124e-05 7.45636067223882e-06 1.64204765036494e-05 0.000101661972705554 -3.58355303794014e-06 2.87848843599027e-06 7.45636067223882e-06 0.000159082629322481 1633 1642 0 52 9 1586 1608 0 53 5 0 0 0 0 0 0 3 0 343 0 112 114 0 0 1605 +334 413 0.990075028382929 0.0269168196623866 0.137938112905045 0.0429723586947663 -0.0429995045842563 0.992437259758522 0.114975336696637 -0.0343462554423766 -0.133800152384259 -0.119765480261464 0.983744758034161 0.0941506015553155 7.40359196753265e-05 2.35435627472457e-05 -1.01430281679124e-05 -8.5122581658843e-06 8.60380958027412e-06 4.81744262398094e-06 2.35435627472457e-05 7.46242640881713e-05 -7.60854733006007e-06 1.51315722866179e-05 1.44059406464877e-05 6.22056901139872e-05 -1.01430281679124e-05 -7.60854733006007e-06 1.61923850642682e-05 5.32638101830074e-06 2.96544685872486e-06 1.57938639312113e-06 -8.5122581658843e-06 1.51315722866179e-05 5.32638101830074e-06 8.64265581743572e-05 -1.90516911774036e-05 1.64549639553811e-05 8.60380958027412e-06 1.44059406464877e-05 2.96544685872486e-06 -1.90516911774036e-05 6.01921106366414e-05 1.68749778702639e-05 4.81744262398094e-06 6.22056901139872e-05 1.57938639312113e-06 1.64549639553811e-05 1.68749778702639e-05 0.000123880912402895 1782 1797 0 61 6 1754 1772 0 58 1 0 0 0 0 0 0 3 0 298 0 109 113 0 0 1658 +334 388 0.990722061572262 0.0292091000166108 0.13272763536742 0.0361748356920896 -0.0432786331141449 0.993594600920916 0.104387398360994 -0.0296409762020232 -0.128828399934869 -0.109163169141544 0.985640221314652 0.0842850185881321 0.000169812269244779 0.000120077644728141 -1.43647688311464e-05 -4.90882162965975e-07 -1.85919978829589e-05 8.91113482225949e-05 0.000120077644728141 0.00020792962987044 -8.23398818099773e-06 3.61320588121923e-05 -2.50812379165516e-05 0.000175842219751206 -1.43647688311464e-05 -8.23398818099773e-06 1.54164000318354e-05 7.46161590100752e-06 5.77291828404173e-06 -4.25975375616321e-06 -4.90882162965975e-07 3.61320588121923e-05 7.46161590100752e-06 8.94352659751144e-05 -4.29515733050248e-05 3.80307019216565e-05 -1.85919978829589e-05 -2.50812379165516e-05 5.77291828404173e-06 -4.29515733050248e-05 7.69812316943016e-05 -2.15100540976586e-05 8.91113482225949e-05 0.000175842219751206 -4.25975375616321e-06 3.80307019216565e-05 -2.15100540976586e-05 0.000216600401754578 1647 1658 0 60 4 1636 1653 0 58 0 0 0 0 0 0 0 6 0 358 0 144 136 0 0 2076 +334 394 0.988538127038672 0.0282748008747347 0.14830005740514 0.0479006678184322 -0.0445602264315977 0.993187697466218 0.107668861896636 -0.0292094027703841 -0.144245476917782 -0.113043059217478 0.983063837780393 0.107164218357083 0.000123348488030612 1.89128936155306e-05 -1.39022828650401e-05 -1.61648637265096e-05 -1.7584794191986e-05 5.58505963745905e-06 1.89128936155306e-05 0.000113020419373107 8.66792188727772e-08 1.52023633897873e-05 5.15146663082743e-06 9.49273686555043e-05 -1.39022828650401e-05 8.66792188727772e-08 1.87082685565707e-05 6.81662287674269e-06 1.15146187684262e-05 7.39651866130525e-06 -1.61648637265096e-05 1.52023633897873e-05 6.81662287674269e-06 6.46573867298897e-05 -7.34375527712426e-06 1.68317794400555e-05 -1.7584794191986e-05 5.15146663082743e-06 1.15146187684262e-05 -7.34375527712426e-06 6.17400692213982e-05 1.10901030758525e-05 5.58505963745905e-06 9.49273686555043e-05 7.39651866130525e-06 1.68317794400555e-05 1.10901030758525e-05 0.000151427812496777 1828 1843 0 54 4 1775 1793 0 48 1 0 0 0 0 0 0 6 0 161 0 154 134 0 0 1845 +334 412 0.991204984276263 0.0290795290165207 0.129100968772779 0.0348474798822358 -0.0429927186806722 0.993401296078952 0.106327282900968 -0.0326757781703146 -0.125157122395561 -0.110942534407842 0.985914524070331 0.0828490111169566 0.000171694996921269 5.73023514902427e-05 -2.68056984556835e-05 2.13976171947013e-05 -3.85145003691159e-05 2.93844542045216e-05 5.73023514902427e-05 7.81887708396733e-05 -1.12372758174436e-05 1.76503215539014e-05 -5.04250175219235e-06 5.42059483449189e-05 -2.68056984556835e-05 -1.12372758174436e-05 2.0769818660996e-05 9.14701383429244e-07 8.56663668721106e-06 -5.52084677602226e-07 2.13976171947013e-05 1.76503215539014e-05 9.14701383429244e-07 6.003021110663e-05 -1.52040513864955e-05 1.62077708263252e-05 -3.85145003691159e-05 -5.04250175219235e-06 8.56663668721106e-06 -1.52040513864955e-05 6.59519994087762e-05 -7.24373370419422e-06 2.93844542045216e-05 5.42059483449189e-05 -5.52084677602226e-07 1.62077708263252e-05 -7.24373370419422e-06 0.000125645127311644 1691 1702 0 60 9 1651 1670 0 59 7 0 0 0 0 0 0 6 0 272 0 107 110 0 0 1660 +334 395 0.988315783658503 0.0292686788467169 0.149583609429797 0.0464762728194161 -0.0448289364020561 0.993800953165892 0.10173510676077 -0.024682906785474 -0.14567868146211 -0.10725208587777 0.983501251571308 0.106458758547338 0.000175678003996345 5.08260786211372e-05 -2.5346673512308e-05 3.4423738488661e-06 -1.68649376815177e-05 3.32175277725627e-05 5.08260786211372e-05 0.000178551885056655 -6.86847694209663e-06 5.98431895643998e-05 -1.78088519130686e-05 0.000177699959943591 -2.5346673512308e-05 -6.86847694209663e-06 2.18560365445047e-05 4.56273735754922e-06 7.47309565397779e-06 -3.67949299863958e-06 3.4423738488661e-06 5.98431895643998e-05 4.56273735754922e-06 7.9646550516156e-05 -2.23480793716734e-05 7.77099479088701e-05 -1.68649376815177e-05 -1.78088519130686e-05 7.47309565397779e-06 -2.23480793716734e-05 5.96688625203338e-05 -1.68006255357206e-05 3.32175277725627e-05 0.000177699959943591 -3.67949299863958e-06 7.77099479088701e-05 -1.68006255357206e-05 0.000270440743914063 1868 1879 0 60 2 1852 1867 0 56 0 0 0 0 0 0 0 2 0 153 0 147 132 0 0 1846 +334 427 0.990089181845144 0.0274445092382038 0.137732388732235 0.0404991113494566 -0.0426829971862813 0.993132019785297 0.108935545293413 -0.032932176895057 -0.133796762832324 -0.113734736074128 0.984460682844033 0.0891264333091052 0.000108287428037757 1.39967559592874e-05 -1.40153260572253e-05 1.6938148810441e-05 -3.16810811618403e-05 -4.0154614898029e-06 1.39967559592874e-05 6.53003382924192e-05 -7.58837479474307e-06 8.91042643380627e-06 1.31490633240503e-05 4.19135654660008e-05 -1.40153260572253e-05 -7.58837479474307e-06 1.74346385097418e-05 3.77224508249197e-07 6.32085053574356e-06 -3.3273873796254e-06 1.6938148810441e-05 8.91042643380627e-06 3.77224508249197e-07 5.0279251136368e-05 -1.40628298502451e-05 2.11989623770863e-06 -3.16810811618403e-05 1.31490633240503e-05 6.32085053574356e-06 -1.40628298502451e-05 7.11169811453658e-05 1.54665746098612e-05 -4.0154614898029e-06 4.19135654660008e-05 -3.3273873796254e-06 2.11989623770863e-06 1.54665746098612e-05 0.000103288179680282 1807 1818 0 58 9 1795 1810 0 56 7 0 0 0 0 0 0 3 0 335 0 107 114 0 0 1813 +334 376 0.989892856665925 0.0270900366117156 0.139205826882893 0.0491002210358264 -0.042682988957672 0.992983623643897 0.110280032774185 -0.0344813528302746 -0.135241616285126 -0.115107137447736 0.9841036795649 0.0951327869345516 9.63579153041735e-05 1.65024582860556e-05 -1.47426868747207e-05 -5.67151565642067e-06 -4.82217674560075e-06 -4.41649937605793e-06 1.65024582860556e-05 0.000196665406040825 -9.80524166349339e-06 4.97329102495515e-05 1.17634074268522e-06 0.000202775436813095 -1.47426868747207e-05 -9.80524166349339e-06 1.67970811097575e-05 5.8073426741834e-06 1.12679664036097e-06 9.25128911118012e-07 -5.67151565642067e-06 4.97329102495515e-05 5.8073426741834e-06 7.08700587639089e-05 -1.43491832166335e-05 6.45469925348801e-05 -4.82217674560075e-06 1.17634074268522e-06 1.12679664036097e-06 -1.43491832166335e-05 5.99978319732326e-05 2.52140787824712e-06 -4.41649937605793e-06 0.000202775436813095 9.25128911118012e-07 6.45469925348801e-05 2.52140787824712e-06 0.000286254289338939 1742 1751 0 56 8 1703 1720 0 52 0 0 0 0 0 0 0 5 0 334 0 149 131 0 0 2070 +334 393 0.986238055298067 0.0282815871151357 0.162894598167452 0.0501763090775621 -0.0461549792096895 0.99318636561615 0.107007294369762 -0.019383842784248 -0.158758357814762 -0.113053062693731 0.980823525839143 0.123565865181235 0.000115678444983794 6.75279290265188e-05 -1.22722170522406e-05 1.42852266313601e-05 -5.73867462903036e-06 4.52936374162879e-05 6.75279290265188e-05 0.000148628936519313 -7.61853438904772e-06 3.68026111182498e-05 -7.79823946003433e-06 0.000125785678764117 -1.22722170522406e-05 -7.61853438904772e-06 1.42716426876335e-05 3.77101313407381e-06 3.69697598648671e-06 -5.58832822986009e-06 1.42852266313601e-05 3.68026111182498e-05 3.77101313407381e-06 5.48280426440453e-05 -9.66804773498566e-06 3.40846386104273e-05 -5.73867462903036e-06 -7.79823946003433e-06 3.69697598648671e-06 -9.66804773498566e-06 5.6253754596468e-05 6.36681429656367e-07 4.52936374162879e-05 0.000125785678764117 -5.58832822986009e-06 3.40846386104273e-05 6.36681429656367e-07 0.000193453725981517 1768 1777 0 56 6 1743 1758 0 52 2 0 0 0 0 0 0 4 0 138 0 145 125 0 0 1795 +335 337 0.998206657819669 -0.0512463570866969 -0.0309399284069864 0.00241619388190419 0.0514146670074847 0.998666479294802 0.00466852754462217 0.0161607948881762 0.0306594243422175 -0.00625092139353698 0.999510342958359 0.015117076878286 5.9096022613405e-05 8.42042568705924e-06 -7.39077090079746e-06 6.12972813238635e-06 -4.23233217428552e-06 1.60841213671187e-05 8.42042568705924e-06 3.67088401519695e-05 -4.64516010318755e-06 9.28490779363424e-06 -1.86337222207518e-06 1.04657531860725e-05 -7.39077090079746e-06 -4.64516010318755e-06 1.59948295912945e-05 2.00926137141982e-06 1.55474884787931e-06 -2.06529343117252e-06 6.12972813238635e-06 9.28490779363424e-06 2.00926137141982e-06 5.61164159380904e-05 -2.58472997037862e-05 7.40951808899194e-06 -4.23233217428552e-06 -1.86337222207518e-06 1.55474884787931e-06 -2.58472997037862e-05 7.33588948181376e-05 -1.08409564291239e-06 1.60841213671187e-05 1.04657531860725e-05 -2.06529343117252e-06 7.40951808899194e-06 -1.08409564291239e-06 4.84705600640013e-05 1854 1830 0 0 138 1824 1807 0 0 103 0 0 0 0 0 68 61 0 453 0 19 19 0 0 3236 +334 392 0.987045594498865 0.0273231747301979 0.158096295032632 0.0463668078994899 -0.0454025026163073 0.992681614721019 0.111900958669021 -0.0159134892370708 -0.153881795988213 -0.117629315723304 0.981062555062576 0.121421972779978 8.15171349233457e-05 4.76791493267279e-05 -6.68185850380069e-06 -8.21765176525895e-06 1.76545333159487e-05 3.54468242731314e-05 4.76791493267279e-05 0.000112349885014809 -7.59227505611922e-06 1.26685704179761e-05 1.44781928760767e-05 9.66367943981736e-05 -6.68185850380069e-06 -7.59227505611922e-06 1.46391790657412e-05 6.65344541804037e-06 1.24743695311721e-06 -3.36401289053659e-06 -8.21765176525895e-06 1.26685704179761e-05 6.65344541804037e-06 7.12973024063458e-05 -2.20323970898099e-05 1.58685937915735e-05 1.76545333159487e-05 1.44781928760767e-05 1.24743695311721e-06 -2.20323970898099e-05 5.80957490898215e-05 1.8430569458214e-05 3.54468242731314e-05 9.66367943981736e-05 -3.36401289053659e-06 1.58685937915735e-05 1.8430569458214e-05 0.000151918523692195 1593 1600 0 50 8 1562 1580 0 44 1 0 0 0 0 0 0 6 0 143 0 139 118 0 0 1750 +334 411 0.989807590283928 0.0271739435042365 0.139794531405034 0.039814143129725 -0.0432791420084052 0.992596064841752 0.11348994637273 -0.0274004629070722 -0.135675532368002 -0.118383397717321 0.983655184026172 0.09667257498802 0.00014598629845942 8.70593131173168e-05 -2.5228415306566e-05 1.14004037831779e-05 -3.20121655201697e-05 8.49072485222025e-05 8.70593131173168e-05 0.000101297434694284 -1.84257532179458e-05 1.41766270488811e-05 -1.73479474302806e-05 8.86698520378326e-05 -2.5228415306566e-05 -1.84257532179458e-05 1.82401246972158e-05 2.96478195702426e-06 1.13226240379604e-05 -1.67336819462057e-05 1.14004037831779e-05 1.41766270488811e-05 2.96478195702426e-06 5.30796216249138e-05 -1.80164689407614e-05 1.20273756047502e-05 -3.20121655201697e-05 -1.73479474302806e-05 1.13226240379604e-05 -1.80164689407614e-05 6.43957000398613e-05 -1.80187823884185e-05 8.49072485222025e-05 8.86698520378326e-05 -1.67336819462057e-05 1.20273756047502e-05 -1.80187823884185e-05 0.000170299326709905 1776 1788 0 58 5 1732 1751 0 54 1 0 0 0 0 0 0 6 0 253 0 106 109 0 0 1728 +334 377 0.990675439716028 0.0275058562202572 0.133437629689101 0.0406680975005839 -0.042747771034095 0.992704356770096 0.112741687592864 -0.0318596421492602 -0.129363059700486 -0.11739458217167 0.984623639195031 0.093094918116029 0.000107735614037032 1.13745863704353e-05 -1.32288304407439e-05 8.18495911546537e-06 -2.59311042008072e-05 -1.28834321776627e-05 1.13745863704353e-05 7.39276855524758e-05 -8.36877597396592e-06 1.81943829228842e-05 -2.46288683414997e-06 6.06437645102778e-05 -1.32288304407439e-05 -8.36877597396592e-06 1.58561511384863e-05 2.77055662472888e-06 5.76982016861735e-06 1.18800618436022e-06 8.18495911546537e-06 1.81943829228842e-05 2.77055662472888e-06 5.56212725242748e-05 -1.34251953727149e-05 2.81960309287984e-05 -2.59311042008072e-05 -2.46288683414997e-06 5.76982016861735e-06 -1.34251953727149e-05 5.75356683000831e-05 -1.80005109037347e-06 -1.28834321776627e-05 6.06437645102778e-05 1.18800618436022e-06 2.81960309287984e-05 -1.80005109037347e-06 0.000107968848066175 1703 1715 0 58 9 1654 1668 0 56 0 0 0 0 0 0 0 7 0 334 0 145 121 0 0 2126 +335 432 0.940187967702962 -0.287988962209883 0.181958630001024 -0.0206640011286248 0.296726911585119 0.954704924272324 -0.0221731258809502 -0.0361356244452925 -0.16733118456442 0.0748389284760958 0.983056157834748 0.00120746140936079 8.03304516617812e-05 2.14200563501387e-05 -1.13691968447334e-05 -6.32073339397145e-06 -1.69912435317933e-07 2.30351222793962e-05 2.14200563501387e-05 7.01626420867879e-05 -6.09110367891296e-06 2.80467023138078e-06 -6.10273739708234e-06 4.64309042587542e-05 -1.13691968447334e-05 -6.09110367891296e-06 1.6829936609139e-05 3.16186586325816e-06 -6.97603135580963e-07 -7.90227879523553e-06 -6.32073339397145e-06 2.80467023138078e-06 3.16186586325816e-06 5.31098815263984e-05 -1.13359070679912e-05 1.00583529520149e-05 -1.69912435317933e-07 -6.10273739708234e-06 -6.97603135580963e-07 -1.13359070679912e-05 7.56418825902863e-05 -8.17630338928426e-06 2.30351222793962e-05 4.64309042587542e-05 -7.90227879523553e-06 1.00583529520149e-05 -8.17630338928426e-06 0.000104991117097527 1711 1703 0 0 479 1667 1659 0 0 440 0 0 0 0 0 143 143 0 619 0 0 0 0 0 2037 +334 396 0.99000957517364 0.0306369139010303 0.137631466500688 0.0367661566412201 -0.0445797922591916 0.994048967520909 0.0993946290940441 -0.0313835688658989 -0.133767272479619 -0.104537216708865 0.985483783294341 0.0993421565175845 0.000124974981036905 2.61603655950972e-05 -1.30250219329732e-05 -2.04346352707263e-05 1.43810186264994e-06 1.37429577577457e-05 2.61603655950972e-05 0.000131184635681795 -7.18289804877851e-07 3.1027982619418e-05 -1.03353678330912e-05 9.75838757358009e-05 -1.30250219329732e-05 -7.18289804877851e-07 1.54406675151517e-05 7.12585393910081e-06 4.44572992600238e-06 1.36755635511458e-06 -2.04346352707263e-05 3.1027982619418e-05 7.12585393910081e-06 9.39159638299187e-05 -2.98677402929215e-05 2.65401531242248e-05 1.43810186264994e-06 -1.03353678330912e-05 4.44572992600238e-06 -2.98677402929215e-05 7.85036996236347e-05 -1.54491414477464e-06 1.37429577577457e-05 9.75838757358009e-05 1.36755635511458e-06 2.65401531242248e-05 -1.54491414477464e-06 0.00015107398013109 1918 1930 0 56 3 1870 1886 0 54 0 0 0 0 0 0 0 2 0 160 0 157 139 0 0 1873 +335 431 0.978026643081414 -0.160938293543002 0.132524530160901 0.0113313552676221 0.163429126043308 0.986522108786358 -0.00806533548203023 -0.0391360101682485 -0.129440357630923 0.0295464811303115 0.991146911042553 0.0415066874709578 7.76830031042696e-05 2.59027649488288e-05 -1.53705388314469e-05 -2.30287923588603e-06 4.36235827965242e-06 1.01674046596876e-05 2.59027649488288e-05 7.01612246476723e-05 -9.50259801044194e-06 8.923443013975e-06 5.92537851042138e-06 4.27683507108468e-05 -1.53705388314469e-05 -9.50259801044194e-06 1.7092215864042e-05 3.26439905367161e-06 2.24080786939767e-06 -5.74966898988545e-06 -2.30287923588603e-06 8.923443013975e-06 3.26439905367161e-06 4.25802932105081e-05 -9.5289455689108e-06 2.08203969453968e-05 4.36235827965242e-06 5.92537851042138e-06 2.24080786939767e-06 -9.5289455689108e-06 4.80262314484485e-05 5.57038190119773e-06 1.01674046596876e-05 4.27683507108468e-05 -5.74966898988545e-06 2.08203969453968e-05 5.57038190119773e-06 9.9853177828242e-05 1795 1795 0 0 340 1757 1757 0 0 302 0 0 0 0 0 106 104 0 473 0 0 0 0 0 2183 +334 373 0.990763819496019 0.0270834284093519 0.132866631940661 0.0437427915081335 -0.0420118424376072 0.992946124346951 0.11087379870541 -0.0376976853898003 -0.128926564650801 -0.115431720293711 0.984912919438758 0.0878039480947906 9.21298795910745e-05 1.49770595882101e-05 -1.30354023188056e-05 7.99631011523965e-06 -9.3798302051519e-06 -1.31380137714684e-05 1.49770595882101e-05 0.000101580920980041 -6.06402652319385e-06 2.48854426647688e-05 -2.20393201685963e-06 7.84570285118462e-05 -1.30354023188056e-05 -6.06402652319385e-06 1.51057739584636e-05 1.17398549731912e-06 4.76386201196063e-06 1.55492546784388e-06 7.99631011523965e-06 2.48854426647688e-05 1.17398549731912e-06 5.70767596860097e-05 -1.87429938037036e-05 2.50215131041349e-05 -9.3798302051519e-06 -2.20393201685963e-06 4.76386201196063e-06 -1.87429938037036e-05 5.77186886189598e-05 3.74445545109835e-07 -1.31380137714684e-05 7.84570285118462e-05 1.55492546784388e-06 2.50215131041349e-05 3.74445545109835e-07 0.000128323401151863 1790 1800 0 57 4 1780 1795 0 50 0 0 0 0 0 0 0 0 0 349 0 152 136 0 0 2130 +335 433 0.895474791106109 -0.401663946920497 0.191809729257196 -0.0421044902178198 0.414538567328368 0.909513500317519 -0.0307077992946167 -0.055987798450995 -0.16211932238575 0.107010590524595 0.980951608808897 -0.0540801942638682 6.70795006199716e-05 2.28080278355914e-05 -8.84528093481676e-06 -1.04842178167679e-05 -1.51780145017349e-05 7.97554522036908e-06 2.28080278355914e-05 4.47213995640268e-05 -4.03987095912234e-06 3.58331880071078e-06 -4.51298235731513e-06 2.30497353967623e-05 -8.84528093481676e-06 -4.03987095912234e-06 1.98625364541225e-05 1.0830073234081e-05 -3.98480670378995e-06 -1.60136108737258e-06 -1.04842178167679e-05 3.58331880071078e-06 1.0830073234081e-05 5.27404649091005e-05 -1.04883448923404e-05 1.14245806741851e-05 -1.51780145017349e-05 -4.51298235731513e-06 -3.98480670378995e-06 -1.04883448923404e-05 0.000112778908952175 -2.69978046683637e-06 7.97554522036908e-06 2.30497353967623e-05 -1.60136108737258e-06 1.14245806741851e-05 -2.69978046683637e-06 7.80853694444406e-05 1399 1385 0 0 540 1374 1360 0 0 502 0 0 0 0 0 145 145 0 767 0 0 0 0 0 1677 +335 430 0.990278100654041 -0.039957577344806 0.133239166080243 0.0128061855824869 0.0313647749490119 0.997327955079756 0.0659787913562389 -0.0220387123094564 -0.135519497702074 -0.0611583357292047 0.988885293506487 0.0725490136840887 8.78994827970997e-05 1.15124518031233e-05 -1.60118083499573e-05 -6.02793905789207e-06 -8.96823162247992e-06 -5.76768284650758e-06 1.15124518031233e-05 8.19737800009846e-05 -1.00859587701783e-05 3.27485577664474e-05 -9.81036035711239e-06 5.90456120972905e-05 -1.60118083499573e-05 -1.00859587701783e-05 1.70022986837258e-05 2.99762649430495e-06 3.76649658155262e-06 -3.71933971258558e-06 -6.02793905789207e-06 3.27485577664474e-05 2.99762649430495e-06 8.56195632393586e-05 -3.83796527659839e-05 3.27657266028993e-05 -8.96823162247992e-06 -9.81036035711239e-06 3.76649658155262e-06 -3.83796527659839e-05 9.6005637604888e-05 -2.38999980251134e-06 -5.76768284650758e-06 5.90456120972905e-05 -3.71933971258558e-06 3.27657266028993e-05 -2.38999980251134e-06 0.000128320836105798 1614 1593 0 0 101 1572 1575 0 0 36 0 0 0 0 0 31 40 0 392 0 44 17 0 0 2008 +335 381 0.987156658325369 0.0342744234523772 0.156035239035604 0.0219520726404542 -0.0502834756790104 0.993732450307247 0.0998368132503928 -0.0157894082864035 -0.151635431207647 -0.106400569093227 0.982693042052862 0.0814845329629355 7.22624608793724e-05 1.28986434099394e-05 -9.87703520514227e-06 3.2271232843211e-06 -7.4340634481614e-06 -6.86526609982501e-06 1.28986434099394e-05 4.4358663995196e-05 -6.07008526336608e-06 -2.52197007368726e-06 9.14087093305703e-06 1.90363357879919e-05 -9.87703520514227e-06 -6.07008526336608e-06 1.49449181526698e-05 1.7156116202803e-06 4.00209549630587e-06 -5.84828255967483e-07 3.2271232843211e-06 -2.52197007368726e-06 1.7156116202803e-06 6.51557173828618e-05 -2.68864195341914e-05 -3.95688437834548e-06 -7.4340634481614e-06 9.14087093305703e-06 4.00209549630587e-06 -2.68864195341914e-05 6.90687763047758e-05 9.49436511414247e-06 -6.86526609982501e-06 1.90363357879919e-05 -5.84828255967483e-07 -3.95688437834548e-06 9.49436511414247e-06 5.88503394462703e-05 1697 1709 0 57 2 1684 1700 0 53 0 0 0 0 0 0 0 0 0 364 0 147 127 0 0 2328 +335 417 0.986476823587087 0.0339020338842416 0.160356255331817 0.0246086086282895 -0.05041829285995 0.993701456603615 0.100077024780629 -0.0213781935784309 -0.15595342981358 -0.106808554162885 0.981972739177119 0.0845252630892298 0.000118321288256246 0.000102200555643227 -2.30145735307185e-05 2.29705556050771e-05 -1.78429867372557e-05 0.000104943228228533 0.000102200555643227 0.000274056301008565 -2.80893298106519e-05 8.36892362033581e-05 -3.4476194490865e-05 0.000251068581083011 -2.30145735307185e-05 -2.80893298106519e-05 1.80187477362719e-05 -1.52851981213744e-06 6.74540348020249e-06 -2.39729304291902e-05 2.29705556050771e-05 8.36892362033581e-05 -1.52851981213744e-06 7.85143156705172e-05 -1.66362931480047e-05 7.78444790487594e-05 -1.78429867372557e-05 -3.4476194490865e-05 6.74540348020249e-06 -1.66362931480047e-05 6.70409087473878e-05 -3.09315955692194e-05 0.000104943228228533 0.000251068581083011 -2.39729304291902e-05 7.78444790487594e-05 -3.09315955692194e-05 0.000309413429495742 1700 1714 0 51 2 1668 1691 0 48 2 0 0 0 0 0 0 0 0 323 0 153 157 0 0 1818 +335 384 0.986626322623849 0.0333250085559364 0.159555455282758 0.0269830872993098 -0.0502078883382116 0.993415582234482 0.102978876097691 -0.0139423677594822 -0.155073103581372 -0.109612612314791 0.981803141045682 0.0823102261421581 6.73210130355467e-05 1.59123186031704e-05 -8.5239257061707e-06 -2.50918423560823e-06 1.85835981315761e-06 7.73507465334914e-07 1.59123186031704e-05 4.1888106485907e-05 -5.09918152264443e-06 6.88100054776289e-07 4.89364057939335e-06 2.27829866294528e-05 -8.5239257061707e-06 -5.09918152264443e-06 1.32656150264274e-05 4.50056523714232e-06 2.14775421561585e-06 -1.9445971762417e-06 -2.50918423560823e-06 6.88100054776289e-07 4.50056523714232e-06 4.49589572469116e-05 -4.86866038684909e-06 -7.50740260659904e-06 1.85835981315761e-06 4.89364057939335e-06 2.14775421561585e-06 -4.86866038684909e-06 5.3309213193244e-05 1.69705704321737e-05 7.73507465334914e-07 2.27829866294528e-05 -1.9445971762417e-06 -7.50740260659904e-06 1.69705704321737e-05 7.45278914949324e-05 1919 1937 0 56 0 1879 1906 0 55 0 0 0 0 0 0 0 0 0 383 0 196 177 0 0 2302 +335 380 0.987007402574814 0.0337333120961407 0.157093764731588 0.0216038999891694 -0.0501764158846636 0.99352732633842 0.101910642760209 -0.020470702720026 -0.152639164540063 -0.108468960877543 0.982311442453287 0.0819474272262173 5.71871826475573e-05 1.47030439654026e-05 -6.07285995301072e-06 4.10385401512426e-06 -6.00219453803018e-06 -4.14487085565441e-06 1.47030439654026e-05 6.34980135009138e-05 -5.1767777202946e-06 1.76042237842225e-05 -8.6332141043171e-06 4.38744603960864e-05 -6.07285995301072e-06 -5.1767777202946e-06 1.39993789465467e-05 1.97352203278027e-06 4.6848461039494e-06 -3.59626455769902e-07 4.10385401512426e-06 1.76042237842225e-05 1.97352203278027e-06 5.84246237452484e-05 -2.13114864552148e-05 1.6840722436714e-05 -6.00219453803018e-06 -8.6332141043171e-06 4.6848461039494e-06 -2.13114864552148e-05 6.12515285489679e-05 7.88740869604471e-06 -4.14487085565441e-06 4.38744603960864e-05 -3.59626455769902e-07 1.6840722436714e-05 7.88740869604471e-06 0.000103869332591113 1918 1934 0 57 0 1876 1903 0 54 0 0 0 0 0 0 0 0 0 354 0 203 181 0 0 2336 +335 383 0.986431750264422 0.0332956035581993 0.160760084765976 0.0233733645456869 -0.0506626781570332 0.993162789500727 0.105171130036205 -0.0147772049834824 -0.156159197975096 -0.111888678313897 0.981374153191811 0.0873272727308409 5.54566739434254e-05 1.81440653892466e-05 -8.55326803156341e-06 6.18740573234397e-06 -3.82599192315535e-06 5.09535635528776e-06 1.81440653892466e-05 7.17391545870988e-05 -6.87683950792879e-06 2.2472341650641e-05 1.33186768373146e-06 5.21582990000548e-05 -8.55326803156341e-06 -6.87683950792879e-06 1.45829131773591e-05 2.54212691624301e-06 2.92999124439722e-06 -3.8923899931591e-07 6.18740573234397e-06 2.2472341650641e-05 2.54212691624301e-06 7.39640279904072e-05 -2.30764225049805e-05 1.61341264518461e-05 -3.82599192315535e-06 1.33186768373146e-06 2.92999124439722e-06 -2.30764225049805e-05 6.08849092443604e-05 3.26635398198383e-06 5.09535635528776e-06 5.21582990000548e-05 -3.8923899931591e-07 1.61341264518461e-05 3.26635398198383e-06 0.00010465469265885 1696 1712 0 53 0 1652 1677 0 55 0 0 0 0 0 0 0 0 0 356 0 200 180 0 0 2260 +335 382 0.986930140791979 0.033026081078133 0.157728168584261 0.0155419304467821 -0.0500206796505329 0.99321103015214 0.105022765110349 -0.010109273398185 -0.153188866448 -0.111539802549338 0.98188188884592 0.0811519626090959 4.09460073435949e-05 4.14855293225221e-06 -5.7315766017698e-06 4.28400468639873e-06 -1.74806792559609e-06 -9.6436320432661e-06 4.14855293225221e-06 3.99434346150817e-05 -4.86639686461124e-06 -1.40800284351074e-06 1.15646396348075e-05 2.05698830544604e-05 -5.7315766017698e-06 -4.86639686461124e-06 1.26042234731735e-05 1.5820204724967e-07 2.14260120113799e-06 1.03186229016506e-07 4.28400468639873e-06 -1.40800284351074e-06 1.5820204724967e-07 5.53964468311033e-05 -1.52095426240292e-05 -7.53755761818585e-06 -1.74806792559609e-06 1.15646396348075e-05 2.14260120113799e-06 -1.52095426240292e-05 5.71725209681338e-05 1.58220903333731e-05 -9.6436320432661e-06 2.05698830544604e-05 1.03186229016506e-07 -7.53755761818585e-06 1.58220903333731e-05 6.56269676472717e-05 1770 1782 0 54 3 1751 1768 0 52 0 0 0 0 0 0 0 0 0 381 0 149 127 0 0 2271 +335 387 0.986893850146307 0.0335901842847657 0.157836079725499 0.0201431151641209 -0.0505095309993583 0.993247896580029 0.104438514052872 -0.00931965586566345 -0.153262245258327 -0.111041953598911 0.981926865259992 0.0825199220048689 6.05746471494734e-05 1.5903560814117e-05 -8.32773128033954e-06 1.10784783744649e-05 -1.09961930690515e-05 1.36515888276924e-05 1.5903560814117e-05 5.49875538594215e-05 -7.07967768598122e-06 1.61531682292674e-05 -9.2786798395424e-06 4.02953223545068e-05 -8.32773128033954e-06 -7.07967768598122e-06 1.43552885401269e-05 2.18332529958553e-06 2.40719943661623e-06 -3.37864762525382e-06 1.10784783744649e-05 1.61531682292674e-05 2.18332529958553e-06 6.85188337923122e-05 -2.60769432302794e-05 1.96034182837475e-05 -1.09961930690515e-05 -9.2786798395424e-06 2.40719943661623e-06 -2.60769432302794e-05 6.78754251109795e-05 -1.5651283080193e-05 1.36515888276924e-05 4.02953223545068e-05 -3.37864762525382e-06 1.96034182837475e-05 -1.5651283080193e-05 9.73911472450859e-05 1909 1927 0 56 0 1864 1891 0 54 0 0 0 0 0 0 0 0 0 356 0 200 180 0 0 2207 +335 415 0.986452128150409 0.0339087196363558 0.160506690203715 0.0308293259610293 -0.0499810432656647 0.994010897835723 0.097181429799602 -0.0278781163023819 -0.1562501013811 -0.103887120070017 0.982238958757976 0.0805978174993536 8.76645746295876e-05 2.38084714566419e-05 -1.68163693815362e-05 1.15013220985263e-05 -1.4712509844841e-05 1.0187289153464e-06 2.38084714566419e-05 7.0528011059123e-05 -1.02213465077158e-05 2.09039242662155e-05 -1.8341152546353e-06 4.43328084545391e-05 -1.68163693815362e-05 -1.02213465077158e-05 1.94377506430548e-05 2.29483308134679e-06 2.37572323511635e-06 -3.48528579457813e-06 1.15013220985263e-05 2.09039242662155e-05 2.29483308134679e-06 6.45645962820096e-05 -3.18514455111258e-05 1.58333321623098e-05 -1.4712509844841e-05 -1.8341152546353e-06 2.37572323511635e-06 -3.18514455111258e-05 8.32768264600398e-05 1.91197119227723e-06 1.0187289153464e-06 4.43328084545391e-05 -3.48528579457813e-06 1.58333321623098e-05 1.91197119227723e-06 0.000104709033919181 1836 1851 0 58 2 1821 1839 0 56 1 0 0 0 0 0 0 0 0 290 0 109 112 0 0 1851 +335 418 0.986811605110738 0.0341427066491985 0.158231259874385 0.020007536646378 -0.0507735563150746 0.99345859175559 0.102284272721273 -0.0141744969560104 -0.153703942688171 -0.108969271125701 0.98209001418019 0.0840617932007471 6.77630476060994e-05 2.10095977701271e-05 -1.18577157231917e-05 -2.38528945614723e-06 3.3570995148975e-06 1.74317665194066e-05 2.10095977701271e-05 8.91463139225511e-05 -1.10210709414833e-05 2.54277894185476e-05 6.67963907147868e-06 6.79920673914197e-05 -1.18577157231917e-05 -1.10210709414833e-05 1.59025148836008e-05 2.69621514210534e-06 8.20155085837429e-07 -6.39121012306049e-06 -2.38528945614723e-06 2.54277894185476e-05 2.69621514210534e-06 7.24392257903076e-05 -2.19555787148445e-05 1.73756140582405e-05 3.3570995148975e-06 6.67963907147868e-06 8.20155085837429e-07 -2.19555787148445e-05 7.69029061698579e-05 6.88874736181139e-06 1.74317665194066e-05 6.79920673914197e-05 -6.39121012306049e-06 1.73756140582405e-05 6.88874736181139e-06 0.000117655570472058 1439 1452 0 58 10 1377 1393 0 53 10 0 0 0 0 0 0 0 0 332 0 122 131 0 0 1684 +335 379 0.987553190688042 0.0346083509709949 0.153430627988467 0.0261236737767433 -0.0499555804510033 0.993997791087415 0.0973284711435651 -0.02280263322373 -0.149141327416884 -0.103781758302743 0.983354570386451 0.084047921069944 6.56482620813161e-05 1.318030310142e-05 -1.11248201715432e-05 -1.1094163951067e-07 -4.61394496150588e-06 6.03580751843007e-06 1.318030310142e-05 6.79856796741254e-05 -6.89303673600579e-06 2.51003494282569e-05 -4.05471699377596e-09 4.21250216841629e-05 -1.11248201715432e-05 -6.89303673600579e-06 1.47856131206439e-05 2.59388421744223e-06 3.17415921407751e-06 -3.84892831140768e-06 -1.1094163951067e-07 2.51003494282569e-05 2.59388421744223e-06 6.8975310992144e-05 -1.07854559010005e-05 1.446347248325e-05 -4.61394496150588e-06 -4.05471699377596e-09 3.17415921407751e-06 -1.07854559010005e-05 5.12167202042451e-05 -3.30145609218775e-06 6.03580751843007e-06 4.21250216841629e-05 -3.84892831140768e-06 1.446347248325e-05 -3.30145609218775e-06 8.64650919204185e-05 1806 1819 0 56 0 1763 1790 0 56 0 0 0 0 0 0 0 0 0 361 0 201 179 0 0 2290 +335 419 0.987809413551151 0.0328277378639568 0.152167349081421 0.023398155283768 -0.0492840963994849 0.993179242864937 0.105669623754019 -0.0210734814066019 -0.14766055784067 -0.111880879371611 0.982689690843054 0.0753410928105416 8.15691737872731e-05 4.17971438415929e-05 -1.452918596566e-05 1.1818392858778e-05 -3.43661168096122e-06 3.70146747528717e-05 4.17971438415929e-05 9.33681935648874e-05 -1.07740308610637e-05 1.88027984683959e-05 -6.49988974736442e-08 7.4343182169589e-05 -1.452918596566e-05 -1.07740308610637e-05 1.72169703724335e-05 -2.21306744674325e-07 5.91614029817832e-06 -4.34886873283581e-06 1.1818392858778e-05 1.88027984683959e-05 -2.21306744674325e-07 5.90327659061797e-05 -1.19428707486511e-05 2.12244496148861e-05 -3.43661168096122e-06 -6.49988974736442e-08 5.91614029817832e-06 -1.19428707486511e-05 4.7535473353463e-05 -3.54369251719411e-06 3.70146747528717e-05 7.4343182169589e-05 -4.34886873283581e-06 2.12244496148861e-05 -3.54369251719411e-06 0.000141055817283906 1700 1711 0 55 3 1687 1701 0 54 2 0 0 0 0 0 0 0 0 307 0 105 108 0 0 1746 +335 385 0.987313137371956 0.0341891893194248 0.155060852914027 0.0215024032916149 -0.0498778924183973 0.993891877024514 0.0984435504875152 -0.0199191044836838 -0.15074801697085 -0.104928719225814 0.982987792020321 0.0773529002623458 6.91257455974446e-05 1.29696485769633e-05 -1.23336886636061e-05 -7.50662660939028e-06 -1.26698018912949e-06 4.36709282057979e-06 1.29696485769633e-05 5.14610834811337e-05 -6.80186147391642e-06 1.58572006540831e-05 -1.56695036862492e-06 2.98557925629451e-05 -1.23336886636061e-05 -6.80186147391642e-06 1.45271403152539e-05 6.08199215979834e-06 2.77927646110891e-06 -3.611875063478e-06 -7.50662660939028e-06 1.58572006540831e-05 6.08199215979834e-06 6.52766909142871e-05 -1.72671475168802e-05 1.81296362443523e-05 -1.26698018912949e-06 -1.56695036862492e-06 2.77927646110891e-06 -1.72671475168802e-05 4.84731089971273e-05 -8.07176549696267e-06 4.36709282057979e-06 2.98557925629451e-05 -3.611875063478e-06 1.81296362443523e-05 -8.07176549696267e-06 7.82120263477374e-05 1716 1726 0 58 1 1705 1718 0 56 0 0 0 0 0 0 0 0 0 361 0 149 129 0 0 2294 +335 426 0.987724290151312 0.0336720385581826 0.152534981117197 0.0191817253494252 -0.049840054680078 0.993385724223119 0.103444535182852 -0.012778009875568 -0.148042884309157 -0.109777031883021 0.982869425547656 0.0742462575057473 8.72209707955637e-05 2.66332143729955e-05 -1.30318087451411e-05 -2.91553299658701e-06 -2.4971253917448e-06 2.7100631968241e-05 2.66332143729955e-05 7.51584668056198e-05 -1.01374529181705e-05 1.36554092310082e-05 1.01058225738041e-05 6.09591535307043e-05 -1.30318087451411e-05 -1.01374529181705e-05 1.57615693641187e-05 2.03144136307855e-06 4.25085587490299e-06 -6.50295615594235e-06 -2.91553299658701e-06 1.36554092310082e-05 2.03144136307855e-06 6.35071887082853e-05 -1.35065998057753e-05 1.78852294327966e-06 -2.4971253917448e-06 1.01058225738041e-05 4.25085587490299e-06 -1.35065998057753e-05 6.16148556899814e-05 1.72970758647754e-05 2.7100631968241e-05 6.09591535307043e-05 -6.50295615594235e-06 1.78852294327966e-06 1.72970758647754e-05 0.000120106286781707 1403 1411 0 50 10 1338 1350 0 53 10 0 0 0 0 0 0 0 0 364 0 121 129 0 0 1703 +335 413 0.986795642115925 0.0345872580801973 0.15823426392382 0.0266124291791152 -0.0507240264941018 0.993783182523819 0.0991063028725006 -0.026294575519078 -0.153822735111702 -0.105823946776351 0.982415318717818 0.0831226700345132 9.99782791437199e-05 3.15772103588406e-05 -1.53954656571336e-05 8.5895475845493e-06 -1.52303463630967e-05 1.59913634909954e-05 3.15772103588406e-05 6.35625740410138e-05 -9.28734774170193e-06 1.19843717162935e-05 3.11223958419349e-06 5.30779354456269e-05 -1.53954656571336e-05 -9.28734774170193e-06 1.59686920080709e-05 4.14450953213391e-06 3.16246347878787e-06 -3.11917259540457e-06 8.5895475845493e-06 1.19843717162935e-05 4.14450953213391e-06 5.83813878656026e-05 -1.38024479936814e-05 8.39728673287651e-06 -1.52303463630967e-05 3.11223958419349e-06 3.16246347878787e-06 -1.38024479936814e-05 6.51846728475117e-05 3.35738311122626e-07 1.59913634909954e-05 5.30779354456269e-05 -3.11917259540457e-06 8.39728673287651e-06 3.35738311122626e-07 0.000121296037250898 1716 1727 0 53 7 1661 1672 0 53 7 0 0 0 0 0 0 0 0 310 0 106 113 0 0 1847 +335 425 0.988446891917266 0.0351254866747787 0.147441317292529 0.0161755662131638 -0.050223952146548 0.993722749050856 0.0999632564975285 -0.0196518732160245 -0.14300453310954 -0.106213455855035 0.984006303488678 0.0768791281753077 8.64031452641694e-05 4.18115360321635e-05 -1.20057512906166e-05 1.19632566672068e-05 4.94221682171305e-07 3.26112730982195e-05 4.18115360321635e-05 9.08847189552165e-05 -9.49218992979457e-06 2.17360418947572e-05 2.65279478215138e-06 7.40953798654744e-05 -1.20057512906166e-05 -9.49218992979457e-06 1.67622488734103e-05 1.2216770371448e-06 1.04284501638253e-06 -5.03041624029115e-06 1.19632566672068e-05 2.17360418947572e-05 1.2216770371448e-06 6.98649195675676e-05 -1.66816145411296e-05 1.16448588245143e-05 4.94221682171305e-07 2.65279478215138e-06 1.04284501638253e-06 -1.66816145411296e-05 5.54080660141709e-05 2.53881267320998e-06 3.26112730982195e-05 7.40953798654744e-05 -5.03041624029115e-06 1.16448588245143e-05 2.53881267320998e-06 0.000127818909636799 1633 1644 0 56 4 1616 1628 0 56 4 0 0 0 0 0 0 0 0 348 0 114 117 0 0 1692 +335 424 0.987553251775568 0.0347507661990209 0.153398041565344 0.0149805839045044 -0.0508976132972817 0.993417363195535 0.102622490041271 -0.0116365374659543 -0.148822067813017 -0.109152767945717 0.982821278453843 0.0811977801710514 0.000108417524909478 5.069671919503e-05 -1.59339603721863e-05 2.04435218219129e-05 -1.37925025867012e-05 3.10344094830737e-05 5.069671919503e-05 0.000104708233999696 -1.36338012034424e-05 2.57155911704015e-05 9.84505458867246e-06 8.00694093767411e-05 -1.59339603721863e-05 -1.36338012034424e-05 1.72819117184712e-05 1.28978675359623e-07 5.51531673625825e-07 -4.77555422576685e-06 2.04435218219129e-05 2.57155911704015e-05 1.28978675359623e-07 5.98031940582376e-05 -2.26669979705315e-05 2.1364017653653e-05 -1.37925025867012e-05 9.84505458867246e-06 5.51531673625825e-07 -2.26669979705315e-05 8.36083152741292e-05 5.82598165739281e-06 3.10344094830737e-05 8.00694093767411e-05 -4.77555422576685e-06 2.1364017653653e-05 5.82598165739281e-06 0.00012337865393106 1589 1602 0 54 7 1570 1584 0 52 7 0 0 0 0 0 0 0 0 336 0 114 116 0 0 1687 +335 378 0.987255223127046 0.0340729642322878 0.155454679944969 0.0353070940309529 -0.0500209205699778 0.993743418567342 0.0998595291368036 -0.0273948261949178 -0.151079554916275 -0.106362827917075 0.982782741466181 0.0872384719347317 7.92436995679665e-05 3.73636661358656e-06 -1.38076785013028e-05 3.24268271402525e-07 -6.35615666354056e-06 -1.06875135464366e-05 3.73636661358656e-06 6.9482273429742e-05 -6.68089638292138e-06 1.08836696035664e-07 1.6762689570254e-05 5.76086110836652e-05 -1.38076785013028e-05 -6.68089638292138e-06 1.56202822949826e-05 7.79256898711701e-07 4.49403225225706e-06 -1.55113857335451e-06 3.24268271402525e-07 1.08836696035664e-07 7.79256898711701e-07 4.27580263027836e-05 -4.85992273067266e-06 4.23879396328646e-07 -6.35615666354056e-06 1.6762689570254e-05 4.49403225225706e-06 -4.85992273067266e-06 4.41385241526469e-05 1.80161625378089e-05 -1.06875135464366e-05 5.76086110836652e-05 -1.55113857335451e-06 4.23879396328646e-07 1.80161625378089e-05 0.00010707621396595 1663 1672 0 61 0 1625 1634 0 56 0 0 0 0 0 0 0 0 0 380 0 150 127 0 0 2288 +335 388 0.987791365318223 0.0350584257957954 0.151786446639616 0.0193166712050779 -0.0501106129977924 0.994070182761425 0.0965059490894304 -0.0164422526303361 -0.147503034096745 -0.102933855098247 0.983690742259409 0.0748940886675269 5.71279858355278e-05 5.33450186838632e-06 -3.7820050531388e-06 -1.13253322151592e-05 2.97121007989727e-06 -1.1643476169624e-05 5.33450186838632e-06 5.21502002524182e-05 1.49534602087433e-06 9.83309483694597e-06 -6.15635653304574e-06 2.71380798090132e-05 -3.7820050531388e-06 1.49534602087433e-06 1.54082142069985e-05 5.91288144360268e-06 6.00982085057518e-06 5.12996358956637e-06 -1.13253322151592e-05 9.83309483694597e-06 5.91288144360268e-06 6.80420944559677e-05 -2.59291801948571e-05 4.08016975965334e-06 2.97121007989727e-06 -6.15635653304574e-06 6.00982085057518e-06 -2.59291801948571e-05 5.46791648925796e-05 -2.08922479910252e-06 -1.1643476169624e-05 2.71380798090132e-05 5.12996358956637e-06 4.08016975965334e-06 -2.08922479910252e-06 6.45510390798004e-05 1670 1685 0 56 1 1659 1677 0 55 0 0 0 0 0 0 0 0 0 382 0 148 128 0 0 2196 +335 420 0.986710725554308 0.0337594538986129 0.158941005875007 0.0233258858444162 -0.0505775586506283 0.993395950243515 0.102987361364034 -0.0145535760432909 -0.154414554485754 -0.109657582101062 0.98190190958706 0.0832705790403817 5.06198434863552e-05 8.18209026933759e-06 -1.00977294508561e-05 -4.11003330588665e-06 9.27505658872414e-06 -2.37901606430727e-06 8.18209026933759e-06 4.93747122866136e-05 -6.36052302617994e-06 5.99910270781911e-06 1.09127220202274e-05 3.86314782264278e-05 -1.00977294508561e-05 -6.36052302617994e-06 1.57049811822212e-05 4.16640560687958e-06 3.5345514640276e-07 -1.95161975713502e-07 -4.11003330588665e-06 5.99910270781911e-06 4.16640560687958e-06 5.53100932878373e-05 -1.57490869010776e-05 7.99334333965676e-06 9.27505658872414e-06 1.09127220202274e-05 3.5345514640276e-07 -1.57490869010776e-05 6.3335401231412e-05 1.00563087339334e-05 -2.37901606430727e-06 3.86314782264278e-05 -1.95161975713502e-07 7.99334333965676e-06 1.00563087339334e-05 9.16080393210545e-05 1597 1608 0 59 4 1534 1547 0 55 4 0 0 0 0 0 0 0 0 342 0 119 128 0 0 1756 +335 422 0.986808843037315 0.034962658065863 0.158069351375671 0.0237738675639425 -0.0507158707922496 0.994015620712578 0.096751466289519 -0.0199587338964225 -0.15374071599007 -0.103491827311907 0.98267656628542 0.0833412077968956 6.55778852853306e-05 1.41193241492636e-05 -1.01113233314303e-05 9.42922295743382e-06 3.32497195533131e-07 2.36979212205462e-06 1.41193241492636e-05 6.43223931840587e-05 -7.28192969224779e-06 2.28894041897913e-05 4.18975268274551e-06 3.79594650958203e-05 -1.01113233314303e-05 -7.28192969224779e-06 1.55881982333511e-05 2.31107406330225e-06 2.00554897471424e-06 -1.66556767337313e-06 9.42922295743382e-06 2.28894041897913e-05 2.31107406330225e-06 6.85435157602314e-05 -1.66496429719589e-05 2.02960976948696e-05 3.32497195533131e-07 4.18975268274551e-06 2.00554897471424e-06 -1.66496429719589e-05 5.21388676790638e-05 -6.21892780193818e-06 2.36979212205462e-06 3.79594650958203e-05 -1.66556767337313e-06 2.02960976948696e-05 -6.21892780193818e-06 9.41262184695935e-05 1943 1963 0 59 2 1916 1942 0 57 2 0 0 0 0 0 0 0 0 316 0 152 155 0 0 1815 +335 386 0.98691104077687 0.0326875595485092 0.157918083332716 0.0270492343293054 -0.0500553740308112 0.992967272350981 0.107286791220952 -0.0150602538498991 -0.153300545084979 -0.113787167512928 0.981606552232631 0.0842796491763317 7.00371959552192e-05 2.63986210812866e-05 -9.50502763044668e-06 1.49762099323437e-06 -1.65247228541869e-06 1.50746663330596e-05 2.63986210812866e-05 7.13833922817093e-05 -6.71121770392298e-06 1.96964134113692e-05 1.78108452934916e-06 4.77822089935325e-05 -9.50502763044668e-06 -6.71121770392298e-06 1.50251135969071e-05 2.08313100745836e-06 4.72746289416088e-06 -9.90759374036744e-07 1.49762099323437e-06 1.96964134113692e-05 2.08313100745836e-06 6.71165981068669e-05 -1.16557332142069e-05 7.52339542905194e-06 -1.65247228541869e-06 1.78108452934916e-06 4.72746289416088e-06 -1.16557332142069e-05 4.50648904139323e-05 1.1991201736201e-06 1.50746663330596e-05 4.77822089935325e-05 -9.90759374036744e-07 7.52339542905194e-06 1.1991201736201e-06 9.50568256093827e-05 1600 1611 0 59 0 1581 1595 0 54 0 0 0 0 0 0 0 0 0 348 0 148 126 0 0 2201 +335 421 0.987564431272068 0.0332728090734803 0.153653552717261 0.0203859534042368 -0.0497466310133267 0.993264510380132 0.104646476874004 -0.01648376410776 -0.149136738562637 -0.110988885009614 0.982567911452039 0.0784947346089925 8.98726021689155e-05 2.91459761109977e-05 -1.31948121429787e-05 1.26786752060832e-07 -1.15102005985747e-06 1.70746946357848e-05 2.91459761109977e-05 9.55845831269721e-05 -6.0709327015674e-06 2.80559095668084e-05 -1.13735613035052e-05 7.89323101560077e-05 -1.31948121429787e-05 -6.0709327015674e-06 1.77094400113792e-05 2.99567469453703e-06 1.46256158589413e-06 -3.43535651317418e-07 1.26786752060832e-07 2.80559095668084e-05 2.99567469453703e-06 6.49618813815071e-05 -6.60478312272433e-06 2.15064009638396e-05 -1.15102005985747e-06 -1.13735613035052e-05 1.46256158589413e-06 -6.60478312272433e-06 6.83242224130938e-05 -3.22956518535373e-06 1.70746946357848e-05 7.89323101560077e-05 -3.43535651317418e-07 2.15064009638396e-05 -3.22956518535373e-06 0.000142580395480535 1418 1430 0 58 3 1353 1368 0 54 2 0 0 0 0 0 0 0 0 334 0 120 125 0 0 1771 +335 395 0.984495389097565 0.0354697423655981 0.171786862775219 0.0396160870344933 -0.0517967001736873 0.994455983457705 0.0915117414121596 -0.0239559460973904 -0.167588575674928 -0.0989908800935062 0.980874545985144 0.0993961969830326 0.000118897804530804 4.89459634892823e-05 -1.63689112914388e-05 4.67470397786259e-06 -1.72009722095544e-05 3.38608257873222e-05 4.89459634892823e-05 0.000137884945650759 -5.63493260991934e-06 1.93397097535402e-05 -5.77715778819486e-06 0.000108371193060986 -1.63689112914388e-05 -5.63493260991934e-06 1.79110305017644e-05 7.00014396874081e-06 5.39798141059729e-06 -4.3792596923297e-06 4.67470397786259e-06 1.93397097535402e-05 7.00014396874081e-06 6.00509413011636e-05 -1.17950195078642e-05 1.62902938527992e-05 -1.72009722095544e-05 -5.77715778819486e-06 5.39798141059729e-06 -1.17950195078642e-05 5.28190293454258e-05 -6.94171508128819e-06 3.38608257873222e-05 0.000108371193060986 -4.3792596923297e-06 1.62902938527992e-05 -6.94171508128819e-06 0.000166115475374589 1941 1953 0 63 0 1913 1938 0 56 0 0 0 0 0 0 0 0 0 157 0 200 185 0 0 1953 +335 396 0.984854255685644 0.0330697808819517 0.170201306253199 0.0341171940520971 -0.0513655453387319 0.993224810218442 0.104240381420038 -0.0183728977436578 -0.165600953529653 -0.111404066168879 0.979880328525433 0.0974212662525426 8.23532313839452e-05 4.67161759686103e-05 -1.25736078179529e-05 1.69352993917625e-06 3.07118869806108e-06 4.19398832701441e-05 4.67161759686103e-05 0.000111662908378726 -9.8884799657534e-06 3.0261946861765e-05 8.62533075145138e-06 8.51886039367169e-05 -1.25736078179529e-05 -9.8884799657534e-06 1.57261206748267e-05 6.65185522994382e-06 4.2600237206327e-06 -5.81174303189471e-06 1.69352993917625e-06 3.0261946861765e-05 6.65185522994382e-06 6.93296399012423e-05 4.391550106465e-06 1.9563695454241e-05 3.07118869806108e-06 8.62533075145138e-06 4.2600237206327e-06 4.391550106465e-06 5.54316966782431e-05 1.54931517214785e-05 4.19398832701441e-05 8.51886039367169e-05 -5.81174303189471e-06 1.9563695454241e-05 1.54931517214785e-05 0.000136862180669091 1486 1496 0 60 0 1432 1442 0 59 0 0 0 0 0 0 0 0 0 177 0 140 123 0 0 1940 +335 411 0.98713008052295 0.0320449692601645 0.156675856697416 0.0244398760550488 -0.0497312532620253 0.992653135822028 0.110302105109935 -0.0125858711949483 -0.151990152890713 -0.116674212608485 0.981471406377408 0.0824359599089371 5.93131576632691e-05 2.99727550790439e-05 -7.21698832491675e-06 1.93907982278432e-06 5.21003375938807e-06 2.72601007707155e-05 2.99727550790439e-05 5.80300515641208e-05 -5.73791149438744e-06 7.36159389926996e-06 1.14285101162293e-05 4.29024424492295e-05 -7.21698832491675e-06 -5.73791149438744e-06 1.42623697357416e-05 5.89009517646721e-06 3.809878228886e-06 -4.47202848701884e-06 1.93907982278432e-06 7.36159389926996e-06 5.89009517646721e-06 5.55045452584988e-05 -8.28692806686688e-06 -2.40929976335736e-06 5.21003375938807e-06 1.14285101162293e-05 3.809878228886e-06 -8.28692806686688e-06 6.28591205992168e-05 1.91963717035936e-05 2.72601007707155e-05 4.29024424492295e-05 -4.47202848701884e-06 -2.40929976335736e-06 1.91963717035936e-05 9.95656528880809e-05 1598 1610 0 50 3 1530 1545 0 50 3 0 0 0 0 0 0 0 0 271 0 110 117 0 0 1799 +335 423 0.987466163124757 0.0351660071636296 0.153863343990172 0.0172525505376099 -0.0505009416370047 0.99401003624683 0.0969211160395493 -0.0164447033020662 -0.149533379475776 -0.103476566336265 0.983327193075535 0.0798351392667223 8.07934421770863e-05 4.25231951288133e-06 -1.51797891043236e-05 -9.09963124882712e-06 3.92919372197947e-06 -8.19982407975982e-06 4.25231951288133e-06 7.78567837686565e-05 -5.53397908976189e-06 2.07506384828293e-05 4.66408281734538e-06 5.69903456052593e-05 -1.51797891043236e-05 -5.53397908976189e-06 1.80232084582524e-05 4.95348622494266e-06 2.46089879726708e-06 4.42160025715159e-07 -9.09963124882712e-06 2.07506384828293e-05 4.95348622494266e-06 7.13009071204045e-05 -1.49464489175943e-05 1.20691539509129e-05 3.92919372197947e-06 4.66408281734538e-06 2.46089879726708e-06 -1.49464489175943e-05 5.44281420009961e-05 -2.31891321926838e-06 -8.19982407975982e-06 5.69903456052593e-05 4.42160025715159e-07 1.20691539509129e-05 -2.31891321926838e-06 0.000107521290578708 1480 1489 0 56 2 1421 1431 0 56 2 0 0 0 0 0 0 0 0 341 0 121 130 0 0 1786 +335 394 0.986129564635933 0.0340127539993011 0.162454960885561 0.0258554652166255 -0.0509464862335022 0.993557151849772 0.101235574521155 -0.018026362740257 -0.157964987549158 -0.108107902456535 0.981508911897922 0.0914615029503583 7.31355928257938e-05 9.94702234321625e-06 -9.40965636562023e-06 3.6386729629893e-07 -4.43079045085409e-06 -3.57946989944132e-07 9.94702234321625e-06 7.16512568698296e-05 1.7747441456698e-06 1.12459520150699e-05 -3.50286535612276e-06 5.94653922084159e-05 -9.40965636562023e-06 1.7747441456698e-06 1.61866140852412e-05 5.24791946881433e-06 3.75145800237252e-06 3.40071448380554e-06 3.6386729629893e-07 1.12459520150699e-05 5.24791946881433e-06 5.49923177371056e-05 -1.45270320665001e-05 1.66968618214315e-05 -4.43079045085409e-06 -3.50286535612276e-06 3.75145800237252e-06 -1.45270320665001e-05 6.29445321281314e-05 -3.52376016893809e-06 -3.57946989944132e-07 5.94653922084159e-05 3.40071448380554e-06 1.66968618214315e-05 -3.52376016893809e-06 0.000116173374486264 1701 1715 0 58 0 1645 1660 0 52 0 0 0 0 0 0 0 0 0 172 0 146 126 0 0 1939 +335 412 0.98698168039741 0.0346654400821522 0.157052442909418 0.0247706485630687 -0.0503627290357247 0.993999675813691 0.0970991246425638 -0.0228422976578831 -0.152744093450383 -0.103744646831481 0.982805316514839 0.0846063571816601 6.74313720242041e-05 2.55780086278623e-05 -1.07183471877458e-05 -6.73204803931065e-06 1.28654472519965e-05 1.44006239835647e-05 2.55780086278623e-05 9.24647012044781e-05 -6.38529628667683e-06 1.76141891424051e-05 1.92526066206789e-05 6.8696726098659e-05 -1.07183471877458e-05 -6.38529628667683e-06 1.56780863690049e-05 6.19298693659408e-06 8.94653289092764e-07 -9.37854983186459e-07 -6.73204803931065e-06 1.76141891424051e-05 6.19298693659408e-06 6.33541805808669e-05 -1.35374483215557e-05 9.81907028553987e-06 1.28654472519965e-05 1.92526066206789e-05 8.94653289092764e-07 -1.35374483215557e-05 6.30799036651807e-05 1.91555985529396e-05 1.44006239835647e-05 6.8696726098659e-05 -9.37854983186459e-07 9.81907028553987e-06 1.91555985529396e-05 0.00011240926617584 1515 1526 0 53 1 1455 1467 0 51 1 0 0 0 0 0 0 0 0 296 0 117 123 0 0 1764 +335 393 0.984312209954927 0.0350082468568927 0.172927429824348 0.0331541386964964 -0.0521295943232537 0.994065316163695 0.0954811635667829 -0.0124918149646587 -0.168558532057387 -0.102997911883594 0.980295593899248 0.10165735666201 0.000130627881418031 4.52723670226281e-05 -1.4145050071518e-05 5.60228342504149e-06 -1.90894346091113e-05 3.33504261854315e-05 4.52723670226281e-05 0.000156403655377658 -5.17249374471396e-06 3.21397328686311e-05 -1.27592562678294e-05 0.000137223121107573 -1.4145050071518e-05 -5.17249374471396e-06 1.54462292656647e-05 5.31668088994815e-06 6.69429653949242e-06 -4.17570870007011e-06 5.60228342504149e-06 3.21397328686311e-05 5.31668088994815e-06 7.30476085225826e-05 -2.39560859099114e-05 2.85370184843422e-05 -1.90894346091113e-05 -1.27592562678294e-05 6.69429653949242e-06 -2.39560859099114e-05 6.8101580216593e-05 -1.13897463579173e-05 3.33504261854315e-05 0.000137223121107573 -4.17570870007011e-06 2.85370184843422e-05 -1.13897463579173e-05 0.000183693461391524 1726 1738 0 59 1 1679 1691 0 54 0 0 0 0 0 0 0 0 0 151 0 157 144 0 0 1925 +335 427 0.986814726697616 0.0338501008117871 0.158274653206828 0.0229779363404932 -0.0501645723717119 0.993697274937849 0.100245904953055 -0.018733996710828 -0.153883757594728 -0.106863915594205 0.982293180619921 0.0802124068830855 9.45080401915491e-05 3.53194440206183e-05 -1.74419238511904e-05 1.15991537131458e-05 -1.54632988483791e-05 1.83235062818506e-05 3.53194440206183e-05 7.48276539928785e-05 -1.04277161509892e-05 3.17490727423143e-05 -2.27309009100645e-05 4.38884834753086e-05 -1.74419238511904e-05 -1.04277161509892e-05 1.70885681759623e-05 -6.33942325474673e-07 3.31584940172877e-06 -2.8512430334967e-06 1.15991537131458e-05 3.17490727423143e-05 -6.33942325474673e-07 8.1263933817224e-05 -4.29293555677801e-05 3.70658303774722e-05 -1.54632988483791e-05 -2.27309009100645e-05 3.31584940172877e-06 -4.29293555677801e-05 7.81972177156555e-05 -3.10132463426058e-05 1.83235062818506e-05 4.38884834753086e-05 -2.8512430334967e-06 3.70658303774722e-05 -3.10132463426058e-05 9.25042853863756e-05 1869 1882 0 52 1 1862 1878 0 53 1 0 0 0 0 0 0 0 0 369 0 111 112 0 0 1918 +335 392 0.984558537034716 0.0349964239277774 0.171521827952964 0.0304619108790363 -0.0521029094322897 0.993990722631702 0.0962690508460456 -0.0122846889913709 -0.167122033199544 -0.103719302130197 0.980465467206711 0.0981832342026602 6.6908694752836e-05 2.90147840756682e-05 -6.39409297956219e-06 1.51187098756919e-05 -1.82280320234431e-05 1.81724340423562e-05 2.90147840756682e-05 0.000104913853843423 -3.89570737335941e-06 3.29021119565388e-05 -8.06292974890089e-06 8.05998756066343e-05 -6.39409297956219e-06 -3.89570737335941e-06 1.42438096835672e-05 1.75024024009664e-06 7.48435879613511e-06 -1.07354879593618e-06 1.51187098756919e-05 3.29021119565388e-05 1.75024024009664e-06 5.34996241464076e-05 -1.20739459030721e-05 3.77089252476811e-05 -1.82280320234431e-05 -8.06292974890089e-06 7.48435879613511e-06 -1.20739459030721e-05 7.16114234645307e-05 4.88908785104537e-06 1.81724340423562e-05 8.05998756066343e-05 -1.07354879593618e-06 3.77089252476811e-05 4.88908785104537e-06 0.000146640766994628 1802 1814 0 60 1 1779 1797 0 54 0 0 0 0 0 0 0 0 0 148 0 151 131 0 0 1882 +335 376 0.986338803394748 0.0329959008560606 0.161390939784465 0.0343340983575291 -0.0504979495806208 0.993128277905957 0.105575474006521 -0.0175231672360175 -0.156798348224619 -0.11228309823943 0.981227182585045 0.0855129701048807 3.89422627287297e-05 9.45172631535312e-06 -3.25729311972788e-06 4.81003377688495e-06 1.51748400544952e-06 -1.77773029787593e-07 9.45172631535312e-06 3.78671380750168e-05 -4.95804765451242e-06 8.56835824919171e-06 -3.50067133820256e-06 2.05698945916214e-05 -3.25729311972788e-06 -4.95804765451242e-06 1.25048732437127e-05 3.46596811473687e-06 3.97998129760383e-06 -7.4562106952694e-07 4.81003377688495e-06 8.56835824919171e-06 3.46596811473687e-06 7.23040442144037e-05 -6.27323209951915e-06 8.53341783622938e-06 1.51748400544952e-06 -3.50067133820256e-06 3.97998129760383e-06 -6.27323209951915e-06 5.15817409150565e-05 2.73171702136333e-06 -1.77773029787593e-07 2.05698945916214e-05 -7.4562106952694e-07 8.53341783622938e-06 2.73171702136333e-06 7.08228746841897e-05 1693 1709 0 54 0 1650 1675 0 54 0 0 0 0 0 0 0 0 0 359 0 194 176 0 0 2185 +335 377 0.986854874839141 0.0331694913953757 0.158168393956556 0.0342830605918188 -0.0500646271235671 0.993310197900877 0.104059520742208 -0.0259375599805623 -0.153658677324785 -0.110610286984041 0.9819136292445 0.0894251077326154 5.18841085575257e-05 1.38874446648452e-05 -1.00744941508532e-05 2.08936925284631e-07 -2.43445592710277e-06 3.40914995697301e-06 1.38874446648452e-05 6.0882085981287e-05 -8.43052946713129e-06 1.402312686628e-05 -3.70040244096502e-07 5.01458397163557e-05 -1.00744941508532e-05 -8.43052946713129e-06 1.51785305773061e-05 1.53601714843247e-06 4.24293332773045e-06 -2.07871137319371e-06 2.08936925284631e-07 1.402312686628e-05 1.53601714843247e-06 5.41264683860894e-05 -8.94334659264233e-06 1.71107093842226e-05 -2.43445592710277e-06 -3.70040244096502e-07 4.24293332773045e-06 -8.94334659264233e-06 5.0500351643435e-05 9.0160573158065e-06 3.40914995697301e-06 5.01458397163557e-05 -2.07871137319371e-06 1.71107093842226e-05 9.0160573158065e-06 9.17323170185862e-05 1621 1636 0 57 1 1562 1577 0 56 0 0 0 0 0 0 0 0 0 346 0 159 144 0 0 2213 +335 389 0.987490257357992 0.0342368897503038 0.153918247791715 0.0218434637556909 -0.0498742247894187 0.993845703224933 0.0989104639711717 -0.0208922198894278 -0.149584602565574 -0.105349672811848 0.983120487587221 0.0794252728036847 7.45637186544916e-05 1.12513144908376e-05 -6.31140641043831e-06 1.31796483660364e-05 -1.58775247098601e-05 2.79782970623228e-06 1.12513144908376e-05 5.46800429556164e-05 -2.3664942845482e-06 9.00807400255388e-06 -2.94018325372904e-06 3.4598943121433e-05 -6.31140641043831e-06 -2.3664942845482e-06 1.3816752968753e-05 2.72551265445444e-06 7.09724330762191e-06 -1.19723307720518e-06 1.31796483660364e-05 9.00807400255388e-06 2.72551265445444e-06 5.3349031690863e-05 -2.14795314412042e-05 -1.52512336819096e-06 -1.58775247098601e-05 -2.94018325372904e-06 7.09724330762191e-06 -2.14795314412042e-05 5.85301777355281e-05 -1.44756748969752e-06 2.79782970623228e-06 3.4598943121433e-05 -1.19723307720518e-06 -1.52512336819096e-06 -1.44756748969752e-06 8.90145071917163e-05 1549 1560 0 56 0 1486 1498 0 55 0 0 0 0 0 0 0 0 0 223 0 163 150 0 0 2143 +336 338 0.999603839671249 -0.0273487444178091 -0.00664905205767092 0.0105132753042832 0.0272220571570684 0.999459120680313 -0.018450628527843 0.0159348404173215 0.00715005724687332 0.0182623182456255 0.999807663710207 0.029790141367266 4.70537862416195e-05 7.27537219998079e-06 -6.52845591408538e-06 3.61147470484032e-06 -5.71095847808537e-06 1.26080749600771e-05 7.27537219998079e-06 4.28947638837783e-05 -7.50305058671855e-06 1.22495446137679e-05 5.36355013207096e-06 1.66536658952248e-05 -6.52845591408538e-06 -7.50305058671855e-06 1.70238936556287e-05 5.52359699202036e-07 9.54757491173815e-09 -7.3770402014336e-06 3.61147470484032e-06 1.22495446137679e-05 5.52359699202036e-07 4.08311968812951e-05 -1.30320960456661e-05 7.4187549956224e-06 -5.71095847808537e-06 5.36355013207096e-06 9.54757491173815e-09 -1.30320960456661e-05 5.72544411042509e-05 1.35744295168094e-06 1.26080749600771e-05 1.66536658952248e-05 -7.3770402014336e-06 7.4187549956224e-06 1.35744295168094e-06 5.90517524532325e-05 2094 2073 0 1 105 2073 2067 0 1 72 0 0 0 0 0 33 36 0 476 0 16 4 0 0 3230 +335 391 0.985461177074516 0.0330646796648727 0.166652319028476 0.0354951999007169 -0.0509379886595739 0.993257037130534 0.104143072270749 -0.0189766731278953 -0.162085131305208 -0.111117888520852 0.980500497226004 0.0956471088916311 8.37474916133027e-05 -8.37787301617332e-06 -1.20615065266033e-05 -1.1079109540988e-05 -5.64546049384766e-06 -1.89935314261446e-05 -8.37787301617332e-06 6.27165375335183e-05 1.84541528266458e-06 2.17940296007898e-05 5.7584124665002e-06 5.20852094995246e-05 -1.20615065266033e-05 1.84541528266458e-06 1.54175413648901e-05 8.08495347035827e-06 4.36059228006942e-06 5.51785203994339e-06 -1.1079109540988e-05 2.17940296007898e-05 8.08495347035827e-06 6.57948627604311e-05 -7.81752698589409e-06 3.85113685550621e-05 -5.64546049384766e-06 5.7584124665002e-06 4.36059228006942e-06 -7.81752698589409e-06 5.41619172003861e-05 7.85253204491715e-06 -1.89935314261446e-05 5.20852094995246e-05 5.51785203994339e-06 3.85113685550621e-05 7.85253204491715e-06 0.000116857168204212 1991 2005 0 57 0 1953 1979 0 58 0 0 0 0 0 0 0 0 0 144 0 192 176 0 0 1891 +336 416 0.987758344126548 0.0572211904689743 0.145117845111117 -0.00762138682086181 -0.0700285679510013 0.993939423171343 0.0847373750864946 -0.0145693970727568 -0.139389573781947 -0.0938624441783328 0.985779076818816 0.0554531252915091 6.89049691633019e-05 1.49656781271512e-05 -1.35656501638217e-05 4.1696791388105e-07 -3.41410041007229e-06 3.32468943106938e-06 1.49656781271512e-05 6.54098792160114e-05 -7.52111558744217e-06 2.04518123767364e-05 3.11021651887175e-06 3.86706651561684e-05 -1.35656501638217e-05 -7.52111558744217e-06 1.7347487621697e-05 2.95917192827732e-07 6.47671396050789e-07 -6.88780100206818e-07 4.1696791388105e-07 2.04518123767364e-05 2.95917192827732e-07 0.000105417708961641 -6.22373660196354e-05 2.10508614048633e-06 -3.41410041007229e-06 3.11021651887175e-06 6.47671396050789e-07 -6.22373660196354e-05 9.60411265901803e-05 6.88530458317005e-06 3.32468943106938e-06 3.86706651561684e-05 -6.88780100206818e-07 2.10508614048633e-06 6.88530458317005e-06 8.66722311534322e-05 1180 1193 0 69 0 1158 1172 0 79 0 0 0 0 0 0 0 0 0 344 0 187 203 0 0 1723 +336 339 0.999957944384101 -0.00725525398772952 -0.005609879918286 0.00798221994592005 0.00708708339484473 0.999541491946289 -0.0294377160585019 0.0311156315953434 0.00582088584998621 0.0293967203504064 0.99955087420329 0.0430578549104527 8.61820599161219e-05 1.59545287882665e-05 -1.39868716381238e-05 1.49705677293061e-05 -1.39077935254373e-05 2.77465074270874e-05 1.59545287882665e-05 7.24992906571345e-05 -1.23798020115191e-05 2.36252667855189e-05 -2.3682587845401e-07 4.07791727902438e-05 -1.39868716381238e-05 -1.23798020115191e-05 1.70018148612975e-05 -2.83434906096249e-06 3.69617016574045e-06 -1.30825629486697e-05 1.49705677293061e-05 2.36252667855189e-05 -2.83434906096249e-06 6.75473556840675e-05 -2.87523837412451e-05 2.96390109874161e-05 -1.39077935254373e-05 -2.3682587845401e-07 3.69617016574045e-06 -2.87523837412451e-05 9.00470907242239e-05 -7.43230910376434e-06 2.77465074270874e-05 4.07791727902438e-05 -1.30825629486697e-05 2.96390109874161e-05 -7.43230910376434e-06 8.64208473728905e-05 1942 1896 0 0 84 1904 1922 0 12 28 0 0 0 0 0 14 20 0 422 0 68 43 0 0 3102 +336 381 0.985451629129841 0.0555461335459841 0.160622892806209 0.00848719725054422 -0.0709096814561538 0.993272232029001 0.091553755553304 -0.0169363794571163 -0.154456802119978 -0.101611515726413 0.982760497858278 0.0667893159756953 0.000103505910650096 2.50407215379448e-05 -1.37285457769741e-05 1.44407139260903e-05 -1.38646137447008e-05 1.67238529356196e-05 2.50407215379448e-05 7.00973924277691e-05 -8.35235725986697e-06 1.88773654967327e-05 -9.4878947622785e-06 4.05535209221209e-05 -1.37285457769741e-05 -8.35235725986697e-06 1.35320723362598e-05 -1.03382246173349e-06 3.48558946167857e-06 -4.16358479262799e-06 1.44407139260903e-05 1.88773654967327e-05 -1.03382246173349e-06 7.16957377478907e-05 -3.06648519653341e-05 1.28981519008126e-05 -1.38646137447008e-05 -9.4878947622785e-06 3.48558946167857e-06 -3.06648519653341e-05 6.45056191033625e-05 -7.52088943597889e-06 1.67238529356196e-05 4.05535209221209e-05 -4.16358479262799e-06 1.28981519008126e-05 -7.52088943597889e-06 8.61620960295394e-05 1530 1540 0 71 0 1518 1528 0 75 0 0 0 0 0 0 0 0 0 380 0 181 169 0 0 2206 +336 432 0.946222049758394 -0.266925848421514 0.182796126861262 -0.0292468402629932 0.278640489789599 0.959509800741305 -0.0412361459304162 -0.0411289186780313 -0.164387682022822 0.0899529528466784 0.98228567956238 -0.0146204459930284 6.46331700028209e-05 6.26926786430822e-06 -5.89151984808127e-06 5.71677767041665e-06 -2.83116089278491e-05 -7.900791619726e-06 6.26926786430822e-06 7.21181840063902e-05 -7.15479264631821e-06 1.43757862994912e-05 5.94247434031387e-06 3.15532294374648e-05 -5.89151984808127e-06 -7.15479264631821e-06 1.54069252737924e-05 -1.03344812076245e-06 5.16221964403541e-06 -9.81059041106806e-07 5.71677767041665e-06 1.43757862994912e-05 -1.03344812076245e-06 5.50026126585249e-05 -2.28305962486579e-05 1.73147514894631e-05 -2.83116089278491e-05 5.94247434031387e-06 5.16221964403541e-06 -2.28305962486579e-05 0.000133315317354 -4.99230515498756e-06 -7.900791619726e-06 3.15532294374648e-05 -9.81059041106806e-07 1.73147514894631e-05 -4.99230515498756e-06 9.20751132739923e-05 1650 1650 0 0 374 1624 1624 0 0 332 0 0 0 0 0 145 145 0 624 0 0 0 0 0 1930 +336 417 0.987212591695483 0.0560060479800972 0.149246847161131 0.00044842626602217 -0.0695168996776852 0.993788462008436 0.086901630813872 -0.0207262044870153 -0.143452777794959 -0.0961655622796378 0.984973849995192 0.0557371376644179 8.07746815365244e-05 4.72326218451179e-05 -1.50570901935024e-05 1.02424934416442e-05 2.9281877930066e-06 2.76490316905262e-05 4.72326218451179e-05 9.44919395692044e-05 -1.31164951457473e-05 1.48760011800448e-07 1.78911057711289e-05 7.08757656310325e-05 -1.50570901935024e-05 -1.31164951457473e-05 1.79069599085786e-05 -4.54392052825423e-07 1.61385708139122e-06 -7.08724922597605e-06 1.02424934416442e-05 1.48760011800448e-07 -4.54392052825423e-07 4.86291648911125e-05 -1.75335876747014e-05 -6.02047947371203e-07 2.9281877930066e-06 1.78911057711289e-05 1.61385708139122e-06 -1.75335876747014e-05 7.26445273525015e-05 2.15399641726183e-05 2.76490316905262e-05 7.08757656310325e-05 -7.08724922597605e-06 -6.02047947371203e-07 2.15399641726183e-05 0.000116007003667579 1659 1670 0 70 0 1631 1647 0 78 0 0 0 0 0 0 0 0 0 341 0 182 195 0 0 1652 +336 431 0.981061263534632 -0.13865008552787 0.135258829563717 -0.00472309360944854 0.142846691866947 0.989505082284306 -0.0217833596169037 -0.039030325493981 -0.130819034603157 0.040692086658761 0.990570812344506 0.0309676525336637 6.47889295711166e-05 1.09764695271149e-05 -1.30853077157103e-05 -1.12597456190958e-06 -7.62996573376452e-06 -1.37500686509767e-06 1.09764695271149e-05 4.66443259997829e-05 -8.08342665388682e-06 2.91688471716277e-06 4.63015187449621e-06 2.06473578843558e-05 -1.30853077157103e-05 -8.08342665388682e-06 1.76488842726215e-05 2.25054850785815e-06 1.68505980135424e-06 1.72225092074195e-08 -1.12597456190958e-06 2.91688471716277e-06 2.25054850785815e-06 4.90905796203187e-05 -2.41604291706969e-05 1.59059563978065e-05 -7.62996573376452e-06 4.63015187449621e-06 1.68505980135424e-06 -2.41604291706969e-05 7.62771215890871e-05 -3.01932208377191e-08 -1.37500686509767e-06 2.06473578843558e-05 1.72225092074195e-08 1.59059563978065e-05 -3.01932208377191e-08 8.05660387819664e-05 1718 1725 0 0 235 1701 1708 0 0 209 0 0 0 0 0 113 111 0 468 0 0 0 0 0 2052 +336 430 0.990929365617419 -0.0186899020866945 0.13307772134001 -0.00105928505923093 0.0115639458705422 0.99846746008001 0.0541202948742556 -0.0232295444275854 -0.133885277431698 -0.0520904859006228 0.989626855822776 0.0544440953349153 6.99618101800125e-05 2.0489113659281e-05 -1.05416643779154e-05 7.96344502332792e-06 -1.7052396884943e-05 1.56824544864127e-05 2.0489113659281e-05 6.51802363740193e-05 -7.26684735582604e-06 2.11046906309332e-05 -2.17100939922962e-06 3.5466335705843e-05 -1.05416643779154e-05 -7.26684735582604e-06 1.38655474332017e-05 2.21153784694426e-06 5.32012806089579e-06 -4.61591825328683e-06 7.96344502332792e-06 2.11046906309332e-05 2.21153784694426e-06 6.00503348493447e-05 -2.20967869079452e-05 1.72262418505071e-05 -1.7052396884943e-05 -2.17100939922962e-06 5.32012806089579e-06 -2.20967869079452e-05 6.80095213169348e-05 -4.38980373626759e-06 1.56824544864127e-05 3.5466335705843e-05 -4.61591825328683e-06 1.72262418505071e-05 -4.38980373626759e-06 8.63774602049338e-05 1587 1567 0 2 53 1549 1549 0 7 5 0 0 0 0 0 19 31 0 445 0 63 44 0 0 1928 +336 380 0.986576350332067 0.0560590145462383 0.153376959982795 -0.00335237001760852 -0.0703030551160188 0.993540479822197 0.0890774685093473 -0.016208775426 -0.147392623312069 -0.0986645926499693 0.984144660479547 0.0620230520033611 9.52443843241533e-05 3.58158057490827e-05 -1.5619009071298e-05 5.81357675636138e-06 -6.510282474967e-06 1.4428877196025e-05 3.58158057490827e-05 0.00010699687108855 -1.20716240927595e-05 4.31623524608037e-05 -1.15828085109081e-05 7.73514364366313e-05 -1.5619009071298e-05 -1.20716240927595e-05 1.59452795358572e-05 -1.50374566677857e-06 2.27687720020487e-06 -2.31691340997258e-06 5.81357675636138e-06 4.31623524608037e-05 -1.50374566677857e-06 7.9396907085446e-05 -2.34616011570114e-05 3.06603172548046e-05 -6.510282474967e-06 -1.15828085109081e-05 2.27687720020487e-06 -2.34616011570114e-05 6.38550629579665e-05 -1.03747745951204e-05 1.4428877196025e-05 7.73514364366313e-05 -2.31691340997258e-06 3.06603172548046e-05 -1.03747745951204e-05 0.000136053490879723 1545 1557 0 73 0 1517 1532 0 78 0 0 0 0 0 0 0 0 0 385 0 237 228 0 0 2146 +336 387 0.986411805338586 0.0559597943209025 0.154467639679752 -0.00173770733543843 -0.0703626372963798 0.993506891322794 0.0894044527236578 -0.00955036683054442 -0.148461609722411 -0.0990583581212658 0.983944404997025 0.0601261941637196 7.14099766788306e-05 1.37872453574725e-05 -1.15094072300869e-05 1.29067438204543e-07 -1.0667226073617e-05 1.55404873303714e-06 1.37872453574725e-05 6.9655123192056e-05 -6.81559457171162e-06 2.24141623055669e-05 -4.01936174958269e-06 4.12011309789831e-05 -1.15094072300869e-05 -6.81559457171162e-06 1.47224440060196e-05 -5.07053910931116e-07 6.10042973410423e-06 1.97105716850942e-07 1.29067438204543e-07 2.24141623055669e-05 -5.07053910931116e-07 6.54063739246351e-05 -1.02708384601387e-05 1.12486890593572e-05 -1.0667226073617e-05 -4.01936174958269e-06 6.10042973410423e-06 -1.02708384601387e-05 6.43938969755169e-05 4.15542177577377e-06 1.55404873303714e-06 4.12011309789831e-05 1.97105716850942e-07 1.12486890593572e-05 4.15542177577377e-06 0.000101610046280192 1517 1529 0 72 0 1485 1502 0 76 0 0 0 0 0 0 0 0 0 382 0 232 222 0 0 2110 +336 414 0.986521464593874 0.0568203888736864 0.153449807115557 -0.00356869184272623 -0.0702271978843799 0.994037804657515 0.0834085342694388 -0.0150537111972466 -0.147795604037694 -0.0930606593567392 0.98462996760571 0.0630465763397994 5.96349193805501e-05 1.37510632220165e-05 -8.72348153028864e-06 6.61263710434648e-06 -1.03954638177858e-05 -1.07696164151675e-06 1.37510632220165e-05 4.58178605082519e-05 -7.37726509843024e-06 8.04653447362457e-06 1.86597201315846e-06 2.59588745891132e-05 -8.72348153028864e-06 -7.37726509843024e-06 1.57508345253319e-05 -5.35501538410242e-07 4.2560086687577e-06 2.62039782794841e-07 6.61263710434648e-06 8.04653447362457e-06 -5.35501538410242e-07 8.03051710547582e-05 -4.42648050859268e-05 4.77798028914497e-07 -1.03954638177858e-05 1.86597201315846e-06 4.2560086687577e-06 -4.42648050859268e-05 0.000102071669966239 -4.53935386380675e-06 -1.07696164151675e-06 2.59588745891132e-05 2.62039782794841e-07 4.77798028914497e-07 -4.53935386380675e-06 7.47964240059171e-05 1476 1489 0 78 0 1452 1468 0 85 0 0 0 0 0 0 0 0 0 338 0 179 195 0 0 1739 +336 382 0.986242775842822 0.0559679824898643 0.155540258563046 0.00271824979359521 -0.0700812908251499 0.993759060566685 0.0867844583891587 -0.0157329372424927 -0.149712390182395 -0.0964910072371156 0.984010002870012 0.063257217503798 4.8402247646736e-05 1.26622907511043e-05 -4.7331589247913e-06 3.24983909064192e-06 1.73154453871764e-06 -3.39125454652059e-06 1.26622907511043e-05 4.5138414172138e-05 -7.23340756636178e-06 9.98768347587646e-06 -1.58166582267039e-06 1.96710919111838e-05 -4.7331589247913e-06 -7.23340756636178e-06 1.34318034849301e-05 3.61592499726427e-08 2.98068719101754e-06 -1.59245738288706e-06 3.24983909064192e-06 9.98768347587646e-06 3.61592499726427e-08 7.06196666447613e-05 -2.54393519318129e-05 1.38929601055007e-06 1.73154453871764e-06 -1.58166582267039e-06 2.98068719101754e-06 -2.54393519318129e-05 6.18617180484583e-05 -7.84400112042778e-07 -3.39125454652059e-06 1.96710919111838e-05 -1.59245738288706e-06 1.38929601055007e-06 -7.84400112042778e-07 7.06581167078036e-05 1499 1510 0 72 0 1483 1494 0 77 0 0 0 0 0 0 0 0 0 398 0 181 171 0 0 2134 +336 384 0.986069026227324 0.0558597587678144 0.156676618758185 0.00259855730731984 -0.0701561637945643 0.993712887023986 0.0872514231636636 -0.0125660663090991 -0.150817731705282 -0.0970277564043198 0.983788405242925 0.0644988337091578 6.3011774405005e-05 3.07515476158368e-06 -9.17400434292293e-06 -7.31724247756933e-06 5.78125608321493e-06 -1.41497963041901e-05 3.07515476158368e-06 5.81633125238141e-05 -4.0628015527345e-06 2.14381239771961e-05 4.89181937524963e-07 2.76337199336974e-05 -9.17400434292293e-06 -4.0628015527345e-06 1.43261395854059e-05 3.2093963567675e-06 1.25653034607153e-06 1.25036395929422e-06 -7.31724247756933e-06 2.14381239771961e-05 3.2093963567675e-06 5.40702545316513e-05 -7.99902749418066e-06 8.65803377789572e-06 5.78125608321493e-06 4.89181937524963e-07 1.25653034607153e-06 -7.99902749418066e-06 5.42403983114554e-05 3.89628945205388e-06 -1.41497963041901e-05 2.76337199336974e-05 1.25036395929422e-06 8.65803377789572e-06 3.89628945205388e-06 7.20250660769613e-05 1560 1574 0 73 0 1533 1552 0 82 0 0 0 0 0 0 0 0 0 406 0 227 218 0 0 2146 +336 415 0.987615304586186 0.0560542484311457 0.146539862767627 0.00806598421443448 -0.0692740409054674 0.993821125491383 0.086721841445328 -0.0326085660350317 -0.140773283700293 -0.0957992263009487 0.985396057855102 0.0535053352586679 9.71530590416323e-05 8.51335060570101e-05 -1.90337478968218e-05 3.07950477605479e-05 -1.06173976735289e-05 7.54081519955429e-05 8.51335060570101e-05 0.000220115010739669 -1.77758325464767e-05 0.000107840378937819 -4.52842319903054e-05 0.000197644517493487 -1.90337478968218e-05 -1.77758325464767e-05 1.95880892712101e-05 7.91480428808991e-07 -4.37174634189548e-07 -1.17946842599109e-05 3.07950477605479e-05 0.000107840378937819 7.91480428808991e-07 0.000147653904590648 -6.67124664189964e-05 0.000106907028606729 -1.06173976735289e-05 -4.52842319903054e-05 -4.37174634189548e-07 -6.67124664189964e-05 8.99174167209352e-05 -5.14718462340091e-05 7.54081519955429e-05 0.000197644517493487 -1.17946842599109e-05 0.000106907028606729 -5.14718462340091e-05 0.000257840214788739 1585 1598 0 72 0 1572 1585 0 82 0 0 0 0 0 0 0 0 0 317 0 141 148 0 0 1706 +336 378 0.986471900772479 0.0561591937722921 0.154010824103953 0.0125515615401981 -0.0700418384379645 0.993808723087981 0.0862459435710833 -0.0282467854042068 -0.148213797787395 -0.0958664011480694 0.984297873245876 0.0649339147381035 6.79347359813077e-05 8.06881350488522e-06 -7.98124558023256e-06 -1.1165134779287e-06 -2.74607731281962e-06 -2.0641435462367e-05 8.06881350488522e-06 5.42873870112751e-05 -5.04802011856468e-06 1.24606311141159e-05 1.14477523484472e-05 2.75607734359963e-05 -7.98124558023256e-06 -5.04802011856468e-06 1.34714049424892e-05 1.8505222867236e-06 2.55758976317532e-06 2.06991573550498e-06 -1.1165134779287e-06 1.24606311141159e-05 1.8505222867236e-06 3.92424393606419e-05 2.84129116198225e-06 3.7662250688577e-06 -2.74607731281962e-06 1.14477523484472e-05 2.55758976317532e-06 2.84129116198225e-06 3.92267742549591e-05 1.4207840963871e-05 -2.0641435462367e-05 2.75607734359963e-05 2.06991573550498e-06 3.7662250688577e-06 1.4207840963871e-05 7.50529464031282e-05 1498 1506 0 77 0 1486 1494 0 82 0 0 0 0 0 0 0 0 0 415 0 203 193 0 0 2114 +336 386 0.985435957348266 0.0550422176156311 0.160892287711563 0.0116539134857666 -0.0706946821715975 0.993131068594557 0.0932359507104929 -0.0157944446577962 -0.154655216135001 -0.1032522874913 0.982558257433141 0.069188156475049 5.78091731236342e-05 1.56939824813089e-05 -6.85647211234689e-06 4.67442150066872e-07 -9.31491423409689e-06 2.52490155746206e-06 1.56939824813089e-05 5.05786038978928e-05 -8.25900610245671e-06 1.03314730207463e-05 4.40429011546194e-06 3.18535146133771e-05 -6.85647211234689e-06 -8.25900610245671e-06 1.36574544265858e-05 7.67192750152016e-07 2.15120723403153e-06 -3.45386990110241e-06 4.67442150066872e-07 1.03314730207463e-05 7.67192750152016e-07 4.38146946223269e-05 3.01666148261675e-07 8.67298562067686e-06 -9.31491423409689e-06 4.40429011546194e-06 2.15120723403153e-06 3.01666148261675e-07 5.16638200550743e-05 -6.75410710175562e-06 2.52490155746206e-06 3.18535146133771e-05 -3.45386990110241e-06 8.67298562067686e-06 -6.75410710175562e-06 8.94060782294637e-05 1572 1581 0 68 0 1561 1570 0 73 0 0 0 0 0 0 0 0 0 375 0 190 177 0 0 2095 +336 425 0.986379654133021 0.0566234826020555 0.1544310821384 0.00384596829072179 -0.0706207068428057 0.99372748693365 0.0867086932063571 -0.0235681607592393 -0.148552662976619 -0.096433722994326 0.984191365229348 0.0646229870654798 7.73435541140331e-05 -5.5145295974915e-06 -1.41190400338601e-05 -6.03069188773694e-06 9.4421888678893e-07 -1.86945543483674e-05 -5.5145295974915e-06 7.28965098607634e-05 -2.88073530647712e-06 1.51559498958089e-05 3.86837416944562e-06 4.03905643692285e-05 -1.41190400338601e-05 -2.88073530647712e-06 1.684136955052e-05 2.46207820672777e-06 -1.81777267540563e-06 3.11280214748175e-06 -6.03069188773694e-06 1.51559498958089e-05 2.46207820672777e-06 4.95347792015651e-05 -1.04309751284486e-05 1.05833495230336e-05 9.4421888678893e-07 3.86837416944562e-06 -1.81777267540563e-06 -1.04309751284486e-05 5.77670147936454e-05 -3.94146977913685e-06 -1.86945543483674e-05 4.03905643692285e-05 3.11280214748175e-06 1.05833495230336e-05 -3.94146977913685e-06 7.93746846497927e-05 1563 1575 0 76 0 1549 1561 0 84 0 0 0 0 0 0 0 0 0 360 0 162 177 0 0 1561 +336 383 0.984788097763389 0.0548052002754109 0.164890243878581 0.00714118880510241 -0.0710709037995802 0.99299252060601 0.0944181161305102 -0.0127855799918431 -0.158560175128172 -0.104700735638752 0.981782270577356 0.0713139705350438 6.62849276696457e-05 2.15663118515143e-05 -8.81635481095664e-06 2.29782441979975e-08 3.05784887269613e-06 2.75637593163558e-06 2.15663118515143e-05 5.62732840027454e-05 -8.01465780093612e-06 9.80887839748287e-06 2.62422139915197e-06 2.86413268027788e-05 -8.81635481095664e-06 -8.01465780093612e-06 1.38482667282697e-05 3.86254010742033e-07 -8.1393236050609e-07 -9.31965250134466e-07 2.29782441979975e-08 9.80887839748287e-06 3.86254010742033e-07 6.5292082410484e-05 -2.27038141542474e-05 1.23045247549119e-05 3.05784887269613e-06 2.62422139915197e-06 -8.1393236050609e-07 -2.27038141542474e-05 6.05880615014442e-05 -5.89373649799395e-06 2.75637593163558e-06 2.86413268027788e-05 -9.31965250134466e-07 1.23045247549119e-05 -5.89373649799395e-06 7.14187813698518e-05 1674 1683 0 69 0 1647 1663 0 71 0 0 0 0 0 0 0 0 0 372 0 229 218 0 0 2162 +336 419 0.986192063780179 0.0566607940794672 0.155610949972283 0.0110439472517506 -0.0705614719224457 0.993853027282641 0.0853067338565277 -0.0300645868672711 -0.149820866427644 -0.0951089615936098 0.984128037100587 0.0610192772625335 7.27499119695439e-05 -8.7097571591402e-06 -1.3818517993984e-05 -8.88490173829873e-06 1.48259841945849e-06 -2.87071003181308e-05 -8.7097571591402e-06 7.3510116441281e-05 -2.69630696281193e-06 3.91977239464657e-05 -1.58127760356043e-05 4.37388719249568e-05 -1.3818517993984e-05 -2.69630696281193e-06 1.69374063673427e-05 4.03910235103449e-06 1.09939598657385e-06 6.12133887090252e-06 -8.88490173829873e-06 3.91977239464657e-05 4.03910235103449e-06 0.000108256888227045 -5.25845211885474e-05 2.82596406705352e-05 1.48259841945849e-06 -1.58127760356043e-05 1.09939598657385e-06 -5.25845211885474e-05 8.23367996784668e-05 -7.00489552984311e-06 -2.87071003181308e-05 4.37388719249568e-05 6.12133887090252e-06 2.82596406705352e-05 -7.00489552984311e-06 0.000102937487385154 1487 1499 0 78 0 1479 1491 0 83 0 0 0 0 0 0 0 0 0 319 0 140 148 0 0 1667 +336 394 0.985706759440861 0.0566210861394735 0.158670214586679 0.00761080750156582 -0.0714145952996508 0.993455913697288 0.0891364298032733 -0.015238006335736 -0.152584861538698 -0.0991937505303288 0.983299781289991 0.069752013136985 6.18709327161366e-05 5.05194147044723e-06 -6.02339348401281e-06 -1.63234508303479e-05 -3.31333554486976e-06 -3.7541579781981e-06 5.05194147044723e-06 8.34064954708597e-05 2.67651129348017e-06 3.23204006064481e-05 3.38119440188541e-06 5.68585443781339e-05 -6.02339348401281e-06 2.67651129348017e-06 1.43303178221655e-05 8.42444936143482e-06 4.28425148891837e-06 1.69672751935665e-06 -1.63234508303479e-05 3.23204006064481e-05 8.42444936143482e-06 7.16006681567558e-05 -7.33155122488664e-06 3.27056739227934e-05 -3.31333554486976e-06 3.38119440188541e-06 4.28425148891837e-06 -7.33155122488664e-06 5.16966367945095e-05 7.76693842654031e-06 -3.7541579781981e-06 5.68585443781339e-05 1.69672751935665e-06 3.27056739227934e-05 7.76693842654031e-06 0.000110094723712384 1603 1615 0 77 0 1594 1606 0 81 0 0 0 0 0 0 0 0 0 202 0 192 185 0 0 1815 +336 418 0.986896549782101 0.0545125574856696 0.151866984906387 -0.00108801960494516 -0.06963603155921 0.992931623299116 0.0961125099103457 -0.0163452160360269 -0.145554193127062 -0.105428518575161 0.983716831376884 0.0580337096014649 0.000100143259492641 5.82978582236393e-05 -1.91868086622619e-05 1.9710001593352e-05 -7.99033357378356e-07 4.80690870989874e-05 5.82978582236393e-05 9.71152382389151e-05 -1.74551630566027e-05 3.45612452951639e-05 -6.0465884982924e-06 6.36420894410497e-05 -1.91868086622619e-05 -1.74551630566027e-05 1.96869153484099e-05 -2.87282381899205e-06 1.72728216866095e-06 -1.05492475089006e-05 1.9710001593352e-05 3.45612452951639e-05 -2.87282381899205e-06 9.69056118853251e-05 -3.99390697881061e-05 2.31385258235623e-05 -7.99033357378356e-07 -6.0465884982924e-06 1.72728216866095e-06 -3.99390697881061e-05 7.71604558831246e-05 -1.02306454215092e-05 4.80690870989874e-05 6.36420894410497e-05 -1.05492475089006e-05 2.31385258235623e-05 -1.02306454215092e-05 0.000116203528009125 1675 1686 0 74 0 1628 1640 0 76 0 0 0 0 0 0 0 0 0 346 0 150 162 0 0 1598 +336 385 0.986293566024216 0.0563191343974142 0.155090801532399 0.00452692618960053 -0.0702832544274926 0.993806407808476 0.0860760590750649 -0.0245499610264817 -0.149282503215602 -0.0957965495179222 0.984143157947127 0.0595228989723629 8.73158563266093e-05 1.18473584530235e-05 -1.13776341929079e-05 1.10405392500714e-05 -1.65806725585407e-05 -1.12607359657465e-05 1.18473584530235e-05 9.2170724571872e-05 -6.74663696191148e-06 2.44870139307232e-05 4.27987508874894e-06 6.2999892618429e-05 -1.13776341929079e-05 -6.74663696191148e-06 1.39016058012214e-05 6.13135473961004e-07 2.99059311713593e-06 -3.1597028697654e-07 1.10405392500714e-05 2.44870139307232e-05 6.13135473961004e-07 6.29260179836257e-05 -1.6502049957983e-05 2.130296339406e-05 -1.65806725585407e-05 4.27987508874894e-06 2.99059311713593e-06 -1.6502049957983e-05 6.18171330335185e-05 -8.87904214940155e-08 -1.12607359657465e-05 6.2999892618429e-05 -3.1597028697654e-07 2.130296339406e-05 -8.87904214940155e-08 0.000112407602986349 1457 1465 0 72 0 1447 1455 0 75 0 0 0 0 0 0 0 0 0 382 0 183 169 0 0 2164 +336 379 0.986596950894685 0.0559785006474658 0.153273820173482 0.0069266561407546 -0.0702801383199026 0.993500911218775 0.089535699948117 -0.0200894054707051 -0.14726560577082 -0.0991077538476458 0.984119146487979 0.0624881674400993 6.42245448219946e-05 -2.46299355134474e-06 -1.11666434656938e-05 -1.69019720791249e-05 7.79420203535137e-06 -1.15096660243654e-05 -2.46299355134474e-06 7.45796293410265e-05 -6.10575999879915e-06 3.5534320019796e-05 -5.07451165655243e-06 4.65833034006515e-05 -1.11666434656938e-05 -6.10575999879915e-06 1.49199849338209e-05 4.84288233285233e-06 3.66735769187287e-07 -6.60826965255882e-07 -1.69019720791249e-05 3.5534320019796e-05 4.84288233285233e-06 8.05318503829669e-05 -2.96772032756154e-05 2.13140608055392e-05 7.79420203535137e-06 -5.07451165655243e-06 3.66735769187287e-07 -2.96772032756154e-05 6.41690595760627e-05 -2.5177360339638e-07 -1.15096660243654e-05 4.65833034006515e-05 -6.60826965255882e-07 2.13140608055392e-05 -2.5177360339638e-07 9.88220005712233e-05 1691 1704 0 78 0 1661 1679 0 82 0 0 0 0 0 0 0 0 0 384 0 234 223 0 0 2152 +336 413 0.988318721936397 0.0558088142652138 0.141814950270829 0.0057267693508106 -0.0692966331068198 0.993342953825692 0.0920203929838769 -0.0298614876135338 -0.13573533257802 -0.10077277576389 0.985606801495797 0.0517271160010808 0.000127932702020655 6.47833645832571e-05 -2.12432476570552e-05 2.03328373953928e-05 -1.20511354708769e-05 5.71244270034804e-05 6.47833645832571e-05 0.000118106433600064 -1.29363248447542e-05 3.92645188923758e-05 -1.87541483251832e-05 9.29390826806817e-05 -2.12432476570552e-05 -1.29363248447542e-05 1.77650644203924e-05 7.66239844734302e-07 3.1215092631386e-06 -1.11972598897215e-05 2.03328373953928e-05 3.92645188923758e-05 7.66239844734302e-07 6.00511386266396e-05 -1.79826167644057e-05 3.35760985553477e-05 -1.20511354708769e-05 -1.87541483251832e-05 3.1215092631386e-06 -1.79826167644057e-05 5.33870162162868e-05 -1.9791997873542e-05 5.71244270034804e-05 9.29390826806817e-05 -1.11972598897215e-05 3.35760985553477e-05 -1.9791997873542e-05 0.000151114255719851 1458 1469 0 70 0 1453 1464 0 79 0 0 0 0 0 0 0 0 0 324 0 153 168 0 0 1726 +336 395 0.984501339512017 0.057596387838624 0.165649535486784 0.0176206187438638 -0.0721109696560558 0.993938554157231 0.0829828814581426 -0.0207601303903181 -0.159865945574122 -0.0936419065791355 0.982687169336161 0.0731341963016504 0.000114253937525831 6.53010334718244e-05 -1.61019073006374e-05 9.21658013880696e-06 -7.68007540055883e-06 3.94658406813712e-05 6.53010334718244e-05 0.000202469254659574 -1.07192254662375e-05 4.04330988917356e-05 -1.28367597003486e-05 0.00016333134725873 -1.61019073006374e-05 -1.07192254662375e-05 1.7366356789804e-05 2.86402153833206e-06 5.21210890239532e-06 -5.62883208105792e-06 9.21658013880696e-06 4.04330988917356e-05 2.86402153833206e-06 6.69844985421116e-05 -2.05799318791965e-05 2.39813670129675e-05 -7.68007540055883e-06 -1.28367597003486e-05 5.21210890239532e-06 -2.05799318791965e-05 5.63920636183498e-05 -3.62313059971654e-06 3.94658406813712e-05 0.00016333134725873 -5.62883208105792e-06 2.39813670129675e-05 -3.62313059971654e-06 0.000223714175811302 1505 1513 0 76 0 1486 1500 0 79 0 0 0 0 0 0 0 0 0 193 0 210 202 0 0 1821 +336 388 0.986148578405784 0.0570830474789233 0.155732164303876 0.0074819501278338 -0.0705304253771572 0.994114229917364 0.0822335513760911 -0.0250113066016708 -0.15012141887275 -0.092078355580049 0.984370426226482 0.0600011180004269 7.61478016604208e-05 3.70707326460125e-05 -6.30685401627797e-06 5.96766997937839e-06 -1.58351667170345e-05 1.03633427923658e-05 3.70707326460125e-05 0.000102798324524842 -7.63506333504258e-06 1.23056453592404e-05 -1.71459238692393e-05 7.42392152480114e-05 -6.30685401627797e-06 -7.63506333504258e-06 1.50185986457307e-05 1.3721899971902e-06 6.92263020467085e-06 -3.22996745722773e-06 5.96766997937839e-06 1.23056453592404e-05 1.3721899971902e-06 5.80664553227407e-05 -2.52179155996134e-05 5.34722414692707e-06 -1.58351667170345e-05 -1.71459238692393e-05 6.92263020467085e-06 -2.52179155996134e-05 6.09932539452024e-05 -1.21289459347407e-05 1.03633427923658e-05 7.42392152480114e-05 -3.22996745722773e-06 5.34722414692707e-06 -1.21289459347407e-05 0.000126751251796487 1499 1513 0 76 0 1490 1504 0 80 0 0 0 0 0 0 0 0 0 384 0 183 168 0 0 2086 +336 426 0.986523352375488 0.0563687481905646 0.1536041648044 0.00151670482963946 -0.0706774905739909 0.993490224277369 0.0893412927568536 -0.0105670531725337 -0.147568179307031 -0.0989936285461398 0.984085308275292 0.0579926373608023 6.61555424358674e-05 1.16443196555279e-05 -1.24825014357143e-05 -4.37836677057945e-06 7.37035279022633e-06 -2.9669568174186e-06 1.16443196555279e-05 8.7451917950822e-05 -5.89510598578448e-06 3.21176942927392e-05 -6.225028575249e-06 5.06484864032918e-05 -1.24825014357143e-05 -5.89510598578448e-06 1.64371044131499e-05 4.80740141278205e-06 9.39328901719576e-07 -1.80829905192066e-07 -4.37836677057945e-06 3.21176942927392e-05 4.80740141278205e-06 6.85149542191595e-05 -2.15552653283489e-05 1.93149173216173e-05 7.37035279022633e-06 -6.225028575249e-06 9.39328901719576e-07 -2.15552653283489e-05 6.06274801741195e-05 1.86787528216995e-07 -2.9669568174186e-06 5.06484864032918e-05 -1.80829905192066e-07 1.93149173216173e-05 1.86787528216995e-07 0.000120618195977665 1593 1602 0 68 0 1537 1547 0 75 0 0 0 0 0 0 0 0 0 382 0 152 164 0 0 1584 +336 411 0.985843630655107 0.0555793958357053 0.158187441522056 0.00807220969803043 -0.0706326139825914 0.993325930279647 0.0911845934139136 -0.0155065544874782 -0.152063702896984 -0.101066943124904 0.983189759542198 0.0654897487126945 8.75003270637071e-05 5.73706076716723e-05 -1.36259131096256e-05 1.62308251132514e-05 -1.58597997830115e-05 4.99987607915649e-05 5.73706076716723e-05 9.82856529062246e-05 -1.17920734227665e-05 3.37548654180782e-05 -1.67078866012824e-05 7.63694859135426e-05 -1.36259131096256e-05 -1.17920734227665e-05 1.45478010966247e-05 4.81644485509931e-07 4.56657358905029e-06 -8.13848906072367e-06 1.62308251132514e-05 3.37548654180782e-05 4.81644485509931e-07 6.25066410251511e-05 -1.25606557030527e-05 2.99782341236782e-05 -1.58597997830115e-05 -1.67078866012824e-05 4.56657358905029e-06 -1.25606557030527e-05 5.44644977257266e-05 -1.92143870073505e-05 4.99987607915649e-05 7.63694859135426e-05 -8.13848906072367e-06 2.99782341236782e-05 -1.92143870073505e-05 0.000134505305722977 1553 1565 0 67 0 1500 1512 0 71 0 0 0 0 0 0 0 0 0 275 0 143 156 0 0 1703 +336 412 0.987149855724721 0.0558427604739346 0.149722237644627 0.0056442563790642 -0.0696798673662229 0.993607206892719 0.0888224886764277 -0.0254954411618339 -0.143805001395949 -0.0981137325428979 0.984730327074378 0.0571253883259218 0.000145170822860149 0.00011533248974438 -2.43061105407748e-05 2.37649640577787e-05 -4.28175192747959e-06 0.000110955870635412 0.00011533248974438 0.00019297728696884 -2.37821529866681e-05 4.87912453066715e-05 -1.59623816797991e-05 0.000182133974975115 -2.43061105407748e-05 -2.37821529866681e-05 1.86952877043093e-05 1.2645123979624e-06 -5.08138229623099e-07 -1.6209258607892e-05 2.37649640577787e-05 4.87912453066715e-05 1.2645123979624e-06 6.8203355939857e-05 -2.5352833934879e-05 6.16962876548912e-05 -4.28175192747959e-06 -1.59623816797991e-05 -5.08138229623099e-07 -2.5352833934879e-05 6.61844213936082e-05 -2.18759022768967e-05 0.000110955870635412 0.000182133974975115 -1.6209258607892e-05 6.16962876548912e-05 -2.18759022768967e-05 0.000247812452582926 1706 1717 0 75 0 1652 1663 0 80 0 0 0 0 0 0 0 0 0 306 0 145 156 0 0 1695 +336 420 0.987912128886442 0.0557454389427655 0.144644639154502 -0.000944185505140349 -0.0696363088949533 0.993244952867712 0.0928183607176035 -0.0188146352422199 -0.13849335753943 -0.101768903108439 0.985120642498958 0.0530363149711239 0.000132096383636342 7.7101815686783e-05 -2.0657753008518e-05 2.98000375401875e-05 -1.90113679869986e-05 6.7205581188527e-05 7.7101815686783e-05 0.000155921654300105 -1.80062618021657e-05 5.78528658044556e-05 -3.22299281292586e-05 0.000137508224045886 -2.0657753008518e-05 -1.80062618021657e-05 1.777040745213e-05 -1.19720163646122e-06 1.99174137728134e-06 -1.22393794027963e-05 2.98000375401875e-05 5.78528658044556e-05 -1.19720163646122e-06 8.86667080795577e-05 -4.87833759967279e-05 4.65716144448305e-05 -1.90113679869986e-05 -3.22299281292586e-05 1.99174137728134e-06 -4.87833759967279e-05 8.48966795746999e-05 -3.39889584844789e-05 6.7205581188527e-05 0.000137508224045886 -1.22393794027963e-05 4.65716144448305e-05 -3.39889584844789e-05 0.000204780748272769 1612 1623 0 74 0 1570 1581 0 81 0 0 0 0 0 0 0 0 0 349 0 147 159 0 0 1587 +336 421 0.986798372571734 0.0567239215607988 0.151694985456153 0.00269488101087111 -0.0702416288685164 0.993877323324566 0.0852876295549002 -0.0180682888426472 -0.145928357297942 -0.0948169969149025 0.984740905838873 0.0602946004478155 5.65410893869642e-05 -2.3611525688093e-06 -1.28547963240894e-05 7.66439862096257e-07 6.39074965874256e-06 -1.18254780326641e-05 -2.3611525688093e-06 5.92927203246776e-05 -2.73862005942413e-06 1.73452312370159e-05 1.9994028294625e-06 3.4168143231982e-05 -1.28547963240894e-05 -2.73862005942413e-06 1.69441396216231e-05 3.20572057940451e-06 -5.1589938185107e-07 1.67705897468992e-06 7.66439862096257e-07 1.73452312370159e-05 3.20572057940451e-06 5.98869980541858e-05 -1.0410254409121e-05 -6.32875246037283e-07 6.39074965874256e-06 1.9994028294625e-06 -5.1589938185107e-07 -1.0410254409121e-05 5.13012631113428e-05 6.35816698755738e-06 -1.18254780326641e-05 3.4168143231982e-05 1.67705897468992e-06 -6.32875246037283e-07 6.35816698755738e-06 8.24699272132084e-05 1570 1581 0 77 0 1518 1529 0 81 0 0 0 0 0 0 0 0 0 364 0 153 165 0 0 1609 +336 427 0.986356497640512 0.0565521437972151 0.154605027713466 0.00757120399817747 -0.070562184240709 0.993733850949222 0.0866833988305174 -0.0232635244529944 -0.148734117530319 -0.0964100021241023 0.984166283598919 0.0607241208061677 6.63120631604508e-05 7.55881180838849e-06 -7.61650224799019e-06 1.12197884256502e-06 -3.70996320375223e-06 -4.08238342950595e-06 7.55881180838849e-06 6.56306806838599e-05 -5.24147002310243e-06 2.41431057644333e-05 -1.31512766530527e-05 3.70761379834482e-05 -7.61650224799019e-06 -5.24147002310243e-06 1.51099042343308e-05 3.61737576980076e-06 5.79416047629681e-07 -2.64344661871569e-07 1.12197884256502e-06 2.41431057644333e-05 3.61737576980076e-06 8.40080729930078e-05 -4.35266993887225e-05 1.93469100130736e-05 -3.70996320375223e-06 -1.31512766530527e-05 5.79416047629681e-07 -4.35266993887225e-05 8.01830306006455e-05 -8.27786933258477e-06 -4.08238342950595e-06 3.70761379834482e-05 -2.64344661871569e-07 1.93469100130736e-05 -8.27786933258477e-06 8.62583752040102e-05 1594 1605 0 78 0 1581 1592 0 81 0 0 0 0 0 0 0 0 0 385 0 148 154 0 0 1784 +336 389 0.986291630176173 0.0573321129094286 0.154731538717119 0.00301904444803544 -0.0706913070236497 0.994100537471782 0.0822609294234063 -0.0214150286368251 -0.149102512908787 -0.0920714408905121 0.984525921658049 0.0632810988629414 7.12327985793944e-05 1.10470495382752e-05 -5.2071853329449e-06 4.0914846103195e-06 -1.18547245555685e-05 -9.51458043273434e-07 1.10470495382752e-05 7.53648675649802e-05 -3.81776546087612e-06 3.11587798368054e-06 9.69328133862136e-06 4.16398466797354e-05 -5.2071853329449e-06 -3.81776546087612e-06 1.48619585430639e-05 3.39502691532368e-06 7.38307075617632e-06 1.7541134290334e-06 4.0914846103195e-06 3.11587798368054e-06 3.39502691532368e-06 5.28033375304656e-05 -2.06511010808089e-05 -2.8799096883576e-06 -1.18547245555685e-05 9.69328133862136e-06 7.38307075617632e-06 -2.06511010808089e-05 5.68759237238398e-05 7.14671256722715e-06 -9.51458043273434e-07 4.16398466797354e-05 1.7541134290334e-06 -2.8799096883576e-06 7.14671256722715e-06 8.8443136138205e-05 1600 1611 0 78 0 1553 1564 0 80 0 0 0 0 0 0 0 0 0 251 0 193 180 0 0 1979 +336 396 0.984173664202003 0.0567672140047304 0.167868049685887 0.0128563828868449 -0.0717852018624858 0.993809730032673 0.0847885917205101 -0.0152086686857074 -0.162015689008085 -0.0954971408290653 0.98215640944236 0.0780340880729062 0.000107457366794489 5.38385257164243e-05 -1.53495756803764e-05 7.06284875800923e-06 -8.36864648574849e-06 2.68910688938072e-05 5.38385257164243e-05 0.000101375462413138 -1.00073051172494e-05 2.70330000526703e-05 -6.52863985992727e-06 6.66864479191114e-05 -1.53495756803764e-05 -1.00073051172494e-05 1.54464874838428e-05 2.10872463577083e-06 5.98578502843979e-06 -5.88720750573334e-06 7.06284875800923e-06 2.70330000526703e-05 2.10872463577083e-06 5.81587496952717e-05 -4.55817950980884e-06 2.3448329806266e-05 -8.36864648574849e-06 -6.52863985992727e-06 5.98578502843979e-06 -4.55817950980884e-06 6.26790444934647e-05 4.74228383806971e-06 2.68910688938072e-05 6.66864479191114e-05 -5.88720750573334e-06 2.3448329806266e-05 4.74228383806971e-06 0.000108851425379118 1654 1664 0 67 0 1635 1645 0 69 0 0 0 0 0 0 0 0 0 189 0 194 186 0 0 1839 +336 422 0.987591032542388 0.0558248356398572 0.146790804097676 0.00141724680704542 -0.0695013870338264 0.993536059743448 0.0897533018325095 -0.0257266784917337 -0.140831493786843 -0.0988417205194558 0.985087206618033 0.0498524666624022 9.72683049557096e-05 5.83785407490818e-05 -1.63260670821989e-05 2.48488904477214e-05 -3.50284985614681e-06 3.81861350940084e-05 5.83785407490818e-05 0.000125449015158894 -1.51640382917522e-05 2.88605224580478e-05 -2.36370214018131e-06 0.000101155403860575 -1.63260670821989e-05 -1.51640382917522e-05 1.74497631819383e-05 -3.23308605348678e-06 2.58576489767999e-06 -5.99526785528916e-06 2.48488904477214e-05 2.88605224580478e-05 -3.23308605348678e-06 6.89566917904811e-05 -2.63680045526559e-05 2.75394029513015e-05 -3.50284985614681e-06 -2.36370214018131e-06 2.58576489767999e-06 -2.63680045526559e-05 6.37406624469566e-05 -4.65479287945144e-06 3.81861350940084e-05 0.000101155403860575 -5.99526785528916e-06 2.75394029513015e-05 -4.65479287945144e-06 0.000159903684478403 1751 1765 0 78 0 1727 1742 0 81 0 0 0 0 0 0 0 0 0 331 0 185 200 0 0 1653 +336 393 0.984807793461968 0.0579387879554522 0.163696996877837 0.0118151965763103 -0.0722558305342705 0.993934825275983 0.0829014961107667 -0.0171945324664845 -0.157900933785625 -0.0934701019249141 0.983021177368918 0.0750269159520401 9.89553127472723e-05 2.93386570985736e-05 -1.46657533294482e-05 -9.39944900746363e-06 2.68423072930096e-06 3.89928624966188e-06 2.93386570985736e-05 0.000110082421241546 -9.52489847150728e-07 2.11790698202083e-05 -5.61538893506131e-06 6.68445557871389e-05 -1.46657533294482e-05 -9.52489847150728e-07 1.57721248785879e-05 5.74147987160426e-06 1.00358466754407e-06 1.30068222079288e-06 -9.39944900746363e-06 2.11790698202083e-05 5.74147987160426e-06 6.23731066069271e-05 -1.70482755087694e-05 1.11288414740791e-05 2.68423072930096e-06 -5.61538893506131e-06 1.00358466754407e-06 -1.70482755087694e-05 6.61837423313576e-05 2.78873275229661e-06 3.89928624966188e-06 6.68445557871389e-05 1.30068222079288e-06 1.11288414740791e-05 2.78873275229661e-06 0.00012170714038623 1342 1352 0 73 0 1298 1308 0 78 0 0 0 0 0 0 0 0 0 188 0 188 178 0 0 1795 +336 391 0.984588100127724 0.057850097079443 0.165044355719235 0.0151094977616898 -0.0720493650015809 0.994075404267798 0.0813816910163584 -0.0197083307625557 -0.159358595907932 -0.0920187855696437 0.982922876431585 0.0773620677928593 9.67764045413492e-05 2.8617440291024e-05 -1.40352022057671e-05 2.24940766461674e-05 -1.69646451405073e-05 2.53043163161731e-05 2.8617440291024e-05 0.000100992613503506 -6.97340637246585e-06 3.60409403193725e-05 -4.48089905614898e-06 7.16876679319475e-05 -1.40352022057671e-05 -6.97340637246585e-06 1.66684996387585e-05 -5.21827469813323e-06 7.55685883826969e-06 -8.50185120387324e-06 2.24940766461674e-05 3.60409403193725e-05 -5.21827469813323e-06 7.94074049191214e-05 -3.40297146536613e-05 3.3417710557408e-05 -1.69646451405073e-05 -4.48089905614898e-06 7.55685883826969e-06 -3.40297146536613e-05 7.97481979314144e-05 -2.55198927167093e-06 2.53043163161731e-05 7.16876679319475e-05 -8.50185120387324e-06 3.3417710557408e-05 -2.55198927167093e-06 0.000130281129125691 1661 1671 0 68 0 1642 1658 0 76 0 0 0 0 0 0 0 0 0 150 0 212 205 0 0 1791 +336 392 0.984810699771502 0.0588037890060767 0.163370744058086 0.00820986832456477 -0.0723657366468504 0.994296922174245 0.0783379264110407 -0.0144695644711881 -0.157832461094423 -0.0889704723678129 0.98344962721612 0.076841837517676 0.000135572402268285 5.38427465931122e-05 -2.24597949864101e-05 1.89861599642281e-05 -1.73221190647342e-05 3.93244431698754e-05 5.38427465931122e-05 0.000131156553918592 -7.87450102703027e-06 4.43802339740639e-05 -1.69378182809177e-05 9.52535258484291e-05 -2.24597949864101e-05 -7.87450102703027e-06 1.73105898557543e-05 -5.81530624149689e-07 6.95636084300015e-06 -6.55985749771598e-06 1.89861599642281e-05 4.43802339740639e-05 -5.81530624149689e-07 8.1457732970416e-05 -3.29936392747271e-05 4.11819612669153e-05 -1.73221190647342e-05 -1.69378182809177e-05 6.95636084300015e-06 -3.29936392747271e-05 5.94653559470782e-05 -1.40137054962317e-05 3.93244431698754e-05 9.52535258484291e-05 -6.55985749771598e-06 4.11819612669153e-05 -1.40137054962317e-05 0.000165214585427121 1530 1540 0 79 0 1514 1525 0 82 0 0 0 0 0 0 0 0 0 173 0 181 169 0 0 1756 +337 339 0.999759533861481 0.0217481277205853 -0.00280951841495443 0.0040887624075541 -0.0218265440826438 0.999255786557505 -0.0318036948285934 0.01436197517493 0.00211575671646432 0.0318573691944423 0.999490185845527 0.0273333148207532 6.04104084086834e-05 1.07457335102094e-05 -6.55541944831185e-06 5.62406973182548e-06 -4.85795697350548e-06 1.8956231259079e-05 1.07457335102094e-05 5.93186966464109e-05 -6.14670326852701e-06 1.54756742900723e-05 3.55331819215986e-06 1.8665836520336e-05 -6.55541944831185e-06 -6.14670326852701e-06 1.3020044301354e-05 8.24496381267493e-07 1.86471446271431e-06 -5.44467368304221e-06 5.62406973182548e-06 1.54756742900723e-05 8.24496381267493e-07 4.34605716526368e-05 -8.8421788345485e-06 1.07501806887958e-05 -4.85795697350548e-06 3.55331819215986e-06 1.86471446271431e-06 -8.8421788345485e-06 4.87211096270141e-05 -1.64978488549262e-06 1.8956231259079e-05 1.8665836520336e-05 -5.44467368304221e-06 1.07501806887958e-05 -1.64978488549262e-06 6.86634241090761e-05 1986 1977 0 23 31 1919 1932 0 28 0 0 0 0 0 0 4 5 0 401 0 95 71 0 0 3242 +336 377 0.986027591710555 0.0559520273950889 0.156904298908166 0.00716456138402185 -0.0704879460834038 0.99356474159436 0.088659763802278 -0.0216126736097669 -0.150933885666629 -0.0984808351452798 0.983626192853088 0.0674354053382603 7.03345662976289e-05 -4.61956460789228e-06 -1.05475980329198e-05 1.81349922855442e-06 -9.1333843256532e-06 -1.55237562379596e-05 -4.61956460789228e-06 5.54334454710093e-05 -3.17207901236683e-06 7.14854663127332e-06 6.76210699425101e-06 3.83180037958343e-05 -1.05475980329198e-05 -3.17207901236683e-06 1.39696055708007e-05 1.46929382870565e-06 3.67071402239685e-06 1.58275835801992e-06 1.81349922855442e-06 7.14854663127332e-06 1.46929382870565e-06 4.19245079503806e-05 -8.9052460377757e-06 4.32489008676725e-06 -9.1333843256532e-06 6.76210699425101e-06 3.67071402239685e-06 -8.9052460377757e-06 5.1371023662349e-05 3.38693593167506e-06 -1.55237562379596e-05 3.83180037958343e-05 1.58275835801992e-06 4.32489008676725e-06 3.38693593167506e-06 7.96931095077931e-05 1455 1467 0 68 0 1403 1415 0 74 0 0 0 0 0 0 0 0 0 376 0 192 178 0 0 2076 +336 376 0.985407612121182 0.0552649971922512 0.160989496734947 0.013033200985716 -0.0706012478885415 0.993331122629064 0.0911523154564084 -0.0166069932095968 -0.154878345065447 -0.101188244879652 0.982737827361888 0.0654045533292623 4.78480530892812e-05 -3.3772022877649e-06 -2.75770686644422e-06 -3.49357289712044e-07 -3.1670262616887e-06 -6.50252477234196e-06 -3.3772022877649e-06 5.98698479580721e-05 -3.54107619388279e-06 3.94007264531292e-06 1.51927229768916e-05 2.8457318626509e-05 -2.75770686644422e-06 -3.54107619388279e-06 1.46405218863979e-05 4.11888507687695e-06 3.7131343054082e-07 6.74039084997276e-07 -3.49357289712044e-07 3.94007264531292e-06 4.11888507687695e-06 4.89869465024666e-05 -4.88647003386489e-06 1.60418561342305e-06 -3.1670262616887e-06 1.51927229768916e-05 3.7131343054082e-07 -4.88647003386489e-06 6.47920977965843e-05 1.20685911772651e-05 -6.50252477234196e-06 2.8457318626509e-05 6.74039084997276e-07 1.60418561342305e-06 1.20685911772651e-05 6.55864171435861e-05 1691 1700 0 74 0 1665 1682 0 79 0 0 0 0 0 0 0 0 0 373 0 224 213 0 0 2019 +336 390 0.985015134521791 0.0567883402490003 0.16285045033644 0.0131797925228348 -0.0714571450724653 0.993757171840758 0.0856770671367209 -0.0188574671727356 -0.156968344519238 -0.096030036065917 0.982923786970317 0.0781234172030653 7.59196670102909e-05 6.71137171973078e-07 -1.16052622172294e-05 -1.63981741006977e-05 -4.07535012205604e-06 1.66174321609638e-06 6.71137171973078e-07 6.59294734312736e-05 -2.3714035596515e-06 1.08662521461061e-05 1.38352028315096e-05 3.60155396007934e-05 -1.16052622172294e-05 -2.3714035596515e-06 1.59617427930155e-05 6.46267953961464e-06 3.93383614288324e-06 2.84834728044781e-07 -1.63981741006977e-05 1.08662521461061e-05 6.46267953961464e-06 5.88790004172281e-05 5.72127471995278e-06 6.96894363440247e-06 -4.07535012205604e-06 1.38352028315096e-05 3.93383614288324e-06 5.72127471995278e-06 4.90847926037285e-05 1.06031011474482e-05 1.66174321609638e-06 3.60155396007934e-05 2.84834728044781e-07 6.96894363440247e-06 1.06031011474482e-05 0.000108262471203898 1629 1643 0 75 0 1582 1596 0 82 0 0 0 0 0 0 0 0 0 148 0 189 175 0 0 1857 +337 341 0.997075213148594 0.0763528434260696 0.00335598352787042 0.0128116720445263 -0.076250736387199 0.996798699202176 -0.0240453419451431 0.0169823829959296 -0.00518117024378898 0.023719118229881 0.999705236009746 0.0329989695852022 5.95097470117115e-05 1.11215674391924e-05 -9.51131379201151e-06 -1.61719348295848e-06 -1.2405388552407e-07 5.3828780412607e-06 1.11215674391924e-05 8.75454621400532e-05 -1.14202846959348e-05 1.4986285039346e-05 2.2050170996427e-05 4.93397204947181e-05 -9.51131379201151e-06 -1.14202846959348e-05 1.616390323102e-05 9.51094700306999e-07 -2.59284297395879e-06 -6.47427817292217e-06 -1.61719348295848e-06 1.4986285039346e-05 9.51094700306999e-07 8.12176918009541e-05 -4.20098118146659e-05 5.06554588653855e-06 -1.2405388552407e-07 2.2050170996427e-05 -2.59284297395879e-06 -4.20098118146659e-05 8.52700440892594e-05 2.28310759307849e-05 5.3828780412607e-06 4.93397204947181e-05 -6.47427817292217e-06 5.06554588653855e-06 2.28310759307849e-05 8.01930988163728e-05 1581 1573 0 45 0 1521 1517 0 48 0 0 0 0 0 0 0 0 0 271 0 195 181 0 0 2935 +336 373 0.986179139599342 0.0560317270073824 0.155920332823116 0.00433834441012161 -0.0704106180522129 0.993604341929844 0.0882765912553627 -0.0204773523553219 -0.149976829825831 -0.0980349798119587 0.983817103555667 0.0614617900667304 7.98620478933498e-05 1.45597222511876e-05 -1.15951514130444e-05 5.09802894661039e-06 -5.24326483243837e-06 4.16858815653239e-06 1.45597222511876e-05 6.42593864691642e-05 -7.27376134319907e-06 1.92332111921335e-05 -3.30020095972133e-06 4.68742782514839e-05 -1.15951514130444e-05 -7.27376134319907e-06 1.59157534098992e-05 4.8973085271135e-06 1.29221211078765e-06 -1.03252477999882e-06 5.09802894661039e-06 1.92332111921335e-05 4.8973085271135e-06 6.98296181222595e-05 -4.14551256191657e-05 2.56373800070822e-05 -5.24326483243837e-06 -3.30020095972133e-06 1.29221211078765e-06 -4.14551256191657e-05 8.46050475719e-05 -1.13275374031682e-05 4.16858815653239e-06 4.68742782514839e-05 -1.03252477999882e-06 2.56373800070822e-05 -1.13275374031682e-05 9.58388008270533e-05 1622 1631 0 69 0 1611 1620 0 75 0 0 0 0 0 0 0 0 0 384 0 184 170 0 0 2112 +337 431 0.985235248857325 -0.109716481657546 0.131429821812759 -0.0245888201684332 0.114890855663658 0.992848521416855 -0.032433081957105 -0.0336311595314618 -0.126931460615234 0.0470543002610084 0.990794780533805 0.0113875322914965 6.36127704089649e-05 -8.97238923352706e-06 -5.74663873621827e-06 -6.97151581110403e-06 -1.14216544283822e-06 -1.35482514385393e-05 -8.97238923352706e-06 6.95452264690024e-05 -6.10919436462067e-06 2.76988462021208e-05 5.64565423635445e-06 3.54375980897869e-05 -5.74663873621827e-06 -6.10919436462067e-06 1.40203665435193e-05 2.51138733211726e-07 2.39807777914184e-06 -2.0805904510975e-06 -6.97151581110403e-06 2.76988462021208e-05 2.51138733211726e-07 6.27929810985892e-05 -4.21608287867612e-06 2.60571404239623e-05 -1.14216544283822e-06 5.64565423635445e-06 2.39807777914184e-06 -4.21608287867612e-06 6.36645597708539e-05 5.19763974061435e-06 -1.35482514385393e-05 3.54375980897869e-05 -2.0805904510975e-06 2.60571404239623e-05 5.19763974061435e-06 8.93383354524816e-05 1380 1379 0 0 209 1359 1358 0 0 171 0 0 0 0 0 80 80 0 506 0 0 0 0 0 2013 +337 340 0.998098911380212 0.0600314948208298 0.013956458405043 0.0117795074659701 -0.0594874372770848 0.997558457951973 -0.0365837091433791 0.0226802696054331 -0.016118557870973 0.0356839263262768 0.999233130702791 0.0410181689249276 4.40060506678944e-05 2.03813734908103e-05 -6.923012796708e-06 7.68134799760395e-06 -4.95141336111495e-06 1.90387385045068e-05 2.03813734908103e-05 5.53077118251903e-05 -9.30119235567308e-06 1.026049510574e-05 5.93362132885195e-06 3.53744377718299e-05 -6.923012796708e-06 -9.30119235567308e-06 1.57024257901142e-05 -4.9718023427812e-07 -3.65990661084617e-06 -7.81080036322443e-06 7.68134799760395e-06 1.026049510574e-05 -4.9718023427812e-07 5.13139903404204e-05 -2.52560964835332e-05 -3.09742521714793e-07 -4.95141336111495e-06 5.93362132885195e-06 -3.65990661084617e-06 -2.52560964835332e-05 6.52021424822575e-05 1.05176563137631e-05 1.90387385045068e-05 3.53744377718299e-05 -7.81080036322443e-06 -3.09742521714793e-07 1.05176563137631e-05 6.768060756678e-05 1995 1987 0 49 0 1953 1954 0 44 0 0 0 0 0 0 0 0 0 365 0 152 134 0 0 3037 +337 381 0.983401470844715 0.0845589285099497 0.160534528216522 -0.00740660456608604 -0.0983372492732984 0.991939954036419 0.0799056505610766 -0.0220996318146494 -0.15248387634702 -0.094365858208766 0.983790502220219 0.04404898090246 5.90650114027968e-05 2.53463961087941e-05 -1.00093861413089e-05 2.10020628562281e-06 4.38585922922943e-06 6.0226541000251e-06 2.53463961087941e-05 5.08432091405676e-05 -8.83671987604318e-06 1.60952331266843e-05 -3.9037685136669e-06 3.37934453368545e-05 -1.00093861413089e-05 -8.83671987604318e-06 1.46641562114193e-05 2.74843234943431e-06 -4.24762358158474e-08 -2.58863412731759e-06 2.10020628562281e-06 1.60952331266843e-05 2.74843234943431e-06 5.33086771216412e-05 -9.02146482531474e-06 1.42155886060763e-05 4.38585922922943e-06 -3.9037685136669e-06 -4.24762358158474e-08 -9.02146482531474e-06 4.2955796028217e-05 -2.15803363490069e-06 6.0226541000251e-06 3.37934453368545e-05 -2.58863412731759e-06 1.42155886060763e-05 -2.15803363490069e-06 8.50217868985465e-05 1290 1291 0 74 0 1258 1261 0 67 0 0 0 0 0 0 0 0 0 341 0 247 250 0 0 2063 +337 432 0.954667181298894 -0.23693086449371 0.180206377248664 -0.052846407556939 0.251522190405842 0.965822853751911 -0.0626322832408555 -0.0435205670326207 -0.159207916525127 0.105118888030547 0.981632751437598 -0.0341086260766777 6.42760682600288e-05 2.85171341121543e-05 -6.08567560738051e-06 3.77738789841878e-06 -1.55985742936499e-05 1.92046950687345e-05 2.85171341121543e-05 6.25286426624117e-05 -8.54732700493665e-06 7.19390907889909e-06 -9.30606223435837e-06 3.54009017227461e-05 -6.08567560738051e-06 -8.54732700493665e-06 1.57764526469743e-05 3.68058114310278e-07 4.79213856731135e-06 -5.11251539956016e-06 3.77738789841878e-06 7.19390907889909e-06 3.68058114310278e-07 4.97751757050003e-05 -1.39275687995858e-05 3.74426337426532e-06 -1.55985742936499e-05 -9.30606223435837e-06 4.79213856731135e-06 -1.39275687995858e-05 7.1657348914954e-05 1.1660219958019e-06 1.92046950687345e-05 3.54009017227461e-05 -5.11251539956016e-06 3.74426337426532e-06 1.1660219958019e-06 9.91913701058264e-05 1462 1488 0 0 290 1375 1401 0 0 248 0 0 0 0 0 80 80 0 655 0 0 0 0 0 1812 +337 415 0.984215859145266 0.0853566482673126 0.15502704668385 -0.0120158111607142 -0.097980666780889 0.992305687310292 0.0756915574474566 -0.0207687308051367 -0.147373442465455 -0.0896864846463474 0.985006295882245 0.0382340622100675 7.43720754188682e-05 4.08499796740701e-05 -1.7871811725754e-05 1.02479525055904e-05 1.65836391687971e-06 2.16563930155031e-05 4.08499796740701e-05 8.90937474209664e-05 -1.28450373178322e-05 3.0336612082805e-05 -1.06042336334527e-05 5.60027339509111e-05 -1.7871811725754e-05 -1.28450373178322e-05 1.72343652615749e-05 -2.97136103580366e-07 1.7355160558012e-06 -6.23333109190509e-06 1.02479525055904e-05 3.0336612082805e-05 -2.97136103580366e-07 5.61453050471974e-05 -2.20793147968623e-06 2.04826942408325e-05 1.65836391687971e-06 -1.06042336334527e-05 1.7355160558012e-06 -2.20793147968623e-06 4.89333956294074e-05 -4.63231334102354e-06 2.16563930155031e-05 5.60027339509111e-05 -6.23333109190509e-06 2.04826942408325e-05 -4.63231334102354e-06 0.000109868589921616 1330 1335 0 78 0 1301 1307 0 73 0 0 0 0 0 0 0 0 0 287 0 206 228 0 0 1586 +337 382 0.983908289485508 0.0851419201385405 0.157083835313578 -0.0142452427103035 -0.0978381334031862 0.992377281399118 0.0749335106282626 -0.0208698524907547 -0.149506446462623 -0.089096491502292 0.984738360006403 0.0415527043994615 7.04142263058861e-05 2.18843815159173e-05 -1.10104879167764e-05 1.520575399949e-08 -8.31698357670805e-07 -2.15400409434777e-06 2.18843815159173e-05 6.75401775779113e-05 -8.81933675536796e-06 1.24180595284018e-05 5.20848523489762e-06 3.69724890271934e-05 -1.10104879167764e-05 -8.81933675536796e-06 1.49085555259167e-05 2.00302377547541e-07 1.01181952419018e-06 -9.38115798344885e-07 1.520575399949e-08 1.24180595284018e-05 2.00302377547541e-07 4.89799264972648e-05 1.36144583337788e-06 5.8139804847437e-06 -8.31698357670805e-07 5.20848523489762e-06 1.01181952419018e-06 1.36144583337788e-06 4.42879557321123e-05 2.15938983051382e-06 -2.15400409434777e-06 3.69724890271934e-05 -9.38115798344885e-07 5.8139804847437e-06 2.15938983051382e-06 9.01643107670385e-05 1373 1376 0 76 0 1342 1346 0 69 0 0 0 0 0 0 0 0 0 356 0 254 256 0 0 2038 +337 380 0.983474573127286 0.0845454563035596 0.160093191081088 -0.0105873799862438 -0.0979847569272275 0.992127286336514 0.0779899680501023 -0.015501296220065 -0.152239125792337 -0.0923878429500696 0.984016125402942 0.0459739746334013 5.41693279252125e-05 1.80693502404244e-05 -8.5290342555588e-06 -3.01341601541747e-06 -2.21521104062706e-06 3.84233539417078e-06 1.80693502404244e-05 5.38327757691959e-05 -7.56902727331859e-06 3.39104918367792e-06 7.89913322892708e-06 3.37714701254512e-05 -8.5290342555588e-06 -7.56902727331859e-06 1.31575501126885e-05 2.04922046597119e-07 1.78563872801761e-06 -1.07359189444627e-06 -3.01341601541747e-06 3.39104918367792e-06 2.04922046597119e-07 4.27977810893677e-05 -1.26404922816238e-05 2.01798185055784e-07 -2.21521104062706e-06 7.89913322892708e-06 1.78563872801761e-06 -1.26404922816238e-05 6.30315413054113e-05 8.98029404749992e-06 3.84233539417078e-06 3.37714701254512e-05 -1.07359189444627e-06 2.01798185055784e-07 8.98029404749992e-06 8.49493830566772e-05 1364 1364 0 71 0 1316 1317 0 70 0 0 0 0 0 0 0 0 0 343 0 262 253 0 0 2026 +337 379 0.983613450305112 0.0844177143321083 0.159305460941599 -0.0026971459328595 -0.0977991820147666 0.992136476284944 0.0781059051681649 -0.0234225989065306 -0.15145923668141 -0.0924059626422363 0.984134766021426 0.0415615691272408 6.19381424393415e-05 1.90418133118589e-05 -1.24361819386421e-05 -1.02742605675773e-06 1.52595284259466e-06 2.80739535336945e-06 1.90418133118589e-05 5.31157070296426e-05 -8.49587212301056e-06 8.61191702849471e-06 7.83928796158459e-07 4.1220974848116e-05 -1.24361819386421e-05 -8.49587212301056e-06 1.47327475377739e-05 3.00907159032191e-06 2.50759783688983e-06 -2.36500017722814e-06 -1.02742605675773e-06 8.61191702849471e-06 3.00907159032191e-06 3.40231248587788e-05 3.84586941630182e-06 1.56728985340135e-06 1.52595284259466e-06 7.83928796158459e-07 2.50759783688983e-06 3.84586941630182e-06 4.06093243790185e-05 1.17196031502094e-06 2.80739535336945e-06 4.1220974848116e-05 -2.36500017722814e-06 1.56728985340135e-06 1.17196031502094e-06 9.16477685344007e-05 1500 1501 0 74 0 1454 1457 0 71 0 0 0 0 0 0 0 0 0 342 0 262 252 0 0 1988 +337 384 0.984351837679875 0.0853014253926128 0.154191849597318 -0.0173988045435455 -0.097884146499825 0.992296838739729 0.0759320597056383 -0.0151211129666355 -0.146526971988962 -0.0898368001051258 0.985118873957157 0.0410372491682264 5.43991461638591e-05 3.75298992476065e-06 -9.20370531007568e-06 -7.12266483136494e-06 3.17665374525146e-06 -1.23289126963247e-05 3.75298992476065e-06 6.10913695124412e-05 -4.89312412078727e-06 1.77839796515668e-05 7.30542422489698e-06 3.76882409148838e-05 -9.20370531007568e-06 -4.89312412078727e-06 1.43069759448445e-05 1.66739197078686e-06 -5.84170813175969e-07 -7.9484484644106e-08 -7.12266483136494e-06 1.77839796515668e-05 1.66739197078686e-06 7.18272979807328e-05 -1.43043595903158e-05 7.26138223744885e-06 3.17665374525146e-06 7.30542422489698e-06 -5.84170813175969e-07 -1.43043595903158e-05 5.80824006677546e-05 1.34850185817711e-05 -1.23289126963247e-05 3.76882409148838e-05 -7.9484484644106e-08 7.26138223744885e-06 1.34850185817711e-05 8.62710756913404e-05 1343 1347 0 76 0 1295 1301 0 75 0 0 0 0 0 0 0 0 0 362 0 262 256 0 0 2045 +337 417 0.984636461648757 0.0858000186936021 0.152083513846812 -0.0191149090115623 -0.0983739577061339 0.992153122181743 0.0771670045437265 -0.0139576184642014 -0.144269202663104 -0.0909425034689349 0.985350627048948 0.0362929694973784 7.1496852800646e-05 3.58657130769033e-05 -1.30816053252424e-05 5.51683639704472e-06 4.51036120830218e-06 1.95708039647282e-05 3.58657130769033e-05 0.000102748665615225 -1.41533029923016e-05 2.54458266921854e-05 1.60060660985174e-05 8.83127400394075e-05 -1.30816053252424e-05 -1.41533029923016e-05 1.75873227389631e-05 2.71355096830596e-06 -1.65905469790443e-06 -6.62080018789359e-06 5.51683639704472e-06 2.54458266921854e-05 2.71355096830596e-06 6.2645958985928e-05 -5.45263457804062e-06 3.91009992705914e-05 4.51036120830218e-06 1.60060660985174e-05 -1.65905469790443e-06 -5.45263457804062e-06 6.06500675144038e-05 1.23059269842417e-05 1.95708039647282e-05 8.83127400394075e-05 -6.62080018789359e-06 3.91009992705914e-05 1.23059269842417e-05 0.000181229850003732 1475 1477 0 74 0 1424 1428 0 75 0 0 0 0 0 0 0 0 0 309 0 215 230 0 0 1537 +337 413 0.984934244691314 0.0860170278884707 0.150018680662062 -0.0192230020379377 -0.0983568259053273 0.992178482486761 0.0768621733240609 -0.0193423619988827 -0.142233851217566 -0.0904595478846921 0.985690926083991 0.0394107320966106 9.7394970666918e-05 8.064977421571e-05 -1.76605739741971e-05 1.64381600783991e-05 2.82245094398961e-06 6.6134257267926e-05 8.064977421571e-05 0.000122386731492057 -1.90782926200604e-05 2.99511734019626e-05 -8.90222317233601e-07 0.000101256697190077 -1.76605739741971e-05 -1.90782926200604e-05 1.64906077913315e-05 7.56857046906457e-07 3.93662552022887e-06 -1.21847846931043e-05 1.64381600783991e-05 2.99511734019626e-05 7.56857046906457e-07 5.52040743685901e-05 -3.09802394270708e-06 1.97077081919093e-05 2.82245094398961e-06 -8.90222317233601e-07 3.93662552022887e-06 -3.09802394270708e-06 5.16090559587511e-05 1.6915208032311e-06 6.6134257267926e-05 0.000101256697190077 -1.21847846931043e-05 1.97077081919093e-05 1.6915208032311e-06 0.00016566986434705 1159 1160 0 71 0 1136 1139 0 70 0 0 0 0 0 0 0 0 0 313 0 223 239 0 0 1554 +337 378 0.984365514554799 0.0847243007402947 0.1544225586478 -0.00564074113169042 -0.097609428949154 0.992175167412953 0.0778513747425081 -0.0265869355955932 -0.146618324691988 -0.0917073063236865 0.984932909812322 0.0454290436501885 5.14058525280718e-05 1.40320928323605e-05 -8.72227029578018e-06 5.23521255625405e-07 1.89324810141753e-07 -5.16335403234309e-06 1.40320928323605e-05 4.85499489014771e-05 -9.04964883736271e-06 4.12556932523831e-06 3.48756090865212e-06 3.30144860332286e-05 -8.72227029578018e-06 -9.04964883736271e-06 1.36418383625138e-05 1.24283975285128e-06 -3.38558783590663e-07 -4.64229037614165e-07 5.23521255625405e-07 4.12556932523831e-06 1.24283975285128e-06 4.00206088992728e-05 -2.3491473784623e-06 4.8575272368052e-06 1.89324810141753e-07 3.48756090865212e-06 -3.38558783590663e-07 -2.3491473784623e-06 4.35425336154282e-05 8.51418921632102e-06 -5.16335403234309e-06 3.30144860332286e-05 -4.64229037614165e-07 4.8575272368052e-06 8.51418921632102e-06 8.16864362719555e-05 1313 1314 0 74 0 1298 1301 0 74 0 0 0 0 0 0 0 0 0 363 0 263 253 0 0 2057 +337 383 0.983202143382233 0.0844063667586757 0.161830499286085 -0.0156570521410317 -0.0982886380969649 0.991955168633305 0.07977648176446 -0.0137560659080098 -0.153794957230812 -0.0943425072396917 0.983588634774773 0.0474547240174095 6.95125276903881e-05 2.7189048828754e-05 -1.18769827576755e-05 5.62021975392901e-06 -6.39645313981469e-06 2.12105338281551e-05 2.7189048828754e-05 5.78451762829016e-05 -7.67284183058518e-06 1.21196245437121e-05 -2.19302950129901e-06 3.69969732987861e-05 -1.18769827576755e-05 -7.67284183058518e-06 1.37431214923461e-05 -5.96239057580286e-07 1.2860734676017e-06 -5.10933503560614e-06 5.62021975392901e-06 1.21196245437121e-05 -5.96239057580286e-07 6.38389518685289e-05 -1.64495560382222e-05 6.26334389043788e-07 -6.39645313981469e-06 -2.19302950129901e-06 1.2860734676017e-06 -1.64495560382222e-05 5.25601660860697e-05 -1.99814527086913e-06 2.12105338281551e-05 3.69969732987861e-05 -5.10933503560614e-06 6.26334389043788e-07 -1.99814527086913e-06 9.69124540738358e-05 1481 1478 0 70 0 1434 1433 0 70 0 0 0 0 0 0 0 0 0 334 0 260 251 0 0 2006 +337 363 0.989468249662007 0.091283084039115 0.112338690926646 0.0100645354556349 -0.0935992677471349 0.99548916091305 0.0155083068654113 -0.0173579430074166 -0.110416303089738 -0.0258597964597456 0.993548947429897 0.0445499521157776 6.20334785200175e-05 1.02746051643435e-05 -9.81169043828547e-06 4.37704575871478e-06 -1.82351493355195e-06 4.91434782627455e-06 1.02746051643435e-05 5.20860030607536e-05 -1.00313173156579e-05 1.54632666720222e-05 -2.33051028447136e-06 3.54151876034038e-05 -9.81169043828547e-06 -1.00313173156579e-05 1.61506194697632e-05 -7.31379116530851e-07 2.7147021866376e-06 -5.49473370094642e-06 4.37704575871478e-06 1.54632666720222e-05 -7.31379116530851e-07 4.42693421802762e-05 -5.05861512631407e-06 1.43178457119685e-05 -1.82351493355195e-06 -2.33051028447136e-06 2.7147021866376e-06 -5.05861512631407e-06 4.72085403046434e-05 1.82926117117301e-06 4.91434782627455e-06 3.54151876034038e-05 -5.49473370094642e-06 1.43178457119685e-05 1.82926117117301e-06 7.08227409151931e-05 1515 1509 0 72 0 1494 1488 0 75 0 0 0 0 0 0 0 0 0 281 0 244 236 0 0 2460 +337 385 0.983785128287301 0.0843349672151762 0.158285926934623 -0.0131421961637696 -0.0978647255842492 0.992002213807276 0.0797126294120554 -0.0185388147396747 -0.150297427945582 -0.0939107081555624 0.984170443595348 0.0386762606884749 6.68106884749356e-05 2.76538031094195e-05 -1.16247437269016e-05 1.08976123102193e-05 -3.84490836924073e-07 9.52003589528282e-06 2.76538031094195e-05 4.57035996359096e-05 -9.44350594168235e-06 1.56476150707545e-05 -8.06253272958086e-06 2.30026084483659e-05 -1.16247437269016e-05 -9.44350594168235e-06 1.3585779511041e-05 -7.56259327809822e-07 1.25129893452101e-06 -2.19920458932752e-06 1.08976123102193e-05 1.56476150707545e-05 -7.56259327809822e-07 5.73361189436819e-05 -1.15775330274912e-05 8.94775602702559e-06 -3.84490836924073e-07 -8.06253272958086e-06 1.25129893452101e-06 -1.15775330274912e-05 3.94822510287998e-05 -9.86987696612615e-06 9.52003589528282e-06 2.30026084483659e-05 -2.19920458932752e-06 8.94775602702559e-06 -9.86987696612615e-06 6.68339125521649e-05 1576 1575 0 71 0 1547 1548 0 72 0 0 0 0 0 0 0 0 0 326 0 248 249 0 0 2074 +337 418 0.984240616985646 0.0847345339757528 0.155211039000539 -0.0224313047256073 -0.0980655713642516 0.991931990967565 0.0803372205650931 -0.0114223396637583 -0.147151457990458 -0.0942920147575261 0.984609295286333 0.044116163641545 6.55494626492925e-05 3.11548285407916e-05 -1.30830643772484e-05 2.07396017851354e-06 3.12128650455944e-06 1.95651663598663e-05 3.11548285407916e-05 6.34993391001175e-05 -1.13143811139342e-05 1.40912433026448e-05 -4.51543679808348e-06 3.35039042631847e-05 -1.30830643772484e-05 -1.13143811139342e-05 1.68543509011887e-05 2.47866734290323e-06 -7.59626004816912e-07 -4.96034457136824e-06 2.07396017851354e-06 1.40912433026448e-05 2.47866734290323e-06 8.79881836725903e-05 -4.10307068501436e-05 7.91108869276215e-06 3.12128650455944e-06 -4.51543679808348e-06 -7.59626004816912e-07 -4.10307068501436e-05 8.26369121104239e-05 -5.8325446559835e-06 1.95651663598663e-05 3.35039042631847e-05 -4.96034457136824e-06 7.91108869276215e-06 -5.8325446559835e-06 9.21779423338714e-05 1234 1238 0 75 0 1236 1242 0 75 0 0 0 0 0 0 0 0 0 320 0 191 203 0 0 1470 +337 387 0.984638744887619 0.0851270325170291 0.152446483727826 -0.0171583315469515 -0.0978142819842117 0.992163409421119 0.0777440367216319 -0.0150900528085006 -0.144633703907654 -0.0914612340869397 0.985249173738932 0.0384974081101679 6.8914072800427e-05 2.86318673165643e-05 -1.25233048977685e-05 2.58702801024324e-06 -1.45693965157704e-06 6.53952267284532e-06 2.86318673165643e-05 6.00227843668197e-05 -1.06109850779783e-05 7.99389313505754e-06 -1.37745840980302e-06 3.37949819266007e-05 -1.25233048977685e-05 -1.06109850779783e-05 1.45202050437305e-05 -1.15726794099671e-06 5.99784161646132e-07 -1.81494255155495e-06 2.58702801024324e-06 7.99389313505754e-06 -1.15726794099671e-06 4.86742705820652e-05 1.1714939864778e-06 3.57376657120439e-06 -1.45693965157704e-06 -1.37745840980302e-06 5.99784161646132e-07 1.1714939864778e-06 4.29886989418897e-05 2.72560402057562e-07 6.53952267284532e-06 3.37949819266007e-05 -1.81494255155495e-06 3.57376657120439e-06 2.72560402057562e-07 7.9839978544447e-05 1316 1319 0 74 0 1267 1273 0 73 0 0 0 0 0 0 0 0 0 342 0 266 259 0 0 2037 +337 425 0.983809715498182 0.0854512136338497 0.157532643537422 -0.0202128930279638 -0.0987350163207613 0.99201190363449 0.0785097420681945 -0.0129159362360969 -0.149565504858323 -0.0927926351386661 0.984387975658224 0.0447821968537532 7.23677795930482e-05 4.54678324988613e-05 -1.29003577014231e-05 1.11754126823514e-05 1.12541877914094e-06 2.51404333780735e-05 4.54678324988613e-05 0.0001033589342173 -9.0560744647963e-06 3.63971687498217e-05 -3.93822406510234e-06 8.40773607594741e-05 -1.29003577014231e-05 -9.0560744647963e-06 1.59888726727415e-05 -1.60082408543081e-06 -4.03307609555258e-07 -1.19946265017018e-07 1.11754126823514e-05 3.63971687498217e-05 -1.60082408543081e-06 7.30632846111715e-05 -1.67987061736119e-05 2.83701420323588e-05 1.12541877914094e-06 -3.93822406510234e-06 -4.03307609555258e-07 -1.67987061736119e-05 5.933849155706e-05 -9.68986772402809e-06 2.51404333780735e-05 8.40773607594741e-05 -1.19946265017018e-07 2.83701420323588e-05 -9.68986772402809e-06 0.000143417892515368 1364 1366 0 74 0 1343 1346 0 71 0 0 0 0 0 0 0 0 0 337 0 227 243 0 0 1427 +337 386 0.983795374634252 0.0845502086406982 0.158107315033383 -0.0135778377048353 -0.0980560160639979 0.991987831641487 0.0796565100219585 -0.0155909557208395 -0.150105558064676 -0.0938690795418587 0.984203697079043 0.049036147148257 5.40140407569392e-05 2.14562342068423e-05 -7.14486789229233e-06 -2.0416128493991e-06 7.03538931328817e-06 -1.22651362304328e-06 2.14562342068423e-05 5.77877801692365e-05 -6.60225426029138e-06 6.53992661038567e-06 1.10124399910657e-05 3.2753014688484e-05 -7.14486789229233e-06 -6.60225426029138e-06 1.24757380951048e-05 2.29889758182826e-06 2.90010277872144e-06 -4.93406315949051e-07 -2.0416128493991e-06 6.53992661038567e-06 2.29889758182826e-06 5.14689765560883e-05 -4.94268123044925e-06 -5.87208689220109e-06 7.03538931328817e-06 1.10124399910657e-05 2.90010277872144e-06 -4.94268123044925e-06 6.06503176000499e-05 2.21490405648244e-05 -1.22651362304328e-06 3.2753014688484e-05 -4.93406315949051e-07 -5.87208689220109e-06 2.21490405648244e-05 7.91853360374542e-05 1151 1153 0 70 0 1127 1131 0 69 0 0 0 0 0 0 0 0 0 335 0 263 255 0 0 1998 +337 419 0.983345031808981 0.085299328644885 0.16048854460467 -0.00894682360007387 -0.0983676968892784 0.992296045800104 0.07531502969645 -0.0209580809049707 -0.152827826737451 -0.0898475487824236 0.984160085226229 0.0411320144497386 9.26054066375156e-05 2.46064966260131e-05 -1.73434423840168e-05 3.51361203927311e-06 -5.25230016574093e-06 8.62023361974935e-06 2.46064966260131e-05 7.93252064905946e-05 -7.21276455015682e-06 2.08639458960606e-05 -1.88717908639309e-06 4.91843214730643e-05 -1.73434423840168e-05 -7.21276455015682e-06 1.65013709122921e-05 2.45520950250411e-07 7.88641772543187e-07 -2.17405928992134e-06 3.51361203927311e-06 2.08639458960606e-05 2.45520950250411e-07 4.83955748671702e-05 -6.81908784291864e-06 1.26763348092721e-05 -5.25230016574093e-06 -1.88717908639309e-06 7.88641772543187e-07 -6.81908784291864e-06 5.39402743891664e-05 -1.02642903044083e-05 8.62023361974935e-06 4.91843214730643e-05 -2.17405928992134e-06 1.26763348092721e-05 -1.02642903044083e-05 0.000104915362570428 1478 1480 0 75 0 1441 1445 0 75 0 0 0 0 0 0 0 0 0 287 0 205 230 0 0 1515 +337 395 0.981233848307825 0.0880447446763748 0.17154666382617 -0.00423534457434939 -0.100562779711766 0.992759995519517 0.065686517891665 -0.00984138153839083 -0.164521312515005 -0.0817050440974188 0.982983735113343 0.0608696820678483 0.000173015542126551 9.72741478345811e-05 -2.65583540878985e-05 6.90882863039422e-06 -3.86668270971561e-06 8.17647285524582e-05 9.72741478345811e-05 0.000145840944289739 -2.03457701193823e-05 2.544948991054e-05 -2.15341641565269e-06 0.0001302734453079 -2.65583540878985e-05 -2.03457701193823e-05 1.9511911835664e-05 8.21507741221695e-07 3.57362114704299e-06 -1.91320950182107e-05 6.90882863039422e-06 2.544948991054e-05 8.21507741221695e-07 7.139430818014e-05 -1.67895867861047e-05 2.85056093245087e-05 -3.86668270971561e-06 -2.15341641565269e-06 3.57362114704299e-06 -1.67895867861047e-05 5.61826091356841e-05 1.79677770844357e-06 8.17647285524582e-05 0.0001302734453079 -1.91320950182107e-05 2.85056093245087e-05 1.79677770844357e-06 0.000210318729528276 1457 1460 0 80 0 1434 1438 0 77 0 0 0 0 0 0 0 0 0 146 0 245 241 0 0 1704 +337 388 0.983593458248098 0.0853152909162579 0.158950338242552 -0.0119491980839428 -0.098647149400195 0.9920646732932 0.077951420249233 -0.0156774585473558 -0.151038567282542 -0.0923525047821184 0.984204433059365 0.0406419613567044 9.43392184767809e-05 7.65922407526307e-05 -1.0679786527951e-05 -8.18779237334291e-07 -6.3838498418151e-06 5.71833804479871e-05 7.65922407526307e-05 0.000122941402418924 -1.03040885855858e-05 1.74168241258532e-05 -1.30206729954129e-05 0.000102039981313943 -1.0679786527951e-05 -1.03040885855858e-05 1.44367549427217e-05 2.33670931126062e-06 4.03775318337226e-06 -8.93514384917484e-06 -8.18779237334291e-07 1.74168241258532e-05 2.33670931126062e-06 5.80147934316549e-05 -1.78641798694525e-05 1.94878128848331e-05 -6.3838498418151e-06 -1.30206729954129e-05 4.03775318337226e-06 -1.78641798694525e-05 4.56278619714041e-05 -1.11548211900108e-05 5.71833804479871e-05 0.000102039981313943 -8.93514384917484e-06 1.94878128848331e-05 -1.11548211900108e-05 0.000155853119982993 1565 1568 0 74 0 1527 1532 0 66 0 0 0 0 0 0 0 0 0 354 0 251 251 0 0 1968 +337 411 0.984136263608113 0.086431340023704 0.154936884288959 -0.0186592408924443 -0.0986169794149467 0.99246216053434 0.0727567954117152 -0.0122666438234009 -0.147480527604614 -0.0868820083171255 0.985241600120624 0.0446208880393445 6.59940240288082e-05 4.16701246507002e-05 -1.06565124492889e-05 1.37936446573926e-05 -3.22763875587944e-06 1.97927043326001e-05 4.16701246507002e-05 9.7410607141273e-05 -9.28357567700519e-06 3.88540270677082e-05 -2.36566603348926e-05 6.51688994622357e-05 -1.06565124492889e-05 -9.28357567700519e-06 1.47751257468469e-05 7.99714891249681e-08 4.6230280331869e-06 -3.51805991184466e-06 1.37936446573926e-05 3.88540270677082e-05 7.99714891249681e-08 9.59955098636949e-05 -4.00391566440978e-05 2.11001574089944e-05 -3.22763875587944e-06 -2.36566603348926e-05 4.6230280331869e-06 -4.00391566440978e-05 6.53145784652411e-05 -2.13009180466172e-05 1.97927043326001e-05 6.51688994622357e-05 -3.51805991184466e-06 2.11001574089944e-05 -2.13009180466172e-05 0.000123601709777281 1141 1144 0 67 0 1142 1146 0 68 0 0 0 0 0 0 0 0 0 242 0 186 199 0 0 1526 +337 394 0.98313030484852 0.0872972685294948 0.160729557318328 -0.011483154489237 -0.100107504330635 0.992265984806048 0.0733941617131509 -0.0143482449079225 -0.153079362636341 -0.0882462594344572 0.984265871820555 0.0543963448019189 8.16486301209599e-05 2.67447226243177e-05 -9.74474880719931e-06 -4.39030929070942e-06 -1.20730198320808e-05 -1.00858042431099e-06 2.67447226243177e-05 9.2091039744232e-05 -2.82033903797171e-06 1.45074888100817e-05 1.33937983797683e-05 5.76476096439359e-05 -9.74474880719931e-06 -2.82033903797171e-06 1.63447735230096e-05 4.49887339451034e-06 5.92902888103303e-06 3.8961459229427e-06 -4.39030929070942e-06 1.45074888100817e-05 4.49887339451034e-06 5.79552257931527e-05 1.11864114607325e-05 8.57677999429601e-06 -1.20730198320808e-05 1.33937983797683e-05 5.92902888103303e-06 1.11864114607325e-05 6.29034621739192e-05 9.20770864954796e-06 -1.00858042431099e-06 5.76476096439359e-05 3.8961459229427e-06 8.57677999429601e-06 9.20770864954796e-06 0.000118782726331219 1158 1161 0 78 0 1135 1140 0 67 0 0 0 0 0 0 0 0 0 169 0 262 255 0 0 1716 +337 392 0.982191962649207 0.0895685241068164 0.165155768886907 -0.00936762826325486 -0.101159365089412 0.99286438023499 0.0631435294808311 -0.00908983613736227 -0.158321607375638 -0.0787261198708286 0.984244109298135 0.0608248250309705 0.000190287941929461 0.000135211243556805 -3.40026384876384e-05 3.73555994801432e-05 -2.9265902603121e-05 0.000108063533998194 0.000135211243556805 0.000203945450642435 -2.89991688072365e-05 5.67882175922058e-05 -1.77744657011603e-05 0.000164235155565232 -3.40026384876384e-05 -2.89991688072365e-05 2.03378878061774e-05 -4.17566110058942e-06 9.24443648308946e-06 -2.31763040318796e-05 3.73555994801432e-05 5.67882175922058e-05 -4.17566110058942e-06 8.14894215948574e-05 -2.33205563508923e-05 3.72677026325583e-05 -2.9265902603121e-05 -1.77744657011603e-05 9.24443648308946e-06 -2.33205563508923e-05 6.7284522189543e-05 2.35531001936274e-06 0.000108063533998194 0.000164235155565232 -2.31763040318796e-05 3.72677026325583e-05 2.35531001936274e-06 0.000224356524889348 1304 1302 0 66 0 1283 1283 0 65 0 0 0 0 0 0 0 0 0 131 0 234 235 0 0 1627 +337 427 0.982983629315845 0.0851057914715631 0.162788785716487 -0.00907611797578245 -0.0986661545501951 0.992129192428323 0.0771015919277939 -0.0192981159103065 -0.154945714504554 -0.0918513461497536 0.983643815497842 0.0470485679286607 6.58808563227687e-05 3.18541109808681e-05 -1.1254673985763e-05 1.04088376888325e-05 -3.74485370594526e-06 1.44821761414064e-05 3.18541109808681e-05 7.30519293218209e-05 -1.0906242459696e-05 1.40192220389749e-05 -2.19960161862253e-06 5.23636034799349e-05 -1.1254673985763e-05 -1.0906242459696e-05 1.54054232559233e-05 2.57094487660332e-07 1.71149623481575e-06 -3.85960367869747e-06 1.04088376888325e-05 1.40192220389749e-05 2.57094487660332e-07 5.34556979841662e-05 -1.2320131476038e-05 1.33280703559293e-05 -3.74485370594526e-06 -2.19960161862253e-06 1.71149623481575e-06 -1.2320131476038e-05 5.45433135442886e-05 -4.34309410483371e-06 1.44821761414064e-05 5.23636034799349e-05 -3.85960367869747e-06 1.33280703559293e-05 -4.34309410483371e-06 0.000111737348384374 1417 1416 0 71 0 1383 1383 0 68 0 0 0 0 0 0 0 0 0 335 0 215 237 0 0 1695 +337 376 0.983113966088361 0.0836502982921546 0.162756128233767 -0.00159126827898662 -0.097908695811963 0.991841014380693 0.0816412241253043 -0.0223438947590855 -0.154598890573035 -0.0961978678969094 0.983282844986973 0.0498256055584255 7.26373397238129e-05 2.86329111439708e-05 -1.3032254706592e-05 7.67083596063798e-07 5.8205767565783e-06 2.03672217067118e-05 2.86329111439708e-05 7.01261899491133e-05 -1.13246436387238e-05 1.16336003217504e-05 5.81421324037415e-06 5.42856847542463e-05 -1.3032254706592e-05 -1.13246436387238e-05 1.48084326141684e-05 -3.15652741832221e-07 -5.57270700608607e-07 -5.25244210864014e-06 7.67083596063798e-07 1.16336003217504e-05 -3.15652741832221e-07 3.99812193359757e-05 1.4214411743241e-06 7.72630155532903e-06 5.8205767565783e-06 5.81421324037415e-06 -5.57270700608607e-07 1.4214411743241e-06 4.04609263462413e-05 1.5449398551288e-05 2.03672217067118e-05 5.42856847542463e-05 -5.25244210864014e-06 7.72630155532903e-06 1.5449398551288e-05 0.000109871023201401 1477 1476 0 73 0 1425 1427 0 67 0 0 0 0 0 0 0 0 0 336 0 264 258 0 0 1976 +337 377 0.983786761784049 0.0844475908216997 0.158215712692721 -0.00476023451418407 -0.097771364089978 0.992115889195382 0.0784016758114379 -0.0262769424439873 -0.15034748984416 -0.0925994968154127 0.984287034094777 0.0482440993599335 6.27530418180141e-05 8.15361701710133e-06 -1.05433704377283e-05 -7.4163420807283e-06 -5.23649058048563e-06 -2.25691934680169e-05 8.15361701710133e-06 6.12266246005464e-05 -8.00956158325202e-06 1.73253216633398e-05 2.59222952932683e-06 5.17128192901912e-05 -1.05433704377283e-05 -8.00956158325202e-06 1.4339043074725e-05 2.41884020595608e-06 1.82425667634379e-06 1.20046492574797e-06 -7.4163420807283e-06 1.73253216633398e-05 2.41884020595608e-06 5.57252879404462e-05 -6.10704404714698e-06 2.45414299873996e-05 -5.23649058048563e-06 2.59222952932683e-06 1.82425667634379e-06 -6.10704404714698e-06 4.92809410847412e-05 7.33200963088118e-08 -2.25691934680169e-05 5.17128192901912e-05 1.20046492574797e-06 2.45414299873996e-05 7.33200963088118e-08 0.000104604691998124 1359 1363 0 73 0 1341 1346 0 74 0 0 0 0 0 0 0 0 0 339 0 244 230 0 0 2030 +337 393 0.9821972411855 0.0886350804545497 0.165627298234342 -0.00967542088061179 -0.100665335290214 0.992749066022187 0.0656946130438662 -0.00575526787484615 -0.158603498317348 -0.0811979952024068 0.983997873928907 0.0580497919414913 0.000141489151413959 8.98846250099102e-05 -2.48884118442778e-05 2.74259911677201e-05 -2.70762627517385e-05 7.14033915884175e-05 8.98846250099102e-05 0.000148550587596909 -2.09856084952266e-05 5.56236403232884e-05 -2.7880462944781e-05 0.000127683039958054 -2.48884118442778e-05 -2.09856084952266e-05 1.77980211941362e-05 -7.57424281148132e-06 9.23212648664619e-06 -1.50156895559153e-05 2.74259911677201e-05 5.56236403232884e-05 -7.57424281148132e-06 9.39875860006335e-05 -2.87916679188032e-05 5.50906519660268e-05 -2.70762627517385e-05 -2.7880462944781e-05 9.23212648664619e-06 -2.87916679188032e-05 7.28606541106548e-05 -3.01962021194845e-05 7.14033915884175e-05 0.000127683039958054 -1.50156895559153e-05 5.50906519660268e-05 -3.01962021194845e-05 0.000195103727839296 1403 1405 0 75 0 1389 1392 0 69 0 0 0 0 0 0 0 0 0 146 0 233 223 0 0 1651 +337 391 0.979940427843227 0.0887659560462223 0.178430274689116 0.00165937230642583 -0.101053888012419 0.99301013531519 0.0609834639790194 -0.0103136493345079 -0.171769815730258 -0.0777912347794215 0.982060921835039 0.0703206291178635 8.90102214496005e-05 -1.04983227295882e-05 -1.10608826967122e-05 -2.92557759857751e-06 -4.17334688427756e-06 -3.21571839777094e-05 -1.04983227295882e-05 0.00012929402552577 6.20330420229778e-06 5.00089976316236e-05 -5.22866308009048e-07 9.88123812162364e-05 -1.10608826967122e-05 6.20330420229778e-06 1.5928761487459e-05 5.69711260529816e-06 7.58144287758656e-06 1.00743168730469e-05 -2.92557759857751e-06 5.00089976316236e-05 5.69711260529816e-06 7.35502670877518e-05 -1.16695577528298e-05 5.18595128756425e-05 -4.17334688427756e-06 -5.22866308009048e-07 7.58144287758656e-06 -1.16695577528298e-05 5.41057823487875e-05 3.32222896639805e-06 -3.21571839777094e-05 9.88123812162364e-05 1.00743168730469e-05 5.18595128756425e-05 3.32222896639805e-06 0.000163440508538051 1361 1362 0 70 0 1334 1336 0 67 0 0 0 0 0 0 0 0 0 115 0 246 239 0 0 1676 +337 396 0.980985431514421 0.0877981877420165 0.173086860811801 -0.00720959571707361 -0.100243449902024 0.992869668173994 0.0645063777606857 -0.0200268437217466 -0.166189150994301 -0.0806306408834848 0.98279187310565 0.0659316527891568 0.000166847193863341 0.00010751835136064 -2.7724745974247e-05 1.53639649343792e-05 -2.89411188821022e-05 8.50419587899057e-05 0.00010751835136064 0.00011574299730498 -2.24860768486441e-05 2.11009251911607e-05 -1.40482611659041e-05 8.28176886609539e-05 -2.7724745974247e-05 -2.24860768486441e-05 1.7713907521674e-05 -2.63300276223716e-07 1.0781161339601e-05 -1.74601221541826e-05 1.53639649343792e-05 2.11009251911607e-05 -2.63300276223716e-07 6.25080992679115e-05 -2.45715201761913e-06 2.20614700678087e-05 -2.89411188821022e-05 -1.40482611659041e-05 1.0781161339601e-05 -2.45715201761913e-06 6.84558565560486e-05 -9.32194337606094e-06 8.50419587899057e-05 8.28176886609539e-05 -1.74601221541826e-05 2.20614700678087e-05 -9.32194337606094e-06 0.000144756898547958 1241 1244 0 72 0 1235 1238 0 72 0 0 0 0 0 0 0 0 0 150 0 266 261 0 0 1765 +338 342 0.997161556069113 0.0752810478768135 0.0012629047447508 0.0177460645674029 -0.075240410801582 0.996961542326206 -0.0201634249313227 0.00213321200518629 -0.00277699121975328 0.0200111707084021 0.999795899854888 0.013768045600252 4.78688497605977e-05 1.76820872621838e-05 -1.13354013476347e-05 3.73404249062224e-06 9.61760900959322e-06 1.55681394340462e-05 1.76820872621838e-05 3.87702691746445e-05 -8.51426395225382e-06 4.73845172825069e-06 8.28638746287511e-06 1.00404067332057e-05 -1.13354013476347e-05 -8.51426395225382e-06 1.7732334674861e-05 1.60787709527595e-06 -4.52403901503471e-06 -6.78400074996916e-06 3.73404249062224e-06 4.73845172825069e-06 1.60787709527595e-06 3.81670302404593e-05 -2.45412435909046e-06 7.10617186175956e-06 9.61760900959322e-06 8.28638746287511e-06 -4.52403901503471e-06 -2.45412435909046e-06 4.67586245541067e-05 9.72156529537048e-06 1.55681394340462e-05 1.00404067332057e-05 -6.78400074996916e-06 7.10617186175956e-06 9.72156529537048e-06 5.69397558241767e-05 1617 1608 0 61 0 1603 1598 0 62 0 0 0 0 0 0 0 0 0 294 0 170 151 0 0 3065 +338 431 0.98338559546738 -0.112241389013471 0.142669692715704 -0.027898995860944 0.113413758707014 0.993547840792353 -8.59813895189241e-05 -0.0304827858987855 -0.141739514473607 0.0162652589643939 0.989770352853432 -0.00476373737908621 8.69286207875353e-05 3.98017073666601e-05 -1.83580512124169e-05 7.58573487126097e-06 -1.38418039359798e-05 2.65317149001646e-05 3.98017073666601e-05 5.7073752931548e-05 -1.36215060359944e-05 8.01246402580859e-06 8.26426215287727e-06 3.36725389445341e-05 -1.83580512124169e-05 -1.36215060359944e-05 1.76191807330184e-05 -3.70828986190545e-07 -4.15261766385614e-08 -1.08278950395008e-05 7.58573487126097e-06 8.01246402580859e-06 -3.70828986190545e-07 4.08933225055046e-05 -3.48257888421996e-06 1.40689604570569e-05 -1.38418039359798e-05 8.26426215287727e-06 -4.15261766385614e-08 -3.48257888421996e-06 7.09913222851884e-05 8.44096593571892e-06 2.65317149001646e-05 3.36725389445341e-05 -1.08278950395008e-05 1.40689604570569e-05 8.44096593571892e-06 9.31755866813826e-05 1814 1818 0 0 189 1732 1739 0 0 189 0 0 0 0 0 85 85 0 504 0 0 0 0 0 2125 +338 430 0.990693407791225 0.00812540109037137 0.135869605196051 -0.035109192583103 -0.0179340360314078 0.997306230455893 0.0711242085754322 -0.0115487083073751 -0.134925691069694 -0.0728989749652079 0.988170429297693 0.0145878494220019 9.08429429679e-05 5.3210797179814e-05 -1.70514127679872e-05 7.17668027834077e-06 5.9521572961023e-07 2.74374922449485e-05 5.3210797179814e-05 8.01219579211294e-05 -1.36318749263076e-05 1.9714882951772e-05 -2.37983254381819e-07 4.84833981432558e-05 -1.70514127679872e-05 -1.36318749263076e-05 1.55799724965737e-05 -3.96671045823107e-07 -5.79810406811284e-08 -7.61941849919574e-06 7.17668027834077e-06 1.9714882951772e-05 -3.96671045823107e-07 5.85295996250336e-05 -1.35457972693174e-05 1.19207829297826e-05 5.9521572961023e-07 -2.37983254381819e-07 -5.79810406811284e-08 -1.35457972693174e-05 6.34505024131836e-05 2.18344429257489e-06 2.74374922449485e-05 4.84833981432558e-05 -7.61941849919574e-06 1.19207829297826e-05 2.18344429257489e-06 0.000122098142237178 1611 1606 0 11 23 1556 1577 0 22 5 0 0 0 0 0 1 13 0 441 0 100 72 0 0 1930 +338 380 0.982877307191898 0.0815300189225153 0.165242412902071 -0.0206681310143039 -0.0997443508845959 0.989446936552365 0.10509911614162 -0.0139285149638577 -0.154929866306709 -0.119781533475046 0.980637099422897 0.0287604196626301 9.22010585515504e-05 5.07733669681296e-05 -1.89138739215722e-05 1.61510036564516e-05 -1.29951140873401e-05 3.57413910901384e-05 5.07733669681296e-05 5.94871042596221e-05 -1.46450232750357e-05 1.34934859688053e-05 -4.86838042059354e-06 4.23219332444319e-05 -1.89138739215722e-05 -1.46450232750357e-05 1.47043279049809e-05 -2.25058221483621e-06 2.83872479233167e-06 -7.01918760788744e-06 1.61510036564516e-05 1.34934859688053e-05 -2.25058221483621e-06 5.06724733117328e-05 -2.23517735908212e-05 1.389003866312e-05 -1.29951140873401e-05 -4.86838042059354e-06 2.83872479233167e-06 -2.23517735908212e-05 6.48455585974364e-05 -1.3388206447266e-05 3.57413910901384e-05 4.23219332444319e-05 -7.01918760788744e-06 1.389003866312e-05 -1.3388206447266e-05 9.84484890765602e-05 1564 1575 0 92 0 1589 1602 0 95 0 0 0 0 0 0 0 0 0 366 0 236 227 0 0 2068 +338 384 0.982363290201073 0.0811546726389393 0.168452619968314 -0.0139915848999902 -0.100016959195564 0.989250087946255 0.106681166902128 -0.017282191335713 -0.15798409394175 -0.121647780938221 0.979919814808442 0.0292615501079351 5.19386099685568e-05 1.89431303055303e-05 -8.09503632600174e-06 1.22413580372807e-06 5.37150101555885e-06 1.04854797874285e-06 1.89431303055303e-05 5.05525899457393e-05 -9.0203011697807e-06 1.19842819121765e-05 2.32720792674931e-07 2.04868278018411e-05 -8.09503632600174e-06 -9.0203011697807e-06 1.35645604179144e-05 1.78643090791426e-06 1.93174817245273e-07 -2.09990160390488e-06 1.22413580372807e-06 1.19842819121765e-05 1.78643090791426e-06 3.66383852550162e-05 -4.16483945609286e-06 7.55971451703372e-06 5.37150101555885e-06 2.32720792674931e-07 1.93174817245273e-07 -4.16483945609286e-06 3.80779190354044e-05 -6.49900648668437e-06 1.04854797874285e-06 2.04868278018411e-05 -2.09990160390488e-06 7.55971451703372e-06 -6.49900648668437e-06 7.6182240963745e-05 1575 1582 0 87 0 1600 1608 0 89 0 0 0 0 0 0 0 0 0 380 0 231 225 0 0 2144 +338 341 0.997209225353752 0.0738948382871582 0.0106448928545525 0.00924575786885502 -0.0739272414988685 0.997260028916892 0.0026828509179115 0.00942751077672275 -0.0104174773212206 -0.00346231125037821 0.999939742468049 0.00725274022721412 4.7325606137057e-05 1.06270230475026e-05 -7.72530461983793e-06 7.01182426898425e-06 -3.19528267135436e-06 1.89423058367401e-05 1.06270230475026e-05 4.72314745782343e-05 -6.84461291800246e-06 1.25963657310492e-05 3.08966669108208e-06 2.04592670083764e-05 -7.72530461983793e-06 -6.84461291800246e-06 1.36800403093716e-05 1.3171091211383e-07 1.3864145265425e-07 -5.1214036781383e-06 7.01182426898425e-06 1.25963657310492e-05 1.3171091211383e-07 5.30514117049074e-05 -2.62320889643188e-05 4.90347673677811e-06 -3.19528267135436e-06 3.08966669108208e-06 1.3864145265425e-07 -2.62320889643188e-05 5.44679490752207e-05 4.02957281443236e-06 1.89423058367401e-05 2.04592670083764e-05 -5.1214036781383e-06 4.90347673677811e-06 4.02957281443236e-06 6.10434610498224e-05 2108 2105 0 63 0 2096 2104 0 60 1 0 0 0 0 0 0 0 0 290 0 181 166 0 0 3076 +338 340 0.998159672631542 0.0576352457975632 0.0188532854947842 0.00772650857748514 -0.0573465483808893 0.998233825974315 -0.0155113529222846 0.013526699386686 -0.0197139879499731 0.0144016361062145 0.999701931355828 0.0159107254546795 6.88499153070503e-05 3.02356951432174e-05 -1.39725338895276e-05 1.60813447786504e-05 7.11061738781733e-06 4.40041256462985e-05 3.02356951432174e-05 4.66265088964656e-05 -1.36260529315914e-05 1.36005105578462e-05 3.93418541972743e-06 3.37516907373527e-05 -1.39725338895276e-05 -1.36260529315914e-05 1.73924159831997e-05 -3.14329836606373e-06 1.76196257385909e-07 -1.64530559385307e-05 1.60813447786504e-05 1.36005105578462e-05 -3.14329836606373e-06 3.84794771346129e-05 -4.85214072969174e-06 1.26682690745978e-05 7.11061738781733e-06 3.93418541972743e-06 1.76196257385909e-07 -4.85214072969174e-06 3.50968285235183e-05 7.57095739902515e-06 4.40041256462985e-05 3.37516907373527e-05 -1.64530559385307e-05 1.26682690745978e-05 7.57095739902515e-06 7.7664264359554e-05 2224 2216 0 52 0 2219 2220 0 52 1 0 0 0 0 0 0 0 0 334 0 156 136 0 0 3198 +338 382 0.982220312829773 0.0810491198088939 0.169334867179758 -0.0163505760570701 -0.0998901233539904 0.989349592314278 0.10587420575332 -0.0189558406666191 -0.158950370622113 -0.120906676266348 0.979855272636382 0.0316914447806107 5.46312770454934e-05 1.86249052710948e-05 -7.07493503035336e-06 5.37332136419533e-06 -3.98747936798079e-06 2.39385742407948e-06 1.86249052710948e-05 4.53105791904992e-05 -8.41997849927716e-06 8.80476212521533e-06 1.08848098580017e-06 1.58851945227914e-05 -7.07493503035336e-06 -8.41997849927716e-06 1.25945132043888e-05 1.47760497192103e-06 9.18880601859509e-07 -1.92591704457831e-06 5.37332136419533e-06 8.80476212521533e-06 1.47760497192103e-06 6.07503701784792e-05 -2.07888263806481e-05 4.25691052506071e-06 -3.98747936798079e-06 1.08848098580017e-06 9.18880601859509e-07 -2.07888263806481e-05 5.51397791859442e-05 -1.1747420050855e-06 2.39385742407948e-06 1.58851945227914e-05 -1.92591704457831e-06 4.25691052506071e-06 -1.1747420050855e-06 6.60497595214353e-05 1532 1538 0 88 0 1525 1532 0 82 0 0 0 0 0 0 0 0 0 364 0 235 225 0 0 2132 +338 417 0.98348705457966 0.08122549673758 0.161727029756808 -0.0184756443923947 -0.0996224509823802 0.989026903657122 0.109092397089203 -0.0219816851987839 -0.151091299334175 -0.123402603384769 0.980787039445043 0.0240125734695451 0.000162161882764272 0.00014055419328394 -3.35860941962349e-05 4.27982764961699e-05 -2.00066168060441e-05 0.000147433418809157 0.00014055419328394 0.000186867367585866 -3.41987956868501e-05 5.21329990582229e-05 -2.52019122900332e-05 0.000183558156969378 -3.35860941962349e-05 -3.41987956868501e-05 2.09780090270681e-05 -6.83437574678228e-06 4.51149286714715e-06 -3.19727408076128e-05 4.27982764961699e-05 5.21329990582229e-05 -6.83437574678228e-06 6.37028399330663e-05 -1.53399593968156e-05 6.34764314198916e-05 -2.00066168060441e-05 -2.52019122900332e-05 4.51149286714715e-06 -1.53399593968156e-05 5.72384326247273e-05 -4.25197869592236e-05 0.000147433418809157 0.000183558156969378 -3.19727408076128e-05 6.34764314198916e-05 -4.25197869592236e-05 0.00027119187740552 1584 1593 0 90 0 1606 1618 0 92 0 0 0 0 0 0 0 0 0 316 0 196 213 0 0 1636 +338 381 0.982906620249077 0.0814374334611438 0.16511365873785 -0.0153102442141132 -0.0999454570125892 0.989215875944707 0.107064729960386 -0.0156728743756619 -0.154613975736613 -0.121736991954818 0.980446134826748 0.0281090288114162 6.50860688338453e-05 2.98960141116315e-05 -1.14323715405633e-05 9.73988661325963e-07 3.67053577078134e-06 1.92999296359872e-05 2.98960141116315e-05 7.2882595259083e-05 -1.06882570061135e-05 5.917317561574e-06 1.27145349685439e-05 6.01191629622767e-05 -1.14323715405633e-05 -1.06882570061135e-05 1.35291990317469e-05 7.32697551353678e-07 8.10163187214131e-07 -4.62887855295755e-06 9.73988661325963e-07 5.917317561574e-06 7.32697551353678e-07 5.58286687441738e-05 -2.3633995482166e-05 1.78650337458318e-06 3.67053577078134e-06 1.27145349685439e-05 8.10163187214131e-07 -2.3633995482166e-05 6.26602987719821e-05 1.85840377697505e-05 1.92999296359872e-05 6.01191629622767e-05 -4.62887855295755e-06 1.78650337458318e-06 1.85840377697505e-05 0.00011928984477222 1536 1544 0 94 0 1525 1536 0 87 0 0 0 0 0 0 0 0 0 352 0 237 227 0 0 2103 +338 388 0.98282674652233 0.0824912043482028 0.165066009600752 -0.0219522919030062 -0.1005437056592 0.989464275614467 0.104170103844882 -0.00767486563341636 -0.154733802294937 -0.118977512530395 0.980765926171699 0.0259612952499591 5.55259069678269e-05 4.84540350165494e-05 -5.22370526387845e-06 -1.68803839382805e-07 -4.45289606903444e-07 2.97037173025761e-05 4.84540350165494e-05 0.000114144774638553 -6.86647673963713e-06 1.3633608038878e-05 4.55060511182754e-06 0.00010136007552235 -5.22370526387845e-06 -6.86647673963713e-06 1.34742110659444e-05 -3.00548681108618e-07 4.93494490652128e-06 -3.65279170389957e-06 -1.68803839382805e-07 1.3633608038878e-05 -3.00548681108618e-07 6.81503893814219e-05 -2.32802470482946e-05 1.7127469278266e-05 -4.45289606903444e-07 4.55060511182754e-06 4.93494490652128e-06 -2.32802470482946e-05 6.2243631625193e-05 1.06330507467876e-05 2.97037173025761e-05 0.00010136007552235 -3.65279170389957e-06 1.7127469278266e-05 1.06330507467876e-05 0.000160212618995964 1374 1385 0 93 0 1365 1376 0 91 0 0 0 0 0 0 0 0 0 364 0 239 226 0 0 1972 +338 378 0.983344209281531 0.0817841409497126 0.162313032014061 -0.0158341478128411 -0.099620592002294 0.989473024395849 0.104970813286571 -0.0157887736237345 -0.152019418896378 -0.119392161727851 0.981139953317751 0.0358476887283067 4.78386364247154e-05 2.20247404531669e-05 -7.98402199942804e-06 6.83601555605032e-06 6.83866082359263e-08 -1.50882757547768e-06 2.20247404531669e-05 5.50434421857873e-05 -8.25762840054381e-06 1.14270155411058e-05 1.62733225222525e-06 3.76001053948404e-05 -7.98402199942804e-06 -8.25762840054381e-06 1.38770961026623e-05 -7.72795221228734e-07 1.70277299431724e-06 -2.67212635277345e-06 6.83601555605032e-06 1.14270155411058e-05 -7.72795221228734e-07 4.79394834610707e-05 -2.11744248621447e-05 1.05390916425443e-05 6.83866082359263e-08 1.62733225222525e-06 1.70277299431724e-06 -2.11744248621447e-05 6.03615237019039e-05 4.11084197826727e-06 -1.50882757547768e-06 3.76001053948404e-05 -2.67212635277345e-06 1.05390916425443e-05 4.11084197826727e-06 8.77234658113909e-05 1558 1564 0 88 0 1530 1536 0 86 0 0 0 0 0 0 0 0 0 382 0 237 225 0 0 2086 +338 413 0.983659211856179 0.0823048197429879 0.160126423733109 -0.0296347534825938 -0.100369268447148 0.989049469729345 0.108199613582883 -0.00785751385160455 -0.149467604790688 -0.122503318629232 0.981148496428018 0.0261359331270255 0.000200116692138044 0.000124930562919338 -3.70979804186222e-05 6.81855153541107e-05 -4.86598854499318e-05 0.000132785244887689 0.000124930562919338 0.000161300394881903 -2.66832847907915e-05 7.90389414564418e-05 -2.58723451353104e-05 0.000152706084834417 -3.70979804186222e-05 -2.66832847907915e-05 1.94559866230979e-05 -8.27880096005577e-06 8.05142628431972e-06 -2.46461324175426e-05 6.81855153541107e-05 7.90389414564418e-05 -8.27880096005577e-06 9.93757422536803e-05 -2.62704225250211e-05 7.71440464587992e-05 -4.86598854499318e-05 -2.58723451353104e-05 8.05142628431972e-06 -2.62704225250211e-05 8.87016201908748e-05 -3.51055324648829e-05 0.000132785244887689 0.000152706084834417 -2.46461324175426e-05 7.71440464587992e-05 -3.51055324648829e-05 0.000231235519221502 1558 1567 0 88 0 1524 1535 0 89 0 0 0 0 0 0 0 0 0 315 0 201 214 0 0 1610 +338 379 0.982397582142624 0.0809126764208387 0.168369027421146 -0.0119268896089688 -0.100027925759053 0.989070125979704 0.108326820145492 -0.0176905508652177 -0.157763762216382 -0.123261610767137 0.979753627521952 0.0287732976125935 7.38868382700053e-05 3.50694390156059e-05 -1.24758748974249e-05 1.51151913149273e-05 -6.35401007075893e-06 2.43856293415223e-05 3.50694390156059e-05 5.74052866659647e-05 -1.084410058427e-05 1.4880453325406e-05 -1.93410211527325e-06 3.38047250218548e-05 -1.24758748974249e-05 -1.084410058427e-05 1.31303824478823e-05 -1.39610725718933e-06 2.35435903725673e-06 -5.79404333229664e-06 1.51151913149273e-05 1.4880453325406e-05 -1.39610725718933e-06 5.07466775578204e-05 -1.07395256309945e-05 -3.79250869115816e-06 -6.35401007075893e-06 -1.93410211527325e-06 2.35435903725673e-06 -1.07395256309945e-05 4.16757253677384e-05 -3.68282090324175e-07 2.43856293415223e-05 3.38047250218548e-05 -5.79404333229664e-06 -3.79250869115816e-06 -3.68282090324175e-07 9.41380362274679e-05 1493 1498 0 84 0 1517 1524 0 83 0 0 0 0 0 0 0 0 0 366 0 237 227 0 0 2082 +338 414 0.983808845818779 0.0826705447865574 0.15901489211208 -0.0247875347177417 -0.0996732708322587 0.989768507277024 0.10209574469198 -0.0164802957064652 -0.148947621566515 -0.116292231156275 0.981983056372346 0.0253414470725751 9.45299856218606e-05 4.14650443713351e-05 -1.8871365751638e-05 1.29009451843824e-05 -5.25381656600547e-06 2.80699425147461e-05 4.14650443713351e-05 7.78278569356632e-05 -1.13256269739665e-05 2.1239602570697e-05 1.15990960700927e-07 5.52487569120287e-05 -1.8871365751638e-05 -1.13256269739665e-05 1.64782940201948e-05 7.20889555422943e-07 1.38106996897385e-06 -3.30625557778728e-06 1.29009451843824e-05 2.1239602570697e-05 7.20889555422943e-07 4.31618967339434e-05 -4.54857799690762e-06 2.07083146304288e-05 -5.25381656600547e-06 1.15990960700927e-07 1.38106996897385e-06 -4.54857799690762e-06 4.89334103182817e-05 -1.16282569568472e-05 2.80699425147461e-05 5.52487569120287e-05 -3.30625557778728e-06 2.07083146304288e-05 -1.16282569568472e-05 0.000123156068701169 1482 1491 0 87 0 1510 1519 0 87 0 0 0 0 0 0 0 0 0 314 0 189 208 0 0 1686 +338 383 0.981527888637275 0.0810253463890871 0.173314445646578 -0.0141984356008101 -0.100655333054672 0.989081604322361 0.107638672970071 -0.0135135337506954 -0.162700669190096 -0.123095382665774 0.97896681200716 0.0332580038042846 7.86990748923232e-05 4.73829818300316e-05 -1.40612444728425e-05 1.38527090085478e-05 -4.82540039907747e-06 3.47823342417055e-05 4.73829818300316e-05 7.09659772349574e-05 -1.35281197143206e-05 1.61980646868819e-05 -1.27527476662709e-06 3.19076694558426e-05 -1.40612444728425e-05 -1.35281197143206e-05 1.51706837140542e-05 -3.08873507684582e-06 1.17243987923808e-06 -9.27113500574526e-06 1.38527090085478e-05 1.61980646868819e-05 -3.08873507684582e-06 6.84991822778448e-05 -2.02465573876576e-05 1.52403904399632e-05 -4.82540039907747e-06 -1.27527476662709e-06 1.17243987923808e-06 -2.02465573876576e-05 6.37750152484146e-05 -2.06650454442258e-05 3.47823342417055e-05 3.19076694558426e-05 -9.27113500574526e-06 1.52403904399632e-05 -2.06650454442258e-05 0.000101621609859384 1402 1408 0 81 0 1424 1431 0 75 0 0 0 0 0 0 0 0 0 349 0 231 222 0 0 2042 +338 385 0.983002033376276 0.0817480253066478 0.164390579829167 -0.0235428719636538 -0.100078399460877 0.989263848249625 0.106495786337733 -0.0122775395504806 -0.153919837381201 -0.121137520631745 0.980629585906798 0.0230015415925055 5.0605192993994e-05 1.2335103830095e-05 -8.28809215055619e-06 1.39977887190719e-06 -9.30679382041529e-07 -3.19251670512615e-06 1.2335103830095e-05 5.16192627690567e-05 -6.38825583298768e-06 1.44424821017804e-05 5.01251799308436e-07 2.53393947229921e-05 -8.28809215055619e-06 -6.38825583298768e-06 1.41953273162064e-05 1.34677883847695e-06 1.08080647833908e-06 -1.76485451997432e-06 1.39977887190719e-06 1.44424821017804e-05 1.34677883847695e-06 5.08639921410575e-05 -1.70347954911976e-05 1.38830395921228e-05 -9.30679382041529e-07 5.01251799308436e-07 1.08080647833908e-06 -1.70347954911976e-05 6.23061342278423e-05 2.68924999429491e-06 -3.19251670512615e-06 2.53393947229921e-05 -1.76485451997432e-06 1.38830395921228e-05 2.68924999429491e-06 8.67442436857363e-05 1421 1427 0 91 0 1412 1422 0 84 0 0 0 0 0 0 0 0 0 359 0 243 232 0 0 2085 +338 415 0.982746094168839 0.0820925315953679 0.165743568961683 -0.0174893548788759 -0.099899187545505 0.98974370333079 0.102115395728559 -0.021117892435085 -0.155660742397178 -0.116911154186911 0.980867735886467 0.0246391960930928 0.000103197359756025 5.44951868153906e-05 -1.74050515271477e-05 1.39216708881684e-05 -1.02598453650578e-05 4.73122036912766e-05 5.44951868153906e-05 0.000100177744222744 -1.22855024298203e-05 2.53919335857396e-05 -4.9164497734378e-06 8.22300036779024e-05 -1.74050515271477e-05 -1.22855024298203e-05 1.65048384654029e-05 1.05466855330501e-06 -2.10617371944141e-07 -8.47863755116142e-06 1.39216708881684e-05 2.53919335857396e-05 1.05466855330501e-06 5.29058596528648e-05 -5.07835519437767e-06 2.19852753643095e-05 -1.02598453650578e-05 -4.9164497734378e-06 -2.10617371944141e-07 -5.07835519437767e-06 5.45567372165772e-05 -2.11162782064445e-05 4.73122036912766e-05 8.22300036779024e-05 -8.47863755116142e-06 2.19852753643095e-05 -2.11162782064445e-05 0.000143206526992569 1591 1603 0 93 0 1588 1600 0 92 0 0 0 0 0 0 0 0 0 302 0 191 204 0 0 1616 +338 387 0.983096995929763 0.0818614588662322 0.163765069981871 -0.0237319035538924 -0.100039877997372 0.989319230282991 0.106016429870757 -0.00963867901443042 -0.153337273368695 -0.120607471346357 0.980786173664419 0.0249992243396717 8.52813584720638e-05 1.84564028857522e-05 -1.65457024149487e-05 2.2762997362801e-07 4.15043071397959e-07 9.40232213095725e-07 1.84564028857522e-05 5.94250606073899e-05 -8.69839373127481e-06 1.79885954701573e-05 -3.70997223054494e-06 4.1349559226716e-05 -1.65457024149487e-05 -8.69839373127481e-06 1.71187348472632e-05 1.11814509727847e-06 -3.6495653507772e-06 -2.01804987947506e-06 2.2762997362801e-07 1.79885954701573e-05 1.11814509727847e-06 6.2593817627944e-05 -1.02855825826424e-05 1.54656558621639e-05 4.15043071397959e-07 -3.70997223054494e-06 -3.6495653507772e-06 -1.02855825826424e-05 5.86819005525851e-05 -7.00282069928532e-06 9.40232213095725e-07 4.1349559226716e-05 -2.01804987947506e-06 1.54656558621639e-05 -7.00282069928532e-06 9.8250573311064e-05 1569 1579 0 94 0 1599 1609 0 88 0 0 0 0 0 0 0 0 0 351 0 237 231 0 0 2075 +338 411 0.983664365866757 0.0822198557640869 0.160138410889094 -0.0211613914098267 -0.100160234382737 0.989160121986197 0.107378678147229 -0.0132833019465094 -0.149573870620328 -0.121664080115635 0.981236724158482 0.0243356079720785 0.000101350567553703 8.30212716623521e-05 -1.39349909343425e-05 2.73770369501736e-05 -1.92900494610772e-05 5.40490274956031e-05 8.30212716623521e-05 0.000116956174142247 -1.3861481088781e-05 3.79523318421442e-05 -3.12044192132888e-05 0.000103355942753057 -1.39349909343425e-05 -1.3861481088781e-05 1.3564342047001e-05 3.23428234844128e-07 3.97836446870265e-06 -5.31821978848543e-06 2.73770369501736e-05 3.79523318421442e-05 3.23428234844128e-07 5.41823090822032e-05 -2.28868453911388e-05 2.99855077610421e-05 -1.92900494610772e-05 -3.12044192132888e-05 3.97836446870265e-06 -2.28868453911388e-05 6.26946243681463e-05 -3.04059978604944e-05 5.40490274956031e-05 0.000103355942753057 -5.31821978848543e-06 2.99855077610421e-05 -3.04059978604944e-05 0.000177725647683063 1608 1619 0 90 0 1593 1604 0 85 0 0 0 0 0 0 0 0 0 255 0 167 179 0 0 1615 +338 419 0.982683765073187 0.0814566893878343 0.166425435602734 -0.020372695780464 -0.100179978559193 0.989157330784468 0.107385971389315 -0.0135681400970927 -0.155873633939372 -0.12219894725128 0.9801891794614 0.0236365018417179 4.86098761366828e-05 1.21421783212721e-05 -5.76452118215181e-06 4.64627607462377e-06 6.11925790405429e-07 1.47157001227251e-06 1.21421783212721e-05 4.27319291625322e-05 -6.7009000576965e-06 4.35310290863366e-06 1.42824763880245e-05 2.30034691998398e-05 -5.76452118215181e-06 -6.7009000576965e-06 1.3956918868019e-05 -1.73503526675908e-06 1.13610797532192e-06 -4.38148091461946e-06 4.64627607462377e-06 4.35310290863366e-06 -1.73503526675908e-06 4.98810805521826e-05 -9.14024734013979e-06 7.09117460797949e-06 6.11925790405429e-07 1.42824763880245e-05 1.13610797532192e-06 -9.14024734013979e-06 5.32097025793033e-05 3.23558075190073e-06 1.47157001227251e-06 2.30034691998398e-05 -4.38148091461946e-06 7.09117460797949e-06 3.23558075190073e-06 8.87431820114481e-05 1412 1421 0 91 0 1403 1415 0 88 0 0 0 0 0 0 0 0 0 314 0 194 209 0 0 1573 +338 418 0.983737790553039 0.0813243812275056 0.160144636050627 -0.022044392098934 -0.0999891413818301 0.988646559139489 0.112161279893616 -0.0178233455387002 -0.149204996711065 -0.126350014323754 0.980700536778092 0.0282260437323996 0.000217267772071083 0.000168649758502496 -3.78646686607226e-05 6.47298763060991e-05 -4.89239016838571e-05 0.00018203632714455 0.000168649758502496 0.000186954533250022 -3.47657542469693e-05 6.34368655316616e-05 -3.23886760536489e-05 0.000186950639436046 -3.78646686607226e-05 -3.47657542469693e-05 2.00571100746361e-05 -8.26031285578173e-06 6.53927049814376e-06 -3.23602744066283e-05 6.47298763060991e-05 6.34368655316616e-05 -8.26031285578173e-06 7.94835008949689e-05 -2.96385656260781e-05 6.78051396394493e-05 -4.89239016838571e-05 -3.23886760536489e-05 6.53927049814376e-06 -2.96385656260781e-05 9.78303207327056e-05 -5.03920328883395e-05 0.00018203632714455 0.000186950639436046 -3.23602744066283e-05 6.78051396394493e-05 -5.03920328883395e-05 0.000279509454918634 1706 1717 0 93 0 1682 1693 0 92 0 0 0 0 0 0 0 0 0 335 0 174 186 0 0 1593 +338 386 0.983138840576501 0.0806756063053131 0.164102000893237 -0.0192045994712968 -0.0996638634334745 0.988813921636589 0.110969106976594 -0.00990704516401236 -0.153313843065157 -0.125453078578962 0.980181815072925 0.0335697124281913 8.25411946751763e-05 5.59155974781138e-05 -1.29390197018636e-05 2.2582523407077e-05 -1.40295993152485e-05 2.91654497048267e-05 5.59155974781138e-05 9.01771976790306e-05 -1.32924997646274e-05 3.33910536602336e-05 -1.83474183150085e-05 5.2167976562714e-05 -1.29390197018636e-05 -1.32924997646274e-05 1.39034008206537e-05 -2.96200403954138e-06 4.02435989323008e-06 -5.53601883428748e-06 2.2582523407077e-05 3.33910536602336e-05 -2.96200403954138e-06 6.56942493647323e-05 -2.19364159812466e-05 2.066747933528e-05 -1.40295993152485e-05 -1.83474183150085e-05 4.02435989323008e-06 -2.19364159812466e-05 5.3083635456611e-05 -1.08559831702773e-05 2.91654497048267e-05 5.2167976562714e-05 -5.53601883428748e-06 2.066747933528e-05 -1.08559831702773e-05 0.000113570443020464 1505 1513 0 89 0 1480 1489 0 90 0 0 0 0 0 0 0 0 0 345 0 240 228 0 0 2065 +338 396 0.982348241601058 0.0841717783610026 0.167054015069545 -0.016535708680786 -0.101666134352003 0.989871958523353 0.0990833126972558 -0.0198274078595224 -0.157022066440453 -0.114318053940259 0.980956397193108 0.0389418739870159 9.0898006266918e-05 6.13623452917155e-05 -1.28007302797648e-05 1.39858548983821e-05 -4.13958074167179e-06 4.52908294653659e-05 6.13623452917155e-05 0.000154574127704427 -1.09971698803471e-05 3.65511045602325e-05 -1.26388099710924e-05 0.000130925946165551 -1.28007302797648e-05 -1.09971698803471e-05 1.59783681576283e-05 2.61458712465535e-06 3.06273637740944e-06 -8.24704941308435e-06 1.39858548983821e-05 3.65511045602325e-05 2.61458712465535e-06 6.40537173212886e-05 -3.79527187926088e-06 4.07032368933812e-05 -4.13958074167179e-06 -1.26388099710924e-05 3.06273637740944e-06 -3.79527187926088e-06 5.17824101090789e-05 -9.71766334283923e-06 4.52908294653659e-05 0.000130925946165551 -8.24704941308435e-06 4.07032368933812e-05 -9.71766334283923e-06 0.000195437225459339 1683 1691 0 82 0 1655 1663 0 76 0 0 0 0 0 0 0 0 0 174 0 240 235 0 0 1805 +338 395 0.98214102884161 0.0847491674124286 0.167977909526352 -0.0108256313662391 -0.102083863310094 0.98999703114954 0.0973897487766725 -0.0129961603503714 -0.158043931606466 -0.11279830201735 0.980968225145123 0.0403074668570099 6.6882841559187e-05 5.04961342948514e-05 -6.97075163494952e-06 9.75882033577332e-06 -1.33339711431773e-05 3.99572135828172e-05 5.04961342948514e-05 0.000104922966184959 -9.33126780684871e-06 2.82995911534228e-05 -1.32940256641878e-05 8.19159462170668e-05 -6.97075163494952e-06 -9.33126780684871e-06 1.45547107571565e-05 3.07396235486588e-06 5.29607242505981e-06 -5.85853229446871e-06 9.75882033577332e-06 2.82995911534228e-05 3.07396235486588e-06 6.26906971754449e-05 -1.99580250055715e-05 3.33616919526666e-05 -1.33339711431773e-05 -1.32940256641878e-05 5.29607242505981e-06 -1.99580250055715e-05 6.66423290055029e-05 -2.04200673050519e-05 3.99572135828172e-05 8.19159462170668e-05 -5.85853229446871e-06 3.33616919526666e-05 -2.04200673050519e-05 0.000154650709320232 1376 1382 0 91 0 1392 1399 0 89 0 0 0 0 0 0 0 0 0 164 0 232 229 0 0 1779 +338 393 0.981409388419362 0.0851159940593268 0.172019998481649 -0.0175349970319464 -0.102333678348212 0.990315580024315 0.0938236123629333 -0.00355879387901129 -0.162368194539627 -0.109682813222483 0.980615240492184 0.0479871966839673 0.00014961146013389 0.000107295085453905 -2.13789608306093e-05 7.45411246285038e-06 -7.25401756085881e-06 0.000105970355937699 0.000107295085453905 0.000234781125510497 -1.407299647256e-05 6.82014169727593e-05 -5.61453864218256e-06 0.000181898505912675 -2.13789608306093e-05 -1.407299647256e-05 1.69256288849665e-05 2.38301056684546e-06 6.76977373356525e-06 -1.54206389881833e-05 7.45411246285038e-06 6.82014169727593e-05 2.38301056684546e-06 9.59086678147027e-05 -1.82300589313271e-05 3.74326031616448e-05 -7.25401756085881e-06 -5.61453864218256e-06 6.76977373356525e-06 -1.82300589313271e-05 5.96800383778845e-05 -2.17101553513509e-06 0.000105970355937699 0.000181898505912675 -1.54206389881833e-05 3.74326031616448e-05 -2.17101553513509e-06 0.00027385046757187 1244 1249 0 78 0 1223 1232 0 79 0 0 0 0 0 0 0 0 0 147 0 220 209 0 0 1714 +338 426 0.983437696205089 0.0817439293368902 0.161765965825301 -0.021897470826107 -0.0998068019767503 0.989250518634498 0.10687382121245 -0.0135281667432471 -0.151290779500935 -0.12124908823551 0.981024851183729 0.0285542312220448 4.5211333024566e-05 1.51628022334561e-05 -6.44430246521987e-06 3.77059830663524e-06 2.86412071316715e-06 -7.23179988599918e-06 1.51628022334561e-05 7.50176993524512e-05 -6.08332192880956e-06 1.87404533348298e-05 1.32669430810242e-05 3.1706423957614e-05 -6.44430246521987e-06 -6.08332192880956e-06 1.26438902887887e-05 1.74714975819451e-06 5.25633849028909e-08 6.19240890865993e-08 3.77059830663524e-06 1.87404533348298e-05 1.74714975819451e-06 5.38051817852668e-05 -3.30442929936123e-06 -7.50259513595453e-06 2.86412071316715e-06 1.32669430810242e-05 5.25633849028909e-08 -3.30442929936123e-06 5.93008508264112e-05 2.23627191282659e-05 -7.23179988599918e-06 3.1706423957614e-05 6.19240890865993e-08 -7.50259513595453e-06 2.23627191282659e-05 8.03653600641995e-05 1595 1603 0 91 0 1579 1588 0 89 0 0 0 0 0 0 0 0 0 364 0 181 194 0 0 1608 +338 389 0.983027677822339 0.0828034488301727 0.163707585337545 -0.0232708209629028 -0.10047739636343 0.989614666525387 0.102796423176457 -0.0113661483958342 -0.153495529105074 -0.117500641103255 0.981138482521748 0.0315757632981963 5.2595235000739e-05 2.13315161910331e-05 -4.77783502295911e-06 -1.45909873025648e-07 -6.03164001482628e-06 -1.57977047020495e-06 2.13315161910331e-05 7.86252443911394e-05 -3.68305573780048e-07 1.45654767010203e-05 2.66217996044014e-06 3.99715603226663e-05 -4.77783502295911e-06 -3.68305573780048e-07 1.3874412455229e-05 5.77366758437174e-06 4.4149149063609e-06 3.92462948344102e-06 -1.45909873025648e-07 1.45654767010203e-05 5.77366758437174e-06 6.37301331350425e-05 -3.05999955282686e-05 6.92188903247632e-06 -6.03164001482628e-06 2.66217996044014e-06 4.4149149063609e-06 -3.05999955282686e-05 7.70361136446958e-05 2.83830909390836e-06 -1.57977047020495e-06 3.99715603226663e-05 3.92462948344102e-06 6.92188903247632e-06 2.83830909390836e-06 9.83171917340706e-05 1340 1342 0 83 0 1319 1323 0 74 0 0 0 0 0 0 0 0 0 227 0 220 207 0 0 1941 +338 394 0.981309204788328 0.0833515461633586 0.173449601757621 -0.0133439575482287 -0.101695112298507 0.989807378995073 0.0996968235276267 -0.0181303572517977 -0.163371811314847 -0.11547238734469 0.979783536822611 0.0410989213852998 0.000128046479783377 8.45038192446661e-05 -1.7836738910745e-05 1.99223188096261e-05 -2.1389954828954e-05 8.13251451399581e-05 8.45038192446661e-05 0.000112140414720696 -1.59261769386093e-05 2.66604166705201e-05 -9.91020591573831e-06 8.98084368162989e-05 -1.7836738910745e-05 -1.59261769386093e-05 1.48569729222694e-05 2.04976993779415e-06 7.66551365599861e-06 -1.57457752930138e-05 1.99223188096261e-05 2.66604166705201e-05 2.04976993779415e-06 5.78787491874312e-05 -1.18952015784451e-06 3.42802033154951e-05 -2.1389954828954e-05 -9.91020591573831e-06 7.66551365599861e-06 -1.18952015784451e-06 4.62759515078252e-05 -1.53430176927736e-05 8.13251451399581e-05 8.98084368162989e-05 -1.57457752930138e-05 3.42802033154951e-05 -1.53430176927736e-05 0.000161666678130907 1601 1611 0 95 0 1571 1582 0 95 0 0 0 0 0 0 0 0 0 165 0 238 231 0 0 1790 +338 420 0.982802286644089 0.0818703106219498 0.16552014259846 -0.0213760550780841 -0.100308292183854 0.989263492454791 0.106282590367886 -0.0107265620627698 -0.155041645651443 -0.121057815670095 0.980462693517136 0.0330273681953232 9.11914597502066e-05 6.53882477599037e-05 -1.72801610849038e-05 1.21609777101185e-05 1.30835874546704e-05 4.39687239808337e-05 6.53882477599037e-05 9.29362323820541e-05 -1.81881138286667e-05 1.77998453784144e-05 1.33757382967252e-05 6.64247892891576e-05 -1.72801610849038e-05 -1.81881138286667e-05 1.65924169113285e-05 -1.94792968634177e-06 -2.89803439811708e-06 -1.18552579775518e-05 1.21609777101185e-05 1.77998453784144e-05 -1.94792968634177e-06 5.85418215171967e-05 -1.05176240730388e-05 6.12409630934516e-06 1.30835874546704e-05 1.33757382967252e-05 -2.89803439811708e-06 -1.05176240730388e-05 6.21144346601195e-05 1.16267382093386e-05 4.39687239808337e-05 6.64247892891576e-05 -1.18552579775518e-05 6.12409630934516e-06 1.16267382093386e-05 0.000122709217772303 1508 1518 0 94 0 1492 1504 0 90 0 0 0 0 0 0 0 0 0 332 0 177 189 0 0 1569 +338 376 0.981906033054143 0.080770617556658 0.171279448829662 -0.0106501790583564 -0.100576157813449 0.988797433159928 0.110290854814997 -0.0179571509714608 -0.160452418901558 -0.125521884609237 0.979029763466251 0.0356952554733241 5.4580326482663e-05 1.93472624078839e-05 -6.82129724168697e-06 1.09130070386806e-05 -3.89245727197373e-06 6.5872838656247e-06 1.93472624078839e-05 7.03200132243382e-05 -7.30766837754788e-06 1.95956855080834e-05 -5.20994229938006e-07 5.12861185591062e-05 -6.82129724168697e-06 -7.30766837754788e-06 1.24087660622777e-05 -7.42914841644991e-07 3.31559756743904e-06 -4.33476446574182e-06 1.09130070386806e-05 1.95956855080834e-05 -7.42914841644991e-07 3.86638926747517e-05 -5.66227846211082e-06 2.17620411585676e-05 -3.89245727197373e-06 -5.20994229938006e-07 3.31559756743904e-06 -5.66227846211082e-06 4.20705950271875e-05 -1.88837834335583e-06 6.5872838656247e-06 5.12861185591062e-05 -4.33476446574182e-06 2.17620411585676e-05 -1.88837834335583e-06 0.000106826572574458 1420 1424 0 78 0 1444 1449 0 79 0 0 0 0 0 0 0 0 0 349 0 236 229 0 0 2023 +338 392 0.980928936311682 0.08367574402765 0.175433154699595 -0.0117555767594779 -0.102398213025275 0.98965101878283 0.100525951830047 -0.00564135322862182 -0.165206016463273 -0.116572856546992 0.979345567836405 0.0393545984705809 0.000117228609703009 6.36705975040166e-05 -2.12559737061154e-05 1.75170104317697e-05 -4.11322912924665e-06 5.95940318580843e-05 6.36705975040166e-05 9.1710420201504e-05 -1.64271070303872e-05 1.20934844942279e-05 7.25056073108911e-06 7.91074479356102e-05 -2.12559737061154e-05 -1.64271070303872e-05 1.70784500950725e-05 -2.16247045723195e-06 3.63576925116126e-06 -1.7389119367359e-05 1.75170104317697e-05 1.20934844942279e-05 -2.16247045723195e-06 3.6064869595823e-05 -2.82860701921682e-07 1.34031974312712e-05 -4.11322912924665e-06 7.25056073108911e-06 3.63576925116126e-06 -2.82860701921682e-07 4.85432044388246e-05 1.23115552806056e-05 5.95940318580843e-05 7.91074479356102e-05 -1.7389119367359e-05 1.34031974312712e-05 1.23115552806056e-05 0.000157727122375131 1535 1541 0 90 0 1536 1545 0 83 0 0 0 0 0 0 0 0 0 154 0 223 211 0 0 1695 +338 377 0.983160360952518 0.0809109602168218 0.163857014401298 -0.0158460441046188 -0.0993624223159733 0.989202689982158 0.107727188599559 -0.0151284914307791 -0.15337148914716 -0.122194331492319 0.980584382737114 0.0352029291345358 9.41450119040025e-05 4.48987880632218e-05 -1.49794021536299e-05 9.97400991976384e-06 -3.41867494060063e-06 1.08537443875085e-05 4.48987880632218e-05 8.29668955149756e-05 -1.20529828495543e-05 2.41284923371586e-05 -1.68510161335052e-06 5.67521968785939e-05 -1.49794021536299e-05 -1.20529828495543e-05 1.44675397750367e-05 1.2505880552032e-06 4.98773463062795e-07 -2.34478225210354e-06 9.97400991976384e-06 2.41284923371586e-05 1.2505880552032e-06 5.82823567396713e-05 -1.85420077782399e-05 2.64332109427655e-05 -3.41867494060063e-06 -1.68510161335052e-06 4.98773463062795e-07 -1.85420077782399e-05 5.89973479754995e-05 -4.66240952728135e-06 1.08537443875085e-05 5.67521968785939e-05 -2.34478225210354e-06 2.64332109427655e-05 -4.66240952728135e-06 0.000110427548532404 1468 1479 0 92 0 1452 1463 0 92 0 0 0 0 0 0 0 0 0 353 0 220 206 0 0 2080 +338 410 0.984195929962086 0.0839801172051118 0.155902890801551 -0.0273939000360182 -0.100785526473944 0.989540100660886 0.103211757263469 -0.00488605721997211 -0.145604426785158 -0.117293346351185 0.982365319930578 0.0276220408522996 6.71271683729627e-05 3.60292927806236e-05 -8.35944160783729e-06 6.64807564389119e-06 -3.54497822528216e-06 1.53845009872771e-05 3.60292927806236e-05 9.13326047272985e-05 -5.62325499482892e-06 3.84827296999445e-05 -2.31235552831039e-05 4.7383711692877e-05 -8.35944160783729e-06 -5.62325499482892e-06 1.30269703314392e-05 5.22349239699348e-06 7.40164860601032e-07 -1.5721498572029e-06 6.64807564389119e-06 3.84827296999445e-05 5.22349239699348e-06 6.37282416493429e-05 -2.81270529378167e-05 2.52815063526656e-05 -3.54497822528216e-06 -2.31235552831039e-05 7.40164860601032e-07 -2.81270529378167e-05 6.82029854304121e-05 -1.74518566194856e-05 1.53845009872771e-05 4.7383711692877e-05 -1.5721498572029e-06 2.52815063526656e-05 -1.74518566194856e-05 0.000105048085259494 1395 1402 0 82 0 1364 1372 0 79 0 0 0 0 0 0 0 0 0 231 0 196 209 0 0 1558 +338 391 0.979923035790004 0.0838163399767144 0.180902363392551 0.000759587308416399 -0.102611456860681 0.989965284175652 0.0971577328263131 -0.0169936114089972 -0.170943654018017 -0.113769755558885 0.97869030334986 0.0474778421299539 0.000113008937786573 7.03041716789785e-05 -1.49392417624008e-05 1.10976960832659e-05 -6.75647232458031e-06 7.77108665188817e-05 7.03041716789785e-05 0.000123260103970339 -1.32564067536192e-05 2.77197261993671e-05 6.3993627845265e-06 0.000126947613782511 -1.49392417624008e-05 -1.32564067536192e-05 1.53944605099778e-05 2.05954536810056e-06 3.78317692702116e-06 -1.54740455351439e-05 1.10976960832659e-05 2.77197261993671e-05 2.05954536810056e-06 4.45732767534886e-05 -2.4350749988116e-06 3.68392865379288e-05 -6.75647232458031e-06 6.3993627845265e-06 3.78317692702116e-06 -2.4350749988116e-06 4.86606667158263e-05 1.12056089517037e-05 7.77108665188817e-05 0.000126947613782511 -1.54740455351439e-05 3.68392865379288e-05 1.12056089517037e-05 0.000219715484260545 1702 1701 0 74 0 1700 1702 0 74 0 0 0 0 0 0 0 0 0 118 0 229 223 0 0 1787 +339 381 0.985094649516369 0.0619201862126313 0.160481843314486 -0.0175050251748379 -0.0817133423515222 0.989426421408869 0.11982606686269 -0.0230022467906768 -0.151365323558485 -0.131153525142986 0.979738379194468 0.0111419245147934 4.67927325919254e-05 1.03383675276277e-05 -5.03790777637511e-06 9.97011752141953e-07 -2.47016500682666e-06 -1.5735225503765e-05 1.03383675276277e-05 5.8968623714982e-05 -3.22104064006657e-06 9.84612608282565e-06 1.02422663308633e-05 3.24495112628254e-05 -5.03790777637511e-06 -3.22104064006657e-06 1.30934034451838e-05 9.56215458962246e-07 2.18363320321198e-06 2.89946334289053e-06 9.97011752141953e-07 9.84612608282565e-06 9.56215458962246e-07 3.9235251756321e-05 3.08184088182402e-07 2.54353636641519e-06 -2.47016500682666e-06 1.02422663308633e-05 2.18363320321198e-06 3.08184088182402e-07 4.81312050009442e-05 6.55920304324828e-06 -1.5735225503765e-05 3.24495112628254e-05 2.89946334289053e-06 2.54353636641519e-06 6.55920304324828e-06 8.9041336685131e-05 1328 1335 0 69 0 1338 1352 0 73 0 0 0 0 0 0 0 0 0 369 0 190 175 0 0 2099 +339 384 0.984807539102062 0.0620177917061195 0.162197116002836 -0.0184618889537923 -0.082091225348996 0.989357104563654 0.120139711877976 -0.0172789413975244 -0.153020069430259 -0.131629454003726 0.979417451953068 0.0140023982814481 4.98233402857091e-05 1.80045540595568e-05 -6.24485414645152e-06 8.32318808365581e-06 -5.10937175677381e-06 2.99161071693404e-06 1.80045540595568e-05 5.29968630236361e-05 -7.01035741672523e-06 1.25971711991694e-05 -4.4934477779278e-06 1.84878338073915e-05 -6.24485414645152e-06 -7.01035741672523e-06 1.26126885097243e-05 4.62887869665044e-07 3.60251999393156e-06 -2.63875679885171e-06 8.32318808365581e-06 1.25971711991694e-05 4.62887869665044e-07 4.60534100480461e-05 -3.66765987548614e-06 1.02610650320162e-05 -5.10937175677381e-06 -4.4934477779278e-06 3.60251999393156e-06 -3.66765987548614e-06 4.32074885188386e-05 -2.94040391797281e-06 2.99161071693404e-06 1.84878338073915e-05 -2.63875679885171e-06 1.02610650320162e-05 -2.94040391797281e-06 6.86212413134868e-05 1343 1354 0 62 0 1349 1360 0 70 0 0 0 0 0 0 0 0 0 390 0 235 224 0 0 2132 +339 383 0.984891385319744 0.0619989238320668 0.161694441978135 -0.0228238655607407 -0.0822079347524765 0.989187786107866 0.121447022519085 -0.0201257996025461 -0.152416582387506 -0.132904692387756 0.979339332486257 0.0130603651424443 7.82085668138304e-05 4.0162086854158e-05 -1.02045535089133e-05 5.93460992165807e-06 -1.04465600152182e-05 1.82227846596899e-05 4.0162086854158e-05 7.45175047237119e-05 -1.02014474939928e-05 1.59157144280726e-05 -6.11885832337182e-06 5.10555184254669e-05 -1.02045535089133e-05 -1.02014474939928e-05 1.35241660510741e-05 4.05904306267275e-07 2.26787274117094e-06 -4.99196404129211e-06 5.93460992165807e-06 1.59157144280726e-05 4.05904306267275e-07 5.4643523093346e-05 -9.48541364376955e-06 6.0474536605581e-06 -1.04465600152182e-05 -6.11885832337182e-06 2.26787274117094e-06 -9.48541364376955e-06 4.53430212362643e-05 -2.57370827826392e-06 1.82227846596899e-05 5.10555184254669e-05 -4.99196404129211e-06 6.0474536605581e-06 -2.57370827826392e-06 0.000120387107513657 1484 1491 0 69 0 1486 1493 0 73 0 0 0 0 0 0 0 0 0 362 0 238 227 0 0 2089 +339 341 0.998420529431366 0.0553525038448963 0.00962012100190242 0.0157036720689244 -0.0554321889014906 0.99842858674237 0.00822372234598449 -0.00283545310574909 -0.00914980019344456 -0.00874399758320704 0.999919908624028 0.00750527923203361 4.72835856864202e-05 1.18977380408679e-05 -1.22927939594677e-05 4.25987172391712e-07 2.60434793713321e-06 1.42497519311304e-05 1.18977380408679e-05 4.68716568091573e-05 -8.45717074057551e-06 1.78181730590149e-05 2.56069250397828e-06 1.95662466376315e-05 -1.22927939594677e-05 -8.45717074057551e-06 1.58641353781175e-05 2.52363872144396e-06 -3.01448315594479e-06 -6.18175596072177e-06 4.25987172391712e-07 1.78181730590149e-05 2.52363872144396e-06 4.78640700481629e-05 -1.15074068898605e-05 1.15756018719751e-05 2.60434793713321e-06 2.56069250397828e-06 -3.01448315594479e-06 -1.15074068898605e-05 4.00619209597219e-05 1.62560914355563e-06 1.42497519311304e-05 1.95662466376315e-05 -6.18175596072177e-06 1.15756018719751e-05 1.62560914355563e-06 4.77992169023822e-05 1809 1808 0 58 0 1808 1813 0 57 0 0 0 0 0 0 0 0 0 337 0 160 146 0 0 3148 +339 342 0.998426678151668 0.0550513910639443 0.0106542337570638 0.0254336624307878 -0.0550176340218631 0.998479470191183 -0.00343621206710497 -0.00667896475644816 -0.0108272019313309 0.00284463506595478 0.999937337911571 0.00636418784516057 6.89426326650702e-05 1.32016889916496e-05 -1.31160352223525e-05 7.51984684678962e-06 3.47537304343989e-08 2.46785294037586e-05 1.32016889916496e-05 3.17489621741173e-05 -6.88689003868247e-06 7.03850809340278e-06 6.36638432452673e-06 1.12410632347903e-05 -1.31160352223525e-05 -6.88689003868247e-06 1.64016503948883e-05 -6.72620042859236e-08 -6.34809558581285e-07 -8.16952953714243e-06 7.51984684678962e-06 7.03850809340278e-06 -6.72620042859236e-08 3.60393959068444e-05 1.51332351036141e-06 1.46506914393177e-05 3.47537304343989e-08 6.36638432452673e-06 -6.34809558581285e-07 1.51332351036141e-06 4.93199048581159e-05 4.17043003062885e-06 2.46785294037586e-05 1.12410632347903e-05 -8.16952953714243e-06 1.46506914393177e-05 4.17043003062885e-06 5.85233246179046e-05 1614 1607 0 50 1 1660 1663 0 57 1 0 0 0 0 0 0 0 0 274 0 146 113 0 0 3162 +339 380 0.985386929751055 0.0622733838727754 0.158539030957122 -0.0221250780322937 -0.0815128150184065 0.989674676490587 0.117896970703355 -0.0239841619741491 -0.149560220859574 -0.129097096691934 0.98028856973962 0.0145795918555593 5.70173428458067e-05 1.51565863235108e-05 -9.07238517388095e-06 7.39986865689253e-06 -9.6693102237347e-06 -5.47731592772663e-06 1.51565863235108e-05 5.31276442112462e-05 -6.40245313460684e-06 1.28823924585662e-05 -1.12511698369427e-06 3.09195413845318e-05 -9.07238517388095e-06 -6.40245313460684e-06 1.37775080976399e-05 -7.16658160174331e-07 2.92990256003457e-06 1.82915236676743e-06 7.39986865689253e-06 1.28823924585662e-05 -7.16658160174331e-07 4.99339682341768e-05 -1.84349681815344e-05 9.93540874103451e-06 -9.6693102237347e-06 -1.12511698369427e-06 2.92990256003457e-06 -1.84349681815344e-05 6.62730599772635e-05 5.87479844294011e-06 -5.47731592772663e-06 3.09195413845318e-05 1.82915236676743e-06 9.93540874103451e-06 5.87479844294011e-06 9.40621699701724e-05 1363 1374 0 70 0 1364 1375 0 75 0 0 0 0 0 0 0 0 0 368 0 241 228 0 0 2076 +339 382 0.984889882265854 0.0616773801042933 0.161826513877742 -0.0220513662702277 -0.0818887109846561 0.98922550499255 0.121355425447341 -0.0197469036904318 -0.152598030208859 -0.132773495305743 0.979328872300144 0.0115337499713752 5.89259960449339e-05 1.08015959396467e-05 -6.24538730476576e-06 5.94290777039641e-09 -7.68386060011717e-06 -1.34605278887028e-05 1.08015959396467e-05 5.08420953747971e-05 -3.60205866544771e-06 1.44418715944781e-05 4.7078625020993e-06 2.73424232565453e-05 -6.24538730476576e-06 -3.60205866544771e-06 1.16562647335895e-05 1.44172644465535e-06 2.19081512068599e-06 2.30823999350618e-06 5.94290777039641e-09 1.44418715944781e-05 1.44172644465535e-06 5.60165984109552e-05 -9.46320269964671e-06 2.36927770802244e-06 -7.68386060011717e-06 4.7078625020993e-06 2.19081512068599e-06 -9.46320269964671e-06 5.08730839876455e-05 3.56586571508802e-06 -1.34605278887028e-05 2.73424232565453e-05 2.30823999350618e-06 2.36927770802244e-06 3.56586571508802e-06 9.09864276945844e-05 1340 1348 0 65 0 1349 1364 0 72 0 0 0 0 0 0 0 0 0 386 0 193 178 0 0 2124 +339 385 0.985072717444115 0.0620127517895348 0.160580696108706 -0.0228400376110288 -0.0819198183329501 0.989330612224789 0.120474408399542 -0.017773284823585 -0.151396448807637 -0.131830794317613 0.979642667995848 0.0111945938013647 5.78429708026108e-05 2.54811065102975e-05 -7.64383254023629e-06 8.68833855871992e-06 -1.18156097303689e-05 4.59203798378252e-06 2.54811065102975e-05 6.3156873466862e-05 -7.72117513961174e-06 2.11159598016951e-05 -5.34493377955613e-06 4.05678752933678e-05 -7.64383254023629e-06 -7.72117513961174e-06 1.27637869206359e-05 -7.08744097297644e-07 1.98052396076694e-06 -2.38721661384019e-06 8.68833855871992e-06 2.11159598016951e-05 -7.08744097297644e-07 5.603744649163e-05 -1.78848383915492e-05 1.77440682529555e-05 -1.18156097303689e-05 -5.34493377955613e-06 1.98052396076694e-06 -1.78848383915492e-05 7.00700787981357e-05 -9.36137011717519e-06 4.59203798378252e-06 4.05678752933678e-05 -2.38721661384019e-06 1.77440682529555e-05 -9.36137011717519e-06 9.42002551937175e-05 1437 1441 0 69 0 1445 1455 0 71 0 0 0 0 0 0 0 0 0 366 0 195 179 0 0 2091 +339 379 0.984896215880349 0.0620841059975486 0.161632322655629 -0.0119903328307806 -0.0819041400173903 0.989510365666343 0.118999781877414 -0.0270299865876066 -0.152548863622709 -0.130440791247775 0.97964996002964 0.0133434185859677 5.97372289304939e-05 2.80337609768255e-05 -9.52198517146537e-06 9.91763880662765e-06 7.23239650338157e-07 8.9398258703294e-06 2.80337609768255e-05 6.86865994639054e-05 -1.35493859683004e-05 1.76018571974454e-05 4.43670888783454e-06 4.24791171037378e-05 -9.52198517146537e-06 -1.35493859683004e-05 1.5252192075007e-05 -1.62685238496299e-06 -1.90107779810759e-07 -5.84654521851053e-06 9.91763880662765e-06 1.76018571974454e-05 -1.62685238496299e-06 4.41638459683869e-05 -2.88552040050687e-06 1.18222632684217e-05 7.23239650338157e-07 4.43670888783454e-06 -1.90107779810759e-07 -2.88552040050687e-06 4.37664027785479e-05 1.32335806168658e-06 8.9398258703294e-06 4.24791171037378e-05 -5.84654521851053e-06 1.18222632684217e-05 1.32335806168658e-06 0.000100088367092421 1546 1555 0 71 0 1553 1562 0 74 0 0 0 0 0 0 0 0 0 371 0 235 216 0 0 2113 +339 417 0.984290178364315 0.0642552819823949 0.164450915208485 -0.0202274673741661 -0.0835331940001656 0.990062655995584 0.113128876521867 -0.0205466075751498 -0.155547582030953 -0.125088752253478 0.979876397197112 0.0167672227346509 0.000157110682333773 8.23184140855514e-05 -2.93062038330212e-05 2.62851298437237e-05 -4.7489656964422e-06 5.08953147934842e-05 8.23184140855514e-05 0.000117192759088428 -2.0783123434627e-05 2.91481493055299e-05 -4.15975152465016e-06 8.97294828403861e-05 -2.93062038330212e-05 -2.0783123434627e-05 1.84683950336037e-05 -3.33746621085629e-06 3.59949787767503e-06 -1.17587520510851e-05 2.62851298437237e-05 2.91481493055299e-05 -3.33746621085629e-06 4.97195962079048e-05 7.98603561926634e-07 2.24429611306191e-05 -4.7489656964422e-06 -4.15975152465016e-06 3.59949787767503e-06 7.98603561926634e-07 4.71161062903772e-05 -1.98625291938389e-06 5.08953147934842e-05 8.97294828403861e-05 -1.17587520510851e-05 2.24429611306191e-05 -1.98625291938389e-06 0.000167274195996493 1579 1588 0 65 3 1600 1609 0 72 3 0 0 0 0 0 0 0 0 323 0 178 189 0 0 1612 +339 413 0.985257129267157 0.0642387467850787 0.158561573654285 -0.0186536623044798 -0.0829620089898947 0.989960503601528 0.11443559923979 -0.0269702345855142 -0.149618495823883 -0.125903076691921 0.980695019354594 0.0153857995041885 6.63878529845099e-05 3.04622801393979e-05 -7.60957652786848e-06 7.00716565996616e-06 -3.44538572599553e-06 8.329677540127e-06 3.04622801393979e-05 8.68726717865821e-05 -7.83509213133821e-06 3.54661750870827e-05 -4.43575932042841e-06 6.07198773055524e-05 -7.60957652786848e-06 -7.83509213133821e-06 1.35174000183245e-05 3.62422960522329e-06 3.31958189990766e-06 -1.76135653578093e-06 7.00716565996616e-06 3.54661750870827e-05 3.62422960522329e-06 6.35512254043179e-05 5.87342939341324e-06 2.07367451517093e-05 -3.44538572599553e-06 -4.43575932042841e-06 3.31958189990766e-06 5.87342939341324e-06 4.85993709228937e-05 -1.17203387565478e-05 8.329677540127e-06 6.07198773055524e-05 -1.76135653578093e-06 2.07367451517093e-05 -1.17203387565478e-05 0.000128620342990315 1340 1349 0 70 1 1343 1352 0 75 1 0 0 0 0 0 0 0 0 325 0 156 169 0 0 1619 +339 387 0.985744014696377 0.0628577450676722 0.156069347968387 -0.0242371886641738 -0.0818834225672904 0.98955624006534 0.118632006037212 -0.0152412918919753 -0.146982456772692 -0.129720282272103 0.980596148150863 0.00820392956306105 6.00018713201534e-05 5.18154918597793e-06 -9.42911833985842e-06 -7.63647911418694e-06 7.35772738549634e-06 -7.13290489424362e-06 5.18154918597793e-06 6.0095117292406e-05 -7.24013799018103e-06 1.21299268996701e-05 1.05454901852842e-05 4.26584578306971e-05 -9.42911833985842e-06 -7.24013799018103e-06 1.45585196971231e-05 1.99551329254489e-06 -1.08051231407339e-06 -2.89628616722459e-06 -7.63647911418694e-06 1.21299268996701e-05 1.99551329254489e-06 4.9015087096347e-05 4.67053752826192e-06 1.0295641439653e-06 7.35772738549634e-06 1.05454901852842e-05 -1.08051231407339e-06 4.67053752826192e-06 5.83738742729568e-05 1.13143763370396e-05 -7.13290489424362e-06 4.26584578306971e-05 -2.89628616722459e-06 1.0295641439653e-06 1.13143763370396e-05 9.56681175930704e-05 1372 1382 0 72 0 1370 1380 0 76 0 0 0 0 0 0 0 0 0 364 0 239 229 0 0 2098 +339 394 0.984358719948607 0.0636705557291967 0.16426798469049 -0.0163558155732106 -0.0838674528499662 0.989333908627651 0.119099402147926 -0.0197780801374515 -0.154932762234456 -0.131013272505765 0.979199347229016 0.0246469365512112 0.000113369911416063 1.65620261006825e-05 -1.83965296172733e-05 4.57315102524185e-07 -2.74871700089757e-05 2.24352658334924e-06 1.65620261006825e-05 9.72429278528845e-05 -2.40373559281413e-06 3.30359731345898e-05 1.53292513935292e-06 4.64003790787011e-05 -1.83965296172733e-05 -2.40373559281413e-06 1.61865865379377e-05 5.2621751405433e-06 6.83990893252364e-06 -2.40731531804853e-08 4.57315102524185e-07 3.30359731345898e-05 5.2621751405433e-06 6.67657298006934e-05 -2.36992596398585e-06 2.12089928549872e-05 -2.74871700089757e-05 1.53292513935292e-06 6.83990893252364e-06 -2.36992596398585e-06 7.99137915664811e-05 -8.12805113360343e-06 2.24352658334924e-06 4.64003790787011e-05 -2.40731531804853e-08 2.12089928549872e-05 -8.12805113360343e-06 9.71078711884367e-05 1348 1357 0 68 0 1354 1363 0 72 0 0 0 0 0 0 0 0 0 183 0 203 189 0 0 1785 +339 388 0.985942408651901 0.0641554899440982 0.154277801163098 -0.0220662484595629 -0.0824763219980446 0.989884031570575 0.115443754059106 -0.0204713682804122 -0.145310781194524 -0.126545158546731 0.981259955219319 0.00516244437029892 5.80912313997227e-05 1.83649653965438e-05 -4.15329996176178e-06 -6.43589433120932e-06 -1.09410701330071e-05 -1.15444098273315e-06 1.83649653965438e-05 4.77405964409277e-05 -1.47534492918841e-06 -7.03203178587256e-07 5.9307261810492e-07 2.75864010750008e-05 -4.15329996176178e-06 -1.47534492918841e-06 1.26057117028983e-05 3.89711589529339e-06 6.87280210572029e-06 -4.55614544588301e-07 -6.43589433120932e-06 -7.03203178587256e-07 3.89711589529339e-06 4.60295876585886e-05 -5.17623232461203e-06 2.15235823042124e-06 -1.09410701330071e-05 5.9307261810492e-07 6.87280210572029e-06 -5.17623232461203e-06 4.59177377025439e-05 3.15780597833841e-07 -1.15444098273315e-06 2.75864010750008e-05 -4.55614544588301e-07 2.15235823042124e-06 3.15780597833841e-07 8.32315686026209e-05 1392 1403 0 70 0 1399 1416 0 73 0 0 0 0 0 0 0 0 0 391 0 192 177 0 0 2001 +339 378 0.985379920234001 0.0620683297070478 0.158662961169304 -0.0123601330144317 -0.0813263995940269 0.989687561138147 0.117917547708128 -0.0256816964816855 -0.14970781385321 -0.12909707113565 0.980266043834779 0.0194576343864453 6.72643247980588e-05 3.23700264271583e-05 -1.45217736101845e-05 9.69515045722804e-06 -1.13525865669449e-06 4.86397335097167e-06 3.23700264271583e-05 6.79824336466344e-05 -1.42763751038562e-05 1.30153193699477e-05 7.54541043113267e-06 3.49476971044095e-05 -1.45217736101845e-05 -1.42763751038562e-05 1.56726283786146e-05 -1.36901797780756e-06 1.27683186778445e-06 -3.2125691884805e-06 9.69515045722804e-06 1.30153193699477e-05 -1.36901797780756e-06 4.08781024814627e-05 4.70527233364681e-06 1.183905021746e-05 -1.13525865669449e-06 7.54541043113267e-06 1.27683186778445e-06 4.70527233364681e-06 3.92986925879718e-05 6.45346235146688e-07 4.86397335097167e-06 3.49476971044095e-05 -3.2125691884805e-06 1.183905021746e-05 6.45346235146688e-07 8.92031772193188e-05 1364 1371 0 70 0 1372 1379 0 74 0 0 0 0 0 0 0 0 0 388 0 196 180 0 0 2109 +339 418 0.984394091234644 0.0622339488810922 0.164606223299684 -0.0245348576596132 -0.0829256919834802 0.989062568999462 0.121977720151036 -0.0108894144191105 -0.155214698889573 -0.133724231950866 0.978788142060257 0.0197749787348847 6.0853137398835e-05 1.43440218155754e-05 -1.11166594021197e-05 1.35177247969797e-05 -6.7376908615838e-06 3.46512568528743e-06 1.43440218155754e-05 7.90185415992143e-05 -9.05332738518347e-06 1.51505448600397e-05 1.38215927641151e-05 4.98482419607897e-05 -1.11166594021197e-05 -9.05332738518347e-06 1.48173663000334e-05 -3.3430319461796e-07 2.00668495893733e-06 -3.4808255507735e-06 1.35177247969797e-05 1.51505448600397e-05 -3.3430319461796e-07 6.26478607532863e-05 -9.21428967275372e-06 9.75115611948724e-06 -6.7376908615838e-06 1.38215927641151e-05 2.00668495893733e-06 -9.21428967275372e-06 5.39425533386696e-05 4.86293797498135e-06 3.46512568528743e-06 4.98482419607897e-05 -3.4808255507735e-06 9.75115611948724e-06 4.86293797498135e-06 0.000113949217772828 1385 1394 0 68 2 1358 1367 0 73 2 0 0 0 0 0 0 0 0 330 0 157 168 0 0 1548 +339 412 0.985104218281461 0.0640063045567745 0.159602230877445 -0.020009318875953 -0.0828544721414642 0.989975718259291 0.114381876637693 -0.0227723108769895 -0.150681171916836 -0.125901827762691 0.980532464631224 0.0124071087462151 0.000102025455687276 6.21195946220521e-05 -1.99444204985407e-05 1.10736824925839e-05 -8.05987374019349e-06 3.1074276955424e-05 6.21195946220521e-05 0.000110860214396001 -1.54517437069796e-05 2.86743673797059e-05 -4.78031672897959e-06 8.23468750031803e-05 -1.99444204985407e-05 -1.54517437069796e-05 1.60145988956639e-05 2.75822220599128e-06 7.75769570317614e-07 -5.42379538140996e-06 1.10736824925839e-05 2.86743673797059e-05 2.75822220599128e-06 6.47878031827185e-05 -2.74120239631212e-05 2.25866100860995e-05 -8.05987374019349e-06 -4.78031672897959e-06 7.75769570317614e-07 -2.74120239631212e-05 7.39840020333833e-05 -4.3113112579532e-06 3.1074276955424e-05 8.23468750031803e-05 -5.42379538140996e-06 2.25866100860995e-05 -4.3113112579532e-06 0.000154529290382742 1304 1313 0 69 1 1280 1289 0 73 1 0 0 0 0 0 0 0 0 292 0 147 158 0 0 1634 +339 395 0.982825781845884 0.0649819601453779 0.17271603108771 -0.00844538385987761 -0.0849253171179495 0.990218243474643 0.110704655739531 -0.0213467985409084 -0.16383275939641 -0.123471353542661 0.978730632913317 0.0290374782543386 0.000115224646219192 0.000106378567696135 -1.38708158876146e-05 3.79371689027481e-05 -2.57030362575217e-05 0.00010111945916872 0.000106378567696135 0.000213847210391462 -1.72754404509915e-05 7.55508067673516e-05 -1.88682442397043e-05 0.000200970722689793 -1.38708158876146e-05 -1.72754404509915e-05 1.45014526434201e-05 -8.90238925830565e-07 7.22197459292068e-06 -1.65762385327306e-05 3.79371689027481e-05 7.55508067673516e-05 -8.90238925830565e-07 6.55372696620692e-05 -1.24140355268977e-05 7.03665887521014e-05 -2.57030362575217e-05 -1.88682442397043e-05 7.22197459292068e-06 -1.24140355268977e-05 6.87576306222727e-05 -1.25375157496782e-05 0.00010111945916872 0.000200970722689793 -1.65762385327306e-05 7.03665887521014e-05 -1.25375157496782e-05 0.000282046103659016 1501 1511 0 72 0 1517 1527 0 73 0 0 0 0 0 0 0 0 0 174 0 213 203 0 0 1791 +339 386 0.984264900252595 0.0615582076565602 0.165629686955152 -0.0159355825102071 -0.0826620622301076 0.988870822977757 0.123699146848958 -0.0197140240010237 -0.156171667080222 -0.13544401992486 0.978399370332983 0.022940228619553 5.80883995201843e-05 2.31839221347112e-05 -9.7172601543194e-06 3.38158423890891e-06 -2.38261213486978e-06 4.95945930457325e-06 2.31839221347112e-05 5.68181754791619e-05 -8.67832189603186e-06 9.55215717249733e-06 7.16463543079661e-06 3.47758020696987e-05 -9.7172601543194e-06 -8.67832189603186e-06 1.282786235011e-05 3.27558004219288e-07 7.04784927656477e-07 -3.73074598015856e-06 3.38158423890891e-06 9.55215717249733e-06 3.27558004219288e-07 3.42449793511966e-05 8.61916106368704e-06 -1.08893713579771e-07 -2.38261213486978e-06 7.16463543079661e-06 7.04784927656477e-07 8.61916106368704e-06 4.58229630539895e-05 2.38769496801686e-06 4.95945930457325e-06 3.47758020696987e-05 -3.73074598015856e-06 -1.08893713579771e-07 2.38769496801686e-06 0.000104621242842943 1298 1304 0 63 0 1302 1308 0 69 0 0 0 0 0 0 0 0 0 359 0 199 180 0 0 2075 +339 377 0.985209282604746 0.061702196476465 0.159860903348572 -0.0115309720823075 -0.0815835608548128 0.989300610224912 0.120948026882892 -0.033103934387838 -0.150687730315679 -0.132201140534397 0.979702029381237 0.020014164700472 6.71332381746234e-05 1.62105847554311e-05 -7.11325048258188e-06 -5.1359131611475e-06 -1.15350738982109e-06 -1.01631195472849e-05 1.62105847554311e-05 5.73292380996934e-05 -6.23736346405897e-06 3.21805357233468e-06 4.00606042291184e-06 3.38543031032272e-05 -7.11325048258188e-06 -6.23736346405897e-06 1.29299702185787e-05 4.03454087341539e-06 -7.37109475455958e-07 2.00396580639096e-06 -5.1359131611475e-06 3.21805357233468e-06 4.03454087341539e-06 4.52307586574288e-05 -8.9215156157404e-06 1.67380266507099e-05 -1.15350738982109e-06 4.00606042291184e-06 -7.37109475455958e-07 -8.9215156157404e-06 5.40111847186962e-05 -5.57327592433359e-06 -1.01631195472849e-05 3.38543031032272e-05 2.00396580639096e-06 1.67380266507099e-05 -5.57327592433359e-06 9.45045843529059e-05 1379 1390 0 68 0 1359 1370 0 73 0 0 0 0 0 0 0 0 0 363 0 194 180 0 0 2072 +339 392 0.982328201139792 0.0657274856525804 0.175246120856497 -0.010029755718289 -0.0853799555722647 0.990579218989166 0.107065746591947 -0.0109878104365564 -0.166558003205905 -0.120136208266296 0.978685712080982 0.034403170588886 0.000144286832305479 8.18446389869649e-05 -2.21254696293753e-05 2.64647082939508e-05 -5.04515964984832e-05 6.84940059652479e-05 8.18446389869649e-05 0.00017891868522788 -1.61309022768387e-05 5.80504050924214e-05 -1.89954547470376e-05 0.000149488124680355 -2.21254696293753e-05 -1.61309022768387e-05 1.6504302612315e-05 4.13211656068505e-07 1.22736734750984e-05 -1.20491634887962e-05 2.64647082939508e-05 5.80504050924214e-05 4.13211656068505e-07 6.81098102703795e-05 -2.21654434153367e-05 5.82249282623841e-05 -5.04515964984832e-05 -1.89954547470376e-05 1.22736734750984e-05 -2.21654434153367e-05 9.33213445869681e-05 -2.35481259788821e-05 6.84940059652479e-05 0.000149488124680355 -1.20491634887962e-05 5.82249282623841e-05 -2.35481259788821e-05 0.000217075354639653 1333 1341 0 71 0 1359 1375 0 77 0 0 0 0 0 0 0 0 0 147 0 193 180 0 0 1676 +339 396 0.981962594243082 0.0646897407925577 0.177664574250435 -0.0103263281556257 -0.0849935640673275 0.990384530912324 0.10915390509143 -0.0199630122281551 -0.168895108201895 -0.122285397189393 0.978018774901435 0.0374293098934318 0.000176436613294143 0.00011269965787831 -2.67325676251403e-05 1.26504542234912e-06 -1.54846504221149e-05 9.55344456936511e-05 0.00011269965787831 0.000150536859460584 -1.8965274221117e-05 1.46848363648422e-05 -8.48231505370594e-06 0.0001186430308946 -2.67325676251403e-05 -1.8965274221117e-05 1.82283134980294e-05 5.53112104829862e-06 6.38167938776026e-06 -1.53958848450445e-05 1.26504542234912e-06 1.46848363648422e-05 5.53112104829862e-06 4.73059997757679e-05 1.17534584975796e-06 1.32374647098764e-05 -1.54846504221149e-05 -8.48231505370594e-06 6.38167938776026e-06 1.17534584975796e-06 7.22905026499673e-05 1.47062360258539e-06 9.55344456936511e-05 0.0001186430308946 -1.53958848450445e-05 1.32374647098764e-05 1.47062360258539e-06 0.00017494705273012 1374 1385 0 71 0 1313 1324 0 75 0 0 0 0 0 0 0 0 0 166 0 193 179 0 0 1799 +339 389 0.985722871707372 0.0634345773955584 0.15596946683123 -0.0230488100569161 -0.0821213027347464 0.989796527165988 0.116442803329776 -0.0242260703336255 -0.146991536593503 -0.127588750290908 0.980874405298194 0.0127527828066419 6.36946988124556e-05 8.58942181496955e-06 -6.0606249168974e-06 -1.02249255422283e-05 -6.64683233936557e-06 -8.94066922112765e-06 8.58942181496955e-06 5.65175635190876e-05 1.36664218926821e-07 1.74371161392573e-05 -9.20632767008034e-06 2.97230032768999e-05 -6.0606249168974e-06 1.36664218926821e-07 1.34638353765885e-05 6.26319467318058e-06 3.19420224087033e-06 4.53866024966008e-06 -1.02249255422283e-05 1.74371161392573e-05 6.26319467318058e-06 4.95794091826965e-05 -4.12480591874719e-06 9.35814451281442e-06 -6.64683233936557e-06 -9.20632767008034e-06 3.19420224087033e-06 -4.12480591874719e-06 4.56986102000644e-05 -1.13940038098841e-05 -8.94066922112765e-06 2.97230032768999e-05 4.53866024966008e-06 9.35814451281442e-06 -1.13940038098841e-05 9.14468566134925e-05 1291 1299 0 75 0 1268 1276 0 76 0 0 0 0 0 0 0 0 0 228 0 197 184 0 0 1961 +339 376 0.983828804632687 0.0604152786199768 0.168614582063027 -0.00892040232982637 -0.0828589746098281 0.988122462477887 0.129415568898196 -0.0170611825992977 -0.158793178385051 -0.141293995823979 0.977149289127545 0.0223212581155047 6.1449998241974e-05 4.09677874724712e-05 -8.09065951581224e-06 1.3968491819867e-05 -5.01894235006807e-06 2.49594944915187e-05 4.09677874724712e-05 7.51146457675556e-05 -1.22933956619855e-05 1.85931924428594e-05 -6.14599741416221e-07 5.83508913528426e-05 -8.09065951581224e-06 -1.22933956619855e-05 1.3648622001024e-05 -1.31409814594073e-06 2.08748199005045e-06 -7.93687544931895e-06 1.3968491819867e-05 1.85931924428594e-05 -1.31409814594073e-06 4.47594891526531e-05 3.36936939298172e-06 2.01223618206201e-05 -5.01894235006807e-06 -6.14599741416221e-07 2.08748199005045e-06 3.36936939298172e-06 5.60425488379472e-05 -2.17788153006368e-06 2.49594944915187e-05 5.83508913528426e-05 -7.93687544931895e-06 2.01223618206201e-05 -2.17788153006368e-06 0.000126123207265047 1459 1466 0 63 0 1450 1457 0 69 0 0 0 0 0 0 0 0 0 361 0 233 219 0 0 2018 +340 342 0.999656095294452 0.0182650847585217 -0.0188169556361525 0.0112328787521762 -0.0184586887665367 0.999777929736315 -0.0101670065008217 -0.0134563495778959 0.0186270757143746 0.0105108463470662 0.999771250916628 0.000116618289260782 7.59642468780819e-05 3.33643925327656e-05 -1.38156951864398e-05 1.02736079186936e-05 1.16011520113984e-06 4.32292895634147e-05 3.33643925327656e-05 3.97853973489723e-05 -8.2493533190521e-06 5.50706614105055e-06 4.6711633927938e-07 2.16165984324464e-05 -1.38156951864398e-05 -8.2493533190521e-06 1.85247933970268e-05 -2.01239786275781e-06 2.4341759927359e-06 -1.11799088834987e-05 1.02736079186936e-05 5.50706614105055e-06 -2.01239786275781e-06 3.92053858938857e-05 -5.16915768876491e-06 1.0886091574317e-05 1.16011520113984e-06 4.6711633927938e-07 2.4341759927359e-06 -5.16915768876491e-06 3.4434711494627e-05 -5.06057406565323e-06 4.32292895634147e-05 2.16165984324464e-05 -1.11799088834987e-05 1.0886091574317e-05 -5.06057406565323e-06 7.10197006448985e-05 1656 1635 0 20 55 1679 1680 0 22 16 0 0 0 0 0 0 1 0 311 0 92 66 0 0 3136 +339 393 0.982862110620116 0.0657810612333957 0.17220604951737 -0.00899458044382452 -0.0845211125274553 0.990994952460806 0.103851748826517 -0.0217791359800982 -0.163823847606177 -0.116626995932387 0.979571279068193 0.0331004510608676 0.000206385121215852 0.000128877301301863 -3.22867641303939e-05 3.24460498726274e-05 -3.09091631775128e-05 0.000106946889159711 0.000128877301301863 0.000197033720788176 -2.610518719524e-05 7.21399884346664e-05 -2.70919557972113e-05 0.000169829782997719 -3.22867641303939e-05 -2.610518719524e-05 1.90033534075212e-05 -4.16728866773402e-06 1.18864975061433e-05 -2.26248921585463e-05 3.24460498726274e-05 7.21399884346664e-05 -4.16728866773402e-06 8.7474687181721e-05 -1.93135371083332e-05 6.76626171955843e-05 -3.09091631775128e-05 -2.70919557972113e-05 1.18864975061433e-05 -1.93135371083332e-05 6.0589660410756e-05 -2.67180068683829e-05 0.000106946889159711 0.000169829782997719 -2.26248921585463e-05 6.76626171955843e-05 -2.67180068683829e-05 0.000236834728522654 1244 1253 0 69 0 1246 1255 0 75 0 0 0 0 0 0 0 0 0 161 0 187 177 0 0 1745 +340 344 0.999476138520742 0.02663479484925 -0.0183857616378754 0.0189045781114122 -0.0266967396129267 0.999638672216928 -0.00313194866121603 -0.00834874193137088 0.0182956995413128 0.0036211478449891 0.999826062206111 0.00442948399094252 0.000124057554122769 2.41707787544037e-05 -2.62387569375661e-05 4.01357852097335e-06 -1.48728118773198e-05 1.98234833301103e-05 2.41707787544037e-05 8.46041995359862e-05 -1.85275993050467e-05 3.44028018959752e-05 8.42280364089369e-06 4.54308453633496e-05 -2.62387569375661e-05 -1.85275993050467e-05 2.34115900086685e-05 -6.29531019953348e-06 3.22914767640961e-07 -1.25075466154131e-05 4.01357852097335e-06 3.44028018959752e-05 -6.29531019953348e-06 5.25942243006817e-05 4.34453310239951e-06 2.86417817956939e-05 -1.48728118773198e-05 8.42280364089369e-06 3.22914767640961e-07 4.34453310239951e-06 4.34451854803495e-05 1.41927926169923e-05 1.98234833301103e-05 4.54308453633496e-05 -1.25075466154131e-05 2.86417817956939e-05 1.41927926169923e-05 9.58103012272737e-05 1676 1676 0 21 23 1664 1670 0 23 1 0 0 0 0 0 0 0 0 271 0 99 70 0 0 2982 +340 343 0.999806620814486 0.0128657574206575 -0.0148725674149407 0.01080443620637 -0.0129668138733063 0.999893356219715 -0.00671847643806941 -0.00110324494775739 0.0147845430600405 0.00691002703805566 0.999866825538701 0.000151396898236024 5.11272535779673e-05 1.26044716181388e-05 -6.09972296603357e-06 9.90554234478954e-07 -7.24875787364138e-06 -2.09056781948654e-06 1.26044716181388e-05 5.92880623515324e-05 -7.67821618831895e-06 2.60962535676889e-05 4.87289105922867e-06 3.72288329471765e-05 -6.09972296603357e-06 -7.67821618831895e-06 1.44873283850929e-05 1.28436580533404e-06 1.57484947707954e-06 -5.75900328441991e-06 9.90554234478954e-07 2.60962535676889e-05 1.28436580533404e-06 5.43265230680636e-05 -9.06870577254272e-06 2.62065629996366e-05 -7.24875787364138e-06 4.87289105922867e-06 1.57484947707954e-06 -9.06870577254272e-06 5.31225986477677e-05 9.90629405992379e-06 -2.09056781948654e-06 3.72288329471765e-05 -5.75900328441991e-06 2.62065629996366e-05 9.90629405992379e-06 8.23582968488999e-05 2039 2020 0 8 51 2046 2060 0 14 1 0 0 0 0 0 0 3 0 292 0 81 53 0 0 3158 +340 379 0.989640999870706 0.0295027063566981 0.140500112784798 -0.0290677463260947 -0.0465226403498311 0.991750801276204 0.119440328628519 -0.0262943038640242 -0.135817286491045 -0.124739482465011 0.982849798394735 0.00609771040707884 0.000124568478300134 3.49263804061728e-05 -2.43328542074357e-05 2.97634773641393e-06 -9.88998713971623e-06 -6.84494468202797e-06 3.49263804061728e-05 5.67124581152554e-05 -1.04236108648546e-05 1.20288296080979e-05 7.0125091762236e-06 2.08526312973592e-05 -2.43328542074357e-05 -1.04236108648546e-05 1.77713056355678e-05 9.74969782514807e-07 2.27062308628325e-06 1.37229793066042e-06 2.97634773641393e-06 1.20288296080979e-05 9.74969782514807e-07 4.39337137795469e-05 -5.81342809865089e-06 -4.58697478533733e-06 -9.88998713971623e-06 7.0125091762236e-06 2.27062308628325e-06 -5.81342809865089e-06 4.62788689878307e-05 6.38550093069544e-06 -6.84494468202797e-06 2.08526312973592e-05 1.37229793066042e-06 -4.58697478533733e-06 6.38550093069544e-06 8.44366672476923e-05 1910 1915 0 30 1 1875 1883 0 30 0 0 0 0 0 0 0 0 0 416 0 170 155 0 0 2091 +340 384 0.989094564562891 0.0285911511056029 0.144480062398249 -0.0286035900017626 -0.0465944932070679 0.991336381462794 0.122805260437125 -0.0187637700072379 -0.139717198493678 -0.128197990884063 0.981857616754266 0.00437725335356689 0.000117909910059453 3.87368522126674e-05 -1.89098059960857e-05 1.20096288289479e-05 -5.27897252602691e-06 2.33767878781475e-06 3.87368522126674e-05 6.35818147152483e-05 -1.22064276887164e-05 1.47833254261006e-05 4.37259087277877e-06 3.21959721335625e-05 -1.89098059960857e-05 -1.22064276887164e-05 1.50612182509456e-05 -2.00640658151834e-06 -5.53801848192813e-07 -3.26063698769008e-06 1.20096288289479e-05 1.47833254261006e-05 -2.00640658151834e-06 3.85660063762676e-05 -2.72430420720782e-06 7.97028864526184e-06 -5.27897252602691e-06 4.37259087277877e-06 -5.53801848192813e-07 -2.72430420720782e-06 4.89397012445048e-05 1.98432018401245e-07 2.33767878781475e-06 3.21959721335625e-05 -3.26063698769008e-06 7.97028864526184e-06 1.98432018401245e-07 9.50372585382057e-05 1971 1979 0 33 2 1931 1943 0 31 0 0 0 0 0 0 0 0 0 430 0 169 152 0 0 2163 +340 378 0.98974915884075 0.0283621059805867 0.139972116931812 -0.0260755210671686 -0.0460906205461941 0.991074157056039 0.125090646785955 -0.0204697010599399 -0.135174913618222 -0.130259764163796 0.982222040359663 0.010805206084512 0.000102038156762372 4.50627682934483e-05 -1.9389350496436e-05 8.65115058354827e-06 -3.57129121350145e-06 7.09438735391519e-06 4.50627682934483e-05 8.63213158748601e-05 -1.37144378512372e-05 1.80288262745583e-05 6.58960899464901e-06 6.98492327457764e-05 -1.9389350496436e-05 -1.37144378512372e-05 1.67749153341378e-05 -1.16215230304494e-06 7.46390184510931e-08 3.15719086755377e-09 8.65115058354827e-06 1.80288262745583e-05 -1.16215230304494e-06 4.1449915434431e-05 -3.22361448814042e-08 2.46773953635077e-05 -3.57129121350145e-06 6.58960899464901e-06 7.46390184510931e-08 -3.22361448814042e-08 5.72364218720482e-05 5.67313733436333e-06 7.09438735391519e-06 6.98492327457764e-05 3.15719086755377e-09 2.46773953635077e-05 5.67313733436333e-06 0.000134966158428855 1804 1809 0 30 1 1789 1799 0 33 0 0 0 0 0 0 0 0 0 433 0 134 111 0 0 2119 +340 386 0.989084539356607 0.0274157310341648 0.144776212471496 -0.0262842039506995 -0.0464153853320256 0.990487719669098 0.129536439619092 -0.0165760743140512 -0.1398477243655 -0.13484233339932 0.980948601667395 0.0140945675821895 6.26294658644648e-05 2.7196346356256e-05 -9.85066994391744e-06 5.5670807288613e-06 1.71073576454768e-06 8.37852032794629e-06 2.7196346356256e-05 4.59530953145648e-05 -8.12549981726952e-06 1.3433359544974e-05 -2.73710014099565e-06 3.08304393176849e-05 -9.85066994391744e-06 -8.12549981726952e-06 1.37454955368412e-05 2.29801344671041e-07 3.4241969621946e-07 -8.18476390413863e-07 5.5670807288613e-06 1.3433359544974e-05 2.29801344671041e-07 3.81184705924294e-05 -2.01492183075472e-06 9.80307252509287e-06 1.71073576454768e-06 -2.73710014099565e-06 3.4241969621946e-07 -2.01492183075472e-06 4.07727624971187e-05 -5.38746751239519e-06 8.37852032794629e-06 3.08304393176849e-05 -8.18476390413863e-07 9.80307252509287e-06 -5.38746751239519e-06 7.691774237894e-05 1859 1864 0 31 2 1843 1855 0 31 1 0 0 0 0 0 0 0 0 406 0 133 111 0 0 2101 +340 395 0.988143021336236 0.0357147704585924 0.149324561126374 -0.0253992432931529 -0.0499093297124058 0.994468651654511 0.0924183947280919 -0.0243487331146375 -0.145197893208382 -0.0987752805490781 0.984459758324482 0.020924309835979 0.000206774840160957 5.08014908214955e-05 -3.59713624747791e-05 -1.01143119793235e-05 -1.79175449818338e-05 1.86777604599902e-05 5.08014908214955e-05 0.000153525844406425 -1.24097317362079e-05 5.3129849058161e-05 -8.84737611425163e-06 9.95347926361992e-05 -3.59713624747791e-05 -1.24097317362079e-05 2.07501966262126e-05 7.02247756994688e-06 7.34921373422726e-06 -2.74853762394816e-06 -1.01143119793235e-05 5.3129849058161e-05 7.02247756994688e-06 7.36575915176337e-05 -1.1847411156865e-05 3.70465223371375e-05 -1.79175449818338e-05 -8.84737611425163e-06 7.34921373422726e-06 -1.1847411156865e-05 4.83904227689405e-05 -2.64951322974174e-06 1.86777604599902e-05 9.95347926361992e-05 -2.74853762394816e-06 3.70465223371375e-05 -2.64951322974174e-06 0.000187587032729891 1516 1524 0 37 0 1504 1512 0 36 0 0 0 0 0 0 0 0 0 212 0 155 148 0 0 1729 +341 343 0.999991478402204 -0.00285741200366652 0.00297965092182343 0.0130727796720127 0.00291992688718293 0.999771166731372 -0.0211917011956066 0.00408296017421133 -0.00291841565718918 0.0212002209712935 0.999770990517739 0.0139027698356537 6.87461247357431e-05 2.06553421484063e-05 -7.81763581317209e-06 1.93470597421289e-07 -7.34510532766061e-06 9.02135541912508e-06 2.06553421484063e-05 7.84294449769456e-05 -1.11390477866416e-05 2.17255067268445e-05 1.36072255576462e-05 4.70148908212233e-05 -7.81763581317209e-06 -1.11390477866416e-05 1.40584821103539e-05 3.22869140297594e-06 4.66323550907893e-07 -7.96445164094004e-06 1.93470597421289e-07 2.17255067268445e-05 3.22869140297594e-06 4.60214301804418e-05 -2.24733021999035e-07 2.84842887906651e-05 -7.34510532766061e-06 1.36072255576462e-05 4.66323550907893e-07 -2.24733021999035e-07 4.68313832636231e-05 1.09612808344633e-05 9.02135541912508e-06 4.70148908212233e-05 -7.96445164094004e-06 2.84842887906651e-05 1.09612808344633e-05 9.91820205897748e-05 1972 1933 0 1 77 1928 1947 0 10 16 0 0 0 0 0 5 14 0 303 0 66 38 0 0 3279 +341 411 0.989944070731963 0.0103659294212066 0.141079000314947 -0.043059513452114 -0.0271054839273802 0.992731776061866 0.117255761215027 -0.0123170152529112 -0.138838141602705 -0.119900660149507 0.983029909072974 0.00442248648540751 0.000207794132251462 0.000157783350057589 -3.20401180913599e-05 5.25869014972347e-05 -4.53312108031744e-05 0.000143875604047029 0.000157783350057589 0.000220648882361117 -2.60478649806469e-05 7.53256400016498e-05 -5.28045607243383e-05 0.000198662900334464 -3.20401180913599e-05 -2.60478649806469e-05 1.65927855216457e-05 -3.28165764172252e-06 9.67681491373343e-06 -2.0730895544285e-05 5.25869014972347e-05 7.53256400016498e-05 -3.28165764172252e-06 8.00597843911536e-05 -4.06656354667277e-05 7.19475548071727e-05 -4.53312108031744e-05 -5.28045607243383e-05 9.67681491373343e-06 -4.06656354667277e-05 6.83735832495104e-05 -5.78610292853249e-05 0.000143875604047029 0.000198662900334464 -2.0730895544285e-05 7.19475548071727e-05 -5.78610292853249e-05 0.000278928787296993 1639 1649 0 17 6 1608 1626 0 33 1 0 0 0 0 0 0 10 0 322 0 66 70 0 0 1712 +341 382 0.989554653988756 0.00934776471294227 0.143854808970937 -0.0421356159430181 -0.0264419754424982 0.992734782086345 0.117381746326567 -0.0169265975758296 -0.141712415489581 -0.119959458696877 0.982612497155039 0.00433148529723026 0.000124239303647028 3.62736674734066e-05 -2.35500510056262e-05 -3.42607703829621e-06 -7.56668056024972e-06 1.69038759510546e-05 3.62736674734066e-05 7.01689370675063e-05 -1.02291185870754e-05 1.77137978711913e-05 3.43876240883635e-06 3.90676526380088e-05 -2.35500510056262e-05 -1.02291185870754e-05 1.66207167993114e-05 1.45621451104848e-06 2.10486646874202e-06 -3.00261104739148e-06 -3.42607703829621e-06 1.77137978711913e-05 1.45621451104848e-06 5.00091891692977e-05 -8.53019085706101e-06 1.0262798408996e-05 -7.56668056024972e-06 3.43876240883635e-06 2.10486646874202e-06 -8.53019085706101e-06 4.99195226799176e-05 2.99150393275463e-06 1.69038759510546e-05 3.90676526380088e-05 -3.00261104739148e-06 1.0262798408996e-05 2.99150393275463e-06 0.000105936636571836 1667 1672 0 23 13 1601 1626 0 35 0 0 0 0 0 0 0 9 0 440 0 128 105 0 0 2207 +340 396 0.989064402948647 0.0317440339111707 0.144027508243678 -0.0265901117653167 -0.0480878624480451 0.992605241893622 0.11145578159289 -0.0270024202046938 -0.139424403549071 -0.117162921081503 0.983277013673479 0.0170021745364657 0.000157410755611439 5.24521585979519e-05 -2.31921012726607e-05 1.68604401280606e-05 -3.85565305986698e-05 -1.16590208593289e-05 5.24521585979519e-05 0.000127062117633511 -8.58337890896773e-06 4.1320131445087e-05 -1.74196964678793e-05 6.74034150488151e-05 -2.31921012726607e-05 -8.58337890896773e-06 1.56524700211055e-05 2.61346450451076e-06 8.79387910715686e-06 1.13932304043568e-06 1.68604401280606e-05 4.1320131445087e-05 2.61346450451076e-06 6.40875769237116e-05 -1.69871733070272e-05 3.6054514244654e-05 -3.85565305986698e-05 -1.74196964678793e-05 8.79387910715686e-06 -1.69871733070272e-05 6.42436498674184e-05 -4.22869803768757e-06 -1.16590208593289e-05 6.74034150488151e-05 1.13932304043568e-06 3.6054514244654e-05 -4.22869803768757e-06 0.000142335178560597 1772 1782 0 35 0 1768 1779 0 38 0 0 0 0 0 0 0 0 0 218 0 137 120 0 0 1776 +340 394 0.989177754716503 0.0324248205193861 0.143094376508311 -0.0297334589535288 -0.0483543523560507 0.992833227783058 0.109288784502808 -0.0236085193318665 -0.138525182484065 -0.115025270372035 0.98365642426286 0.010128169989791 0.000235019893749232 8.85648274358116e-05 -3.69676069539738e-05 7.74968065069562e-06 -3.79452961122881e-05 3.15223721048235e-05 8.85648274358116e-05 0.000154926084453957 -1.30697668297876e-05 3.83576859040744e-05 -6.58962198013174e-06 0.00011623454694038 -3.69676069539738e-05 -1.30697668297876e-05 1.89600219610015e-05 3.61822032434239e-06 1.03098246027302e-05 -8.74273727430421e-07 7.74968065069562e-06 3.83576859040744e-05 3.61822032434239e-06 5.03941872675506e-05 -3.3921631905181e-07 3.91659358600793e-05 -3.79452961122881e-05 -6.58962198013174e-06 1.03098246027302e-05 -3.3921631905181e-07 5.3064199847393e-05 -3.4271945109528e-06 3.15223721048235e-05 0.00011623454694038 -8.74273727430421e-07 3.91659358600793e-05 -3.4271945109528e-06 0.000201349170107558 1705 1711 0 34 0 1694 1705 0 31 0 0 0 0 0 0 0 0 0 224 0 139 120 0 0 1755 +341 345 0.999762414399256 0.0116061790038415 -0.0184502402017026 0.00423648170222661 -0.0116659059408708 0.99992704324945 -0.00313286083176637 -0.00366135739906619 0.018412533588523 0.00334735527592315 0.999824871574772 0.0153991058929673 6.82242207966623e-05 2.13061907648538e-05 -6.14479793682879e-06 1.18931701141847e-05 -6.5044285254464e-06 1.24332270771749e-05 2.13061907648538e-05 8.86741767226389e-05 -1.5819427681549e-05 3.20454327845214e-05 8.6567537020407e-06 3.86088957932625e-05 -6.14479793682879e-06 -1.5819427681549e-05 1.89902141294236e-05 6.99075747317115e-07 1.13968657321036e-06 -9.14481727000394e-06 1.18931701141847e-05 3.20454327845214e-05 6.99075747317115e-07 5.4118008961232e-05 -8.9019870936538e-06 3.68490552656569e-05 -6.5044285254464e-06 8.6567537020407e-06 1.13968657321036e-06 -8.9019870936538e-06 4.91912833223515e-05 9.15737094217302e-06 1.24332270771749e-05 3.86088957932625e-05 -9.14481727000394e-06 3.68490552656569e-05 9.15737094217302e-06 9.94741644141318e-05 1847 1818 0 10 56 1799 1811 0 21 18 0 0 0 0 0 0 5 0 281 0 74 54 0 0 3050 +341 344 0.999813983058588 0.00550855517473451 -0.018483914639725 0.00745619809720842 -0.00569162066728213 0.999935130690164 -0.00986609678773692 -0.00497345611599203 0.0184283676624248 0.00996946495716452 0.999780478422022 0.000352342694628337 4.7263034331807e-05 7.17698409723265e-06 -9.80127335176924e-06 2.87003860365026e-06 -8.16083296982899e-06 -4.53761928343716e-06 7.17698409723265e-06 6.22574657696209e-05 -8.07629514295218e-06 2.67335251482627e-05 6.87046319595818e-06 3.32445983322008e-05 -9.80127335176924e-06 -8.07629514295218e-06 1.52068550519593e-05 5.83496033632677e-07 -8.50132754128117e-07 -2.06643397901429e-06 2.87003860365026e-06 2.67335251482627e-05 5.83496033632677e-07 5.17941412905387e-05 -3.83367412432325e-06 3.327098263408e-05 -8.16083296982899e-06 6.87046319595818e-06 -8.50132754128117e-07 -3.83367412432325e-06 4.2222664397747e-05 5.45315147499391e-06 -4.53761928343716e-06 3.32445983322008e-05 -2.06643397901429e-06 3.327098263408e-05 5.45315147499391e-06 7.69078239711436e-05 2224 2195 0 9 65 2179 2187 0 18 36 0 0 0 0 0 1 8 0 351 0 72 41 0 0 3215 +341 381 0.989661247149125 0.00936757813084055 0.143118357911209 -0.0382744082284019 -0.0264016713625609 0.992711105575246 0.1175908696151 -0.0158923503108441 -0.140973641651557 -0.120153690528151 0.982695030521659 0.003333093354858 7.33554602447278e-05 2.30100953124857e-05 -1.19786585412742e-05 3.3030501541488e-06 -8.42774144222856e-07 -4.71554767717587e-06 2.30100953124857e-05 6.60861887605445e-05 -1.03635988274306e-05 8.01116225819783e-06 1.32030258188358e-05 4.51002895272954e-05 -1.19786585412742e-05 -1.03635988274306e-05 1.53323386185567e-05 1.39344532774396e-06 1.22038831822626e-06 -1.8189780182189e-06 3.3030501541488e-06 8.01116225819783e-06 1.39344532774396e-06 3.83957268587278e-05 -1.99173705641481e-06 7.73370020595981e-06 -8.42774144222856e-07 1.32030258188358e-05 1.22038831822626e-06 -1.99173705641481e-06 5.26240710493376e-05 3.80237321409342e-06 -4.71554767717587e-06 4.51002895272954e-05 -1.8189780182189e-06 7.73370020595981e-06 3.80237321409342e-06 0.000103903232191664 1769 1769 0 17 12 1707 1731 0 32 0 0 0 0 0 0 0 10 0 425 0 126 104 0 0 2198 +341 414 0.989047082279557 0.0115465592417913 0.14714804111496 -0.0448163092955567 -0.0280293301195583 0.993487524171801 0.110439557985506 -0.0112467578591432 -0.144914546155116 -0.113354383614666 0.982929579383994 0.00918792971871334 0.000133395790772739 7.09064124853035e-05 -2.43272084203662e-05 2.94152095139901e-05 -2.42125277889058e-05 4.21556183343291e-05 7.09064124853035e-05 9.43196750217624e-05 -1.92946818333365e-05 2.77854628329429e-05 -1.2703628830769e-06 7.31974042432134e-05 -2.43272084203662e-05 -1.92946818333365e-05 1.60533409536226e-05 -2.32172864513617e-06 3.63123029611946e-06 -1.23780540756387e-05 2.94152095139901e-05 2.77854628329429e-05 -2.32172864513617e-06 6.32233566380918e-05 -1.902569711108e-05 2.20558182605638e-05 -2.42125277889058e-05 -1.2703628830769e-06 3.63123029611946e-06 -1.902569711108e-05 6.67311568165156e-05 4.39595961472525e-06 4.21556183343291e-05 7.31974042432134e-05 -1.23780540756387e-05 2.20558182605638e-05 4.39595961472525e-06 0.000136906985366701 1842 1848 0 23 8 1809 1829 0 37 1 0 0 0 0 0 0 10 0 368 0 104 107 0 0 1727 +341 389 0.989522336169555 0.0111201647278918 0.143950992209053 -0.042425382253121 -0.0272248556296333 0.993514781442943 0.110395589994921 -0.0172745743999678 -0.141789821417095 -0.113157947095224 0.983407812431701 0.00671195959620296 8.34132522962066e-05 4.95792377323203e-05 -9.32721799719919e-06 1.35889305766012e-05 -1.53202126517463e-05 1.82665528954099e-05 4.95792377323203e-05 0.000127504380581363 -7.41383192994878e-06 3.56302822135238e-05 -1.18789211138924e-06 8.40288570417308e-05 -9.32721799719919e-06 -7.41383192994878e-06 1.24055374318682e-05 2.29546365942025e-06 6.71528204311936e-06 -4.31376349510886e-06 1.35889305766012e-05 3.56302822135238e-05 2.29546365942025e-06 5.08815749851076e-05 -1.4211273707913e-05 2.54296111436165e-05 -1.53202126517463e-05 -1.18789211138924e-06 6.71528204311936e-06 -1.4211273707913e-05 5.02681041010476e-05 9.73841888959388e-07 1.82665528954099e-05 8.40288570417308e-05 -4.31376349510886e-06 2.54296111436165e-05 9.73841888959388e-07 0.00013833663864387 1615 1622 0 20 7 1576 1591 0 33 0 0 0 0 0 0 0 9 0 279 0 124 108 0 0 2018 +341 409 0.989623973440554 0.0122653892811117 0.143157086508184 -0.0515257161904721 -0.0280537290193161 0.993668165141951 0.108795982791364 -0.00953306942678933 -0.140916214396497 -0.111683202896455 0.983701927776372 0.00714444307529119 0.000234788302077231 0.000142790974174555 -3.66480744701915e-05 3.46828970538061e-05 -4.63355762369079e-05 0.000119393399218166 0.000142790974174555 0.000176648741947413 -2.40765559576654e-05 5.55978302097175e-05 -4.74241575764176e-05 0.000167981609827456 -3.66480744701915e-05 -2.40765559576654e-05 1.75985043770208e-05 -2.90414325076837e-06 1.26172708511873e-05 -1.85541314028061e-05 3.46828970538061e-05 5.55978302097175e-05 -2.90414325076837e-06 6.49581768282657e-05 -1.75890742637497e-05 6.5174176921649e-05 -4.63355762369079e-05 -4.74241575764176e-05 1.26172708511873e-05 -1.75890742637497e-05 5.19098774370629e-05 -5.9602966568711e-05 0.000119393399218166 0.000167981609827456 -1.85541314028061e-05 6.5174176921649e-05 -5.9602966568711e-05 0.00026786240491075 1741 1740 0 19 8 1702 1713 0 37 0 0 0 0 0 0 0 10 0 286 0 70 73 0 0 1658 +341 397 0.988659104084757 0.0120903757078175 0.14968967474602 -0.0418609549413454 -0.0284327245657451 0.993796076452071 0.107521805240783 -0.0145321389203635 -0.147461032425838 -0.110558496931318 0.982869300910448 0.0181788168533449 0.000292517772958009 0.000162848511583963 -4.34150210977297e-05 3.94875148375344e-05 -6.37982708108256e-05 0.000125710783360993 0.000162848511583963 0.000252024599269514 -2.16140073661757e-05 7.03540523018747e-05 -3.77412348199015e-05 0.000190705385224153 -4.34150210977297e-05 -2.16140073661757e-05 1.80767373675033e-05 -3.89032971375743e-07 1.29888222960643e-05 -1.43193150575038e-05 3.94875148375344e-05 7.03540523018747e-05 -3.89032971375743e-07 8.2285454432225e-05 -3.53240440470956e-05 5.86026066038507e-05 -6.37982708108256e-05 -3.77412348199015e-05 1.29888222960643e-05 -3.53240440470956e-05 7.68773960849696e-05 -4.18422922438034e-05 0.000125710783360993 0.000190705385224153 -1.43193150575038e-05 5.86026066038507e-05 -4.18422922438034e-05 0.000243963294601945 1550 1558 0 25 7 1502 1520 0 39 0 0 0 0 0 0 0 10 0 240 0 123 110 0 0 1809 +341 380 0.989908676631635 0.00923650076624417 0.141405441843656 -0.039199468326999 -0.0259223718335705 0.992838486502284 0.116618053312407 -0.0208706222779764 -0.139315622124464 -0.119106787268604 0.983058864289736 0.00131961264450737 0.00011855677007158 4.34854560719712e-05 -2.05048242488996e-05 1.31290534126488e-05 -1.84059756556168e-05 -3.93919864813892e-07 4.34854560719712e-05 7.58789798238712e-05 -1.53596990793323e-05 1.32702986509088e-05 7.0702331698487e-06 3.87399204955118e-05 -2.05048242488996e-05 -1.53596990793323e-05 1.60187863852008e-05 -1.21148933738381e-06 4.37566732792256e-06 -3.20593170229004e-06 1.31290534126488e-05 1.32702986509088e-05 -1.21148933738381e-06 4.47203542772722e-05 -9.76544580272695e-06 1.0430175378987e-05 -1.84059756556168e-05 7.0702331698487e-06 4.37566732792256e-06 -9.76544580272695e-06 5.23390552692842e-05 1.38124920455201e-05 -3.93919864813892e-07 3.87399204955118e-05 -3.20593170229004e-06 1.0430175378987e-05 1.38124920455201e-05 0.000100379975153575 1707 1710 0 21 11 1659 1676 0 37 0 0 0 0 0 0 0 10 0 426 0 155 133 0 0 2153 +341 378 0.989617801548071 0.00982326389974344 0.143387971411548 -0.032908993137809 -0.0265769083908367 0.99296360622983 0.115399066908866 -0.0202566542390357 -0.141245441694761 -0.118011779875603 0.982915532999171 0.0118425522709221 9.56877286176422e-05 2.76810094234544e-05 -1.62286561806512e-05 9.19785126460371e-06 -1.98868097694209e-05 -1.35988244783644e-05 2.76810094234544e-05 4.78194316635201e-05 -8.09892782608326e-06 9.59638120964459e-06 -3.62798372452522e-06 2.19094767070293e-05 -1.62286561806512e-05 -8.09892782608326e-06 1.32026848559243e-05 -3.74357001153021e-07 4.42371349203049e-06 1.99012526192013e-06 9.19785126460371e-06 9.59638120964459e-06 -3.74357001153021e-07 4.48437329673245e-05 -1.6326120874484e-05 1.62749229281835e-05 -1.98868097694209e-05 -3.62798372452522e-06 4.42371349203049e-06 -1.6326120874484e-05 6.00663042589092e-05 -1.59988326151726e-06 -1.35988244783644e-05 2.19094767070293e-05 1.99012526192013e-06 1.62749229281835e-05 -1.59988326151726e-06 8.68310121296016e-05 1836 1838 0 24 10 1800 1813 0 35 0 0 0 0 0 0 0 10 0 439 0 110 94 0 0 2201 +341 388 0.989310061699978 0.0106229150336102 0.145439869002193 -0.0425554184143032 -0.0277193270648314 0.992858382159258 0.116033925569957 -0.0122940277169631 -0.143168574506626 -0.118825025362043 0.982539247369514 0.00227178251655495 0.000193105641569808 0.000149003812327906 -2.66507257207103e-05 3.20590613702654e-05 -3.24219570267525e-05 0.000114058973416534 0.000149003812327906 0.000195562648737707 -2.25293848972169e-05 3.62182609508708e-05 -2.20689842492877e-05 0.000169428596954266 -2.66507257207103e-05 -2.25293848972169e-05 1.61538338552488e-05 -3.33818831590124e-06 8.87444884048632e-06 -1.90589810506702e-05 3.20590613702654e-05 3.62182609508708e-05 -3.33818831590124e-06 6.53190385736224e-05 -3.0351400600577e-05 3.7181812261404e-05 -3.24219570267525e-05 -2.20689842492877e-05 8.87444884048632e-06 -3.0351400600577e-05 5.77298834054173e-05 -1.92523898304117e-05 0.000114058973416534 0.000169428596954266 -1.90589810506702e-05 3.7181812261404e-05 -1.92523898304117e-05 0.000239329208226291 1709 1711 0 21 14 1649 1673 0 31 0 0 0 0 0 0 0 7 0 435 0 128 104 0 0 2081 +341 386 0.989421356016082 0.0100655354959253 0.14472064557097 -0.040506179231686 -0.027036592091785 0.99290629339932 0.115784779725515 -0.0132845232030531 -0.142528603962014 -0.118472686823604 0.982674828989445 0.00883928530227 0.000144695681447225 6.53594820654194e-05 -2.64650831778852e-05 1.34261786263652e-05 -1.94961427953959e-05 2.57521235476552e-05 6.53594820654194e-05 9.93696538536074e-05 -1.83182752385692e-05 2.3763081967557e-05 -1.05691774909751e-06 6.16091381091819e-05 -2.64650831778852e-05 -1.83182752385692e-05 1.80420284833478e-05 -2.46978043196187e-06 4.56628559707669e-06 -7.0904899407523e-06 1.34261786263652e-05 2.3763081967557e-05 -2.46978043196187e-06 5.33719331091336e-05 -6.44118562656687e-06 8.75832228713733e-06 -1.94961427953959e-05 -1.05691774909751e-06 4.56628559707669e-06 -6.44118562656687e-06 4.9823298215324e-05 1.17039055705731e-06 2.57521235476552e-05 6.16091381091819e-05 -7.0904899407523e-06 8.75832228713733e-06 1.17039055705731e-06 0.000122927891094731 1813 1817 0 21 8 1779 1793 0 35 0 0 0 0 0 0 0 10 0 408 0 109 92 0 0 2133 +341 396 0.988624371012348 0.012257408250452 0.149905333405524 -0.0416332041639452 -0.0284448551286121 0.993924735280163 0.106322673099254 -0.0181190189586655 -0.147691378411713 -0.109377221308828 0.982966876451902 0.0192519537332884 0.000212462482436099 0.000111342406708075 -3.16983023761768e-05 1.51773912239087e-05 -3.83881771070747e-05 6.77054769339072e-05 0.000111342406708075 0.000135964739710537 -1.98861744568533e-05 3.1756906021623e-05 -3.45311826843758e-05 8.86308123116184e-05 -3.16983023761768e-05 -1.98861744568533e-05 1.85315245647997e-05 2.75764343397502e-06 8.3778534096003e-06 -1.07171851560964e-05 1.51773912239087e-05 3.1756906021623e-05 2.75764343397502e-06 6.60147312991872e-05 -1.82416794357513e-05 2.97236472669229e-05 -3.83881771070747e-05 -3.45311826843758e-05 8.3778534096003e-06 -1.82416794357513e-05 6.17312817776682e-05 -2.75273692098892e-05 6.77054769339072e-05 8.86308123116184e-05 -1.07171851560964e-05 2.97236472669229e-05 -2.75273692098892e-05 0.000157670766871397 1475 1477 0 19 8 1442 1454 0 37 0 0 0 0 0 0 0 10 0 237 0 113 102 0 0 1861 +341 395 0.988278257646586 0.0119804520715569 0.152192490718793 -0.0362268435236412 -0.0286462325766858 0.993760952122162 0.107789440096967 -0.0135306730089447 -0.14995158826165 -0.110885701537287 0.982455537096917 0.016859214595159 0.000140419764731968 6.98910348954146e-05 -1.98824616955934e-05 2.240548127543e-05 -2.84031662396345e-05 6.11203790409448e-05 6.98910348954146e-05 0.000105613336609307 -1.19637229588627e-05 3.84772693919034e-05 -2.16184954112719e-05 8.12721935670233e-05 -1.98824616955934e-05 -1.19637229588627e-05 1.59021782481477e-05 -2.11650005114071e-06 1.0174889985775e-05 -8.89109536871782e-06 2.240548127543e-05 3.84772693919034e-05 -2.11650005114071e-06 5.98941927748761e-05 -2.08212321879696e-05 4.122027969114e-05 -2.84031662396345e-05 -2.16184954112719e-05 1.0174889985775e-05 -2.08212321879696e-05 5.07790671471488e-05 -2.60016192538495e-05 6.11203790409448e-05 8.12721935670233e-05 -8.89109536871782e-06 4.122027969114e-05 -2.60016192538495e-05 0.000163714900626136 1819 1822 0 25 9 1793 1809 0 39 0 0 0 0 0 0 0 10 0 234 0 150 136 0 0 1821 +342 410 0.98994171790352 0.010954880080443 0.141051004096573 -0.0591819597809056 -0.0293004006719549 0.991256764875716 0.128652682088607 -0.00581260827532793 -0.138408387298932 -0.131491508054902 0.981607407080222 -0.00227221159246062 0.000136218143362355 4.31666279471116e-05 -2.08804599403811e-05 1.07978258073247e-05 -3.16251515117012e-05 6.95143500920102e-06 4.31666279471116e-05 8.75060517242075e-05 -5.59667447373923e-06 2.26000217944166e-05 -7.9700513781471e-06 5.15239525956531e-05 -2.08804599403811e-05 -5.59667447373923e-06 1.48324058821131e-05 2.43579498484741e-06 9.77915614595608e-06 7.14778457371865e-07 1.07978258073247e-05 2.26000217944166e-05 2.43579498484741e-06 5.43414236400934e-05 -2.69036367145551e-05 2.53207139989145e-05 -3.16251515117012e-05 -7.9700513781471e-06 9.77915614595608e-06 -2.69036367145551e-05 7.14184354012023e-05 -1.34080479467676e-05 6.95143500920102e-06 5.15239525956531e-05 7.14778457371865e-07 2.53207139989145e-05 -1.34080479467676e-05 0.000138487746811068 1353 1355 0 13 2 1376 1391 0 26 0 0 0 0 0 0 1 7 0 314 0 91 101 0 0 1675 +341 384 0.989100324147681 0.00949905528349542 0.146936437685391 -0.0427966135468915 -0.0269089250314016 0.992772380190705 0.11695687617296 -0.00877687387961069 -0.144763457145117 -0.119635985720033 0.982207092417984 0.00804522490090142 8.61796300871138e-05 1.18641568375739e-05 -1.64646680669689e-05 4.14246162567451e-07 -6.95277177110256e-06 -6.92963422498225e-06 1.18641568375739e-05 4.61426644562713e-05 -6.81632218217463e-06 1.62026687953595e-05 -7.3883871557053e-07 1.95738265639708e-05 -1.64646680669689e-05 -6.81632218217463e-06 1.61527241652911e-05 -1.50262709092461e-06 1.5815304585122e-06 -2.5188541337469e-06 4.14246162567451e-07 1.62026687953595e-05 -1.50262709092461e-06 5.60361449327057e-05 -2.01144311311254e-05 9.24584082950583e-06 -6.95277177110256e-06 -7.3883871557053e-07 1.5815304585122e-06 -2.01144311311254e-05 6.20372325401265e-05 5.28763666041518e-06 -6.92963422498225e-06 1.95738265639708e-05 -2.5188541337469e-06 9.24584082950583e-06 5.28763666041518e-06 7.57065258302882e-05 1656 1658 0 21 11 1620 1639 0 33 0 0 0 0 0 0 0 9 0 435 0 155 136 0 0 2221 +341 379 0.989125695496581 0.0102073886970683 0.146717987051319 -0.0334266732196762 -0.0271524224008806 0.99311416691331 0.113960508220374 -0.0199477301945828 -0.144544472278148 -0.116705015710846 0.982591896385149 0.00968700753339793 8.54213898651025e-05 3.20923538996667e-05 -1.16176103696222e-05 -1.38270842374297e-06 -1.74764958154293e-07 1.10548259990804e-05 3.20923538996667e-05 7.58938868960993e-05 -9.06284071456501e-06 1.51114742676916e-05 1.12338836405572e-05 5.3617081400921e-05 -1.16176103696222e-05 -9.06284071456501e-06 1.3402048476711e-05 2.83827495086592e-06 1.26703679626768e-06 -3.24624677160426e-06 -1.38270842374297e-06 1.51114742676916e-05 2.83827495086592e-06 5.16612702883856e-05 -6.0569884514674e-06 9.23793301077021e-06 -1.74764958154293e-07 1.12338836405572e-05 1.26703679626768e-06 -6.0569884514674e-06 4.49612378392273e-05 4.75940675793971e-06 1.10548259990804e-05 5.3617081400921e-05 -3.24624677160426e-06 9.23793301077021e-06 4.75940675793971e-06 0.000125731802777811 1622 1625 0 24 10 1577 1593 0 36 0 0 0 0 0 0 0 9 0 422 0 156 134 0 0 2175 +342 344 0.999964651988881 0.00808740319769512 -0.00229971351996188 0.00374574241228287 -0.00808428154219501 0.999966392089608 0.00136348202711662 -0.0053298281024038 0.00231066326030208 -0.001344842299177 0.999996426110857 0.012089777606906 0.00012122828606484 1.66422541598485e-05 -2.29115886792117e-05 1.60166106482993e-05 -3.03271827535779e-05 3.65069987240876e-05 1.66422541598485e-05 5.99997077074819e-05 -1.08362560527311e-05 2.76998942509494e-05 2.30727922603793e-07 3.61096519343115e-05 -2.29115886792117e-05 -1.08362560527311e-05 1.76695202148931e-05 -3.49860068746013e-06 6.94564435849308e-06 -1.26889424800453e-05 1.60166106482993e-05 2.76998942509494e-05 -3.49860068746013e-06 5.27350177014705e-05 -1.4721088656897e-05 3.87677288446821e-05 -3.03271827535779e-05 2.30727922603793e-07 6.94564435849308e-06 -1.4721088656897e-05 4.77179696952876e-05 -1.4013246694641e-05 3.65069987240876e-05 3.61096519343115e-05 -1.26889424800453e-05 3.87677288446821e-05 -1.4013246694641e-05 0.000102435846323101 1788 1767 0 5 50 1778 1782 0 16 32 0 0 0 0 0 0 7 0 305 0 113 89 0 0 3227 +341 398 0.988509688154309 0.0119905318828046 0.150681198462978 -0.0293689385421569 -0.0281776472888019 0.993992848012048 0.105755559164356 -0.0316047060840977 -0.14850796819814 -0.108786236473485 0.982909425194201 0.0118661615978215 0.000266071119573593 0.000201839199241972 -4.52251309197843e-05 7.18952106923818e-05 -6.5850619413586e-05 0.000153958971552986 0.000201839199241972 0.000235675289501186 -3.81314117762822e-05 9.01876314059693e-05 -6.49065962888204e-05 0.00018417625725632 -4.52251309197843e-05 -3.81314117762822e-05 2.09779264088149e-05 -6.70366103100351e-06 1.4439687312013e-05 -2.69597465689045e-05 7.18952106923818e-05 9.01876314059693e-05 -6.70366103100351e-06 8.7687985862938e-05 -5.41908969862208e-05 9.5126659207143e-05 -6.5850619413586e-05 -6.49065962888204e-05 1.4439687312013e-05 -5.41908969862208e-05 9.32948419456075e-05 -7.62510853295975e-05 0.000153958971552986 0.00018417625725632 -2.69597465689045e-05 9.5126659207143e-05 -7.62510853295975e-05 0.000249982679289233 1431 1434 0 29 12 1392 1416 0 40 0 0 0 0 0 0 0 8 0 243 0 122 107 0 0 1768 +342 387 0.989074919279911 0.0100935709418041 0.1470677526757 -0.0578247182514204 -0.0294667150486614 0.991055789098496 0.130154276144117 -0.00685512903835915 -0.144438626259318 -0.133065933732119 0.980525848983249 -0.000891252806579939 8.89469117928715e-05 3.6422896344651e-05 -1.65476677681107e-05 4.72151198487127e-06 6.44346774379638e-07 7.73435282952622e-06 3.6422896344651e-05 9.73946089680764e-05 -1.04681985601741e-05 1.7986450666136e-05 5.05194409381159e-06 7.61446957986726e-05 -1.65476677681107e-05 -1.04681985601741e-05 1.65709530184011e-05 6.90522768457493e-07 -2.03227239232343e-06 -2.49365294967567e-06 4.72151198487127e-06 1.7986450666136e-05 6.90522768457493e-07 5.63033471887817e-05 -1.4812730386008e-05 2.10364204455484e-05 6.44346774379638e-07 5.05194409381159e-06 -2.03227239232343e-06 -1.4812730386008e-05 6.11698878391328e-05 1.12284640999467e-05 7.73435282952622e-06 7.61446957986726e-05 -2.49365294967567e-06 2.10364204455484e-05 1.12284640999467e-05 0.000151734524449523 1575 1576 0 12 12 1573 1597 0 25 0 0 0 0 0 0 3 10 0 429 0 150 135 0 0 2172 +342 346 0.999956369325485 0.00933462194039403 -0.000352531735444689 -0.00797981209916886 -0.00933301736245153 0.999947167696311 0.00430773757769697 -0.00364561049766522 0.000392724212087212 -0.0043042594433931 0.999990659515546 0.0165247070968392 6.70625682660805e-05 2.09037276658679e-05 -1.48337247790649e-05 1.48280547645941e-05 -7.51174903608715e-06 1.32372905893065e-05 2.09037276658679e-05 4.16020708061861e-05 -1.13435395439884e-05 1.34850575555136e-05 8.87720457129485e-10 1.3062722162694e-05 -1.48337247790649e-05 -1.13435395439884e-05 2.06208179202146e-05 -1.30591878683891e-06 2.29649598012707e-06 -8.42345117342122e-06 1.48280547645941e-05 1.34850575555136e-05 -1.30591878683891e-06 5.03221582752716e-05 -2.42094757593418e-05 2.26459125986733e-05 -7.51174903608715e-06 8.87720457129485e-10 2.29649598012707e-06 -2.42094757593418e-05 5.57865900604278e-05 -2.7026668789781e-07 1.32372905893065e-05 1.3062722162694e-05 -8.42345117342122e-06 2.26459125986733e-05 -2.7026668789781e-07 6.42462058579305e-05 1621 1613 0 12 33 1639 1654 0 24 32 0 0 0 0 0 0 8 0 290 0 90 59 0 0 3007 +342 345 0.999927462715462 0.0119932601412546 -0.0011095127774825 0.000379054209249408 -0.011980622302266 0.999870218495303 0.0107708335520406 -0.000531841119823855 0.00123854619197253 -0.010756759611496 0.999941377344688 0.0136453598431983 5.03377517845085e-05 -1.9245038278474e-06 -3.11653032855533e-06 7.64196039145758e-06 -6.25804531376229e-06 1.2357941459192e-05 -1.9245038278474e-06 2.84796576776568e-05 -5.71475907167133e-06 1.48794558929798e-06 7.11167859862188e-08 -3.2221807792719e-07 -3.11653032855533e-06 -5.71475907167133e-06 1.55976302904585e-05 5.06316009176063e-06 5.25784946688694e-07 -1.69897129264708e-06 7.64196039145758e-06 1.48794558929798e-06 5.06316009176063e-06 3.11456483420469e-05 -1.03607701994154e-05 1.22305997349975e-05 -6.25804531376229e-06 7.11167859862188e-08 5.25784946688694e-07 -1.03607701994154e-05 4.56176805307209e-05 -3.82012545922311e-06 1.2357941459192e-05 -3.2221807792719e-07 -1.69897129264708e-06 1.22305997349975e-05 -3.82012545922311e-06 5.41866383822668e-05 1837 1819 0 7 48 1798 1818 0 17 13 0 0 0 0 0 0 5 0 272 0 84 61 0 0 3057 +342 409 0.989537076259036 0.0123137368485878 0.143752379436105 -0.0557810087937089 -0.0297492296183337 0.992354886257753 0.119777974008073 -0.0158179284566473 -0.141178461692405 -0.122801268744205 0.982338276943833 0.00152818417480371 8.86639803673805e-05 3.89479824617887e-05 -1.04589770578011e-05 1.8563353060081e-05 -2.01536949175876e-05 2.65797384422647e-05 3.89479824617887e-05 6.04499359249759e-05 -6.02843633022878e-06 1.94788839200051e-05 -1.23748880193413e-05 2.88830481637637e-05 -1.04589770578011e-05 -6.02843633022878e-06 1.32200447484697e-05 1.07249488561892e-06 7.55437922798144e-06 -4.92138813004272e-06 1.8563353060081e-05 1.94788839200051e-05 1.07249488561892e-06 5.83841625890044e-05 -2.03943970539118e-05 6.69776878456621e-06 -2.01536949175876e-05 -1.23748880193413e-05 7.55437922798144e-06 -2.03943970539118e-05 4.98772075196844e-05 -8.70613888818326e-06 2.65797384422647e-05 2.88830481637637e-05 -4.92138813004272e-06 6.69776878456621e-06 -8.70613888818326e-06 9.43158115493297e-05 1249 1250 0 15 1 1277 1295 0 25 0 0 0 0 0 0 1 6 0 299 0 100 106 0 0 1657 +342 412 0.98928249340861 0.010578175824628 0.145630527127612 -0.0544572273711552 -0.0295072547738934 0.99127793047286 0.128442152244319 -0.0108431887966191 -0.143001643874996 -0.131362729697839 0.980966035648218 0.00294128952250034 0.000176646311923434 0.000153111649405886 -3.0359515820438e-05 5.51282608493482e-05 -2.59243528830668e-05 0.000129084152461423 0.000153111649405886 0.000232715393454251 -3.05728138398923e-05 7.22621802159638e-05 -2.07966993191155e-05 0.000212538174894654 -3.0359515820438e-05 -3.05728138398923e-05 1.68270606330581e-05 -7.32792204647854e-06 6.03415383230923e-06 -2.16494107180225e-05 5.51282608493482e-05 7.22621802159638e-05 -7.32792204647854e-06 7.68779731119404e-05 -4.1800644170454e-05 8.01554678723395e-05 -2.59243528830668e-05 -2.07966993191155e-05 6.03415383230923e-06 -4.1800644170454e-05 7.72513083470267e-05 -4.45147050580491e-05 0.000129084152461423 0.000212538174894654 -2.16494107180225e-05 8.01554678723395e-05 -4.45147050580491e-05 0.000304635196885862 1439 1441 0 12 3 1424 1434 0 21 0 0 0 0 0 0 1 5 0 368 0 91 100 0 0 1720 +342 388 0.989291407713673 0.0117652755837612 0.14547882634369 -0.0502574625056209 -0.0298166551509138 0.992016398188599 0.122533394633994 -0.0173553207592291 -0.14287574216609 -0.125558926466248 0.981744100203883 -0.00170082699371438 5.59441114944355e-05 3.48052940252471e-05 -5.19860349276815e-06 1.27959699366497e-06 -5.02049206504008e-06 1.82167400295302e-05 3.48052940252471e-05 5.73643652376543e-05 -3.11054992670252e-06 6.27136485241614e-06 -4.55773670556379e-06 3.83871947905843e-05 -5.19860349276815e-06 -3.11054992670252e-06 1.28867825377128e-05 2.4019160511673e-06 4.38070566887055e-06 -1.97260850081986e-06 1.27959699366497e-06 6.27136485241614e-06 2.4019160511673e-06 3.53710630534484e-05 -1.18623759355166e-05 9.74696250006884e-06 -5.02049206504008e-06 -4.55773670556379e-06 4.38070566887055e-06 -1.18623759355166e-05 3.96730899036962e-05 -4.4416891701456e-06 1.82167400295302e-05 3.83871947905843e-05 -1.97260850081986e-06 9.74696250006884e-06 -4.4416891701456e-06 0.00010233973123463 1667 1673 0 15 9 1629 1641 0 24 0 0 0 0 0 0 1 6 0 439 0 146 131 0 0 2095 +342 397 0.987767529209299 0.00956176236004108 0.155640229183611 -0.0429119492496732 -0.0304930516746248 0.990692392165255 0.132660310211655 -0.0181406801873437 -0.152923124606207 -0.135783492393052 0.978865343729269 0.0132956237721769 8.68549506756886e-05 2.99001447604775e-05 -1.21600586535002e-05 5.34765505012931e-08 -8.88748457719135e-06 1.00921793704241e-05 2.99001447604775e-05 6.71154135066816e-05 -6.18642398757146e-06 1.30003976714566e-05 -1.36422436753853e-06 4.1247837407317e-05 -1.21600586535002e-05 -6.18642398757146e-06 1.27055544215879e-05 2.99264055832353e-06 4.27570076630128e-06 -2.84444402404426e-08 5.34765505012931e-08 1.30003976714566e-05 2.99264055832353e-06 5.8611846492361e-05 -2.20477584594264e-05 1.27549779935273e-05 -8.88748457719135e-06 -1.36422436753853e-06 4.27570076630128e-06 -2.20477584594264e-05 5.82331917143808e-05 -1.92578536153962e-06 1.00921793704241e-05 4.1247837407317e-05 -2.84444402404426e-08 1.27549779935273e-05 -1.92578536153962e-06 0.000105352015666945 1486 1486 0 12 6 1463 1473 0 22 3 0 0 0 0 0 0 5 0 253 0 131 122 0 0 1887 +342 389 0.989296555114251 0.0111849009452979 0.145489601105783 -0.0519399170997696 -0.0295435768297976 0.991761416923595 0.124645372837526 -0.0159905895288928 -0.142896826791843 -0.127609521167301 0.981476595238151 0.003629447659402 7.80612428904723e-05 3.51504328047548e-05 -9.99075010594826e-06 7.18102181144283e-06 -1.66145144623894e-05 -9.03208229573545e-06 3.51504328047548e-05 6.8662894074814e-05 -6.90713648439723e-06 1.56676472139392e-05 -2.08194846236052e-06 2.15703965014013e-05 -9.99075010594826e-06 -6.90713648439723e-06 1.32796951191848e-05 1.92839265599836e-06 8.74812758870356e-06 -5.44292746126036e-07 7.18102181144283e-06 1.56676472139392e-05 1.92839265599836e-06 3.49560191295126e-05 -9.1175162421768e-06 9.27075251680781e-06 -1.66145144623894e-05 -2.08194846236052e-06 8.74812758870356e-06 -9.1175162421768e-06 4.86271599827011e-05 -4.97724638399645e-07 -9.03208229573545e-06 2.15703965014013e-05 -5.44292746126036e-07 9.27075251680781e-06 -4.97724638399645e-07 8.6759601984973e-05 1455 1456 0 13 6 1432 1439 0 22 0 0 0 0 0 0 2 5 0 308 0 137 124 0 0 2038 +342 398 0.987858520995101 0.0113387348577681 0.154941845829965 -0.0365141160478055 -0.0303532706579093 0.99219895580107 0.120912824248027 -0.0322645741323709 -0.15236213918733 -0.12414775551371 0.980496360698585 0.00465976059844542 0.00015588046688632 0.000107346692780189 -2.52160433795998e-05 3.51368021355884e-05 -2.46320282763445e-05 8.06958398208487e-05 0.000107346692780189 0.000139198595276779 -2.06733049691362e-05 4.30920957142788e-05 -2.27648652882947e-05 9.74734795094598e-05 -2.52160433795998e-05 -2.06733049691362e-05 1.60210623294593e-05 -1.52546403260672e-06 7.05401537024521e-06 -1.17954080211758e-05 3.51368021355884e-05 4.30920957142788e-05 -1.52546403260672e-06 5.42666630061133e-05 -2.34694348116491e-05 3.68586841417376e-05 -2.46320282763445e-05 -2.27648652882947e-05 7.05401537024521e-06 -2.34694348116491e-05 5.57786542944585e-05 -3.05870202920331e-05 8.06958398208487e-05 9.74734795094598e-05 -1.17954080211758e-05 3.68586841417376e-05 -3.05870202920331e-05 0.000156183913915878 1725 1733 0 16 8 1689 1703 0 25 1 0 0 0 0 0 0 5 0 249 0 135 124 0 0 1847 +342 396 0.986852313725655 0.0115224032939386 0.161213352786464 -0.0400380626432112 -0.0313862675986825 0.992129628417987 0.121217583796295 -0.0206005978490602 -0.158547825909235 -0.124683738464644 0.979447064553228 0.0226314331298595 0.000161411851408643 4.56437394906085e-05 -2.52681789996287e-05 1.09062576756216e-05 -4.18155614723563e-05 2.93628640038818e-05 4.56437394906085e-05 9.44685929443228e-05 -9.21131884891644e-06 1.36945255033888e-05 -6.53333843318073e-06 5.98862186852666e-05 -2.52681789996287e-05 -9.21131884891644e-06 1.62310753619057e-05 1.3833193400076e-06 1.11420053529187e-05 -4.46780728708427e-06 1.09062576756216e-05 1.36945255033888e-05 1.3833193400076e-06 4.5047261260639e-05 -4.09799983736727e-06 1.36344600539027e-05 -4.18155614723563e-05 -6.53333843318073e-06 1.11420053529187e-05 -4.09799983736727e-06 6.06452757540748e-05 1.13492956560323e-06 2.93628640038818e-05 5.98862186852666e-05 -4.46780728708427e-06 1.36344600539027e-05 1.13492956560323e-06 0.00013053225370423 1494 1496 0 15 1 1519 1533 0 24 0 0 0 0 0 0 0 4 0 225 0 144 127 0 0 1904 +342 381 0.989164802831442 0.00932100123220469 0.1465131795282 -0.0533228578572535 -0.028853188408027 0.990861497370171 0.131761096489188 -0.0119993256188727 -0.143946123109045 -0.134560811402769 0.980394258284138 0.00140442724979126 4.93142842144248e-05 1.24511873416263e-05 -5.67521726069676e-06 3.07252209069735e-06 -4.24705838414322e-06 -7.96991386557637e-06 1.24511873416263e-05 6.71654088213585e-05 -4.94094877946252e-06 2.38697081004193e-05 1.37785308238078e-06 3.43606988386527e-05 -5.67521726069676e-06 -4.94094877946252e-06 1.38480394028428e-05 3.81462585170387e-06 2.26009112088127e-07 -5.53692448254876e-07 3.07252209069735e-06 2.38697081004193e-05 3.81462585170387e-06 5.80071018993724e-05 -2.09937163590053e-05 1.40436079159144e-05 -4.24705838414322e-06 1.37785308238078e-06 2.26009112088127e-07 -2.09937163590053e-05 5.66118001566697e-05 4.14958556898226e-06 -7.96991386557637e-06 3.43606988386527e-05 -5.53692448254876e-07 1.40436079159144e-05 4.14958556898226e-06 0.000107259872917703 1635 1635 0 13 10 1590 1600 0 21 0 0 0 0 0 0 1 6 0 423 0 136 125 0 0 2230 +342 408 0.989064313453481 0.00943346925733254 0.147182857393669 -0.0478231749864946 -0.0290091180884025 0.990900909891004 0.131430049246409 -0.0206930519619797 -0.144603785982689 -0.134262416315778 0.980338384765445 -0.00458221424130403 6.741615099122e-05 1.70094010760128e-05 -9.1898582955461e-06 -2.83825780550424e-06 -6.02495916963781e-06 -5.15896172750869e-06 1.70094010760128e-05 5.14003455982347e-05 -2.55547624157013e-06 8.35417534484014e-06 5.98863407371681e-06 2.58251709348601e-05 -9.1898582955461e-06 -2.55547624157013e-06 1.26689012779377e-05 4.19680620897898e-06 4.50918013846835e-06 4.62241886202925e-07 -2.83825780550424e-06 8.35417534484014e-06 4.19680620897898e-06 4.36162691575445e-05 -9.31604477263133e-06 -3.00011688820581e-06 -6.02495916963781e-06 5.98863407371681e-06 4.50918013846835e-06 -9.31604477263133e-06 4.48710017723867e-05 1.44045116275e-05 -5.15896172750869e-06 2.58251709348601e-05 4.62241886202925e-07 -3.00011688820581e-06 1.44045116275e-05 0.000104158476219615 1568 1572 0 14 6 1592 1615 0 24 1 0 0 0 0 0 0 5 0 291 0 91 95 0 0 1783 +342 382 0.988243836890109 0.00909504253805839 0.152615199275653 -0.0503421882866442 -0.029693531577177 0.990638796287004 0.133240644975587 -0.0115522061404905 -0.149974707971682 -0.136205930459236 0.979262748947667 0.00520034267601043 7.33910620450601e-05 1.87751098429529e-05 -1.12610939449806e-05 5.09378534053804e-06 -1.48055412742077e-05 -6.90813951735704e-06 1.87751098429529e-05 5.31472157757896e-05 -4.86622846214697e-06 1.01609727768468e-05 6.1953877569977e-07 1.71208536458705e-05 -1.12610939449806e-05 -4.86622846214697e-06 1.32429239760227e-05 6.92750692839159e-07 4.13785525130027e-06 2.26858677158109e-06 5.09378534053804e-06 1.01609727768468e-05 6.92750692839159e-07 4.35653890235211e-05 -1.21717835784764e-05 3.10690733771433e-06 -1.48055412742077e-05 6.1953877569977e-07 4.13785525130027e-06 -1.21717835784764e-05 4.62865715763239e-05 4.12989637637018e-06 -6.90813951735704e-06 1.71208536458705e-05 2.26858677158109e-06 3.10690733771433e-06 4.12989637637018e-06 7.4609666883157e-05 1669 1673 0 13 11 1631 1642 0 23 1 0 0 0 0 0 1 5 0 437 0 142 127 0 0 2221 +342 406 0.989163831877448 0.0110317441263349 0.146400868600751 -0.0529486383244024 -0.0301079536746472 0.991221988036352 0.128734150709076 -0.00836184835307212 -0.143695597813742 -0.131746996378638 0.980813083168326 -0.00391655211059616 0.000117118698673052 2.29388625809521e-05 -1.58129987423236e-05 8.54000599295018e-06 -3.98856082032441e-05 1.06483493218898e-05 2.29388625809521e-05 8.30567032494966e-05 -3.91927109717738e-06 1.47120436705418e-05 -1.94443257629139e-06 3.7823722428367e-05 -1.58129987423236e-05 -3.91927109717738e-06 1.35797659619406e-05 2.61093306884008e-06 9.32596760449759e-06 -3.97145902722328e-07 8.54000599295018e-06 1.47120436705418e-05 2.61093306884008e-06 4.23698614571317e-05 -2.11436113164782e-05 9.35878190170319e-06 -3.98856082032441e-05 -1.94443257629139e-06 9.32596760449759e-06 -2.11436113164782e-05 7.31174625229624e-05 -7.71927820891944e-06 1.06483493218898e-05 3.7823722428367e-05 -3.97145902722328e-07 9.35878190170319e-06 -7.71927820891944e-06 0.000104030785209568 1603 1608 0 13 4 1572 1587 0 22 2 0 0 0 0 0 0 5 0 270 0 103 106 0 0 1766 +342 414 0.988895167660548 0.00936022374520483 0.148319700610057 -0.0569021803197151 -0.0291641349541974 0.990831671354984 0.131916838471297 -0.0122642200307404 -0.145725085726483 -0.13477753986228 0.980101634596474 0.00166925940190628 7.54749170140669e-05 4.32744985188604e-05 -1.28039166178731e-05 1.94531577901163e-05 -8.56418267021377e-06 3.44011712988263e-05 4.32744985188604e-05 9.71967832688983e-05 -1.31328420235085e-05 3.67156396402376e-05 -3.70635586609094e-06 8.36848618260868e-05 -1.28039166178731e-05 -1.31328420235085e-05 1.42116608887512e-05 -2.86897443896682e-06 8.6768203703734e-07 -1.03972420303627e-05 1.94531577901163e-05 3.67156396402376e-05 -2.86897443896682e-06 6.29391888843693e-05 -1.42437905064055e-05 3.09865244383794e-05 -8.56418267021377e-06 -3.70635586609094e-06 8.6768203703734e-07 -1.42437905064055e-05 5.46355555855471e-05 -8.51012907575101e-06 3.44011712988263e-05 8.36848618260868e-05 -1.03972420303627e-05 3.09865244383794e-05 -8.51012907575101e-06 0.000180728638157072 1555 1556 0 12 5 1567 1585 0 23 0 0 0 0 0 0 0 6 0 384 0 93 103 0 0 1806 +342 386 0.988385609770373 0.00914979279107548 0.151691027060691 -0.051374704098134 -0.0295497973860922 0.990704660890744 0.132782093535974 -0.00647892541871982 -0.149066078882112 -0.135722349601072 0.97946860487995 0.0105393546261272 6.54838529551137e-05 2.13725364982942e-05 -9.18353178929081e-06 6.19118457123168e-07 -3.72684899709969e-06 -1.80707424495442e-07 2.13725364982942e-05 5.06885420548991e-05 -8.17911611101343e-06 1.48383654380865e-05 -2.18769812100787e-07 2.04326585413719e-05 -9.18353178929081e-06 -8.17911611101343e-06 1.2266953096145e-05 1.93707184113535e-06 -5.52532129658541e-07 -2.55117993124542e-06 6.19118457123168e-07 1.48383654380865e-05 1.93707184113535e-06 5.3091937796009e-05 -2.14504097627749e-05 2.07099174897136e-07 -3.72684899709969e-06 -2.18769812100787e-07 -5.52532129658541e-07 -2.14504097627749e-05 6.00911667417316e-05 1.09322817374209e-05 -1.80707424495442e-07 2.04326585413719e-05 -2.55117993124542e-06 2.07099174897136e-07 1.09322817374209e-05 8.48223187462396e-05 1377 1376 0 12 0 1400 1422 0 23 0 0 0 0 0 0 1 7 0 406 0 140 118 0 0 2170 +342 385 0.988971255051509 0.00989236718423197 0.147776851209301 -0.0527060083941026 -0.0290954734136719 0.991301062202672 0.128357537771213 -0.0182678505327595 -0.14522158967825 -0.131241552670434 0.980656078726877 -0.00127953083556008 8.24533936419262e-05 5.35905947208861e-06 -1.45679489146454e-05 2.48410028295645e-06 -2.01311712514062e-05 -2.08613052675541e-05 5.35905947208861e-06 5.56809552598134e-05 -5.5777669709759e-06 1.23038766132244e-05 1.281326272439e-05 1.77891553803081e-05 -1.45679489146454e-05 -5.5777669709759e-06 1.49717221718973e-05 1.94113889673132e-06 3.43681669411106e-06 2.76801456068801e-06 2.48410028295645e-06 1.23038766132244e-05 1.94113889673132e-06 4.30816916355891e-05 -1.31044297132242e-05 3.37427645732529e-06 -2.01311712514062e-05 1.281326272439e-05 3.43681669411106e-06 -1.31044297132242e-05 5.69607886943583e-05 1.60258262453113e-05 -2.08613052675541e-05 1.77891553803081e-05 2.76801456068801e-06 3.37427645732529e-06 1.60258262453113e-05 8.53295605024815e-05 1638 1637 0 13 9 1595 1605 0 22 0 0 0 0 0 0 0 5 0 417 0 144 129 0 0 2173 +342 378 0.98947774557383 0.0100365915070366 0.144336612974851 -0.0495420265715742 -0.0287779368808301 0.991311183055454 0.128350959085155 -0.0142600986808064 -0.141794292420443 -0.131154127575601 0.981169186968725 0.00915994109478764 7.44502830724888e-05 1.16297124459522e-05 -1.21467796660032e-05 -2.94899622304552e-06 -1.68672936918828e-07 -1.51254971758799e-05 1.16297124459522e-05 5.80615624866115e-05 -7.26630055510879e-06 1.84782242296646e-05 7.1424703834458e-06 3.67314579722671e-05 -1.21467796660032e-05 -7.26630055510879e-06 1.32620800854973e-05 7.00880747121151e-07 9.050944091835e-07 -1.96744707141414e-07 -2.94899622304552e-06 1.84782242296646e-05 7.00880747121151e-07 5.29298098069192e-05 -2.15429799834132e-05 1.94297792024955e-05 -1.68672936918828e-07 7.1424703834458e-06 9.050944091835e-07 -2.15429799834132e-05 6.3645680680775e-05 1.29544716415553e-06 -1.51254971758799e-05 3.67314579722671e-05 -1.96744707141414e-07 1.94297792024955e-05 1.29544716415553e-06 9.41387975607073e-05 1308 1306 0 14 2 1333 1351 0 23 0 0 0 0 0 0 0 5 0 445 0 141 119 0 0 2182 +343 346 0.999891918423208 0.0138876105432733 -0.00482553057752073 -0.0126240964079971 -0.0138697239204141 0.999896888749368 0.00372056819666978 -0.0110936019581843 0.00487670281314295 -0.0036532372949128 0.999981435641152 0.0139098566635234 0.000216853154037685 -0.000128553843645469 -2.61499083813296e-05 -5.54907617983605e-05 -5.46722784014205e-05 5.03946565240494e-06 -0.000128553843645469 0.0002763453726425 -1.38852411155988e-06 0.000115305349525756 6.2466367028977e-05 8.36749641961418e-05 -2.61499083813296e-05 -1.38852411155988e-06 2.27234929566276e-05 8.33703433099387e-06 1.86850508238831e-06 -1.21461994831325e-05 -5.54907617983605e-05 0.000115305349525756 8.33703433099387e-06 9.55094732129115e-05 9.88022009361732e-06 5.75518005724176e-05 -5.46722784014205e-05 6.2466367028977e-05 1.86850508238831e-06 9.88022009361732e-06 7.9272775424084e-05 1.83169589234179e-05 5.03946565240494e-06 8.36749641961418e-05 -1.21461994831325e-05 5.75518005724176e-05 1.83169589234179e-05 0.000114277058495723 1620 1617 0 12 23 1624 1629 0 21 0 0 0 0 0 0 1 9 0 278 0 108 83 0 0 3119 +342 404 0.987345462190717 0.0126461098769894 0.158079139029725 -0.0467887262438742 -0.0316317139263082 0.992489372573194 0.118170554722201 -0.0103767970274475 -0.155397467693281 -0.12167547507303 0.980329896412564 0.0181340855888522 0.000190842870818457 0.000102283101163981 -3.26143884638821e-05 3.98291339589335e-05 -4.09401630514227e-05 9.65728324659559e-05 0.000102283101163981 0.00015284906681197 -1.92176321868793e-05 5.15048086799211e-05 -1.93763299717974e-05 0.000136795883009581 -3.26143884638821e-05 -1.92176321868793e-05 1.75017704429805e-05 -3.20186675056207e-06 1.08615150080947e-05 -1.89433306899067e-05 3.98291339589335e-05 5.15048086799211e-05 -3.20186675056207e-06 6.22136961417034e-05 -1.85179741789454e-05 5.127127335724e-05 -4.09401630514227e-05 -1.93763299717974e-05 1.08615150080947e-05 -1.85179741789454e-05 5.79897021848924e-05 -8.97753826262552e-06 9.65728324659559e-05 0.000136795883009581 -1.89433306899067e-05 5.127127335724e-05 -8.97753826262552e-06 0.000228942237460653 1397 1400 0 13 2 1418 1437 0 25 0 0 0 0 0 0 1 6 0 225 0 113 115 0 0 1755 +342 380 0.989140278739691 0.0096221588849363 0.146659207120317 -0.0524389323274191 -0.0286309087101815 0.991353202081025 0.12805896997137 -0.0165261505832672 -0.144158870837685 -0.130867271623168 0.980862873788539 -0.00150023894620671 5.50897401280471e-05 2.22031916348608e-05 -8.78550620321761e-06 1.76385399064943e-06 -1.13785568100442e-07 4.60113119082509e-06 2.22031916348608e-05 4.52606146887874e-05 -8.73293701611756e-06 5.56985054801762e-06 2.15277379377674e-06 2.4049175998251e-05 -8.78550620321761e-06 -8.73293701611756e-06 1.33576117384246e-05 1.94414797355726e-06 2.20901743989539e-06 -2.48839973959667e-06 1.76385399064943e-06 5.56985054801762e-06 1.94414797355726e-06 4.84801633877229e-05 -1.31781925267218e-05 -2.17779689860251e-06 -1.13785568100442e-07 2.15277379377674e-06 2.20901743989539e-06 -1.31781925267218e-05 4.85453673001505e-05 1.14463141258392e-05 4.60113119082509e-06 2.4049175998251e-05 -2.48839973959667e-06 -2.17779689860251e-06 1.14463141258392e-05 9.8857375756731e-05 1644 1646 0 13 12 1652 1681 0 27 0 0 0 0 0 0 1 9 0 436 0 146 123 0 0 2192 +342 395 0.988147164290591 0.0120518274636282 0.153035731642161 -0.0444035054711764 -0.030871664835661 0.992147421413598 0.121204102622904 -0.0146874077384295 -0.150373275600218 -0.124491958122345 0.980759721006183 0.0128994146552757 0.000185859499861138 0.000104984321804205 -2.9661175350041e-05 2.36457643839635e-05 -3.0421129775802e-05 0.000105204936662454 0.000104984321804205 0.000139792799125695 -1.9560119587649e-05 4.05089088632658e-05 -1.51896594662611e-05 0.000122367271716032 -2.9661175350041e-05 -1.9560119587649e-05 1.7001264320937e-05 -3.27753404899582e-07 7.53629222728718e-06 -1.90465237802772e-05 2.36457643839635e-05 4.05089088632658e-05 -3.27753404899582e-07 5.79301639782303e-05 -1.56833397087562e-05 5.70613604528766e-05 -3.0421129775802e-05 -1.51896594662611e-05 7.53629222728718e-06 -1.56833397087562e-05 5.82676985399012e-05 -2.85395811795954e-05 0.000105204936662454 0.000122367271716032 -1.90465237802772e-05 5.70613604528766e-05 -2.85395811795954e-05 0.000243373937588309 1579 1581 0 17 9 1597 1624 0 27 0 0 0 0 0 0 0 7 0 239 0 137 120 0 0 1897 +343 397 0.987197530908425 0.017043407151578 0.158589272149711 -0.0501365194079673 -0.0363741379250692 0.992131358140616 0.119801044587535 -0.0219108151794551 -0.155299571984335 -0.124035843475675 0.980049566335683 0.00679904670397246 0.000148785516065142 2.41297808414016e-05 -2.55350996037123e-05 1.15713209014214e-06 -2.01359507586414e-05 -2.760879842676e-06 2.41297808414016e-05 8.56642864495056e-05 -7.29678563188603e-06 2.01631575775859e-05 4.09054548598149e-06 5.67241439621222e-05 -2.55350996037123e-05 -7.29678563188603e-06 1.70137681495644e-05 5.14295179344892e-06 6.2391687674898e-06 4.37055892786489e-07 1.15713209014214e-06 2.01631575775859e-05 5.14295179344892e-06 5.96237333631797e-05 -2.63138981896845e-05 1.76631302628719e-05 -2.01359507586414e-05 4.09054548598149e-06 6.2391687674898e-06 -2.63138981896845e-05 6.12742133399228e-05 8.67184689929468e-06 -2.760879842676e-06 5.67241439621222e-05 4.37055892786489e-07 1.76631302628719e-05 8.67184689929468e-06 0.000144738916678985 1675 1680 0 20 10 1631 1641 0 33 0 0 0 0 0 0 0 6 0 245 0 142 135 0 0 1751 +342 383 0.988440202831794 0.0101159864760956 0.151273369247391 -0.0496154840154034 -0.0295762004592774 0.991467671642831 0.126953158501613 -0.0165518310510293 -0.148698398754778 -0.129959697232482 0.980305698903667 0.0011980851956033 7.85437814019887e-05 3.33932862469125e-05 -1.38295527345668e-05 2.24095940089243e-06 6.07965894404989e-06 1.54132574514638e-05 3.33932862469125e-05 6.63248133526303e-05 -1.0843355414641e-05 1.3716791432173e-05 5.78649344250156e-06 3.99946157110327e-05 -1.38295527345668e-05 -1.0843355414641e-05 1.52498771098024e-05 -1.61474608364863e-08 4.35049354827534e-07 -2.03273760000929e-06 2.24095940089243e-06 1.3716791432173e-05 -1.61474608364863e-08 4.64120944381728e-05 -8.11628708330602e-06 1.00179394108697e-05 6.07965894404989e-06 5.78649344250156e-06 4.35049354827534e-07 -8.11628708330602e-06 4.03796194110563e-05 -1.50729087419099e-06 1.54132574514638e-05 3.99946157110327e-05 -2.03273760000929e-06 1.00179394108697e-05 -1.50729087419099e-06 0.000116882031051142 1706 1706 0 13 12 1707 1737 0 27 1 0 0 0 0 0 1 8 0 424 0 145 124 0 0 2174 +343 345 0.999811923759893 0.0193936841198428 -4.60847301974935e-05 -0.00575396192655965 -0.01939299598558 0.999791601420842 0.00637694558945126 -0.00696104212341304 0.000169747594616442 -0.00637485251651371 0.999979666013838 0.0154707645448735 5.35263119525147e-05 3.17531709812263e-06 -1.97188951279789e-06 1.51789554048885e-06 -1.65964541950511e-07 8.25707553585428e-06 3.17531709812263e-06 3.82468114498143e-05 -4.63624797504807e-06 3.89309721588524e-06 2.96353515968164e-06 -1.32857952181677e-07 -1.97188951279789e-06 -4.63624797504807e-06 1.44812516566239e-05 5.2392835239968e-06 2.8611316167722e-08 -3.23345461703247e-06 1.51789554048885e-06 3.89309721588524e-06 5.2392835239968e-06 3.60728464905591e-05 -7.09534450928333e-06 1.76385428780261e-05 -1.65964541950511e-07 2.96353515968164e-06 2.8611316167722e-08 -7.09534450928333e-06 4.33856774507804e-05 2.55197264562804e-07 8.25707553585428e-06 -1.32857952181677e-07 -3.23345461703247e-06 1.76385428780261e-05 2.55197264562804e-07 5.39404037393429e-05 1807 1807 0 21 26 1784 1790 0 22 3 0 0 0 0 0 1 4 0 264 0 97 85 0 0 3147 +343 408 0.988443517141111 0.0161289708826514 0.150729126979418 -0.0540612717922701 -0.0353460240941675 0.991438420888275 0.125700104086264 -0.020917444488778 -0.147411234315589 -0.129575128341938 0.980550974765068 -0.0117733639455945 7.88863077539062e-05 8.542952516685e-07 -1.36229291182656e-05 -9.85319809067213e-06 -3.00112440629335e-06 -1.71146992779653e-05 8.542952516685e-07 6.06809371025604e-05 -2.56421456633602e-07 9.43061497018273e-06 6.95264964153796e-06 3.00757470327411e-05 -1.36229291182656e-05 -2.56421456633602e-07 1.37293806859256e-05 7.41044172702002e-06 5.20739969400534e-06 4.12468798212359e-06 -9.85319809067213e-06 9.43061497018273e-06 7.41044172702002e-06 3.15307313702537e-05 -3.26806986665556e-06 1.10787035119442e-05 -3.00112440629335e-06 6.95264964153796e-06 5.20739969400534e-06 -3.26806986665556e-06 3.6925694882804e-05 8.47372081630529e-06 -1.71146992779653e-05 3.00757470327411e-05 4.12468798212359e-06 1.10787035119442e-05 8.47372081630529e-06 0.000101395885100831 1675 1683 0 20 1 1693 1714 0 35 0 0 0 0 0 0 1 6 0 286 0 128 137 0 0 1656 +343 389 0.988233365401106 0.0161176966323972 0.152102055749654 -0.0565817108054871 -0.0349897736880559 0.991885066384532 0.122228191595115 -0.0199775838965248 -0.148897720752412 -0.1261119936351 0.980777871801825 -0.00852826768771381 8.69471901489745e-05 1.03415741169897e-05 -1.27861924979863e-05 -7.10164433113484e-06 -1.24517532767394e-05 -1.3381361506401e-05 1.03415741169897e-05 7.15815808578165e-05 -1.33894767789129e-06 1.4775068525096e-05 1.12934761597167e-06 2.89420936522584e-05 -1.27861924979863e-05 -1.33894767789129e-06 1.40829680910089e-05 5.51837396202103e-06 7.26227331241144e-06 5.00984937305284e-06 -7.10164433113484e-06 1.4775068525096e-05 5.51837396202103e-06 5.10587240672394e-05 -1.89184677692449e-05 1.70493640362158e-05 -1.24517532767394e-05 1.12934761597167e-06 7.26227331241144e-06 -1.89184677692449e-05 5.03300260060082e-05 -5.13099737357492e-06 -1.3381361506401e-05 2.89420936522584e-05 5.00984937305284e-06 1.70493640362158e-05 -5.13099737357492e-06 9.83531007117739e-05 1652 1654 0 22 12 1601 1609 0 35 0 0 0 0 0 0 0 7 0 301 0 145 132 0 0 1974 +343 339 0.998626418445492 -0.0498670768540811 -0.0160795220314228 -0.0418993237754916 0.049878560290094 0.998755240704223 0.000313670586134036 0.00379594587444718 0.0160438650616769 -0.00111526314308295 0.99987066692748 -0.0345011882406465 6.24326102310895e-05 1.57085414961876e-05 -1.25895525701979e-05 5.85880780917281e-06 5.74408007948086e-06 2.86983086551313e-05 1.57085414961876e-05 5.63601378993597e-05 -1.08799071378935e-05 1.46358607017845e-05 2.90047428695964e-06 2.23031672119879e-05 -1.25895525701979e-05 -1.08799071378935e-05 1.57600883429524e-05 4.56692701308015e-07 1.71934332689611e-06 -1.09026366102084e-05 5.85880780917281e-06 1.46358607017845e-05 4.56692701308015e-07 4.39118631342327e-05 -5.62027995139424e-06 2.3395020399187e-05 5.74408007948086e-06 2.90047428695964e-06 1.71934332689611e-06 -5.62027995139424e-06 4.18271355469052e-05 -4.84793534591474e-06 2.86983086551313e-05 2.23031672119879e-05 -1.09026366102084e-05 2.3395020399187e-05 -4.84793534591474e-06 8.58730859014788e-05 1727 1701 0 1 110 1733 1718 0 0 93 0 0 0 0 0 71 70 0 399 0 22 21 0 0 2919 +343 411 0.989018946750809 0.0171072934545495 0.146795311500672 -0.0599834238759227 -0.0351999896964083 0.991960356960941 0.121554970870366 -0.0166134121861216 -0.143535653038861 -0.12538736271484 0.9816697640134 -0.0126082616025647 0.000128850225099167 1.95905961001331e-05 -2.38453808242379e-05 3.09919842643213e-07 -2.55893285636529e-05 -1.12982529775825e-05 1.95905961001331e-05 8.18083671367754e-05 -3.63934134842324e-06 3.09565911141132e-05 -7.54591150838833e-06 4.90119526262891e-05 -2.38453808242379e-05 -3.63934134842324e-06 1.55308873288174e-05 5.97573323203561e-06 7.48710271885118e-06 6.25913152493595e-06 3.09919842643213e-07 3.09565911141132e-05 5.97573323203561e-06 5.49795397852015e-05 -1.53737279064387e-05 2.32769050445849e-05 -2.55893285636529e-05 -7.54591150838833e-06 7.48710271885118e-06 -1.53737279064387e-05 5.33001140621289e-05 -6.77497332991891e-06 -1.12982529775825e-05 4.90119526262891e-05 6.25913152493595e-06 2.32769050445849e-05 -6.77497332991891e-06 0.000130927902397039 1662 1669 0 22 4 1621 1631 0 37 0 0 0 0 0 0 0 6 0 331 0 97 109 0 0 1627 +343 409 0.98824214410848 0.017245046209439 0.151921272339029 -0.0566945727288873 -0.0354897394369167 0.992353692680589 0.118214326618642 -0.019801838715046 -0.148721024077212 -0.122216025972184 0.981297763165183 -0.00601305279809818 9.759719061925e-05 5.18546593601249e-05 -1.19884066231816e-05 1.40199975702031e-05 -1.98772385302667e-05 2.18025580987755e-05 5.18546593601249e-05 0.000125038529735019 -7.81068813252728e-06 2.21652222333318e-05 -3.96243396348786e-06 8.85383015802111e-05 -1.19884066231816e-05 -7.81068813252728e-06 1.29725768262312e-05 1.16842205377462e-06 9.09104080441536e-06 -3.32948666334618e-06 1.40199975702031e-05 2.21652222333318e-05 1.16842205377462e-06 4.77533703791553e-05 -1.0778840683842e-05 2.55732258450866e-05 -1.98772385302667e-05 -3.96243396348786e-06 9.09104080441536e-06 -1.0778840683842e-05 4.57822357749991e-05 -1.20691495889835e-05 2.18025580987755e-05 8.85383015802111e-05 -3.32948666334618e-06 2.55732258450866e-05 -1.20691495889835e-05 0.000161872234574835 1630 1632 0 18 1 1606 1612 0 31 0 0 0 0 0 0 0 4 0 290 0 116 130 0 0 1564 +343 404 0.987706967565419 0.0168338825356898 0.155407743119508 -0.0582029419885912 -0.0360345641337685 0.991928019317567 0.121574317519852 -0.0116890853958184 -0.152106727038661 -0.125679850777693 0.980340817623179 0.0040350121175341 0.000156474043995109 5.62274891715522e-05 -2.36993389444481e-05 1.21652334757382e-05 -2.65682400832525e-05 2.86375428161343e-05 5.62274891715522e-05 9.85112107315692e-05 -9.892100801959e-06 2.67164071136205e-05 -5.82415423457199e-06 7.5877699309832e-05 -2.36993389444481e-05 -9.892100801959e-06 1.63912810781151e-05 1.91006523968564e-06 8.49348830471174e-06 -4.67497361164361e-06 1.21652334757382e-05 2.67164071136205e-05 1.91006523968564e-06 6.15308679227683e-05 -1.82109762367043e-05 2.41480688688212e-05 -2.65682400832525e-05 -5.82415423457199e-06 8.49348830471174e-06 -1.82109762367043e-05 6.50406145001072e-05 3.82959342560231e-06 2.86375428161343e-05 7.5877699309832e-05 -4.67497361164361e-06 2.41480688688212e-05 3.82959342560231e-06 0.000149707508239282 1528 1533 0 19 1 1510 1520 0 33 0 0 0 0 0 0 0 8 0 237 0 123 134 0 0 1675 +343 406 0.98863765051252 0.015333112302304 0.149534249107722 -0.0540842038272708 -0.0349449324287417 0.990973534055817 0.129422975156944 -0.0177839410940016 -0.146200026288083 -0.133177890312353 0.980249561002358 -0.0124354324609467 8.74005640918072e-05 1.24167582365772e-05 -1.24051044448822e-05 1.08195244397142e-05 -2.55679254923165e-05 -1.53470152128324e-05 1.24167582365772e-05 7.49336563327955e-05 -2.37169453945291e-06 1.83120965988962e-05 -3.14525007705842e-06 4.57614610925087e-05 -1.24051044448822e-05 -2.37169453945291e-06 1.35403450943155e-05 1.98140827698944e-06 8.3917452008809e-06 3.10866954284986e-06 1.08195244397142e-05 1.83120965988962e-05 1.98140827698944e-06 4.62063122380669e-05 -2.09152224419362e-05 7.96109588387929e-06 -2.55679254923165e-05 -3.14525007705842e-06 8.3917452008809e-06 -2.09152224419362e-05 5.71753705278298e-05 1.35067725563585e-05 -1.53470152128324e-05 4.57614610925087e-05 3.10866954284986e-06 7.96109588387929e-06 1.35067725563585e-05 0.000128447084577381 1848 1856 0 20 2 1824 1835 0 31 0 0 0 0 0 0 0 5 0 264 0 97 104 0 0 1672 +343 387 0.988766307219552 0.0146886541773902 0.148746203803213 -0.0606707295793317 -0.0343297445315567 0.99087314286351 0.130352918617835 -0.0170453014932979 -0.145473909508915 -0.133994993153651 0.980246236137607 -0.0105333062817825 7.37000652644151e-05 3.46698349515831e-07 -1.21748105504761e-05 -5.8842623374081e-06 -1.31615667303651e-05 -2.3465888924732e-05 3.46698349515831e-07 8.39086470761851e-05 -3.78878610136556e-06 2.92324354231836e-05 4.59360329154354e-06 6.10317291168447e-05 -1.21748105504761e-05 -3.78878610136556e-06 1.36723815611934e-05 2.76680532495597e-06 1.55566454130902e-06 1.97338010538166e-06 -5.8842623374081e-06 2.92324354231836e-05 2.76680532495597e-06 5.76884405343107e-05 -2.30793670483247e-06 3.10426452185302e-05 -1.31615667303651e-05 4.59360329154354e-06 1.55566454130902e-06 -2.30793670483247e-06 5.63546915982013e-05 1.06572116059458e-05 -2.3465888924732e-05 6.10317291168447e-05 1.97338010538166e-06 3.10426452185302e-05 1.06572116059458e-05 0.000131955810854394 1716 1722 0 21 0 1726 1744 0 31 0 0 0 0 0 0 0 6 0 421 0 182 168 0 0 2104 +343 405 0.987953243935863 0.0152441314622842 0.154000013807032 -0.0547144443585694 -0.0357580909156661 0.990693383860739 0.131331557931159 -0.0118179345446102 -0.15056475925884 -0.135256185183965 0.979303843369773 -0.00657093035327544 7.15249689548324e-05 -1.85858693367234e-07 -9.18404624915806e-06 -2.6781946951678e-07 -1.21908184581927e-05 -3.6219010214899e-05 -1.85858693367234e-07 6.51334808182784e-05 2.31540613589195e-06 1.09879788687035e-05 1.08957731604916e-05 3.80132319950338e-05 -9.18404624915806e-06 2.31540613589195e-06 1.37223152427045e-05 5.68658825001042e-06 3.92172852313377e-06 7.23896146631504e-06 -2.6781946951678e-07 1.09879788687035e-05 5.68658825001042e-06 4.21562237273425e-05 -1.14842013738269e-05 5.83423599645329e-06 -1.21908184581927e-05 1.08957731604916e-05 3.92172852313377e-06 -1.14842013738269e-05 5.69111471132401e-05 2.02513778949814e-05 -3.6219010214899e-05 3.80132319950338e-05 7.23896146631504e-06 5.83423599645329e-06 2.02513778949814e-05 0.000106152135710192 1681 1687 0 20 1 1687 1708 0 31 0 0 0 0 0 0 0 6 0 243 0 130 138 0 0 1694 +343 388 0.986985907373631 0.0158307692147509 0.160025639795378 -0.047767086489738 -0.0358111938148893 0.991790384964509 0.12275744657455 -0.0245483926046979 -0.156768546090736 -0.126890578996316 0.979450051773227 -0.00423104735036567 0.000103311763758842 1.60350220176151e-05 -1.56123686978327e-05 -5.21844780277019e-06 -7.24880833939711e-06 -1.16140859232837e-05 1.60350220176151e-05 9.58162058137247e-05 -1.34919929317046e-06 1.8653772937068e-05 4.90409731362566e-07 6.49031405775725e-05 -1.56123686978327e-05 -1.34919929317046e-06 1.52556476602607e-05 6.09906530082999e-06 5.08139522939294e-06 2.94555064884635e-06 -5.21844780277019e-06 1.8653772937068e-05 6.09906530082999e-06 4.73670729288957e-05 -1.46871986133812e-05 1.87558948628004e-05 -7.24880833939711e-06 4.90409731362566e-07 5.08139522939294e-06 -1.46871986133812e-05 3.88647887504544e-05 1.12260978451888e-07 -1.16140859232837e-05 6.49031405775725e-05 2.94555064884635e-06 1.87558948628004e-05 1.12260978451888e-07 0.000133158973591704 1737 1749 0 22 0 1718 1732 0 32 0 0 0 0 0 0 0 6 0 423 0 138 124 0 0 2039 +343 396 0.987848999983038 0.0160123199925487 0.15458964661635 -0.0514265694373469 -0.0354648278161319 0.991659560500242 0.123909491389642 -0.0252903250546398 -0.151316222595213 -0.12788636235707 0.980177779335255 -0.000686859869461576 0.000146400095676505 4.67029355139729e-05 -2.4290793752051e-05 1.54307279539302e-05 -3.80077150783174e-05 1.45822211094042e-05 4.67029355139729e-05 0.000107920248641671 -9.38561329672625e-06 2.16502525805231e-05 -1.22209272023095e-05 7.20874661230678e-05 -2.4290793752051e-05 -9.38561329672625e-06 1.54243111481253e-05 6.29288209734925e-07 1.10518541902952e-05 -3.45829037702963e-06 1.54307279539302e-05 2.16502525805231e-05 6.29288209734925e-07 5.50512305971475e-05 -1.72822114321693e-05 1.96139878155341e-05 -3.80077150783174e-05 -1.22209272023095e-05 1.10518541902952e-05 -1.72822114321693e-05 5.49794960434101e-05 -2.8236866499005e-06 1.45822211094042e-05 7.20874661230678e-05 -3.45829037702963e-06 1.96139878155341e-05 -2.8236866499005e-06 0.000146750567649094 1429 1436 0 23 1 1410 1419 0 38 0 0 0 0 0 0 0 5 0 254 0 166 160 0 0 1834 +343 407 0.987381471546731 0.0166039552672732 0.157486946493021 -0.0563895875792217 -0.0362787366708253 0.991756743228352 0.122891885520006 -0.0171801460018078 -0.154148249785011 -0.127054598226809 0.979844603066038 -0.00514729995186453 9.2997425627985e-05 3.77069829692459e-05 -1.1066291039801e-05 -8.94886372072907e-07 -9.87284263125227e-06 -5.14484779590778e-06 3.77069829692459e-05 8.28713566753236e-05 -6.01920769612781e-06 2.05213250755309e-05 1.05258470097065e-06 3.71371173851063e-05 -1.1066291039801e-05 -6.01920769612781e-06 1.26141902001353e-05 3.71253860916742e-06 7.20755132812481e-06 1.65819959124616e-06 -8.94886372072907e-07 2.05213250755309e-05 3.71253860916742e-06 5.92238275508907e-05 -1.75796152822556e-05 1.44455053742113e-05 -9.87284263125227e-06 1.05258470097065e-06 7.20755132812481e-06 -1.75796152822556e-05 4.652634285928e-05 2.70207796991727e-06 -5.14484779590778e-06 3.71371173851063e-05 1.65819959124616e-06 1.44455053742113e-05 2.70207796991727e-06 0.000107295415234744 1525 1531 0 22 1 1499 1510 0 33 0 0 0 0 0 0 0 7 0 267 0 125 139 0 0 1597 +343 386 0.988261253095579 0.0141323922961451 0.152118280025592 -0.0545267727778926 -0.0344891697472349 0.990645586340336 0.132029615747977 -0.0184521025582962 -0.148829408384577 -0.135726186686284 0.979504063007141 -0.00408226977036081 8.54864375369871e-05 3.35991231945213e-05 -1.2814149784814e-05 8.01555726977738e-06 -1.88270864141532e-05 -7.37785114340064e-06 3.35991231945213e-05 6.18688205654416e-05 -9.53329762794664e-06 1.35279749583777e-05 -2.2031483184163e-06 3.18246581683888e-05 -1.2814149784814e-05 -9.53329762794664e-06 1.29604198642794e-05 -3.39603419977768e-07 3.9132323374719e-06 1.9478565269483e-06 8.01555726977738e-06 1.35279749583777e-05 -3.39603419977768e-07 4.19590019593365e-05 -3.3632146351366e-06 1.34003835086835e-05 -1.88270864141532e-05 -2.2031483184163e-06 3.9132323374719e-06 -3.3632146351366e-06 5.33059905779529e-05 4.51128024298874e-07 -7.37785114340064e-06 3.18246581683888e-05 1.9478565269483e-06 1.34003835086835e-05 4.51128024298874e-07 0.000114222192427373 1663 1666 0 16 0 1652 1659 0 27 0 0 0 0 0 0 0 7 0 420 0 152 142 0 0 2106 +343 382 0.987878770898346 0.0141758782184599 0.154578712910636 -0.0558542728439384 -0.0347267459317101 0.99076451532616 0.131071462521459 -0.017800395962471 -0.151293050486029 -0.134850730985246 0.979247513771353 -0.00768549951725934 7.92215907835769e-05 -4.39036037868849e-06 -1.09569828684605e-05 6.16085307540126e-06 -2.63680852222811e-05 -3.1676302654367e-05 -4.39036037868849e-06 5.80080529580542e-05 -3.92308439417937e-06 7.92238988456365e-06 1.5288413452356e-05 1.72849118508915e-05 -1.09569828684605e-05 -3.92308439417937e-06 1.24799652093836e-05 1.31896197731507e-07 6.58911642024984e-06 4.67483149713322e-06 6.16085307540126e-06 7.92238988456365e-06 1.31896197731507e-07 4.63625262125887e-05 -1.84234502236993e-05 3.31169306921514e-06 -2.63680852222811e-05 1.5288413452356e-05 6.58911642024984e-06 -1.84234502236993e-05 6.19467037065397e-05 1.29308753235923e-05 -3.1676302654367e-05 1.72849118508915e-05 4.67483149713322e-06 3.31169306921514e-06 1.29308753235923e-05 0.000109067999174327 1730 1734 0 15 1 1706 1713 0 29 0 0 0 0 0 0 0 8 0 442 0 137 122 0 0 2142 +343 390 0.986902636495816 0.0161537201366619 0.160506209859165 -0.0488888464492695 -0.0361773793838227 0.991793228015551 0.122627036510765 -0.0197024831092309 -0.15720808916378 -0.126827639685677 0.979387750849087 0.0077831838206181 0.000136205427207147 2.87709608190541e-05 -2.24034841688377e-05 4.3274181811141e-06 -2.26644205022472e-05 -7.23363071883677e-06 2.87709608190541e-05 9.28176498774451e-05 -1.26902857654131e-05 2.26308425003653e-05 8.41548703343012e-06 4.92050752756367e-05 -2.24034841688377e-05 -1.26902857654131e-05 1.7666863257859e-05 5.0494622193373e-06 7.4054723971018e-06 -2.22710097702755e-06 4.3274181811141e-06 2.26308425003653e-05 5.0494622193373e-06 4.85444294877041e-05 -3.9260605339755e-06 1.76768949483006e-05 -2.26644205022472e-05 8.41548703343012e-06 7.4054723971018e-06 -3.9260605339755e-06 4.60001980925541e-05 1.179569772633e-05 -7.23363071883677e-06 4.92050752756367e-05 -2.22710097702755e-06 1.76768949483006e-05 1.179569772633e-05 0.000138828349292253 1575 1582 0 23 12 1529 1539 0 32 0 0 0 0 0 0 0 5 0 203 0 145 131 0 0 1823 +343 378 0.988347354660332 0.0145393166675909 0.151519354561599 -0.0501034608576868 -0.0345798045660603 0.990847400679268 0.130482434386058 -0.0203565309485536 -0.148235433186864 -0.134201478523817 0.979804174062309 -0.000632058101735314 5.91126417260771e-05 -3.09418052393361e-06 -8.53600900633271e-06 -6.63502813248701e-08 -3.69998191465956e-06 -3.77482839184555e-05 -3.09418052393361e-06 6.49170091624318e-05 -3.88977014853421e-06 1.79920322921594e-05 1.06579243176897e-05 6.06479200916905e-05 -8.53600900633271e-06 -3.88977014853421e-06 1.24577566813652e-05 1.03027522450383e-06 4.0138897539999e-07 4.68843350105824e-06 -6.63502813248701e-08 1.79920322921594e-05 1.03027522450383e-06 4.01890703267794e-05 -4.14487145188193e-06 1.76442511300814e-05 -3.69998191465956e-06 1.06579243176897e-05 4.0138897539999e-07 -4.14487145188193e-06 4.18605786685154e-05 1.67314300060128e-05 -3.77482839184555e-05 6.06479200916905e-05 4.68843350105824e-06 1.76442511300814e-05 1.67314300060128e-05 0.000124581541593993 1719 1723 0 19 0 1706 1713 0 33 0 0 0 0 0 0 0 5 0 446 0 160 150 0 0 2078 +343 381 0.988355559327553 0.0148911174024474 0.151431644542434 -0.0559581762172477 -0.0346686223067512 0.991062250487131 0.128816545081507 -0.018213637203616 -0.148159964139006 -0.132566474954608 0.980038139433582 -0.0119358092513512 7.66393402759153e-05 1.42011846497032e-05 -1.45389733729998e-05 3.22639542319434e-06 1.54405739615597e-06 -2.47276054497558e-05 1.42011846497032e-05 8.39886418790466e-05 -1.03041335497286e-05 2.53489782017009e-05 1.22575761234525e-06 5.38984079261968e-05 -1.45389733729998e-05 -1.03041335497286e-05 1.53301823325272e-05 -1.58726658002638e-06 1.25175671704071e-06 4.49369631122563e-06 3.22639542319434e-06 2.53489782017009e-05 -1.58726658002638e-06 5.41318624032093e-05 -1.31804260745336e-05 2.30236167965477e-05 1.54405739615597e-06 1.22575761234525e-06 1.25175671704071e-06 -1.31804260745336e-05 4.41120046761515e-05 -3.7764926923043e-06 -2.47276054497558e-05 5.38984079261968e-05 4.49369631122563e-06 2.30236167965477e-05 -3.7764926923043e-06 0.000137482016034354 1852 1856 0 17 0 1828 1836 0 28 0 0 0 0 0 0 0 5 0 427 0 135 119 0 0 2122 +344 346 0.999735260749935 -0.000495244383113105 0.0230035463844244 -0.00444103470611333 -0.00011431438194444 0.99964908247581 0.0264895986661255 0.0114589182296589 -0.0230085928618299 -0.0264852154658276 0.999384379513832 0.00576049294278385 3.96096142521579e-05 -1.78852060980663e-06 -5.97427118864029e-06 2.40576350974885e-07 -2.60727144423562e-06 5.18697674359191e-06 -1.78852060980663e-06 2.88230560698841e-05 -4.53594469697667e-06 6.93223814566003e-06 4.63876360638186e-06 -3.99550347921094e-06 -5.97427118864029e-06 -4.53594469697667e-06 1.64510926376881e-05 5.97536775204104e-06 1.27218866578532e-06 -1.49590890046213e-06 2.40576350974885e-07 6.93223814566003e-06 5.97536775204104e-06 3.73773013275965e-05 -5.04730603156119e-06 7.07971432717578e-06 -2.60727144423562e-06 4.63876360638186e-06 1.27218866578532e-06 -5.04730603156119e-06 4.03864389770647e-05 2.59091102163623e-06 5.18697674359191e-06 -3.99550347921094e-06 -1.49590890046213e-06 7.07971432717578e-06 2.59091102163623e-06 4.53076887045506e-05 1757 1727 0 1 62 1735 1737 0 12 42 0 0 0 0 0 4 11 0 332 0 71 39 0 0 3184 +343 385 0.988244281003867 0.0139389102764138 0.152246339343368 -0.0568788473780936 -0.0341776920728257 0.990774532683782 0.131140042511084 -0.0222377585794496 -0.149013846429534 -0.134801825527476 0.979603665472284 -0.0126090261525813 0.000101543787897043 1.81784319202303e-05 -1.51614621362555e-05 4.88945912050137e-06 -2.27838114086316e-05 -2.16023666924453e-06 1.81784319202303e-05 6.76852882971131e-05 -6.94971895504804e-06 2.78527985728988e-05 -2.21935930863841e-07 4.05742091528909e-05 -1.51614621362555e-05 -6.94971895504804e-06 1.35495468904781e-05 1.18195789984185e-06 3.56391768859772e-06 1.21407265626498e-06 4.88945912050137e-06 2.78527985728988e-05 1.18195789984185e-06 5.84044002671321e-05 -1.8156994041939e-05 1.87487079786344e-05 -2.27838114086316e-05 -2.21935930863841e-07 3.56391768859772e-06 -1.8156994041939e-05 6.21934328433648e-05 3.48945939099862e-07 -2.16023666924453e-06 4.05742091528909e-05 1.21407265626498e-06 1.87487079786344e-05 3.48945939099862e-07 0.000110110371039088 1744 1746 0 16 1 1721 1725 0 29 0 0 0 0 0 0 0 4 0 423 0 137 122 0 0 2090 +343 395 0.987977161376186 0.0163304084738726 0.153734987423589 -0.0502727702375537 -0.0358866397213118 0.99146874431251 0.125307135235337 -0.0197512260884319 -0.150377118234682 -0.129317619876221 0.980134519084489 -0.00526055789494505 0.000132331001413413 6.17316932869081e-05 -2.09620327557856e-05 5.16904605565693e-06 -9.67106294751582e-06 2.48337691070904e-05 6.17316932869081e-05 0.000110980595471862 -1.03183527117683e-05 3.13880920324259e-05 -2.45226133115124e-06 6.36737790679426e-05 -2.09620327557856e-05 -1.03183527117683e-05 1.48918975029317e-05 4.40660614969084e-06 4.77064771160652e-06 -5.0675223741773e-06 5.16904605565693e-06 3.13880920324259e-05 4.40660614969084e-06 4.50331576188006e-05 -3.79449851487684e-06 2.71396824097811e-05 -9.67106294751582e-06 -2.45226133115124e-06 4.77064771160652e-06 -3.79449851487684e-06 4.30366880539349e-05 5.22478125371005e-06 2.48337691070904e-05 6.36737790679426e-05 -5.0675223741773e-06 2.71396824097811e-05 5.22478125371005e-06 0.000132194145779981 1624 1631 0 27 0 1632 1650 0 31 0 0 0 0 0 0 0 5 0 237 0 177 165 0 0 1790 +344 410 0.988169761771806 0.00303523314163094 0.153333979533654 -0.0539101551435156 -0.0216564228330826 0.99254748418735 0.119918684880367 -0.0180909962368912 -0.151827274459914 -0.12182068376568 0.980871143288932 -0.0114623360208438 7.79554236336128e-05 3.68341853212301e-05 -1.05671293527909e-05 1.18749737471634e-05 -1.72349606966448e-05 1.93782021780378e-05 3.68341853212301e-05 0.000104071040208643 -7.14898682376184e-06 3.25111269757142e-05 -1.36394679307148e-05 8.53767814172743e-05 -1.05671293527909e-05 -7.14898682376184e-06 1.30950206299705e-05 2.73083560526554e-06 8.08027601954463e-06 -3.77854580849397e-06 1.18749737471634e-05 3.25111269757142e-05 2.73083560526554e-06 5.8624536621871e-05 -1.94709776541793e-05 2.12042089246738e-05 -1.72349606966448e-05 -1.36394679307148e-05 8.08027601954463e-06 -1.94709776541793e-05 5.01619335713072e-05 -2.35542942653663e-06 1.93782021780378e-05 8.53767814172743e-05 -3.77854580849397e-06 2.12042089246738e-05 -2.35542942653663e-06 0.00017167397662038 1715 1714 0 9 22 1692 1707 0 23 16 0 0 0 0 0 4 16 0 300 0 62 67 0 0 1581 +344 347 0.999224629829484 0.00166280293086149 0.0393366779042641 0.00387795155515335 -0.00248646174419049 0.9997784990777 0.0208990499768691 0.00857277571019211 -0.0392932137922744 -0.0209806546216774 0.999007435148268 0.0128203120857803 0.000148662640020995 5.94273001285558e-05 -2.47276240795234e-05 4.02520403995026e-05 -3.84974267411522e-05 8.79039358987975e-05 5.94273001285558e-05 8.80164548629228e-05 -2.34259480107923e-05 2.84773605665613e-05 -8.09303060468535e-06 4.86552313681047e-05 -2.47276240795234e-05 -2.34259480107923e-05 2.62400146322963e-05 -5.03721687267378e-06 4.08737311905199e-06 -2.10067892258404e-05 4.02520403995026e-05 2.84773605665613e-05 -5.03721687267378e-06 6.14581239997646e-05 -4.00069427843985e-05 4.0782849079057e-05 -3.84974267411522e-05 -8.09303060468535e-06 4.08737311905199e-06 -4.00069427843985e-05 8.67069670888664e-05 -2.86557913240694e-05 8.79039358987975e-05 4.86552313681047e-05 -2.10067892258404e-05 4.0782849079057e-05 -2.86557913240694e-05 0.000126886558394384 1617 1602 0 2 59 1588 1605 0 10 36 0 0 0 0 0 3 12 0 318 0 65 34 0 0 3124 +344 348 0.999888143905701 0.00242315814434786 0.0147589966264717 -0.00103666367753732 -0.00248609410554665 0.999987889431634 0.00424739051244254 -0.00509594973339538 -0.0147485257877216 -0.00428360767044571 0.999882058891155 0.000734222968040423 3.6317459275903e-05 6.55741451709924e-06 -8.61290405846737e-06 -3.9840026648654e-06 -2.13462303848678e-06 -6.03949895226414e-06 6.55741451709924e-06 4.12219347177636e-05 -8.67396467688184e-06 1.19278837074799e-05 7.43885492382512e-06 1.61553514138649e-05 -8.61290405846737e-06 -8.67396467688184e-06 1.66378957559853e-05 6.16578245061502e-07 -5.96100746196556e-06 -1.9948836186187e-06 -3.9840026648654e-06 1.19278837074799e-05 6.16578245061502e-07 4.64515911692972e-05 -2.78813523201318e-05 7.96903573287375e-06 -2.13462303848678e-06 7.43885492382512e-06 -5.96100746196556e-06 -2.78813523201318e-05 7.13222760267295e-05 1.63731900506338e-05 -6.03949895226414e-06 1.61553514138649e-05 -1.9948836186187e-06 7.96903573287375e-06 1.63731900506338e-05 5.65844179082726e-05 2046 2016 0 3 58 2015 2027 0 18 22 0 0 0 0 0 4 16 0 327 0 84 59 0 0 3007 +344 398 0.988134856709713 0.00276658085776098 0.153563833586013 -0.0432549954089309 -0.0214672890463594 0.992510984087491 0.120254322029105 -0.0324265688743113 -0.152081098287313 -0.122124086469612 0.980794090035053 -0.0197489301555843 7.0833699623576e-05 1.55189354458197e-05 -1.28821629428972e-05 1.57126313435731e-06 -2.33967258599089e-06 1.39194504617012e-05 1.55189354458197e-05 5.16999858220204e-05 -4.9983233747658e-06 1.05174737386831e-05 7.4603590145328e-07 2.50998172298719e-05 -1.28821629428972e-05 -4.9983233747658e-06 1.54687451928821e-05 3.91750664519877e-06 4.55939886097541e-06 -3.42037215107096e-06 1.57126313435731e-06 1.05174737386831e-05 3.91750664519877e-06 3.83456233449232e-05 -4.2437584374837e-06 1.33903365401111e-05 -2.33967258599089e-06 7.4603590145328e-07 4.55939886097541e-06 -4.2437584374837e-06 4.06376017066013e-05 -1.76375142011442e-06 1.39194504617012e-05 2.50998172298719e-05 -3.42037215107096e-06 1.33903365401111e-05 -1.76375142011442e-06 8.80158081872781e-05 1366 1362 0 11 15 1346 1361 0 25 3 0 0 0 0 0 0 14 0 263 0 115 105 0 0 1722 +344 404 0.985968544721815 0.00497560911143129 0.166857041005516 -0.04595539129518 -0.023714331420204 0.993593065776021 0.110500905548779 -0.0141462800827103 -0.165238189606516 -0.112907320204571 0.979769502352356 0.0109348048000736 0.000163617476174305 6.01437716804192e-05 -2.63816633187219e-05 8.46691484996854e-06 -3.24769527357506e-05 2.37131753282221e-05 6.01437716804192e-05 9.58921894747076e-05 -1.39221288922929e-05 2.62169590623113e-05 -1.90594930351844e-05 4.75363320421613e-05 -2.63816633187219e-05 -1.39221288922929e-05 1.69787123271734e-05 4.50230776254765e-06 8.12447660182836e-06 -6.21048658334946e-06 8.46691484996854e-06 2.62169590623113e-05 4.50230776254765e-06 6.10503656635378e-05 -2.54851029563578e-05 1.63960667465331e-05 -3.24769527357506e-05 -1.90594930351844e-05 8.12447660182836e-06 -2.54851029563578e-05 6.88301477642711e-05 -6.3343956073151e-06 2.37131753282221e-05 4.75363320421613e-05 -6.21048658334946e-06 1.63960667465331e-05 -6.3343956073151e-06 0.000133987161910165 1652 1653 0 9 11 1618 1631 0 23 4 0 0 0 0 0 3 15 0 233 0 86 95 0 0 1704 +344 397 0.987109207093544 0.00391080266992922 0.16000037154217 -0.0456058363042945 -0.0224630173778648 0.993191401912579 0.114307707601928 -0.0240787156215198 -0.158463958430418 -0.116428281742036 0.980476225662387 0.0037222395370563 0.000250298240609049 0.000187715012769163 -4.026463124076e-05 6.38373610027793e-05 -6.44652806187482e-05 0.000174071250731945 0.000187715012769163 0.000223041344138254 -3.55289016977005e-05 8.01536315394543e-05 -5.83961159721628e-05 0.000191508674665492 -4.026463124076e-05 -3.55289016977005e-05 1.86179585895104e-05 -6.02194689721921e-06 1.30328721048767e-05 -3.28361201354654e-05 6.38373610027793e-05 8.01536315394543e-05 -6.02194689721921e-06 8.268576865721e-05 -4.49371879523154e-05 7.28698732612845e-05 -6.44652806187482e-05 -5.83961159721628e-05 1.30328721048767e-05 -4.49371879523154e-05 7.3908626251582e-05 -5.3702772749879e-05 0.000174071250731945 0.000191508674665492 -3.28361201354654e-05 7.28698732612845e-05 -5.3702772749879e-05 0.00026499518831211 1495 1495 0 9 16 1475 1495 0 23 5 0 0 0 0 0 1 14 0 247 0 121 105 0 0 1756 +344 408 0.986870312407297 0.00313336682072898 0.16148426704014 -0.0437615230941397 -0.0221523494210807 0.992989180976853 0.116110980867635 -0.0250236563788283 -0.159988311773863 -0.118163735872241 0.98002095468437 -0.00670917467665628 0.00017512471256319 0.000143555439596036 -2.78006593636572e-05 5.9325600157709e-05 -7.09183525114976e-05 0.00013718618628494 0.000143555439596036 0.000183664732017383 -2.69195617856347e-05 7.13022344264334e-05 -7.14191176496131e-05 0.000155497336052922 -2.78006593636572e-05 -2.69195617856347e-05 1.70808820015065e-05 -3.77810236018376e-06 1.56358538930623e-05 -2.56913465613483e-05 5.9325600157709e-05 7.13022344264334e-05 -3.77810236018376e-06 7.78947377585622e-05 -5.09380897175292e-05 7.65555876782933e-05 -7.09183525114976e-05 -7.14191176496131e-05 1.56358538930623e-05 -5.09380897175292e-05 8.43707477295873e-05 -7.79642993257029e-05 0.00013718618628494 0.000155497336052922 -2.56913465613483e-05 7.65555876782933e-05 -7.79642993257029e-05 0.000235820080115068 1676 1675 0 11 24 1656 1665 0 23 17 0 0 0 0 0 1 15 0 284 0 92 98 0 0 1636 +344 411 0.987001471452759 0.00493011105844184 0.160635579356005 -0.0469756366846784 -0.0226025850333507 0.993853032576356 0.108375609749571 -0.0223804231333372 -0.159113853890534 -0.110597665634192 0.981045838815073 -0.00452734107921511 0.00021798127847026 0.000117053091180911 -3.56511781698097e-05 2.10572624193212e-05 -4.67023091223533e-05 0.000124476575612771 0.000117053091180911 0.000188404658418701 -2.26867921171996e-05 5.47425721273911e-05 -2.7908556745571e-05 0.00013114632045699 -3.56511781698097e-05 -2.26867921171996e-05 1.92907750351712e-05 3.85283253686793e-06 1.20655100668191e-05 -2.17250539453274e-05 2.10572624193212e-05 5.47425721273911e-05 3.85283253686793e-06 7.25120635933735e-05 -2.59304229459205e-05 3.88749642968221e-05 -4.67023091223533e-05 -2.7908556745571e-05 1.20655100668191e-05 -2.59304229459205e-05 6.58500451160577e-05 -4.19528442263929e-05 0.000124476575612771 0.00013114632045699 -2.17250539453274e-05 3.88749642968221e-05 -4.19528442263929e-05 0.000224872799220286 1403 1401 0 9 19 1379 1395 0 22 14 0 0 0 0 0 1 14 0 322 0 71 74 0 0 1587 +344 387 0.988105317842705 0.00110844006793396 0.153774680008064 -0.0531961247335422 -0.0208945736559511 0.991668079549197 0.127113479989117 -0.0180681842001235 -0.152352543932495 -0.128814561924588 0.979895663320067 -0.0127359174295996 0.000105195028593722 6.33669427115185e-07 -1.59858158396478e-05 -3.43958271442395e-06 -1.93012749646427e-05 -7.5872117812212e-06 6.33669427115185e-07 6.54493131615071e-05 -4.05716920867927e-06 1.60587801304126e-05 1.17623505426045e-05 3.51399342879588e-05 -1.59858158396478e-05 -4.05716920867927e-06 1.61707668716e-05 6.72857903854231e-07 3.11727142430703e-06 -3.9031407582668e-07 -3.43958271442395e-06 1.60587801304126e-05 6.72857903854231e-07 4.47726701625042e-05 5.19192622032212e-06 1.21598633288653e-05 -1.93012749646427e-05 1.17623505426045e-05 3.11727142430703e-06 5.19192622032212e-06 5.34086371938126e-05 7.0823965611953e-06 -7.5872117812212e-06 3.51399342879588e-05 -3.9031407582668e-07 1.21598633288653e-05 7.0823965611953e-06 0.0001060319893759 1639 1637 0 8 12 1609 1620 0 20 4 0 0 0 0 0 4 16 0 430 0 147 127 0 0 2095 +344 386 0.988211049788722 0.00193298137658878 0.153085546863411 -0.0514254072533972 -0.0207660701209179 0.992371680098358 0.121520446306356 -0.0195384995102028 -0.151682864580035 -0.123266833015862 0.980712800197405 -0.00822180522414948 7.01129401537257e-05 2.58386660354987e-05 -1.08503315514062e-05 9.81362459706688e-07 -6.8374422233871e-06 -9.75615903023636e-06 2.58386660354987e-05 6.37189943567955e-05 -8.28739324584229e-06 1.65043498759458e-05 -3.25899291127875e-06 4.28078271140298e-05 -1.08503315514062e-05 -8.28739324584229e-06 1.32476878325865e-05 1.46534646810122e-06 2.98821337926084e-06 9.7029258944373e-09 9.81362459706688e-07 1.65043498759458e-05 1.46534646810122e-06 3.58150899646561e-05 1.90443053676861e-06 1.36027630757003e-05 -6.8374422233871e-06 -3.25899291127875e-06 2.98821337926084e-06 1.90443053676861e-06 3.94290156276556e-05 1.22144105268457e-05 -9.75615903023636e-06 4.28078271140298e-05 9.7029258944373e-09 1.36027630757003e-05 1.22144105268457e-05 0.000125492935482993 1757 1755 0 10 17 1731 1742 0 22 8 0 0 0 0 0 2 15 0 421 0 104 92 0 0 2050 +344 406 0.987059454848673 0.00327889235032022 0.160321182189986 -0.0462509934953864 -0.0223558508108985 0.992840840020677 0.117334062921035 -0.0190310799959525 -0.15878869143727 -0.119399812612883 0.980066240730517 -0.0122424505504369 0.000108412876951713 6.23537060004871e-05 -1.5099197184339e-05 1.03692118292322e-05 -1.84487843333446e-05 3.94371117728631e-05 6.23537060004871e-05 0.000101143853697548 -1.04577941496216e-05 2.48564004104847e-05 -1.49573368223204e-05 6.09936670878264e-05 -1.5099197184339e-05 -1.04577941496216e-05 1.37082122052265e-05 2.90520234058563e-06 6.5516785480051e-06 -5.97653825666122e-06 1.03692118292322e-05 2.48564004104847e-05 2.90520234058563e-06 4.82338040724591e-05 -1.40247268847047e-05 1.83644619952177e-05 -1.84487843333446e-05 -1.49573368223204e-05 6.5516785480051e-06 -1.40247268847047e-05 4.82823670632896e-05 -7.87438079110995e-06 3.94371117728631e-05 6.09936670878264e-05 -5.97653825666122e-06 1.83644619952177e-05 -7.87438079110995e-06 0.000122061608127197 1574 1575 0 11 23 1565 1589 0 20 18 0 0 0 0 0 2 15 0 255 0 79 83 0 0 1707 +344 412 0.98768136326015 0.000764842648776655 0.156476642615739 -0.0473504542820295 -0.0211558185910285 0.991459252639066 0.1286894777988 -0.020646187071888 -0.155041787942201 -0.130414590334467 0.979262007135771 -0.0151245777554634 7.94416221522013e-05 7.96757799201867e-06 -1.34853553949689e-05 3.78314484653055e-06 -1.395432756896e-05 -1.86457226308579e-05 7.96757799201867e-06 5.09736487046097e-05 -5.40881258681341e-06 1.68343601981006e-05 3.43825000175774e-06 2.262386748492e-05 -1.34853553949689e-05 -5.40881258681341e-06 1.34126704433196e-05 2.96737903380953e-06 3.90862437912836e-06 1.11797182437439e-06 3.78314484653055e-06 1.68343601981006e-05 2.96737903380953e-06 4.17131119797647e-05 -9.85026815217303e-06 1.47656707033477e-05 -1.395432756896e-05 3.43825000175774e-06 3.90862437912836e-06 -9.85026815217303e-06 4.39081003381499e-05 2.54266610494785e-06 -1.86457226308579e-05 2.262386748492e-05 1.11797182437439e-06 1.47656707033477e-05 2.54266610494785e-06 9.63614749241425e-05 1521 1521 0 8 25 1497 1512 0 18 18 0 0 0 0 0 3 15 0 347 0 73 76 0 0 1611 +344 382 0.987418853613377 0.00133752949444123 0.158120898503947 -0.0495911172421524 -0.0212771717057472 0.99199414024587 0.124478543058879 -0.0214409113132849 -0.156688511043561 -0.126276825794397 0.97954217559748 -0.00986832427346508 9.08598345967451e-05 2.13331505061298e-05 -1.3117482788966e-05 1.74979147655466e-05 -3.16257988056126e-05 -9.09689087834597e-06 2.13331505061298e-05 5.55474604364325e-05 -8.67139169192945e-06 1.37838050832782e-05 4.16872542380388e-06 9.73796618140521e-06 -1.3117482788966e-05 -8.67139169192945e-06 1.35747536855513e-05 -2.20153327158242e-06 6.89286845967959e-06 3.11393637669139e-07 1.74979147655466e-05 1.37838050832782e-05 -2.20153327158242e-06 4.67963596911802e-05 -1.18494195403129e-05 1.97317070066921e-06 -3.16257988056126e-05 4.16872542380388e-06 6.89286845967959e-06 -1.18494195403129e-05 5.3430025708166e-05 8.38379817436094e-06 -9.09689087834597e-06 9.73796618140521e-06 3.11393637669139e-07 1.97317070066921e-06 8.38379817436094e-06 7.69032008737364e-05 1515 1513 0 9 16 1488 1509 0 22 3 0 0 0 0 0 2 12 0 449 0 123 105 0 0 2114 +344 403 0.985019278479716 0.00588964856294743 0.172343648165821 -0.0393718902506921 -0.0240432078453666 0.994345387219768 0.103436816807525 -0.0179350452501305 -0.170759905070844 -0.106030952813667 0.979590981923385 0.0147579946590188 0.000149281256901665 7.23388943552349e-05 -2.10296816408264e-05 1.55973231677077e-05 -2.62733456116497e-05 3.54439110505766e-05 7.23388943552349e-05 0.000159389097363707 -1.66272305630082e-05 5.58620929951911e-05 -3.14512688465629e-05 9.54815696018799e-05 -2.10296816408264e-05 -1.66272305630082e-05 1.64180585341877e-05 -7.85143862921351e-07 1.04433393921625e-05 -6.30093372020273e-06 1.55973231677077e-05 5.58620929951911e-05 -7.85143862921351e-07 6.9836059663506e-05 -2.37400055345753e-05 4.43906512606962e-05 -2.62733456116497e-05 -3.14512688465629e-05 1.04433393921625e-05 -2.37400055345753e-05 5.05834358256261e-05 -2.22021120194691e-05 3.54439110505766e-05 9.54815696018799e-05 -6.30093372020273e-06 4.43906512606962e-05 -2.22021120194691e-05 0.00018222417562309 1501 1498 0 7 17 1465 1482 0 24 7 0 0 0 0 0 0 12 0 236 0 91 87 0 0 1672 +344 396 0.986917202153923 0.00332366215626762 0.161193639336494 -0.0455545363926341 -0.0225357823551521 0.992816477887857 0.117505658365847 -0.0264313297199225 -0.159645152154126 -0.119600980364799 0.979902561936372 0.000361674211584609 0.000186273612130506 7.25252928008298e-05 -3.01628188355353e-05 -2.48349659878842e-06 -4.23095474402693e-05 5.5068775429183e-05 7.25252928008298e-05 7.82593555739839e-05 -1.57032874823242e-05 1.41165738686919e-05 -1.22033129849122e-05 4.80378024472819e-05 -3.01628188355353e-05 -1.57032874823242e-05 1.73359937610631e-05 3.26528640337013e-06 1.16534745709486e-05 -1.13611592531821e-05 -2.48349659878842e-06 1.41165738686919e-05 3.26528640337013e-06 4.89561586153695e-05 -4.51035249189098e-06 2.26075613143346e-05 -4.23095474402693e-05 -1.22033129849122e-05 1.16534745709486e-05 -4.51035249189098e-06 6.49261054954609e-05 -1.36845206329495e-05 5.5068775429183e-05 4.80378024472819e-05 -1.13611592531821e-05 2.26075613143346e-05 -1.36845206329495e-05 0.000132647184355727 1521 1520 0 10 14 1491 1501 0 26 2 0 0 0 0 0 3 15 0 247 0 109 101 0 0 1813 +344 389 0.988572345959439 0.00216214200639502 0.150731688593329 -0.0539579745351001 -0.0208215143454087 0.992271758280968 0.122324250491718 -0.0240612121114201 -0.149302315268773 -0.124064833292682 0.980977438983916 -0.0164052289330374 9.20845057515788e-05 1.23395529001718e-05 -1.30400996510359e-05 -5.8832542542327e-06 -1.66938317408864e-05 -7.98585116647752e-06 1.23395529001718e-05 7.72056554742102e-05 -2.05299304661941e-06 1.82528458649847e-05 7.97361406624042e-06 3.07559961166426e-05 -1.30400996510359e-05 -2.05299304661941e-06 1.45459332320983e-05 5.56909392180814e-06 8.28616549148699e-06 2.07817833738539e-07 -5.8832542542327e-06 1.82528458649847e-05 5.56909392180814e-06 4.23770424697308e-05 1.31561134571058e-06 9.84499484040231e-06 -1.66938317408864e-05 7.97361406624042e-06 8.28616549148699e-06 1.31561134571058e-06 3.96297447695177e-05 -1.59757765454089e-07 -7.98585116647752e-06 3.07559961166426e-05 2.07817833738539e-07 9.84499484040231e-06 -1.59757765454089e-07 0.000112369591207071 1588 1583 0 8 21 1552 1575 0 24 2 0 0 0 0 0 4 17 0 301 0 122 99 0 0 1932 +344 378 0.988322476037248 0.00195224458241473 0.152364274358179 -0.0451388468347611 -0.0206186256201463 0.992434906965829 0.121028210402624 -0.0256385141586717 -0.150975347779497 -0.122756442506355 0.980885977158428 -0.00754725394944093 7.91666549115393e-05 7.76573994815331e-06 -1.28321368298562e-05 -6.20637266002207e-06 -6.73737397172717e-06 -2.23353514235494e-05 7.76573994815331e-06 5.31062680405533e-05 -5.22324421214349e-06 1.25650898532965e-05 9.46800317487796e-06 3.13085994666101e-05 -1.28321368298562e-05 -5.22324421214349e-06 1.3412414494702e-05 3.34917280618157e-06 1.87532300135572e-06 1.72889887895755e-06 -6.20637266002207e-06 1.25650898532965e-05 3.34917280618157e-06 3.7990403367088e-05 1.38998754820566e-07 1.78623525320377e-05 -6.73737397172717e-06 9.46800317487796e-06 1.87532300135572e-06 1.38998754820566e-07 3.8067205703478e-05 6.51903557696201e-06 -2.23353514235494e-05 3.13085994666101e-05 1.72889887895755e-06 1.78623525320377e-05 6.51903557696201e-06 0.00010758650124624 1817 1811 0 9 21 1791 1801 0 22 9 0 0 0 0 0 3 15 0 460 0 109 97 0 0 2124 +344 399 0.986742232093369 0.00281784192893678 0.162270845102441 -0.037552207519226 -0.0224146723644157 0.992633686353942 0.119062786705923 -0.0362559253106059 -0.160740007049249 -0.121121527740727 0.979536740327569 -0.00429268672592745 0.000111570965165152 4.24147415360685e-05 -1.7389175276275e-05 6.77258991534548e-06 -2.62054987466475e-05 1.05333373011504e-05 4.24147415360685e-05 9.15434400816807e-05 -1.09751994595331e-05 1.91126193343976e-05 5.87168422993732e-06 4.03236367030742e-05 -1.7389175276275e-05 -1.09751994595331e-05 1.51698194657669e-05 2.95073804170604e-06 8.32390017564604e-06 -3.66540035421071e-06 6.77258991534548e-06 1.91126193343976e-05 2.95073804170604e-06 4.3608305926622e-05 -1.15647805457122e-05 3.03666131008151e-06 -2.62054987466475e-05 5.87168422993732e-06 8.32390017564604e-06 -1.15647805457122e-05 6.48622706162499e-05 1.07192806976663e-05 1.05333373011504e-05 4.03236367030742e-05 -3.66540035421071e-06 3.03666131008151e-06 1.07192806976663e-05 0.00010312496315134 1480 1474 0 10 13 1462 1477 0 25 2 0 0 0 0 0 0 15 0 268 0 121 108 0 0 1806 +344 405 0.986714540561689 0.00287049794333755 0.162438221135583 -0.0465848493880506 -0.0230011684137533 0.992240898658328 0.122184063123287 -0.0154897589874162 -0.160827117414127 -0.124297060589824 0.979124547252796 -0.0057029357325028 0.000140222386207169 1.34089846276186e-05 -2.24508449059435e-05 6.68054456089035e-06 -4.23186699768685e-05 -1.49620786705458e-05 1.34089846276186e-05 0.000112765546815211 -5.2550595363147e-06 3.00519957433246e-05 1.53337151763328e-05 4.78253579350959e-05 -2.24508449059435e-05 -5.2550595363147e-06 1.64761212803964e-05 1.94582162334784e-06 1.13467499702216e-05 6.39993941172054e-07 6.68054456089035e-06 3.00519957433246e-05 1.94582162334784e-06 3.9609694275561e-05 1.71304911989439e-06 2.18934659865929e-05 -4.23186699768685e-05 1.53337151763328e-05 1.13467499702216e-05 1.71304911989439e-06 5.92421654424325e-05 1.16125362797251e-05 -1.49620786705458e-05 4.78253579350959e-05 6.39993941172054e-07 2.18934659865929e-05 1.16125362797251e-05 0.000131754730828247 1749 1748 0 8 21 1722 1732 0 21 13 0 0 0 0 0 3 15 0 239 0 95 100 0 0 1721 +344 400 0.985732122282193 0.00391728457532755 0.168276076679366 -0.0324867928043641 -0.0232143589515069 0.993339469113331 0.112861829863404 -0.0415423889761428 -0.166713156767889 -0.115157952322892 0.979257560285998 -0.00360929417571911 0.000214467147061643 0.00010885404079795 -4.03089097231515e-05 2.8249202206385e-05 -2.602164378978e-05 8.17321982531894e-05 0.00010885404079795 0.00014125589691956 -2.07314607985081e-05 2.49055587899863e-05 -5.61773160338068e-06 8.82944561972121e-05 -4.03089097231515e-05 -2.07314607985081e-05 2.17702159344979e-05 -2.71567516472934e-06 9.61451120029442e-06 -1.58949223731578e-05 2.8249202206385e-05 2.49055587899863e-05 -2.71567516472934e-06 6.49744632752865e-05 -3.79859547953794e-05 5.2028800969489e-05 -2.602164378978e-05 -5.61773160338068e-06 9.61451120029442e-06 -3.79859547953794e-05 6.93981517359227e-05 -3.45385409391734e-05 8.17321982531894e-05 8.82944561972121e-05 -1.58949223731578e-05 5.2028800969489e-05 -3.45385409391734e-05 0.00020742433654978 1556 1555 0 14 13 1541 1550 0 20 6 0 0 0 0 0 0 13 0 270 0 109 98 0 0 1762 +344 413 0.988396571524571 0.00174374328916055 0.151885406665077 -0.0534430908546233 -0.021020255269744 0.991883282725083 0.125402162337452 -0.019794355217113 -0.150433926581969 -0.127139737335954 0.980410689927071 -0.0171492482947961 5.31181949181076e-05 1.47958234020983e-05 -6.86138980261142e-06 1.21039316430653e-06 4.26880645859217e-06 8.36557566098797e-07 1.47958234020983e-05 3.76211851972839e-05 -7.39822565078881e-06 8.70848214743659e-06 6.46726020267146e-06 6.92432102892197e-06 -6.86138980261142e-06 -7.39822565078881e-06 1.28836774180585e-05 2.89080628117276e-06 2.13741293713836e-06 -2.99119247237522e-07 1.21039316430653e-06 8.70848214743659e-06 2.89080628117276e-06 3.42959675565365e-05 7.39913075504977e-06 8.73910848882094e-06 4.26880645859217e-06 6.46726020267146e-06 2.13741293713836e-06 7.39913075504977e-06 3.36679104751948e-05 -2.91384796434979e-06 8.36557566098797e-07 6.92432102892197e-06 -2.99119247237522e-07 8.73910848882094e-06 -2.91384796434979e-06 6.85377368965045e-05 1665 1663 0 9 23 1641 1656 0 21 15 0 0 0 0 0 3 18 0 383 0 64 72 0 0 1620 +345 347 0.999957194741146 -0.00741846832796906 -0.00552946770359824 -0.0131804658580527 0.00747107056821819 0.999926450198862 0.00955391528472667 0.00277242132417966 0.0054581855944004 -0.00959481737032811 0.999939071988712 -0.00787662150501634 9.13401100124015e-05 3.78584606813208e-05 -9.40950066601291e-06 2.78639829731766e-05 -5.19655181098642e-07 6.29081338000671e-05 3.78584606813208e-05 6.24597825521823e-05 -1.40099488258346e-05 2.30454199151212e-05 -2.60410923969697e-06 4.15918634183672e-05 -9.40950066601291e-06 -1.40099488258346e-05 1.97086802944478e-05 7.14490912330039e-07 -7.25769315437363e-07 -1.58799579973801e-05 2.78639829731766e-05 2.30454199151212e-05 7.14490912330039e-07 5.14465239028404e-05 -1.27464611224877e-05 2.70170896532732e-05 -5.19655181098642e-07 -2.60410923969697e-06 -7.25769315437363e-07 -1.27464611224877e-05 4.25680682590403e-05 -9.97313564937296e-07 6.29081338000671e-05 4.15918634183672e-05 -1.58799579973801e-05 2.70170896532732e-05 -9.97313564937296e-07 0.000115945796198038 1839 1807 0 15 66 1845 1847 0 19 36 0 0 0 0 0 9 20 0 287 0 77 47 0 0 3228 +344 381 0.987969889089323 0.00216899721190091 0.154631153730178 -0.04738524055864 -0.020959310957358 0.992553729464422 0.119990838860554 -0.0235479275587432 -0.153219468531333 -0.121788298195522 0.980658658701189 -0.0164122226151472 8.61485159351953e-05 1.73395078253971e-05 -1.08606122325018e-05 4.13326936535604e-06 -9.28075417835021e-06 -5.24017819822259e-06 1.73395078253971e-05 5.57998321369372e-05 -8.47462495956407e-06 1.29068041711822e-05 6.93544204129885e-06 2.83050281953764e-05 -1.08606122325018e-05 -8.47462495956407e-06 1.50348012604584e-05 1.9248775876681e-06 4.54160174667011e-06 -8.49134099833285e-07 4.13326936535604e-06 1.29068041711822e-05 1.9248775876681e-06 4.04349373722966e-05 -7.85198237707385e-06 1.37547702341135e-05 -9.28075417835021e-06 6.93544204129885e-06 4.54160174667011e-06 -7.85198237707385e-06 4.31803985015602e-05 1.25042009934529e-06 -5.24017819822259e-06 2.83050281953764e-05 -8.49134099833285e-07 1.37547702341135e-05 1.25042009934529e-06 0.000105559704094862 1678 1673 0 11 18 1657 1676 0 21 5 0 0 0 0 0 3 16 0 439 0 119 101 0 0 2101 +345 411 0.987875437276739 -0.00339328801030856 0.155211488047025 -0.0394127719062806 -0.0153670781084561 0.992714064901239 0.119509992292136 -0.0244021976740453 -0.154486159042489 -0.120446132954682 0.980625696033182 -0.021565865854417 5.83380435203166e-05 2.80964522842225e-05 -1.07203074342624e-05 6.95213064555712e-07 2.91176363241112e-06 3.50042661949864e-06 2.80964522842225e-05 6.46958735449162e-05 -6.6470948593386e-06 2.07547013814041e-05 -1.07965326499791e-06 2.71179382231081e-05 -1.07203074342624e-05 -6.6470948593386e-06 1.41801149028798e-05 5.795900543809e-06 5.80415482530995e-07 1.03784711198793e-07 6.95213064555712e-07 2.07547013814041e-05 5.795900543809e-06 4.70288460877194e-05 -3.81455679750974e-06 1.03960564426407e-05 2.91176363241112e-06 -1.07965326499791e-06 5.80415482530995e-07 -3.81455679750974e-06 4.16340496183578e-05 1.65834556768765e-06 3.50042661949864e-06 2.71179382231081e-05 1.03784711198793e-07 1.03960564426407e-05 1.65834556768765e-06 7.82251394267999e-05 1575 1582 0 17 11 1556 1575 0 25 4 0 0 0 0 0 6 18 0 332 0 54 58 0 0 1689 +344 390 0.986116081519219 0.00358264607921477 0.166018789347025 -0.042257369053549 -0.0230297388562327 0.993056537728456 0.115361796115464 -0.0231448957517312 -0.164452743660282 -0.11758349170629 0.979351529115446 0.00564668343298183 0.000118498409769459 3.38915196186662e-05 -1.84151120241491e-05 2.14405295252291e-05 -2.93380266706956e-05 3.35306459031526e-05 3.38915196186662e-05 0.000105736061119107 -9.5503197377377e-06 3.98496296110586e-05 1.88976644054777e-06 5.18386341874874e-05 -1.84151120241491e-05 -9.5503197377377e-06 1.64034824885747e-05 5.08842479943858e-07 1.02895472739463e-05 -8.19027089142806e-06 2.14405295252291e-05 3.98496296110586e-05 5.08842479943858e-07 5.24928381952768e-05 6.05511221061411e-07 2.53141634578885e-05 -2.93380266706956e-05 1.88976644054777e-06 1.02895472739463e-05 6.05511221061411e-07 4.84097470648412e-05 -4.94316437676929e-06 3.35306459031526e-05 5.18386341874874e-05 -8.19027089142806e-06 2.53141634578885e-05 -4.94316437676929e-06 0.000134768648190237 1325 1324 0 12 13 1298 1320 0 22 2 0 0 0 0 0 0 14 0 206 0 124 100 0 0 1832 +344 395 0.986561844689598 0.00318472275468839 0.163357228623752 -0.0430950630010411 -0.022887244436544 0.992645930088402 0.118870650376924 -0.0195347949077646 -0.161777318078768 -0.121012044937298 0.979379489439785 -0.00350429036416011 0.000145092334211466 4.85235217589202e-05 -2.10335039288987e-05 7.06166063957946e-06 -3.79730889179335e-05 1.85930117164689e-05 4.85235217589202e-05 8.23472943993055e-05 -1.02189553491469e-05 1.87654847913923e-05 -5.73153951433314e-06 3.74342207538623e-05 -2.10335039288987e-05 -1.02189553491469e-05 1.52546680182893e-05 2.79361204652238e-06 1.07897653075552e-05 -7.17389768516281e-06 7.06166063957946e-06 1.87654847913923e-05 2.79361204652238e-06 3.83000090413907e-05 -3.95788425314757e-06 1.67946735497522e-05 -3.79730889179335e-05 -5.73153951433314e-06 1.07897653075552e-05 -3.95788425314757e-06 5.20653524208089e-05 -2.87469157282457e-06 1.85930117164689e-05 3.74342207538623e-05 -7.17389768516281e-06 1.67946735497522e-05 -2.87469157282457e-06 0.000105832298121374 1673 1673 0 11 17 1648 1658 0 20 9 0 0 0 0 0 3 16 0 243 0 138 123 0 0 1789 +345 409 0.987480571741774 -0.00268646430617306 0.15771779652934 -0.0463454371444061 -0.0162651573170017 0.992791231430499 0.118747696618361 -0.0180885179915054 -0.156899856883274 -0.119826348121958 0.980318357068643 -0.0168310056375966 6.0902203333944e-05 3.16893932718854e-05 -9.54590971516909e-06 7.97196881569403e-06 -8.36451172329539e-06 7.21946569556845e-06 3.16893932718854e-05 8.19929553310356e-05 -7.37652294780593e-06 3.22625295875388e-05 -7.64889617902509e-06 4.04856703545859e-05 -9.54590971516909e-06 -7.37652294780593e-06 1.2541710560951e-05 2.14204686820999e-06 5.6887040251736e-06 -8.97460068875632e-07 7.97196881569403e-06 3.22625295875388e-05 2.14204686820999e-06 5.92725062279119e-05 -1.1332640910553e-05 1.72507592531036e-05 -8.36451172329539e-06 -7.64889617902509e-06 5.6887040251736e-06 -1.1332640910553e-05 4.12191744270384e-05 -2.31543017868069e-06 7.21946569556845e-06 4.04856703545859e-05 -8.97460068875632e-07 1.72507592531036e-05 -2.31543017868069e-06 9.61364342662515e-05 1530 1527 0 13 11 1491 1499 0 19 2 0 0 0 0 0 4 15 0 301 0 59 61 0 0 1668 +344 385 0.988091428528766 0.00112276700456049 0.153863797763596 -0.0522653500788151 -0.0210453603749936 0.991561855257503 0.127914737247067 -0.0230410780726145 -0.152421854321058 -0.129629574528936 0.979777399072247 -0.0210351376359107 7.26163844929116e-05 1.8263713913386e-05 -1.06898312166169e-05 -8.60000034398653e-07 -6.93602188244286e-06 1.53426229888666e-06 1.8263713913386e-05 7.23096289446722e-05 -7.50197614897796e-06 2.0006779676871e-05 8.09626115836457e-06 4.05620724435854e-05 -1.06898312166169e-05 -7.50197614897796e-06 1.44270475308569e-05 3.01267403489521e-06 -5.59764729436054e-07 -2.30729904646276e-06 -8.60000034398653e-07 2.0006779676871e-05 3.01267403489521e-06 3.47881353197545e-05 3.14444488965148e-06 1.31688332734088e-05 -6.93602188244286e-06 8.09626115836457e-06 -5.59764729436054e-07 3.14444488965148e-06 4.11852152973316e-05 8.47094351713554e-06 1.53426229888666e-06 4.05620724435854e-05 -2.30729904646276e-06 1.31688332734088e-05 8.47094351713554e-06 0.000106283166693026 1614 1607 0 8 14 1592 1609 0 22 2 0 0 0 0 0 0 10 0 426 0 124 104 0 0 2110 +345 407 0.987263947899393 -0.00273574501418005 0.159067321839914 -0.0466536960431967 -0.0162570577866751 0.992883245892737 0.117976981219322 -0.0189224294523547 -0.158258033762038 -0.119060386882963 0.980193357978441 -0.012900297734482 7.37674361656102e-05 4.89148008813375e-05 -1.31158969294099e-05 -6.37728069512605e-06 3.4181740224458e-06 3.50696148636663e-05 4.89148008813375e-05 9.46163439144953e-05 -1.15057373690968e-05 1.94896557006634e-05 -6.69348033566771e-06 5.75509330473126e-05 -1.31158969294099e-05 -1.15057373690968e-05 1.44677095944484e-05 5.96659609519799e-06 3.38894354902265e-06 -8.54842083704563e-06 -6.37728069512605e-06 1.94896557006634e-05 5.96659609519799e-06 5.20968284962862e-05 -1.262628309764e-05 6.35018029755153e-06 3.4181740224458e-06 -6.69348033566771e-06 3.38894354902265e-06 -1.262628309764e-05 3.78662110003587e-05 -2.87939800508152e-06 3.50696148636663e-05 5.75509330473126e-05 -8.54842083704563e-06 6.35018029755153e-06 -2.87939800508152e-06 0.000108845801595835 1450 1449 0 13 13 1411 1426 0 25 2 0 0 0 0 0 6 18 0 271 0 70 73 0 0 1742 +345 398 0.983969570671057 -0.00111290236351388 0.178332962297341 -0.019596761980631 -0.0175743520315909 0.994507999168608 0.103174520790367 -0.0416995004811072 -0.177468380688181 -0.104654675184539 0.978546050432954 0.00118919501741033 0.000101679281488862 2.62968646023479e-05 -1.86278731161459e-05 8.50802494244952e-06 -2.10793029316031e-05 -7.64049102134257e-06 2.62968646023479e-05 8.41290365062359e-05 -8.17474609013296e-06 2.08879726026101e-05 3.6995684946371e-06 3.31913670319945e-05 -1.86278731161459e-05 -8.17474609013296e-06 1.54015384170349e-05 1.33740560014412e-06 8.11409440077365e-06 -8.53373711066177e-07 8.50802494244952e-06 2.08879726026101e-05 1.33740560014412e-06 5.56544244045268e-05 -2.25354378103278e-05 1.13518060203765e-05 -2.10793029316031e-05 3.6995684946371e-06 8.11409440077365e-06 -2.25354378103278e-05 6.36417924094688e-05 6.11393917798572e-06 -7.64049102134257e-06 3.31913670319945e-05 -8.53373711066177e-07 1.13518060203765e-05 6.11393917798572e-06 0.000108398874603054 1407 1405 0 22 13 1418 1446 0 30 0 0 0 0 0 0 4 16 0 247 0 100 84 0 0 1776 +345 348 0.999905702765371 -0.00429374119251509 0.0130441313954455 -0.00245911906771709 0.00423559337899804 0.999980984921495 0.00448213611634252 -0.00176128080402053 -0.0130631284927362 -0.00442646382672819 0.999904876021701 -0.00847693468469853 7.4649624766221e-05 1.12389352161742e-05 -1.73865463782695e-05 -2.00957134372933e-06 -7.32530889426451e-06 1.2955411415284e-05 1.12389352161742e-05 5.50206642606495e-05 -1.34417901648265e-05 1.72735593911995e-05 3.8214917253531e-06 1.63539856355223e-05 -1.73865463782695e-05 -1.34417901648265e-05 2.17231092379389e-05 4.7867835518943e-06 -2.95335113518215e-06 -8.00686206812332e-06 -2.00957134372933e-06 1.72735593911995e-05 4.7867835518943e-06 5.60260707386702e-05 -2.82166364315557e-05 1.65027940923025e-05 -7.32530889426451e-06 3.8214917253531e-06 -2.95335113518215e-06 -2.82166364315557e-05 5.98598111782697e-05 -8.39564244275231e-07 1.2955411415284e-05 1.63539856355223e-05 -8.00686206812332e-06 1.65027940923025e-05 -8.39564244275231e-07 7.48978549597389e-05 1933 1903 0 9 63 1916 1938 0 11 42 0 0 0 0 0 5 14 0 273 0 62 33 0 0 3215 +345 410 0.987815498396006 -0.00375227108391538 0.155584258812911 -0.0448407513170053 -0.0154853712116872 0.992378379107256 0.122251200234972 -0.0221993110486266 -0.154857174218977 -0.123170910292032 0.980228637844634 -0.0200758652303829 8.47631601395689e-05 5.30410577353144e-05 -1.22786079205656e-05 3.10034557831551e-06 -6.67897686370645e-06 2.93276706180796e-05 5.30410577353144e-05 0.000102295318522414 -9.07314294419961e-06 3.06072026829975e-05 -6.3876563004531e-06 6.81140935170429e-05 -1.22786079205656e-05 -9.07314294419961e-06 1.4048344776039e-05 5.11144024643922e-06 4.07196562506103e-06 -4.26763979411769e-06 3.10034557831551e-06 3.06072026829975e-05 5.11144024643922e-06 5.52086666426093e-05 -2.10792708051142e-06 2.63908882593742e-05 -6.67897686370645e-06 -6.3876563004531e-06 4.07196562506103e-06 -2.10792708051142e-06 4.74940658477644e-05 -1.42904003195033e-05 2.93276706180796e-05 6.81140935170429e-05 -4.26763979411769e-06 2.63908882593742e-05 -1.42904003195033e-05 0.000133593515557327 1544 1547 0 14 9 1514 1531 0 24 3 0 0 0 0 0 8 20 0 306 0 52 54 0 0 1703 +345 396 0.985995310092597 -0.00235574695917973 0.16675640596891 -0.034895105630578 -0.0167595363667243 0.993438861606234 0.113129775882754 -0.0301371187343082 -0.16592879923683 -0.114340188502442 0.979486577180642 -0.000643685424140037 0.000126023293356646 9.32909316722777e-05 -1.94460422587857e-05 1.75037900547889e-05 -1.86252670866917e-05 7.82035323217236e-05 9.32909316722777e-05 0.000164965526462938 -1.87890624328058e-05 3.41165749076531e-05 -1.39676989397089e-05 0.00012288069014448 -1.94460422587857e-05 -1.87890624328058e-05 1.57242072899896e-05 1.61753544834028e-06 6.60927317984222e-06 -1.45192708257891e-05 1.75037900547889e-05 3.41165749076531e-05 1.61753544834028e-06 4.85624527614945e-05 -6.08325637694939e-06 2.79095196042787e-05 -1.86252670866917e-05 -1.39676989397089e-05 6.60927317984222e-06 -6.08325637694939e-06 4.16967318516849e-05 -1.90953627517175e-05 7.82035323217236e-05 0.00012288069014448 -1.45192708257891e-05 2.79095196042787e-05 -1.90953627517175e-05 0.000195220759374062 1594 1590 0 14 13 1566 1577 0 24 2 0 0 0 0 0 7 20 0 250 0 104 87 0 0 1905 +345 408 0.987735476620298 -0.004438893237337 0.156073458513934 -0.041379105078668 -0.0149987035742561 0.9922755844749 0.123143019883735 -0.0240124847831883 -0.15541450098612 -0.123973628977383 0.980039219726136 -0.0209167698174783 3.70545240931616e-05 1.74432419813688e-05 -3.95386190200849e-06 4.92545704337191e-06 -6.57804960537804e-06 -9.48244996939631e-07 1.74432419813688e-05 4.69683114465634e-05 -3.27465791786249e-06 8.32594273473017e-06 4.17599454241479e-07 2.42400300765762e-05 -3.95386190200849e-06 -3.27465791786249e-06 1.23195906923278e-05 4.10689384486428e-06 6.08282442573764e-06 1.63163596245056e-06 4.92545704337191e-06 8.32594273473017e-06 4.10689384486428e-06 4.56423400162666e-05 -3.32513440819052e-06 3.27783550905672e-06 -6.57804960537804e-06 4.17599454241479e-07 6.08282442573764e-06 -3.32513440819052e-06 4.52746870542148e-05 5.69456103464765e-06 -9.48244996939631e-07 2.42400300765762e-05 1.63163596245056e-06 3.27783550905672e-06 5.69456103464765e-06 8.62225029630226e-05 1582 1583 0 14 13 1572 1594 0 21 2 0 0 0 0 0 6 15 0 280 0 96 100 0 0 1741 +345 349 0.999724635276202 -0.00253409048732916 0.0233287806639457 0.0123414725440456 0.00273693751507601 0.999958692499984 -0.00866732177559963 -0.0171354100557656 -0.0233058532326759 0.00872878451591295 0.999690274798135 -0.00578964565348694 0.000102246636017691 3.35867511636448e-05 -3.2186850208364e-05 2.12643367603769e-05 -1.29285174414756e-05 2.14418451937418e-05 3.35867511636448e-05 5.57740081454907e-05 -2.01214167226944e-05 2.55027163044427e-05 -7.62702972809878e-06 2.93693689730493e-05 -3.2186850208364e-05 -2.01214167226944e-05 2.9167203788378e-05 -1.52146364128749e-06 -1.11463004993075e-06 -1.36215936977697e-05 2.12643367603769e-05 2.55027163044427e-05 -1.52146364128749e-06 7.33626604540479e-05 -4.70463649083818e-05 3.80100395486324e-05 -1.29285174414756e-05 -7.62702972809878e-06 -1.11463004993075e-06 -4.70463649083818e-05 7.63447583853776e-05 -2.63762700596033e-06 2.14418451937418e-05 2.93693689730493e-05 -1.36215936977697e-05 3.80100395486324e-05 -2.63762700596033e-06 0.000106876517642811 2111 2089 0 10 61 2093 2096 0 12 42 0 0 0 0 0 7 16 0 261 0 61 28 0 0 3114 +345 397 0.98703302448044 -0.0026405145742159 0.160495595789348 -0.0385270880864385 -0.0163497441930929 0.993010670124015 0.116886675394052 -0.0287438815578842 -0.159682480096643 -0.117995070670928 0.980091153336029 -0.0092872566001017 8.43680644040035e-05 4.17388628735411e-05 -1.30442613137241e-05 5.53463940815458e-06 -5.1394276205218e-06 1.79207114415649e-05 4.17388628735411e-05 6.93151929645144e-05 -1.07071820800696e-05 1.10762796445885e-05 3.4120807413687e-06 3.32836595404162e-05 -1.30442613137241e-05 -1.07071820800696e-05 1.39807793977617e-05 2.34695186456016e-06 3.95285185369313e-06 -5.32456466943143e-06 5.53463940815458e-06 1.10762796445885e-05 2.34695186456016e-06 4.99515629904872e-05 -1.83630619132929e-05 1.2501545852113e-06 -5.1394276205218e-06 3.4120807413687e-06 3.95285185369313e-06 -1.83630619132929e-05 5.03604613145364e-05 1.03966448792679e-05 1.79207114415649e-05 3.32836595404162e-05 -5.32456466943143e-06 1.2501545852113e-06 1.03966448792679e-05 9.99831419592741e-05 1560 1560 0 15 16 1549 1561 0 21 8 0 0 0 0 0 3 15 0 251 0 102 90 0 0 1866 +345 406 0.986140439736801 -0.0031046036524281 0.165883677774123 -0.0343894626819879 -0.016389175205566 0.993112058619905 0.116016524511878 -0.0263260771466777 -0.165101266051442 -0.117127283157663 0.97929708030215 -0.0142318543732682 0.000207424423067413 0.000179213290684991 -3.57837729527405e-05 5.73744028655915e-05 -5.56003402133225e-05 0.000167136107233485 0.000179213290684991 0.000214470082639407 -3.64148704209259e-05 6.59600542305102e-05 -4.87281963601781e-05 0.000190120919219052 -3.57837729527405e-05 -3.64148704209259e-05 1.85155868113168e-05 -6.93874364854061e-06 1.42707879760408e-05 -3.31582271961952e-05 5.73744028655915e-05 6.59600542305102e-05 -6.93874364854061e-06 7.70433737923943e-05 -4.3323206762556e-05 8.31482273443773e-05 -5.56003402133225e-05 -4.87281963601781e-05 1.42707879760408e-05 -4.3323206762556e-05 7.55942003731716e-05 -6.86142287931041e-05 0.000167136107233485 0.000190120919219052 -3.31582271961952e-05 8.31482273443773e-05 -6.86142287931041e-05 0.00026959441368458 1593 1592 0 11 12 1606 1630 0 18 3 0 0 0 0 0 4 15 0 246 0 78 80 0 0 1800 +345 399 0.988686543069142 -0.00319999665250328 0.149962260503815 -0.0366258435820419 -0.0148954519816828 0.992735939957267 0.119387935016156 -0.0390868628835047 -0.149254966631772 -0.120271000405686 0.981456999260367 -0.0239221995722796 7.97305867080376e-05 4.33446472053566e-05 -1.41292483408545e-05 4.2920683892968e-06 2.77347427257431e-06 1.60893647606824e-05 4.33446472053566e-05 7.96809215272434e-05 -1.2377642297042e-05 2.7130727448776e-05 -6.08905963886532e-06 4.23581538055667e-05 -1.41292483408545e-05 -1.2377642297042e-05 1.56013835004377e-05 1.29412575037592e-06 4.21653598243185e-06 -4.26053479794706e-06 4.2920683892968e-06 2.7130727448776e-05 1.29412575037592e-06 5.48714860641525e-05 -1.92056929528486e-05 1.68962509544327e-05 2.77347427257431e-06 -6.08905963886532e-06 4.21653598243185e-06 -1.92056929528486e-05 5.67031534203203e-05 -8.01986397074473e-06 1.60893647606824e-05 4.23581538055667e-05 -4.26053479794706e-06 1.68962509544327e-05 -8.01986397074473e-06 0.00012474468458859 1471 1469 0 16 17 1450 1464 0 25 6 0 0 0 0 0 3 16 0 276 0 100 90 0 0 1890 +345 389 0.987807961052124 -0.00312190294430558 0.155646027267167 -0.0409718842376348 -0.0156378899514336 0.992752118246504 0.119158248203581 -0.0263535839583209 -0.154889923752038 -0.120139441646304 0.980599625780574 -0.0200534289699486 7.60587695533865e-05 -9.37014718503836e-06 -9.28028377807703e-06 -8.52906772194055e-06 -2.11543592302262e-05 -8.47522826769001e-06 -9.37014718503836e-06 5.81881317057964e-05 2.56719779856173e-06 1.28252085598013e-05 1.14185483377247e-05 1.13842075816622e-05 -9.28028377807703e-06 2.56719779856173e-06 1.31290631274874e-05 5.87576125539767e-06 7.25300120723289e-06 1.63293826712726e-06 -8.52906772194055e-06 1.28252085598013e-05 5.87576125539767e-06 3.79721879857372e-05 -3.063644076967e-06 2.33376156545685e-06 -2.11543592302262e-05 1.14185483377247e-05 7.25300120723289e-06 -3.063644076967e-06 4.4238787458492e-05 6.46227965844729e-06 -8.47522826769001e-06 1.13842075816622e-05 1.63293826712726e-06 2.33376156545685e-06 6.46227965844729e-06 7.22255790634002e-05 1466 1467 0 14 18 1446 1456 0 19 9 0 0 0 0 0 6 17 0 307 0 104 86 0 0 1990 +345 412 0.985927172267195 -0.00266649391501323 0.167154122878897 -0.0318894394908023 -0.0166396429970238 0.993342321234959 0.113991908153497 -0.0277256736562664 -0.166345223153969 -0.115169104597304 0.979318816361716 -0.00965027731890157 0.000120974821115057 0.00010290317822344 -1.94413529405401e-05 1.91597453348281e-05 -1.73936134344099e-05 7.0501670038295e-05 0.00010290317822344 0.000139899794289926 -2.2755712480118e-05 2.80649937892943e-05 -1.35455742354866e-05 9.34048677599612e-05 -1.94413529405401e-05 -2.2755712480118e-05 1.48918684998125e-05 -5.4262580884066e-07 6.79013898831856e-06 -1.37510305379705e-05 1.91597453348281e-05 2.80649937892943e-05 -5.4262580884066e-07 4.49649673498734e-05 -1.00795165402173e-05 2.08235208786494e-05 -1.73936134344099e-05 -1.35455742354866e-05 6.79013898831856e-06 -1.00795165402173e-05 4.68690297455509e-05 -1.67675202829404e-05 7.0501670038295e-05 9.34048677599612e-05 -1.37510305379705e-05 2.08235208786494e-05 -1.67675202829404e-05 0.000154866495184639 1401 1404 0 9 9 1390 1407 0 19 2 0 0 0 0 0 4 16 0 350 0 60 61 0 0 1632 +345 388 0.986608823372225 -0.00388869328046532 0.163057988791242 -0.0363562801988187 -0.0160883883687627 0.992520226362218 0.121015552808664 -0.0259017744141713 -0.16230894431229 -0.122018352416598 0.979166649896619 -0.019250511584581 4.35351193728867e-05 1.58507825788688e-05 -4.45509224697923e-06 -4.34501933786698e-06 -3.51935894212447e-06 -2.44825838920871e-06 1.58507825788688e-05 4.87165981377834e-05 -2.50308461364619e-06 6.37154291908988e-06 2.15071370325798e-07 6.28366519272494e-06 -4.45509224697923e-06 -2.50308461364619e-06 1.23662890776767e-05 4.70360258772144e-06 4.75775818731517e-06 9.569168678693e-07 -4.34501933786698e-06 6.37154291908988e-06 4.70360258772144e-06 3.63254485521609e-05 -7.46073701696243e-06 1.43190242242115e-09 -3.51935894212447e-06 2.15071370325798e-07 4.75775818731517e-06 -7.46073701696243e-06 3.33737822117031e-05 4.33780171439798e-07 -2.44825838920871e-06 6.28366519272494e-06 9.569168678693e-07 1.43190242242115e-09 4.33780171439798e-07 8.32285282499594e-05 1531 1534 0 17 18 1535 1564 0 19 1 0 0 0 0 0 6 16 0 438 0 114 91 0 0 2078 +345 404 0.987058595523689 -0.00193487099535749 0.160348324833887 -0.0462272057973367 -0.0166653041268423 0.993275105391306 0.114572390427404 -0.0130721787202743 -0.159491682043805 -0.115761916380652 0.980388485282603 -0.0063367523117288 0.000105585846828701 6.18327288566485e-05 -1.55219833178846e-05 1.81607825178385e-05 -1.6800992716408e-05 4.32740170391962e-05 6.18327288566485e-05 0.000124901521150055 -1.45849004466615e-05 3.88681033984054e-05 -4.36231571929437e-06 9.62313940998263e-05 -1.55219833178846e-05 -1.45849004466615e-05 1.54522234902004e-05 -7.72118665709691e-07 4.6733892049569e-06 -9.92994880242666e-06 1.81607825178385e-05 3.88681033984054e-05 -7.72118665709691e-07 5.55453461552314e-05 -4.28432713732509e-06 3.76745775368163e-05 -1.6800992716408e-05 -4.36231571929437e-06 4.6733892049569e-06 -4.28432713732509e-06 4.87407205557476e-05 7.25245566727384e-07 4.32740170391962e-05 9.62313940998263e-05 -9.92994880242666e-06 3.76745775368163e-05 7.25245566727384e-07 0.000196681166280775 1574 1576 0 14 11 1540 1554 0 23 1 0 0 0 0 0 7 20 0 246 0 73 74 0 0 1744 +345 413 0.986916545389924 -0.000546881481289143 0.161230993783032 -0.0445576488318572 -0.0171126579592132 0.993990510543966 0.108120404578033 -0.0194886871437245 -0.16032120687292 -0.109464907021346 0.980976322220684 -0.0124025063439761 0.000166385492146958 0.00010077589097072 -3.010056353483e-05 1.74871966748663e-05 -1.20424090665386e-05 6.36173763936434e-05 0.00010077589097072 0.000131942674228215 -2.54861027353871e-05 3.19409017483833e-05 -4.14007299016435e-06 7.88557633550545e-05 -3.010056353483e-05 -2.54861027353871e-05 1.80620266826631e-05 1.65794029011166e-06 3.15481723816341e-06 -1.31186330857205e-05 1.74871966748663e-05 3.19409017483833e-05 1.65794029011166e-06 5.8550781437181e-05 -4.3217898396908e-06 2.18255344001368e-05 -1.20424090665386e-05 -4.14007299016435e-06 3.15481723816341e-06 -4.3217898396908e-06 4.44639158436333e-05 -1.0173879621722e-05 6.36173763936434e-05 7.88557633550545e-05 -1.31186330857205e-05 2.18255344001368e-05 -1.0173879621722e-05 0.000139022673373752 1591 1594 0 16 9 1566 1581 0 23 4 0 0 0 0 0 6 18 0 384 0 59 64 0 0 1639 +345 391 0.986203870756202 -0.00263897374141088 0.165514232388266 -0.033403839845645 -0.01667875793863 0.993200570636722 0.115214779956888 -0.0233667638445948 -0.164692878835453 -0.116385833779209 0.979454232394964 -0.00542509682483461 9.34861042072816e-05 6.78188765282501e-05 -8.80827548734185e-06 2.24064496889894e-05 -2.00838965534631e-05 5.39966397059153e-05 6.78188765282501e-05 0.000117728764302396 -1.10796353276969e-05 3.93323551420084e-05 -1.82017826029015e-05 9.86923771380058e-05 -8.80827548734185e-06 -1.10796353276969e-05 1.36803403738317e-05 9.62589013342288e-07 6.8753519797028e-06 -7.76504882387265e-06 2.24064496889894e-05 3.93323551420084e-05 9.62589013342288e-07 5.00069926596004e-05 -1.11766697292162e-05 4.64207058180264e-05 -2.00838965534631e-05 -1.82017826029015e-05 6.8753519797028e-06 -1.11766697292162e-05 4.47113895352069e-05 -1.26377598390324e-05 5.39966397059153e-05 9.86923771380058e-05 -7.76504882387265e-06 4.64207058180264e-05 -1.26377598390324e-05 0.000185857269442241 1596 1592 0 13 14 1576 1593 0 15 0 0 0 0 0 0 5 13 0 206 0 127 113 0 0 1851 +345 386 0.987299951741989 -0.00412992122031309 0.158813566929847 -0.0411727918246406 -0.015757178733101 0.992187105677132 0.123759681020953 -0.0198634914876874 -0.158083891047254 -0.124690380858945 0.979521205647234 -0.0112559108138026 4.95958836384707e-05 1.50860349354899e-05 -8.1203063134372e-06 -1.18003508790827e-06 -1.93350504907783e-06 -4.98483447233366e-06 1.50860349354899e-05 4.81833404073568e-05 -8.01513436350434e-06 1.28648832032268e-05 4.06591992077912e-06 1.9401556455828e-05 -8.1203063134372e-06 -8.01513436350434e-06 1.37263071926147e-05 1.74475626029291e-06 -4.97785012613374e-07 -2.06994902489424e-07 -1.18003508790827e-06 1.28648832032268e-05 1.74475626029291e-06 4.12734825743503e-05 -2.83541220089808e-07 4.64024723852921e-06 -1.93350504907783e-06 4.06591992077912e-06 -4.97785012613374e-07 -2.83541220089808e-07 3.83220277644002e-05 4.32315056413047e-06 -4.98483447233366e-06 1.9401556455828e-05 -2.06994902489424e-07 4.64024723852921e-06 4.32315056413047e-06 7.19696131917253e-05 1585 1582 0 15 15 1540 1547 0 20 0 0 0 0 0 0 7 16 0 410 0 103 81 0 0 2183 +345 378 0.987543447553406 -0.00374232118558511 0.157302047750428 -0.0375290903220155 -0.015328653298784 0.992673694616608 0.119849774318768 -0.0242340634347021 -0.156598121260696 -0.120768087872409 0.980251037933275 -0.00829526124175015 5.7321341586586e-05 3.16937937175643e-05 -1.08165043623326e-05 2.94096927884071e-06 4.82742964756863e-06 2.1173967030449e-06 3.16937937175643e-05 5.7464780736488e-05 -1.03635435366687e-05 2.66301989981069e-06 1.18836229961548e-05 2.6623697715829e-05 -1.08165043623326e-05 -1.03635435366687e-05 1.32349551680034e-05 2.87162555992539e-07 -1.5870452560566e-08 -1.52047266962852e-06 2.94096927884071e-06 2.66301989981069e-06 2.87162555992539e-07 3.59910395232015e-05 -1.11899363989225e-05 1.16668234868187e-05 4.82742964756863e-06 1.18836229961548e-05 -1.5870452560566e-08 -1.11899363989225e-05 4.60132781611426e-05 -1.49739976447254e-07 2.1173967030449e-06 2.6623697715829e-05 -1.52047266962852e-06 1.16668234868187e-05 -1.49739976447254e-07 8.8270827036648e-05 1592 1583 0 17 18 1548 1552 0 22 2 0 0 0 0 0 5 16 0 442 0 103 80 0 0 2243 +346 349 0.999866913300348 0.00216906468329119 0.0161694417230019 0.00706202052136195 -0.00204677614431726 0.999969209586967 -0.00757565742570808 -0.00562739434675641 -0.0161853759501876 0.00754155397887803 0.999840566574959 -0.0123104702201277 0.00014141026171161 5.46181720194787e-05 -2.85082859214522e-05 1.43785357275004e-05 -2.4279789456824e-05 4.90472518156001e-05 5.46181720194787e-05 0.000120873379875686 -2.16596832619366e-05 3.33919685836679e-05 8.96151751786078e-06 5.1701325775618e-05 -2.85082859214522e-05 -2.16596832619366e-05 2.5445622313845e-05 -9.26434518770051e-07 -1.68220710924311e-06 -1.83293403852821e-05 1.43785357275004e-05 3.33919685836679e-05 -9.26434518770051e-07 8.95608270206588e-05 -5.96803951663814e-05 3.24080850651171e-05 -2.4279789456824e-05 8.96151751786078e-06 -1.68220710924311e-06 -5.96803951663814e-05 0.000108385350504122 3.21368557802422e-06 4.90472518156001e-05 5.1701325775618e-05 -1.83293403852821e-05 3.24080850651171e-05 3.21368557802422e-06 0.000114378318345809 1448 1412 0 4 68 1417 1436 0 13 31 0 0 0 0 0 9 18 0 262 0 82 49 0 0 3207 +345 405 0.986176072183245 -0.00241883884748365 0.165683142992453 -0.0386053129470093 -0.0169191010369105 0.993197590217504 0.115205428718639 -0.0195984627800811 -0.164834761726192 -0.116416047024336 0.979426773843709 -0.0099234826791973 0.000112552758167604 0.00010092091728489 -1.60819399206105e-05 4.90232487389075e-05 -3.48850870286884e-05 8.86570922855121e-05 0.00010092091728489 0.000170112737283666 -1.86261707367478e-05 7.06346246477245e-05 -3.62150128000361e-05 0.000134282162352715 -1.60819399206105e-05 -1.86261707367478e-05 1.39925081250087e-05 -6.18728876118022e-06 9.57327420639332e-06 -1.63412166021852e-05 4.90232487389075e-05 7.06346246477245e-05 -6.18728876118022e-06 7.73522663761168e-05 -2.62570299457721e-05 6.70319674790937e-05 -3.48850870286884e-05 -3.62150128000361e-05 9.57327420639332e-06 -2.62570299457721e-05 6.2728722326971e-05 -4.5773299016987e-05 8.86570922855121e-05 0.000134282162352715 -1.63412166021852e-05 6.70319674790937e-05 -4.5773299016987e-05 0.000213857206601784 1526 1526 0 14 16 1510 1534 0 21 9 0 0 0 0 0 4 17 0 240 0 85 89 0 0 1769 +345 395 0.984142250260212 -3.0990603978317e-05 0.177381031376946 -0.0297981657415802 -0.0184861997247817 0.994536600129672 0.102738558595344 -0.022674693773105 -0.176415111803105 -0.104388457417935 0.978764914719261 0.00321496812707077 0.000296402986948825 0.000242946252200132 -6.03756364921794e-05 6.66913671545183e-05 -5.71686651426941e-05 0.000232431866920788 0.000242946252200132 0.000291270659896613 -5.36281080995273e-05 8.72818677443588e-05 -5.8182957175686e-05 0.000244951367765572 -6.03756364921794e-05 -5.36281080995273e-05 2.72233924438187e-05 -9.15984486652965e-06 1.58766653208569e-05 -5.07824037789061e-05 6.66913671545183e-05 8.72818677443588e-05 -9.15984486652965e-06 7.7165499029054e-05 -2.82236614879867e-05 9.09055261649572e-05 -5.71686651426941e-05 -5.8182957175686e-05 1.58766653208569e-05 -2.82236614879867e-05 6.40869739248105e-05 -7.72116344848671e-05 0.000232431866920788 0.000244951367765572 -5.07824037789061e-05 9.09055261649572e-05 -7.72116344848671e-05 0.00035078021403434 1549 1547 0 20 13 1532 1552 0 26 1 0 0 0 0 0 5 18 0 225 0 133 119 0 0 1801 +345 403 0.985909710563773 -0.00189157629154437 0.167267643479518 -0.0338080482467169 -0.0171445721982719 0.993527664974015 0.112289102656583 -0.0207433688580134 -0.166397434656295 -0.113574648889687 0.979496142345333 -0.0051966002357233 0.000155758085818175 9.44287959125304e-05 -2.53610003752943e-05 -4.25654794043426e-07 -3.79992625676833e-06 7.14839151066192e-05 9.44287959125304e-05 0.000114496197538013 -1.96538276231465e-05 1.6482939993429e-05 -6.93778632052123e-06 7.52321683726788e-05 -2.53610003752943e-05 -1.96538276231465e-05 1.65739444309214e-05 3.82422164708038e-06 3.06928717531494e-06 -1.17184829564166e-05 -4.25654794043426e-07 1.6482939993429e-05 3.82422164708038e-06 4.86449571943231e-05 -8.47639312229453e-06 2.33678620117948e-05 -3.79992625676833e-06 -6.93778632052123e-06 3.06928717531494e-06 -8.47639312229453e-06 4.13837431757253e-05 -9.85123444283924e-06 7.14839151066192e-05 7.52321683726788e-05 -1.17184829564166e-05 2.33678620117948e-05 -9.85123444283924e-06 0.000146920056723591 1542 1547 0 13 13 1531 1547 0 19 6 0 0 0 0 0 3 14 0 226 0 78 72 0 0 1757 +345 382 0.987441403653116 -0.00380946044473225 0.157939742822013 -0.0436869336860333 -0.0156462147238963 0.992436535380223 0.121757624842606 -0.0230312090653628 -0.157209002020804 -0.122699679109683 0.979913321896383 -0.0175204297793279 5.95673669451125e-05 2.48474297633421e-05 -9.63459325730586e-06 2.80839758434146e-06 3.62159080144744e-06 -6.68583034693054e-06 2.48474297633421e-05 4.91963120327321e-05 -1.02394755055479e-05 1.12638664711631e-05 4.16155063943422e-06 8.99233650905228e-06 -9.63459325730586e-06 -1.02394755055479e-05 1.49302022842224e-05 1.35451638195065e-06 -1.10830218788036e-06 -2.01327015220106e-07 2.80839758434146e-06 1.12638664711631e-05 1.35451638195065e-06 4.85947745415926e-05 -1.43065266222608e-05 -8.14568703207206e-07 3.62159080144744e-06 4.16155063943422e-06 -1.10830218788036e-06 -1.43065266222608e-05 4.19666003460836e-05 6.86752167092873e-06 -6.68583034693054e-06 8.99233650905228e-06 -2.01327015220106e-07 -8.14568703207206e-07 6.86752167092873e-06 7.01402310102991e-05 1650 1654 0 18 18 1658 1685 0 22 3 0 0 0 0 0 7 17 0 450 0 112 90 0 0 2209 +345 390 0.986470605571153 -0.00207925381487315 0.163925047041801 -0.0358827198288876 -0.0167948889344932 0.993376745665968 0.113668697871355 -0.0237083968915148 -0.163075675837205 -0.114883932182288 0.979902039020521 -0.00681675673093837 9.70170933617925e-05 4.70858063174464e-05 -1.50917779179732e-05 2.05239655518761e-05 -9.42550821045865e-06 2.45136049691742e-05 4.70858063174464e-05 8.70237647217392e-05 -1.31451434877299e-05 2.93607136115724e-05 2.90977902013444e-06 5.55204048395424e-05 -1.50917779179732e-05 -1.31451434877299e-05 1.48322734097882e-05 3.49445083004258e-07 4.77821844766233e-06 -6.19446749144089e-06 2.05239655518761e-05 2.93607136115724e-05 3.49445083004258e-07 4.5267322534023e-05 -5.44524675437935e-07 2.74595194387475e-05 -9.42550821045865e-06 2.90977902013444e-06 4.77821844766233e-06 -5.44524675437935e-07 4.60330361161383e-05 6.24840957115705e-06 2.45136049691742e-05 5.55204048395424e-05 -6.19446749144089e-06 2.74595194387475e-05 6.24840957115705e-06 0.000151408837438331 1602 1607 0 15 13 1599 1612 0 22 12 0 0 0 0 0 5 16 0 204 0 108 88 0 0 1855 +345 381 0.98701029234331 -0.00319093558692534 0.160625342765253 -0.040185416559791 -0.0161254116061451 0.992786081832282 0.118809792612555 -0.0236260313377061 -0.159845719082206 -0.119856637906234 0.979838625713901 -0.0163462117464952 7.83791468433407e-05 5.0034967866553e-05 -1.13591253390086e-05 1.27734829459028e-05 -8.2980587208984e-06 2.5321758731998e-05 5.0034967866553e-05 7.51217264148348e-05 -1.21153837330919e-05 1.57859073107452e-05 -3.05151307493451e-06 5.21194988761504e-05 -1.13591253390086e-05 -1.21153837330919e-05 1.33116430617487e-05 -9.39759860306644e-07 4.41447190921263e-06 -3.12085642785212e-06 1.27734829459028e-05 1.57859073107452e-05 -9.39759860306644e-07 3.81513779205252e-05 -7.39954715126479e-06 1.69901508131931e-05 -8.2980587208984e-06 -3.05151307493451e-06 4.41447190921263e-06 -7.39954715126479e-06 3.92255614276847e-05 5.47611571779476e-07 2.5321758731998e-05 5.21194988761504e-05 -3.12085642785212e-06 1.69901508131931e-05 5.47611571779476e-07 0.000118495953076618 1655 1657 0 14 17 1655 1682 0 17 0 0 0 0 0 0 6 15 0 427 0 111 90 0 0 2204 +346 397 0.987625197302821 0.00362555839866702 0.156790704376443 -0.0333054741966611 -0.0206066295324249 0.994065361240542 0.106814907204116 -0.0269679943503805 -0.155472944501211 -0.108724021761561 0.98183870906586 -0.0045329181925019 0.000211470944854727 0.000168242931009075 -3.45174307945851e-05 9.55786897273892e-06 -1.62638071869372e-05 0.000129792687306667 0.000168242931009075 0.000230447443822187 -3.09962269664121e-05 4.51907935559169e-05 -2.95810037992306e-05 0.000169579692699158 -3.45174307945851e-05 -3.09962269664121e-05 1.98625778346933e-05 3.14650593276453e-06 5.75627550771865e-06 -2.18999652451542e-05 9.55786897273892e-06 4.51907935559169e-05 3.14650593276453e-06 7.53237919187282e-05 -4.01875570083113e-05 2.60253339707583e-05 -1.62638071869372e-05 -2.95810037992306e-05 5.75627550771865e-06 -4.01875570083113e-05 7.38754168504873e-05 -1.63171713653949e-05 0.000129792687306667 0.000169579692699158 -2.18999652451542e-05 2.60253339707583e-05 -1.63171713653949e-05 0.00022283231779536 1179 1177 0 10 19 1161 1179 0 21 6 0 0 0 0 0 4 16 0 241 0 110 92 0 0 1895 +346 410 0.988988612993095 0.00374242467928166 0.14794430582998 -0.0465086066551307 -0.0201316967320249 0.993789656171214 0.109438722917391 -0.0118985335236954 -0.146615954645749 -0.111212020684005 0.98292199502234 -0.0133569684566899 0.000109692991458007 4.82053852755871e-05 -1.65486807572948e-05 1.45462351335674e-05 -3.50265820834588e-05 2.75888761912136e-05 4.82053852755871e-05 7.33108752115503e-05 -9.66447697630343e-06 1.09086422241594e-05 -3.64371489288732e-06 2.56060312115083e-05 -1.65486807572948e-05 -9.66447697630343e-06 1.45860826773976e-05 1.97001322824556e-06 1.16141491793068e-05 -3.0831025432569e-06 1.45462351335674e-05 1.09086422241594e-05 1.97001322824556e-06 5.36073958461976e-05 -2.24989785253121e-05 7.94522776049572e-06 -3.50265820834588e-05 -3.64371489288732e-06 1.16141491793068e-05 -2.24989785253121e-05 6.67701698456991e-05 -8.82944993780474e-06 2.75888761912136e-05 2.56060312115083e-05 -3.0831025432569e-06 7.94522776049572e-06 -8.82944993780474e-06 9.08100043925238e-05 1372 1372 0 11 13 1354 1376 0 24 6 0 0 0 0 0 4 16 0 299 0 79 81 0 0 1690 +346 350 0.999999845677587 0.00046084606393361 -0.00031026715516853 -0.0105450757306472 -0.000463432592581492 0.999964707293234 -0.00838864698208638 -0.00401673625315926 0.00030639033005738 0.00838878947544224 0.999964766547353 -0.023282924125829 4.73225893383786e-05 1.39700262160892e-05 -4.61307087529392e-06 6.25819197635162e-06 -2.51630359784465e-06 8.51648564093427e-07 1.39700262160892e-05 4.37507273841195e-05 -8.39624835303337e-06 1.53718499425004e-05 -6.4525877679172e-08 2.27210267813205e-05 -4.61307087529392e-06 -8.39624835303337e-06 1.67080646459843e-05 6.11754067599937e-06 -6.11746259656778e-06 -4.2254702201074e-06 6.25819197635162e-06 1.53718499425004e-05 6.11754067599937e-06 6.72236340361578e-05 -4.30278349116168e-05 2.87378142870446e-05 -2.51630359784465e-06 -6.4525877679172e-08 -6.11746259656778e-06 -4.30278349116168e-05 6.84697374387738e-05 -4.17294245547462e-06 8.51648564093427e-07 2.27210267813205e-05 -4.2254702201074e-06 2.87378142870446e-05 -4.17294245547462e-06 7.76908516685938e-05 1875 1845 0 2 65 1842 1864 0 13 31 0 0 0 0 0 4 14 0 286 0 64 32 0 0 3100 +346 348 0.999952898308021 0.00263852260149479 0.00934020148984878 0.00607275686090395 -0.00257205596176033 0.999971337086495 -0.00712106267186014 -0.000665801715657832 -0.00935872285726772 0.0070967037368336 0.999931023172375 0.00460078803546138 6.81533288264193e-05 1.98691696370216e-05 -1.1002718308845e-05 2.39465588244639e-06 -1.19246204533925e-05 2.07967388605551e-05 1.98691696370216e-05 8.71328556898933e-05 -1.32618295739139e-05 2.72112103425485e-05 1.4685771509366e-06 3.53210955130154e-05 -1.1002718308845e-05 -1.32618295739139e-05 1.96512719539209e-05 3.99677395526987e-07 -5.33549933206037e-07 -7.61242675273065e-06 2.39465588244639e-06 2.72112103425485e-05 3.99677395526987e-07 5.79826832519858e-05 -2.18378825039308e-05 2.26595849847946e-05 -1.19246204533925e-05 1.4685771509366e-06 -5.33549933206037e-07 -2.18378825039308e-05 6.00913870114885e-05 -9.89956535299242e-06 2.07967388605551e-05 3.53210955130154e-05 -7.61242675273065e-06 2.26595849847946e-05 -9.89956535299242e-06 7.16435539756436e-05 1405 1373 0 3 64 1363 1371 0 14 21 0 0 0 0 0 5 15 0 274 0 87 65 0 0 3212 +346 409 0.990687002872775 0.00356577141548809 0.136112261068469 -0.0517494340353774 -0.0189652045731757 0.993526117563515 0.11200970821615 -0.0197526387470366 -0.134831685276334 -0.113547959001393 0.984341037269178 -0.0249881642765996 9.0853605942966e-05 6.01489262835084e-05 -1.0623953343021e-05 1.27599682276608e-05 -1.70067357876396e-05 2.35738722243235e-05 6.01489262835084e-05 9.78544908349969e-05 -9.85752173524615e-06 2.36648615847174e-05 -2.09270953131516e-05 6.38192432042929e-05 -1.0623953343021e-05 -9.85752173524615e-06 1.42279161154993e-05 -9.47177329527702e-08 8.06560208341398e-06 -7.35967254185614e-06 1.27599682276608e-05 2.36648615847174e-05 -9.47177329527702e-08 5.91754146188313e-05 -1.82333681073985e-05 1.07603956954967e-05 -1.70067357876396e-05 -2.09270953131516e-05 8.06560208341398e-06 -1.82333681073985e-05 5.91216341984685e-05 -1.15788010955981e-05 2.35738722243235e-05 6.38192432042929e-05 -7.35967254185614e-06 1.07603956954967e-05 -1.15788010955981e-05 0.000137045619203206 1465 1464 0 10 21 1443 1464 0 19 11 0 0 0 0 0 3 14 0 293 0 71 74 0 0 1659 +346 411 0.988749656041403 0.00419831388669887 0.149520874256793 -0.0418398273755357 -0.0203015169040089 0.994122963539421 0.106336173407717 -0.0180247571946802 -0.148195701993692 -0.108175355437865 0.983023970402802 -0.013976284286037 0.000119475187690614 0.000100171818687233 -1.56435573799539e-05 3.10283120262172e-05 -2.19184994747421e-05 5.40499937375033e-05 0.000100171818687233 0.000153107607518636 -1.78829608487629e-05 4.11991940701665e-05 -1.87933278973543e-05 8.91595792369845e-05 -1.56435573799539e-05 -1.78829608487629e-05 1.51479197164881e-05 -6.16069669171819e-07 5.75190118886667e-06 -8.09764026751965e-06 3.10283120262172e-05 4.11991940701665e-05 -6.16069669171819e-07 5.78009664090188e-05 -2.4508065018716e-05 3.43983714430221e-05 -2.19184994747421e-05 -1.87933278973543e-05 5.75190118886667e-06 -2.4508065018716e-05 5.62731507070126e-05 -1.46575834160994e-05 5.40499937375033e-05 8.91595792369845e-05 -8.09764026751965e-06 3.43983714430221e-05 -1.46575834160994e-05 0.000147052139484619 1185 1185 0 11 11 1167 1184 0 23 2 0 0 0 0 0 5 17 0 324 0 66 71 0 0 1707 +346 386 0.989215493147671 0.00197395762788328 0.146454127998815 -0.0443710733387075 -0.0195010876115391 0.992781878157033 0.118337863699495 -0.0122737946589934 -0.145163410329797 -0.119917662978715 0.982113709509824 -0.0140095469951941 8.26117044670998e-05 1.57428637993425e-05 -1.35839079514053e-05 -9.55581390761808e-07 -5.6442611560897e-06 9.047746911765e-06 1.57428637993425e-05 7.24128314652501e-05 -5.17380709435914e-06 1.79583171109685e-05 5.82594531098697e-06 3.95593257253813e-05 -1.35839079514053e-05 -5.17380709435914e-06 1.41736660703205e-05 1.21696303417791e-06 2.81312724636597e-06 -4.64041185899858e-07 -9.55581390761808e-07 1.79583171109685e-05 1.21696303417791e-06 4.78238780948932e-05 -8.09622478665266e-06 1.00841915378046e-05 -5.6442611560897e-06 5.82594531098697e-06 2.81312724636597e-06 -8.09622478665266e-06 5.70349345849929e-05 6.45039196115814e-06 9.047746911765e-06 3.95593257253813e-05 -4.64041185899858e-07 1.00841915378046e-05 6.45039196115814e-06 9.36492375820922e-05 1418 1416 0 10 19 1389 1415 0 22 7 0 0 0 0 0 6 16 0 411 0 113 90 0 0 2174 +346 408 0.986839388491555 0.00334493315143809 0.161668898505019 -0.031717400756558 -0.0210226012966263 0.993954791905742 0.107758627878864 -0.0252143855098482 -0.160331130964441 -0.109739159236003 0.98094405822852 -0.00922596745767361 0.000232886767301178 9.09035566548293e-05 -3.44224972001507e-05 3.27175954831039e-05 -7.46579901421418e-05 8.13662017472641e-05 9.09035566548293e-05 0.000113006859922139 -1.61485145269196e-05 3.16201028935546e-05 -3.59171403441585e-05 7.79606338953041e-05 -3.44224972001507e-05 -1.61485145269196e-05 1.8705927578988e-05 -3.41159269365541e-07 1.71080255752156e-05 -1.35742765107547e-05 3.27175954831039e-05 3.16201028935546e-05 -3.41159269365541e-07 5.03220406828462e-05 -2.6616844503472e-05 3.33915588265164e-05 -7.46579901421418e-05 -3.59171403441585e-05 1.71080255752156e-05 -2.6616844503472e-05 6.96943283039068e-05 -3.80019777857441e-05 8.13662017472641e-05 7.79606338953041e-05 -1.35742765107547e-05 3.33915588265164e-05 -3.80019777857441e-05 0.000154311401861345 1500 1510 0 12 20 1474 1495 0 23 11 0 0 0 0 0 6 17 0 271 0 80 87 0 0 1751 +346 387 0.989053254867206 0.00191507103356595 0.147546574136852 -0.0414997374215191 -0.0191570690882039 0.993119704818365 0.115526008350643 -0.0184473490019932 -0.146310169641535 -0.117087934495487 0.982284963671462 -0.0191685418951429 6.71506801255852e-05 1.72143829459765e-05 -1.02590241011685e-05 2.11887851873408e-06 -1.63642805373843e-07 5.25906154079626e-06 1.72143829459765e-05 6.78155668292451e-05 -1.17986175196261e-05 1.3722075778086e-05 6.37228679868225e-06 3.21308454158384e-05 -1.02590241011685e-05 -1.17986175196261e-05 1.59236068501442e-05 -7.15862043689773e-07 -6.67613547458571e-07 -4.65638182381943e-06 2.11887851873408e-06 1.3722075778086e-05 -7.15862043689773e-07 4.19628747739303e-05 -5.45140065074318e-06 2.88909889208665e-06 -1.63642805373843e-07 6.37228679868225e-06 -6.67613547458571e-07 -5.45140065074318e-06 5.28434105952861e-05 8.99053517512978e-06 5.25906154079626e-06 3.21308454158384e-05 -4.65638182381943e-06 2.88909889208665e-06 8.99053517512978e-06 8.84479320085879e-05 1500 1507 0 11 18 1465 1487 0 23 7 0 0 0 0 0 6 19 0 428 0 123 110 0 0 2199 +346 396 0.987660729647495 0.00384228082704347 0.15656155335913 -0.034462531789559 -0.0209529786554391 0.993953125416674 0.107787555681957 -0.0255892189121205 -0.155200695222806 -0.109737966777558 0.981768976312597 -0.00119985619154328 0.000173642950030512 9.31064352115139e-05 -2.77109408956546e-05 1.50152969439464e-05 -2.60046754669875e-05 8.76902100748541e-05 9.31064352115139e-05 0.000145983828040396 -1.92507910587561e-05 3.01415187728495e-05 -1.1250943947655e-05 9.30916452912377e-05 -2.77109408956546e-05 -1.92507910587561e-05 1.69423872255441e-05 2.29853016181514e-06 9.3322258578408e-06 -1.57752480382855e-05 1.50152969439464e-05 3.01415187728495e-05 2.29853016181514e-06 5.40958406353576e-05 -8.18577567251172e-06 2.13673431093637e-05 -2.60046754669875e-05 -1.1250943947655e-05 9.3322258578408e-06 -8.18577567251172e-06 5.42907446151635e-05 -1.31450948056183e-05 8.76902100748541e-05 9.30916452912377e-05 -1.57752480382855e-05 2.13673431093637e-05 -1.31450948056183e-05 0.00016401322137843 1532 1532 0 12 15 1518 1539 0 24 3 0 0 0 0 0 3 16 0 240 0 131 114 0 0 1919 +346 389 0.989190891933999 0.00332228017822109 0.146595844993086 -0.0433454828745296 -0.019561049816981 0.993797538774212 0.109470622800716 -0.0180073153365912 -0.145322897868427 -0.111154911635683 0.983120461069948 -0.0138907510724423 0.000127435781677807 3.45175626377291e-05 -1.45166081099898e-05 9.78914681083129e-06 -4.29300285563278e-05 1.29214865711946e-05 3.45175626377291e-05 8.0789255333207e-05 -6.26961667061656e-06 2.19688178563655e-05 -9.74555727617297e-06 3.78293146819534e-05 -1.45166081099898e-05 -6.26961667061656e-06 1.51073600224498e-05 2.91164138994017e-06 9.77317368536249e-06 -3.56272649457524e-06 9.78914681083129e-06 2.19688178563655e-05 2.91164138994017e-06 4.53680417876432e-05 -1.83375322280288e-05 7.97946729428964e-06 -4.29300285563278e-05 -9.74555727617297e-06 9.77317368536249e-06 -1.83375322280288e-05 6.47339611636421e-05 -5.27120803297768e-06 1.29214865711946e-05 3.78293146819534e-05 -3.56272649457524e-06 7.97946729428964e-06 -5.27120803297768e-06 0.000121840919767466 1285 1281 0 10 21 1261 1277 0 23 3 0 0 0 0 0 5 16 0 301 0 121 98 0 0 2022 +346 406 0.988239846604532 0.00240681671216347 0.152892814796395 -0.0420349919330807 -0.0202774448006593 0.993108372626873 0.115432168180108 -0.0130899546858751 -0.151561310417293 -0.11717494378799 0.981478069919484 -0.0205341258423198 9.09491422110503e-05 3.82988252163245e-05 -9.44420541903576e-06 1.07605587644973e-05 -1.87721592140193e-05 4.11718773337115e-07 3.82988252163245e-05 7.24307084152456e-05 -9.5783452355014e-06 1.74832424584021e-05 -5.96923412354072e-06 9.12908966447218e-06 -9.44420541903576e-06 -9.5783452355014e-06 1.53415931755377e-05 3.79872373219944e-06 5.5929863759841e-06 -2.77759604559256e-06 1.07605587644973e-05 1.74832424584021e-05 3.79872373219944e-06 5.3710668649791e-05 -2.82637969057966e-05 2.36501394441108e-06 -1.87721592140193e-05 -5.96923412354072e-06 5.5929863759841e-06 -2.82637969057966e-05 6.8951286206732e-05 -1.62951947761046e-06 4.11718773337115e-07 9.12908966447218e-06 -2.77759604559256e-06 2.36501394441108e-06 -1.62951947761046e-06 0.000106140286863895 1467 1467 0 8 13 1422 1439 0 21 5 0 0 0 0 0 6 16 0 255 0 87 89 0 0 1779 +346 383 0.988679993461668 0.00243364707255792 0.150019824991772 -0.0372710560333291 -0.0194674502265281 0.993497164785529 0.112180220826995 -0.0245878569040219 -0.148771263724932 -0.113830843469782 0.982298147287596 -0.0186732640463281 8.60664845005315e-05 3.68992687018955e-05 -1.46250644268128e-05 -4.49096162762372e-06 -1.75037535615908e-06 -7.41512886461214e-06 3.68992687018955e-05 6.33481072091661e-05 -1.25978613073882e-05 5.8074545443168e-06 5.82435852190778e-06 1.70630785488248e-05 -1.46250644268128e-05 -1.25978613073882e-05 1.51176749665732e-05 6.4400165698208e-07 1.1196266169595e-07 -7.07248436591649e-07 -4.49096162762372e-06 5.8074545443168e-06 6.4400165698208e-07 3.79811326381474e-05 -6.68246785750295e-06 -2.32341136414611e-06 -1.75037535615908e-06 5.82435852190778e-06 1.1196266169595e-07 -6.68246785750295e-06 4.35343905014334e-05 8.29476716772752e-06 -7.41512886461214e-06 1.70630785488248e-05 -7.07248436591649e-07 -2.32341136414611e-06 8.29476716772752e-06 7.49044863860444e-05 1713 1720 0 10 14 1681 1703 0 24 2 0 0 0 0 0 2 15 0 418 0 118 104 0 0 2197 +346 412 0.989568377094141 0.00303851763375391 0.144031921690499 -0.0462398922848988 -0.0191869282887845 0.993650670506534 0.110861205048283 -0.0173723407577961 -0.14278056183567 -0.112468272915102 0.983343581231598 -0.0209561235543004 7.86627941997263e-05 2.53132906987374e-05 -1.33098407451124e-05 1.9223604802599e-05 -2.00379361434381e-05 2.76787569103618e-06 2.53132906987374e-05 6.45685415876367e-05 -1.11970287906867e-05 1.27103061031662e-05 9.14877306344651e-06 2.16815034465198e-05 -1.33098407451124e-05 -1.11970287906867e-05 1.61291969697914e-05 -2.30210190118067e-07 4.68809632282097e-06 -3.97853563216622e-06 1.9223604802599e-05 1.27103061031662e-05 -2.30210190118067e-07 6.65852181856711e-05 -3.86623584200344e-05 7.47217126716885e-06 -2.00379361434381e-05 9.14877306344651e-06 4.68809632282097e-06 -3.86623584200344e-05 8.12608101676143e-05 -1.13662506830013e-06 2.76787569103618e-06 2.16815034465198e-05 -3.97853563216622e-06 7.47217126716885e-06 -1.13662506830013e-06 0.000106762015984146 1299 1298 0 9 14 1290 1308 0 20 7 0 0 0 0 0 3 15 0 356 0 75 77 0 0 1706 +346 385 0.989109880739542 0.00282215126033846 0.147151891886146 -0.0441803771071256 -0.0194481915265299 0.993555032778644 0.111669891584867 -0.0220798617178211 -0.145888353441101 -0.113315631324598 0.982789985718084 -0.0202728155239069 6.48242704157879e-05 2.10823682061237e-05 -1.04489378059607e-05 3.47557946570779e-06 -6.30099169792929e-06 -5.44988620413068e-06 2.10823682061237e-05 6.95248888335616e-05 -7.86979141634146e-06 1.82566423713035e-05 4.18022715216811e-06 1.89492371623703e-05 -1.04489378059607e-05 -7.86979141634146e-06 1.44765831921632e-05 -5.49201246652038e-07 2.45172180676364e-06 -2.30698180731338e-06 3.47557946570779e-06 1.82566423713035e-05 -5.49201246652038e-07 5.74826628540289e-05 -2.20809003513463e-05 -5.91629853176318e-06 -6.30099169792929e-06 4.18022715216811e-06 2.45172180676364e-06 -2.20809003513463e-05 5.96310558486902e-05 2.11260415068622e-05 -5.44988620413068e-06 1.89492371623703e-05 -2.30698180731338e-06 -5.91629853176318e-06 2.11260415068622e-05 8.77868294139367e-05 1623 1616 0 10 16 1571 1580 0 20 2 0 0 0 0 0 2 13 0 424 0 132 115 0 0 2157 +346 407 0.990760299382396 0.00358269783820916 0.135577260054571 -0.0528787736818818 -0.0192038271959482 0.99328501582708 0.114088081561689 -0.0162211827036037 -0.13425811777592 -0.11563754411781 0.984176161163066 -0.0205267567603609 8.44848033011414e-05 3.54761985147844e-05 -1.14648999350164e-05 1.54397571645388e-05 -1.34933461482114e-05 1.35754672623067e-05 3.54761985147844e-05 7.54974557974508e-05 -5.85767823985926e-06 2.33557485442099e-05 -6.43330472809478e-06 2.90607424335909e-05 -1.14648999350164e-05 -5.85767823985926e-06 1.37088422596318e-05 3.34145181489998e-06 5.11791294127768e-06 -2.79760955170209e-07 1.54397571645388e-05 2.33557485442099e-05 3.34145181489998e-06 7.04925825052983e-05 -2.40152400372398e-05 1.95602317301518e-05 -1.34933461482114e-05 -6.43330472809478e-06 5.11791294127768e-06 -2.40152400372398e-05 5.00929939923047e-05 -1.32033599605368e-05 1.35754672623067e-05 2.90607424335909e-05 -2.79760955170209e-07 1.95602317301518e-05 -1.32033599605368e-05 0.000103458869176249 1593 1590 0 8 24 1570 1592 0 22 12 0 0 0 0 0 5 17 0 276 0 75 80 0 0 1716 +346 382 0.988372595866092 0.00191627704453104 0.152039270003546 -0.0356725835134792 -0.0196939221973607 0.993111218426143 0.115508689130409 -0.0243719033082771 -0.150770558032419 -0.117159872475305 0.981601651950608 -0.0158501338132071 7.45841674982647e-05 2.35932838147317e-05 -1.00211666747426e-05 1.60598584365422e-05 -1.63709217695467e-05 -3.62024834135488e-06 2.35932838147317e-05 6.98826361850989e-05 -9.15328167183142e-06 1.93334750698861e-05 1.91099909789013e-06 1.81376028492124e-05 -1.00211666747426e-05 -9.15328167183142e-06 1.53399072004366e-05 -1.68384260003285e-06 3.29388310934829e-06 -1.83311198562602e-06 1.60598584365422e-05 1.93334750698861e-05 -1.68384260003285e-06 4.93295073013417e-05 -1.08635447729013e-05 7.81019975717852e-06 -1.63709217695467e-05 1.91099909789013e-06 3.29388310934829e-06 -1.08635447729013e-05 4.50077106429958e-05 4.33448159170429e-06 -3.62024834135488e-06 1.81376028492124e-05 -1.83311198562602e-06 7.81019975717852e-06 4.33448159170429e-06 9.7571066987106e-05 1514 1512 0 13 20 1465 1475 0 23 5 0 0 0 0 0 4 16 0 439 0 130 114 0 0 2237 +346 378 0.989289676743081 0.00255572854308661 0.145943152429926 -0.0348688166375 -0.0191487828070044 0.993478034490144 0.112404266389719 -0.0214220788805639 -0.144704041431401 -0.113995014089279 0.982886502682891 -0.00857831948265155 9.88319424523766e-05 2.0229424201721e-05 -1.74660448346985e-05 6.4429344572607e-06 -2.06053180834927e-05 -1.24334814810518e-05 2.0229424201721e-05 5.59383835335634e-05 -9.40501557574403e-06 1.65385147077674e-05 -3.27426593632165e-06 2.41801533248016e-05 -1.74660448346985e-05 -9.40501557574403e-06 1.52231820396471e-05 -2.70530008563397e-07 5.00817302779417e-06 1.09545776371883e-06 6.4429344572607e-06 1.65385147077674e-05 -2.70530008563397e-07 5.64307437341061e-05 -2.6406826401623e-05 1.07897104431786e-05 -2.06053180834927e-05 -3.27426593632165e-06 5.00817302779417e-06 -2.6406826401623e-05 5.95762029169342e-05 2.62653765755331e-06 -1.24334814810518e-05 2.41801533248016e-05 1.09545776371883e-06 1.07897104431786e-05 2.62653765755331e-06 8.75286685341928e-05 1443 1436 0 11 22 1422 1443 0 21 7 0 0 0 0 0 4 15 0 442 0 119 95 0 0 2225 +346 395 0.987503379200221 0.00527122562843088 0.157509651286896 -0.032628674827254 -0.0210797250815395 0.994877632215524 0.0988642610234793 -0.0245519610880789 -0.156181693096957 -0.100949051989635 0.982556139690635 -0.00261445274153382 0.000285982772673701 0.000138883592396295 -4.74493097613942e-05 -3.74818905638554e-06 -2.95242250969699e-05 0.000142644755298934 0.000138883592396295 0.000133137507535491 -2.57850789904941e-05 1.5889651751787e-05 -1.32273703205232e-05 9.43118847156124e-05 -4.74493097613942e-05 -2.57850789904941e-05 2.0959258590723e-05 6.58163635119784e-06 6.12497735292046e-06 -2.68840600348888e-05 -3.74818905638554e-06 1.5889651751787e-05 6.58163635119784e-06 5.30279623463055e-05 -1.48435719069296e-05 6.54426018007142e-06 -2.95242250969699e-05 -1.32273703205232e-05 6.12497735292046e-06 -1.48435719069296e-05 5.42342316657157e-05 -7.97991034719269e-06 0.000142644755298934 9.43118847156124e-05 -2.68840600348888e-05 6.54426018007142e-06 -7.97991034719269e-06 0.000217450432252873 1695 1700 0 14 19 1665 1684 0 24 6 0 0 0 0 0 7 18 0 231 0 133 124 0 0 1901 +346 388 0.98945838053022 0.00280611776668363 0.144790327375806 -0.0421319609024895 -0.0194584328097731 0.993321972980415 0.113722589606825 -0.0191730803753498 -0.143504294678247 -0.115341162198819 0.982905353384305 -0.0222542930342158 0.000118833294877859 5.69965542014372e-05 -1.68269939628058e-05 1.00082836945382e-05 -2.43973059291096e-05 5.48746459604447e-05 5.69965542014372e-05 0.00010558580019945 -1.05113711632391e-05 2.2282716371485e-05 -1.08858111261234e-05 7.8642733501061e-05 -1.68269939628058e-05 -1.05113711632391e-05 1.65219231797482e-05 3.1931206553772e-06 8.94813869425879e-06 -1.58392125041419e-05 1.00082836945382e-05 2.2282716371485e-05 3.1931206553772e-06 5.58143020534902e-05 -3.03508431466457e-05 1.4375207901e-05 -2.43973059291096e-05 -1.08858111261234e-05 8.94813869425879e-06 -3.03508431466457e-05 6.52667863914775e-05 -1.88522758203046e-05 5.48746459604447e-05 7.8642733501061e-05 -1.58392125041419e-05 1.4375207901e-05 -1.88522758203046e-05 0.000197837128611309 1608 1604 0 12 20 1557 1567 0 22 5 0 0 0 0 0 4 15 0 435 0 132 115 0 0 2086 +346 381 0.989317638839326 0.00211691953861175 0.145760516372053 -0.0385009707565695 -0.0190241625082501 0.993218279001498 0.114697565354115 -0.0216705380392206 -0.14452920370029 -0.1162452962875 0.982648635255141 -0.0197522242811932 7.37272398986105e-05 2.3766827832071e-05 -1.02234172203165e-05 2.45792906435223e-06 -7.47217076492638e-06 -4.12874622030409e-06 2.3766827832071e-05 6.35220066883014e-05 -6.51574018581089e-06 1.5938726090817e-05 -2.44962210235553e-06 1.13066711183528e-05 -1.02234172203165e-05 -6.51574018581089e-06 1.38597537570422e-05 1.30815746289459e-06 3.08587982930561e-06 -1.32852485399224e-07 2.45792906435223e-06 1.5938726090817e-05 1.30815746289459e-06 4.83692060412958e-05 -1.62422358571254e-05 -4.90308003667285e-08 -7.47217076492638e-06 -2.44962210235553e-06 3.08587982930561e-06 -1.62422358571254e-05 5.07232451538858e-05 2.64859531564771e-06 -4.12874622030409e-06 1.13066711183528e-05 -1.32852485399224e-07 -4.90308003667285e-08 2.64859531564771e-06 8.613368147619e-05 1432 1426 0 11 23 1379 1387 0 20 8 0 0 0 0 0 7 16 0 425 0 127 112 0 0 2247 +346 377 0.989101502693181 0.00166358814533045 0.147225846387697 -0.0372237500018373 -0.0190922688277321 0.99294284061752 0.117047001402941 -0.0206660963835844 -0.145992132120538 -0.118582240411004 0.982153017415314 -0.0113849036169357 0.000100376854297849 4.87501932023022e-05 -1.79776727674551e-05 1.36928729859909e-05 -9.27481811632315e-06 2.04032709322826e-05 4.87501932023022e-05 9.02377014859172e-05 -1.5308616772525e-05 1.28694016151081e-05 1.09150130736681e-06 5.41293649647596e-05 -1.79776727674551e-05 -1.5308616772525e-05 1.62277903733084e-05 3.24410976449852e-07 3.57392005387049e-06 -5.27616990298963e-06 1.36928729859909e-05 1.28694016151081e-05 3.24410976449852e-07 5.55096163260009e-05 -3.35479411068254e-05 8.2961174760218e-06 -9.27481811632315e-06 1.09150130736681e-06 3.57392005387049e-06 -3.35479411068254e-05 7.24579513740997e-05 5.64782877220471e-06 2.04032709322826e-05 5.41293649647596e-05 -5.27616990298963e-06 8.2961174760218e-06 5.64782877220471e-06 0.000134758591476186 1336 1334 0 10 21 1325 1342 0 21 5 0 0 0 0 0 4 16 0 424 0 131 107 0 0 2175 +346 399 0.988607908137849 0.00369305700611717 0.150468486060224 -0.0338199723056364 -0.0201699924318442 0.993932556425956 0.108126059217298 -0.0334154529175427 -0.149156211310845 -0.109929225443068 0.982684074370233 -0.00848201088294301 0.000106132193459969 5.64072736853035e-05 -1.57526104898155e-05 4.75761374610571e-06 -3.0747687488187e-06 3.68599636738276e-05 5.64072736853035e-05 0.00011868095864134 -1.24574898167244e-05 4.3102046925488e-05 -2.95942892790544e-06 6.58025564404013e-05 -1.57526104898155e-05 -1.24574898167244e-05 1.5839164981999e-05 6.13804612034961e-06 2.87605201178472e-06 -8.35385804457787e-06 4.75761374610571e-06 4.3102046925488e-05 6.13804612034961e-06 7.1288830628756e-05 -1.8619929904169e-05 3.34844161526781e-05 -3.0747687488187e-06 -2.95942892790544e-06 2.87605201178472e-06 -1.8619929904169e-05 5.33873518177054e-05 -1.79477970394538e-05 3.68599636738276e-05 6.58025564404013e-05 -8.35385804457787e-06 3.34844161526781e-05 -1.79477970394538e-05 0.000146144230337324 1325 1320 0 12 15 1312 1324 0 25 2 0 0 0 0 0 1 14 0 266 0 112 98 0 0 1891 +346 391 0.986701867829121 0.00266339821413893 0.162518707638464 -0.0279234164103032 -0.0210386397394364 0.993547357425535 0.111449648678904 -0.0213490816779893 -0.161173197711151 -0.113386749061298 0.980391067623972 -0.00427206594254169 0.000126927085109975 5.93490253539958e-05 -1.44562208484229e-05 1.66489172868592e-05 -2.99423620902953e-05 3.5599467933868e-05 5.93490253539958e-05 9.59939795691829e-05 -1.03132595028869e-05 2.53510423166509e-05 -1.64102182559089e-05 5.42604461747047e-05 -1.44562208484229e-05 -1.03132595028869e-05 1.44089214120652e-05 9.76880121312489e-07 7.65959257062829e-06 -4.28817647181784e-06 1.66489172868592e-05 2.53510423166509e-05 9.76880121312489e-07 4.9363329736795e-05 -2.31014668282426e-05 2.29470020261353e-05 -2.99423620902953e-05 -1.64102182559089e-05 7.65959257062829e-06 -2.31014668282426e-05 6.2308771232307e-05 -1.36229406164922e-05 3.5599467933868e-05 5.42604461747047e-05 -4.28817647181784e-06 2.29470020261353e-05 -1.36229406164922e-05 0.000125845520514494 1546 1556 0 15 21 1517 1535 0 19 11 0 0 0 0 0 5 14 0 197 0 121 109 0 0 1882 +347 350 0.999973468107286 0.00238043419357192 0.00688451992062851 0.00184200920313342 -0.00227495534521586 0.999880534162954 -0.015288622573139 -0.0131482810451213 -0.00692009101563924 0.0152725549616525 0.999859420821387 -0.00775240582707873 8.53699200602571e-05 3.48397788338744e-05 -1.81155333991637e-05 4.6835424969858e-06 5.53326662085653e-06 4.00198599700559e-05 3.48397788338744e-05 8.42052721753978e-05 -1.97567509348451e-05 3.15469161910864e-05 5.64503146162307e-06 6.13879649540853e-05 -1.81155333991637e-05 -1.97567509348451e-05 2.03801623363994e-05 -4.32316471415381e-06 -4.10882211432542e-06 -1.89821530946337e-05 4.6835424969858e-06 3.15469161910864e-05 -4.32316471415381e-06 6.35288251695505e-05 -2.40932079508634e-05 3.13742719764184e-05 5.53326662085653e-06 5.64503146162307e-06 -4.10882211432542e-06 -2.40932079508634e-05 4.82891288748948e-05 1.2523292292699e-05 4.00198599700559e-05 6.13879649540853e-05 -1.89821530946337e-05 3.13742719764184e-05 1.2523292292699e-05 0.000129230111078576 1923 1899 0 5 59 1890 1912 0 14 24 0 0 0 0 0 5 15 0 290 0 66 36 0 0 3216 +346 390 0.986415002214096 0.00425884460655444 0.164217251376288 -0.027146944994206 -0.0210092518959642 0.994725284517388 0.100400297193651 -0.0269420268516379 -0.162923462833742 -0.102486440978399 0.981301418868761 0.00759361940784709 0.00014436789383406 4.62377515874062e-05 -1.98875635276908e-05 1.88653185980607e-05 -2.01844076994907e-05 2.98075407495228e-05 4.62377515874062e-05 9.68401692076034e-05 -1.042117934056e-05 2.07667473746608e-05 7.87770288471913e-06 5.82961186556335e-05 -1.98875635276908e-05 -1.042117934056e-05 1.8233397728625e-05 4.58725304444917e-06 5.2009036656036e-06 -5.16529205877643e-06 1.88653185980607e-05 2.07667473746608e-05 4.58725304444917e-06 4.80099092134907e-05 -8.681405543726e-06 2.00991207116812e-05 -2.01844076994907e-05 7.87770288471913e-06 5.2009036656036e-06 -8.681405543726e-06 5.75591859214039e-05 2.88760768400161e-06 2.98075407495228e-05 5.82961186556335e-05 -5.16529205877643e-06 2.00991207116812e-05 2.88760768400161e-06 0.000145577188221733 1416 1415 0 13 17 1396 1410 0 21 3 0 0 0 0 0 4 15 0 198 0 114 90 0 0 1889 +346 413 0.990010286241977 0.00376843874394848 0.140944783530685 -0.0463846128727019 -0.0192171512632004 0.993920642281077 0.108408754004916 -0.0215770340812372 -0.139679398024211 -0.110034338808412 0.984064078223867 -0.0226653901341637 9.28005909078087e-05 2.39543837263656e-05 -1.2392977423354e-05 1.26288350332753e-05 -2.41467598293433e-05 -1.46954088429618e-07 2.39543837263656e-05 9.42206787321575e-05 -1.08318811977144e-05 2.35719899245827e-05 6.61326778197945e-06 5.92876171472105e-05 -1.2392977423354e-05 -1.08318811977144e-05 1.45229651068121e-05 2.75662555546384e-06 4.16912693070153e-06 -2.42000914389514e-06 1.26288350332753e-05 2.35719899245827e-05 2.75662555546384e-06 5.87228086849978e-05 -1.30460852514513e-05 1.50303354419057e-05 -2.41467598293433e-05 6.61326778197945e-06 4.16912693070153e-06 -1.30460852514513e-05 6.38745920758845e-05 6.69900966934716e-06 -1.46954088429618e-07 5.92876171472105e-05 -2.42000914389514e-06 1.50303354419057e-05 6.69900966934716e-06 0.000124118916743278 1393 1392 0 10 11 1376 1395 0 24 3 0 0 0 0 0 6 17 0 391 0 79 84 0 0 1669 +347 409 0.988410115245386 0.00539315490237031 0.151711429895051 -0.0439125573324259 -0.0207313367376164 0.994801340371576 0.0997020805800359 -0.0231430542708383 -0.150385025044629 -0.101691725696418 0.983383514793293 -0.00772543291838593 0.000190761478919075 0.000116138278473159 -2.34042845244238e-05 4.87276287295768e-05 -5.00515929708411e-05 7.74841807576628e-05 0.000116138278473159 0.000192364845058501 -2.15636064083958e-05 5.32642176065909e-05 -2.6490659791296e-05 0.000112323963399587 -2.34042845244238e-05 -2.15636064083958e-05 1.68499893914253e-05 -3.40655099134804e-06 1.24648849079206e-05 -1.49981482922918e-05 4.87276287295768e-05 5.32642176065909e-05 -3.40655099134804e-06 6.71048308932123e-05 -2.27507272390337e-05 2.86510184337672e-05 -5.00515929708411e-05 -2.6490659791296e-05 1.24648849079206e-05 -2.27507272390337e-05 5.68779062371034e-05 -2.99425465573103e-05 7.74841807576628e-05 0.000112323963399587 -1.49981482922918e-05 2.86510184337672e-05 -2.99425465573103e-05 0.00017187368667634 1320 1317 0 15 8 1288 1310 0 31 0 0 0 0 0 0 5 19 0 286 0 73 76 0 0 1655 +346 379 0.988626739306184 0.00267408318745939 0.15036628481122 -0.0265566893568906 -0.0193627996718358 0.993783510471084 0.109633098581755 -0.0315865464815293 -0.149138366350482 -0.111297725021112 0.982532729270346 -0.0122995990864117 9.25004619585634e-05 4.5780698601042e-05 -1.41252179509623e-05 1.78227289706125e-05 -2.01254576131963e-05 1.44582409512863e-05 4.5780698601042e-05 8.25271114467778e-05 -1.30414627482585e-05 2.21631186495688e-05 -2.58612731647376e-06 4.76851413773879e-05 -1.41252179509623e-05 -1.30414627482585e-05 1.54635941902381e-05 -1.33531128269907e-06 4.55665603848569e-06 -5.73394810198396e-06 1.78227289706125e-05 2.21631186495688e-05 -1.33531128269907e-06 5.13365139799442e-05 -1.99704864327792e-05 1.86834601506418e-05 -2.01254576131963e-05 -2.58612731647376e-06 4.55665603848569e-06 -1.99704864327792e-05 5.24664059958326e-05 -1.47547966097043e-05 1.44582409512863e-05 4.76851413773879e-05 -5.73394810198396e-06 1.86834601506418e-05 -1.47547966097043e-05 0.000114208704028774 1723 1726 0 12 19 1695 1711 0 25 7 0 0 0 0 0 4 15 0 427 0 115 101 0 0 2209 +347 410 0.989682124540129 0.00376526833098232 0.143230985195708 -0.0491559661928075 -0.0200253779958115 0.993477902276549 0.112252580924948 -0.0136727478894004 -0.141874157625208 -0.113962627394172 0.983302721930309 -0.0173383655922183 6.31633230079559e-05 1.77233498496377e-05 -7.33490308288853e-06 5.28423701411958e-06 -6.34119932056998e-06 -2.4664665165784e-06 1.77233498496377e-05 6.34710141058378e-05 -7.12609767992919e-06 3.67559600927819e-06 1.50976309732804e-05 1.60585745937269e-05 -7.33490308288853e-06 -7.12609767992919e-06 1.65753774666792e-05 6.17881851074369e-06 2.56514570576644e-06 -5.55494772394456e-06 5.28423701411958e-06 3.67559600927819e-06 6.17881851074369e-06 5.45423991564364e-05 -2.1198103960153e-05 -1.70485109763125e-05 -6.34119932056998e-06 1.50976309732804e-05 2.56514570576644e-06 -2.1198103960153e-05 6.06845349559688e-05 2.18024107519969e-05 -2.4664665165784e-06 1.60585745937269e-05 -5.55494772394456e-06 -1.70485109763125e-05 2.18024107519969e-05 0.000100234276427282 1332 1333 0 15 7 1310 1326 0 28 1 0 0 0 0 0 6 20 0 299 0 59 63 0 0 1652 +346 380 0.988624047301817 0.00292454502047949 0.150379320829024 -0.035575668110839 -0.0193823417101938 0.99395179464981 0.108093268718511 -0.0252793873916175 -0.14915367218545 -0.109778308189032 0.982701330580533 -0.0172880715299797 8.02392436114071e-05 5.08889472498602e-05 -1.35427748480897e-05 9.99969348421025e-06 -1.57609198560329e-05 7.71990996953379e-06 5.08889472498602e-05 0.000109670889061944 -1.47248659475895e-05 2.86119809683833e-05 -1.7370267674435e-05 4.5202455272257e-05 -1.35427748480897e-05 -1.47248659475895e-05 1.52651038880238e-05 -1.23755778322848e-06 4.19510470432533e-06 -4.52192031755387e-06 9.99969348421025e-06 2.86119809683833e-05 -1.23755778322848e-06 5.26034219582934e-05 -1.59577237290821e-05 1.51225323139905e-05 -1.57609198560329e-05 -1.7370267674435e-05 4.19510470432533e-06 -1.59577237290821e-05 4.9846520566372e-05 8.14506050890244e-06 7.71990996953379e-06 4.5202455272257e-05 -4.52192031755387e-06 1.51225323139905e-05 8.14506050890244e-06 0.000136825042187429 1531 1539 0 9 17 1504 1525 0 25 5 0 0 0 0 0 8 20 0 437 0 117 101 0 0 2180 +347 396 0.988269999582784 0.0038416013631494 0.152668431653734 -0.0351193756948267 -0.0210465719369158 0.993570715817568 0.111239716286358 -0.0286153430128133 -0.151259544275224 -0.113148021497205 0.981996983445937 -0.00496696410521126 0.000114461089323597 8.14724988460952e-05 -1.59430397640323e-05 2.1764441238806e-05 -1.87373466687677e-05 5.02982162489964e-05 8.14724988460952e-05 0.000163687762256471 -1.56902056221777e-05 5.74239501413777e-05 -2.44049225539453e-05 9.21386266117136e-05 -1.59430397640323e-05 -1.56902056221777e-05 1.63154272495632e-05 -3.17781916963891e-08 8.40089401884952e-06 -8.31044635109635e-06 2.1764441238806e-05 5.74239501413777e-05 -3.17781916963891e-08 7.48544448823062e-05 -2.32131851593072e-05 4.00779933557521e-05 -1.87373466687677e-05 -2.44049225539453e-05 8.40089401884952e-06 -2.32131851593072e-05 5.35999133952181e-05 -2.20025594711028e-05 5.02982162489964e-05 9.21386266117136e-05 -8.31044635109635e-06 4.00779933557521e-05 -2.20025594711028e-05 0.000154132912206051 1527 1527 0 14 15 1514 1535 0 28 1 0 0 0 0 0 6 19 0 248 0 118 101 0 0 1923 +347 349 0.999993356536458 0.00259275967995489 -0.00256212415609876 -0.00921060282434527 -0.00262060249825983 0.99993689572901 -0.0109241476727893 0.00347873154320946 0.00253363878549782 0.0109307894075768 0.999937047277193 -0.0146533056076459 0.000142472801692666 8.80638567532865e-05 -4.08271949786713e-05 2.54060261861513e-05 -1.29917392008404e-05 6.46322254499747e-05 8.80638567532865e-05 0.000179598982268207 -3.47485397774597e-05 6.50599837995855e-05 -8.91068073086764e-06 9.14128037138892e-05 -4.08271949786713e-05 -3.47485397774597e-05 3.00692914146708e-05 -9.18223777628386e-06 -3.65400835108582e-06 -2.32399573815213e-05 2.54060261861513e-05 6.50599837995855e-05 -9.18223777628386e-06 8.8374268552765e-05 -3.75470718161275e-05 6.29972424936575e-05 -1.29917392008404e-05 -8.91068073086764e-06 -3.65400835108582e-06 -3.75470718161275e-05 6.5241148276784e-05 -2.00088037987149e-05 6.46322254499747e-05 9.14128037138892e-05 -2.32399573815213e-05 6.29972424936575e-05 -2.00088037987149e-05 0.000129974322798723 1662 1630 0 5 60 1633 1648 0 15 24 0 0 0 0 0 6 15 0 275 0 74 41 0 0 3251 +347 411 0.988953302012199 0.00333573376758265 0.148189875900482 -0.0396349172974985 -0.0197913050006032 0.993766713467995 0.109708812086328 -0.019359004851561 -0.146900206553774 -0.111429763004558 0.982854891238379 -0.0115576343077858 9.57520357609667e-05 6.17806018791525e-05 -1.45941837643467e-05 8.57077337763757e-06 -7.72080108002481e-06 1.94648772616276e-05 6.17806018791525e-05 9.96233243624334e-05 -1.21365675053071e-05 2.38548035466243e-05 -1.02733331298923e-05 4.49641258204411e-05 -1.45941837643467e-05 -1.21365675053071e-05 1.47935791364971e-05 2.08142376057435e-06 3.50485415522383e-06 -3.66309115694262e-06 8.57077337763757e-06 2.38548035466243e-05 2.08142376057435e-06 4.82317205928336e-05 -1.48239278539079e-05 1.44896503386773e-05 -7.72080108002481e-06 -1.02733331298923e-05 3.50485415522383e-06 -1.48239278539079e-05 4.5101998018596e-05 -1.01247015435857e-05 1.94648772616276e-05 4.49641258204411e-05 -3.66309115694262e-06 1.44896503386773e-05 -1.01247015435857e-05 0.000109208458874879 1507 1512 0 16 9 1452 1467 0 28 0 0 0 0 0 0 5 19 0 327 0 67 73 0 0 1734 +347 351 0.999997233637969 0.00207170304556065 0.00111389537262835 -0.000904181358669759 -0.00205408632993786 0.999876350223473 -0.0155905417845751 -0.0163937870828622 -0.00114605661261149 0.0155882106182344 0.999877839660407 -0.0217567254158672 7.36132133151526e-05 3.48353860544228e-05 -1.72939741485651e-05 6.48454905978243e-06 -1.0336408354851e-06 1.53958652894721e-05 3.48353860544228e-05 0.00013868568631364 -2.61089096969681e-05 5.78934807264708e-05 7.81828902087173e-06 7.74248043287943e-05 -1.72939741485651e-05 -2.61089096969681e-05 2.15578987153278e-05 -5.51202126711328e-06 -2.45946955345262e-06 -1.59649083710492e-05 6.48454905978243e-06 5.78934807264708e-05 -5.51202126711328e-06 7.58335295554714e-05 -2.96418791204841e-05 5.14253967291882e-05 -1.0336408354851e-06 7.81828902087173e-06 -2.45946955345262e-06 -2.96418791204841e-05 6.38537072668849e-05 2.95785596143768e-06 1.53958652894721e-05 7.74248043287943e-05 -1.59649083710492e-05 5.14253967291882e-05 2.95785596143768e-06 0.000113692595750104 1898 1901 0 6 29 1884 1905 0 14 20 0 0 0 0 0 9 17 0 317 0 36 44 0 0 3010 +347 387 0.989723682692786 0.00292964378042998 0.142963103996625 -0.0455290747723198 -0.0195459019148258 0.993177525764639 0.11496242879465 -0.0161382087375843 -0.1416509429385 -0.116575381206105 0.983028580897466 -0.013558630741311 6.65555013801904e-05 1.42039454124186e-05 -1.11566007241305e-05 -8.94278070759641e-07 -7.41494310854704e-08 -8.25991398041612e-06 1.42039454124186e-05 5.54657656034112e-05 -9.03383562831798e-06 1.14289406752775e-05 9.57402507505099e-06 1.62074322410796e-05 -1.11566007241305e-05 -9.03383562831798e-06 1.73710832068303e-05 3.22580466338022e-08 -1.81738891393471e-06 -1.4372637497112e-06 -8.94278070759641e-07 1.14289406752775e-05 3.22580466338022e-08 4.97717171017865e-05 -9.37170862902473e-06 4.2911473570945e-06 -7.41494310854704e-08 9.57402507505099e-06 -1.81738891393471e-06 -9.37170862902473e-06 5.14155076301948e-05 6.98101873221454e-06 -8.25991398041612e-06 1.62074322410796e-05 -1.4372637497112e-06 4.2911473570945e-06 6.98101873221454e-06 6.89119793876407e-05 1639 1646 0 15 15 1596 1617 0 29 2 0 0 0 0 0 8 22 0 426 0 133 114 0 0 2166 +347 398 0.989812440247009 0.00241961488284287 0.142356870561557 -0.0323369206587962 -0.0187351749010616 0.993374796614882 0.113382126773884 -0.0384622488110173 -0.141139386259427 -0.114894120450793 0.983300063425276 -0.0226114822280036 9.28037190862796e-05 4.45287109164337e-05 -1.56929931898593e-05 6.42440281124764e-06 3.39987015009644e-07 2.56086587520357e-05 4.45287109164337e-05 9.94349966394536e-05 -1.11390883769683e-05 2.81695476811815e-05 -1.95131783731104e-06 7.76949975200938e-05 -1.56929931898593e-05 -1.11390883769683e-05 1.57601135300219e-05 3.59555611706603e-06 2.36878615344811e-06 -4.74725888675278e-06 6.42440281124764e-06 2.81695476811815e-05 3.59555611706603e-06 4.87071774221212e-05 -1.20429691218986e-05 3.26594249521277e-05 3.39987015009644e-07 -1.95131783731104e-06 2.36878615344811e-06 -1.20429691218986e-05 5.20864718952109e-05 -8.17576494037313e-06 2.56086587520357e-05 7.76949975200938e-05 -4.74725888675278e-06 3.26594249521277e-05 -8.17576494037313e-06 0.0001561682351857 1832 1839 0 22 14 1795 1812 0 32 1 0 0 0 0 0 2 16 0 254 0 111 103 0 0 1815 +347 389 0.988914449893793 0.00315711538221762 0.148452832285949 -0.0394791348934962 -0.0198544533953817 0.993607636545671 0.111129047861016 -0.0226694706008665 -0.147153020599739 -0.112844571072732 0.982655632105054 -0.0117778420526465 6.61106746093463e-05 3.77648060604859e-05 -6.90282327426346e-06 7.74678796186472e-06 -1.64345562720756e-05 4.53814375379457e-06 3.77648060604859e-05 0.000163835622841101 -8.63760658803222e-06 5.00611685260746e-05 -2.21719064433986e-05 4.92830260606918e-05 -6.90282327426346e-06 -8.63760658803222e-06 1.40109449036756e-05 2.82548838362942e-06 6.23335675331538e-06 -2.81655794521741e-06 7.74678796186472e-06 5.00611685260746e-05 2.82548838362942e-06 6.29855903141911e-05 -2.79067316258801e-05 1.2025778458529e-05 -1.64345562720756e-05 -2.21719064433986e-05 6.23335675331538e-06 -2.79067316258801e-05 6.15599028187832e-05 2.43321348564857e-06 4.53814375379457e-06 4.92830260606918e-05 -2.81655794521741e-06 1.2025778458529e-05 2.43321348564857e-06 0.000104364914650163 1396 1396 0 13 14 1338 1349 0 26 0 0 0 0 0 0 7 19 0 298 0 115 99 0 0 2015 +347 408 0.98828733788262 0.00370097690468089 0.152559629492327 -0.0334147391836957 -0.0202469301238136 0.994047937753076 0.107045594348476 -0.0281099111418346 -0.151255411808789 -0.108880669628764 0.982479923550474 -0.0112859498610037 0.00011191333431037 6.09303696659007e-05 -1.55412578796883e-05 8.46738647358576e-06 -1.92133019915412e-05 6.11917944237374e-05 6.09303696659007e-05 9.79154747210864e-05 -9.50843696038401e-06 2.20067339422514e-05 -4.69856352876054e-06 7.83269430153768e-05 -1.55412578796883e-05 -9.50843696038401e-06 1.53306260715858e-05 3.41096441238117e-06 6.9436561842581e-06 -8.91855984649673e-06 8.46738647358576e-06 2.20067339422514e-05 3.41096441238117e-06 4.02605740004647e-05 -1.004514989552e-05 1.41727178895456e-05 -1.92133019915412e-05 -4.69856352876054e-06 6.9436561842581e-06 -1.004514989552e-05 5.13438065488914e-05 -5.86774205257368e-06 6.11917944237374e-05 7.83269430153768e-05 -8.91855984649673e-06 1.41727178895456e-05 -5.86774205257368e-06 0.000177393060013956 1581 1594 0 19 9 1554 1576 0 30 1 0 0 0 0 0 9 22 0 286 0 75 82 0 0 1728 +347 383 0.989089713355176 0.0023103384978199 0.147296304335853 -0.0384457588586872 -0.0193397098229033 0.993259597912749 0.114286249296095 -0.0262601951706891 -0.146039428097143 -0.115888021340554 0.98246753226294 -0.0168416779339437 9.36994706892294e-05 5.21992716013302e-05 -1.58056308775135e-05 1.33634755647742e-06 3.58280620040789e-06 -3.73892962276973e-06 5.21992716013302e-05 7.66769056267797e-05 -1.45348913580036e-05 8.86962928317911e-06 4.81198236886863e-06 1.89323419915994e-05 -1.58056308775135e-05 -1.45348913580036e-05 1.59981207239586e-05 5.6411825341615e-07 -2.14888845293187e-06 -2.05387946338723e-06 1.33634755647742e-06 8.86962928317911e-06 5.6411825341615e-07 3.77356124032156e-05 -4.57874553563568e-06 -1.53450982215686e-06 3.58280620040789e-06 4.81198236886863e-06 -2.14888845293187e-06 -4.57874553563568e-06 3.75739842004424e-05 7.33683707974505e-06 -3.73892962276973e-06 1.89323419915994e-05 -2.05387946338723e-06 -1.53450982215686e-06 7.33683707974505e-06 9.13936787527424e-05 1796 1801 0 17 16 1754 1773 0 30 2 0 0 0 0 0 4 17 0 408 0 130 112 0 0 2182 +347 397 0.987960314748365 0.004602181826905 0.154639052004157 -0.0368315268039213 -0.0206849942612621 0.994512230857792 0.102555125111669 -0.0274078781286704 -0.153318451253343 -0.104519101587655 0.982633812724041 -0.00102369156160588 0.000112373899128832 7.7756234818416e-05 -1.44846690802627e-05 2.10864617962179e-05 -2.4233080228357e-05 3.59607849171041e-05 7.7756234818416e-05 0.000150081403987431 -1.58123711920043e-05 5.56228678153089e-05 -2.6798409513511e-05 9.99109275030289e-05 -1.44846690802627e-05 -1.58123711920043e-05 1.67252889968881e-05 2.59906895917517e-06 3.85205776801302e-06 -2.22852642903979e-06 2.10864617962179e-05 5.56228678153089e-05 2.59906895917517e-06 7.92528178494545e-05 -3.94757946997042e-05 4.85038330540968e-05 -2.4233080228357e-05 -2.6798409513511e-05 3.85205776801302e-06 -3.94757946997042e-05 7.54761698293783e-05 -2.21974630303074e-05 3.59607849171041e-05 9.99109275030289e-05 -2.22852642903979e-06 4.85038330540968e-05 -2.21974630303074e-05 0.000162350966187588 1436 1439 0 19 13 1389 1404 0 31 0 0 0 0 0 0 7 21 0 251 0 112 102 0 0 1875 +347 386 0.989137329623171 0.00195782280899798 0.14698132560224 -0.0428720981382743 -0.0194682910684453 0.992847621723542 0.117790431193628 -0.0154390963134138 -0.145699446769085 -0.119372387794477 0.982100760738646 -0.0129603918003778 8.85745905898449e-05 3.43947104953594e-05 -1.05943719930407e-05 6.34494487038849e-06 -3.81491272784747e-06 9.70044280715881e-06 3.43947104953594e-05 8.37070006610354e-05 -1.02035952327894e-05 1.5790241525291e-05 9.78674345500502e-06 4.28642847061072e-05 -1.05943719930407e-05 -1.02035952327894e-05 1.54691949532217e-05 4.78269977966788e-07 3.86716874737651e-06 -5.41583354323718e-06 6.34494487038849e-06 1.5790241525291e-05 4.78269977966788e-07 5.08518941175435e-05 -1.24570257295652e-05 5.57565104632864e-06 -3.81491272784747e-06 9.78674345500502e-06 3.86716874737651e-06 -1.24570257295652e-05 5.54343300092057e-05 8.33056402724174e-06 9.70044280715881e-06 4.28642847061072e-05 -5.41583354323718e-06 5.57565104632864e-06 8.33056402724174e-06 0.000114862692690747 1384 1384 0 15 16 1357 1382 0 27 3 0 0 0 0 0 6 18 0 409 0 109 87 0 0 2191 +347 407 0.989798800553304 0.00427347329310969 0.142408117216867 -0.0476641945092177 -0.0198215621950201 0.993959662189363 0.107941167367027 -0.0201902379304794 -0.14108664038593 -0.109662789342697 0.983904788350067 -0.0127527924882993 0.000248094098698641 0.000221598953972741 -2.87340017333817e-05 0.000102242142945396 -8.22609569735718e-05 0.000177807412047645 0.000221598953972741 0.000373310268401699 -2.76366981619772e-05 0.000165762829871892 -0.000101032211201336 0.000273792251638544 -2.87340017333817e-05 -2.76366981619772e-05 1.71376716782916e-05 -8.57420251205077e-06 1.44341872766653e-05 -1.80012885559681e-05 0.000102242142945396 0.000165762829871892 -8.57420251205077e-06 0.000135713707255339 -7.58277462937875e-05 0.000111669832927097 -8.22609569735718e-05 -0.000101032211201336 1.44341872766653e-05 -7.58277462937875e-05 9.0689249093243e-05 -6.95279751759071e-05 0.000177807412047645 0.000273792251638544 -1.80012885559681e-05 0.000111669832927097 -6.95279751759071e-05 0.000331415080834204 1424 1423 0 16 8 1410 1432 0 32 0 0 0 0 0 0 6 20 0 278 0 80 84 0 0 1710 +347 382 0.989539950445488 0.00263006971472417 0.144235117796038 -0.0414997711535255 -0.0192856924546626 0.99327061484828 0.114199596082753 -0.0219725302020524 -0.142964151236894 -0.115786736771599 0.982931677711579 -0.0173042090216327 6.02978216679729e-05 2.77178035711166e-05 -9.85508056265362e-06 6.57052314840287e-06 -2.15206240089674e-06 -1.08573205795651e-05 2.77178035711166e-05 7.09634294922116e-05 -1.16757941144301e-05 2.01788984170708e-05 3.62358207925746e-06 2.53695609005433e-05 -9.85508056265362e-06 -1.16757941144301e-05 1.49154916094994e-05 1.70978378687182e-06 -6.35792918086475e-07 2.20036155611723e-06 6.57052314840287e-06 2.01788984170708e-05 1.70978378687182e-06 5.41378807149561e-05 -1.48867016220635e-05 1.18386747793719e-05 -2.15206240089674e-06 3.62358207925746e-06 -6.35792918086475e-07 -1.48867016220635e-05 4.4890234564501e-05 5.58497340261592e-06 -1.08573205795651e-05 2.53695609005433e-05 2.20036155611723e-06 1.18386747793719e-05 5.58497340261592e-06 0.000109315531513482 1705 1709 0 17 16 1661 1674 0 29 2 0 0 0 0 0 5 19 0 439 0 121 106 0 0 2226 +347 412 0.988692365825603 0.00304039656139631 0.149927188151188 -0.0418001354531457 -0.020062641726427 0.993488096589664 0.112155661210671 -0.0185847231572387 -0.148609879096678 -0.113895381484041 0.982315095023728 -0.0160362054222874 0.000236326056881932 0.000220437737445904 -4.16711422226481e-05 5.94801029537056e-05 -3.44593575705993e-05 0.000209544632492642 0.000220437737445904 0.000300915429092186 -4.38781649803087e-05 7.76303305279434e-05 -2.93326048601129e-05 0.000265828814961421 -4.16711422226481e-05 -4.38781649803087e-05 2.08487657723706e-05 -1.00777472073712e-05 8.27423271320177e-06 -3.69557881906044e-05 5.94801029537056e-05 7.76303305279434e-05 -1.00777472073712e-05 7.68403357299188e-05 -3.82149697743592e-05 7.67292268723689e-05 -3.44593575705993e-05 -2.93326048601129e-05 8.27423271320177e-06 -3.82149697743592e-05 6.69249410924956e-05 -4.88172296490756e-05 0.000209544632492642 0.000265828814961421 -3.69557881906044e-05 7.67292268723689e-05 -4.88172296490756e-05 0.000396222983452627 1383 1384 0 14 8 1328 1341 0 26 1 0 0 0 0 0 4 16 0 350 0 68 71 0 0 1720 +347 378 0.99009606795616 0.00279167894589313 0.140363751540113 -0.0380792740321723 -0.0186051935014585 0.993592991529277 0.111475620467772 -0.0234668175879386 -0.139153235652373 -0.112983068256109 0.983804453788918 -0.011291975043178 5.63897173885862e-05 2.1873460648567e-05 -8.43824606893143e-06 -1.44413462492992e-06 3.62597651204609e-06 -8.66727363322775e-06 2.1873460648567e-05 5.86295046430746e-05 -9.70038510363312e-06 1.0286464592139e-05 -3.14047431474395e-06 2.06521387920644e-05 -8.43824606893143e-06 -9.70038510363312e-06 1.545572878199e-05 3.16190550353082e-06 -6.6875557725176e-07 1.30703336052247e-06 -1.44413462492992e-06 1.0286464592139e-05 3.16190550353082e-06 5.27863298163508e-05 -2.47088664727421e-05 1.46369115338821e-06 3.62597651204609e-06 -3.14047431474395e-06 -6.6875557725176e-07 -2.47088664727421e-05 5.78555507775142e-05 1.93141081014701e-06 -8.66727363322775e-06 2.06521387920644e-05 1.30703336052247e-06 1.46369115338821e-06 1.93141081014701e-06 8.43239687943985e-05 1362 1359 0 18 16 1344 1370 0 29 1 0 0 0 0 0 5 19 0 442 0 114 91 0 0 2218 +347 381 0.989433259622267 0.0029161433140943 0.144959721514035 -0.040093560053295 -0.019201121154731 0.99362708463402 0.111069949257665 -0.0216719881525437 -0.143712009587426 -0.112679691115438 0.983183678419487 -0.0145846071258694 0.000109718302529848 5.59766912166797e-05 -1.94664298971402e-05 5.17316267524513e-06 -8.73497011724614e-06 1.68691911713457e-05 5.59766912166797e-05 9.66665890291042e-05 -1.69519399747165e-05 3.23583272801501e-05 -1.10418064265343e-05 5.19140063113751e-05 -1.94664298971402e-05 -1.69519399747165e-05 1.67899825927981e-05 -9.5595616742432e-07 3.45191517689395e-06 -5.20150297767248e-06 5.17316267524513e-06 3.23583272801501e-05 -9.5595616742432e-07 5.29954949805464e-05 -1.59017118630686e-05 2.8964603902414e-05 -8.73497011724614e-06 -1.10418064265343e-05 3.45191517689395e-06 -1.59017118630686e-05 5.08937664005897e-05 -5.91433050085361e-06 1.68691911713457e-05 5.19140063113751e-05 -5.20150297767248e-06 2.8964603902414e-05 -5.91433050085361e-06 0.000135694864396403 1604 1603 0 17 17 1554 1570 0 29 3 0 0 0 0 0 9 24 0 428 0 118 103 0 0 2203 +347 379 0.989384473067712 0.00247489098203322 0.145300513994796 -0.0296092376022844 -0.0191318876847919 0.993370512482969 0.113353411077654 -0.0311086171216924 -0.144056708716191 -0.114929978003784 0.982872710390266 -0.0128759238882391 5.67878367396041e-05 1.78108810083401e-05 -7.75438235374621e-06 1.24456274017071e-06 -7.0190073392223e-07 -8.36724111571645e-06 1.78108810083401e-05 6.377481324788e-05 -1.16626439021659e-05 1.77895567933262e-05 4.36833379522863e-06 2.9353785408456e-05 -7.75438235374621e-06 -1.16626439021659e-05 1.58871846259479e-05 -6.36248525148662e-07 3.42368393019083e-06 -6.81369839057804e-07 1.24456274017071e-06 1.77895567933262e-05 -6.36248525148662e-07 4.58505395805293e-05 -1.21653814319302e-05 9.65351927918697e-07 -7.0190073392223e-07 4.36833379522863e-06 3.42368393019083e-06 -1.21653814319302e-05 4.01552139805808e-05 8.24415732152496e-06 -8.36724111571645e-06 2.9353785408456e-05 -6.81369839057804e-07 9.65351927918697e-07 8.24415732152496e-06 0.00010881546691375 1892 1899 0 19 16 1852 1872 0 31 2 0 0 0 0 0 6 20 0 429 0 128 113 0 0 2187 +347 384 0.98931324937785 0.00225227367038905 0.145788277542313 -0.0377296283221981 -0.0191666067678984 0.993212981551123 0.114719721335666 -0.0231027663763341 -0.144540429605165 -0.116288006869332 0.982641930546378 -0.0182984910200305 7.63435180695209e-05 1.44724016061378e-05 -1.11912807670883e-05 1.04786217186905e-06 -5.59862573011934e-06 -1.24755788650046e-06 1.44724016061378e-05 5.11511518373739e-05 -9.53156451630024e-06 6.69997132647151e-06 6.56381334798394e-06 1.12100634231345e-05 -1.11912807670883e-05 -9.53156451630024e-06 1.44634807729947e-05 3.66582664793272e-07 -2.14103928476318e-06 4.66673953381803e-07 1.04786217186905e-06 6.69997132647151e-06 3.66582664793272e-07 3.49220878272039e-05 -4.17291990932797e-06 4.55086169569344e-06 -5.59862573011934e-06 6.56381334798394e-06 -2.14103928476318e-06 -4.17291990932797e-06 4.37607534867452e-05 2.2503131629897e-06 -1.24755788650046e-06 1.12100634231345e-05 4.66673953381803e-07 4.55086169569344e-06 2.2503131629897e-06 7.10381679487414e-05 1665 1671 0 16 16 1624 1642 0 25 2 0 0 0 0 0 6 18 0 438 0 128 110 0 0 2195 +347 395 0.988416677458695 0.0053554917491996 0.151670005042654 -0.0339006847215565 -0.020786856854336 0.994735902681602 0.100341369824893 -0.0263946547353336 -0.150334221997627 -0.102331826057893 0.9833248797178 -0.00371249209938102 0.000172253181021632 0.000126775773441433 -2.28582097681753e-05 2.44488120429543e-05 -4.04827044754971e-05 7.12759959762641e-05 0.000126775773441433 0.000164424823659026 -2.47260004237088e-05 3.25666213398222e-05 -2.62135629144637e-05 8.7501595171065e-05 -2.28582097681753e-05 -2.47260004237088e-05 1.9061443390973e-05 -8.80259410619186e-07 9.13968657192593e-06 -1.58541635884118e-05 2.44488120429543e-05 3.25666213398222e-05 -8.80259410619186e-07 5.34316438402397e-05 -1.91251672998545e-05 2.7904638229187e-05 -4.04827044754971e-05 -2.62135629144637e-05 9.13968657192593e-06 -1.91251672998545e-05 6.51800623893041e-05 -1.96275707676398e-05 7.12759959762641e-05 8.7501595171065e-05 -1.58541635884118e-05 2.7904638229187e-05 -1.96275707676398e-05 0.000158744756552411 1699 1702 0 18 13 1667 1685 0 32 1 0 0 0 0 0 7 21 0 244 0 118 107 0 0 1870 +347 388 0.988894506141403 0.00397762089383456 0.148565925620163 -0.0389934648553395 -0.019904358073473 0.994180631741549 0.105871091425645 -0.0209831012762587 -0.147280250723014 -0.107652450051075 0.983218936831959 -0.0151743420985745 0.000140056133507734 0.000111030210991149 -1.77624220003792e-05 2.78413634053174e-05 -3.20922749748459e-05 7.73088032182516e-05 0.000111030210991149 0.000183139628200888 -1.63552697740023e-05 4.85051417428091e-05 -2.74439324276359e-05 0.000124318914293389 -1.77624220003792e-05 -1.63552697740023e-05 1.48384820374673e-05 -2.60753714032405e-06 7.85619287832649e-06 -1.4208318923043e-05 2.78413634053174e-05 4.85051417428091e-05 -2.60753714032405e-06 6.62915877440623e-05 -3.86473649148301e-05 3.13694160485637e-05 -3.20922749748459e-05 -2.74439324276359e-05 7.85619287832649e-06 -3.86473649148301e-05 6.63735317574966e-05 -1.2789598263197e-05 7.73088032182516e-05 0.000124318914293389 -1.4208318923043e-05 3.13694160485637e-05 -1.2789598263197e-05 0.000205385574550227 1716 1720 0 17 12 1678 1695 0 28 3 0 0 0 0 0 6 20 0 439 0 120 103 0 0 2046 +347 390 0.988494323440369 0.00381805181926334 0.151209771531053 -0.0354483798766622 -0.0203807871339832 0.993927025502895 0.108137373237778 -0.0251456979189835 -0.14987860435021 -0.109974953763448 0.982569037524977 -0.00250349174779791 0.000137058054780565 4.70477704337727e-05 -2.13754497773349e-05 3.16120018106489e-05 -5.18614564059527e-05 1.79014466586134e-05 4.70477704337727e-05 8.38496096400842e-05 -1.38401203840679e-05 3.01461226661071e-05 -1.65210671492075e-05 4.59573572794442e-05 -2.13754497773349e-05 -1.38401203840679e-05 1.81705641684824e-05 -9.47217366460163e-07 1.21440424116386e-05 -7.94030408326297e-06 3.16120018106489e-05 3.01461226661071e-05 -9.47217366460163e-07 6.75678074087636e-05 -3.92463900658585e-05 1.40177160306221e-05 -5.18614564059527e-05 -1.65210671492075e-05 1.21440424116386e-05 -3.92463900658585e-05 9.88401823859928e-05 7.69467008666086e-06 1.79014466586134e-05 4.59573572794442e-05 -7.94030408326297e-06 1.40177160306221e-05 7.69467008666086e-06 0.000150802467941345 1622 1627 0 22 14 1563 1578 0 31 0 0 0 0 0 0 7 21 0 211 0 115 100 0 0 1895 +347 406 0.989095432192816 0.00304353214382442 0.1472445684139 -0.043121156498799 -0.0201395616505964 0.993189580179282 0.114755635503552 -0.0144638688075943 -0.145892508621341 -0.116469715958235 0.982420572460074 -0.0205079663109612 6.40272606141937e-05 1.5962692483345e-05 -7.24588001436117e-06 6.43102230380279e-07 -7.0607790741905e-06 -1.15554119861161e-05 1.5962692483345e-05 6.58013704534507e-05 -3.71523549532902e-06 1.10487626314615e-05 4.992397814187e-06 2.83083779753772e-05 -7.24588001436117e-06 -3.71523549532902e-06 1.30290463400692e-05 2.95250004202494e-06 5.03936490240622e-06 2.60278655447152e-06 6.43102230380279e-07 1.10487626314615e-05 2.95250004202494e-06 4.71788185242213e-05 -1.61245031294996e-05 -4.01306728284319e-07 -7.0607790741905e-06 4.992397814187e-06 5.03936490240622e-06 -1.61245031294996e-05 4.46272947335493e-05 5.65851646100436e-06 -1.15554119861161e-05 2.83083779753772e-05 2.60278655447152e-06 -4.01306728284319e-07 5.65851646100436e-06 0.000118046880428759 1632 1635 0 11 10 1592 1609 0 25 2 0 0 0 0 0 6 17 0 258 0 81 85 0 0 1758 +347 385 0.989276648380637 0.00281270747361297 0.146026715519595 -0.0430241786520305 -0.0194429798944181 0.993452027124891 0.11258348162262 -0.0237378647649859 -0.144753872147166 -0.114215403856544 0.98285357913592 -0.0193344948134392 8.64600244840583e-05 4.11844250508453e-05 -1.37062983617529e-05 4.97666532647282e-06 -4.59295548171198e-06 5.62587263627781e-06 4.11844250508453e-05 9.84613899363524e-05 -1.52147437496199e-05 2.40775446189288e-05 2.98961671410505e-06 3.95212008994146e-05 -1.37062983617529e-05 -1.52147437496199e-05 1.64183732442581e-05 8.33861985854012e-07 1.19111820291739e-06 -2.34188834412188e-06 4.97666532647282e-06 2.40775446189288e-05 8.33861985854012e-07 4.6451331082244e-05 -1.24584772961995e-05 1.37029327924085e-05 -4.59295548171198e-06 2.98961671410505e-06 1.19111820291739e-06 -1.24584772961995e-05 4.24335045128235e-05 -2.88639188281232e-06 5.62587263627781e-06 3.95212008994146e-05 -2.34188834412188e-06 1.37029327924085e-05 -2.88639188281232e-06 0.000126181630385131 1694 1692 0 14 14 1648 1661 0 29 2 0 0 0 0 0 4 17 0 421 0 124 108 0 0 2118 +347 380 0.989449462736483 0.00267674455391746 0.144853704574919 -0.0399349233332881 -0.0188680510185582 0.993694874194311 0.110519200371308 -0.0238927344918833 -0.143644552076457 -0.112086270517603 0.983261364348365 -0.0178949417563532 8.7649683883912e-05 4.00543101198859e-05 -1.49986673062012e-05 -1.19473103849056e-06 4.4431109114394e-06 8.67581351995978e-06 4.00543101198859e-05 7.27704640387802e-05 -1.46508722230118e-05 5.20165954001204e-06 6.24234113737602e-06 4.63743434491874e-05 -1.49986673062012e-05 -1.46508722230118e-05 1.60206677168041e-05 2.53705304875565e-06 -7.12617353265108e-07 -7.71781230874307e-06 -1.19473103849056e-06 5.20165954001204e-06 2.53705304875565e-06 4.02269366500628e-05 -1.45600876064332e-05 2.25168186856998e-06 4.4431109114394e-06 6.24234113737602e-06 -7.12617353265108e-07 -1.45600876064332e-05 4.84082169678233e-05 1.21907532286913e-05 8.67581351995978e-06 4.63743434491874e-05 -7.71781230874307e-06 2.25168186856998e-06 1.21907532286913e-05 0.000120258543412567 1721 1728 0 16 16 1681 1702 0 31 2 0 0 0 0 0 9 23 0 433 0 131 112 0 0 2137 +347 377 0.988952106779832 0.00224111865660427 0.148218446500089 -0.0358473541055751 -0.0197469353214814 0.992965862828154 0.116742682011974 -0.0195259856246792 -0.14691422341333 -0.118379781403358 0.982039937229516 -0.00537496810316249 0.000115694609197089 3.28910015043374e-05 -2.03143491227196e-05 9.31395891700795e-06 -2.29214665490191e-05 9.78778971287367e-06 3.28910015043374e-05 7.68976992966441e-05 -1.39019390386032e-05 1.04008797279851e-05 8.95901448644887e-06 4.0900871181435e-05 -2.03143491227196e-05 -1.39019390386032e-05 1.79143956247853e-05 -4.02383146913967e-07 2.80182858306071e-06 -4.90376869399296e-06 9.31395891700795e-06 1.04008797279851e-05 -4.02383146913967e-07 4.95391343906565e-05 -2.74546976885344e-05 4.31555750857008e-06 -2.29214665490191e-05 8.95901448644887e-06 2.80182858306071e-06 -2.74546976885344e-05 7.79316923832541e-05 6.82868513991548e-06 9.78778971287367e-06 4.0900871181435e-05 -4.90376869399296e-06 4.31555750857008e-06 6.82868513991548e-06 9.99078686025887e-05 1459 1457 0 11 19 1400 1411 0 26 0 0 0 0 0 0 6 18 0 416 0 108 93 0 0 2141 +347 391 0.988529710999822 0.00353773319194819 0.150985081761318 -0.0322068467756352 -0.0206965987905072 0.993467051771073 0.112226858834229 -0.023537843047278 -0.149601675355305 -0.114064461990384 0.982144916619605 -0.0109158050938158 8.59753732651776e-05 2.83258795779468e-05 -5.78465576236002e-06 6.50021030805356e-06 -1.84729720912799e-05 -1.17458494454774e-05 2.83258795779468e-05 7.04797430020813e-05 -3.75242347909618e-06 1.29055250208335e-05 3.13067620846603e-06 3.06656190876727e-05 -5.78465576236002e-06 -3.75242347909618e-06 1.47509372374101e-05 1.00659020990835e-06 6.1432757889354e-06 -2.53008562947536e-06 6.50021030805356e-06 1.29055250208335e-05 1.00659020990835e-06 3.94995150860436e-05 -9.07228404525711e-06 6.7343656691671e-06 -1.84729720912799e-05 3.13067620846603e-06 6.1432757889354e-06 -9.07228404525711e-06 4.66789303576651e-05 1.21057992116073e-05 -1.17458494454774e-05 3.06656190876727e-05 -2.53008562947536e-06 6.7343656691671e-06 1.21057992116073e-05 0.000132697717666935 1686 1693 0 18 16 1648 1664 0 24 3 0 0 0 0 0 6 15 0 208 0 124 110 0 0 1837 +347 413 0.990441961086104 0.00341328391240021 0.137887893641343 -0.0495199501802973 -0.0190792226620811 0.99347390133286 0.112452615056642 -0.0221745505280507 -0.136604190940555 -0.11400858241115 0.984043361927754 -0.0247604056702119 9.39066042584079e-05 6.67525247641024e-05 -2.00862545499743e-05 8.26228300082255e-06 1.03660992331539e-06 2.32830191692028e-05 6.67525247641024e-05 0.000135021222392494 -2.09946000228838e-05 3.38678406465425e-05 5.01662399338924e-07 7.0376027016944e-05 -2.00862545499743e-05 -2.09946000228838e-05 1.81249054981824e-05 -1.58595609613622e-06 4.72647153709679e-07 -8.07251722959097e-06 8.26228300082255e-06 3.38678406465425e-05 -1.58595609613622e-06 6.35559407411028e-05 -1.39706268444739e-05 1.47982398730876e-05 1.03660992331539e-06 5.01662399338924e-07 4.72647153709679e-07 -1.39706268444739e-05 4.6526023297145e-05 -7.83725996058447e-07 2.32830191692028e-05 7.0376027016944e-05 -8.07251722959097e-06 1.47982398730876e-05 -7.83725996058447e-07 0.00013871201182984 1346 1347 0 14 9 1335 1355 0 31 0 0 0 0 0 0 4 18 0 376 0 66 75 0 0 1629 +348 351 0.999834079128665 0.00425892532890694 0.0177108940479411 0.00949419791135413 -0.00401586519120777 0.999897581910759 -0.0137367578337881 -0.0236505012181665 -0.0177675839578893 0.0136633540560467 0.999748781302702 -0.0104867735339925 7.58290452461618e-05 3.03425112383145e-05 -1.47597434835441e-05 8.61604158163894e-06 -1.29596189996588e-05 1.51892631940828e-07 3.03425112383145e-05 5.71330177572901e-05 -1.35351730266591e-05 1.56194833042313e-05 3.97342137874714e-06 1.59085131320144e-05 -1.47597434835441e-05 -1.35351730266591e-05 1.91974658883417e-05 1.00472320299619e-06 -2.84678687917098e-06 -7.60634664829871e-06 8.61604158163894e-06 1.56194833042313e-05 1.00472320299619e-06 5.68939587312513e-05 -3.30251153113924e-05 2.00933736440257e-05 -1.29596189996588e-05 3.97342137874714e-06 -2.84678687917098e-06 -3.30251153113924e-05 7.41982355701133e-05 1.52317591582419e-05 1.51892631940828e-07 1.59085131320144e-05 -7.60634664829871e-06 2.00933736440257e-05 1.52317591582419e-05 0.000101557512701765 1566 1565 0 5 28 1570 1581 0 16 13 0 0 0 0 0 5 13 0 275 0 50 60 0 0 3080 +348 409 0.989729383927717 0.00105977629458967 0.142949723554357 -0.0424113404745231 -0.0183088462382509 0.992676905856343 0.119404131959078 -0.0198616309513122 -0.141776347602433 -0.120795022470639 0.982500905753695 -0.0125495034135285 9.43353795560334e-05 5.61204484168493e-05 -1.28736129126608e-05 1.6819551884776e-05 -1.88495471132153e-05 3.42828946310013e-05 5.61204484168493e-05 0.000114438340851739 -1.06684522403094e-05 3.72099671780055e-05 -1.18990174484875e-05 8.87861690192064e-05 -1.28736129126608e-05 -1.06684522403094e-05 1.48524527823528e-05 3.10353857854198e-06 8.65915826632491e-06 -5.82780023585618e-06 1.6819551884776e-05 3.72099671780055e-05 3.10353857854198e-06 6.2677012076648e-05 -7.81855836170036e-06 4.40295515543913e-05 -1.88495471132153e-05 -1.18990174484875e-05 8.65915826632491e-06 -7.81855836170036e-06 4.26625809012621e-05 -1.70697693720318e-05 3.42828946310013e-05 8.87861690192064e-05 -5.82780023585618e-06 4.40295515543913e-05 -1.70697693720318e-05 0.000171945125213087 1709 1708 0 11 10 1668 1677 0 24 0 0 0 0 0 0 5 18 0 297 0 62 66 0 0 1738 +348 410 0.988971983198471 0.00101511114279391 0.148099243745037 -0.0382368338119993 -0.0189278085514509 0.992642725540763 0.119591628028237 -0.0201886911420323 -0.146888238167403 -0.12107596367724 0.981715058714953 -0.00841388504563052 6.45878940075519e-05 8.31106645198403e-06 -9.01322741659662e-06 -1.26978128294251e-06 -1.3189514654525e-05 -5.32098571197295e-06 8.31106645198403e-06 5.39999579866231e-05 -1.71713400904045e-06 1.44862826533606e-05 3.4767822553377e-06 2.20155748963433e-05 -9.01322741659662e-06 -1.71713400904045e-06 1.3753330649852e-05 5.36515697978989e-06 7.11999381906605e-06 1.40769505190966e-06 -1.26978128294251e-06 1.44862826533606e-05 5.36515697978989e-06 4.28498786857074e-05 -7.63031437991046e-07 1.15598103385683e-05 -1.3189514654525e-05 3.4767822553377e-06 7.11999381906605e-06 -7.63031437991046e-07 4.0858902527991e-05 -3.48474091732616e-06 -5.32098571197295e-06 2.20155748963433e-05 1.40769505190966e-06 1.15598103385683e-05 -3.48474091732616e-06 8.47007953232325e-05 1637 1637 0 10 8 1609 1622 0 24 2 0 0 0 0 0 4 17 0 301 0 56 64 0 0 1732 +348 350 0.999956812213841 0.0029209172991718 0.00882280846811324 -0.00655093211303346 -0.00277256824682219 0.999855362546162 -0.0167799539033636 -0.00658126623557336 -0.00887054521719636 0.0167547673756962 0.99982027944913 -0.00834883575905729 9.00495502754882e-05 5.77410417378964e-05 -2.40791336104504e-05 1.38415321328063e-05 5.35819203455649e-06 3.91718510611451e-05 5.77410417378964e-05 0.000110706435203648 -2.85534454020849e-05 3.70745966151149e-05 6.48480299743778e-06 5.18369419519871e-05 -2.40791336104504e-05 -2.85534454020849e-05 2.1134337896274e-05 -4.21797879945048e-06 -5.50457340004981e-06 -1.45167906017336e-05 1.38415321328063e-05 3.70745966151149e-05 -4.21797879945048e-06 6.41476176416428e-05 -3.18463034193941e-05 3.67593232557757e-05 5.35819203455649e-06 6.48480299743778e-06 -5.50457340004981e-06 -3.18463034193941e-05 6.27963709511486e-05 3.82972968800619e-06 3.91718510611451e-05 5.18369419519871e-05 -1.45167906017336e-05 3.67593232557757e-05 3.82972968800619e-06 0.000106370331808282 1589 1561 0 2 55 1546 1554 0 15 6 0 0 0 0 0 6 16 0 286 0 92 63 0 0 3264 +348 411 0.987082369383728 0.00190989585560026 0.160202210813792 -0.0284757790679018 -0.0202538016433852 0.993394185904713 0.112950320626824 -0.0269539949022457 -0.158928221442248 -0.114735973907632 0.980600569406663 -0.00473350035908721 0.000130153205741278 6.59316539173984e-05 -2.29094540566196e-05 1.4569384698745e-05 -2.65112822224211e-05 4.52150728015314e-05 6.59316539173984e-05 0.000101249205095341 -1.63683735948827e-05 3.01188138090379e-05 -1.08528390890616e-05 4.72037267622335e-05 -2.29094540566196e-05 -1.63683735948827e-05 1.72915153943024e-05 2.49579588944885e-06 8.36492591275231e-06 -8.8668109274681e-06 1.4569384698745e-05 3.01188138090379e-05 2.49579588944885e-06 5.89436294748984e-05 -1.42122797383557e-05 1.66550488428327e-05 -2.65112822224211e-05 -1.08528390890616e-05 8.36492591275231e-06 -1.42122797383557e-05 4.75734686078064e-05 -1.51437119700645e-05 4.52150728015314e-05 4.72037267622335e-05 -8.8668109274681e-06 1.66550488428327e-05 -1.51437119700645e-05 0.00012901959705923 1235 1238 0 14 9 1208 1222 0 27 0 0 0 0 0 0 2 15 0 312 0 62 72 0 0 1785 +348 352 0.999880161324129 0.00496998049676138 0.0146615921473673 0.00286369400538625 -0.00471795612525726 0.999841380922558 -0.0171742215215632 -0.0205653066320405 -0.0147446220851563 0.0171029906371192 0.999745009405315 -0.0171156840870681 6.319261773159e-05 3.81871482556698e-05 -2.22578106113292e-05 9.9222210991583e-06 7.12053925133457e-06 2.03025015159599e-05 3.81871482556698e-05 5.65484572122269e-05 -2.18056427124209e-05 1.73291649944393e-05 3.30919932169515e-06 2.33585644032847e-05 -2.22578106113292e-05 -2.18056427124209e-05 2.36220720824215e-05 -2.62780720937985e-07 -5.18692204602012e-06 -9.73275334177304e-06 9.9222210991583e-06 1.73291649944393e-05 -2.62780720937985e-07 4.5493635039087e-05 -2.00361110574857e-05 1.57570795337336e-05 7.12053925133457e-06 3.30919932169515e-06 -5.18692204602012e-06 -2.00361110574857e-05 6.66307207018895e-05 5.38786391989537e-06 2.03025015159599e-05 2.33585644032847e-05 -9.73275334177304e-06 1.57570795337336e-05 5.38786391989537e-06 7.26672425878742e-05 1831 1816 0 4 23 1816 1822 0 19 8 0 0 0 0 0 5 15 0 310 0 36 26 0 0 3009 +348 396 0.988927168323548 0.000973451934331377 0.148398477562611 -0.0340099711456657 -0.0191535509310329 0.992451964215265 0.121129022996121 -0.0299350037928196 -0.147160447261829 -0.122630139511435 0.981481355729748 -0.00756168089583968 7.022802394726e-05 2.05719948071969e-05 -7.21665492401138e-06 2.37066252761572e-06 -1.95889609881481e-05 1.05462807445992e-05 2.05719948071969e-05 6.83667592930726e-05 -7.95454941404277e-06 1.45997743284446e-05 4.26919246714057e-06 2.43871729418094e-05 -7.21665492401138e-06 -7.95454941404277e-06 1.68322164644612e-05 7.13954771369572e-06 5.01373139361625e-06 -1.33013710584252e-06 2.37066252761572e-06 1.45997743284446e-05 7.13954771369572e-06 5.31795805769104e-05 -1.05412995436086e-06 1.3090558068968e-05 -1.95889609881481e-05 4.26919246714057e-06 5.01373139361625e-06 -1.05412995436086e-06 6.02781635000839e-05 -1.32641314524957e-06 1.05462807445992e-05 2.43871729418094e-05 -1.33013710584252e-06 1.3090558068968e-05 -1.32641314524957e-06 0.000110204947249916 1445 1444 0 11 15 1406 1416 0 27 0 0 0 0 0 0 3 16 0 260 0 106 91 0 0 1976 +348 387 0.98907436361682 0.000188456912135 0.147417325033305 -0.0401969172174199 -0.0188447235825229 0.991956609844305 0.125167729784046 -0.0178703610211101 -0.146208001248499 -0.126578231423045 0.98112240403567 -0.0134801297449411 7.4196587109138e-05 2.18516060052017e-05 -1.16231369119231e-05 -9.43619591574263e-06 -6.28511678159305e-07 1.42610029826527e-05 2.18516060052017e-05 4.93021058618812e-05 -8.99398213263719e-06 9.9158800834808e-06 -2.05331595397317e-06 9.19101364653604e-06 -1.16231369119231e-05 -8.99398213263719e-06 1.63769754215619e-05 3.71590131798215e-06 -1.144540171116e-06 -1.05390826164386e-06 -9.43619591574263e-06 9.9158800834808e-06 3.71590131798215e-06 5.67146873799511e-05 -4.66249784903587e-06 -3.50812545126201e-06 -6.28511678159305e-07 -2.05331595397317e-06 -1.144540171116e-06 -4.66249784903587e-06 4.70560867840816e-05 4.90113583528406e-06 1.42610029826527e-05 9.19101364653604e-06 -1.05390826164386e-06 -3.50812545126201e-06 4.90113583528406e-06 8.30851899533528e-05 1603 1599 0 11 21 1553 1570 0 25 0 0 0 0 0 0 5 18 0 433 0 150 130 0 0 2253 +348 397 0.98884636587081 0.00114264414918635 0.148934747686498 -0.0336322452836436 -0.0190697636852614 0.992711497992921 0.118996747290162 -0.029818218743866 -0.147713265541998 -0.120509651551229 0.981660947102369 -0.00784261051794453 8.77817188116185e-05 3.71965524177012e-05 -1.48816448933682e-05 3.617180651464e-06 -2.03094467640086e-05 2.03113179575089e-05 3.71965524177012e-05 8.50675389703728e-05 -1.05484249897247e-05 2.32806929141981e-05 -1.31004209774849e-05 2.35270133247944e-05 -1.48816448933682e-05 -1.05484249897247e-05 1.54560020940739e-05 5.72196260536458e-06 5.71841450860645e-06 -5.50622518546203e-06 3.617180651464e-06 2.32806929141981e-05 5.72196260536458e-06 6.24857561604403e-05 -2.98368129772811e-05 8.52000143928621e-06 -2.03094467640086e-05 -1.31004209774849e-05 5.71841450860645e-06 -2.98368129772811e-05 6.41554130946071e-05 -7.2358765948398e-06 2.03113179575089e-05 2.35270133247944e-05 -5.50622518546203e-06 8.52000143928621e-06 -7.2358765948398e-06 0.000100827282771388 1370 1369 0 12 15 1341 1354 0 25 2 0 0 0 0 0 4 17 0 250 0 105 96 0 0 1957 +348 386 0.989345604005941 0.000706689671527202 0.145584258846305 -0.0379109353664005 -0.0184095883947213 0.992568353631351 0.120287781693266 -0.0213399771542274 -0.144417321984784 -0.12168633431597 0.982006147206567 -0.0105980360343826 7.45839891361919e-05 3.24686113339191e-05 -1.40707343997136e-05 6.52658296102955e-06 -8.10766555550739e-06 1.2226085893673e-07 3.24686113339191e-05 6.89717172299069e-05 -1.49189055028689e-05 1.43134023555423e-05 4.60623269827413e-06 1.90609918032012e-05 -1.40707343997136e-05 -1.49189055028689e-05 1.71492115607063e-05 -2.30908834780812e-07 4.05107889548053e-06 -2.42454178978262e-06 6.52658296102955e-06 1.43134023555423e-05 -2.30908834780812e-07 3.36819652677522e-05 5.21691189582157e-06 5.61505325549455e-06 -8.10766555550739e-06 4.60623269827413e-06 4.05107889548053e-06 5.21691189582157e-06 4.06957281591312e-05 -2.15925719096842e-06 1.2226085893673e-07 1.90609918032012e-05 -2.42454178978262e-06 5.61505325549455e-06 -2.15925719096842e-06 8.9259049808228e-05 1634 1632 0 11 13 1589 1601 0 24 0 0 0 0 0 0 5 18 0 428 0 104 83 0 0 2243 +348 382 0.988718454348304 0.000833945139598076 0.149783585771623 -0.0392996178531879 -0.0190325965587485 0.992578441440811 0.120107442963217 -0.0237748212151364 -0.148571795100325 -0.121603215921433 0.981396494582201 -0.0169515147487653 7.93394085494973e-05 1.56652782697977e-05 -1.6709222427446e-05 -9.83006469391526e-06 9.20877504387245e-07 -9.19910951405904e-06 1.56652782697977e-05 6.33225737611199e-05 -8.93458492986154e-06 1.37630002020908e-05 7.9974951487298e-06 5.54253817485715e-06 -1.6709222427446e-05 -8.93458492986154e-06 1.72016571549479e-05 5.81045895985024e-06 -2.92888669047146e-06 4.01046868337822e-08 -9.83006469391526e-06 1.37630002020908e-05 5.81045895985024e-06 5.688570656781e-05 -1.9720432860301e-05 5.2315026027526e-06 9.20877504387245e-07 7.9974951487298e-06 -2.92888669047146e-06 -1.9720432860301e-05 5.41030149951595e-05 2.292761859799e-06 -9.19910951405904e-06 5.54253817485715e-06 4.01046868337822e-08 5.2315026027526e-06 2.292761859799e-06 9.03135708680188e-05 1585 1587 0 12 17 1551 1584 0 27 3 0 0 0 0 0 5 15 0 438 0 114 93 0 0 2266 +348 381 0.989213976291941 0.0014759303854535 0.146470238404203 -0.0379982366550033 -0.0186968690107679 0.993042088588808 0.11626623491097 -0.0253732745966922 -0.145279510592103 -0.117750719406193 0.982358708355274 -0.0148453346893731 8.0271168058484e-05 4.64799600834122e-05 -1.43020110706788e-05 2.12881121237468e-05 -1.62005067622003e-05 2.04519436539825e-05 4.64799600834122e-05 8.00785696848923e-05 -1.51193966620557e-05 2.80322840369519e-05 -1.08710391860376e-05 4.74837344044029e-05 -1.43020110706788e-05 -1.51193966620557e-05 1.47661235424668e-05 -1.67937974717009e-06 4.40309940246839e-06 -5.96376177267265e-06 2.12881121237468e-05 2.80322840369519e-05 -1.67937974717009e-06 6.49449602294424e-05 -2.60119383308308e-05 1.59743068045607e-05 -1.62005067622003e-05 -1.08710391860376e-05 4.40309940246839e-06 -2.60119383308308e-05 5.22497116495518e-05 -9.20963584658024e-06 2.04519436539825e-05 4.74837344044029e-05 -5.96376177267265e-06 1.59743068045607e-05 -9.20963584658024e-06 0.000117758647286459 1897 1894 0 12 16 1868 1894 0 22 2 0 0 0 0 0 4 17 0 435 0 112 93 0 0 2267 +348 388 0.987713923625927 0.00125122765446977 0.156267845396402 -0.0322162631555969 -0.0199344079868332 0.992807660827163 0.118049006692604 -0.0245595521275316 -0.154996207868746 -0.119713754565851 0.980634892564024 -0.0163072142196982 0.000145572591421442 0.000124642934457138 -2.02377594562064e-05 3.47405425564879e-05 -3.59790580927053e-05 8.52966020327072e-05 0.000124642934457138 0.000196255960266482 -1.79045062125929e-05 5.21326025258655e-05 -3.43288632137574e-05 0.000114069028232367 -2.02377594562064e-05 -1.79045062125929e-05 1.59638299318321e-05 -1.64624829391217e-06 1.03978030121335e-05 -1.45810814473478e-05 3.47405425564879e-05 5.21326025258655e-05 -1.64624829391217e-06 6.09106717417018e-05 -2.74534321831915e-05 3.77790683865921e-05 -3.59790580927053e-05 -3.43288632137574e-05 1.03978030121335e-05 -2.74534321831915e-05 5.11177111382768e-05 -3.22361902630466e-05 8.52966020327072e-05 0.000114069028232367 -1.45810814473478e-05 3.77790683865921e-05 -3.22361902630466e-05 0.000172513303082643 1858 1860 0 13 18 1807 1841 0 25 0 0 0 0 0 0 2 15 0 433 0 116 92 0 0 2167 +348 389 0.988687510679902 0.00194048909916468 0.14997746739972 -0.0364173017122667 -0.0194021345081258 0.993169814030008 0.115053368816942 -0.0261679063575714 -0.14872983359806 -0.116661711806636 0.981972240746264 -0.0124773074089506 0.000111609892391671 4.86363100207149e-05 -1.64455938093545e-05 1.07891718748101e-05 -2.89802387922053e-05 2.01320647400874e-05 4.86363100207149e-05 0.00010144434355317 -1.0745687020856e-05 2.92789445216445e-05 -1.71353387787147e-05 4.13005529760163e-05 -1.64455938093545e-05 -1.0745687020856e-05 1.52256499110342e-05 2.36779197211242e-06 8.72574883555883e-06 -5.79664051814869e-06 1.07891718748101e-05 2.92789445216445e-05 2.36779197211242e-06 4.94208085449538e-05 -1.63948331639543e-05 1.47959922888269e-05 -2.89802387922053e-05 -1.71353387787147e-05 8.72574883555883e-06 -1.63948331639543e-05 5.16460303245208e-05 -1.20155851460793e-05 2.01320647400874e-05 4.13005529760163e-05 -5.79664051814869e-06 1.47959922888269e-05 -1.20155851460793e-05 0.000125882422901505 1638 1636 0 11 16 1605 1616 0 27 0 0 0 0 0 0 6 18 0 300 0 112 99 0 0 2072 +348 408 0.987734178952806 0.000417687388638528 0.156144219443663 -0.0312397504424258 -0.0191948119574849 0.992736648672618 0.118766601265575 -0.0238690462276865 -0.154960481808564 -0.120306990318537 0.980567936023891 -0.00612088271471207 0.000130450366155179 6.22688716993068e-05 -1.83446231683866e-05 1.48800237887089e-05 -3.13432988476406e-05 4.76986576413639e-05 6.22688716993068e-05 0.000107363538762147 -9.8583974303754e-06 3.74440510051032e-05 -2.2174723712268e-05 5.94957790980704e-05 -1.83446231683866e-05 -9.8583974303754e-06 1.65340970157996e-05 4.93867602051462e-06 1.05456728304521e-05 -7.46319552634983e-06 1.48800237887089e-05 3.74440510051032e-05 4.93867602051462e-06 5.66009724383839e-05 -1.2331900716748e-05 3.71680290866306e-05 -3.13432988476406e-05 -2.2174723712268e-05 1.05456728304521e-05 -1.2331900716748e-05 4.45227512376941e-05 -2.6985264105659e-05 4.76986576413639e-05 5.94957790980704e-05 -7.46319552634983e-06 3.71680290866306e-05 -2.6985264105659e-05 0.000135223264779329 1478 1480 0 12 10 1438 1452 0 25 0 0 0 0 0 0 5 17 0 279 0 94 96 0 0 1852 +348 398 0.989250927652101 0.000203714097577867 0.146227769729366 -0.0292033599739195 -0.0182266126498866 0.992372190508531 0.121923033494948 -0.0385043591713607 -0.145087534718766 -0.12327771090455 0.98170882305466 -0.024882081557211 9.51166715877174e-05 4.41064763030428e-05 -1.67026295910879e-05 4.36673981076905e-06 -1.46995998781616e-05 2.23361861620195e-05 4.41064763030428e-05 7.05688035137743e-05 -1.27085323446898e-05 1.11424907459608e-05 1.11833754942949e-06 2.55429770274398e-05 -1.67026295910879e-05 -1.27085323446898e-05 1.70222332471368e-05 4.8142768945649e-06 7.07890714610234e-06 -6.20813755321999e-06 4.36673981076905e-06 1.11424907459608e-05 4.8142768945649e-06 4.97542669548522e-05 -1.39720560532237e-05 1.37572395673103e-05 -1.46995998781616e-05 1.11833754942949e-06 7.07890714610234e-06 -1.39720560532237e-05 6.01784533360026e-05 -4.90238913609745e-06 2.23361861620195e-05 2.55429770274398e-05 -6.20813755321999e-06 1.37572395673103e-05 -4.90238913609745e-06 0.000107242612921829 1590 1588 0 16 17 1573 1600 0 32 3 0 0 0 0 0 3 15 0 266 0 106 91 0 0 1900 +348 406 0.988028793795337 0.000400957759275496 0.154269056729492 -0.0292708649272465 -0.0192126369331065 0.992531126818899 0.120469236229352 -0.0263645202541003 -0.153068537633991 -0.121990989538089 0.980657035491058 -0.0121196499343014 0.000103167819637987 3.6260746005639e-05 -1.47961137357278e-05 -1.47379098422679e-06 -1.87639379994205e-05 1.24357166471593e-05 3.6260746005639e-05 0.000115336592692197 -8.65520871141839e-06 1.89521333440232e-05 -5.31712899700092e-06 6.00091713793683e-05 -1.47961137357278e-05 -8.65520871141839e-06 1.54672710231453e-05 6.10424242275903e-06 8.07905221805004e-06 -3.71056436733193e-06 -1.47379098422679e-06 1.89521333440232e-05 6.10424242275903e-06 3.95540893224671e-05 -2.38112986800566e-06 1.89821972471243e-05 -1.87639379994205e-05 -5.31712899700092e-06 8.07905221805004e-06 -2.38112986800566e-06 4.11668148038428e-05 1.32090673904309e-06 1.24357166471593e-05 6.00091713793683e-05 -3.71056436733193e-06 1.89821972471243e-05 1.32090673904309e-06 0.000169371360938916 1826 1826 0 10 11 1792 1818 0 21 1 0 0 0 0 0 5 18 0 252 0 73 77 0 0 1848 +348 407 0.989567356652851 8.92615239545257e-05 0.144070950158143 -0.0436178755495387 -0.0181545262694796 0.992105913052522 0.124081708813801 -0.0203905934104252 -0.142922565828565 -0.125402748449156 0.981757246399728 -0.0149815854638782 9.29608628856616e-05 4.31961741084344e-05 -1.10664757970885e-05 9.28285014642158e-06 -2.02405932823906e-05 3.6186556899772e-05 4.31961741084344e-05 8.74008263633658e-05 -8.91267995138278e-06 2.15568673259231e-05 -1.138609865188e-05 6.29078453655323e-05 -1.10664757970885e-05 -8.91267995138278e-06 1.46784415119131e-05 4.36640021688374e-06 6.21579374062028e-06 -4.93810443291175e-06 9.28285014642158e-06 2.15568673259231e-05 4.36640021688374e-06 4.40104950759124e-05 -6.77104589731339e-06 2.63190188483537e-05 -2.02405932823906e-05 -1.138609865188e-05 6.21579374062028e-06 -6.77104589731339e-06 4.55808061951313e-05 -1.8183193295375e-05 3.6186556899772e-05 6.29078453655323e-05 -4.93810443291175e-06 2.63190188483537e-05 -1.8183193295375e-05 0.000141132316304189 1702 1700 0 10 10 1655 1669 0 26 0 0 0 0 0 0 4 18 0 276 0 68 72 0 0 1791 +348 412 0.989263512673408 -0.00059045157223563 0.14614155418638 -0.0366766573627474 -0.0181051114110085 0.991793140565546 0.126564494499546 -0.022276177061619 -0.145016921198406 -0.127851545528677 0.981134075889765 -0.0177182518496965 0.000110472326237608 6.1295943952854e-05 -2.16737677609914e-05 1.64321738024361e-08 -1.66936541875275e-05 1.38319591398605e-05 6.1295943952854e-05 8.56466927732791e-05 -1.73997389505714e-05 1.68782037583526e-05 -9.04080756865528e-06 2.58774511376731e-05 -2.16737677609914e-05 -1.73997389505714e-05 1.81244510579369e-05 5.86580789630584e-06 5.35142677422202e-06 -6.39082964629347e-06 1.64321738024361e-08 1.68782037583526e-05 5.86580789630584e-06 5.03947525666754e-05 -4.86308023482905e-06 1.79284937761308e-05 -1.66936541875275e-05 -9.04080756865528e-06 5.35142677422202e-06 -4.86308023482905e-06 4.67212032697063e-05 -5.68337776875257e-06 1.38319591398605e-05 2.58774511376731e-05 -6.39082964629347e-06 1.79284937761308e-05 -5.68337776875257e-06 0.000104734454383322 1568 1570 0 11 9 1546 1559 0 24 4 0 0 0 0 0 6 17 0 357 0 60 68 0 0 1795 +348 385 0.988751810104262 0.000512982538171068 0.149564684549734 -0.036730330887414 -0.0187266782674247 0.992549392728262 0.12039524291195 -0.0242470708085187 -0.14838857616614 -0.121841864084864 0.981394615136904 -0.0205098029886483 7.70125032112995e-05 3.30313680409137e-05 -1.17886160544054e-05 1.07684554054394e-06 -1.03728572137919e-05 -3.34150156503182e-06 3.30313680409137e-05 6.73008619075625e-05 -1.12367259674532e-05 1.71558635249309e-05 -7.21665000625379e-07 1.47554266892454e-05 -1.17886160544054e-05 -1.12367259674532e-05 1.55497749961357e-05 2.7730801480046e-07 2.87076035713829e-06 -2.23875684382663e-06 1.07684554054394e-06 1.71558635249309e-05 2.7730801480046e-07 4.66161856635136e-05 -2.87824188274665e-06 1.53850903107322e-05 -1.03728572137919e-05 -7.21665000625379e-07 2.87076035713829e-06 -2.87824188274665e-06 3.67952095776979e-05 5.21455566043641e-07 -3.34150156503182e-06 1.47554266892454e-05 -2.23875684382663e-06 1.53850903107322e-05 5.21455566043641e-07 9.31486305850543e-05 1884 1878 0 10 18 1851 1880 0 27 2 0 0 0 0 0 4 17 0 429 0 113 91 0 0 2235 +348 377 0.989081321611418 0.000372604336853038 0.14737028331865 -0.0322039777654963 -0.0181999553508296 0.992650517244567 0.119639927446154 -0.0280544708341666 -0.14624260960691 -0.121015750132375 0.981818866876808 -0.00629207932425064 0.000112490025452529 4.3822365751854e-05 -1.79694665083162e-05 1.12496711459909e-05 -2.46530292558436e-05 2.25799585466456e-06 4.3822365751854e-05 7.32174037765055e-05 -1.50948717322456e-05 2.22513743533364e-05 -7.63565433707324e-06 2.93724682433802e-05 -1.79694665083162e-05 -1.50948717322456e-05 1.71448429367135e-05 -1.53460796976208e-07 5.92889745063632e-06 -1.94949040103051e-06 1.12496711459909e-05 2.22513743533364e-05 -1.53460796976208e-07 4.00800065257094e-05 -4.64676587359325e-06 2.061590400664e-05 -2.46530292558436e-05 -7.63565433707324e-06 5.92889745063632e-06 -4.64676587359325e-06 4.77074684892098e-05 -4.00739492947561e-06 2.25799585466456e-06 2.93724682433802e-05 -1.94949040103051e-06 2.061590400664e-05 -4.00739492947561e-06 9.74059132348318e-05 1674 1671 0 9 19 1643 1655 0 26 4 0 0 0 0 0 5 18 0 435 0 109 95 0 0 2200 +348 413 0.990186492207945 0.000560690435975102 0.139751194181517 -0.0425280614126323 -0.0179085459499762 0.992256550859635 0.122907368607822 -0.0236301383029937 -0.138600124930978 -0.124203956870852 0.982529074616492 -0.0205677551157632 5.84063161369624e-05 1.43846875874828e-05 -9.10137699471592e-06 -2.22591544099865e-07 -6.80283131792501e-06 -5.03295257458428e-07 1.43846875874828e-05 5.15625072836872e-05 -9.19700544005605e-06 9.95780640662644e-06 9.64373021275877e-06 2.9662201321137e-06 -9.10137699471592e-06 -9.19700544005605e-06 1.41327216190038e-05 4.23822914341301e-06 -6.76750079291243e-07 -2.07938821969372e-07 -2.22591544099865e-07 9.95780640662644e-06 4.23822914341301e-06 4.16425666641453e-05 9.00429841843006e-06 6.66121507608906e-06 -6.80283131792501e-06 9.64373021275877e-06 -6.76750079291243e-07 9.00429841843006e-06 4.30091580869129e-05 1.26542013412306e-06 -5.03295257458428e-07 2.9662201321137e-06 -2.07938821969372e-07 6.66121507608906e-06 1.26542013412306e-06 6.62038584359815e-05 1536 1535 0 11 9 1495 1509 0 24 1 0 0 0 0 0 3 16 0 386 0 58 65 0 0 1744 +348 378 0.989649014568256 0.000390622819493996 0.143508450545232 -0.0346547060783049 -0.0175676464836078 0.992805086489253 0.118445928752718 -0.0259570663175947 -0.142429651972851 -0.119741002396339 0.982535437826042 -0.00771999482831934 7.71186957337077e-05 2.48896258627525e-05 -1.53231644911053e-05 7.53068207694495e-07 -4.89022868956147e-06 1.51381140217314e-06 2.48896258627525e-05 6.14554163883664e-05 -1.17465314014924e-05 1.49031628135896e-05 1.57359198331726e-06 3.5918061933896e-05 -1.53231644911053e-05 -1.17465314014924e-05 1.580949791162e-05 1.62301408770659e-06 7.85785337867897e-07 -2.00350860159029e-06 7.53068207694495e-07 1.49031628135896e-05 1.62301408770659e-06 3.32229182287519e-05 -7.68264056300502e-07 1.61631035323155e-05 -4.89022868956147e-06 1.57359198331726e-06 7.85785337867897e-07 -7.68264056300502e-07 3.40483139470316e-05 2.12082439221013e-06 1.51381140217314e-06 3.5918061933896e-05 -2.00350860159029e-06 1.61631035323155e-05 2.12082439221013e-06 9.54175950455668e-05 1730 1724 0 13 17 1683 1691 0 25 0 0 0 0 0 0 4 16 0 454 0 105 84 0 0 2295 +348 395 0.986862519467922 0.00218237106499903 0.16154753147591 -0.0250847236909637 -0.0200763019966968 0.993815209476256 0.109216626535536 -0.0252621717931474 -0.160310042628536 -0.111025072259377 0.980802795449848 -0.00134531779380603 0.00015167477308835 6.77500914484357e-05 -2.56081861922825e-05 -6.25194118168842e-06 -1.71466935916139e-05 2.45742294664408e-05 6.77500914484357e-05 0.000118117963339284 -1.46150663360742e-05 1.5404207657509e-05 -2.13660225969429e-06 6.33614095690217e-05 -2.56081861922825e-05 -1.46150663360742e-05 1.80658720257116e-05 4.97518936083829e-06 8.23726253932082e-06 -6.473496644981e-06 -6.25194118168842e-06 1.5404207657509e-05 4.97518936083829e-06 4.41392968276549e-05 5.878801351949e-06 2.81189188153221e-05 -1.71466935916139e-05 -2.13660225969429e-06 8.23726253932082e-06 5.878801351949e-06 3.69210760052632e-05 1.05367896334314e-06 2.45742294664408e-05 6.33614095690217e-05 -6.473496644981e-06 2.81189188153221e-05 1.05367896334314e-06 0.000145346446094249 1768 1765 0 16 14 1735 1745 0 28 0 0 0 0 0 0 3 16 0 237 0 133 120 0 0 1960 +348 383 0.989155931413861 -0.000269789758051853 0.146868889021003 -0.0352577599409308 -0.0176738142987152 0.992512750405847 0.120855602145518 -0.0251107417713931 -0.145801850594949 -0.122140769177648 0.981745105853745 -0.0166052943689394 9.88681332695347e-05 4.38227923096631e-05 -1.73354997581482e-05 -5.15495170973549e-06 -1.67787910527095e-06 2.34066861944658e-05 4.38227923096631e-05 8.75951668714645e-05 -1.42860866970487e-05 1.93723828987375e-05 2.73698045955289e-06 3.95330861319893e-05 -1.73354997581482e-05 -1.42860866970487e-05 1.54979283609081e-05 3.71943648028069e-06 -2.49729815801035e-07 -5.9869122319177e-06 -5.15495170973549e-06 1.93723828987375e-05 3.71943648028069e-06 5.20390941061654e-05 7.87763859312307e-07 1.6532521611797e-05 -1.67787910527095e-06 2.73698045955289e-06 -2.49729815801035e-07 7.87763859312307e-07 4.08310275868661e-05 -2.9174487249351e-06 2.34066861944658e-05 3.95330861319893e-05 -5.9869122319177e-06 1.6532521611797e-05 -2.9174487249351e-06 0.000109962924552121 1621 1616 0 12 20 1569 1581 0 25 0 0 0 0 0 0 4 17 0 429 0 152 132 0 0 2248 +348 390 0.987330820032791 0.00271715830334871 0.15865203706266 -0.0291949700171055 -0.0206399353969967 0.993557786727088 0.111431223186224 -0.0286481759942419 -0.157327190530387 -0.113294048761287 0.981026306291065 -0.0022421701712307 0.000143014981764824 4.44355659874878e-05 -2.43439820586593e-05 1.22388887844276e-05 -2.73598385262583e-05 1.64164635204181e-05 4.44355659874878e-05 0.000122067389726017 -1.22440241358113e-05 3.54107452283644e-05 -1.68398242482159e-06 3.84567916578979e-05 -2.43439820586593e-05 -1.22440241358113e-05 1.87440189484483e-05 5.6741989070591e-06 1.13013317010353e-05 -5.55263045616571e-06 1.22388887844276e-05 3.54107452283644e-05 5.6741989070591e-06 5.50491664473635e-05 -3.06433607915198e-06 1.97318452375705e-05 -2.73598385262583e-05 -1.68398242482159e-06 1.13013317010353e-05 -3.06433607915198e-06 6.35881651679506e-05 -7.76286745002919e-06 1.64164635204181e-05 3.84567916578979e-05 -5.55263045616571e-06 1.97318452375705e-05 -7.76286745002919e-06 0.000126333717212001 1399 1402 0 17 15 1367 1379 0 27 2 0 0 0 0 0 3 15 0 203 0 114 100 0 0 1955 +349 352 0.999984366246371 0.00379907589084921 0.00410296054327978 -0.00562776349832243 -0.00373880902105304 0.999886457157256 -0.0145977429972904 -0.0135196371346443 -0.00415795261495785 0.0145821745938806 0.99988502919794 -0.0161810102349567 5.77968496328948e-05 3.61387532938469e-05 -1.70597031211897e-05 1.33488093043597e-05 -2.66628634073509e-06 2.03657581676719e-05 3.61387532938469e-05 6.72345230868686e-05 -1.86892405533522e-05 2.39664048000619e-05 1.12844947155643e-06 3.33698917632581e-05 -1.70597031211897e-05 -1.86892405533522e-05 1.94620026502985e-05 5.05611842552571e-07 -3.83771667762666e-06 -1.05549928691937e-05 1.33488093043597e-05 2.39664048000619e-05 5.05611842552571e-07 7.85336341571328e-05 -5.32620310983302e-05 3.37905709147522e-05 -2.66628634073509e-06 1.12844947155643e-06 -3.83771667762666e-06 -5.32620310983302e-05 9.7498409903331e-05 -5.91756608187788e-06 2.03657581676719e-05 3.33698917632581e-05 -1.05549928691937e-05 3.37905709147522e-05 -5.91756608187788e-06 9.85497746953697e-05 1648 1625 0 4 27 1651 1655 0 21 9 0 0 0 0 0 6 15 0 306 0 32 17 0 0 3174 +349 353 0.999983420576109 0.00421122121909911 0.00392736409672334 -0.0158690917900304 -0.00414233325614475 0.999840258958921 -0.0173867087211317 -0.0062338372102305 -0.00399995601219056 0.0173701520086109 0.999841126465149 -0.0153934523188008 5.62960135521957e-05 3.69654678334415e-05 -1.94512289005307e-05 6.10355727327831e-06 1.26622750544687e-05 1.70655785603755e-05 3.69654678334415e-05 7.93645421067586e-05 -2.01638171670704e-05 1.76355194492708e-05 1.71676740063531e-05 2.56281052233887e-05 -1.94512289005307e-05 -2.01638171670704e-05 2.01791789361883e-05 -2.80170438057747e-06 -7.47304780535604e-06 -9.94967483624518e-06 6.10355727327831e-06 1.76355194492708e-05 -2.80170438057747e-06 6.02332114099817e-05 -3.15632685750014e-05 2.3810379379248e-05 1.26622750544687e-05 1.71676740063531e-05 -7.47304780535604e-06 -3.15632685750014e-05 8.26851813067786e-05 3.63730776830757e-06 1.70655785603755e-05 2.56281052233887e-05 -9.94967483624518e-06 2.3810379379248e-05 3.63730776830757e-06 7.46677162961381e-05 1782 1758 0 2 46 1776 1782 0 18 22 0 0 0 0 0 7 16 0 310 0 59 34 0 0 3042 +349 410 0.989155137478969 0.00213762263126683 0.14685892743871 -0.0362471136948636 -0.0195040510490352 0.992950414919035 0.116914778812573 -0.0235390506077812 -0.145573713257712 -0.118511198127445 0.982223696479961 -0.0127884021159925 0.000125659939367339 8.48740341526902e-05 -1.74148519508503e-05 3.0080775896947e-05 -4.39245288124638e-05 5.74071191074271e-05 8.48740341526902e-05 0.000128390515885999 -1.56876304509242e-05 3.93318610053429e-05 -3.13717556300777e-05 9.47611176119332e-05 -1.74148519508503e-05 -1.56876304509242e-05 1.53085471393407e-05 2.89959488684301e-06 1.16332654135335e-05 -7.86977688058646e-06 3.0080775896947e-05 3.93318610053429e-05 2.89959488684301e-06 6.15837805090258e-05 -2.24454603685709e-05 3.42126631449054e-05 -4.39245288124638e-05 -3.13717556300777e-05 1.16332654135335e-05 -2.24454603685709e-05 6.7479486699025e-05 -2.94865198695926e-05 5.74071191074271e-05 9.47611176119332e-05 -7.86977688058646e-06 3.42126631449054e-05 -2.94865198695926e-05 0.000145290886183495 1566 1568 0 14 22 1548 1566 0 28 15 0 0 0 0 0 4 18 0 303 0 55 60 0 0 1756 +348 379 0.989472511226864 4.29956059867767e-06 0.144720936660586 -0.0353192174652607 -0.0180165658249233 0.992224299352501 0.12315170778481 -0.0244485774205186 -0.143595100481457 -0.124462603845302 0.981778746643951 -0.0189371251642535 5.78794943255001e-05 1.54474078610226e-05 -6.97307022758313e-06 -4.08193256722053e-06 -3.09590781839631e-06 -3.91938054757711e-06 1.54474078610226e-05 6.37692518347898e-05 -7.63332147141671e-06 1.53279347531633e-05 7.9592116182915e-06 1.92884846506091e-05 -6.97307022758313e-06 -7.63332147141671e-06 1.55364913419675e-05 4.91011669599654e-06 1.20991587464742e-06 -2.10779362336672e-06 -4.08193256722053e-06 1.53279347531633e-05 4.91011669599654e-06 5.33523160791225e-05 -5.14732243946538e-06 1.22200336821184e-06 -3.09590781839631e-06 7.9592116182915e-06 1.20991587464742e-06 -5.14732243946538e-06 4.33067538753146e-05 4.46481245843702e-06 -3.91938054757711e-06 1.92884846506091e-05 -2.10779362336672e-06 1.22200336821184e-06 4.46481245843702e-06 7.97794058683344e-05 1678 1673 0 13 22 1629 1642 0 27 0 0 0 0 0 0 5 18 0 435 0 151 130 0 0 2271 +349 409 0.990568875820812 0.000732412658982484 0.137013743204063 -0.0433924321096094 -0.0180150819990774 0.992000614219106 0.124940938885069 -0.02072760454379 -0.135826209089625 -0.126230919194201 0.982658127714684 -0.0182468181966356 9.26754572657897e-05 8.32837769902298e-05 -1.50823900180891e-05 1.716687288644e-05 -2.66053386845714e-05 5.75488946256093e-05 8.32837769902298e-05 0.000149514088410682 -1.48051274869201e-05 4.48619708926197e-05 -3.70689420685024e-05 0.000106419510864759 -1.50823900180891e-05 -1.48051274869201e-05 1.62501913065212e-05 5.22043947289244e-06 9.25906814990796e-06 -1.03726321054783e-05 1.716687288644e-05 4.48619708926197e-05 5.22043947289244e-06 6.10630744314491e-05 -1.50106481435394e-05 3.49518044570516e-05 -2.66053386845714e-05 -3.70689420685024e-05 9.25906814990796e-06 -1.50106481435394e-05 5.20134097863761e-05 -3.32504517688554e-05 5.75488946256093e-05 0.000106419510864759 -1.03726321054783e-05 3.49518044570516e-05 -3.32504517688554e-05 0.000178025359872895 1528 1529 0 12 22 1514 1531 0 26 17 0 0 0 0 0 2 16 0 292 0 56 62 0 0 1745 +349 411 0.988721656013259 0.00158779156549143 0.149756354951444 -0.0300585561567174 -0.0191393908522007 0.993084292994105 0.115832943182006 -0.0282347875825591 -0.148536765308138 -0.117392784813819 0.981914336093252 -0.00879706335957871 0.000128951516514346 7.05002312208943e-05 -2.67940847562828e-05 -6.65934387319271e-06 -5.19130778468272e-06 3.75502906498808e-05 7.05002312208943e-05 0.000116422277916403 -1.5558199979804e-05 2.45114127697837e-05 -6.96459455483536e-06 7.71153374782328e-05 -2.67940847562828e-05 -1.5558199979804e-05 1.77022261900745e-05 9.06030898998792e-06 5.85457670804596e-06 -7.3091025770329e-06 -6.65934387319271e-06 2.45114127697837e-05 9.06030898998792e-06 4.99455604928413e-05 -3.85818312122649e-06 2.12064331300543e-05 -5.19130778468272e-06 -6.96459455483536e-06 5.85457670804596e-06 -3.85818312122649e-06 3.32094367593171e-05 -3.85931796075386e-06 3.75502906498808e-05 7.71153374782328e-05 -7.3091025770329e-06 2.12064331300543e-05 -3.85931796075386e-06 0.000154882176426765 1568 1570 0 14 22 1561 1577 0 35 14 0 0 0 0 0 5 19 0 327 0 72 79 0 0 1786 +348 384 0.988782693615257 0.000760693625597216 0.149359318933119 -0.0328721264794041 -0.0184510004502552 0.992949723120178 0.117091451173628 -0.0249389560626147 -0.148217223659539 -0.118533829351664 0.981825537409722 -0.0152993457347426 7.81290175644948e-05 3.22736624750099e-05 -1.57686796643106e-05 -4.71233442275434e-06 -1.28217814541602e-06 1.09366161297434e-05 3.22736624750099e-05 7.04217861431793e-05 -1.28114358831594e-05 8.67377696263681e-06 1.11928505237027e-05 2.77000033281588e-05 -1.57686796643106e-05 -1.28114358831594e-05 1.69184259551545e-05 9.64156094943402e-07 -1.68092779249257e-06 -8.04510128587223e-06 -4.71233442275434e-06 8.67377696263681e-06 9.64156094943402e-07 3.73548488825878e-05 1.90812924837816e-06 5.55605925249526e-06 -1.28217814541602e-06 1.11928505237027e-05 -1.68092779249257e-06 1.90812924837816e-06 4.24657775238594e-05 1.28076671517746e-05 1.09366161297434e-05 2.77000033281588e-05 -8.04510128587223e-06 5.55605925249526e-06 1.28076671517746e-05 0.000124131986518344 1553 1553 0 13 15 1503 1517 0 27 0 0 0 0 0 0 5 18 0 441 0 153 135 0 0 2314 +349 387 0.989431386133223 0.00127015471733168 0.144996271819257 -0.0364236632005903 -0.018850774133852 0.992602211363297 0.119939561076596 -0.023180389208251 -0.143771278247932 -0.121405258138542 0.982135725267781 -0.00856951218831932 8.57486193220544e-05 3.19385656234376e-05 -1.67051730544739e-05 -5.8121152287945e-06 -5.30933626316077e-06 2.31852993932146e-05 3.19385656234376e-05 5.03566934173616e-05 -1.56905285781673e-05 8.11966484563926e-06 4.63008567111446e-06 1.41345864079465e-05 -1.67051730544739e-05 -1.56905285781673e-05 2.23407651285432e-05 2.23595352629289e-06 -5.41576153294736e-06 -6.38993542603216e-06 -5.8121152287945e-06 8.11966484563926e-06 2.23595352629289e-06 5.25589647982565e-05 5.86826674919029e-06 8.61667781886382e-06 -5.30933626316077e-06 4.63008567111446e-06 -5.41576153294736e-06 5.86826674919029e-06 5.87311950258441e-05 1.40893327734059e-06 2.31852993932146e-05 1.41345864079465e-05 -6.38993542603216e-06 8.61667781886382e-06 1.40893327734059e-06 8.82710103805904e-05 1808 1807 0 14 15 1761 1774 0 29 4 0 0 0 0 0 2 16 0 428 0 136 116 0 0 2260 +349 408 0.988351773630863 0.00105373569711038 0.152182985914352 -0.030479703849931 -0.0192856346632637 0.992781502163562 0.118376320510044 -0.0256782406517086 -0.150959716005173 -0.119932391800306 0.981237680452955 -0.00691979782153275 0.000125663727379395 7.38448610071874e-05 -2.38505283932041e-05 8.52041051687625e-07 -1.71920675147037e-05 3.78222288903059e-05 7.38448610071874e-05 0.000110523284652718 -1.55002761763895e-05 2.40445945895318e-05 -1.58217231858018e-05 6.60245133406843e-05 -2.38505283932041e-05 -1.55002761763895e-05 1.65062093593913e-05 7.35831835751825e-06 1.00325893015201e-05 -5.70392246323374e-06 8.52041051687625e-07 2.40445945895318e-05 7.35831835751825e-06 5.02339000362449e-05 -1.00999359337959e-05 3.15777035523934e-05 -1.71920675147037e-05 -1.58217231858018e-05 1.00325893015201e-05 -1.00999359337959e-05 4.19254891451024e-05 -2.27234526007682e-05 3.78222288903059e-05 6.60245133406843e-05 -5.70392246323374e-06 3.15777035523934e-05 -2.27234526007682e-05 0.000151044545768999 1742 1744 0 14 14 1715 1730 0 31 8 0 0 0 0 0 5 19 0 285 0 76 80 0 0 1852 +349 351 0.999996026036494 0.00222800086429107 0.00172740364946148 -0.00390749882379044 -0.00221120054864708 0.999950824563366 -0.00966742195094959 -0.00902065488724747 -0.00174885772809496 0.00966356389707014 0.999951777352015 -0.0136123249578326 0.000135239515566113 3.92701038443233e-05 -2.89890890476584e-05 1.74688939372935e-05 -1.95156187352846e-05 3.17527556254144e-05 3.92701038443233e-05 4.94500004935252e-05 -1.15523478310437e-05 2.04797489673497e-05 -7.88490831260133e-06 2.45608852232872e-05 -2.89890890476584e-05 -1.15523478310437e-05 2.07290481539533e-05 -1.08697668051141e-06 9.61500282568442e-07 -9.01487749354159e-06 1.74688939372935e-05 2.04797489673497e-05 -1.08697668051141e-06 7.64787713402965e-05 -6.01897533079791e-05 3.08515797815463e-05 -1.95156187352846e-05 -7.88490831260133e-06 9.61500282568442e-07 -6.01897533079791e-05 9.20504351963951e-05 -1.86870337334591e-05 3.17527556254144e-05 2.45608852232872e-05 -9.01487749354159e-06 3.08515797815463e-05 -1.86870337334591e-05 9.46575865786655e-05 1810 1807 0 5 29 1803 1815 0 15 23 0 0 0 0 0 6 14 0 272 0 58 63 0 0 3225 +349 397 0.986816725055277 0.0029245717984408 0.161815320754785 -0.0276002647545631 -0.0207991878551451 0.993837289741769 0.108879912303886 -0.0280159070477964 -0.160499672696689 -0.110810145738246 0.980796088219016 0.0098880476152678 0.000154102557524701 0.00011898587319682 -2.67844662515716e-05 7.90605268423866e-06 -2.61186356316964e-05 0.000106602244949937 0.00011898587319682 0.000168627180695102 -2.06920730533628e-05 3.25928680000426e-05 -2.98981419146253e-05 0.000125126548002601 -2.67844662515716e-05 -2.06920730533628e-05 1.76763142988711e-05 5.16022606579375e-06 1.0604074680935e-05 -1.80131492911056e-05 7.90605268423866e-06 3.25928680000426e-05 5.16022606579375e-06 7.32054340684004e-05 -3.41008025844578e-05 2.57837918466411e-05 -2.61186356316964e-05 -2.98981419146253e-05 1.0604074680935e-05 -3.41008025844578e-05 6.92663705200866e-05 -2.569613761392e-05 0.000106602244949937 0.000125126548002601 -1.80131492911056e-05 2.57837918466411e-05 -2.569613761392e-05 0.000183905887621435 1528 1526 0 12 19 1499 1515 0 29 1 0 0 0 0 0 2 16 0 236 0 111 99 0 0 1964 +349 396 0.988227974041796 0.00167900784033814 0.152979254325285 -0.0289119974506815 -0.0198223066538652 0.992916137914513 0.117152120031386 -0.0298936779074884 -0.151698871057659 -0.118805403924233 0.981260785172949 -0.0031347612637351 0.000121418151401985 8.01218196510104e-05 -1.82938313746511e-05 9.48045654740975e-06 -2.30153322785941e-05 5.1959997582306e-05 8.01218196510104e-05 0.000164512352553989 -1.18910577680899e-05 6.52729584470445e-05 -3.42736511702967e-05 0.000109455557695334 -1.82938313746511e-05 -1.18910577680899e-05 1.6907188782036e-05 1.02189498967168e-05 7.4402622148598e-06 -3.0084169899229e-06 9.48045654740975e-06 6.52729584470445e-05 1.02189498967168e-05 9.17639039505502e-05 -1.61064463548167e-05 6.57001262323619e-05 -2.30153322785941e-05 -3.42736511702967e-05 7.4402622148598e-06 -1.61064463548167e-05 5.38653863401173e-05 -2.55885798642608e-05 5.1959997582306e-05 0.000109455557695334 -3.0084169899229e-06 6.57001262323619e-05 -2.55885798642608e-05 0.000189559309608324 1389 1389 0 16 15 1369 1390 0 34 2 0 0 0 0 0 2 16 0 246 0 103 86 0 0 1994 +349 398 0.989557290010621 0.000591641723204946 0.144138890473415 -0.0257135253529734 -0.0180198867492575 0.992654096475159 0.119637487572371 -0.0408627685730598 -0.143009277560512 -0.12098551446829 0.982298758942748 -0.0169285771706046 8.18823054786619e-05 5.12515306841951e-05 -1.72840443246246e-05 -1.4098078962916e-07 1.91337965908009e-07 3.62495712349974e-05 5.12515306841951e-05 0.000120087062069396 -1.21376937336188e-05 3.76966071104795e-05 -1.03163935460103e-05 8.58605373931152e-05 -1.72840443246246e-05 -1.21376937336188e-05 1.6043668587616e-05 8.87255046589438e-06 3.33689945929757e-06 -6.06416401581294e-06 -1.4098078962916e-07 3.76966071104795e-05 8.87255046589438e-06 6.32912919641572e-05 -1.15312688386678e-05 5.10077157958588e-05 1.91337965908009e-07 -1.03163935460103e-05 3.33689945929757e-06 -1.15312688386678e-05 4.75757191443195e-05 -1.10202390051857e-05 3.62495712349974e-05 8.58605373931152e-05 -6.06416401581294e-06 5.10077157958588e-05 -1.10202390051857e-05 0.000170751822060435 1595 1591 0 16 20 1535 1545 0 35 1 0 0 0 0 0 1 16 0 275 0 118 109 0 0 1933 +349 412 0.989224929646245 0.000310292136415678 0.146403354760649 -0.0315482645005214 -0.0182854968320214 0.992429244532203 0.121448899553871 -0.028511636877898 -0.145257286123583 -0.122817337196465 0.981741423447122 -0.015628512587169 0.000141579990115744 8.66380851141172e-05 -2.98850805687405e-05 7.93248458481723e-06 -3.01994795055109e-05 6.02524547812264e-05 8.66380851141172e-05 0.000125900918196593 -2.35909140680681e-05 1.66218598892717e-05 -1.04291158716152e-05 9.19217340238645e-05 -2.98850805687405e-05 -2.35909140680681e-05 1.90138894395902e-05 5.48304101816194e-06 8.00509164899891e-06 -1.15243063249454e-05 7.93248458481723e-06 1.66218598892717e-05 5.48304101816194e-06 4.87951466902141e-05 -5.53375045652157e-06 2.10213487141735e-05 -3.01994795055109e-05 -1.04291158716152e-05 8.00509164899891e-06 -5.53375045652157e-06 4.67858477351419e-05 -1.44545640086002e-05 6.02524547812264e-05 9.19217340238645e-05 -1.15243063249454e-05 2.10213487141735e-05 -1.44545640086002e-05 0.000171285189353554 1381 1381 0 12 23 1392 1408 0 28 17 0 0 0 0 0 3 17 0 363 0 71 76 0 0 1763 +349 395 0.986576167635915 0.00247351914050835 0.16328302776435 -0.0230401237555155 -0.0209866088900317 0.993514353245892 0.111753264568394 -0.0270526208752574 -0.161947607886405 -0.113679864520759 0.98022949389539 0.00432002759458705 0.000134316416910741 8.96276946703123e-05 -2.13996869694856e-05 1.18901013418966e-05 -1.67798046096294e-05 4.60182055553649e-05 8.96276946703123e-05 0.000182455704544497 -1.53505369800344e-05 4.77259461729749e-05 -1.5881692761743e-05 0.00012078133908902 -2.13996869694856e-05 -1.53505369800344e-05 1.64774802652217e-05 5.62868969891718e-06 9.26182057015719e-06 -9.71281435756622e-06 1.18901013418966e-05 4.77259461729749e-05 5.62868969891718e-06 6.07655028635197e-05 -8.28442754388499e-06 4.32192225653623e-05 -1.67798046096294e-05 -1.5881692761743e-05 9.26182057015719e-06 -8.28442754388499e-06 4.17638854259801e-05 -1.10339430382523e-05 4.60182055553649e-05 0.00012078133908902 -9.71281435756622e-06 4.32192225653623e-05 -1.10339430382523e-05 0.000196695432576468 1644 1646 0 21 16 1623 1636 0 30 8 0 0 0 0 0 4 18 0 223 0 120 104 0 0 2001 +349 388 0.987659251448831 0.00191352300575251 0.156606326364043 -0.0260012877328005 -0.0200971964070301 0.993207250202673 0.114610038135506 -0.0301589232935346 -0.155323229827711 -0.116343012572958 0.9809887857164 -0.00859512417119026 0.000149510185073547 0.00013511544099113 -1.84979287008765e-05 3.04751193952303e-05 -4.46652032460123e-05 0.000102840190955637 0.00013511544099113 0.00025354665622309 -1.6936123481873e-05 8.11889661402392e-05 -6.01533870217572e-05 0.000194604416871594 -1.84979287008765e-05 -1.6936123481873e-05 1.58530879103371e-05 2.41374893990251e-06 1.26602976697293e-05 -1.15870614584946e-05 3.04751193952303e-05 8.11889661402392e-05 2.41374893990251e-06 7.69570169083671e-05 -2.81251545676165e-05 8.17501478451087e-05 -4.46652032460123e-05 -6.01533870217572e-05 1.26602976697293e-05 -2.81251545676165e-05 5.83242586621733e-05 -6.51487940996029e-05 0.000102840190955637 0.000194604416871594 -1.15870614584946e-05 8.17501478451087e-05 -6.51487940996029e-05 0.000276693091004849 1646 1645 0 17 15 1600 1609 0 27 3 0 0 0 0 0 2 15 0 426 0 124 107 0 0 2176 +349 406 0.989210731559433 0.000555828913109116 0.146498531125301 -0.0302335338377104 -0.0186255055163297 0.992355199343223 0.122001019998738 -0.0271196528436382 -0.145310767363994 -0.123413327443557 0.981658765303604 -0.0147615867433715 7.09823059813454e-05 2.99011950977435e-05 -1.32048407960457e-05 -1.10967362148671e-05 -2.13225589635783e-06 1.89614159720834e-06 2.99011950977435e-05 5.0123384108229e-05 -5.93258061772878e-06 6.36408494058222e-06 -5.84747602351239e-07 1.10299315240218e-05 -1.32048407960457e-05 -5.93258061772878e-06 1.48692617194646e-05 9.40535889322486e-06 6.60758157639303e-06 -1.46599897168626e-06 -1.10967362148671e-05 6.36408494058222e-06 9.40535889322486e-06 4.32858732123078e-05 4.93008769626079e-07 1.14836775522127e-05 -2.13225589635783e-06 -5.84747602351239e-07 6.60758157639303e-06 4.93008769626079e-07 2.73051364854333e-05 -1.03124520426967e-05 1.89614159720834e-06 1.10299315240218e-05 -1.46599897168626e-06 1.14836775522127e-05 -1.03124520426967e-05 9.53234963131523e-05 1747 1748 0 10 27 1688 1704 0 25 17 0 0 0 0 0 2 16 0 267 0 81 84 0 0 1878 +349 386 0.989368060685475 -0.000219924991162488 0.14543311909074 -0.0301000259681849 -0.0181895426904631 0.991959487980307 0.125241825052809 -0.02537884740214 -0.144291306155898 -0.126555623497515 0.981409034566618 -0.0100034488220564 6.47721894345134e-05 4.71934133187423e-05 -1.62004874017142e-05 -2.2318374865521e-06 -8.27151941877493e-06 1.56218581039309e-05 4.71934133187423e-05 8.39750398209075e-05 -1.8283743352218e-05 1.47928732653759e-05 -6.73371924256033e-06 5.08209064135654e-05 -1.62004874017142e-05 -1.8283743352218e-05 1.85114584980741e-05 4.6002861832014e-06 4.62284707793838e-06 -5.11358353708815e-06 -2.2318374865521e-06 1.47928732653759e-05 4.6002861832014e-06 4.67410720213497e-05 4.57310499821968e-06 2.53366004898446e-05 -8.27151941877493e-06 -6.73371924256033e-06 4.62284707793838e-06 4.57310499821968e-06 4.316775189399e-05 -5.53290761250405e-06 1.56218581039309e-05 5.08209064135654e-05 -5.11358353708815e-06 2.53366004898446e-05 -5.53290761250405e-06 0.000128038845910642 1615 1616 0 16 18 1602 1627 0 28 13 0 0 0 0 0 5 19 0 426 0 97 76 0 0 2268 +349 382 0.989227794084689 0.00080318462536236 0.146382124266584 -0.0316574667057897 -0.0185068457607017 0.992647263161342 0.119619846172314 -0.0293079494948186 -0.145209738207634 -0.121040347953714 0.981969126855277 -0.0102186334899828 8.65683407441636e-05 3.2193911535055e-05 -1.32349674132847e-05 8.09565549785702e-07 -1.52392130036805e-05 4.16962309339432e-06 3.2193911535055e-05 6.87375180161347e-05 -9.39857746270925e-06 1.59808016964012e-05 -2.18351508659885e-06 1.67268173738282e-05 -1.32349674132847e-05 -9.39857746270925e-06 1.45569760690655e-05 3.50445259864256e-06 7.16022994093379e-06 -1.77871904470797e-06 8.09565549785702e-07 1.59808016964012e-05 3.50445259864256e-06 5.14395359949409e-05 -1.65112990161048e-07 1.26442909773251e-05 -1.52392130036805e-05 -2.18351508659885e-06 7.16022994093379e-06 -1.65112990161048e-07 3.70339452542528e-05 -4.15606884403557e-06 4.16962309339432e-06 1.67268173738282e-05 -1.77871904470797e-06 1.26442909773251e-05 -4.15606884403557e-06 8.57203344020412e-05 1778 1776 0 13 22 1712 1721 0 31 0 0 0 0 0 0 5 19 0 452 0 125 109 0 0 2312 +349 381 0.989488075372708 3.34937311108171e-05 0.144614479127726 -0.0276152630525302 -0.0178909008473549 0.992346185440378 0.122184139350411 -0.0315803080960815 -0.143503534319137 -0.123487032194075 0.981915316367871 -0.0138547094004685 7.74909551610808e-05 3.84529151804392e-05 -1.81656694013487e-05 -6.03431749911196e-06 3.4985891596099e-06 9.08124351502655e-06 3.84529151804392e-05 6.06435559167648e-05 -1.56036410112847e-05 8.74967137535882e-06 3.69995074813567e-06 2.68884928625627e-05 -1.81656694013487e-05 -1.56036410112847e-05 1.81445006249839e-05 4.35753889136575e-06 7.89296545569826e-07 -2.95694344003003e-06 -6.03431749911196e-06 8.74967137535882e-06 4.35753889136575e-06 4.89592082927056e-05 -7.09214915196188e-06 1.67270283654262e-05 3.4985891596099e-06 3.69995074813567e-06 7.89296545569826e-07 -7.09214915196188e-06 4.00072746603258e-05 -2.75354243268544e-06 9.08124351502655e-06 2.68884928625627e-05 -2.95694344003003e-06 1.67270283654262e-05 -2.75354243268544e-06 0.000105802432570056 1822 1814 0 10 24 1749 1759 0 27 1 0 0 0 0 0 6 20 0 440 0 120 105 0 0 2320 +349 389 0.98795225378008 0.00219872806199046 0.154743367695579 -0.0311166400420448 -0.0198722503185233 0.993423730269812 0.112758085315821 -0.0297110187946464 -0.153477809204255 -0.11447470345767 0.981498906953105 -0.00527104102197838 0.000104457967945341 5.56766420627166e-05 -1.35663731474431e-05 1.68554588385129e-06 -1.93639885051751e-05 1.92757844826204e-05 5.56766420627166e-05 9.57730511447463e-05 -8.68300207192744e-06 1.87263920658183e-05 -9.92268666747672e-06 4.05066583784908e-05 -1.35663731474431e-05 -8.68300207192744e-06 1.41665953739556e-05 6.55410842554568e-06 9.48608360583277e-06 -5.34609612732178e-06 1.68554588385129e-06 1.87263920658183e-05 6.55410842554568e-06 4.51185672888654e-05 -5.02583404581049e-06 1.20562388003042e-05 -1.93639885051751e-05 -9.92268666747672e-06 9.48608360583277e-06 -5.02583404581049e-06 4.3369467588512e-05 2.07231341031446e-06 1.92757844826204e-05 4.05066583784908e-05 -5.34609612732178e-06 1.20562388003042e-05 2.07231341031446e-06 0.00013495130758352 1506 1502 0 10 18 1476 1490 0 29 0 0 0 0 0 0 3 18 0 287 0 117 101 0 0 2102 +349 385 0.989367147184859 0.00115304375081335 0.145434928959321 -0.0401418237164011 -0.0189544370916796 0.99246236992467 0.121075074222755 -0.0230212627023569 -0.144199089407082 -0.122544337990855 0.981931518915933 -0.0191745044838756 6.5819653939132e-05 3.16698576983097e-05 -1.54215463227785e-05 -4.75060361746689e-06 -3.21021212741656e-06 1.30491642761825e-07 3.16698576983097e-05 6.73076928094734e-05 -1.26581726911888e-05 1.83247958177071e-05 -3.11954599091223e-06 2.04009319447143e-05 -1.54215463227785e-05 -1.26581726911888e-05 1.71657409460723e-05 5.56270375263992e-06 7.61405708975239e-07 -1.56386671586821e-06 -4.75060361746689e-06 1.83247958177071e-05 5.56270375263992e-06 6.16909457943483e-05 -7.46575442068398e-06 1.5365288473596e-05 -3.21021212741656e-06 -3.11954599091223e-06 7.61405708975239e-07 -7.46575442068398e-06 4.43680433041514e-05 -4.03202876494987e-06 1.30491642761825e-07 2.04009319447143e-05 -1.56386671586821e-06 1.5365288473596e-05 -4.03202876494987e-06 9.21849405435596e-05 1650 1641 0 11 21 1578 1588 0 30 0 0 0 0 0 0 2 16 0 439 0 122 105 0 0 2254 +349 378 0.989047214631428 0.00143461542914173 0.147592510339735 -0.0257312215901254 -0.0190468566554799 0.992832528047547 0.117986391173993 -0.0296345972985467 -0.146365380064276 -0.119505284942916 0.98198557137534 -0.00148166253851726 8.540486598027e-05 4.97307878020934e-05 -1.69958035161522e-05 1.44277404754453e-05 -1.03975365024488e-05 3.0064587016869e-05 4.97307878020934e-05 6.71379906388273e-05 -1.54606351940858e-05 1.98444739837933e-05 -8.38146103393315e-06 5.18006031217185e-05 -1.69958035161522e-05 -1.54606351940858e-05 1.67062646088561e-05 -1.17941402785245e-07 2.62931632370726e-06 -5.40673879721507e-06 1.44277404754453e-05 1.98444739837933e-05 -1.17941402785245e-07 4.76707354195231e-05 -3.20868698356824e-06 3.66256105980534e-05 -1.03975365024488e-05 -8.38146103393315e-06 2.62931632370726e-06 -3.20868698356824e-06 4.04901573951768e-05 -1.23255025994034e-05 3.0064587016869e-05 5.18006031217185e-05 -5.40673879721507e-06 3.66256105980534e-05 -1.23255025994034e-05 0.000144506772693841 1688 1684 0 12 19 1662 1681 0 29 6 0 0 0 0 0 4 16 0 455 0 102 80 0 0 2320 +349 380 0.989117124916852 0.00173050322704463 0.147120082092151 -0.0339016810198562 -0.0190790258153287 0.992996638357897 0.116591882152468 -0.0262982073867698 -0.145887984324132 -0.118129935107483 0.982222996300404 -0.00999756872103763 8.38852896690738e-05 5.96178426843029e-05 -1.37925216560901e-05 6.72939483423767e-06 -1.16331831472703e-05 1.84850714936191e-05 5.96178426843029e-05 9.89954339173628e-05 -1.48576901196551e-05 2.18611565327743e-05 -1.5965668404941e-05 5.00263761678085e-05 -1.37925216560901e-05 -1.48576901196551e-05 1.45305706603574e-05 2.33679540497516e-06 5.7925835262836e-06 -2.47587063939412e-06 6.72939483423767e-06 2.18611565327743e-05 2.33679540497516e-06 4.69920861962265e-05 -2.93766543930265e-06 2.95022913550964e-05 -1.16331831472703e-05 -1.5965668404941e-05 5.7925835262836e-06 -2.93766543930265e-06 4.05753855626327e-05 -1.20176845797151e-05 1.84850714936191e-05 5.00263761678085e-05 -2.47587063939412e-06 2.95022913550964e-05 -1.20176845797151e-05 0.000115004242861406 1814 1814 0 14 14 1779 1792 0 29 4 0 0 0 0 0 6 20 0 442 0 136 114 0 0 2262 +349 413 0.990094067484882 0.000731818993337595 0.140403710678184 -0.0377476336974503 -0.0180048705683471 0.99239214008226 0.121793534059777 -0.0269753117762708 -0.139246408093923 -0.12311500616868 0.982574746820326 -0.0178742160941888 8.52863732997775e-05 5.71527360034189e-05 -1.5124467040157e-05 1.81555783939049e-05 -2.17359214441197e-05 3.54600736929296e-05 5.71527360034189e-05 9.3231216365487e-05 -1.60147728356685e-05 2.58486517131263e-05 -8.69543845489644e-06 5.16558414232422e-05 -1.5124467040157e-05 -1.60147728356685e-05 1.60602295616436e-05 4.76290616335052e-06 2.78597418091702e-06 -6.01255645795119e-06 1.81555783939049e-05 2.58486517131263e-05 4.76290616335052e-06 6.41054008569496e-05 -1.50766790080883e-05 2.78789961964452e-05 -2.17359214441197e-05 -8.69543845489644e-06 2.78597418091702e-06 -1.50766790080883e-05 5.93500859647391e-05 -1.65002608245525e-05 3.54600736929296e-05 5.16558414232422e-05 -6.01255645795119e-06 2.78789961964452e-05 -1.65002608245525e-05 0.000126082857134321 1575 1574 0 12 22 1550 1569 0 30 15 0 0 0 0 0 2 17 0 394 0 58 65 0 0 1724 +349 407 0.98991423520658 0.00124021783943326 0.141662517255209 -0.0412242959409071 -0.0188897655368095 0.992188124840315 0.123312212224997 -0.0215929360288877 -0.140402933350183 -0.124744485992644 0.982204576206553 -0.0163955531171276 0.000125084567965539 0.000123437879182219 -1.5409566485337e-05 4.45389751635692e-05 -3.21877261872365e-05 9.40769342950487e-05 0.000123437879182219 0.000241097503083857 -1.83908045043875e-05 9.77322530977039e-05 -5.34309267974188e-05 0.000200875142573641 -1.5409566485337e-05 -1.83908045043875e-05 1.52925204345419e-05 2.87930829401878e-06 1.03133307247872e-05 -1.13879018650581e-05 4.45389751635692e-05 9.77322530977039e-05 2.87930829401878e-06 9.40823324421788e-05 -2.43206296852507e-05 0.000100681784049201 -3.21877261872365e-05 -5.34309267974188e-05 1.03133307247872e-05 -2.43206296852507e-05 5.07516727259672e-05 -5.23010252706916e-05 9.40769342950487e-05 0.000200875142573641 -1.13879018650581e-05 0.000100681784049201 -5.23010252706916e-05 0.000269796569412581 1369 1369 0 12 16 1360 1381 0 31 11 0 0 0 0 0 6 20 0 288 0 66 71 0 0 1796 +349 384 0.98910358939462 0.000573162865352799 0.1472201104843 -0.0353640973194272 -0.0188552975095988 0.99225021055614 0.122816926386878 -0.0207926977217878 -0.146008791524703 -0.124254541710253 0.981449051994993 -0.0113594915114878 6.92624273599443e-05 3.7077009039623e-05 -1.51657375543302e-05 -4.39029040532673e-06 -5.06524379360149e-06 2.39722841762109e-05 3.7077009039623e-05 7.68533127255793e-05 -1.50229235277782e-05 1.04818939008807e-05 -4.7168160329635e-07 3.12597861075798e-05 -1.51657375543302e-05 -1.50229235277782e-05 1.60136866400608e-05 2.44407911433357e-06 2.60229577028923e-06 -8.14768434387976e-06 -4.39029040532673e-06 1.04818939008807e-05 2.44407911433357e-06 4.9035979093716e-05 -1.23293725217109e-05 7.20395574008264e-07 -5.06524379360149e-06 -4.7168160329635e-07 2.60229577028923e-06 -1.23293725217109e-05 4.84864450565863e-05 4.61291943099098e-07 2.39722841762109e-05 3.12597861075798e-05 -8.14768434387976e-06 7.20395574008264e-07 4.61291943099098e-07 9.15301961185726e-05 1833 1832 0 13 15 1788 1800 0 32 4 0 0 0 0 0 5 19 0 450 0 132 113 0 0 2350 +349 383 0.989299899738504 0.000820195497602582 0.14589391919039 -0.037781396912898 -0.0185881908828194 0.992543444878532 0.12046571789667 -0.0239166135847916 -0.144707247700625 -0.121888626655656 0.981938376454912 -0.0141954980835242 9.78004235917341e-05 4.18580442021482e-05 -2.05371552879686e-05 -1.41771423862467e-06 -3.96237983395064e-06 1.82502090414241e-05 4.18580442021482e-05 6.40253548567579e-05 -1.48086451953887e-05 9.82042134790548e-06 3.32299644135609e-06 1.01321365305037e-05 -2.05371552879686e-05 -1.48086451953887e-05 1.78444262847348e-05 4.71702595161671e-06 3.55797749095234e-06 -6.55249688381435e-06 -1.41771423862467e-06 9.82042134790548e-06 4.71702595161671e-06 4.61762106471483e-05 5.96944474599238e-06 5.64373059881143e-06 -3.96237983395064e-06 3.32299644135609e-06 3.55797749095234e-06 5.96944474599238e-06 3.63632220394497e-05 -7.93593720979727e-07 1.82502090414241e-05 1.01321365305037e-05 -6.55249688381435e-06 5.64373059881143e-06 -7.93593720979727e-07 8.40855939259439e-05 1673 1670 0 13 15 1633 1645 0 29 4 0 0 0 0 0 2 17 0 435 0 137 117 0 0 2246 +349 377 0.989199164852055 0.000824878676977452 0.146575345236382 -0.0287617177885182 -0.018799273275506 0.992439528421159 0.121286313125186 -0.0294348080031889 -0.145367120011057 -0.122731829621969 0.981735859800046 -0.00555985559732902 0.000105342491150509 5.73066099731017e-05 -1.94690438698157e-05 1.61706018756466e-06 -1.36478738039293e-05 4.36824014942874e-05 5.73066099731017e-05 9.46257841367659e-05 -1.67850236612912e-05 1.65974658737711e-05 -1.69925758893987e-06 7.42412340828672e-05 -1.94690438698157e-05 -1.67850236612912e-05 1.71524535230665e-05 5.03604692868127e-06 5.72569647072394e-06 -6.10272423835193e-06 1.61706018756466e-06 1.65974658737711e-05 5.03604692868127e-06 4.97107454453777e-05 2.30473713733931e-06 3.2465114726105e-05 -1.36478738039293e-05 -1.69925758893987e-06 5.72569647072394e-06 2.30473713733931e-06 4.22722250618432e-05 -1.10051189097966e-05 4.36824014942874e-05 7.42412340828672e-05 -6.10272423835193e-06 3.2465114726105e-05 -1.10051189097966e-05 0.000154833145923633 1578 1577 0 12 19 1584 1598 0 31 3 0 0 0 0 0 3 18 0 431 0 119 104 0 0 2235 +350 352 0.999989965752619 0.00390677227913407 0.00219215064132116 -0.0155533645290054 -0.00387751890994477 0.999905439451413 -0.0131938244106773 0.00596519835827864 -0.00224348861781733 0.0131851919150141 0.999910554736265 -0.00919836264162787 7.64262598385306e-05 3.90053350719479e-05 -1.61401965525303e-05 1.66592604517884e-05 4.1318897045798e-06 4.53126044462728e-05 3.90053350719479e-05 6.56313794764959e-05 -1.6078469748215e-05 1.66851426465941e-05 1.53077917128782e-05 3.64645606873895e-05 -1.61401965525303e-05 -1.6078469748215e-05 1.65841205839968e-05 -9.98036756923307e-07 -2.60304575250858e-06 -1.33390785604449e-05 1.66592604517884e-05 1.66851426465941e-05 -9.98036756923307e-07 6.66946204848108e-05 -5.07633436168466e-05 1.85528798771213e-05 4.1318897045798e-06 1.53077917128782e-05 -2.60304575250858e-06 -5.07633436168466e-05 0.000103141579591151 5.87783110947608e-06 4.53126044462728e-05 3.64645606873895e-05 -1.33390785604449e-05 1.85528798771213e-05 5.87783110947608e-06 7.77038524711133e-05 1658 1638 0 11 28 1660 1670 0 18 14 0 0 0 0 0 6 15 0 274 0 64 61 0 0 3314 +350 353 0.999920072853023 0.00330666131522092 0.0122030281713896 -0.0192017856589799 -0.00322907726271631 0.999974484971584 -0.00637200642234635 0.0195363096289237 -0.0122237868779162 0.00633209260524797 0.999905237328819 -0.00587377678439606 7.19510328641139e-05 4.02747470678793e-05 -1.90517616108162e-05 1.59889315956235e-05 -7.26444395589192e-07 4.03858899988891e-05 4.02747470678793e-05 6.37857007806799e-05 -1.45874364087401e-05 2.38433148732205e-05 2.99811398672299e-06 3.62431532779851e-05 -1.90517616108162e-05 -1.45874364087401e-05 1.78578656058133e-05 -4.6897366109411e-06 -5.07691202970112e-07 -1.47380061035711e-05 1.59889315956235e-05 2.38433148732205e-05 -4.6897366109411e-06 4.78172452231928e-05 -1.45508889027239e-05 2.63936298461223e-05 -7.26444395589192e-07 2.99811398672299e-06 -5.07691202970112e-07 -1.45508889027239e-05 4.98482643344049e-05 -4.15388618430168e-06 4.03858899988891e-05 3.62431532779851e-05 -1.47380061035711e-05 2.63936298461223e-05 -4.15388618430168e-06 7.94448375843272e-05 1987 1966 0 6 46 1986 1989 0 15 29 0 0 0 0 0 12 22 0 285 0 79 59 0 0 3258 +350 410 0.98908105721977 0.000992684254093041 0.147369185473065 -0.0316192372461456 -0.0195023065048039 0.99206442570213 0.124208837436377 -0.0176298624162286 -0.146076426195384 -0.125726647272069 0.981251490636172 -0.00498709737031477 7.011516347412e-05 4.22945992069342e-05 -9.29205678255843e-06 1.79194300296019e-06 -1.25274613521046e-05 2.32895388625431e-05 4.22945992069342e-05 6.94321806554281e-05 -6.90161691344592e-06 2.38324406700648e-05 -1.21985671470913e-05 4.74542395760019e-05 -9.29205678255843e-06 -6.90161691344592e-06 1.1869097655033e-05 5.41420613126826e-06 7.35625897314048e-06 -1.83148583814698e-06 1.79194300296019e-06 2.38324406700648e-05 5.41420613126826e-06 5.28447619604696e-05 -1.84774525887442e-06 3.13224753225376e-05 -1.25274613521046e-05 -1.21985671470913e-05 7.35625897314048e-06 -1.84774525887442e-06 3.66953068361704e-05 -3.44756145031428e-06 2.32895388625431e-05 4.74542395760019e-05 -1.83148583814698e-06 3.13224753225376e-05 -3.44756145031428e-06 0.00012429215087788 1674 1672 0 9 8 1684 1704 0 24 13 0 0 0 0 0 3 15 0 305 0 85 89 0 0 1848 +349 390 0.98724865998153 0.00237936752305598 0.159167904977301 -0.0240034862370419 -0.0204585464361446 0.993492636373165 0.112043872434052 -0.0286349600237708 -0.157865547990666 -0.113871506894781 0.980872952361884 0.0047232312663956 0.000128820762654612 4.81144639833459e-05 -2.04589150876202e-05 -9.73356210620202e-06 -7.05413792702058e-06 1.86069062122183e-05 4.81144639833459e-05 9.8489954218787e-05 -1.07866491465412e-05 2.41251008062428e-05 2.9554949190617e-06 3.42019867578581e-05 -2.04589150876202e-05 -1.07866491465412e-05 1.65177997847025e-05 1.00330593097812e-05 6.50749325663021e-06 -4.07452346485146e-06 -9.73356210620202e-06 2.41251008062428e-05 1.00330593097812e-05 6.06161048697521e-05 -2.58257523378674e-07 3.29799148289952e-05 -7.05413792702058e-06 2.9554949190617e-06 6.50749325663021e-06 -2.58257523378674e-07 4.5861221962434e-05 -1.24401104984962e-06 1.86069062122183e-05 3.42019867578581e-05 -4.07452346485146e-06 3.29799148289952e-05 -1.24401104984962e-06 0.000130107556225272 1388 1387 0 16 22 1352 1366 0 30 1 0 0 0 0 0 2 16 0 198 0 115 99 0 0 1964 +350 411 0.988718971354358 0.00213782648684899 0.149767237344796 -0.0294632069108314 -0.02000675499139 0.992823105023041 0.11790679321872 -0.0183247151843678 -0.148440309345861 -0.119573039730199 0.981665810105957 0.0040357239644969 0.000108007497903015 7.41871835454401e-05 -2.07643961632226e-05 3.78089381400813e-06 -1.10478005021222e-05 5.47080121014374e-05 7.41871835454401e-05 0.000110715463387891 -1.6995826716206e-05 2.33810739832584e-05 -1.04398863938864e-05 6.41327202395379e-05 -2.07643961632226e-05 -1.6995826716206e-05 1.58403710757844e-05 4.98487164070035e-06 6.51797707346292e-06 -1.08520448376605e-05 3.78089381400813e-06 2.33810739832584e-05 4.98487164070035e-06 4.63137059045053e-05 -1.32724422192879e-07 1.7632195817235e-05 -1.10478005021222e-05 -1.04398863938864e-05 6.51797707346292e-06 -1.32724422192879e-07 4.15616127428011e-05 -1.14862675124266e-05 5.47080121014374e-05 6.41327202395379e-05 -1.08520448376605e-05 1.7632195817235e-05 -1.14862675124266e-05 0.000126369422249135 1535 1540 0 14 9 1501 1522 0 27 3 0 0 0 0 0 5 17 0 321 0 65 66 0 0 1906 +349 379 0.989255273659985 0.00122585880939849 0.146193367859448 -0.0298190706226933 -0.0186102479576488 0.992885994954653 0.117605525779461 -0.0286835225609106 -0.145009179733089 -0.119062581414515 0.982240520188436 -0.0108016681726895 0.000127055714072524 6.59738447517667e-05 -2.06382412791685e-05 -1.97328126917597e-07 -3.01507282743452e-05 3.87084267894249e-05 6.59738447517667e-05 0.000102936763573794 -1.41595651467255e-05 1.91907044434412e-05 -7.17407849067481e-06 7.10924183586232e-05 -2.06382412791685e-05 -1.41595651467255e-05 1.60738031637431e-05 3.5657935879006e-06 7.75744987960062e-06 -5.39870617404702e-06 -1.97328126917597e-07 1.91907044434412e-05 3.5657935879006e-06 4.8361112327403e-05 -3.71549400343573e-06 2.02803363662118e-05 -3.01507282743452e-05 -7.17407849067481e-06 7.75744987960062e-06 -3.71549400343573e-06 5.37040060805369e-05 -3.09433115436358e-06 3.87084267894249e-05 7.10924183586232e-05 -5.39870617404702e-06 2.02803363662118e-05 -3.09433115436358e-06 0.000146329554517772 1737 1734 0 12 16 1701 1712 0 28 5 0 0 0 0 0 5 19 0 437 0 136 114 0 0 2260 +350 354 0.999988089627472 0.00322154542130504 0.00366636717989643 -0.0205905807791915 -0.0031937674845262 0.999966343557577 -0.00755722180072126 0.0128836905638376 -0.00369058971631044 0.00754542226710885 0.999964722452926 -0.0133882919567469 4.96726824166473e-05 1.10740713333703e-05 -5.97901163407334e-06 -4.2941752859366e-06 3.78608143501945e-06 1.26650810056805e-05 1.10740713333703e-05 7.01339377628683e-05 -6.67841594275462e-06 2.5276796557789e-05 -2.27020217439738e-06 3.16726923656317e-05 -5.97901163407334e-06 -6.67841594275462e-06 1.3319536453316e-05 1.96003208184792e-06 2.0311265408423e-07 -3.6995493150008e-06 -4.2941752859366e-06 2.5276796557789e-05 1.96003208184792e-06 6.4058855193672e-05 -3.09396452083974e-05 2.08358315820072e-05 3.78608143501945e-06 -2.27020217439738e-06 2.0311265408423e-07 -3.09396452083974e-05 6.51311946159199e-05 -8.29982917050083e-06 1.26650810056805e-05 3.16726923656317e-05 -3.6995493150008e-06 2.08358315820072e-05 -8.29982917050083e-06 6.87556547944614e-05 1933 1914 0 8 54 1903 1918 0 13 31 0 0 0 0 0 13 20 0 281 0 68 44 0 0 3138 +350 409 0.988824100182715 0.00177349934213816 0.149076334801764 -0.0319455498468517 -0.0199185728059868 0.99253625827136 0.120312204177554 -0.0223330353167748 -0.147750293925991 -0.121936994865268 0.981479098059664 -0.00206194620645209 0.000167825003207565 0.00012547035998197 -2.42905113058963e-05 1.16827732567177e-05 -3.04395804034189e-05 0.000103718625725557 0.00012547035998197 0.000230014085769085 -1.89812866246837e-05 7.09286116403062e-05 -3.44961663643152e-05 0.000178932111232843 -2.42905113058963e-05 -1.89812866246837e-05 1.5443850815266e-05 5.02052235271629e-06 1.15429881685097e-05 -1.42442422498111e-05 1.16827732567177e-05 7.09286116403062e-05 5.02052235271629e-06 9.0189067663341e-05 -1.5151618378636e-05 6.72187639921747e-05 -3.04395804034189e-05 -3.44961663643152e-05 1.15429881685097e-05 -1.5151618378636e-05 4.9247787499265e-05 -2.70269824192374e-05 0.000103718625725557 0.000178932111232843 -1.42442422498111e-05 6.72187639921747e-05 -2.70269824192374e-05 0.000258604048059444 1583 1579 0 7 9 1590 1606 0 22 4 0 0 0 0 0 4 15 0 291 0 100 105 0 0 1884 +350 408 0.988192572537944 0.00136960753145679 0.153210847383763 -0.0276638015862833 -0.0200239618164956 0.992538086752997 0.120279621290853 -0.022175009393501 -0.151902865456885 -0.121927316545183 0.980846190259247 0.00231933283500553 0.000138438593117258 8.55915663374266e-05 -2.08217783799903e-05 3.41405080904968e-06 -2.96332986649646e-05 7.49126734725313e-05 8.55915663374266e-05 0.000142998335006565 -1.52259204224851e-05 3.186319594505e-05 -2.41615460173926e-05 0.000100195806484977 -2.08217783799903e-05 -1.52259204224851e-05 1.45390623846299e-05 4.32976449565761e-06 1.15210170306133e-05 -1.65682906502268e-05 3.41405080904968e-06 3.186319594505e-05 4.32976449565761e-06 5.3773907321508e-05 -6.44690942110107e-06 3.28817713536522e-05 -2.96332986649646e-05 -2.41615460173926e-05 1.15210170306133e-05 -6.44690942110107e-06 4.24770283999901e-05 -1.94056179781503e-05 7.49126734725313e-05 0.000100195806484977 -1.65682906502268e-05 3.28817713536522e-05 -1.94056179781503e-05 0.000179440215701444 1869 1878 0 11 9 1845 1864 0 27 4 0 0 0 0 0 6 17 0 280 0 70 75 0 0 1980 +350 381 0.989675671302809 0.000456765776330006 0.143324307067436 -0.0317548410290328 -0.0187275191519933 0.991833704128841 0.126155393782725 -0.0227710319479134 -0.142096254904015 -0.12753703273594 0.981602241044286 -0.00700289499981733 5.63349792844247e-05 3.30786415056514e-05 -1.11487628899596e-05 -2.2267361124827e-06 3.75669128764445e-06 1.09560386280194e-05 3.30786415056514e-05 7.09773833287594e-05 -9.59083201128103e-06 2.19188751047023e-05 1.99655576080557e-06 2.73308994952184e-05 -1.11487628899596e-05 -9.59083201128103e-06 1.53293146072481e-05 6.51059028448991e-06 1.38851754809133e-06 -5.74541764083775e-07 -2.2267361124827e-06 2.19188751047023e-05 6.51059028448991e-06 6.30501636096755e-05 -7.58819331249194e-06 2.09472856594328e-05 3.75669128764445e-06 1.99655576080557e-06 1.38851754809133e-06 -7.58819331249194e-06 4.1137452614582e-05 3.58508871368836e-06 1.09560386280194e-05 2.73308994952184e-05 -5.74541764083775e-07 2.09472856594328e-05 3.58508871368836e-06 9.03739398941075e-05 1741 1736 0 11 22 1677 1683 0 20 2 0 0 0 0 0 5 14 0 434 0 125 110 0 0 2419 +350 398 0.988694269136138 0.00149686448268489 0.149937992430463 -0.0258260098833321 -0.0198511658174948 0.992455079161792 0.120991103233452 -0.0277047295968913 -0.148625614861784 -0.122599654333453 0.981264363647368 -0.00693407520673157 0.000153604020197168 0.000133258849800379 -2.58646495720633e-05 3.43466762384248e-05 -3.95415253086853e-05 0.000113108827217931 0.000133258849800379 0.000167926551176893 -2.52323755268389e-05 4.94629019105051e-05 -3.95876597209214e-05 0.000128782846061255 -2.58646495720633e-05 -2.52323755268389e-05 1.55085348041723e-05 5.816708536164e-08 1.06359052572536e-05 -1.82123450896532e-05 3.43466762384248e-05 4.94629019105051e-05 5.816708536164e-08 5.66733132206823e-05 -1.85059417029528e-05 5.20425226526002e-05 -3.95415253086853e-05 -3.95876597209214e-05 1.06359052572536e-05 -1.85059417029528e-05 6.16231765114855e-05 -5.16446940432515e-05 0.000113108827217931 0.000128782846061255 -1.82123450896532e-05 5.20425226526002e-05 -5.16446940432515e-05 0.000232222111875103 1641 1637 0 13 18 1595 1605 0 23 5 0 0 0 0 0 1 13 0 262 0 120 111 0 0 1998 +350 412 0.989879375927403 0.00106787811119912 0.141907296323746 -0.0341747822478939 -0.0188907729260825 0.992063864161227 0.12430779590898 -0.0204943123668439 -0.140648355169305 -0.125730461948699 0.982043731778955 -0.00762004001900226 9.85348067989998e-05 6.17636477532733e-05 -1.74595002077735e-05 -1.8894156567928e-06 -6.55593040842162e-06 5.20933042425045e-05 6.17636477532733e-05 8.91650074764947e-05 -1.51990312209983e-05 1.22979674294336e-05 4.11650477064794e-07 5.85547879980615e-05 -1.74595002077735e-05 -1.51990312209983e-05 1.5564126970234e-05 3.67366726389885e-06 6.24310911863064e-06 -7.75310588545446e-06 -1.8894156567928e-06 1.22979674294336e-05 3.67366726389885e-06 5.78617568039892e-05 -1.17802670761236e-05 1.1978779736196e-05 -6.55593040842162e-06 4.11650477064794e-07 6.24310911863064e-06 -1.17802670761236e-05 4.78185977966784e-05 7.58257138210345e-06 5.20933042425045e-05 5.85547879980615e-05 -7.75310588545446e-06 1.1978779736196e-05 7.58257138210345e-06 0.000131101694202434 1491 1489 0 12 8 1486 1504 0 22 10 0 0 0 0 0 3 14 0 363 0 74 77 0 0 1890 +350 383 0.989422975065345 0.000102493530361315 0.145059180708831 -0.0312043480485374 -0.0189973171078651 0.991478630337345 0.128876792042191 -0.021787368245065 -0.143809868769651 -0.130269394254595 0.980993683244187 -0.0104256674516755 6.39998734650578e-05 3.28393711521274e-05 -8.58377391100917e-06 -5.9589570752289e-06 -2.30837634743874e-06 2.24769599944803e-05 3.28393711521274e-05 6.10227355416575e-05 -8.95183823452522e-06 8.39879696847963e-06 2.26400936586316e-06 2.0119381256904e-05 -8.58377391100917e-06 -8.95183823452522e-06 1.35622741943814e-05 2.58008254437298e-06 3.69798438243734e-06 -4.81503485705003e-06 -5.9589570752289e-06 8.39879696847963e-06 2.58008254437298e-06 5.30113480944386e-05 4.22234851534096e-06 6.06931792951246e-06 -2.30837634743874e-06 2.26400936586316e-06 3.69798438243734e-06 4.22234851534096e-06 3.92381009700735e-05 4.74680979129921e-06 2.24769599944803e-05 2.0119381256904e-05 -4.81503485705003e-06 6.06931792951246e-06 4.74680979129921e-06 9.16964968707998e-05 1775 1781 0 12 16 1733 1754 0 22 8 0 0 0 0 0 4 17 0 438 0 123 102 0 0 2376 +350 396 0.988842194666693 0.000482538936822517 0.148966040435167 -0.029070563384149 -0.0196936589384565 0.991641097381805 0.127515072760142 -0.0204581338790642 -0.147659316822113 -0.129025970794964 0.980586062013959 0.00190110344312578 5.3834787716524e-05 3.52719235852386e-05 -6.22925695288609e-06 -1.10189267978774e-05 -2.96834731965207e-08 2.86255126790152e-05 3.52719235852386e-05 9.78134021130059e-05 -5.55156976752513e-06 1.66177515326832e-05 -1.00832015698357e-05 2.8882389369424e-05 -6.22925695288609e-06 -5.55156976752513e-06 1.20963621545049e-05 9.58100259696097e-06 4.77855782738604e-06 -3.64314069076592e-06 -1.10189267978774e-05 1.66177515326832e-05 9.58100259696097e-06 5.5113869699737e-05 -3.00046551934749e-07 2.65592867253206e-06 -2.96834731965207e-08 -1.00832015698357e-05 4.77855782738604e-06 -3.00046551934749e-07 4.22010998671891e-05 1.03461091382215e-06 2.86255126790152e-05 2.8882389369424e-05 -3.64314069076592e-06 2.65592867253206e-06 1.03461091382215e-06 0.000110462365448704 1478 1476 0 12 14 1490 1512 0 27 9 0 0 0 0 0 3 15 0 253 0 133 117 0 0 2097 +350 395 0.987673612890157 0.00205478076872567 0.156513936365096 -0.0234456267069453 -0.0206780889727918 0.992863095375013 0.117453354480752 -0.0189076327043358 -0.155155570434767 -0.119241988067712 0.980667169453899 0.00307702988897818 0.00019511707947318 0.000149933079739984 -3.21998617312777e-05 1.08830973854807e-05 -3.03189884115588e-05 0.000141525612517453 0.000149933079739984 0.000178083877536954 -2.71089676001208e-05 3.87922915343328e-05 -3.84231280084116e-05 0.000145997623436823 -3.21998617312777e-05 -2.71089676001208e-05 1.69052642535558e-05 4.00683328082875e-06 1.09362487649861e-05 -2.45185177769998e-05 1.08830973854807e-05 3.87922915343328e-05 4.00683328082875e-06 5.96424897706067e-05 -7.19308016425285e-06 5.02781604173205e-05 -3.03189884115588e-05 -3.84231280084116e-05 1.09362487649861e-05 -7.19308016425285e-06 4.00698911857004e-05 -4.2337653805376e-05 0.000141525612517453 0.000145997623436823 -2.45185177769998e-05 5.02781604173205e-05 -4.2337653805376e-05 0.000250994316016783 1949 1955 0 14 14 1927 1950 0 25 10 0 0 0 0 0 5 17 0 227 0 119 102 0 0 2093 +350 387 0.989661688594449 0.00114014642560375 0.143417021983135 -0.0351653373913496 -0.0190831299572306 0.992123984527233 0.123797550366884 -0.0184182319144539 -0.142146319964389 -0.12525453840853 0.981888855384685 -0.00362301588580864 7.28013333487374e-05 4.2317176144407e-05 -1.72238505214327e-05 4.05400104889249e-06 6.09078193263708e-06 1.16161422241682e-05 4.2317176144407e-05 8.54460434472747e-05 -1.19232101484727e-05 2.40654987746583e-05 -3.14086596042404e-07 5.09533720531133e-05 -1.72238505214327e-05 -1.19232101484727e-05 1.70748477342715e-05 2.03619936090347e-06 -7.75073178808895e-07 -2.83960589899244e-06 4.05400104889249e-06 2.40654987746583e-05 2.03619936090347e-06 6.51518052727337e-05 -3.08947905126459e-06 2.30187047749348e-05 6.09078193263708e-06 -3.14086596042404e-07 -7.75073178808895e-07 -3.08947905126459e-06 4.42103316138144e-05 1.96105345129616e-06 1.16161422241682e-05 5.09533720531133e-05 -2.83960589899244e-06 2.30187047749348e-05 1.96105345129616e-06 0.000113477038509967 1891 1897 0 12 15 1851 1871 0 25 6 0 0 0 0 0 5 17 0 440 0 126 106 0 0 2349 +350 382 0.989470911906637 0.00115475947790857 0.144727264263498 -0.0318187222556181 -0.0191414213984136 0.992228356635942 0.122949153207274 -0.0225069181246879 -0.14346051888062 -0.124424896295258 0.98180320059797 -0.00372057307971843 7.41260723956077e-05 5.27608177534275e-05 -1.39715646582387e-05 1.07374750503086e-05 -1.14275806579852e-05 3.3751478664962e-05 5.27608177534275e-05 0.000103571526681624 -1.2137464053672e-05 4.09527324436987e-05 -1.44878667141121e-05 6.36827255041157e-05 -1.39715646582387e-05 -1.2137464053672e-05 1.412420565703e-05 2.93701885186539e-06 5.00068000309613e-06 -3.09547552505068e-06 1.07374750503086e-05 4.09527324436987e-05 2.93701885186539e-06 7.23660043815363e-05 -9.32678898669421e-06 4.70857098862704e-05 -1.14275806579852e-05 -1.44878667141121e-05 5.00068000309613e-06 -9.32678898669421e-06 4.5108689269273e-05 -1.18672005342054e-05 3.3751478664962e-05 6.36827255041157e-05 -3.09547552505068e-06 4.70857098862704e-05 -1.18672005342054e-05 0.000133144287112265 1801 1796 0 11 24 1736 1747 0 25 5 0 0 0 0 0 2 14 0 448 0 126 109 0 0 2415 +350 397 0.989642133501933 0.00157518482800635 0.143547784345491 -0.0334099489835365 -0.0194920667827226 0.992153817179226 0.123494382014844 -0.0203987423731242 -0.142226955709105 -0.125013286691647 0.981907924003199 -0.000926120385445843 0.000128570492306498 0.000120836619893072 -1.90057033511802e-05 8.72055921834112e-06 -8.75944651805709e-06 9.8912890273887e-05 0.000120836619893072 0.000215132353961144 -1.87892295240655e-05 4.41199160295979e-05 -1.23828481616662e-05 0.000147480935182429 -1.90057033511802e-05 -1.87892295240655e-05 1.43005473598198e-05 4.60035982939158e-06 6.47598506592954e-06 -1.44575493653323e-05 8.72055921834112e-06 4.41199160295979e-05 4.60035982939158e-06 6.98530926954252e-05 -1.93484016082547e-05 3.0187237983834e-05 -8.75944651805709e-06 -1.23828481616662e-05 6.47598506592954e-06 -1.93484016082547e-05 5.42916656066691e-05 1.07704256969731e-06 9.8912890273887e-05 0.000147480935182429 -1.44575493653323e-05 3.0187237983834e-05 1.07704256969731e-06 0.00020920215667046 1508 1509 0 11 17 1501 1520 0 21 4 0 0 0 0 0 6 16 0 267 0 115 99 0 0 2063 +350 386 0.988552853374094 0.000274320298548563 0.150874719003255 -0.0248140485140325 -0.0195348695576944 0.991813479520792 0.126191959776456 -0.0201669248069627 -0.14960496301026 -0.127694739865167 0.980465404006417 0.00240795054783145 9.91363846722733e-05 6.00063011523013e-05 -1.75717391324456e-05 -5.72606795079238e-06 -7.15634403203692e-06 5.52349148154538e-05 6.00063011523013e-05 0.000108420807240153 -1.48682231026703e-05 1.77112685973415e-05 -3.09855231667006e-06 7.29579311627986e-05 -1.75717391324456e-05 -1.48682231026703e-05 1.52247147617965e-05 4.71203904298913e-06 4.58101025162505e-06 -1.12526302414906e-05 -5.72606795079238e-06 1.77112685973415e-05 4.71203904298913e-06 4.64398153730114e-05 3.90175136910914e-06 2.27811406911394e-05 -7.15634403203692e-06 -3.09855231667006e-06 4.58101025162505e-06 3.90175136910914e-06 3.87908867737408e-05 -8.35192665419196e-08 5.52349148154538e-05 7.29579311627986e-05 -1.12526302414906e-05 2.27811406911394e-05 -8.35192665419196e-08 0.000151188252475634 1688 1682 0 10 16 1694 1713 0 21 10 0 0 0 0 0 3 14 0 413 0 136 118 0 0 2386 +350 388 0.990045929310647 -0.000303959334230422 0.140744326578872 -0.0318727759447372 -0.0182431487894961 0.99128444637915 0.13046966654754 -0.0224809318875431 -0.139557319326724 -0.131738581954965 0.981411585751276 -0.0164723188116213 7.87011656382739e-05 3.32119501092298e-05 -1.26850137613726e-05 -7.62591880275265e-06 -9.54905599338847e-06 1.16931099045381e-05 3.32119501092298e-05 6.65604045158158e-05 -6.96480277040773e-06 1.29986577319598e-05 -5.53394165917226e-06 2.96872491100914e-05 -1.26850137613726e-05 -6.96480277040773e-06 1.45626381443142e-05 8.21874047966408e-06 9.29448856855906e-06 -1.06619798560459e-06 -7.62591880275265e-06 1.29986577319598e-05 8.21874047966408e-06 5.25024610920533e-05 -3.99735138184632e-06 7.78424148074589e-06 -9.54905599338847e-06 -5.53394165917226e-06 9.29448856855906e-06 -3.99735138184632e-06 3.408787262546e-05 4.36369974106552e-06 1.16931099045381e-05 2.96872491100914e-05 -1.06619798560459e-06 7.78424148074589e-06 4.36369974106552e-06 0.000111554238559304 1735 1735 0 12 20 1669 1682 0 22 5 0 0 0 0 0 4 15 0 444 0 122 105 0 0 2280 +350 385 0.98933997665183 0.00078596077009404 0.145622089204295 -0.0353323760403019 -0.0189956486190147 0.992137898744873 0.123699455163112 -0.0194037380229377 -0.144379970674947 -0.125147002120609 0.981576615414266 -0.00908447350948768 7.5927700922975e-05 3.96357682033384e-05 -1.72811294875085e-05 1.03911345631333e-05 -1.49597411628635e-05 2.05421720167253e-06 3.96357682033384e-05 0.000114953027989262 -1.55751206685339e-05 5.20336034365213e-05 -1.92943371776944e-05 1.62520787818684e-05 -1.72811294875085e-05 -1.55751206685339e-05 1.73826294604176e-05 -1.07547775512249e-06 3.46589581643964e-06 -2.43279269755045e-06 1.03911345631333e-05 5.20336034365213e-05 -1.07547775512249e-06 8.11470914993237e-05 -2.14070520649138e-05 1.89853224920378e-05 -1.49597411628635e-05 -1.92943371776944e-05 3.46589581643964e-06 -2.14070520649138e-05 5.59607671016589e-05 -9.79299369142558e-06 2.05421720167253e-06 1.62520787818684e-05 -2.43279269755045e-06 1.89853224920378e-05 -9.79299369142558e-06 9.27800824058226e-05 1804 1799 0 13 23 1739 1748 0 22 6 0 0 0 0 0 1 12 0 424 0 124 107 0 0 2352 +350 378 0.990019609168797 0.000590252254093853 0.140928439512888 -0.0234163690854154 -0.0181549295172542 0.992193114677621 0.12338242063011 -0.0274735565456593 -0.139755400595057 -0.124709561736855 0.98230135560118 0.00303279620787985 6.75319035957998e-05 2.36999621915462e-05 -1.08992550564782e-05 -1.702129239872e-06 -7.44142792827471e-07 8.97739894178636e-06 2.36999621915462e-05 4.4848728278961e-05 -9.43894472323602e-06 5.74960054244964e-06 5.84428677607155e-06 2.12906096467361e-05 -1.08992550564782e-05 -9.43894472323602e-06 1.33897121433284e-05 2.7206953500694e-06 1.88626803942059e-06 -3.10818660928265e-06 -1.702129239872e-06 5.74960054244964e-06 2.7206953500694e-06 3.4092986167635e-05 7.04588899748867e-06 1.29977859774347e-05 -7.44142792827471e-07 5.84428677607155e-06 1.88626803942059e-06 7.04588899748867e-06 3.28094768496333e-05 8.83319513387573e-06 8.97739894178636e-06 2.12906096467361e-05 -3.10818660928265e-06 1.29977859774347e-05 8.83319513387573e-06 7.68654459207425e-05 1707 1700 0 12 17 1719 1734 0 21 14 0 0 0 0 0 3 14 0 455 0 131 114 0 0 2406 +350 379 0.989969962540331 0.000995268258826936 0.141274494191231 -0.0240557365217052 -0.0183502321147901 0.992409992849562 0.1215963612682 -0.0282514996883487 -0.140081198771386 -0.12296916497003 0.982474346849497 -0.00110168169597379 6.06078752019014e-05 1.96052168459145e-05 -1.05238540071085e-05 -6.13822947268689e-06 -3.98770207125074e-06 4.65559051624714e-06 1.96052168459145e-05 7.15468638032378e-05 -7.56172049406935e-06 2.51615086753242e-05 7.6841838614687e-06 2.80800807600294e-05 -1.05238540071085e-05 -7.56172049406935e-06 1.3929820939201e-05 4.90148538351062e-06 3.24981749185591e-06 -3.1943132274693e-06 -6.13822947268689e-06 2.51615086753242e-05 4.90148538351062e-06 5.84664272489874e-05 7.79462663550975e-06 6.20338393839807e-06 -3.98770207125074e-06 7.6841838614687e-06 3.24981749185591e-06 7.79462663550975e-06 4.40337138389499e-05 1.50708485500028e-06 4.65559051624714e-06 2.80800807600294e-05 -3.1943132274693e-06 6.20338393839807e-06 1.50708485500028e-06 8.11608886192734e-05 1873 1876 0 16 15 1833 1852 0 25 10 0 0 0 0 0 3 15 0 444 0 123 101 0 0 2394 +350 389 0.989264475289468 0.00222582075339926 0.146119278851993 -0.032338252705641 -0.0196154052487175 0.992858159998193 0.117677143073462 -0.0226077721135265 -0.144813790113999 -0.119280006065464 0.982242967063568 -0.00382195366364945 8.39368902194603e-05 6.3396568367031e-05 -1.00034222079749e-05 5.39739759561768e-06 -8.67705281651461e-06 6.24885771130917e-05 6.3396568367031e-05 0.000128183855847719 -1.08628308868623e-05 2.3387738423392e-05 -9.36438567123053e-06 9.56020807028604e-05 -1.00034222079749e-05 -1.08628308868623e-05 1.35104320191518e-05 5.47944049474579e-06 8.84281255457717e-06 -1.02207887159046e-05 5.39739759561768e-06 2.3387738423392e-05 5.47944049474579e-06 5.41108079233916e-05 -4.4449789460479e-06 1.75244702368254e-05 -8.67705281651461e-06 -9.36438567123053e-06 8.84281255457717e-06 -4.4449789460479e-06 4.126772683e-05 -9.10110820748359e-06 6.24885771130917e-05 9.56020807028604e-05 -1.02207887159046e-05 1.75244702368254e-05 -9.10110820748359e-06 0.000186368733340284 1464 1458 0 14 18 1426 1444 0 23 6 0 0 0 0 0 3 15 0 296 0 113 90 0 0 2184 +350 413 0.990856373663939 0.00208492503414736 0.134904780705318 -0.0353816702496576 -0.0184073745463133 0.992620287904508 0.119858802775117 -0.0240018991594167 -0.133659325644939 -0.121246101495985 0.98358251689432 -0.0109859490669425 8.18232102628036e-05 5.79329108389472e-05 -1.69904001912821e-05 -3.06564162640896e-07 4.74247190190095e-06 3.97451865123342e-05 5.79329108389472e-05 7.76241169947946e-05 -1.75331950977225e-05 4.06938181782154e-06 1.02100417312146e-05 4.17252409864505e-05 -1.69904001912821e-05 -1.75331950977225e-05 1.61474553991414e-05 4.3792314354376e-06 1.13056927492326e-06 -1.04321419220301e-05 -3.06564162640896e-07 4.06938181782154e-06 4.3792314354376e-06 5.0069743514857e-05 5.80296678070033e-07 6.87687281158248e-06 4.74247190190095e-06 1.02100417312146e-05 1.13056927492326e-06 5.80296678070033e-07 3.86024873660504e-05 1.55711515683319e-05 3.97451865123342e-05 4.17252409864505e-05 -1.04321419220301e-05 6.87687281158248e-06 1.55711515683319e-05 0.00011542387865899 1698 1700 0 16 9 1707 1730 0 25 2 0 0 0 0 0 1 13 0 395 0 85 87 0 0 1863 +350 384 0.98895438751702 0.00100728638751026 0.148216749340181 -0.0271766766601486 -0.0194686417553276 0.992196009662301 0.123158639154589 -0.0211350115143275 -0.14693601123972 -0.124683855347599 0.981256207530235 -0.00559521976080748 8.04924139777357e-05 6.18217366755321e-05 -1.50340391720764e-05 3.47663967384228e-06 2.87313136617715e-06 2.72630769478849e-05 6.18217366755321e-05 0.000112352703534502 -1.68666067584146e-05 1.21964413940221e-05 1.1485770533958e-05 4.75549084878856e-05 -1.50340391720764e-05 -1.68666067584146e-05 1.38899616743711e-05 1.05974837361215e-06 1.6257392968625e-06 -6.80187222041852e-06 3.47663967384228e-06 1.21964413940221e-05 1.05974837361215e-06 3.97584361004799e-05 5.10975486425998e-06 1.10152897997541e-05 2.87313136617715e-06 1.1485770533958e-05 1.6257392968625e-06 5.10975486425998e-06 3.19642301559046e-05 9.83102322993634e-06 2.72630769478849e-05 4.75549084878856e-05 -6.80187222041852e-06 1.10152897997541e-05 9.83102322993634e-06 0.0001031391875666 1911 1917 0 16 15 1872 1894 0 25 8 0 0 0 0 0 3 15 0 444 0 119 98 0 0 2440 +350 377 0.989550253292299 0.000218589990325584 0.144188239560526 -0.0243749515202035 -0.0187753398537144 0.991680123071793 0.127349990646607 -0.0265015548536822 -0.142960773719664 -0.12872639870178 0.981321421071988 -0.00124569356528941 6.89025591855587e-05 3.03497296011363e-05 -1.18314109689236e-05 -4.16776158940599e-06 2.03645581914538e-06 2.00216132395384e-05 3.03497296011363e-05 6.87957216509213e-05 -1.03086406017924e-05 1.31118661321198e-05 5.48263762866879e-06 5.16040198665384e-05 -1.18314109689236e-05 -1.03086406017924e-05 1.42820671360789e-05 3.38526572319282e-06 2.54786178809439e-06 -3.2514736937042e-06 -4.16776158940599e-06 1.31118661321198e-05 3.38526572319282e-06 5.43046617730818e-05 -2.08446507559867e-06 1.81552400829623e-05 2.03645581914538e-06 5.48263762866879e-06 2.54786178809439e-06 -2.08446507559867e-06 4.26354970909142e-05 8.20765720136847e-06 2.00216132395384e-05 5.16040198665384e-05 -3.2514736937042e-06 1.81552400829623e-05 8.20765720136847e-06 0.000107712177791566 1543 1538 0 10 21 1529 1550 0 23 6 0 0 0 0 0 2 14 0 434 0 121 97 0 0 2348 +350 407 0.990773309581861 0.00128905123554105 0.135523383100917 -0.0409389736748372 -0.018625728518148 0.991761833061361 0.126734165559008 -0.0201510854352169 -0.134243552014143 -0.128089050389493 0.982635163177537 -0.0119272328915753 6.87771198524182e-05 3.18204454955444e-05 -8.79249391437218e-06 -7.3849294624178e-07 -5.69258719585224e-06 2.39966631221954e-05 3.18204454955444e-05 0.000111414522795618 -1.92283376968167e-06 4.54368632864626e-05 -1.37941652984526e-05 6.18994319981192e-05 -8.79249391437218e-06 -1.92283376968167e-06 1.23309125467022e-05 6.85908278567913e-06 8.81964113768434e-06 -5.18002508132541e-07 -7.3849294624178e-07 4.54368632864626e-05 6.85908278567913e-06 8.51474630502155e-05 -1.43814255491903e-05 3.64726822678921e-05 -5.69258719585224e-06 -1.37941652984526e-05 8.81964113768434e-06 -1.43814255491903e-05 3.63621972505116e-05 -1.06741455164157e-05 2.39966631221954e-05 6.18994319981192e-05 -5.18002508132541e-07 3.64726822678921e-05 -1.06741455164157e-05 0.000148857580249331 1696 1695 0 10 10 1701 1722 0 24 4 0 0 0 0 0 3 16 0 284 0 92 95 0 0 1926 +350 380 0.989949799496453 0.000740453463322543 0.141417276899254 -0.0307337635936913 -0.018251195846316 0.992292469930968 0.122566504268003 -0.0280526298244858 -0.1402365441927 -0.123915720741832 0.982333245811177 -0.0100779684849158 8.76679459567544e-05 4.83737649442097e-05 -1.42826165582773e-05 -1.72245535419526e-06 -1.04367682894704e-05 9.5794562158932e-06 4.83737649442097e-05 9.40505041237079e-05 -1.12591685174557e-05 1.34546000234313e-05 -6.47906622227904e-06 3.98007161353723e-05 -1.42826165582773e-05 -1.12591685174557e-05 1.37909494697225e-05 5.44663836121801e-06 6.13411603449072e-06 -7.18743830448443e-07 -1.72245535419526e-06 1.34546000234313e-05 5.44663836121801e-06 4.56541614963416e-05 4.73215774604368e-06 2.20534646680129e-05 -1.04367682894704e-05 -6.47906622227904e-06 6.13411603449072e-06 4.73215774604368e-06 3.61881897943024e-05 7.66476851537652e-06 9.5794562158932e-06 3.98007161353723e-05 -7.18743830448443e-07 2.20534646680129e-05 7.66476851537652e-06 0.000106835284428823 1943 1946 0 13 15 1901 1921 0 25 8 0 0 0 0 0 3 15 0 446 0 125 102 0 0 2367 +351 353 0.999956553895657 0.00147043794819556 0.00920478861040709 -0.00567352759705287 -0.00137967133077324 0.999950443146034 -0.00985939952881056 -2.48296572875837e-05 -0.00921883008525573 0.00984627159335827 0.999909027915824 -0.000283081464594632 8.17181111125693e-05 5.20238476597738e-05 -2.1336525968831e-05 1.63784568543372e-05 -5.92851802709808e-06 3.99979364523646e-05 5.20238476597738e-05 7.3021769183544e-05 -1.76667369916269e-05 1.7441057371391e-05 -7.78407517851182e-07 4.13728830154581e-05 -2.1336525968831e-05 -1.76667369916269e-05 1.91412105522706e-05 -3.81839742243215e-06 1.30415166991018e-06 -1.62710074213677e-05 1.63784568543372e-05 1.7441057371391e-05 -3.81839742243215e-06 6.68021493879817e-05 -4.83482991878821e-05 3.2171679030683e-05 -5.92851802709808e-06 -7.78407517851182e-07 1.30415166991018e-06 -4.83482991878821e-05 8.83138204001305e-05 -1.15699942262236e-05 3.99979364523646e-05 4.13728830154581e-05 -1.62710074213677e-05 3.2171679030683e-05 -1.15699942262236e-05 9.36553263662971e-05 2026 1999 0 8 62 2055 2050 0 14 63 0 0 0 0 0 8 19 0 268 0 124 106 0 0 3289 +351 410 0.991092261808495 -0.000359448277221074 0.133176572189924 -0.038188837378283 -0.0171293907136792 0.991346127456777 0.130151602180802 -0.02014465060864 -0.132070861877631 -0.131273479322321 0.982509318566248 -0.012493000499241 6.59799239967132e-05 4.27364605612147e-05 -6.09924713990855e-06 7.70331119067538e-06 -7.93261233993526e-06 3.77407724540514e-05 4.27364605612147e-05 6.90657843489189e-05 -6.67832538130725e-06 1.47768482430105e-05 -6.53367452874871e-06 3.81066110538867e-05 -6.09924713990855e-06 -6.67832538130725e-06 1.19096122966816e-05 6.17988688115806e-06 5.05168350460932e-06 -3.50561330914011e-06 7.70331119067538e-06 1.47768482430105e-05 6.17988688115806e-06 5.63686566331023e-05 -7.48583379086852e-06 1.7379844162092e-05 -7.93261233993526e-06 -6.53367452874871e-06 5.05168350460932e-06 -7.48583379086852e-06 3.95031398099253e-05 -5.27939439641397e-06 3.77407724540514e-05 3.81066110538867e-05 -3.50561330914011e-06 1.7379844162092e-05 -5.27939439641397e-06 0.000107423836252851 1634 1633 0 16 9 1670 1684 0 27 10 0 0 0 0 0 4 17 0 300 0 60 66 0 0 1907 +351 354 0.99987510642567 0.00423605977792388 0.015225877571175 0.00125965277166367 -0.00402645451728947 0.999897071419055 -0.0137707745467594 -0.00129020305797582 -0.0152826442173714 0.0137077483619788 0.999789247001872 0.00751997840206201 6.10902153706172e-05 3.64264627172951e-05 -1.44745347619463e-05 8.76162454197454e-06 6.79291590734351e-06 3.15143321272022e-05 3.64264627172951e-05 8.77649397963663e-05 -1.97360435463554e-05 2.08745300994582e-05 1.31325341944489e-05 4.24056339553944e-05 -1.44745347619463e-05 -1.97360435463554e-05 1.75316622727398e-05 -1.13616988690525e-06 -5.41465694814616e-06 -1.35589689420493e-05 8.76162454197454e-06 2.08745300994582e-05 -1.13616988690525e-06 5.18223922583885e-05 -1.85603743207084e-05 2.17841856502984e-05 6.79291590734351e-06 1.31325341944489e-05 -5.41465694814616e-06 -1.85603743207084e-05 6.12037984690207e-05 6.79184194986111e-06 3.15143321272022e-05 4.24056339553944e-05 -1.35589689420493e-05 2.17841856502984e-05 6.79184194986111e-06 8.78812305803498e-05 1602 1577 0 8 65 1610 1610 0 16 62 0 0 0 0 0 8 19 0 279 0 105 82 0 0 3207 +351 409 0.990050715094516 -0.000181714915450799 0.140710868523103 -0.0360438035646129 -0.0178086990190246 0.991796022694557 0.12658396267501 -0.0221755005287971 -0.139579481945185 -0.127830420272124 0.981925125390407 -0.00357953265219657 8.54094277904923e-05 4.7769984459879e-05 -1.23654272154157e-05 -1.86581335829983e-07 -5.15114945324033e-06 2.37157902512156e-05 4.7769984459879e-05 7.33491501716067e-05 -9.75121214932918e-06 9.48922405550814e-06 -7.63503581405121e-06 3.77489618462435e-05 -1.23654272154157e-05 -9.75121214932918e-06 1.30117664065647e-05 6.69151426896662e-06 6.22793304416748e-06 -3.69356798170701e-06 -1.86581335829983e-07 9.48922405550814e-06 6.69151426896662e-06 5.54611721176234e-05 -6.50113724385247e-06 9.98814197671531e-06 -5.15114945324033e-06 -7.63503581405121e-06 6.22793304416748e-06 -6.50113724385247e-06 4.22478606733814e-05 -3.10188417309165e-06 2.37157902512156e-05 3.77489618462435e-05 -3.69356798170701e-06 9.98814197671531e-06 -3.10188417309165e-06 0.000118889263362558 1614 1613 0 12 10 1644 1661 0 23 10 0 0 0 0 0 5 16 0 284 0 74 76 0 0 1924 +351 355 0.999886694182699 0.00163341262321541 0.0149643162087572 -0.0171702593815436 -0.00153683092405986 0.999977931311547 -0.00646336140027203 0.0165141637946059 -0.0149745433020245 0.00643963143991903 0.999867138273788 -0.0107022543526405 5.41143232941271e-05 1.02957110043259e-05 -8.72945084161799e-06 4.65878838306096e-06 -7.63739087504334e-06 1.28189468876897e-05 1.02957110043259e-05 6.19011313735519e-05 -1.04531839700723e-05 1.95538606053672e-05 2.42425929013605e-06 1.39408637917414e-05 -8.72945084161799e-06 -1.04531839700723e-05 1.3732680952799e-05 -6.15737196007773e-07 -1.65293067103226e-06 -3.79240542839837e-06 4.65878838306096e-06 1.95538606053672e-05 -6.15737196007773e-07 5.9516861896648e-05 -3.52500204045792e-05 1.83124572462255e-05 -7.63739087504334e-06 2.42425929013605e-06 -1.65293067103226e-06 -3.52500204045792e-05 7.90253736317252e-05 -1.18148042199956e-05 1.28189468876897e-05 1.39408637917414e-05 -3.79240542839837e-06 1.83124572462255e-05 -1.18148042199956e-05 6.20544423395297e-05 1941 1922 0 3 36 1936 1948 0 13 28 0 0 0 0 0 9 20 0 276 0 65 55 0 0 3055 +350 390 0.986633929953281 0.00172993086161825 0.162943228162937 -0.018337208807304 -0.0212957242984077 0.99273668707245 0.118407610680324 -0.0187974596397929 -0.161554883527398 -0.120294960325157 0.979504539105776 0.0183232912492861 6.56704656722846e-05 2.12223087483076e-05 -5.10823615206649e-06 4.2188506736019e-06 -1.516717305336e-05 -2.04385378856286e-06 2.12223087483076e-05 9.12533577043516e-05 -5.83762265640359e-06 3.17048761826926e-05 1.26680863634943e-07 -5.35986500650187e-06 -5.10823615206649e-06 -5.83762265640359e-06 1.30372031766467e-05 5.41156752409346e-06 9.19447241506501e-06 2.19658307413908e-06 4.2188506736019e-06 3.17048761826926e-05 5.41156752409346e-06 5.99899790513027e-05 -4.19470942358958e-06 1.87124333936886e-05 -1.516717305336e-05 1.26680863634943e-07 9.19447241506501e-06 -4.19470942358958e-06 5.44825534810473e-05 -5.68678096559926e-06 -2.04385378856286e-06 -5.35986500650187e-06 2.19658307413908e-06 1.87124333936886e-05 -5.68678096559926e-06 7.91117957503379e-05 1430 1427 0 12 18 1381 1401 0 23 4 0 0 0 0 0 4 15 0 193 0 114 90 0 0 2092 +351 396 0.989283847089605 0.000338473353713689 0.146004641444647 -0.0287125141761302 -0.0185957958191052 0.992145464377838 0.123699530687623 -0.0242264043354897 -0.144815973792414 -0.125089020102776 0.981519776053586 0.0082857369992458 0.000194236293237266 0.000138811013242838 -2.5469697605009e-05 2.95227744544207e-05 -4.96323902182681e-05 0.000125989973819003 0.000138811013242838 0.000157128034922044 -2.14916420391539e-05 3.92508718017193e-05 -4.34954451677312e-05 0.000123434933283346 -2.5469697605009e-05 -2.14916420391539e-05 1.4843851323018e-05 2.71908290012811e-06 1.18603874247619e-05 -1.60758379854925e-05 2.95227744544207e-05 3.92508718017193e-05 2.71908290012811e-06 6.21357398254719e-05 -1.63681189642183e-05 4.90450014102819e-05 -4.96323902182681e-05 -4.34954451677312e-05 1.18603874247619e-05 -1.63681189642183e-05 6.04034958997354e-05 -4.20647557469759e-05 0.000125989973819003 0.000123434933283346 -1.60758379854925e-05 4.90450014102819e-05 -4.20647557469759e-05 0.000194917437240174 1570 1563 0 15 27 1602 1614 0 26 28 0 0 0 0 0 4 17 0 244 0 90 79 0 0 2122 +351 378 0.990880999740703 -0.000768904011161415 0.134737719809589 -0.0259837157490872 -0.0168159679535325 0.991459660459948 0.129325035868657 -0.0273469776567376 -0.133686452472386 -0.130411466011488 0.98240560969392 -0.00045646099514911 5.00342237731581e-05 2.08171808276892e-05 -7.44629458360382e-06 -2.27954137953132e-07 2.20988137422266e-07 -4.79162573764463e-06 2.08171808276892e-05 4.13165572247945e-05 -7.82340303491181e-06 2.40882663426187e-06 3.01855556511825e-06 8.24411679211434e-06 -7.44629458360382e-06 -7.82340303491181e-06 1.20988170968723e-05 4.08825404474222e-06 3.36652548075598e-06 -1.84352124859892e-07 -2.27954137953132e-07 2.40882663426187e-06 4.08825404474222e-06 4.27138480593645e-05 -7.1637058306725e-07 1.43087141341625e-05 2.20988137422266e-07 3.01855556511825e-06 3.36652548075598e-06 -7.1637058306725e-07 3.84510194200207e-05 2.99855029010642e-06 -4.79162573764463e-06 8.24411679211434e-06 -1.84352124859892e-07 1.43087141341625e-05 2.99855029010642e-06 6.52855869541901e-05 1699 1689 0 11 27 1734 1742 0 21 27 0 0 0 0 0 3 13 0 445 0 89 78 0 0 2448 +350 406 0.988689096584522 0.00104599406400386 0.149975918704635 -0.0292688990773099 -0.0198001339332266 0.992133412370651 0.123609250276803 -0.020832460481523 -0.148666825455808 -0.125180661262773 0.980932197990619 -0.00790353003647968 8.70311417660449e-05 5.03786591901364e-05 -1.29604620756994e-05 1.18986000241574e-05 -2.14246270713482e-05 4.20226775844347e-05 5.03786591901364e-05 8.13393825953899e-05 -8.91167888411102e-06 3.04037049087447e-05 -2.01401551496926e-05 3.76785607202139e-05 -1.29604620756994e-05 -8.91167888411102e-06 1.33196700093726e-05 4.52609225584891e-06 9.57747432696958e-06 -6.71420021526378e-06 1.18986000241574e-05 3.04037049087447e-05 4.52609225584891e-06 5.59868897557446e-05 -9.35562572953239e-06 3.01496615045905e-05 -2.14246270713482e-05 -2.01401551496926e-05 9.57747432696958e-06 -9.35562572953239e-06 4.11261471680626e-05 -2.94767020821442e-05 4.20226775844347e-05 3.76785607202139e-05 -6.71420021526378e-06 3.01496615045905e-05 -2.94767020821442e-05 0.000122048464860029 1814 1815 0 13 12 1766 1781 0 21 16 0 0 0 0 0 2 13 0 264 0 86 91 0 0 1968 +351 411 0.99045357740241 -0.0014984801374287 0.137838548918822 -0.0319117826112697 -0.0168038259229612 0.991170957101194 0.131520968797583 -0.0221049057278296 -0.136818648016707 -0.132581629030502 0.981683640078869 -0.0073361449670119 5.23284407650922e-05 2.13342533071833e-05 -7.553295937031e-06 -2.01822662319129e-06 -4.67957759829493e-06 1.55733094061102e-05 2.13342533071833e-05 5.13983693812373e-05 -4.78037836563756e-06 7.91071244123416e-06 4.14876091968041e-07 2.05813513649909e-05 -7.553295937031e-06 -4.78037836563756e-06 1.32695339713864e-05 5.76482067191321e-06 5.75458586664418e-06 5.85229473327317e-07 -2.01822662319129e-06 7.91071244123416e-06 5.76482067191321e-06 4.43773881186625e-05 -6.32640845331193e-06 1.16491692108647e-05 -4.67957759829493e-06 4.14876091968041e-07 5.75458586664418e-06 -6.32640845331193e-06 3.97808509644089e-05 -3.48259454888036e-06 1.55733094061102e-05 2.05813513649909e-05 5.85229473327317e-07 1.16491692108647e-05 -3.48259454888036e-06 8.36196999539643e-05 1609 1611 0 15 10 1618 1639 0 25 10 0 0 0 0 0 7 19 0 327 0 58 61 0 0 1971 +351 408 0.989375899849424 0.000349910785878864 0.145379525241982 -0.0289002326454436 -0.0179989980943088 0.992598312318205 0.12010256637829 -0.0253061813402266 -0.144261446217426 -0.121443270482528 0.982059146482412 0.000282512307377532 0.000199862846595744 0.000200883110099283 -2.50524323626827e-05 6.38366367400811e-05 -5.91466616777259e-05 0.000198854535899352 0.000200883110099283 0.000274139742824213 -2.93257655195454e-05 8.95416771088663e-05 -7.27686155345248e-05 0.000268255393310272 -2.50524323626827e-05 -2.93257655195454e-05 1.44701869069792e-05 -2.28857692058816e-06 1.4233272876903e-05 -2.72077614184563e-05 6.38366367400811e-05 8.95416771088663e-05 -2.28857692058816e-06 6.64457628056235e-05 -2.79747916892072e-05 0.000103874442735771 -5.91466616777259e-05 -7.27686155345248e-05 1.4233272876903e-05 -2.79747916892072e-05 5.68735157220112e-05 -8.35301104203128e-05 0.000198854535899352 0.000268255393310272 -2.72077614184563e-05 0.000103874442735771 -8.35301104203128e-05 0.000395819154976102 1927 1929 0 14 15 1939 1966 0 25 15 0 0 0 0 0 8 19 0 277 0 67 69 0 0 1990 +351 387 0.990939201879077 -0.000988033830008305 0.134307564821971 -0.0400368790631764 -0.0166406913705453 0.991365130977867 0.130070228999366 -0.0188280075342528 -0.13327635037758 -0.131126659647793 0.982366130095925 -0.00836797836140647 7.78377623314647e-05 3.16180063436491e-05 -1.3341188184376e-05 3.9581714968539e-06 -7.27257548317816e-06 1.61458424850043e-05 3.16180063436491e-05 4.9248471237732e-05 -9.36329226728754e-06 6.45905008730082e-06 2.33884094513086e-06 1.3067855508785e-05 -1.3341188184376e-05 -9.36329226728754e-06 1.36036442421242e-05 6.33163057092226e-07 3.34937386191954e-06 -2.43068898359677e-06 3.9581714968539e-06 6.45905008730082e-06 6.33163057092226e-07 4.32098242318159e-05 2.96886068239625e-06 1.32326803678705e-06 -7.27257548317816e-06 2.33884094513086e-06 3.34937386191954e-06 2.96886068239625e-06 4.31816425974631e-05 7.25518193575632e-06 1.61458424850043e-05 1.3067855508785e-05 -2.43068898359677e-06 1.32326803678705e-06 7.25518193575632e-06 7.2085788541911e-05 2006 2003 0 16 29 2010 2031 0 26 30 0 0 0 0 0 7 19 0 437 0 82 74 0 0 2382 +351 382 0.9904332278471 -0.0015997747761784 0.137983556618314 -0.0347192216375472 -0.0167871065713424 0.991109266854058 0.1319871744109 -0.0211364809642953 -0.136967931390294 -0.13304082785625 0.98160069472978 -0.00964549525330871 5.75621688837845e-05 2.12982430710413e-05 -1.18303666465711e-05 -8.59645322650291e-06 6.86629123144719e-06 3.66399451521842e-06 2.12982430710413e-05 4.38056311822567e-05 -8.88536212173454e-06 7.38556585544808e-06 3.05949513402e-06 2.90307350993583e-06 -1.18303666465711e-05 -8.88536212173454e-06 1.44684248705427e-05 6.40615882164804e-06 3.73937315565121e-07 -4.72202397957098e-07 -8.59645322650291e-06 7.38556585544808e-06 6.40615882164804e-06 4.81978134221937e-05 -1.10230772750346e-05 1.14297371971301e-05 6.86629123144719e-06 3.05949513402e-06 3.73937315565121e-07 -1.10230772750346e-05 4.77759868905271e-05 1.52813071775076e-06 3.66399451521842e-06 2.90307350993583e-06 -4.72202397957098e-07 1.14297371971301e-05 1.52813071775076e-06 7.00010064008937e-05 1860 1857 0 12 33 1856 1876 0 24 33 0 0 0 0 0 5 17 0 449 0 80 73 0 0 2427 +351 381 0.990263980352107 -0.000638932800559382 0.139200721916509 -0.0332428597138389 -0.0174199008135571 0.991559716049937 0.128475198239246 -0.0210418128189803 -0.138107915315694 -0.129649223953882 0.981894741026404 -0.00718806907459974 7.29288938241979e-05 3.36957563647303e-05 -1.08330046913431e-05 -5.41041590915868e-06 -9.75550239436524e-07 1.37378240391974e-05 3.36957563647303e-05 7.53960218430948e-05 -1.00456884463284e-05 1.80645160706865e-05 -1.93946656548407e-06 2.64536058768325e-05 -1.08330046913431e-05 -1.00456884463284e-05 1.40953726681736e-05 2.69393735115063e-06 3.56347590233019e-06 -5.38450907413939e-06 -5.41041590915868e-06 1.80645160706865e-05 2.69393735115063e-06 6.01711972137729e-05 -1.18009659874916e-05 1.58109795601881e-05 -9.75550239436524e-07 -1.93946656548407e-06 3.56347590233019e-06 -1.18009659874916e-05 4.4246045268574e-05 -3.5881239027857e-06 1.37378240391974e-05 2.64536058768325e-05 -5.38450907413939e-06 1.58109795601881e-05 -3.5881239027857e-06 8.13163335053895e-05 1821 1817 0 11 31 1816 1834 0 19 32 0 0 0 0 0 9 18 0 421 0 80 73 0 0 2423 +351 395 0.990279065608409 -0.00117374617572509 0.139089879350193 -0.0311427684098164 -0.0173501779748023 0.991112249372522 0.131891927228253 -0.0190408885631185 -0.138008490832915 -0.133023048618106 0.981457347516623 -0.00590995522592204 7.14486457078336e-05 2.39782630607012e-05 -6.27967081931408e-06 -3.97465022817107e-07 -6.86096080289657e-06 1.14869674319535e-05 2.39782630607012e-05 9.27334795608295e-05 -2.63495650764826e-06 1.68681385620923e-05 -3.95500603510366e-06 4.37240301776908e-05 -6.27967081931408e-06 -2.63495650764826e-06 1.32743307397525e-05 6.94386410898805e-06 5.29339153813753e-06 4.3936357645305e-07 -3.97465022817107e-07 1.68681385620923e-05 6.94386410898805e-06 4.73384537994521e-05 -2.76356578102488e-06 1.35639194675255e-05 -6.86096080289657e-06 -3.95500603510366e-06 5.29339153813753e-06 -2.76356578102488e-06 4.24112914094906e-05 4.90464374149544e-06 1.14869674319535e-05 4.37240301776908e-05 4.3936357645305e-07 1.35639194675255e-05 4.90464374149544e-06 8.86329180928332e-05 1827 1821 0 19 30 1833 1850 0 28 32 0 0 0 0 0 5 18 0 242 0 80 69 0 0 2123 +351 386 0.990462908767648 -0.000833830173524017 0.137777106526342 -0.0312606949228483 -0.0174187425184635 0.991200232382558 0.131219993651268 -0.0222643168159 -0.136674115195983 -0.132368440543829 0.9817325410637 -0.00639092349461822 7.05392453845741e-05 4.31442381704758e-05 -1.1538692809527e-05 4.57009052313006e-06 -5.72796578159481e-06 2.70325169848504e-05 4.31442381704758e-05 5.65634366510363e-05 -1.1961505422753e-05 6.57463233453241e-06 -1.7162922855308e-06 1.28329839091075e-05 -1.1538692809527e-05 -1.1961505422753e-05 1.50789019590876e-05 2.53329763598817e-06 2.5506091916597e-06 -5.77513515228333e-06 4.57009052313006e-06 6.57463233453241e-06 2.53329763598817e-06 3.62931304945064e-05 4.90278715309838e-06 2.10928193998089e-05 -5.72796578159481e-06 -1.7162922855308e-06 2.5506091916597e-06 4.90278715309838e-06 3.916583438512e-05 6.3021171171514e-07 2.70325169848504e-05 1.28329839091075e-05 -5.77513515228333e-06 2.10928193998089e-05 6.3021171171514e-07 9.77136552105191e-05 1668 1659 0 14 26 1703 1713 0 24 28 0 0 0 0 0 6 16 0 414 0 90 81 0 0 2412 +351 397 0.989623464370792 0.000381911870577632 0.143684560444311 -0.035905056881829 -0.0184936525611065 0.992017377685119 0.124737753650166 -0.0170804148469795 -0.142489942036976 -0.12610066024436 0.981730736966219 0.00432075610575532 7.82183580443587e-05 4.64409524522444e-05 -1.03931566918824e-05 4.51348617922968e-06 -4.20317269564338e-06 2.86355164240768e-05 4.64409524522444e-05 8.76050242581689e-05 -7.22396999290761e-06 1.30263801524377e-05 5.16945758262059e-06 4.55973794542496e-05 -1.03931566918824e-05 -7.22396999290761e-06 1.22894107919055e-05 5.25121282247494e-06 4.04930742612829e-06 -3.31109860522815e-06 4.51348617922968e-06 1.30263801524377e-05 5.25121282247494e-06 5.94355673760851e-05 -1.99725522172782e-05 1.7897013690165e-05 -4.20317269564338e-06 5.16945758262059e-06 4.04930742612829e-06 -1.99725522172782e-05 5.82234634562715e-05 2.88527174658979e-06 2.86355164240768e-05 4.55973794542496e-05 -3.31109860522815e-06 1.7897013690165e-05 2.88527174658979e-06 9.71526537820259e-05 1613 1609 0 10 30 1624 1636 0 21 29 0 0 0 0 0 10 19 0 242 0 81 73 0 0 2090 +351 412 0.990014506768194 -0.00131858057351556 0.140959347805675 -0.0319635682525583 -0.0175532127726438 0.991020391109142 0.132553646223866 -0.021458430338935 -0.139868370655729 -0.133704322110973 0.981101418375775 -0.00812437043869838 7.77539056514779e-05 7.13382510997253e-05 -1.44431548850959e-05 -6.62453321117874e-06 1.66047084138185e-05 6.63903382995011e-05 7.13382510997253e-05 0.000119610402879607 -1.71909008492593e-05 7.4620763681164e-06 1.53816170423952e-05 9.0116914313982e-05 -1.44431548850959e-05 -1.71909008492593e-05 1.50538545099599e-05 5.37163287134066e-06 1.56136688736042e-07 -1.44415280625643e-05 -6.62453321117874e-06 7.4620763681164e-06 5.37163287134066e-06 4.67633545455329e-05 -4.85063740801565e-06 4.40691272459837e-06 1.66047084138185e-05 1.53816170423952e-05 1.56136688736042e-07 -4.85063740801565e-06 4.26753674618143e-05 2.43466470912294e-05 6.63903382995011e-05 9.0116914313982e-05 -1.44415280625643e-05 4.40691272459837e-06 2.43466470912294e-05 0.000177629958069856 1420 1419 0 11 9 1428 1445 0 24 11 0 0 0 0 0 4 15 0 347 0 57 60 0 0 1953 +351 380 0.990334271573824 -0.000322482167442853 0.138700852742857 -0.0325222548375606 -0.0171217500800926 0.992064699995049 0.124557122228834 -0.0272621080745547 -0.137640387316146 -0.125727988248383 0.982470150564624 -0.00754561692881049 9.61434620112239e-05 3.90138235924426e-05 -1.53960955029081e-05 -2.48754300625793e-06 -1.96855297396998e-06 2.79092310169499e-05 3.90138235924426e-05 5.8944306273399e-05 -1.17801853701276e-05 -3.87939996943974e-06 1.15631496335377e-05 1.8752942342804e-05 -1.53960955029081e-05 -1.17801853701276e-05 1.3713035148455e-05 3.8253698461773e-06 3.50825859688338e-06 -5.67996852037868e-06 -2.48754300625793e-06 -3.87939996943974e-06 3.8253698461773e-06 3.67086558327316e-05 6.35086418175971e-07 9.85178375558459e-06 -1.96855297396998e-06 1.15631496335377e-05 3.50825859688338e-06 6.35086418175971e-07 4.18696757691529e-05 5.93016173132025e-06 2.79092310169499e-05 1.8752942342804e-05 -5.67996852037868e-06 9.85178375558459e-06 5.93016173132025e-06 8.87495731541875e-05 1999 1997 0 19 26 2006 2027 0 27 27 0 0 0 0 0 9 22 0 439 0 80 76 0 0 2368 +351 383 0.990576578987832 -0.00112918172681611 0.136955343486083 -0.0369189802258306 -0.0169877746126408 0.991231192199979 0.131042508841666 -0.0203181370762674 -0.135902379208287 -0.132134206617499 0.981871221070814 -0.0101247824204914 8.97765231609912e-05 1.32399279496177e-05 -1.54490194751583e-05 -8.86242921378039e-06 -1.42298057971398e-06 2.6244756244388e-05 1.32399279496177e-05 5.00942622866951e-05 -6.82086679883331e-06 1.45619516158997e-05 5.50038504073275e-06 1.56485070805681e-05 -1.54490194751583e-05 -6.82086679883331e-06 1.40088601464369e-05 4.65577444839543e-06 2.17570091612793e-06 -5.70769318331737e-06 -8.86242921378039e-06 1.45619516158997e-05 4.65577444839543e-06 5.5125345651206e-05 -2.17715686768852e-06 1.81339643175271e-05 -1.42298057971398e-06 5.50038504073275e-06 2.17570091612793e-06 -2.17715686768852e-06 4.10234208100119e-05 -1.19912872762944e-05 2.6244756244388e-05 1.56485070805681e-05 -5.70769318331737e-06 1.81339643175271e-05 -1.19912872762944e-05 0.000105380259881256 1959 1952 0 16 29 1961 1979 0 26 30 0 0 0 0 0 6 18 0 418 0 81 75 0 0 2403 +351 385 0.9906793675937 -0.00148937598662646 0.136206359555333 -0.0454235938410886 -0.0168111262602989 0.990958765532428 0.133109395041473 -0.0128378973329191 -0.135173135859188 -0.134158513608407 0.981697365061339 -0.0174478318737194 5.37579009504792e-05 1.97136719996705e-05 -7.14359119059062e-06 -1.88122451623659e-06 -2.51060813753076e-06 5.87316971075045e-06 1.97136719996705e-05 4.77582927558936e-05 -6.13904756212364e-06 3.21137963041393e-06 7.87752296232247e-06 -6.07393237789656e-06 -7.14359119059062e-06 -6.13904756212364e-06 1.26492767908374e-05 4.82180750924719e-06 2.04454532119411e-06 -1.44018075923346e-06 -1.88122451623659e-06 3.21137963041393e-06 4.82180750924719e-06 6.58781092732399e-05 -2.84371004347757e-05 -6.00506758229645e-06 -2.51060813753076e-06 7.87752296232247e-06 2.04454532119411e-06 -2.84371004347757e-05 6.16944485777868e-05 4.42737027215744e-06 5.87316971075045e-06 -6.07393237789656e-06 -1.44018075923346e-06 -6.00506758229645e-06 4.42737027215744e-06 7.6033699544724e-05 1696 1692 0 11 31 1685 1705 0 19 32 0 0 0 0 0 8 19 0 435 0 82 76 0 0 2366 +351 389 0.990517751967837 -0.000811508207948926 0.137382402406609 -0.0363896773924878 -0.0172522953143652 0.991331913536277 0.130243600652349 -0.0210329820102808 -0.136297253614916 -0.131378760303677 0.981917858070674 -0.00984210023547587 4.55847199984979e-05 1.10015719593715e-05 -3.52174112793888e-06 -1.39022663851725e-05 2.38052382636078e-07 -1.00596233209494e-06 1.10015719593715e-05 4.64538319879804e-05 9.27844437129803e-08 9.06383764920921e-06 -1.2716620138682e-07 -1.84400088126837e-06 -3.52174112793888e-06 9.27844437129803e-08 1.2082908852807e-05 9.46727449401833e-06 4.62176540924788e-06 -3.91611706255558e-08 -1.39022663851725e-05 9.06383764920921e-06 9.46727449401833e-06 6.04724834530894e-05 -1.83456153275322e-05 4.63459511271862e-06 2.38052382636078e-07 -1.2716620138682e-07 4.62176540924788e-06 -1.83456153275322e-05 5.57179142144172e-05 -6.52821391953722e-06 -1.00596233209494e-06 -1.84400088126837e-06 -3.91611706255558e-08 4.63459511271862e-06 -6.52821391953722e-06 7.23435526991835e-05 1475 1466 0 11 26 1479 1488 0 23 26 0 0 0 0 0 4 16 0 303 0 82 75 0 0 2225 +351 388 0.989889861323105 -0.00114059263440435 0.141833569715235 -0.0303314841324024 -0.0173568299696868 0.991478281817035 0.129110639137692 -0.0231789805203252 -0.140772166649262 -0.130267093824888 0.981434501820315 -0.00977813752144611 9.33101344636192e-05 3.95569922694519e-05 -1.37328026127161e-05 1.24826783281967e-06 -2.22741977771655e-05 1.85134000134056e-05 3.95569922694519e-05 7.3425543653958e-05 -7.13887086266968e-06 1.43333394123335e-05 -1.51243443551845e-05 2.91166549530509e-05 -1.37328026127161e-05 -7.13887086266968e-06 1.4217071821258e-05 5.26909162992432e-06 1.12671034157104e-05 -1.5012491107376e-06 1.24826783281967e-06 1.43333394123335e-05 5.26909162992432e-06 5.14344129645162e-05 -1.13637190136388e-05 2.1499730415439e-05 -2.22741977771655e-05 -1.51243443551845e-05 1.12671034157104e-05 -1.13637190136388e-05 5.09080173855533e-05 -1.83415109109648e-05 1.85134000134056e-05 2.91166549530509e-05 -1.5012491107376e-06 2.1499730415439e-05 -1.83415109109648e-05 0.000101766629564455 1739 1741 0 14 30 1733 1759 0 24 31 0 0 0 0 0 6 17 0 434 0 78 71 0 0 2284 +351 413 0.990308068001095 0.000148593562521197 0.138888114581098 -0.0370526582263189 -0.0178928008235099 0.991802775929118 0.126519173795856 -0.0193551973761115 -0.137730817650333 -0.127778055937821 0.982192949623505 -0.00624697287056167 0.00015943250411624 0.00013117916211267 -2.39690369549152e-05 1.01401653168875e-05 -1.19526931838914e-05 0.000112328574669669 0.00013117916211267 0.000184829774182755 -2.43084298446859e-05 3.46194444044135e-05 -1.98989649319403e-05 0.000149414129397508 -2.39690369549152e-05 -2.43084298446859e-05 1.55144318904701e-05 4.39126786187859e-06 5.13263605546665e-06 -1.74387496323092e-05 1.01401653168875e-05 3.46194444044135e-05 4.39126786187859e-06 4.81302239535029e-05 -4.94862078146747e-06 4.21124736687439e-05 -1.19526931838914e-05 -1.98989649319403e-05 5.13263605546665e-06 -4.94862078146747e-06 4.2567277687397e-05 -2.21804594701104e-05 0.000112328574669669 0.000149414129397508 -1.74387496323092e-05 4.21124736687439e-05 -2.21804594701104e-05 0.000229630324751286 1689 1691 0 15 11 1721 1744 0 25 11 0 0 0 0 0 7 19 0 382 0 73 74 0 0 1890 +351 379 0.990823783249518 -0.0014305903280182 0.13515244710484 -0.0316185054967546 -0.0165898187807922 0.991095781198525 0.132113324094531 -0.0212402163131976 -0.134138020187916 -0.133143178202263 0.981977538255467 -0.00571649855853662 4.40433649690582e-05 2.83796902276261e-05 -7.20854873123696e-06 4.77056707904505e-06 1.26877382778034e-06 6.07295060555663e-06 2.83796902276261e-05 7.50516485998303e-05 -9.48380718439102e-06 2.79882987067722e-05 4.77874589682656e-06 4.25328271549085e-05 -7.20854873123696e-06 -9.48380718439102e-06 1.23752851750417e-05 3.69491464783258e-06 1.53745425892991e-06 -1.48453032239238e-06 4.77056707904505e-06 2.79882987067722e-05 3.69491464783258e-06 6.23448105467426e-05 -5.9657040253902e-06 2.90426192528313e-05 1.26877382778034e-06 4.77874589682656e-06 1.53745425892991e-06 -5.9657040253902e-06 4.02064340866799e-05 -1.6653708616343e-06 6.07295060555663e-06 4.25328271549085e-05 -1.48453032239238e-06 2.90426192528313e-05 -1.6653708616343e-06 0.000103683053317618 1950 1945 0 13 28 1952 1972 0 24 28 0 0 0 0 0 4 16 0 435 0 80 75 0 0 2394 +351 384 0.990253834264002 -0.0010696838541836 0.139270239110495 -0.0305179083480864 -0.0170480968378231 0.99151979656205 0.128832664413025 -0.0231031288722662 -0.138227009371 -0.129951332436428 0.981838044220301 -0.00734076992226915 5.88223389591985e-05 3.23880826667224e-05 -1.19361368914314e-05 4.15782431425475e-06 -2.73457694251965e-07 2.0495704166363e-05 3.23880826667224e-05 5.34200430381189e-05 -1.15034868315057e-05 1.44929162501079e-05 5.7671896292333e-07 2.64277233166243e-05 -1.19361368914314e-05 -1.15034868315057e-05 1.40535377796264e-05 7.54169152882458e-07 3.65759101642178e-07 -4.94915499259188e-06 4.15782431425475e-06 1.44929162501079e-05 7.54169152882458e-07 4.51435003125472e-05 1.41231718561125e-06 2.23512748749806e-05 -2.73457694251965e-07 5.7671896292333e-07 3.65759101642178e-07 1.41231718561125e-06 3.87043541731118e-05 -8.37861644907554e-06 2.0495704166363e-05 2.64277233166243e-05 -4.94915499259188e-06 2.23512748749806e-05 -8.37861644907554e-06 9.2953817484396e-05 2003 1997 0 13 28 2006 2024 0 24 29 0 0 0 0 0 5 17 0 449 0 79 74 0 0 2446 +351 377 0.990136924521946 -0.00106599217030279 0.140099016266764 -0.0224501122921221 -0.0172219064656893 0.991461418344561 0.1292581211061 -0.0292204706847129 -0.13904055752157 -0.13039601065556 0.9816642011244 0.00169812867326175 6.13779761787151e-05 1.53609414685558e-05 -7.4499077345126e-06 -5.20796645738386e-06 -6.57673233255486e-06 4.43493551865073e-06 1.53609414685558e-05 5.55759474266178e-05 -5.64852607660084e-06 2.21793196820392e-05 -8.75617119996858e-06 9.78108573622152e-06 -7.4499077345126e-06 -5.64852607660084e-06 1.2794753373579e-05 7.45108251789907e-06 2.14520618361514e-06 1.41891703133976e-06 -5.20796645738386e-06 2.21793196820392e-05 7.45108251789907e-06 6.85813261838711e-05 -2.08450628853636e-05 1.61833848895244e-05 -6.57673233255486e-06 -8.75617119996858e-06 2.14520618361514e-06 -2.08450628853636e-05 5.62089318603556e-05 -8.6933405603916e-07 4.43493551865073e-06 9.78108573622152e-06 1.41891703133976e-06 1.61833848895244e-05 -8.6933405603916e-07 6.53412556417482e-05 1514 1507 0 16 27 1522 1533 0 27 27 0 0 0 0 0 4 16 0 419 0 81 69 0 0 2369 +351 398 0.987548424719352 0.00160269340022583 0.157307152438122 -0.0139398752045381 -0.0192765750659863 0.993645543539139 0.11089160229041 -0.0388072923888422 -0.156129825747841 -0.112543170288889 0.981303985691118 0.0122117031232781 7.91989189095048e-05 4.79444893134015e-05 -1.49463056048735e-05 1.38915265173876e-06 -4.94680765392393e-06 3.70454152549582e-05 4.79444893134015e-05 8.3137956052275e-05 -1.47989777433165e-05 1.100569199145e-05 1.42837399767634e-07 3.59821843865478e-05 -1.49463056048735e-05 -1.47989777433165e-05 1.52052353756207e-05 5.72505664003953e-06 4.22078044802213e-06 -7.80940528923248e-06 1.38915265173876e-06 1.100569199145e-05 5.72505664003953e-06 4.78067441826256e-05 -1.15923149303437e-05 1.62372950765486e-05 -4.94680765392393e-06 1.42837399767634e-07 4.22078044802213e-06 -1.15923149303437e-05 5.52605973031388e-05 -6.81582303200166e-06 3.70454152549582e-05 3.59821843865478e-05 -7.80940528923248e-06 1.62372950765486e-05 -6.81582303200166e-06 0.000117614338078599 1726 1722 0 18 26 1728 1750 0 29 27 0 0 0 0 0 3 14 0 248 0 73 65 0 0 2077 +352 354 0.999997078770712 0.000548983948859947 0.00235394703983764 -0.00272476394789887 -0.000549108188396686 0.999999847881148 5.21332785097248e-05 -0.000521063373793146 -0.00235391806142482 -5.34256978110917e-05 0.999997228103886 -0.000279548104367134 5.92363147259255e-05 2.86000022422698e-05 -1.07268715072347e-05 8.68131794405891e-06 7.18706947583847e-06 3.1473352794071e-05 2.86000022422698e-05 6.60937805947282e-05 -1.64322572072157e-05 1.71241626801873e-05 1.06773189467387e-05 2.70300230827503e-05 -1.07268715072347e-05 -1.64322572072157e-05 1.60697023591308e-05 1.16355995626915e-06 -1.77597099874715e-06 -1.00813808913768e-05 8.68131794405891e-06 1.71241626801873e-05 1.16355995626915e-06 3.78395493891518e-05 -7.15432631813726e-06 1.36569704625213e-05 7.18706947583847e-06 1.06773189467387e-05 -1.77597099874715e-06 -7.15432631813726e-06 4.13087690081468e-05 7.11355044672033e-06 3.1473352794071e-05 2.70300230827503e-05 -1.00813808913768e-05 1.36569704625213e-05 7.11355044672033e-06 6.1078570253472e-05 1880 1858 0 9 46 1855 1859 0 17 9 0 0 0 0 0 7 14 0 297 0 56 34 0 0 3310 +352 355 0.99986432803171 0.00123450612500581 0.0164256361923498 -0.00879755692189059 -0.00117823947426319 0.99999340701424 -0.00343477507167644 0.0121027238441286 -0.0164297681492283 0.00341495573603012 0.999859190484282 0.0049561950717245 7.00737181768582e-05 2.91213811839445e-06 -8.22953621948524e-06 -1.7253318685084e-05 5.81167954772789e-06 2.98208836048988e-06 2.91213811839445e-06 0.000182961235893575 -1.86224739323778e-05 7.16486852337973e-05 1.09793128642454e-05 7.5973954051146e-05 -8.22953621948524e-06 -1.86224739323778e-05 1.54312327843161e-05 2.78260504534011e-07 -2.36857744732152e-06 -1.08438800800337e-05 -1.7253318685084e-05 7.16486852337973e-05 2.78260504534011e-07 0.000114857756314086 -5.24462480257247e-05 5.60768910275803e-05 5.81167954772789e-06 1.09793128642454e-05 -2.36857744732152e-06 -5.24462480257247e-05 9.13176730573071e-05 -8.00290783917282e-06 2.98208836048988e-06 7.5973954051146e-05 -1.08438800800337e-05 5.60768910275803e-05 -8.00290783917282e-06 0.000102842711093723 1760 1754 0 4 27 1741 1757 0 15 44 0 0 0 0 0 9 20 0 271 0 38 29 0 0 3161 +352 382 0.989867817171248 -0.0028372358194961 0.141963567937461 -0.0286459550047711 -0.0170061831128258 0.990234679476077 0.138369322101553 -0.0183781915196422 -0.140969834590818 -0.139381597263824 0.980153190108374 -0.000812966791914864 9.2373555851468e-05 6.57066970969337e-05 -1.30075933954191e-05 3.27394258849526e-06 -6.10568528420922e-06 5.24400596079811e-05 6.57066970969337e-05 9.59087284426836e-05 -1.27451070097961e-05 1.65925889028586e-05 -9.66624131945006e-06 4.90313472624821e-05 -1.30075933954191e-05 -1.27451070097961e-05 1.4196034275909e-05 5.11900199653957e-06 4.02800307767156e-06 -5.69803949808825e-06 3.27394258849526e-06 1.65925889028586e-05 5.11900199653957e-06 6.46942997853651e-05 -1.53135850059548e-05 1.77201575891479e-05 -6.10568528420922e-06 -9.66624131945006e-06 4.02800307767156e-06 -1.53135850059548e-05 5.86944819534911e-05 3.27059378331054e-07 5.24400596079811e-05 4.90313472624821e-05 -5.69803949808825e-06 1.77201575891479e-05 3.27059378331054e-07 0.000105767189254045 1479 1475 0 17 23 1456 1466 0 23 0 0 0 0 0 0 4 16 0 431 0 97 79 0 0 2560 +352 386 0.989804407798143 -0.00317621083402111 0.142397844043034 -0.0259342371758155 -0.0168865986128855 0.99008337291275 0.139462387291342 -0.0185907436432198 -0.141428699671084 -0.140445100898717 0.979935251199229 0.00341384077032414 0.000102582963390203 4.40273779190255e-05 -1.93285737023272e-05 3.19140896623707e-06 -2.23177169468796e-05 4.27577454874684e-05 4.40273779190255e-05 7.92101699581495e-05 -1.4826468050132e-05 1.93633040221716e-05 3.17486735942816e-06 2.98562572560912e-05 -1.93285737023272e-05 -1.4826468050132e-05 1.58499711346568e-05 1.31740464669949e-06 7.65760163015827e-06 -6.81660224520365e-06 3.19140896623707e-06 1.93633040221716e-05 1.31740464669949e-06 4.95988942876012e-05 -7.28573059043835e-07 1.42354455872151e-05 -2.23177169468796e-05 3.17486735942816e-06 7.65760163015827e-06 -7.28573059043835e-07 6.05630766754395e-05 -5.20657243224535e-06 4.27577454874684e-05 2.98562572560912e-05 -6.81660224520365e-06 1.42354455872151e-05 -5.20657243224535e-06 0.000113021938897922 1394 1391 0 18 17 1367 1373 0 24 3 0 0 0 0 0 4 16 0 398 0 87 65 0 0 2533 +352 396 0.988202943000132 -0.00264103785485666 0.15312729464379 -0.0102050933030191 -0.0173973599190327 0.991443350798295 0.129373158057215 -0.0355578819603923 -0.152158717508149 -0.130510946195707 0.979701289990667 0.0189611331244629 0.000166366815050328 0.000159204714889069 -2.00687392671599e-05 2.58872651399794e-05 -4.16082340781614e-05 0.000126844414629663 0.000159204714889069 0.000250481503673179 -2.12149102883615e-05 5.32191477552189e-05 -4.84789382906715e-05 0.000185335301437499 -2.00687392671599e-05 -2.12149102883615e-05 1.46869834142482e-05 4.48854112603232e-06 1.11458723777888e-05 -1.55739679082176e-05 2.58872651399794e-05 5.32191477552189e-05 4.48854112603232e-06 6.13316391202889e-05 -1.12538499930597e-05 6.30401548246257e-05 -4.16082340781614e-05 -4.84789382906715e-05 1.11458723777888e-05 -1.12538499930597e-05 5.75150184697219e-05 -4.41225838702061e-05 0.000126844414629663 0.000185335301437499 -1.55739679082176e-05 6.30401548246257e-05 -4.41225838702061e-05 0.00022543235968099 1557 1564 0 21 14 1541 1556 0 27 8 0 0 0 0 0 1 14 0 227 0 89 73 0 0 2278 +351 407 0.990171024911405 -9.72137928410899e-05 0.139861831731807 -0.0379756744912564 -0.0179488882581431 0.991642574452743 0.127760877983177 -0.0191561998198351 -0.138705367005731 -0.129015483885517 0.981893999412152 -0.00314187734164935 8.41811524299016e-05 4.73939175031756e-05 -1.11103766853587e-05 -9.49515109953685e-06 9.04346547257218e-07 3.46589366728813e-05 4.73939175031756e-05 8.03668262642513e-05 -1.03161218588068e-05 3.69521202084618e-07 3.06728993653283e-06 3.69856620807716e-05 -1.11103766853587e-05 -1.03161218588068e-05 1.33951062964612e-05 8.95003569009103e-06 6.50597507534793e-06 -6.88789247235087e-06 -9.49515109953685e-06 3.69521202084618e-07 8.95003569009103e-06 5.90525609318944e-05 -7.67097531061586e-06 1.84851045599956e-06 9.04346547257218e-07 3.06728993653283e-06 6.50597507534793e-06 -7.67097531061586e-06 3.57638811771947e-05 -2.16862609504583e-06 3.46589366728813e-05 3.69856620807716e-05 -6.88789247235087e-06 1.84851045599956e-06 -2.16862609504583e-06 0.000112215086846375 1522 1521 0 14 15 1557 1579 0 29 17 0 0 0 0 0 7 18 0 269 0 78 81 0 0 1949 +352 378 0.991047702656961 -0.00269848352469908 0.133480969598765 -0.0266819224677484 -0.0158389932580358 0.990358437917661 0.137620095690502 -0.0210665544287683 -0.132565370104456 -0.138502283851054 0.98144971344288 0.00771651223459249 7.33853218628121e-05 4.81036619677134e-05 -1.24993763704573e-05 -4.99949023031664e-08 3.79469923106293e-06 2.35010815312316e-05 4.81036619677134e-05 7.35801298024694e-05 -1.26482647357199e-05 7.6566096767468e-06 1.09879553386496e-05 5.07689730890669e-05 -1.24993763704573e-05 -1.26482647357199e-05 1.43634681598145e-05 2.56023935320377e-06 1.10440941686613e-06 -4.00759182405591e-06 -4.99949023031664e-08 7.6566096767468e-06 2.56023935320377e-06 5.1057636354188e-05 -7.40029620594879e-06 9.55482976697349e-06 3.79469923106293e-06 1.09879553386496e-05 1.10440941686613e-06 -7.40029620594879e-06 5.11398442189972e-05 1.73054830127074e-05 2.35010815312316e-05 5.07689730890669e-05 -4.00759182405591e-06 9.55482976697349e-06 1.73054830127074e-05 0.000103440259351713 1370 1365 0 18 22 1336 1343 0 22 2 0 0 0 0 0 3 14 0 430 0 90 67 0 0 2551 +352 383 0.990639308610223 -0.00339083110027131 0.136463410849606 -0.0269021079728467 -0.0155912661840507 0.990338643449076 0.137790724325779 -0.0252355826296939 -0.135612214254605 -0.138628545241931 0.981015521686109 -0.00535861642013128 0.000107365246100105 6.64354720550956e-05 -1.78034069513092e-05 1.16074227151356e-06 -5.60043851286451e-06 4.91619445669696e-05 6.64354720550956e-05 8.24251178131421e-05 -1.59585068479006e-05 9.15368449669952e-06 -4.33648827982346e-06 4.20110982962189e-05 -1.78034069513092e-05 -1.59585068479006e-05 1.45010586366688e-05 3.45432757841365e-06 2.98957533387484e-06 -9.35419928143183e-06 1.16074227151356e-06 9.15368449669952e-06 3.45432757841365e-06 4.62522298004625e-05 -4.97292283675016e-06 1.32892806916474e-05 -5.60043851286451e-06 -4.33648827982346e-06 2.98957533387484e-06 -4.97292283675016e-06 3.93191374709557e-05 -6.23073167120203e-06 4.91619445669696e-05 4.20110982962189e-05 -9.35419928143183e-06 1.32892806916474e-05 -6.23073167120203e-06 0.000108166556873123 1688 1683 0 17 21 1646 1649 0 24 0 0 0 0 0 0 3 16 0 404 0 90 73 0 0 2515 +351 390 0.988967330792813 -0.000712818819092444 0.148132071186056 -0.0263991792839336 -0.0180405944057179 0.991965345047781 0.125216976395873 -0.0213482279135434 -0.147031138123963 -0.12650788953092 0.981008459855676 0.00992917929677182 0.000126439743351494 5.55078726106538e-05 -1.86526402948427e-05 3.56315979276592e-07 -2.78878876403517e-05 4.96825554768153e-05 5.55078726106538e-05 8.11298518183511e-05 -1.07965407420434e-05 1.18625201558611e-05 -1.04515909142751e-05 3.39792408381735e-05 -1.86526402948427e-05 -1.07965407420434e-05 1.57331369691669e-05 7.18391769324269e-06 1.01188899711067e-05 -6.71213641962416e-06 3.56315979276592e-07 1.18625201558611e-05 7.18391769324269e-06 5.52827868798353e-05 -8.2128281811477e-06 1.9421653696695e-05 -2.78878876403517e-05 -1.04515909142751e-05 1.01188899711067e-05 -8.2128281811477e-06 6.1246852304986e-05 -5.33762190491645e-06 4.96825554768153e-05 3.39792408381735e-05 -6.71213641962416e-06 1.9421653696695e-05 -5.33762190491645e-06 0.00012826197525069 1512 1506 0 13 29 1520 1532 0 23 31 0 0 0 0 0 6 17 0 205 0 78 69 0 0 2123 +352 410 0.991359264393424 -0.00326174570011082 0.13113416761591 -0.0346208285005305 -0.0155480637821236 0.989721677923066 0.142159269700495 -0.0145481676773703 -0.13025001579254 -0.142969791439097 0.981119040749849 -0.00169194183562824 9.80106205097377e-05 5.75920231539693e-05 -1.12466840406221e-05 -2.14307720189595e-06 -1.43955393507102e-05 4.3477452113681e-05 5.75920231539693e-05 7.7117935368371e-05 -8.93354498142697e-06 7.37445198254954e-06 -7.94092146611868e-06 3.8752060730298e-05 -1.12466840406221e-05 -8.93354498142697e-06 1.26076871573583e-05 8.23430456882332e-06 6.08289507556576e-06 -2.61561344857789e-06 -2.14307720189595e-06 7.37445198254954e-06 8.23430456882332e-06 4.92421652560429e-05 -8.58533123251646e-06 1.37746449291027e-05 -1.43955393507102e-05 -7.94092146611868e-06 6.08289507556576e-06 -8.58533123251646e-06 5.71284504990326e-05 -9.66293577696072e-06 4.3477452113681e-05 3.8752060730298e-05 -2.61561344857789e-06 1.37746449291027e-05 -9.66293577696072e-06 8.78771670620729e-05 1406 1410 0 19 10 1386 1399 0 25 5 0 0 0 0 0 4 17 0 284 0 38 38 0 0 2038 +352 380 0.990621470703019 -0.00256965075346469 0.136610756081627 -0.0321739715109241 -0.0158580622631826 0.990904092599553 0.133632335647903 -0.0189770058646227 -0.135711545726388 -0.134545442748768 0.981570119854966 -0.00245126615717527 7.53731905947907e-05 4.90982184277061e-05 -8.80436871936423e-06 8.95141186650595e-07 6.86234948091224e-06 1.76870903372681e-05 4.90982184277061e-05 8.09294501770989e-05 -9.9790080937966e-06 1.84812447362056e-06 -7.48426741972205e-07 1.12053134524335e-05 -8.80436871936423e-06 -9.9790080937966e-06 1.30941034199521e-05 3.52040927527087e-06 3.67234527164104e-06 -4.14855919374424e-06 8.95141186650595e-07 1.84812447362056e-06 3.52040927527087e-06 4.26620066398316e-05 -4.15301823932913e-06 4.33080453784802e-06 6.86234948091224e-06 -7.48426741972205e-07 3.67234527164104e-06 -4.15301823932913e-06 3.57762808697743e-05 9.53706078646101e-06 1.76870903372681e-05 1.12053134524335e-05 -4.14855919374424e-06 4.33080453784802e-06 9.53706078646101e-06 8.05519384644073e-05 1570 1569 0 16 18 1532 1538 0 21 0 0 0 0 0 0 5 18 0 426 0 94 75 0 0 2548 +352 395 0.987764945982713 -0.00136518082940869 0.155944053330259 -0.0127314974293557 -0.0183980736825852 0.991958510366616 0.125219106353683 -0.0271539862310974 -0.154860977565486 -0.12655611400698 0.979796727711883 0.0151616187875533 0.000164248480470245 0.000133479397313267 -1.97808624878081e-05 1.83453272823429e-05 -2.61815074624991e-05 0.000118012201620859 0.000133479397313267 0.000184781263330209 -2.14329227317707e-05 3.30679621286535e-05 -2.01422095524797e-05 0.000136819008198961 -1.97808624878081e-05 -2.14329227317707e-05 1.50810744966089e-05 2.19659518644709e-06 9.23122367822842e-06 -2.10815622313282e-05 1.83453272823429e-05 3.30679621286535e-05 2.19659518644709e-06 4.67950766500564e-05 -3.41090092156494e-06 4.57370427569108e-05 -2.61815074624991e-05 -2.01422095524797e-05 9.23122367822842e-06 -3.41090092156494e-06 4.82887647636946e-05 -3.07798959520237e-05 0.000118012201620859 0.000136819008198961 -2.10815622313282e-05 4.57370427569108e-05 -3.07798959520237e-05 0.000229179326767159 1584 1582 0 26 19 1558 1566 0 30 5 0 0 0 0 0 3 16 0 219 0 83 71 0 0 2255 +352 356 0.999944261903661 -0.002897015582258 0.010152851159132 -0.0182882882327013 0.00293573667515692 0.999988466901195 -0.00380098865701629 0.00798202759991411 -0.010141722541929 0.00383058289464961 0.999941234322582 -0.00822007666951971 9.64490834234161e-05 4.34987559030091e-05 -2.5863372106157e-05 1.52691676384257e-05 -1.24052005176735e-06 5.17955011112028e-05 4.34987559030091e-05 0.000150172615674719 -2.46255939637433e-05 8.84586203293586e-05 -2.83886348243103e-05 6.68596225923726e-05 -2.5863372106157e-05 -2.46255939637433e-05 2.03015519389825e-05 -1.00334844558414e-05 2.22159642577828e-06 -1.74480719096507e-05 1.52691676384257e-05 8.84586203293586e-05 -1.00334844558414e-05 0.000105830838054975 -5.17056990919673e-05 4.9399235905073e-05 -1.24052005176735e-06 -2.83886348243103e-05 2.22159642577828e-06 -5.17056990919673e-05 7.92736786076037e-05 -1.88801242245046e-05 5.17955011112028e-05 6.68596225923726e-05 -1.74480719096507e-05 4.9399235905073e-05 -1.88801242245046e-05 0.000109677522916546 1848 1840 0 3 16 1852 1861 0 10 22 0 0 0 0 0 10 24 0 286 0 18 13 0 0 3123 +352 412 0.99168101759916 -0.00391938879842168 0.128660008257971 -0.028818679435912 -0.0145987586665045 0.989662351865453 0.142672020892456 -0.0230506482446092 -0.127889153484146 -0.143363411272148 0.981372149966322 -0.00306883651906883 0.000152161339700745 0.000130111999054647 -2.69929270632242e-05 3.6086663535137e-05 -2.29926308269789e-05 0.000125426455112562 0.000130111999054647 0.000156746058528707 -2.63269763668409e-05 5.43887689008917e-05 -2.67195452831424e-05 0.000139830983980476 -2.69929270632242e-05 -2.63269763668409e-05 1.61390450377707e-05 3.67242553191409e-07 7.67847862349236e-06 -2.1266778295242e-05 3.6086663535137e-05 5.43887689008917e-05 3.67242553191409e-07 7.70781472650729e-05 -2.83885004466057e-05 6.24167465377168e-05 -2.29926308269789e-05 -2.67195452831424e-05 7.67847862349236e-06 -2.83885004466057e-05 6.0687650582192e-05 -2.35934695504529e-05 0.000125426455112562 0.000139830983980476 -2.1266778295242e-05 6.24167465377168e-05 -2.35934695504529e-05 0.000205655573243099 1649 1654 0 20 10 1630 1643 0 25 4 0 0 0 0 0 2 14 0 343 0 39 41 0 0 2004 +352 397 0.988730037501031 -0.00182703450447273 0.149698279509587 -0.0179087369922551 -0.0177179193544434 0.991470112629174 0.12912432418736 -0.0287056775129397 -0.148657284641421 -0.130321439939914 0.980263910390986 0.0143196843070003 9.4838222724727e-05 7.37071683156923e-05 -1.10404075427957e-05 1.33938228294454e-05 -7.50164785472641e-06 5.18749117247212e-05 7.37071683156923e-05 0.000123532941382711 -1.130626157742e-05 2.66943766718234e-05 -6.7434928631221e-06 7.22632612024979e-05 -1.10404075427957e-05 -1.130626157742e-05 1.39227219262318e-05 3.69416896328014e-06 5.65286830776266e-06 -5.2152592281339e-06 1.33938228294454e-05 2.66943766718234e-05 3.69416896328014e-06 5.66384273097489e-05 -1.26620253578972e-05 1.75257693346172e-05 -7.50164785472641e-06 -6.7434928631221e-06 5.65286830776266e-06 -1.26620253578972e-05 4.63860350574758e-05 -5.03423800645178e-06 5.18749117247212e-05 7.22632612024979e-05 -5.2152592281339e-06 1.75257693346172e-05 -5.03423800645178e-06 0.000108244143568542 1376 1380 0 22 18 1346 1363 0 27 0 0 0 0 0 0 3 15 0 231 0 81 65 0 0 2228 +352 411 0.990182179425758 -0.00315811766238202 0.139747192603237 -0.0259832757774147 -0.0164424393540395 0.990172705815465 0.13888001600723 -0.0159347830118978 -0.138812455261567 -0.139814301667999 0.980399440694121 0.0014263402992729 6.29889987426099e-05 3.25672383498461e-05 -1.14193802579835e-05 -2.52362668932148e-08 3.30051950598054e-06 2.3792150009085e-05 3.25672383498461e-05 5.71292812775795e-05 -8.47661620790165e-06 2.13290610520102e-05 -9.40457494564077e-06 1.77782057574761e-05 -1.14193802579835e-05 -8.47661620790165e-06 1.3134988553083e-05 8.28897622646007e-06 2.72645643587925e-06 -3.08519891655942e-06 -2.52362668932148e-08 2.13290610520102e-05 8.28897622646007e-06 6.61937171705856e-05 -1.86771112588518e-05 1.60298411879368e-05 3.30051950598054e-06 -9.40457494564077e-06 2.72645643587925e-06 -1.86771112588518e-05 5.45099439894262e-05 -4.71201130384563e-06 2.3792150009085e-05 1.77782057574761e-05 -3.08519891655942e-06 1.60298411879368e-05 -4.71201130384563e-06 7.79264267722153e-05 1454 1462 0 16 10 1444 1460 0 24 5 0 0 0 0 0 4 16 0 313 0 35 38 0 0 2041 +352 387 0.99003574286331 -0.00269262946146021 0.140790545135945 -0.0310160988544431 -0.0168696670469168 0.990348713096784 0.137567586303135 -0.0144914889099178 -0.1398021537274 -0.138571917119334 0.980435200102002 -0.00154495190664357 8.12244833247205e-05 3.65146544646263e-05 -1.27169599709075e-05 8.26374881711628e-07 4.09328972629548e-06 2.29858677756499e-05 3.65146544646263e-05 6.63226690073759e-05 -9.10709431069837e-06 1.1585802316489e-05 -5.47904186313747e-06 2.0199880547946e-05 -1.27169599709075e-05 -9.10709431069837e-06 1.51458894601792e-05 3.11657134344552e-06 7.98805380634727e-07 -4.33360496211746e-06 8.26374881711628e-07 1.1585802316489e-05 3.11657134344552e-06 6.01871808319684e-05 -5.97242171806723e-06 1.48108690307742e-05 4.09328972629548e-06 -5.47904186313747e-06 7.98805380634727e-07 -5.97242171806723e-06 4.60083765736638e-05 1.35551347629593e-06 2.29858677756499e-05 2.0199880547946e-05 -4.33360496211746e-06 1.48108690307742e-05 1.35551347629593e-06 8.59170973900076e-05 1505 1500 0 14 19 1466 1473 0 23 0 0 0 0 0 0 4 17 0 415 0 92 74 0 0 2527 +352 381 0.990358762824452 -0.00229246111940198 0.138507276050169 -0.0300400671989452 -0.0168178068530896 0.990477345290132 0.136644757819923 -0.0185173721869526 -0.137501571880011 -0.137656721917345 0.980889364118858 -0.000283862100309689 6.65631358029804e-05 3.18161062086999e-05 -7.04146820052107e-06 7.33439757571808e-06 -7.95325336906688e-06 1.76433213980697e-05 3.18161062086999e-05 6.26698480745462e-05 -7.71703489354538e-06 1.69664463773218e-05 -1.74845102439073e-06 1.3490982934007e-05 -7.04146820052107e-06 -7.71703489354538e-06 1.34539680183331e-05 5.15259144150392e-06 1.75162970828656e-06 -1.76903391542834e-06 7.33439757571808e-06 1.69664463773218e-05 5.15259144150392e-06 5.39996130428415e-05 -1.28134374149694e-05 9.73022821705516e-06 -7.95325336906688e-06 -1.74845102439073e-06 1.75162970828656e-06 -1.28134374149694e-05 5.29920349153033e-05 1.70113449373728e-06 1.76433213980697e-05 1.3490982934007e-05 -1.76903391542834e-06 9.73022821705516e-06 1.70113449373728e-06 7.89600211187238e-05 1510 1504 0 13 21 1490 1498 0 21 0 0 0 0 0 0 5 15 0 416 0 96 80 0 0 2557 +352 409 0.990542279405699 -0.00312820467171376 0.137172180289206 -0.0301738426153076 -0.0160822341555416 0.990201907536779 0.138713892797693 -0.0215130764308138 -0.136262080030832 -0.139608010680102 0.980786546043335 0.00327819231303729 0.000116690361013435 7.16826212461722e-05 -1.25919259800053e-05 6.75840842161246e-06 -2.66664664869288e-05 6.39711904432923e-05 7.16826212461722e-05 0.000110178337873681 -8.89799235295925e-06 3.37314306055247e-05 -3.0801710300998e-05 7.54287644206617e-05 -1.25919259800053e-05 -8.89799235295925e-06 1.21663078596728e-05 6.28663584486632e-06 7.75347914083455e-06 -5.72844027895759e-06 6.75840842161246e-06 3.37314306055247e-05 6.28663584486632e-06 6.56091590192736e-05 -1.82545553261557e-05 3.23085709807451e-05 -2.66664664869288e-05 -3.0801710300998e-05 7.75347914083455e-06 -1.82545553261557e-05 5.37425215744152e-05 -2.97762073736634e-05 6.39711904432923e-05 7.54287644206617e-05 -5.72844027895759e-06 3.23085709807451e-05 -2.97762073736634e-05 0.000134838698480355 1301 1301 0 17 11 1280 1286 0 22 3 0 0 0 0 0 3 14 0 280 0 45 49 0 0 2031 +352 385 0.990611227909409 -0.00273821026698698 0.136681737420717 -0.0261605356663825 -0.016316837322933 0.990284382787792 0.13809635051796 -0.0267705491986967 -0.13573192682486 -0.139030009030914 0.980942149481444 -0.00420472081751729 7.64173114058515e-05 3.23304249334011e-05 -1.28225724407911e-05 -1.50244006015611e-06 3.070511812655e-06 2.51075011212614e-05 3.23304249334011e-05 6.18544753731571e-05 -1.16838685403382e-05 6.33448320862433e-06 6.24539352602553e-06 2.15425535577839e-05 -1.28225724407911e-05 -1.16838685403382e-05 1.37806374731057e-05 3.43285018612586e-06 2.97874880949297e-06 -6.61118445830093e-06 -1.50244006015611e-06 6.33448320862433e-06 3.43285018612586e-06 4.19758340661211e-05 4.39990125389548e-06 3.24715930915232e-06 3.070511812655e-06 6.24539352602553e-06 2.97874880949297e-06 4.39990125389548e-06 3.30914397496713e-05 5.81464398330424e-06 2.51075011212614e-05 2.15425535577839e-05 -6.61118445830093e-06 3.24715930915232e-06 5.81464398330424e-06 8.60460284522112e-05 1650 1643 0 17 23 1622 1628 0 21 0 0 0 0 0 0 1 12 0 416 0 101 84 0 0 2531 +352 408 0.989993174707018 -0.00328341267700838 0.141077047157613 -0.0188018119242823 -0.0164047086169697 0.990273241556481 0.138165815571043 -0.0272784923025648 -0.140158480188361 -0.139097542244324 0.980309886807675 -0.00142261769409984 6.01691542089789e-05 4.21466682541574e-05 -6.18792989040571e-06 3.57007258217145e-06 -6.45491647431012e-06 1.90433898966341e-05 4.21466682541574e-05 6.31672549916207e-05 -6.03105629804355e-06 1.07905109591311e-05 -4.04711172885423e-06 2.49605354047775e-05 -6.18792989040571e-06 -6.03105629804355e-06 1.1809775238229e-05 6.54432274527164e-06 7.55319948565419e-06 -2.33912484388665e-06 3.57007258217145e-06 1.07905109591311e-05 6.54432274527164e-06 4.75082279142227e-05 -5.64921639281737e-06 2.25915067436171e-05 -6.45491647431012e-06 -4.04711172885423e-06 7.55319948565419e-06 -5.64921639281737e-06 4.61118318592214e-05 -1.08821504698936e-05 1.90433898966341e-05 2.49605354047775e-05 -2.33912484388665e-06 2.25915067436171e-05 -1.08821504698936e-05 9.62210647546781e-05 1521 1525 0 18 15 1492 1500 0 24 3 0 0 0 0 0 4 16 0 278 0 44 50 0 0 2107 +352 379 0.990516564316655 -0.0024078476819015 0.137372260969493 -0.0203570138375374 -0.0160431052478983 0.990979756147941 0.133047892425893 -0.0301664413594532 -0.136453488736399 -0.133990018936143 0.981543234013234 0.00087728613470032 9.43456717922304e-05 6.23050408394481e-05 -1.03122764900196e-05 1.30694509302551e-05 -1.76625101296975e-05 3.73410118216226e-05 6.23050408394481e-05 7.65401721367546e-05 -1.29314562006261e-05 2.2298226327189e-05 -1.52076337263219e-05 3.50579032490002e-05 -1.03122764900196e-05 -1.29314562006261e-05 1.37534937995636e-05 2.67792964148863e-06 2.93253622336592e-06 -3.88323138886663e-06 1.30694509302551e-05 2.2298226327189e-05 2.67792964148863e-06 6.01280763114706e-05 -1.55639016374156e-05 1.92739477664253e-05 -1.76625101296975e-05 -1.52076337263219e-05 2.93253622336592e-06 -1.55639016374156e-05 5.39103602469575e-05 -1.69136147913991e-05 3.73410118216226e-05 3.50579032490002e-05 -3.88323138886663e-06 1.92739477664253e-05 -1.69136147913991e-05 8.98324815993858e-05 1708 1707 0 21 19 1671 1680 0 29 0 0 0 0 0 0 2 14 0 415 0 94 77 0 0 2552 +352 384 0.989899170177637 -0.00294598802041056 0.141742562542832 -0.0261942076458789 -0.0168438385542485 0.990258962073005 0.138215314407823 -0.0178705534609034 -0.140769023525715 -0.139206713877882 0.980206903070438 -0.00330894480753222 6.41233287614281e-05 3.47107593242936e-05 -8.7781172039235e-06 -1.12246019048728e-05 2.27452307683563e-06 -2.250093013547e-06 3.47107593242936e-05 6.30674214110164e-05 -8.18432933893565e-06 4.24299100397214e-06 6.29564214857528e-07 -3.82894005247395e-07 -8.7781172039235e-06 -8.18432933893565e-06 1.29422698419182e-05 5.35060009943777e-06 2.79404766598988e-06 -4.46101129652067e-07 -1.12246019048728e-05 4.24299100397214e-06 5.35060009943777e-06 4.8489126038234e-05 2.8049854434441e-06 3.99542500759602e-06 2.27452307683563e-06 6.29564214857528e-07 2.79404766598988e-06 2.8049854434441e-06 3.62482652598397e-05 4.48058951646981e-06 -2.250093013547e-06 -3.82894005247395e-07 -4.46101129652067e-07 3.99542500759602e-06 4.48058951646981e-06 6.15600706479806e-05 1527 1526 0 22 20 1490 1500 0 32 0 0 0 0 0 0 2 14 0 421 0 89 72 0 0 2598 +352 389 0.990919000888011 -0.00198870722799574 0.13444544887302 -0.0277869873510482 -0.0160979180015051 0.990944134156035 0.133306339000675 -0.0255723861994596 -0.133493036204602 -0.134260076066221 0.981913357307848 0.000454473979189549 8.23534412129776e-05 1.67852464175934e-05 -1.05558780982093e-05 -1.94608170481251e-05 -5.56533268130555e-06 8.01751955841809e-06 1.67852464175934e-05 5.44485692059677e-05 -4.07540033025518e-06 9.22683164466287e-06 -5.70318843925868e-06 2.35371804801021e-05 -1.05558780982093e-05 -4.07540033025518e-06 1.25197758705779e-05 1.01494898575149e-05 6.24276925021428e-06 5.58017842217465e-07 -1.94608170481251e-05 9.22683164466287e-06 1.01494898575149e-05 4.94792840492053e-05 -3.59492040932436e-06 1.56413908987987e-05 -5.56533268130555e-06 -5.70318843925868e-06 6.24276925021428e-06 -3.59492040932436e-06 4.01792652021706e-05 -1.25168873585355e-05 8.01751955841809e-06 2.35371804801021e-05 5.58017842217465e-07 1.56413908987987e-05 -1.25168873585355e-05 9.26629896653183e-05 1622 1619 0 12 22 1603 1620 0 22 6 0 0 0 0 0 1 13 0 293 0 84 61 0 0 2346 +352 388 0.989603053273188 -0.00240648603908882 0.143805444185289 -0.0198650862235423 -0.0168729984423086 0.99101313380934 0.132696158727211 -0.0289376628722564 -0.142832415354325 -0.133742952869805 0.980669018416364 0.00303995987837092 0.000116493107474059 9.56603199714457e-05 -1.26914338778343e-05 1.28195681937265e-05 -2.24828265146936e-05 7.80594851964354e-05 9.56603199714457e-05 0.000131514553966704 -1.22792010205653e-05 2.55405139165188e-05 -2.53346476403083e-05 0.000109444112643996 -1.26914338778343e-05 -1.22792010205653e-05 1.26309587720741e-05 4.68829902275929e-06 8.19675283688381e-06 -7.90211511072103e-06 1.28195681937265e-05 2.55405139165188e-05 4.68829902275929e-06 5.17552961125984e-05 -1.02044288043209e-05 3.41415890809953e-05 -2.24828265146936e-05 -2.53346476403083e-05 8.19675283688381e-06 -1.02044288043209e-05 4.43935520757848e-05 -2.70803388224745e-05 7.80594851964354e-05 0.000109444112643996 -7.90211511072103e-06 3.41415890809953e-05 -2.70803388224745e-05 0.000177225144064947 1562 1562 0 24 20 1527 1536 0 27 1 0 0 0 0 0 4 15 0 418 0 109 92 0 0 2458 +352 413 0.99184732039664 -0.00265575165196487 0.127404238568299 -0.0289335411765139 -0.0149774151748134 0.990423855417069 0.137245268244371 -0.029661591919136 -0.126548686507155 -0.138034537721366 0.982309470757237 -0.00905737337519844 0.000164354009889003 9.27234035852149e-05 -3.00125247565862e-05 1.79607845433092e-05 -1.96163815460281e-06 6.91776099105566e-05 9.27234035852149e-05 0.000102633278256833 -2.13169491573628e-05 3.28599365165189e-05 2.862935439793e-06 6.70588589433265e-05 -3.00125247565862e-05 -2.13169491573628e-05 1.79394588140205e-05 9.70320954387431e-07 5.02373904758677e-07 -1.41638114279995e-05 1.79607845433092e-05 3.28599365165189e-05 9.70320954387431e-07 6.98739469596609e-05 -8.80516678359697e-06 3.78006115995909e-05 -1.96163815460281e-06 2.862935439793e-06 5.02373904758677e-07 -8.80516678359697e-06 6.05141295628677e-05 -5.61379518409704e-06 6.91776099105566e-05 6.70588589433265e-05 -1.41638114279995e-05 3.78006115995909e-05 -5.61379518409704e-06 0.000156163986576414 1309 1310 0 21 10 1289 1303 0 29 5 0 0 0 0 0 3 17 0 372 0 43 46 0 0 2014 +352 394 0.989562497412907 -0.00378176344706339 0.144054718698005 -0.0162184351963136 -0.016260478315571 0.990340829094479 0.137697636411847 -0.0301993162055585 -0.143184009438484 -0.138602815605206 0.979942650846175 0.00769007085585875 9.26615691420372e-05 4.9028766681418e-05 -1.01131846565704e-05 9.39342936768231e-06 -3.02329895167722e-05 3.11608953314466e-05 4.9028766681418e-05 8.64796509287253e-05 -6.77027585044304e-06 2.3142261375757e-05 -1.74828995578441e-05 3.57651768197754e-05 -1.01131846565704e-05 -6.77027585044304e-06 1.35901096672173e-05 6.95852473593451e-06 1.11252610606394e-05 -3.02688583482102e-06 9.39342936768231e-06 2.3142261375757e-05 6.95852473593451e-06 6.89508836446939e-05 -1.91386276245186e-05 3.2345247768555e-05 -3.02329895167722e-05 -1.74828995578441e-05 1.11252610606394e-05 -1.91386276245186e-05 7.49580663053433e-05 -1.44749299027065e-05 3.11608953314466e-05 3.57651768197754e-05 -3.02688583482102e-06 3.2345247768555e-05 -1.44749299027065e-05 9.15047089718737e-05 1344 1347 0 19 19 1318 1331 0 23 4 0 0 0 0 0 2 11 0 228 0 88 69 0 0 2235 +353 357 0.999778361457782 0.00141086582796625 0.0210056520586035 -0.0111782227041349 -0.00128564767564096 0.999981332171553 -0.00597347624585158 -0.00385001551051188 -0.0210136877022039 0.00594514642554001 0.999761511643218 -0.0022845979345524 4.97206994601034e-05 3.10937457633723e-05 -1.35089351320617e-05 4.04057381678135e-06 1.58045281891803e-05 2.16308666619761e-05 3.10937457633723e-05 5.27284076827147e-05 -1.58458186023517e-05 1.11438369944189e-05 1.19216581753345e-05 2.59302640726922e-05 -1.35089351320617e-05 -1.58458186023517e-05 1.66264482107342e-05 2.66902016604721e-07 -4.42337875668389e-06 -8.94990507381215e-06 4.04057381678135e-06 1.11438369944189e-05 2.66902016604721e-07 3.66443537022505e-05 -6.01512662905266e-06 4.9702053255358e-06 1.58045281891803e-05 1.19216581753345e-05 -4.42337875668389e-06 -6.01512662905266e-06 4.16119327198353e-05 1.07275415000488e-05 2.16308666619761e-05 2.59302640726922e-05 -8.94990507381215e-06 4.9702053255358e-06 1.07275415000488e-05 6.10800987168058e-05 2105 2076 0 3 58 2118 2124 0 13 19 0 0 0 0 0 6 15 0 318 0 104 75 0 0 3255 +353 382 0.990669332906754 -0.00225439697973367 0.136268817167926 -0.0234364038044686 -0.0166133276530094 0.990409111727762 0.137163365192454 -0.0259338254986839 -0.135271098843698 -0.138147418002952 0.981130480984429 -0.0012759870796697 0.000114122500482504 5.63875557180087e-05 -1.83869636921415e-05 4.94030060986243e-07 -5.07650137120702e-06 4.4225663333005e-05 5.63875557180087e-05 7.11323556888195e-05 -1.23773839858806e-05 1.74743889819863e-05 -4.83638923552891e-06 3.49461863807587e-05 -1.83869636921415e-05 -1.23773839858806e-05 1.39061061151471e-05 4.3009129242053e-06 3.93156606155317e-06 -6.01477647901092e-06 4.94030060986243e-07 1.74743889819863e-05 4.3009129242053e-06 6.05497617152863e-05 -1.18276527528822e-05 1.84230055740334e-05 -5.07650137120702e-06 -4.83638923552891e-06 3.93156606155317e-06 -1.18276527528822e-05 4.54616109533286e-05 -1.51933440790512e-05 4.4225663333005e-05 3.49461863807587e-05 -6.01477647901092e-06 1.84230055740334e-05 -1.51933440790512e-05 0.000107722721038971 1777 1778 0 18 22 1788 1813 0 25 8 0 0 0 0 0 0 12 0 427 0 137 121 0 0 2599 +353 381 0.990990916280079 -0.00135538404716926 0.133922241559997 -0.0281908341846674 -0.0167781971755156 0.990814634855087 0.134182157742827 -0.022098058205516 -0.132873985226262 -0.135220273225083 0.981865561957962 -0.00265050784146101 8.57554170314692e-05 3.80517546106462e-05 -1.59977729444969e-05 3.65468932275746e-06 -1.81093708222984e-06 1.90680310103593e-05 3.80517546106462e-05 5.45449326025988e-05 -1.09979261573927e-05 1.27096055425456e-05 -4.63577687576685e-06 2.12691410711335e-05 -1.59977729444969e-05 -1.09979261573927e-05 1.36742414928269e-05 2.88901591543541e-06 4.1427583637316e-06 -3.55920673732404e-06 3.65468932275746e-06 1.27096055425456e-05 2.88901591543541e-06 5.0128913914546e-05 -1.04762900387371e-05 8.04060915518414e-06 -1.81093708222984e-06 -4.63577687576685e-06 4.1427583637316e-06 -1.04762900387371e-05 3.7977086234508e-05 -3.44398660115123e-06 1.90680310103593e-05 2.12691410711335e-05 -3.55920673732404e-06 8.04060915518414e-06 -3.44398660115123e-06 8.41320498442935e-05 1713 1708 0 11 20 1725 1749 0 19 7 0 0 0 0 0 3 11 0 426 0 131 116 0 0 2563 +353 387 0.990938950839051 -0.00177036114878576 0.134301383207337 -0.0295216385796582 -0.0165876893122838 0.990645251865005 0.13545048364845 -0.0233332240424262 -0.133284823867086 -0.13645090977609 0.981639600336089 -0.0092535608433163 8.32883373562918e-05 3.37936105605514e-05 -1.43644959703045e-05 4.76523997776309e-06 -7.16171769664059e-07 3.0038645427938e-05 3.37936105605514e-05 5.38388896216679e-05 -9.57531792933561e-06 4.15004529578592e-06 9.01587756544866e-06 1.88289217127122e-05 -1.43644959703045e-05 -9.57531792933561e-06 1.4234150505311e-05 1.07883013572144e-06 1.94159394361156e-06 -5.50906519374618e-06 4.76523997776309e-06 4.15004529578592e-06 1.07883013572144e-06 4.70602477838958e-05 -1.30891712860612e-06 9.22010081931365e-06 -7.16171769664059e-07 9.01587756544866e-06 1.94159394361156e-06 -1.30891712860612e-06 4.79483973018496e-05 8.28226067988923e-06 3.0038645427938e-05 1.88289217127122e-05 -5.50906519374618e-06 9.22010081931365e-06 8.28226067988923e-06 9.93700897844369e-05 1782 1779 0 16 20 1777 1789 0 22 8 0 0 0 0 0 3 15 0 421 0 132 114 0 0 2537 +352 398 0.989945009823662 -0.00211162011127267 0.141436977434249 -0.0182711708428315 -0.0166615301107015 0.991187349764493 0.131415490263557 -0.0344655634316485 -0.140468042413927 -0.132450665258225 0.981185787877634 0.000440316868032601 0.000214823865784398 0.000184569414569294 -3.10727398616663e-05 3.62168053498541e-05 -4.71447283785785e-05 0.000157262761765098 0.000184569414569294 0.000209950141462527 -2.99384427864786e-05 3.50696028054992e-05 -3.61887658268362e-05 0.000167339284891018 -3.10727398616663e-05 -2.99384427864786e-05 1.57069027447206e-05 3.09832195409325e-07 1.26136886712701e-05 -2.20347891803548e-05 3.62168053498541e-05 3.50696028054992e-05 3.09832195409325e-07 4.64849869947168e-05 -1.74367183563418e-05 4.21043996657619e-05 -4.71447283785785e-05 -3.61887658268362e-05 1.26136886712701e-05 -1.74367183563418e-05 5.78967372291101e-05 -4.16160669677447e-05 0.000157262761765098 0.000167339284891018 -2.20347891803548e-05 4.21043996657619e-05 -4.16160669677447e-05 0.000216324593204547 1667 1663 0 20 20 1627 1632 0 25 1 0 0 0 0 0 0 12 0 251 0 110 101 0 0 2217 +353 409 0.992484055311133 -0.00256892129809943 0.122347049807223 -0.0343712490764765 -0.0151467996849521 0.989512889600932 0.143648236233228 -0.0238671650536248 -0.121433003802388 -0.14442175029052 0.982036854517462 -0.0128849338660116 0.000109016385854725 5.73681815638939e-05 -1.13660408642351e-05 1.30846604706963e-05 -1.6726313715917e-05 6.04698504788991e-05 5.73681815638939e-05 8.90867367776415e-05 -6.42058424277548e-06 2.30388557461423e-05 -8.03824010458896e-06 6.68972259635372e-05 -1.13660408642351e-05 -6.42058424277548e-06 1.17286104218882e-05 3.22314705010609e-06 8.43231729467522e-06 -5.43504255737323e-06 1.30846604706963e-05 2.30388557461423e-05 3.22314705010609e-06 6.43722504856227e-05 -9.80222600349461e-06 2.78504746904674e-05 -1.6726313715917e-05 -8.03824010458896e-06 8.43231729467522e-06 -9.80222600349461e-06 4.3623778083295e-05 -1.39132720749438e-05 6.04698504788991e-05 6.68972259635372e-05 -5.43504255737323e-06 2.78504746904674e-05 -1.39132720749438e-05 0.000122589625428245 1546 1546 0 14 10 1524 1532 0 21 4 0 0 0 0 0 3 12 0 281 0 70 74 0 0 2043 +352 390 0.989002259961901 -0.0023867644168783 0.147881145335946 -0.014411482997586 -0.0175597778587805 0.990902727504769 0.133429527561027 -0.0268600045346775 -0.146854295108462 -0.134558864365106 0.979963125851667 0.0171440044571618 8.3420706556493e-05 4.11407299680304e-05 -8.46222082533522e-06 3.79970277982639e-06 -1.60708784872214e-05 2.67476626546159e-05 4.11407299680304e-05 9.66176789408774e-05 -9.89977508860762e-06 2.2361795864948e-05 -1.57322317080753e-05 3.90258256491877e-05 -8.46222082533522e-06 -9.89977508860762e-06 1.33262650608294e-05 5.04544182436062e-06 7.30645884928814e-06 -6.14515351076483e-06 3.79970277982639e-06 2.2361795864948e-05 5.04544182436062e-06 5.80377067254189e-05 -4.89047502306718e-06 2.67537024292281e-05 -1.60708784872214e-05 -1.57322317080753e-05 7.30645884928814e-06 -4.89047502306718e-06 6.57997804459088e-05 -5.82373704203951e-06 2.67476626546159e-05 3.90258256491877e-05 -6.14515351076483e-06 2.67537024292281e-05 -5.82373704203951e-06 0.000106703096688023 1619 1620 0 21 22 1594 1613 0 26 1 0 0 0 0 0 2 13 0 191 0 84 60 0 0 2237 +353 410 0.990354167677905 -0.0017581021221498 0.138547939861739 -0.0257476925834263 -0.0170468777414318 0.990777104637666 0.134425194383615 -0.0216560009855311 -0.137506459929243 -0.135490361290876 0.981190264665827 0.00434429751194219 7.90912518631069e-05 4.62185054386264e-05 -8.14019719283905e-06 4.93504199048928e-06 -3.93462059839672e-06 3.09016309668442e-05 4.62185054386264e-05 6.53587578358219e-05 -5.46786668159987e-06 5.82416699561635e-06 -3.03142360824591e-06 3.15262604238263e-05 -8.14019719283905e-06 -5.46786668159987e-06 1.22793551330084e-05 4.21274562525314e-06 5.93897035607894e-06 -2.86544616299788e-06 4.93504199048928e-06 5.82416699561635e-06 4.21274562525314e-06 4.29370250780863e-05 -7.355001012059e-06 1.39458126186552e-05 -3.93462059839672e-06 -3.03142360824591e-06 5.93897035607894e-06 -7.355001012059e-06 3.58524778504363e-05 -1.11964298336454e-05 3.09016309668442e-05 3.15262604238263e-05 -2.86544616299788e-06 1.39458126186552e-05 -1.11964298336454e-05 8.25123276229373e-05 1534 1538 0 18 9 1508 1520 0 25 3 0 0 0 0 0 1 14 0 290 0 58 60 0 0 2090 +353 383 0.990266412379608 -0.0017895822446006 0.139173380745779 -0.0210347969888692 -0.0167902919359063 0.991079161525535 0.132212638149871 -0.0302806014045621 -0.138168442885946 -0.133262496544345 0.981402358059752 -0.00554094774195956 8.50976358138507e-05 5.82061656991027e-05 -1.21492031268678e-05 6.82225862923083e-06 3.2190892660088e-06 3.84778765091069e-05 5.82061656991027e-05 0.000107639694319171 -1.19230582383609e-05 2.0816018994923e-05 3.90275465209773e-06 5.00999481955829e-05 -1.21492031268678e-05 -1.19230582383609e-05 1.2990160730963e-05 2.1367473405353e-06 -4.09772097595382e-07 -6.48584770160835e-06 6.82225862923083e-06 2.0816018994923e-05 2.1367473405353e-06 4.68861019945432e-05 -3.06941082844262e-06 2.29210941446056e-05 3.2190892660088e-06 3.90275465209773e-06 -4.09772097595382e-07 -3.06941082844262e-06 4.32978365587515e-05 -2.82666367130127e-06 3.84778765091069e-05 5.00999481955829e-05 -6.48584770160835e-06 2.29210941446056e-05 -2.82666367130127e-06 0.000115384502707517 1652 1649 0 17 19 1632 1640 0 24 8 0 0 0 0 0 0 13 0 415 0 128 109 0 0 2545 +353 355 0.999929613268318 0.00219594113766564 0.0116596034062719 -0.00552093208665839 -0.00212659560383937 0.999979998206234 -0.0059565744012626 0.00775162552864342 -0.0116724504800565 0.00593135987611219 0.999914282761183 0.0010913511515585 5.7958664587703e-05 1.14605410857071e-05 -1.05304630802175e-05 1.15290542880714e-05 -1.32082507737243e-05 2.03235101954313e-05 1.14605410857071e-05 4.23077670316416e-05 -7.39542512954818e-06 1.50730172016253e-05 -4.72106217571278e-06 9.72052934050149e-06 -1.05304630802175e-05 -7.39542512954818e-06 1.38159103433601e-05 -8.76567247217688e-08 2.62573092893479e-06 -5.8402378153306e-06 1.15290542880714e-05 1.50730172016253e-05 -8.76567247217688e-08 5.23735200934198e-05 -3.10600000412611e-05 2.39208265752517e-05 -1.32082507737243e-05 -4.72106217571278e-06 2.62573092893479e-06 -3.10600000412611e-05 5.92992581484434e-05 -1.39150008827471e-05 2.03235101954313e-05 9.72052934050149e-06 -5.8402378153306e-06 2.39208265752517e-05 -1.39150008827471e-05 7.43399894621527e-05 1739 1722 0 1 40 1795 1812 0 12 34 0 0 0 0 0 5 17 0 271 0 56 39 0 0 3263 +353 356 0.999727697111997 -0.00128292816013626 0.0232999082075407 -0.00592678677891074 0.00135218689518273 0.999994713922348 -0.00295697784274398 0.00154623057302654 -0.0232959914522733 0.00298767847967483 0.999724147232404 -0.00611407772047689 5.06801544102065e-05 1.07295588678132e-05 -1.26662894689776e-05 7.59052796415022e-06 3.36765047920553e-06 2.1889974972711e-05 1.07295588678132e-05 0.000103668850059376 -1.32797266029933e-05 5.51477077104547e-05 -7.28623346918291e-06 1.7349068796267e-05 -1.26662894689776e-05 -1.32797266029933e-05 1.76724616288713e-05 -5.58991813771895e-06 2.25665266837448e-06 -9.10703184674852e-06 7.59052796415022e-06 5.51477077104547e-05 -5.58991813771895e-06 7.62306024356493e-05 -2.78122615161815e-05 2.97392595585019e-05 3.36765047920553e-06 -7.28623346918291e-06 2.25665266837448e-06 -2.78122615161815e-05 5.40827822625891e-05 -1.17626707876983e-05 2.1889974972711e-05 1.7349068796267e-05 -9.10703184674852e-06 2.97392595585019e-05 -1.17626707876983e-05 8.72569151798022e-05 1882 1868 0 4 34 1874 1883 0 12 18 0 0 0 0 0 9 23 0 289 0 55 43 0 0 3235 +353 380 0.990173305595785 -0.00126960831853179 0.139839954877832 -0.0236937356568736 -0.0172813071653877 0.991183593375816 0.131363772194854 -0.0268976644606286 -0.138773849511254 -0.132489517763948 0.981421594613907 -0.00223832234845861 0.000125340918121416 9.41365814636208e-05 -2.08221593342347e-05 1.33886768744581e-05 -7.89607955264052e-06 7.55970778319406e-05 9.41365814636208e-05 0.000107527880901966 -1.82967282664719e-05 2.19044736072091e-05 -1.34942008515123e-05 6.92894730709002e-05 -2.08221593342347e-05 -1.82967282664719e-05 1.50447319453412e-05 6.07735414005424e-07 2.60048425930103e-06 -1.30110859937665e-05 1.33886768744581e-05 2.19044736072091e-05 6.07735414005424e-07 4.96553549083842e-05 -1.30527029176347e-05 2.60148216799234e-05 -7.89607955264052e-06 -1.34942008515123e-05 2.60048425930103e-06 -1.30527029176347e-05 4.51813511888289e-05 -1.71001577476524e-05 7.55970778319406e-05 6.92894730709002e-05 -1.30110859937665e-05 2.60148216799234e-05 -1.71001577476524e-05 0.000142995749069352 1801 1801 0 17 18 1778 1787 0 23 7 0 0 0 0 0 1 13 0 422 0 129 110 0 0 2533 +353 411 0.991501685490086 -0.00269318755040149 0.130065961769929 -0.0245585552947524 -0.0156695981615845 0.990034521105386 0.139950386612838 -0.0260829966986052 -0.129146704811903 -0.140799125567053 0.981578695202672 -0.00165166942444745 0.000154465262757585 0.000134874013234602 -2.28871071152285e-05 1.84663865387447e-05 -2.41191251970528e-05 0.000136220012222418 0.000134874013234602 0.000163004211081417 -2.21184040574319e-05 3.72105614363011e-05 -2.97052421423403e-05 0.000151067851859656 -2.28871071152285e-05 -2.21184040574319e-05 1.37909977805109e-05 4.18593031528156e-06 8.3977092000853e-06 -1.74883442745896e-05 1.84663865387447e-05 3.72105614363011e-05 4.18593031528156e-06 6.42804519185978e-05 -2.11353694493554e-05 5.14407361329752e-05 -2.41191251970528e-05 -2.97052421423403e-05 8.3977092000853e-06 -2.11353694493554e-05 5.74861546559765e-05 -3.70683365680626e-05 0.000136220012222418 0.000151067851859656 -1.74883442745896e-05 5.14407361329752e-05 -3.70683365680626e-05 0.000234322950091859 1588 1594 0 13 10 1559 1574 0 22 4 0 0 0 0 0 3 14 0 326 0 51 54 0 0 2071 +353 386 0.991029885915111 -0.00278941136253691 0.133611318410279 -0.0238619662358939 -0.0161505186282519 0.989954628726191 0.140459936678145 -0.0242877371717036 -0.132660943653816 -0.141357887108716 0.98102957232748 -0.00173671798391983 9.34025428864853e-05 4.59717196093434e-05 -1.4473552224634e-05 -1.07444772751968e-05 3.40701339443415e-06 2.73773475047876e-05 4.59717196093434e-05 7.07749220953197e-05 -1.03476343955496e-05 9.63766231456331e-06 1.20180485791393e-06 2.82190531283898e-05 -1.4473552224634e-05 -1.03476343955496e-05 1.38872049690303e-05 5.76954833713652e-06 2.83291025735032e-06 -3.52455141557409e-06 -1.07444772751968e-05 9.63766231456331e-06 5.76954833713652e-06 4.04630363291229e-05 2.68398655535164e-06 9.76205981883374e-06 3.40701339443415e-06 1.20180485791393e-06 2.83291025735032e-06 2.68398655535164e-06 3.4000631325607e-05 3.91848312423641e-06 2.73773475047876e-05 2.82190531283898e-05 -3.52455141557409e-06 9.76205981883374e-06 3.91848312423641e-06 8.97534233475779e-05 1559 1557 0 16 16 1519 1528 0 23 0 0 0 0 0 0 3 13 0 411 0 110 88 0 0 2556 +353 396 0.990902773040926 -0.00189526567258198 0.134566349240194 -0.0204027639351372 -0.0165288780157609 0.990616830278652 0.135665366841421 -0.0300801371462291 -0.133560812259224 -0.136655418980396 0.981573637529018 0.00658932835064825 0.000107776981197391 4.38912503621907e-05 -1.39648473822606e-05 -1.46973290702657e-05 -8.05610123060097e-06 4.09620839392476e-05 4.38912503621907e-05 6.75753973871618e-05 -7.8919974679551e-06 1.53562059219223e-05 -1.02701033957304e-05 2.42553058269753e-05 -1.39648473822606e-05 -7.8919974679551e-06 1.30073882392685e-05 9.34736871743652e-06 7.14955784041291e-06 -6.08981166612577e-06 -1.46973290702657e-05 1.53562059219223e-05 9.34736871743652e-06 5.82693025935159e-05 -2.02454419964871e-06 9.9927372681427e-06 -8.05610123060097e-06 -1.02701033957304e-05 7.14955784041291e-06 -2.02454419964871e-06 3.63840816036126e-05 -6.29469441312007e-06 4.09620839392476e-05 2.42553058269753e-05 -6.08981166612577e-06 9.9927372681427e-06 -6.29469441312007e-06 8.98074652696497e-05 1662 1661 0 15 16 1631 1639 0 23 1 0 0 0 0 0 0 13 0 246 0 109 91 0 0 2278 +353 412 0.990350532625374 -0.00276136955835559 0.138557559760554 -0.0228897302968288 -0.0167140397390364 0.990123587354174 0.139197423253818 -0.0238316482517586 -0.137573483652335 -0.14017009881948 0.980523268460621 0.00245000729894454 0.000119168224527945 6.64508967742686e-05 -1.97990776238043e-05 6.4358130685045e-06 -1.1146850813725e-05 7.47272189730369e-05 6.64508967742686e-05 7.04274391774875e-05 -1.70723745291754e-05 1.08594384611347e-05 -3.09364470887807e-07 5.32190740296105e-05 -1.97990776238043e-05 -1.70723745291754e-05 1.47010732968753e-05 2.65377944231247e-06 6.0665106281724e-06 -1.41579808442468e-05 6.4358130685045e-06 1.08594384611347e-05 2.65377944231247e-06 5.1277415381648e-05 -7.54120803810134e-06 9.01276360688482e-06 -1.1146850813725e-05 -3.09364470887807e-07 6.0665106281724e-06 -7.54120803810134e-06 4.95782756942699e-05 -2.12930180802658e-07 7.47272189730369e-05 5.32190740296105e-05 -1.41579808442468e-05 9.01276360688482e-06 -2.12930180802658e-07 0.000133880392074244 1449 1452 0 15 9 1417 1431 0 24 3 0 0 0 0 0 1 12 0 347 0 54 56 0 0 2050 +353 384 0.99033164113005 -0.00222664030349771 0.138702136427745 -0.0176058872604095 -0.0166436152723309 0.990741201225817 0.134739980199984 -0.0321185339665811 -0.137717938727417 -0.135745770713434 0.981125300400559 -0.00725238323626405 0.000128484836518642 8.06767036974445e-05 -1.99080713119592e-05 1.3352242564643e-05 -6.38968437948783e-06 7.6870258108663e-05 8.06767036974445e-05 9.77240347976051e-05 -1.82509414964742e-05 1.7262084909756e-05 2.20523256453848e-06 6.32597805034052e-05 -1.99080713119592e-05 -1.82509414964742e-05 1.52774195579094e-05 -3.26439538386055e-07 5.11079190445227e-07 -1.35785044823497e-05 1.3352242564643e-05 1.7262084909756e-05 -3.26439538386055e-07 4.22015399707534e-05 -6.64022451630213e-06 1.63764623822987e-05 -6.38968437948783e-06 2.20523256453848e-06 5.11079190445227e-07 -6.64022451630213e-06 5.5212054497684e-05 -1.16928399945425e-05 7.6870258108663e-05 6.32597805034052e-05 -1.35785044823497e-05 1.63764623822987e-05 -1.16928399945425e-05 0.000152873428248176 1725 1724 0 17 19 1715 1726 0 28 8 0 0 0 0 0 2 12 0 432 0 125 109 0 0 2605 +353 379 0.989839858721393 -0.00204317391508822 0.142172006832448 -0.0135249789889396 -0.0170673359576605 0.990959862158851 0.13306862001772 -0.0325690632432537 -0.141158634626866 -0.134143121442975 0.980856698422259 0.000166713092406974 0.000101306759177576 5.44680941633068e-05 -1.32130324470401e-05 2.18635005530052e-05 -1.88700811927656e-05 4.15603768564008e-05 5.44680941633068e-05 7.98101175152431e-05 -1.27614288088333e-05 3.53501529120028e-05 -1.26675050249921e-05 2.67229596385285e-05 -1.32130324470401e-05 -1.27614288088333e-05 1.23958866561425e-05 -1.66246420971521e-07 6.91554190347902e-06 -5.20896266439136e-06 2.18635005530052e-05 3.53501529120028e-05 -1.66246420971521e-07 7.20339511018067e-05 -1.65834487996252e-05 2.86460467794237e-05 -1.88700811927656e-05 -1.26675050249921e-05 6.91554190347902e-06 -1.65834487996252e-05 4.81060295683223e-05 -1.79276327351064e-05 4.15603768564008e-05 2.67229596385285e-05 -5.20896266439136e-06 2.86460467794237e-05 -1.79276327351064e-05 0.000105279139451299 1703 1700 0 17 19 1675 1684 0 29 7 0 0 0 0 0 2 12 0 421 0 126 106 0 0 2562 +353 408 0.988627859635686 -0.00118105596925385 0.150378057770938 -0.0150957260545076 -0.0181459533388565 0.991725761780231 0.127085553068963 -0.0286821075004332 -0.149283889048973 -0.128369071540685 0.980426285827852 0.00940156434605821 0.000116914720452604 7.84501284752835e-05 -1.28484312530217e-05 -6.48322750505536e-06 -7.1513965088468e-06 6.53306369759077e-05 7.84501284752835e-05 0.000105672326517902 -1.12470483882395e-05 6.77608556141929e-06 -8.92586241048112e-06 7.17303793856865e-05 -1.28484312530217e-05 -1.12470483882395e-05 1.25251549206554e-05 7.48206950654569e-06 6.62047413372919e-06 -8.56294040678091e-06 -6.48322750505536e-06 6.77608556141929e-06 7.48206950654569e-06 4.0980238522882e-05 -6.25626709716039e-06 1.50128465498479e-05 -7.1513965088468e-06 -8.92586241048112e-06 6.62047413372919e-06 -6.25626709716039e-06 4.03751897116233e-05 -1.40699860125702e-05 6.53306369759077e-05 7.17303793856865e-05 -8.56294040678091e-06 1.50128465498479e-05 -1.40699860125702e-05 0.000146998359331389 1723 1725 0 15 9 1703 1713 0 22 1 0 0 0 0 0 3 15 0 269 0 77 81 0 0 2125 +353 395 0.988634466989691 -0.00144727432249961 0.150332285544539 -0.0154564713403991 -0.0181892835084883 0.991456458673412 0.129163619182124 -0.0273486749009725 -0.149234850639713 -0.130430042366827 0.980161702681109 0.00712433920385838 0.000153333273119782 8.38540324493738e-05 -1.67899602486311e-05 1.22105736372611e-05 -3.1826479922553e-05 8.75417379158612e-05 8.38540324493738e-05 0.000115742201415645 -1.35691914865048e-05 2.38392065598365e-05 -1.85935905027882e-05 7.87442321831105e-05 -1.67899602486311e-05 -1.35691914865048e-05 1.33764490382028e-05 3.88072561833413e-06 1.0395590229775e-05 -1.16107385461426e-05 1.22105736372611e-05 2.38392065598365e-05 3.88072561833413e-06 4.14343538422393e-05 1.65118863829368e-06 3.32106531183904e-05 -3.1826479922553e-05 -1.85935905027882e-05 1.0395590229775e-05 1.65118863829368e-06 4.21273812097955e-05 -2.72199526401931e-05 8.75417379158612e-05 7.87442321831105e-05 -1.16107385461426e-05 3.32106531183904e-05 -2.72199526401931e-05 0.000194876416694776 1645 1641 0 20 17 1616 1625 0 26 0 0 0 0 0 0 2 15 0 221 0 124 109 0 0 2255 +353 389 0.99080735308868 -0.00197531202775315 0.135265986884348 -0.0255549294569961 -0.0165882076130516 0.990573772691775 0.135972174445254 -0.0246706618233062 -0.134259526416526 -0.136966050529237 0.981435010873788 0.00472938323137891 0.000113371495632157 6.43671795504744e-05 -1.19427223089082e-05 1.53724282053466e-05 -2.24426109380681e-05 5.36872378598551e-05 6.43671795504744e-05 0.000112039153228004 -1.12799597469405e-05 2.68406035734971e-05 -1.47865771522711e-05 7.06072082277852e-05 -1.19427223089082e-05 -1.12799597469405e-05 1.28702938015377e-05 2.49373661083238e-06 9.46657240124962e-06 -1.08864070456802e-05 1.53724282053466e-05 2.68406035734971e-05 2.49373661083238e-06 5.23662361799589e-05 -1.28694598688421e-05 3.67049170004863e-05 -2.24426109380681e-05 -1.47865771522711e-05 9.46657240124962e-06 -1.28694598688421e-05 4.51675057540866e-05 -2.00235185993356e-05 5.36872378598551e-05 7.06072082277852e-05 -1.08864070456802e-05 3.67049170004863e-05 -2.00235185993356e-05 0.000156140457152078 1524 1523 0 12 23 1481 1493 0 23 5 0 0 0 0 0 1 12 0 292 0 101 78 0 0 2378 +353 388 0.990936398406441 -0.0028283878343401 0.134302101753954 -0.0226163720585404 -0.0163933046509345 0.989759461585662 0.141800803115785 -0.0271892382739257 -0.133327843588249 -0.14271723240001 0.980742309528955 -0.00833659722236012 0.000100893752377748 4.30688000201602e-05 -1.07833913450794e-05 4.76059350914985e-06 -1.90476150235189e-05 2.77992244984212e-05 4.30688000201602e-05 6.77069264918979e-05 -5.84143659034236e-06 -2.64068328085504e-06 4.54972722806764e-06 1.81038312675022e-05 -1.07833913450794e-05 -5.84143659034236e-06 1.20073653807645e-05 4.34381175034361e-06 9.6030098156993e-06 -3.99557380509018e-06 4.76059350914985e-06 -2.64068328085504e-06 4.34381175034361e-06 4.6006429200082e-05 -7.13460515010921e-06 3.78019378019381e-06 -1.90476150235189e-05 4.54972722806764e-06 9.6030098156993e-06 -7.13460515010921e-06 4.8921416553217e-05 -6.64603828321017e-06 2.77992244984212e-05 1.81038312675022e-05 -3.99557380509018e-06 3.78019378019381e-06 -6.64603828321017e-06 8.21068662429884e-05 1657 1654 0 17 23 1665 1691 0 25 7 0 0 0 0 0 3 12 0 427 0 132 115 0 0 2442 +353 385 0.991039722372389 -0.00218651138790428 0.133549570751871 -0.0294683823235281 -0.016392050802741 0.990316729584931 0.137855271116805 -0.02279037948948 -0.132557796264644 -0.138809200963618 0.98140737534283 -0.00693271344840242 7.98817838617987e-05 7.83283083604766e-06 -1.2546657121971e-05 3.65145828650639e-06 -2.3836546348928e-05 7.87612013232537e-06 7.83283083604766e-06 6.5412136137835e-05 -4.94686208465705e-06 1.98449041172242e-05 -3.76263671912119e-06 5.04043281308976e-06 -1.2546657121971e-05 -4.94686208465705e-06 1.29055327552185e-05 4.20010184703292e-06 5.57010811228285e-06 -1.65696285813416e-08 3.65145828650639e-06 1.98449041172242e-05 4.20010184703292e-06 5.29049348666226e-05 -1.80100485925769e-05 9.78472569146881e-06 -2.3836546348928e-05 -3.76263671912119e-06 5.57010811228285e-06 -1.80100485925769e-05 6.6761465348119e-05 -1.10388637806245e-05 7.87612013232537e-06 5.04043281308976e-06 -1.65696285813416e-08 9.78472569146881e-06 -1.10388637806245e-05 6.63612345459831e-05 1645 1638 0 12 22 1655 1680 0 21 7 0 0 0 0 0 1 11 0 426 0 130 113 0 0 2517 +353 398 0.991495957820846 -0.00199303846168021 0.130122224937226 -0.0179557008933453 -0.0158377046451433 0.990602581743766 0.135851728565224 -0.0405230348951349 -0.129170169685175 -0.136757277101719 0.982146890451335 -0.00757970535978082 5.97709038895587e-05 2.62775094186813e-05 -9.62988902946014e-06 3.92413625261465e-06 -8.56152118556667e-06 2.06008942438945e-05 2.62775094186813e-05 6.5874212758172e-05 -6.50863721412118e-06 2.35378656345435e-05 -1.96807359860232e-06 4.15552198519906e-05 -9.62988902946014e-06 -6.50863721412118e-06 1.23825040006443e-05 5.04213886950418e-06 6.17963914703933e-06 -3.43200259562649e-06 3.92413625261465e-06 2.35378656345435e-05 5.04213886950418e-06 5.14222264944831e-05 -9.72050155283913e-06 2.63585677696422e-05 -8.56152118556667e-06 -1.96807359860232e-06 6.17963914703933e-06 -9.72050155283913e-06 5.17715892577238e-05 -9.69680266173442e-06 2.06008942438945e-05 4.15552198519906e-05 -3.43200259562649e-06 2.63585677696422e-05 -9.69680266173442e-06 0.000103629848933832 1786 1783 0 20 20 1806 1825 0 25 6 0 0 0 0 0 0 11 0 253 0 132 122 0 0 2212 +353 390 0.990708821514138 -0.00163108682284359 0.135990332486701 -0.0208559461171693 -0.0168199904740106 0.990781743487434 0.134419584482522 -0.0265800140255238 -0.134955988731591 -0.135458024228084 0.981548778603337 0.0111325111081592 7.4094222418741e-05 2.46123766898816e-05 -9.33695806856366e-06 5.64008279020181e-06 -6.8799776227111e-06 1.96377493633774e-05 2.46123766898816e-05 6.85083108601697e-05 -7.03099740737563e-06 1.27638276925369e-05 2.13406401295318e-06 2.2956080380481e-05 -9.33695806856366e-06 -7.03099740737563e-06 1.21893017369177e-05 5.61088119982918e-06 6.04790011374246e-06 -2.7027697811367e-06 5.64008279020181e-06 1.27638276925369e-05 5.61088119982918e-06 4.19952903464734e-05 3.65289201985819e-06 1.90567679021638e-05 -6.8799776227111e-06 2.13406401295318e-06 6.04790011374246e-06 3.65289201985819e-06 4.08341014653578e-05 4.58533437094188e-06 1.96377493633774e-05 2.2956080380481e-05 -2.7027697811367e-06 1.90567679021638e-05 4.58533437094188e-06 8.09257242672033e-05 1683 1688 0 15 23 1640 1658 0 22 5 0 0 0 0 0 3 13 0 205 0 102 78 0 0 2270 +354 410 0.991089440012329 -0.00167752577522601 0.133187491166856 -0.03023543790899 -0.0165444091184569 0.99062699283807 0.135589245840234 -0.0161394149198403 -0.13216657831301 -0.136584578074817 0.981772197920248 0.00324014770043732 0.000102373045498911 6.45655058358275e-05 -1.14036554852469e-05 2.95165513321311e-06 -5.6195259105519e-06 6.73750907832802e-05 6.45655058358275e-05 8.07690574353602e-05 -8.72706610958468e-06 1.41533088584507e-05 -1.58112176944942e-06 5.41212297776415e-05 -1.14036554852469e-05 -8.72706610958468e-06 1.2418198845488e-05 4.9691310240988e-06 7.2359341459832e-06 -9.71072233752248e-06 2.95165513321311e-06 1.41533088584507e-05 4.9691310240988e-06 4.79369671147767e-05 -3.49470649009117e-06 1.18799703082934e-05 -5.6195259105519e-06 -1.58112176944942e-06 7.2359341459832e-06 -3.49470649009117e-06 3.89712725072059e-05 -7.33979121501341e-06 6.73750907832802e-05 5.41212297776415e-05 -9.71072233752248e-06 1.18799703082934e-05 -7.33979121501341e-06 0.000123548737390037 1422 1422 0 12 9 1404 1421 0 25 3 0 0 0 0 0 2 13 0 303 0 69 71 0 0 2106 +354 356 0.999954822896698 -0.00126059093995966 0.00942141582333616 -0.0115413668600627 0.00130845460124034 0.999986261658545 -0.0050758684700348 0.00125288091002625 -0.00941488779490284 0.00508796665188482 0.999942734601916 -0.00204907741247747 4.81459113174052e-05 1.60179726847816e-05 -5.68813747038284e-06 3.44520342920837e-06 -1.11843168597053e-06 1.327832557002e-05 1.60179726847816e-05 5.0747161398725e-05 -8.55912354622339e-06 1.59354967800972e-05 3.58843282390636e-06 1.76768664671205e-05 -5.68813747038284e-06 -8.55912354622339e-06 1.35058357714545e-05 -3.42867887192952e-07 2.14541656514415e-06 -3.18835402689083e-06 3.44520342920837e-06 1.59354967800972e-05 -3.42867887192952e-07 5.19297673044241e-05 -2.3801699608329e-05 1.36463901908976e-05 -1.11843168597053e-06 3.58843282390636e-06 2.14541656514415e-06 -2.3801699608329e-05 5.56164980180981e-05 1.32111565853442e-06 1.327832557002e-05 1.76768664671205e-05 -3.18835402689083e-06 1.36463901908976e-05 1.32111565853442e-06 5.74339949619478e-05 2123 2104 0 4 58 2117 2127 0 14 39 0 0 0 0 0 10 23 0 280 0 60 44 0 0 3266 +353 394 0.99097646550327 -0.00259208502029418 0.134010917144441 -0.0238028405177195 -0.0162385931507629 0.99012669184999 0.139231613431283 -0.0257743249741196 -0.133048686243535 -0.140151400925719 0.981150157675892 0.003869303954136 6.43738345961778e-05 2.95048108210116e-05 -4.31112969809283e-06 -2.99035569655553e-06 -1.10982646069623e-05 2.93216591291855e-05 2.95048108210116e-05 6.51357241544032e-05 -2.92803023301975e-06 2.19296160182619e-05 -2.85154488405753e-06 3.16448368504089e-05 -4.31112969809283e-06 -2.92803023301975e-06 1.13516853280513e-05 6.53148946054777e-06 6.18834929803647e-06 -2.6444736974032e-06 -2.99035569655553e-06 2.19296160182619e-05 6.53148946054777e-06 5.1659580743708e-05 -7.85050650309893e-07 2.00752343667664e-05 -1.10982646069623e-05 -2.85154488405753e-06 6.18834929803647e-06 -7.85050650309893e-07 4.42037050842957e-05 -7.72505165917082e-06 2.93216591291855e-05 3.16448368504089e-05 -2.6444736974032e-06 2.00752343667664e-05 -7.72505165917082e-06 8.5377496654327e-05 1671 1666 0 11 17 1631 1640 0 19 0 0 0 0 0 0 0 9 0 249 0 109 90 0 0 2247 +353 413 0.991602323678645 -0.00228015970764288 0.129304418125675 -0.0295938137420545 -0.0158292336441129 0.990186723384532 0.138851316865359 -0.023728047582194 -0.128352121281075 -0.139732078295257 0.981835362603087 -0.0027523425943091 6.65921406714082e-05 3.73600367484688e-05 -1.11007062925353e-05 2.6420813705319e-06 1.84598735733108e-06 2.32754349517821e-05 3.73600367484688e-05 4.81417746798563e-05 -1.08049598263648e-05 5.3699204842709e-06 8.73737760291638e-06 1.77441386656278e-05 -1.11007062925353e-05 -1.08049598263648e-05 1.2497834504197e-05 2.04372219734749e-06 1.73962362933733e-06 -4.5408732390746e-06 2.6420813705319e-06 5.3699204842709e-06 2.04372219734749e-06 4.8035680886855e-05 -4.50709801812974e-06 1.29139703711212e-05 1.84598735733108e-06 8.73737760291638e-06 1.73962362933733e-06 -4.50709801812974e-06 5.45028350478498e-05 5.1310477335555e-06 2.32754349517821e-05 1.77441386656278e-05 -4.5408732390746e-06 1.29139703711212e-05 5.1310477335555e-06 8.65399354189316e-05 1659 1662 0 14 11 1627 1640 0 23 4 0 0 0 0 0 4 16 0 383 0 66 69 0 0 2006 +354 396 0.990869936490615 -0.00248922502164364 0.134798266746555 -0.0241235547143216 -0.0166231890798908 0.989944848946998 0.140473718638469 -0.022308625515834 -0.133792520508054 -0.14143196174167 0.980865210747126 0.00366468584464006 7.12576020961711e-05 1.47364330005338e-05 -5.13075523402241e-06 -1.1397282304655e-05 -1.7023693740049e-05 7.82244987829063e-07 1.47364330005338e-05 4.66973200343332e-05 -1.78622744810359e-06 4.64551750324308e-06 -2.26753378558806e-06 1.57488443090498e-05 -5.13075523402241e-06 -1.78622744810359e-06 1.1339596836416e-05 6.05650980676123e-06 6.86875964630798e-06 8.98612259963103e-07 -1.1397282304655e-05 4.64551750324308e-06 6.05650980676123e-06 4.41897755338125e-05 9.42221281376739e-06 1.14533751980407e-05 -1.7023693740049e-05 -2.26753378558806e-06 6.86875964630798e-06 9.42221281376739e-06 5.61529856972404e-05 1.40733874907821e-05 7.82244987829063e-07 1.57488443090498e-05 8.98612259963103e-07 1.14533751980407e-05 1.40733874907821e-05 7.15153766702379e-05 1567 1561 0 14 25 1543 1565 0 25 3 0 0 0 0 0 2 13 0 251 0 107 89 0 0 2303 +354 358 0.999783811312917 9.742996739672e-05 0.020792333779998 -0.00305767284098207 -2.48647942870359e-05 0.999993908831679 -0.00349022653745565 -0.00638097187321985 -0.0207925471830509 0.0034889549928607 0.999777723884013 -0.00578872767812766 4.67953191216731e-05 2.52750383418358e-05 -1.34202109298402e-05 1.11050234214225e-05 7.70090170751264e-06 2.03220305087254e-05 2.52750383418358e-05 4.68566727044738e-05 -1.51226217036045e-05 1.96267021234967e-05 7.44443529847649e-06 2.77985755328743e-05 -1.34202109298402e-05 -1.51226217036045e-05 1.70732588301408e-05 -3.82264601718977e-06 -1.80041199987947e-06 -9.49090269666198e-06 1.11050234214225e-05 1.96267021234967e-05 -3.82264601718977e-06 4.46647746357247e-05 -6.1017032995468e-06 2.21792273099991e-05 7.70090170751264e-06 7.44443529847649e-06 -1.80041199987947e-06 -6.1017032995468e-06 3.86515983925308e-05 4.48973068631821e-06 2.03220305087254e-05 2.77985755328743e-05 -9.49090269666198e-06 2.21792273099991e-05 4.48973068631821e-06 7.59196893630809e-05 2063 2029 0 6 77 2024 2042 0 20 28 0 0 0 0 0 7 19 0 330 0 90 58 0 0 3282 +354 409 0.992200780313966 -0.00149095699571764 0.124641038954244 -0.0364349717946572 -0.0156305128597146 0.990547718120257 0.136275108491957 -0.0205117502633656 -0.123666077046613 -0.137160472345313 0.982798914434643 -0.00484281487481508 6.45812538434661e-05 4.46816257593017e-05 -5.80950554657383e-06 5.40987561942029e-06 -7.18977082453786e-06 3.11371292026374e-05 4.46816257593017e-05 7.95675255469413e-05 -7.61244447059679e-06 2.41717321879562e-05 -8.70155108360142e-06 4.14772530836312e-05 -5.80950554657383e-06 -7.61244447059679e-06 1.09734495827862e-05 4.06202221646938e-06 6.77194862902828e-06 -3.2221345517258e-06 5.40987561942029e-06 2.41717321879562e-05 4.06202221646938e-06 6.7159496044985e-05 -1.81192974466354e-05 1.8131586282112e-05 -7.18977082453786e-06 -8.70155108360142e-06 6.77194862902828e-06 -1.81192974466354e-05 5.01063567563524e-05 -1.11683049975706e-05 3.11371292026374e-05 4.14772530836312e-05 -3.2221345517258e-06 1.8131586282112e-05 -1.11683049975706e-05 9.48739842752444e-05 1404 1406 0 12 10 1391 1411 0 21 2 0 0 0 0 0 1 10 0 296 0 71 74 0 0 2044 +354 383 0.990779181133956 -0.00267144746905662 0.135460243613942 -0.0255394355009075 -0.0161849691380241 0.99031254012663 0.13790982431264 -0.0256789310794714 -0.134516396790613 -0.138830602665126 0.981137810278509 -0.0062113236678633 7.79417782813505e-05 4.41561976024415e-05 -1.17952348051455e-05 5.63503377674061e-06 -9.98953653118374e-06 2.53404473120603e-05 4.41561976024415e-05 6.3159994830462e-05 -9.31453174117443e-06 1.42521355461007e-05 -1.47698900170198e-05 1.19785014787869e-05 -1.17952348051455e-05 -9.31453174117443e-06 1.35200868770851e-05 2.65761401989747e-06 3.38133123235819e-06 -3.69360247209733e-06 5.63503377674061e-06 1.42521355461007e-05 2.65761401989747e-06 4.67984946507343e-05 2.22224360595813e-06 3.89096560424185e-06 -9.98953653118374e-06 -1.47698900170198e-05 3.38133123235819e-06 2.22224360595813e-06 3.71486538901665e-05 -8.19819139466181e-06 2.53404473120603e-05 1.19785014787869e-05 -3.69360247209733e-06 3.89096560424185e-06 -8.19819139466181e-06 6.78604946957949e-05 1641 1646 0 11 26 1617 1640 0 21 11 0 0 0 0 0 1 11 0 428 0 113 92 0 0 2569 +354 382 0.990951391872607 -0.00308909516730057 0.134185678955658 -0.0306450767531624 -0.0160805872507897 0.989801887532623 0.141540235094217 -0.0160162060816955 -0.133254469566365 -0.142417277490843 0.980795883664222 -0.00194851881273244 5.70139876405961e-05 3.27428519055232e-05 -7.17844316024991e-06 5.65430586613696e-06 -6.06682017729252e-06 1.59000989848211e-05 3.27428519055232e-05 6.86920896607908e-05 -8.87574608497495e-06 2.11514756724842e-05 -6.5866665884052e-06 1.97699060523247e-05 -7.17844316024991e-06 -8.87574608497495e-06 1.21646154055108e-05 4.45619838732025e-06 2.51461091633342e-06 -1.50319379839708e-06 5.65430586613696e-06 2.11514756724842e-05 4.45619838732025e-06 6.03200441715892e-05 -1.6074016965456e-05 1.36631979021346e-05 -6.06682017729252e-06 -6.5866665884052e-06 2.51461091633342e-06 -1.6074016965456e-05 5.69162146459577e-05 1.65479188053687e-06 1.59000989848211e-05 1.97699060523247e-05 -1.50319379839708e-06 1.36631979021346e-05 1.65479188053687e-06 6.53108728897556e-05 1561 1555 0 13 39 1516 1545 0 25 10 0 0 0 0 0 2 10 0 438 0 112 96 0 0 2590 +354 357 0.999594396076701 0.00116897982732391 0.0284548206499077 -0.0069888047987248 -0.00103897471054001 0.999988957426403 -0.00458318195224127 -0.00140141444083897 -0.0284598640827036 0.00455175915661204 0.999584572522493 5.96642517228943e-05 5.87453846368963e-05 2.06714855374416e-05 -1.19407950486377e-05 7.53944197701872e-06 -4.9892372167858e-06 1.66439129225631e-05 2.06714855374416e-05 4.24738558434582e-05 -1.14423912424821e-05 1.49004399596705e-05 9.06144930529648e-07 1.68668970722398e-05 -1.19407950486377e-05 -1.14423912424821e-05 1.5529956255508e-05 -1.41505758103136e-06 -1.95539823026508e-06 -7.30970705171354e-06 7.53944197701872e-06 1.49004399596705e-05 -1.41505758103136e-06 3.84554954287009e-05 -1.16707074615467e-05 8.17947627957636e-06 -4.9892372167858e-06 9.06144930529648e-07 -1.95539823026508e-06 -1.16707074615467e-05 5.15238611146919e-05 -1.49323870499782e-06 1.66439129225631e-05 1.68668970722398e-05 -7.30970705171354e-06 8.17947627957636e-06 -1.49323870499782e-06 5.30100682798845e-05 2152 2118 0 4 74 2118 2131 0 13 37 0 0 0 0 0 7 18 0 320 0 75 41 0 0 3297 +354 385 0.991447903629471 -0.00261924294292044 0.1304767946998 -0.0286151108517107 -0.0155411447896833 0.990314230317617 0.137971729165986 -0.0259773910446847 -0.129574407995383 -0.138819540399873 0.981804261549019 -0.00404007141649994 6.52714108423255e-05 1.73844349892337e-05 -1.07592605834249e-05 3.86734884279672e-06 -5.51075362359927e-06 4.78965105168634e-06 1.73844349892337e-05 4.04339030192062e-05 -9.54063815470808e-06 4.80320215502899e-06 9.70599782089759e-06 9.65289165767802e-06 -1.07592605834249e-05 -9.54063815470808e-06 1.30246825998827e-05 5.3285224375774e-07 8.99188071326948e-07 -6.50810488708953e-07 3.86734884279672e-06 4.80320215502899e-06 5.3285224375774e-07 3.29507128405043e-05 3.92188457820385e-06 1.99590724873824e-06 -5.51075362359927e-06 9.70599782089759e-06 8.99188071326948e-07 3.92188457820385e-06 4.03464040559089e-05 1.1390832265892e-05 4.78965105168634e-06 9.65289165767802e-06 -6.50810488708953e-07 1.99590724873824e-06 1.1390832265892e-05 6.24071931094054e-05 1790 1778 0 11 37 1751 1777 0 21 8 0 0 0 0 0 2 12 0 432 0 114 97 0 0 2508 +354 395 0.990137089795516 -0.0021047076965803 0.140086093588114 -0.0209954815965654 -0.0169923563674364 0.990701559934433 0.134987699323171 -0.0262653271105475 -0.139067621092575 -0.136036720590408 0.980894595466128 0.00113225836052435 9.68710433781132e-05 6.86023965855558e-05 -1.08024206437313e-05 1.30961508053588e-05 -1.49577367024843e-05 4.06745340705845e-05 6.86023965855558e-05 9.04895275120172e-05 -1.16276153386515e-05 1.55320665474798e-05 -1.44936680156172e-05 4.50280794972709e-05 -1.08024206437313e-05 -1.16276153386515e-05 1.355826927761e-05 1.8710584075811e-06 8.09673919702032e-06 -6.274549016525e-06 1.30961508053588e-05 1.55320665474798e-05 1.8710584075811e-06 4.1640529798667e-05 -1.48661383882275e-06 1.79577275234707e-05 -1.49577367024843e-05 -1.44936680156172e-05 8.09673919702032e-06 -1.48661383882275e-06 4.18751024991257e-05 -1.20634556769837e-05 4.06745340705845e-05 4.50280794972709e-05 -6.274549016525e-06 1.79577275234707e-05 -1.20634556769837e-05 0.000122470365387189 1701 1704 0 16 23 1669 1693 0 27 7 0 0 0 0 0 0 11 0 233 0 105 87 0 0 2268 +354 412 0.990760258176423 -0.00200898840183992 0.135610009895247 -0.0267784435457001 -0.0167413655455415 0.990431734996108 0.136984323892443 -0.021437963137759 -0.134587657301323 -0.13798892085309 0.981246768261654 0.00352021282994082 9.09524400186183e-05 4.13609335230093e-05 -1.50289113058483e-05 -6.8584533747769e-07 -2.15928963021257e-06 3.26105567412457e-05 4.13609335230093e-05 6.29838052013601e-05 -1.07417148236125e-05 3.46486085199358e-06 1.18596210056843e-05 3.29225012624087e-05 -1.50289113058483e-05 -1.07417148236125e-05 1.34077236771999e-05 4.09697017709154e-06 4.97187007268818e-06 -3.88381261392159e-06 -6.8584533747769e-07 3.46486085199358e-06 4.09697017709154e-06 3.94244588955081e-05 6.38506867359095e-06 7.40183098649423e-06 -2.15928963021257e-06 1.18596210056843e-05 4.97187007268818e-06 6.38506867359095e-06 3.50009742562124e-05 1.09575729460739e-05 3.26105567412457e-05 3.29225012624087e-05 -3.88381261392159e-06 7.40183098649423e-06 1.09575729460739e-05 9.35677579792908e-05 1528 1529 0 12 9 1502 1515 0 22 3 0 0 0 0 0 1 9 0 359 0 62 64 0 0 2071 +354 381 0.99102933339799 -0.00184038971341438 0.133631857393509 -0.0289631950493808 -0.0165937745006207 0.990473192372646 0.136702237871083 -0.0199055217133849 -0.132610357787613 -0.13769338457908 0.981557448573744 -0.00147439107846749 5.11913068271055e-05 3.41635291754505e-05 -5.9542323629146e-06 1.04585669856809e-05 2.78152450568125e-06 1.86184565351681e-05 3.41635291754505e-05 5.35540579748643e-05 -8.47837849356846e-06 1.02317569543293e-05 4.5614184290173e-06 2.08088280858364e-05 -5.9542323629146e-06 -8.47837849356846e-06 1.25462739117602e-05 1.32039187962573e-06 2.9863632827093e-06 -2.62405424882556e-06 1.04585669856809e-05 1.02317569543293e-05 1.32039187962573e-06 4.03537681012526e-05 -2.56662702790217e-06 1.35542853571126e-05 2.78152450568125e-06 4.5614184290173e-06 2.9863632827093e-06 -2.56662702790217e-06 4.32313374309729e-05 6.8820662837281e-07 1.86184565351681e-05 2.08088280858364e-05 -2.62405424882556e-06 1.35542853571126e-05 6.8820662837281e-07 7.35104392369134e-05 1567 1555 0 10 40 1525 1549 0 19 8 0 0 0 0 0 1 9 0 429 0 113 98 0 0 2608 +354 387 0.990882070929098 -0.00222472081602325 0.134713667192875 -0.02946265861379 -0.0166334593406949 0.990194832732404 0.138699391708857 -0.0154620530153351 -0.133701344576722 -0.139675494798967 0.981129301677939 -0.00494004287046055 6.83447838751326e-05 2.49015126100291e-05 -1.37380413721601e-05 1.39414136345175e-05 -6.33333988334114e-07 4.79025565253283e-06 2.49015126100291e-05 6.02094728115356e-05 -9.60479626330223e-06 1.87461801962744e-05 3.12506857074921e-06 2.02813523163801e-05 -1.37380413721601e-05 -9.60479626330223e-06 1.50140850087757e-05 8.75665818842665e-07 6.33830641639362e-07 -3.68150179038315e-06 1.39414136345175e-05 1.87461801962744e-05 8.75665818842665e-07 6.38139712052126e-05 -1.25335263977778e-05 1.40879263113067e-05 -6.33333988334114e-07 3.12506857074921e-06 6.33830641639362e-07 -1.25335263977778e-05 6.18539917488568e-05 4.8312564270823e-06 4.79025565253283e-06 2.02813523163801e-05 -3.68150179038315e-06 1.40879263113067e-05 4.8312564270823e-06 9.40269254776446e-05 1480 1488 0 12 26 1455 1476 0 24 10 0 0 0 0 0 1 12 0 429 0 111 92 0 0 2558 +354 384 0.990210427681514 -0.00233964611627507 0.139563014322722 -0.0240095731876962 -0.0170146015558497 0.99038021448648 0.137322736965185 -0.0196918321153619 -0.138541734667534 -0.138353015181326 0.980645007607517 -0.00491286753273572 6.8446874912005e-05 4.92421004113253e-05 -1.27179175613759e-05 1.30028676066993e-05 2.49529939030206e-06 2.23561723435298e-05 4.92421004113253e-05 8.86569794828278e-05 -1.52943874899513e-05 2.16163662946714e-05 4.62816258159112e-06 3.19769114464667e-05 -1.27179175613759e-05 -1.52943874899513e-05 1.33784575378852e-05 3.71509516387552e-07 1.06058928903239e-06 -3.99605224810916e-06 1.30028676066993e-05 2.16163662946714e-05 3.71509516387552e-07 4.31805933433833e-05 -1.72381389036989e-06 4.854673338279e-06 2.49529939030206e-06 4.62816258159112e-06 1.06058928903239e-06 -1.72381389036989e-06 4.35270119219566e-05 4.73702199443877e-06 2.23561723435298e-05 3.19769114464667e-05 -3.99605224810916e-06 4.854673338279e-06 4.73702199443877e-06 8.61637208068813e-05 1482 1488 0 13 27 1448 1471 0 20 9 0 0 0 0 0 2 13 0 443 0 111 91 0 0 2588 +354 411 0.991436790027102 -0.0038138113700934 0.130531782427072 -0.0310904961390757 -0.0158029374739538 0.988723397210073 0.14891712788181 -0.0141150162795356 -0.129627769200698 -0.149704704843256 0.980196481732027 -0.00984374644107585 0.00018295600987962 0.000125742552400464 -2.34591880637659e-05 2.37495132682726e-05 -2.70436291068995e-05 0.000114396772725527 0.000125742552400464 0.000143298208819379 -1.65230863657802e-05 4.27252427847667e-05 -2.76044803644454e-05 0.00012106081563551 -2.34591880637659e-05 -1.65230863657802e-05 1.4337204513267e-05 2.08449627350251e-06 7.45476828207415e-06 -9.77382827723215e-06 2.37495132682726e-05 4.27252427847667e-05 2.08449627350251e-06 6.16130119588807e-05 -1.05416973139199e-05 4.31239710544472e-05 -2.70436291068995e-05 -2.76044803644454e-05 7.45476828207415e-06 -1.05416973139199e-05 5.31815127135678e-05 -3.42204532882422e-05 0.000114396772725527 0.00012106081563551 -9.77382827723215e-06 4.31239710544472e-05 -3.42204532882422e-05 0.000197029133215772 1355 1360 0 13 9 1334 1349 0 24 4 0 0 0 0 0 0 11 0 318 0 65 66 0 0 2087 +354 388 0.991772726004475 -0.00277532387254052 0.127981082707782 -0.0268241294683075 -0.0152141022120314 0.990123361191665 0.139370946457291 -0.0278084019801693 -0.127103859294419 -0.140171420767294 0.981935120948703 -0.00963744937377807 5.1656064957354e-05 3.42280715882713e-05 -2.27734445649776e-06 8.41962456060591e-06 -4.99806524518989e-06 1.95235314438833e-05 3.42280715882713e-05 5.6200439930151e-05 -2.87226918871636e-06 1.30697290606924e-05 -6.24800590648469e-06 3.08629455220976e-05 -2.27734445649776e-06 -2.87226918871636e-06 1.10383113723484e-05 3.77253374048034e-06 6.14132215122393e-06 -1.89644894182393e-06 8.41962456060591e-06 1.30697290606924e-05 3.77253374048034e-06 4.33840574751697e-05 -9.15375976834019e-06 1.21226080974307e-05 -4.99806524518989e-06 -6.24800590648469e-06 6.14132215122393e-06 -9.15375976834019e-06 4.23072874104962e-05 1.01412558843508e-06 1.95235314438833e-05 3.08629455220976e-05 -1.89644894182393e-06 1.21226080974307e-05 1.01412558843508e-06 9.07583672411004e-05 1808 1803 0 15 38 1765 1793 0 22 8 0 0 0 0 0 0 9 0 430 0 114 97 0 0 2415 +354 389 0.991606532548957 -0.00250729561906991 0.129267931347697 -0.0278598295320932 -0.0155481323003962 0.990243780237504 0.138475670364536 -0.0267041580200167 -0.128353964442878 -0.139323254231362 0.981893217535481 -0.00373162133655228 7.55746340785238e-05 2.11977314156925e-05 -7.68539747533272e-06 -4.95313206309655e-06 -3.36744396098801e-06 9.20793796447826e-06 2.11977314156925e-05 4.85007127518195e-05 -3.51598538372946e-06 3.27469398748888e-06 4.87396550763889e-06 4.14729352638057e-06 -7.68539747533272e-06 -3.51598538372946e-06 1.13235537021129e-05 5.09685752793737e-06 6.23617087342807e-06 -1.24469809904201e-06 -4.95313206309655e-06 3.27469398748888e-06 5.09685752793737e-06 3.2684819967481e-05 9.77957910108329e-07 7.9885286079674e-07 -3.36744396098801e-06 4.87396550763889e-06 6.23617087342807e-06 9.77957910108329e-07 3.07486484938326e-05 1.25323470579429e-06 9.20793796447826e-06 4.14729352638057e-06 -1.24469809904201e-06 7.9885286079674e-07 1.25323470579429e-06 5.86546633133811e-05 1588 1580 0 11 29 1533 1541 0 19 0 0 0 0 0 0 2 11 0 296 0 112 89 0 0 2370 +354 380 0.990465095022322 -0.00197159935249189 0.137749803406091 -0.031195695358773 -0.0167678322872481 0.990738232254974 0.134746409780282 -0.0227041734683262 -0.136739662654294 -0.135771381168058 0.98125857790539 -0.00314871251036514 0.000105295399849977 7.82316602139623e-05 -1.47848367709578e-05 1.78406566794265e-05 -1.8931712716154e-05 5.92153269657926e-05 7.82316602139623e-05 0.000110600989001317 -1.90260003330026e-05 2.44982346296596e-05 -1.03824608742773e-05 7.75048038540213e-05 -1.47848367709578e-05 -1.90260003330026e-05 1.38438375280452e-05 -3.56058346033511e-07 3.69766991777465e-06 -1.15128277497386e-05 1.78406566794265e-05 2.44982346296596e-05 -3.56058346033511e-07 5.57752792210488e-05 -1.40487982569137e-05 3.01437850802328e-05 -1.8931712716154e-05 -1.03824608742773e-05 3.69766991777465e-06 -1.40487982569137e-05 5.93884400172691e-05 -4.96365910685454e-06 5.92153269657926e-05 7.75048038540213e-05 -1.15128277497386e-05 3.01437850802328e-05 -4.96365910685454e-06 0.000140347031477106 1444 1449 0 13 22 1410 1432 0 24 7 0 0 0 0 0 1 12 0 434 0 114 92 0 0 2523 +354 408 0.98951391415413 -0.00192546670703562 0.144424742593963 -0.019685344927919 -0.017423691450638 0.991017924280325 0.132589172753094 -0.0272316814354741 -0.143382804658039 -0.133715243458167 0.980592476513724 0.000495948075343374 0.00020402809135061 0.000153721912356993 -2.70462375286054e-05 4.87574186170421e-05 -6.88305282578989e-05 0.000152128310057859 0.000153721912356993 0.000196794935224374 -2.19091135388751e-05 5.53943368862807e-05 -5.54014834416185e-05 0.00014534559470236 -2.70462375286054e-05 -2.19091135388751e-05 1.48974406829053e-05 -3.49082961878697e-07 1.59006106431761e-05 -1.94297648624693e-05 4.87574186170421e-05 5.53943368862807e-05 -3.49082961878697e-07 5.73061991311912e-05 -2.07807279436792e-05 5.99941259351036e-05 -6.88305282578989e-05 -5.54014834416185e-05 1.59006106431761e-05 -2.07807279436792e-05 6.58004199616078e-05 -6.58371659124418e-05 0.000152128310057859 0.00014534559470236 -1.94297648624693e-05 5.99941259351036e-05 -6.58371659124418e-05 0.000229986061523951 1454 1461 0 14 15 1424 1450 0 24 3 0 0 0 0 0 0 11 0 266 0 63 66 0 0 2105 +354 386 0.990929504330661 -0.00296048188187287 0.13435011348718 -0.0266119700356079 -0.0164182400807682 0.989600535222072 0.142902841402259 -0.0187519681754263 -0.133376005486899 -0.143812434216295 0.980575761950673 0.00158556197431815 5.00362236709535e-05 1.8727549445125e-05 -7.01369590498001e-06 -4.46644264776285e-06 1.91528795445894e-06 5.03859709783638e-06 1.8727549445125e-05 4.24063531963454e-05 -7.98333618041877e-06 1.28047968835401e-05 3.29909263020247e-06 8.0235713780335e-06 -7.01369590498001e-06 -7.98333618041877e-06 1.24326974050718e-05 1.91470940265374e-06 3.91552931498913e-06 -4.34594548381594e-07 -4.46644264776285e-06 1.28047968835401e-05 1.91470940265374e-06 4.38049184269175e-05 1.15349259314441e-05 8.01162342931589e-06 1.91528795445894e-06 3.29909263020247e-06 3.91552931498913e-06 1.15349259314441e-05 3.28315676221924e-05 3.72640901705094e-06 5.03859709783638e-06 8.0235713780335e-06 -4.34594548381594e-07 8.01162342931589e-06 3.72640901705094e-06 7.40376327145655e-05 1390 1387 0 13 17 1367 1390 0 22 4 0 0 0 0 0 2 10 0 419 0 112 92 0 0 2595 +354 398 0.990894491673611 -0.00197812674372323 0.134626124453922 -0.0237893808997857 -0.0165440641405757 0.990526116349721 0.136324270659523 -0.0238830253327908 -0.133620358900168 -0.137310232115907 0.981474146294066 -0.0030298519315411 8.16630558515973e-05 4.30825442554019e-05 -1.25313820425307e-05 8.87701081193036e-06 -5.29305428212322e-06 3.93782084591284e-05 4.30825442554019e-05 7.08630383750979e-05 -8.34429423396244e-06 2.25708635373912e-05 -3.78745159246327e-06 4.58260035363706e-05 -1.25313820425307e-05 -8.34429423396244e-06 1.28448436926325e-05 7.28362292618438e-06 3.98962444787103e-06 -3.74070687574482e-06 8.87701081193036e-06 2.25708635373912e-05 7.28362292618438e-06 5.570193633259e-05 -1.59301196878884e-05 2.38539753067757e-05 -5.29305428212322e-06 -3.78745159246327e-06 3.98962444787103e-06 -1.59301196878884e-05 5.27103990236356e-05 -2.95308156218892e-06 3.93782084591284e-05 4.58260035363706e-05 -3.74070687574482e-06 2.38539753067757e-05 -2.95308156218892e-06 0.000101343785730387 1778 1775 0 13 30 1742 1772 0 24 7 0 0 0 0 0 2 11 0 257 0 99 89 0 0 2202 +354 413 0.991216065502851 -0.00157167864362835 0.13224311443432 -0.0253625197566502 -0.0164827194987606 0.990665037338885 0.135318527010426 -0.0268694929209612 -0.131221307137876 -0.136309624093779 0.981937195004059 -0.00428006861968683 5.97673385895353e-05 2.58368401391223e-05 -8.20319767562415e-06 -3.54186735969204e-06 4.03975576765014e-06 1.30012061918758e-05 2.58368401391223e-05 5.47683298299232e-05 -7.90053978370865e-06 8.86650060919754e-06 1.1369261459679e-05 2.3508338636214e-05 -8.20319767562415e-06 -7.90053978370865e-06 1.20420757026734e-05 4.03391828225251e-06 3.26732562772645e-06 -4.21044226387045e-06 -3.54186735969204e-06 8.86650060919754e-06 4.03391828225251e-06 4.73197138442055e-05 6.80602588491155e-07 8.26867481977563e-06 4.03975576765014e-06 1.1369261459679e-05 3.26732562772645e-06 6.80602588491155e-07 4.28776855183637e-05 1.45614044460816e-06 1.30012061918758e-05 2.3508338636214e-05 -4.21044226387045e-06 8.26867481977563e-06 1.45614044460816e-06 8.58414018545955e-05 1353 1357 0 15 13 1336 1356 0 24 5 0 0 0 0 0 0 10 0 373 0 76 77 0 0 2063 +354 390 0.990127207416126 -0.00256836598516315 0.140148195245285 -0.0181135473288245 -0.0168614004785866 0.990389678913211 0.137273366229898 -0.0259212736110045 -0.139153894333737 -0.138281189604202 0.98056846078864 0.0105931062402696 6.89503075007639e-05 1.08530637750368e-05 -7.26915220280217e-06 -3.22731275929487e-06 -8.13997791177556e-06 8.39854874816665e-06 1.08530637750368e-05 0.000103828837245301 -5.82299271884363e-06 6.64200786215957e-06 1.73343443346306e-05 3.95094511720976e-05 -7.26915220280217e-06 -5.82299271884363e-06 1.16165018343772e-05 4.9144284505775e-06 5.30685247831822e-06 -3.44608111689011e-06 -3.22731275929487e-06 6.64200786215957e-06 4.9144284505775e-06 4.34677692926676e-05 1.66079206032021e-06 1.22649396814656e-05 -8.13997791177556e-06 1.73343443346306e-05 5.30685247831822e-06 1.66079206032021e-06 5.26796574899545e-05 1.87456040019255e-05 8.39854874816665e-06 3.95094511720976e-05 -3.44608111689011e-06 1.22649396814656e-05 1.87456040019255e-05 0.000107167914260994 1527 1522 0 14 33 1479 1489 0 21 0 0 0 0 0 0 0 8 0 197 0 106 82 0 0 2320 +355 410 0.991896004928047 -0.00175190146152137 0.127040333158605 -0.0258362262019635 -0.016268264984502 0.989922972766479 0.140669298510976 -0.0224701855939238 -0.126006583011262 -0.141596041012611 0.981872141476364 -0.00392292255102021 8.16060965674902e-05 5.95194653180066e-05 -6.7492358104694e-06 2.05004840889269e-05 -1.71664673090125e-05 5.92417700574381e-05 5.95194653180066e-05 8.8155515400893e-05 -6.90354831079657e-06 3.16964471511003e-05 -1.82251200705274e-05 6.88742929567814e-05 -6.7492358104694e-06 -6.90354831079657e-06 1.11392544932265e-05 3.86176591612941e-06 8.48207857953024e-06 -4.76232619725115e-06 2.05004840889269e-05 3.16964471511003e-05 3.86176591612941e-06 5.58368742766748e-05 -1.48265103549678e-05 4.75028473548658e-05 -1.71664673090125e-05 -1.82251200705274e-05 8.48207857953024e-06 -1.48265103549678e-05 4.89244042366905e-05 -3.4685561960398e-05 5.92417700574381e-05 6.88742929567814e-05 -4.76232619725115e-06 4.75028473548658e-05 -3.4685561960398e-05 0.000145528234062068 1400 1400 0 15 8 1408 1429 0 31 6 0 0 0 0 0 4 13 0 290 0 60 63 0 0 2128 +355 357 0.999838708710494 -0.000409069204125364 0.0179552005424156 -0.00562363765922502 0.000387518029968931 0.99999920042244 0.00120373761939223 -0.0062747485246585 -0.0179556785978301 -0.00119658550305748 0.999838067783591 -0.00681010510202804 4.31395891826758e-05 1.97413148649088e-05 -5.69139877551411e-06 7.24746963044828e-06 8.06066563587492e-07 1.450875606078e-05 1.97413148649088e-05 4.5860251951961e-05 -1.02841359775125e-05 1.16878668802939e-05 4.24200467474634e-06 2.15195515815341e-05 -5.69139877551411e-06 -1.02841359775125e-05 1.46904773440657e-05 1.33315455874671e-06 1.49286675225131e-06 -6.93142968739917e-06 7.24746963044828e-06 1.16878668802939e-05 1.33315455874671e-06 3.54480313306803e-05 -2.75721881206215e-06 1.49455123417571e-05 8.06066563587492e-07 4.24200467474634e-06 1.49286675225131e-06 -2.75721881206215e-06 3.47737969472598e-05 2.18460561846051e-06 1.450875606078e-05 2.15195515815341e-05 -6.93142968739917e-06 1.49455123417571e-05 2.18460561846051e-06 6.46137579253642e-05 2096 2070 0 2 61 2065 2083 0 15 27 0 0 0 0 0 8 18 0 306 0 66 35 0 0 3324 +355 383 0.991024738254216 -0.00211711920085638 0.133661834397304 -0.0230336032770093 -0.0168636156419667 0.989906742173826 0.140713397607631 -0.0263811201740919 -0.132610658077105 -0.14170447983424 0.980986367774428 -0.00953524300084737 6.97500896817902e-05 4.21358742331275e-05 -1.07037545218755e-05 6.93871269511758e-06 -3.89817499723949e-06 3.2804620898728e-06 4.21358742331275e-05 5.91793549525909e-05 -1.03346865515167e-05 1.65705448905358e-05 -4.69257113050236e-06 -1.34728029508148e-06 -1.07037545218755e-05 -1.03346865515167e-05 1.25021205873085e-05 1.50650445182281e-06 3.9235115663824e-06 -8.93502268216228e-07 6.93871269511758e-06 1.65705448905358e-05 1.50650445182281e-06 5.25501669383519e-05 -7.15885794560541e-06 2.14330385515057e-05 -3.89817499723949e-06 -4.69257113050236e-06 3.9235115663824e-06 -7.15885794560541e-06 4.01137053880156e-05 -1.19536627339119e-05 3.2804620898728e-06 -1.34728029508148e-06 -8.93502268216228e-07 2.14330385515057e-05 -1.19536627339119e-05 0.00010075603522613 1702 1698 0 15 20 1662 1684 0 29 7 0 0 0 0 0 2 12 0 421 0 93 78 0 0 2557 +355 411 0.991456314123996 -0.00255636926116129 0.130414117946875 -0.0244716651301518 -0.0162590277700643 0.98958840835393 0.143004986163095 -0.0242628509175046 -0.12942187295675 -0.143903603247922 0.981092111767612 -0.00492958030172622 4.90504001048231e-05 3.44766928933433e-05 -7.60868421281298e-06 -5.71605199338229e-06 4.7288600180215e-06 1.74132260666425e-05 3.44766928933433e-05 5.12491818102644e-05 -9.26780146836485e-06 8.66068608804171e-06 1.2067109801053e-06 1.87560166083773e-05 -7.60868421281298e-06 -9.26780146836485e-06 1.21533924995375e-05 5.64017863782316e-06 4.2090470620149e-06 -6.29081062624769e-06 -5.71605199338229e-06 8.66068608804171e-06 5.64017863782316e-06 5.61357336359923e-05 -1.05800233573822e-05 2.48314575023694e-06 4.7288600180215e-06 1.2067109801053e-06 4.2090470620149e-06 -1.05800233573822e-05 4.2830465991222e-05 3.66495946876038e-06 1.74132260666425e-05 1.87560166083773e-05 -6.29081062624769e-06 2.48314575023694e-06 3.66495946876038e-06 8.7733651613531e-05 1337 1341 0 13 9 1335 1354 0 27 6 0 0 0 0 0 2 11 0 316 0 57 61 0 0 2093 +354 394 0.990679826065234 -0.00310060053362182 0.1361758734273 -0.022271730062512 -0.0165227686103109 0.989622874603288 0.142735994687306 -0.0247851585118756 -0.135205326614032 -0.143655672837015 0.980348186776993 0.00176448923413732 5.46382411869203e-05 1.2774922835195e-05 -4.34074184032379e-06 -1.57909518363388e-06 -8.48694891554608e-06 5.81645650809766e-06 1.2774922835195e-05 5.10667892633909e-05 -2.75626785306175e-06 1.24955036424795e-05 1.9039784777305e-06 1.66663235355923e-05 -4.34074184032379e-06 -2.75626785306175e-06 1.13878210955404e-05 5.40677152090289e-06 7.41766991189868e-06 -2.12207098180102e-07 -1.57909518363388e-06 1.24955036424795e-05 5.40677152090289e-06 5.37511989377145e-05 -6.14232341955975e-06 1.52191280500041e-05 -8.48694891554608e-06 1.9039784777305e-06 7.41766991189868e-06 -6.14232341955975e-06 5.02730530873494e-05 6.84428286657196e-06 5.81645650809766e-06 1.66663235355923e-05 -2.12207098180102e-07 1.52191280500041e-05 6.84428286657196e-06 8.8823399558894e-05 1366 1361 0 12 22 1346 1366 0 19 4 0 0 0 0 0 1 8 0 251 0 109 89 0 0 2253 +355 358 0.999904521761949 -0.000885965648345646 0.0137899392630046 8.92837776104577e-05 0.000843311730646467 0.999994843657165 0.00309862621290587 -0.0115270342053021 -0.0137926134337318 -0.00308670114398929 0.999900113056657 -0.0123380715449915 5.78743076079196e-05 3.76303515494683e-05 -9.62321241273363e-06 1.08606053591979e-05 3.59818304836635e-08 1.1503428206581e-05 3.76303515494683e-05 7.95154461481507e-05 -1.50459630046499e-05 1.96237594220532e-05 1.13809943258784e-05 3.13958073271186e-05 -9.62321241273363e-06 -1.50459630046499e-05 1.51344040278521e-05 -8.68454841485261e-07 6.1636793798049e-07 -5.90187867125625e-06 1.08606053591979e-05 1.96237594220532e-05 -8.68454841485261e-07 4.70604754716024e-05 -1.04573245492081e-05 2.5742650778964e-05 3.59818304836635e-08 1.13809943258784e-05 6.1636793798049e-07 -1.04573245492081e-05 4.58920011464439e-05 3.64507499296412e-06 1.1503428206581e-05 3.13958073271186e-05 -5.90187867125625e-06 2.5742650778964e-05 3.64507499296412e-06 6.8705730559324e-05 1658 1630 0 7 57 1657 1680 0 20 31 0 0 0 0 0 5 19 0 293 0 76 47 0 0 3228 +354 391 0.989545108760612 -0.00216291712592178 0.144207487730195 -0.0186012751606054 -0.0173355654388893 0.990854379999597 0.1338173225204 -0.025967779626636 -0.143178056624826 -0.134918195307828 0.980457609831255 0.00169421511551173 0.000121088265657942 7.02962683246051e-05 -1.45197717126274e-05 2.11424419124879e-05 -3.82605851199089e-05 6.3803823261671e-05 7.02962683246051e-05 0.000120947393813053 -1.07341104008613e-05 2.75204264206807e-05 -2.20152949826079e-05 6.20407195485756e-05 -1.45197717126274e-05 -1.07341104008613e-05 1.36227460740882e-05 2.63934047931298e-06 1.07618715017859e-05 -8.74498708669252e-06 2.11424419124879e-05 2.75204264206807e-05 2.63934047931298e-06 4.95575962656358e-05 -1.2807937967141e-05 3.62489503891287e-05 -3.82605851199089e-05 -2.20152949826079e-05 1.07618715017859e-05 -1.2807937967141e-05 6.75609924221605e-05 -2.86470708500455e-05 6.3803823261671e-05 6.20407195485756e-05 -8.74498708669252e-06 3.62489503891287e-05 -2.86470708500455e-05 0.000135330622997489 1515 1516 0 11 23 1480 1497 0 19 5 0 0 0 0 0 2 8 0 192 0 110 94 0 0 2242 +355 395 0.989562716315391 -0.00106001785255447 0.144098948090047 -0.0127244081488584 -0.0180173538272344 0.991215837501722 0.131021137404709 -0.0323432429418868 -0.142972044258904 -0.132249914358807 0.980851137896326 0.00550981095886476 0.000257866837330717 0.000222710771813731 -3.2228063746668e-05 6.91965665686191e-05 -8.06335070825607e-05 0.000211082425206197 0.000222710771813731 0.000247762747517949 -3.20726926167819e-05 6.62175567718695e-05 -7.13268193959687e-05 0.0001847246815904 -3.2228063746668e-05 -3.20726926167819e-05 1.57587030451209e-05 -2.14388670780237e-06 1.40116973219729e-05 -3.0020806309807e-05 6.91965665686191e-05 6.62175567718695e-05 -2.14388670780237e-06 6.83082712675046e-05 -3.70410584959621e-05 7.60748494049154e-05 -8.06335070825607e-05 -7.13268193959687e-05 1.40116973219729e-05 -3.70410584959621e-05 8.00303748458043e-05 -8.4987228819019e-05 0.000211082425206197 0.0001847246815904 -3.0020806309807e-05 7.60748494049154e-05 -8.4987228819019e-05 0.000272497593802276 1777 1775 0 20 21 1739 1765 0 32 10 0 0 0 0 0 2 12 0 212 0 101 87 0 0 2322 +355 386 0.99138093365916 -0.00181721920029383 0.130998252245861 -0.0195349718706197 -0.0166144774090348 0.990086738231448 0.139471179526944 -0.0279101848292424 -0.129953081985449 -0.140445535680528 0.981522922804095 0.00271081534304967 0.000121927410877942 7.59728591912195e-05 -1.81237775283175e-05 -2.47386588254537e-06 1.26408846894834e-06 5.70004122289743e-05 7.59728591912195e-05 8.82273178091156e-05 -1.60076078673282e-05 1.4154091770789e-05 -1.74735042021031e-06 4.05164301401762e-05 -1.81237775283175e-05 -1.60076078673282e-05 1.44512265856942e-05 1.9521283007196e-06 2.74546511091876e-06 -8.07806467850948e-06 -2.47386588254537e-06 1.4154091770789e-05 1.9521283007196e-06 4.66842513893028e-05 -2.72472688899269e-06 8.39041772555898e-06 1.26408846894834e-06 -1.74735042021031e-06 2.74546511091876e-06 -2.72472688899269e-06 4.17717264205916e-05 -3.44604729203928e-06 5.70004122289743e-05 4.05164301401762e-05 -8.07806467850948e-06 8.39041772555898e-06 -3.44604729203928e-06 9.99209055904021e-05 1426 1419 0 14 21 1420 1442 0 26 10 0 0 0 0 0 1 9 0 403 0 108 92 0 0 2611 +355 387 0.99050486067956 -0.00149220652774626 0.137469612241555 -0.0231760029834594 -0.0176001058148512 0.990336593087908 0.13756332602239 -0.0222685848884734 -0.136346460333486 -0.138676622798202 0.980906946169622 -0.00343689087279424 0.000130845801093695 9.1619656584911e-05 -1.85910674851063e-05 1.0671485137229e-05 -1.43061387268317e-05 8.21906416358188e-05 9.1619656584911e-05 0.000114015495397058 -1.89837488508408e-05 1.11796575127476e-05 -1.13524839480906e-05 5.76771634076702e-05 -1.85910674851063e-05 -1.89837488508408e-05 1.53799489894733e-05 7.85460888497443e-07 5.49771672347486e-06 -1.37767477539131e-05 1.0671485137229e-05 1.11796575127476e-05 7.85460888497443e-07 4.54467557228673e-05 -3.58200844882839e-06 4.10336366582879e-06 -1.43061387268317e-05 -1.13524839480906e-05 5.49771672347486e-06 -3.58200844882839e-06 4.51276588410378e-05 -1.68355691238607e-05 8.21906416358188e-05 5.76771634076702e-05 -1.37767477539131e-05 4.10336366582879e-06 -1.68355691238607e-05 0.000152589223052519 1533 1529 0 16 22 1494 1516 0 32 8 0 0 0 0 0 1 12 0 409 0 100 84 0 0 2576 +355 382 0.990944021067257 -0.00267558723897296 0.134248978930877 -0.019894384195075 -0.0168109769806386 0.989462750571569 0.143808401299439 -0.0274506598157472 -0.133219135877744 -0.144762931941401 0.980457217512175 -0.00445745878251978 6.59545715823327e-05 3.36147404015033e-05 -1.20623583659549e-05 -6.60693572208042e-06 1.07496633394396e-05 2.28969057680878e-05 3.36147404015033e-05 6.25325549771009e-05 -9.94335571636279e-06 7.98892917446661e-06 9.69548418110438e-06 6.28747078380123e-06 -1.20623583659549e-05 -9.94335571636279e-06 1.36003399895254e-05 4.34383214428791e-06 6.00012908246943e-07 -4.65282130922759e-06 -6.60693572208042e-06 7.98892917446661e-06 4.34383214428791e-06 5.74648728458451e-05 -1.40184539252436e-05 3.35707653803307e-06 1.07496633394396e-05 9.69548418110438e-06 6.00012908246943e-07 -1.40184539252436e-05 5.05189839725273e-05 1.07120630935841e-06 2.28969057680878e-05 6.28747078380123e-06 -4.65282130922759e-06 3.35707653803307e-06 1.07120630935841e-06 8.3450366165253e-05 1579 1573 0 13 23 1543 1565 0 26 10 0 0 0 0 0 2 10 0 424 0 100 89 0 0 2630 +355 381 0.991354474553496 -0.00180156115073091 0.131198552431733 -0.0203647575370798 -0.0166272157532101 0.990119984389929 0.139233445005084 -0.0280032080692463 -0.130153146251092 -0.140211165351079 0.981529921923847 -0.00112278447381152 6.83514747064035e-05 4.28288531866702e-05 -1.06843795716391e-05 1.30735251972867e-05 3.31799679705985e-06 3.63616185679138e-05 4.28288531866702e-05 6.30285692194379e-05 -1.23396153875266e-05 1.49344641859431e-05 3.7334036268096e-06 3.49032031450619e-05 -1.06843795716391e-05 -1.23396153875266e-05 1.4422818043449e-05 3.13198661549114e-07 5.56753932970844e-07 -8.13916086922247e-06 1.30735251972867e-05 1.49344641859431e-05 3.13198661549114e-07 6.02104398975372e-05 -2.18060650675354e-05 2.63578303407512e-05 3.31799679705985e-06 3.7334036268096e-06 5.56753932970844e-07 -2.18060650675354e-05 5.47578769270945e-05 -6.69138746667849e-06 3.63616185679138e-05 3.49032031450619e-05 -8.13916086922247e-06 2.63578303407512e-05 -6.69138746667849e-06 0.000125232753072162 1757 1750 0 11 19 1722 1740 0 23 7 0 0 0 0 0 1 10 0 418 0 99 89 0 0 2632 +355 359 0.999716894185365 0.00450665754576975 0.0233628234195468 -0.00641240037824897 -0.00439510216453961 0.999978705527835 -0.00482406134272605 -0.00129618119653476 -0.0233840663130053 0.00472001362712876 0.999715412962123 -0.00419602608955302 6.62112185718574e-05 4.74738972602681e-05 -1.67902352452524e-05 1.87996964048233e-05 6.40872685962394e-06 3.62070700372358e-05 4.74738972602681e-05 6.285551336881e-05 -1.80576412960176e-05 1.83907399787171e-05 1.03200084313062e-05 3.81830278478913e-05 -1.67902352452524e-05 -1.80576412960176e-05 1.8169549888109e-05 -1.41918618575096e-06 7.08392363884784e-08 -1.06969665821465e-05 1.87996964048233e-05 1.83907399787171e-05 -1.41918618575096e-06 4.21478077707178e-05 -1.03646327462076e-05 2.15878187535484e-05 6.40872685962394e-06 1.03200084313062e-05 7.08392363884784e-08 -1.03646327462076e-05 5.40493161770211e-05 5.87332941307564e-06 3.62070700372358e-05 3.81830278478913e-05 -1.06969665821465e-05 2.15878187535484e-05 5.87332941307564e-06 8.15585508210106e-05 2181 2155 0 8 51 2152 2168 0 20 21 0 0 0 0 0 7 19 0 308 0 65 39 0 0 3238 +355 396 0.990474256554375 -0.00256838518649912 0.137674073451004 -0.0150959174097175 -0.0169902436084429 0.989906359837227 0.140700854211823 -0.0330522376063092 -0.136645814883531 -0.14169969001852 0.980433128328226 0.00401260850872443 6.94611692988342e-05 4.23272961691715e-05 -4.87437066797149e-06 8.75687181158852e-06 -1.12442109904088e-05 2.71506084520614e-05 4.23272961691715e-05 8.30206145450018e-05 -7.31571026629463e-06 1.52529776565521e-05 -7.61820062729631e-06 3.17355317786125e-05 -4.87437066797149e-06 -7.31571026629463e-06 1.30064371340601e-05 2.70427744610955e-06 7.91908328377983e-06 -4.14972147713448e-06 8.75687181158852e-06 1.52529776565521e-05 2.70427744610955e-06 4.29674682649676e-05 -5.4390843939157e-06 2.20380920939063e-05 -1.12442109904088e-05 -7.61820062729631e-06 7.91908328377983e-06 -5.4390843939157e-06 4.96764077545535e-05 -6.57752114431001e-06 2.71506084520614e-05 3.17355317786125e-05 -4.14972147713448e-06 2.20380920939063e-05 -6.57752114431001e-06 0.000109399663244312 1361 1359 0 15 22 1366 1386 0 30 10 0 0 0 0 0 2 12 0 247 0 110 99 0 0 2338 +355 409 0.991099869705417 -0.00171732449490973 0.133109350034038 -0.0246256190517428 -0.016683694469708 0.990430418428528 0.137000878064091 -0.0246624763315191 -0.132070824214685 -0.138002308125878 0.981586807339618 0.00348945557538056 7.4496469439414e-05 5.48980692072628e-05 -7.30594241007667e-06 3.71290574160255e-06 -6.12395599368426e-06 3.1970252244076e-05 5.48980692072628e-05 9.44411443813887e-05 -8.70116664786045e-06 1.48397553254425e-05 -3.79920399034603e-06 5.83929764589797e-05 -7.30594241007667e-06 -8.70116664786045e-06 1.25435669475272e-05 4.68225999461094e-06 7.48065660429481e-06 -1.59251043333107e-06 3.71290574160255e-06 1.48397553254425e-05 4.68225999461094e-06 4.82500663663494e-05 -3.90930660953361e-06 2.26275729594882e-05 -6.12395599368426e-06 -3.79920399034603e-06 7.48065660429481e-06 -3.90930660953361e-06 3.42616199509513e-05 -5.4154366775121e-06 3.1970252244076e-05 5.83929764589797e-05 -1.59251043333107e-06 2.26275729594882e-05 -5.4154366775121e-06 0.000122261600202838 1391 1390 0 12 9 1396 1416 0 25 5 0 0 0 0 0 2 11 0 278 0 73 77 0 0 2096 +355 384 0.990343465238176 -0.0010156084338983 0.138631848431557 -0.0195070557466246 -0.0176974059038892 0.990865997216291 0.133683871072165 -0.0262732040188899 -0.137501355209009 -0.134846372216961 0.981279691635168 -0.00458324009934399 0.000131075203554104 8.7357137208819e-05 -2.06716872417413e-05 1.18315595658545e-05 -7.87019461289482e-06 6.33603683800942e-05 8.7357137208819e-05 9.2317765188592e-05 -1.88785645588529e-05 1.26463621325795e-05 -7.85064624024536e-07 3.33394052990282e-05 -2.06716872417413e-05 -1.88785645588529e-05 1.57140375711228e-05 -9.81470928406424e-07 5.66406465146765e-06 -1.2604643693945e-05 1.18315595658545e-05 1.26463621325795e-05 -9.81470928406424e-07 5.07726917587998e-05 -9.85296818482088e-06 1.63795036901327e-05 -7.87019461289482e-06 -7.85064624024536e-07 5.66406465146765e-06 -9.85296818482088e-06 4.93805243733138e-05 -1.49962181941222e-05 6.33603683800942e-05 3.33394052990282e-05 -1.2604643693945e-05 1.63795036901327e-05 -1.49962181941222e-05 0.00013651548059926 1576 1574 0 14 20 1538 1562 0 29 7 0 0 0 0 0 1 13 0 422 0 101 85 0 0 2657 +355 412 0.991286166598606 -0.00254098865830118 0.131701477922153 -0.0237590051088612 -0.0165095738310043 0.989533571972411 0.143355306533939 -0.0248729698540294 -0.130687298090364 -0.144280467549005 0.980868990641299 -0.00257811244799039 8.51245740445024e-05 5.89889578147786e-05 -1.18267198070388e-05 1.1412930772481e-05 5.20804359237929e-06 4.46632640362676e-05 5.89889578147786e-05 8.92297626225006e-05 -1.09227138334989e-05 1.63026447098438e-05 7.49942862347574e-06 5.19575720920766e-05 -1.18267198070388e-05 -1.09227138334989e-05 1.20646240266561e-05 2.24388240240821e-06 2.49756199467544e-06 -5.24741239849637e-06 1.1412930772481e-05 1.63026447098438e-05 2.24388240240821e-06 4.61842220282589e-05 -1.65049474108721e-06 1.3205017355758e-05 5.20804359237929e-06 7.49942862347574e-06 2.49756199467544e-06 -1.65049474108721e-06 3.603270713508e-05 6.73595194395389e-06 4.46632640362676e-05 5.19575720920766e-05 -5.24741239849637e-06 1.3205017355758e-05 6.73595194395389e-06 9.86682857942051e-05 1594 1595 0 12 8 1592 1608 0 26 6 0 0 0 0 0 2 11 0 349 0 60 64 0 0 2086 +355 408 0.990619197577663 -0.00256470568281105 0.136627331362896 -0.0221186946448191 -0.0172141418155904 0.989517083863836 0.143386240843263 -0.0227793294131897 -0.135562822013039 -0.144393085105797 0.980190470399244 -0.00793863900345493 6.72799129873863e-05 3.84210141548756e-05 -6.50291157796842e-06 6.72147693287583e-06 -1.07134458893614e-05 2.44712828612147e-05 3.84210141548756e-05 5.83074705221313e-05 -5.20863598132365e-06 1.4078426888019e-05 -7.99831860734478e-06 1.39133152268179e-05 -6.50291157796842e-06 -5.20863598132365e-06 1.24816384374091e-05 5.39447504315911e-06 8.48888669863044e-06 -4.47218074141106e-06 6.72147693287583e-06 1.4078426888019e-05 5.39447504315911e-06 3.2330827670887e-05 -4.4645819952324e-07 1.25136239407795e-05 -1.07134458893614e-05 -7.99831860734478e-06 8.48888669863044e-06 -4.4645819952324e-07 3.56280310034014e-05 -1.93123122448673e-05 2.44712828612147e-05 1.39133152268179e-05 -4.47218074141106e-06 1.25136239407795e-05 -1.93123122448673e-05 0.000114721746126993 1503 1504 0 14 10 1479 1502 0 29 5 0 0 0 0 0 1 12 0 276 0 51 55 0 0 2154 +355 397 0.990505369701145 -0.00151505592166501 0.137465694625068 -0.0176363301751113 -0.0172291048479127 0.990687269065119 0.13506255165084 -0.0327755117955955 -0.136390140916922 -0.136148593521381 0.981254956646239 0.0065586230917278 0.000110013398193367 6.96427138728212e-05 -1.2998060853346e-05 1.03486052636265e-05 -1.64688989733961e-05 4.29150349552995e-05 6.96427138728212e-05 8.82460110523563e-05 -1.23591131157703e-05 1.41605413259396e-05 -8.29573127338374e-06 3.89632275144529e-05 -1.2998060853346e-05 -1.23591131157703e-05 1.33215525615163e-05 6.10776237328598e-06 5.55344104494686e-06 -7.03509928635186e-06 1.03486052636265e-05 1.41605413259396e-05 6.10776237328598e-06 4.80500881021156e-05 -1.7650063730087e-05 6.99026012317059e-06 -1.64688989733961e-05 -8.29573127338374e-06 5.55344104494686e-06 -1.7650063730087e-05 5.34982783482326e-05 -5.45551838683143e-06 4.29150349552995e-05 3.89632275144529e-05 -7.03509928635186e-06 6.99026012317059e-06 -5.45551838683143e-06 9.9404283225349e-05 1373 1366 0 11 26 1371 1381 0 26 14 0 0 0 0 0 1 13 0 228 0 93 86 0 0 2269 +355 385 0.990827375726839 -0.00164461161935467 0.135123672104066 -0.0206697547888342 -0.0172364606833695 0.99022044261809 0.138442693719624 -0.0280075994659879 -0.134029906861776 -0.139501864768384 0.981109175266834 -0.00255905324363928 9.58251972331878e-05 6.43538963308098e-05 -1.11097331017923e-05 8.74795488328221e-06 -1.67110532428104e-07 2.19295308568786e-05 6.43538963308098e-05 8.38787539471244e-05 -1.36444986859912e-05 1.32619455777326e-05 1.85165158105193e-06 2.72806608502857e-05 -1.11097331017923e-05 -1.36444986859912e-05 1.32554807477341e-05 2.42322886160597e-06 3.101137478614e-06 -3.93265957267805e-06 8.74795488328221e-06 1.32619455777326e-05 2.42322886160597e-06 4.57920555085332e-05 -8.09485772474538e-06 1.58445822443761e-05 -1.67110532428104e-07 1.85165158105193e-06 3.101137478614e-06 -8.09485772474538e-06 4.65228718863992e-05 -3.54884126007706e-06 2.19295308568786e-05 2.72806608502857e-05 -3.93265957267805e-06 1.58445822443761e-05 -3.54884126007706e-06 0.000111486560094757 1894 1884 0 13 23 1854 1873 0 25 6 0 0 0 0 0 2 11 0 410 0 95 85 0 0 2589 +355 388 0.990587578637841 -0.00241365681189632 0.136859136739982 -0.0155909957589302 -0.0167650831189073 0.990177303387876 0.138808644700284 -0.0340493571532602 -0.135849847392019 -0.139796574050683 0.980816872228071 -0.00181463425893339 8.80251499461883e-05 6.6890398502401e-05 -6.1664500905042e-06 1.306896103717e-05 -1.06591328162049e-05 5.80786899711163e-05 6.6890398502401e-05 9.66130636485052e-05 -7.94213499328046e-06 1.25014316699741e-05 -8.36086294103336e-06 6.02981955058569e-05 -6.1664500905042e-06 -7.94213499328046e-06 1.21342702020772e-05 4.17117183468465e-06 5.83037810016098e-06 -6.51014984615491e-06 1.306896103717e-05 1.25014316699741e-05 4.17117183468465e-06 4.37386424977703e-05 -1.26323895445518e-05 1.46777775825896e-05 -1.06591328162049e-05 -8.36086294103336e-06 5.83037810016098e-06 -1.26323895445518e-05 4.31527887260713e-05 -1.04961535256498e-05 5.80786899711163e-05 6.02981955058569e-05 -6.51014984615491e-06 1.46777775825896e-05 -1.04961535256498e-05 0.000126242215622041 1880 1875 0 15 21 1844 1863 0 27 6 0 0 0 0 0 1 12 0 415 0 96 86 0 0 2498 +355 389 0.991353043351028 -0.00229118184502317 0.131201729883442 -0.0230126974652399 -0.016302125096021 0.98995135080468 0.140465525155971 -0.0292055541142421 -0.130205161787113 -0.141389792862646 0.981353933256626 -0.00356350460315416 4.25531545407624e-05 2.67135205548998e-05 -1.54267572127229e-06 1.02774698650311e-06 -3.31652443029664e-06 7.40838138884525e-06 2.67135205548998e-05 6.40671251355166e-05 -3.09635290365213e-06 2.26725936130159e-05 -1.79222302670071e-05 2.23025375677841e-05 -1.54267572127229e-06 -3.09635290365213e-06 1.13015368803403e-05 3.84024029641542e-06 5.67669021427763e-06 1.74891764671357e-06 1.02774698650311e-06 2.26725936130159e-05 3.84024029641542e-06 5.16063416928289e-05 -1.17804476031304e-05 1.31029332081861e-05 -3.31652443029664e-06 -1.79222302670071e-05 5.67669021427763e-06 -1.17804476031304e-05 4.39573614742648e-05 -1.65677259709896e-05 7.40838138884525e-06 2.23025375677841e-05 1.74891764671357e-06 1.31029332081861e-05 -1.65677259709896e-05 9.09310789169721e-05 1700 1692 0 12 26 1690 1701 0 25 17 0 0 0 0 0 2 10 0 292 0 97 86 0 0 2409 +355 413 0.9912652839326 -0.0017864870229682 0.131870941962736 -0.0257531469346377 -0.0168436586617795 0.990004760720962 0.140024515398966 -0.0255387726139776 -0.130803012323524 -0.141022630148309 0.981327259253072 -0.00286402099054122 0.000109829044175167 7.86870017870092e-05 -1.45806546064992e-05 2.18834114250693e-05 -2.28341840588481e-05 6.45523259817192e-05 7.86870017870092e-05 9.96949132305708e-05 -1.65708284822665e-05 2.57619843238482e-05 -1.83869092858107e-05 6.12793425388157e-05 -1.45806546064992e-05 -1.65708284822665e-05 1.36896376523226e-05 3.94922243615644e-07 9.6671646000934e-06 -1.20630325536876e-05 2.18834114250693e-05 2.57619843238482e-05 3.94922243615644e-07 6.18826958632779e-05 -2.21741879521739e-05 2.29502051910211e-05 -2.28341840588481e-05 -1.83869092858107e-05 9.6671646000934e-06 -2.21741879521739e-05 6.20452241051215e-05 -1.56537712366022e-05 6.45523259817192e-05 6.12793425388157e-05 -1.20630325536876e-05 2.29502051910211e-05 -1.56537712366022e-05 0.000130473446998381 1223 1225 0 13 9 1226 1244 0 28 6 0 0 0 0 0 1 11 0 368 0 69 75 0 0 2088 +355 390 0.990720123828221 -0.0020987553652656 0.135901550644985 -0.0180142866536023 -0.0172624652049667 0.989840642854902 0.141129405325901 -0.0291578281464527 -0.134817074352035 -0.14216573770959 0.980618814567947 0.0035284447060867 7.17679300017218e-05 2.71945479813985e-05 -8.84587737446218e-06 4.73300845029374e-06 -1.74408282005478e-06 2.24314646369891e-05 2.71945479813985e-05 5.06665491310976e-05 -7.33034165781414e-06 8.75500179808131e-06 -2.63431525015627e-06 6.67432438407187e-06 -8.84587737446218e-06 -7.33034165781414e-06 1.26467764250371e-05 5.80728723649708e-06 5.96451129697873e-06 -4.75896074088024e-06 4.73300845029374e-06 8.75500179808131e-06 5.80728723649708e-06 3.86982542192601e-05 2.80678871449644e-06 1.73740540384723e-05 -1.74408282005478e-06 -2.63431525015627e-06 5.96451129697873e-06 2.80678871449644e-06 4.46393677165702e-05 -4.37207421290771e-06 2.24314646369891e-05 6.67432438407187e-06 -4.75896074088024e-06 1.73740540384723e-05 -4.37207421290771e-06 8.01502613702853e-05 1579 1570 0 13 28 1567 1580 0 28 16 0 0 0 0 0 1 11 0 198 0 98 87 0 0 2309 +355 394 0.990755939191967 -0.00220605628054325 0.13563849848598 -0.0168020014808199 -0.0169246242636692 0.990045510488794 0.139726319118898 -0.0325464896550022 -0.134596530599335 -0.140730311151043 0.980856132913463 0.0036722970922737 6.85805403793062e-05 5.67306161563446e-05 -3.01686955805984e-06 1.49002922272819e-05 -1.50847331999319e-05 5.01539083559682e-05 5.67306161563446e-05 8.12243659171428e-05 -6.46855397002784e-06 2.18149611799022e-05 -1.60795523557614e-05 5.59386673777763e-05 -3.01686955805984e-06 -6.46855397002784e-06 1.11206980792559e-05 2.21181626217584e-06 5.55779543335303e-06 -5.48190332251894e-06 1.49002922272819e-05 2.18149611799022e-05 2.21181626217584e-06 5.18791415274264e-05 -3.08567435769268e-06 2.88596318072306e-05 -1.50847331999319e-05 -1.60795523557614e-05 5.55779543335303e-06 -3.08567435769268e-06 3.93349047170416e-05 -1.5712803103127e-05 5.01539083559682e-05 5.59386673777763e-05 -5.48190332251894e-06 2.88596318072306e-05 -1.5712803103127e-05 0.000124820596486829 1221 1220 0 13 18 1224 1240 0 22 11 0 0 0 0 0 2 8 0 240 0 108 97 0 0 2288 +355 391 0.990417389656756 -0.00179579060787104 0.138094784121597 -0.0169150993301193 -0.0174426945176024 0.990281845883129 0.137976875317091 -0.0260776233217985 -0.137000535303565 -0.139063441818456 0.980761037397052 -0.00150106202593206 9.33424430412097e-05 5.3004255886431e-05 -7.544115193767e-06 8.7432803226049e-06 -5.97140595555686e-06 2.92617699566588e-05 5.3004255886431e-05 7.18225939031143e-05 -9.36716468190519e-06 1.19838797010242e-05 -4.25876375943392e-06 1.48305365909452e-05 -7.544115193767e-06 -9.36716468190519e-06 1.16832983924148e-05 4.6509149069896e-06 6.73380064935918e-06 -4.50260338395697e-06 8.7432803226049e-06 1.19838797010242e-05 4.6509149069896e-06 4.04836226852114e-05 -7.63147455308365e-07 1.07657077012673e-05 -5.97140595555686e-06 -4.25876375943392e-06 6.73380064935918e-06 -7.63147455308365e-07 3.67924283976325e-05 -1.33860071151916e-05 2.92617699566588e-05 1.48305365909452e-05 -4.50260338395697e-06 1.07657077012673e-05 -1.33860071151916e-05 0.000116119801523035 1563 1560 0 13 19 1527 1546 0 20 8 0 0 0 0 0 1 6 0 185 0 94 82 0 0 2245 +356 359 0.999936530270136 0.00581526119789177 0.00964977556843917 -0.00150384451095992 -0.00583168211533358 0.999981593723958 0.00167442437822176 -0.00485197064773399 -0.00963986073689083 -0.00173059252655825 0.999952037917059 -1.48081944195385e-06 6.84008014096616e-05 3.39748991864694e-05 -1.19356545796619e-05 2.05784248216542e-06 5.50526157777557e-06 1.77674407378481e-05 3.39748991864694e-05 7.03101391728331e-05 -1.26211365124727e-05 2.11781523990164e-05 3.23578937677742e-06 3.24803742608223e-05 -1.19356545796619e-05 -1.26211365124727e-05 1.43968731152895e-05 1.9632208081516e-06 2.72789865458228e-07 -6.16772056347468e-06 2.05784248216542e-06 2.11781523990164e-05 1.9632208081516e-06 5.00032770377288e-05 -1.11633775623866e-05 3.06860442868322e-05 5.50526157777557e-06 3.23578937677742e-06 2.72789865458228e-07 -1.11633775623866e-05 4.27819667345748e-05 -7.93624811606862e-07 1.77674407378481e-05 3.24803742608223e-05 -6.16772056347468e-06 3.06860442868322e-05 -7.93624811606862e-07 8.30158632190084e-05 2098 2083 0 9 47 2062 2078 0 23 15 0 0 0 0 0 5 14 0 277 0 81 56 0 0 3274 +356 384 0.992454069989722 0.00165714375128902 0.122605761836151 -0.0291762626437623 -0.0184462121556849 0.990546996616284 0.135927865986218 -0.0143716450558716 -0.121221517140906 -0.137163775717379 0.983102966333135 -0.00188878545030937 9.78245636130749e-05 5.89290260192315e-05 -9.33875175385641e-06 1.72718185046228e-05 -1.86632541440138e-05 1.77384828413258e-05 5.89290260192315e-05 8.4600030067625e-05 -1.04253168054809e-05 2.51669932684971e-05 -1.6972854256631e-05 1.46015610603894e-05 -9.33875175385641e-06 -1.04253168054809e-05 1.25258049596449e-05 -1.81958918731532e-06 6.63601492133914e-06 -2.77208641456757e-06 1.72718185046228e-05 2.51669932684971e-05 -1.81958918731532e-06 6.56427947177165e-05 -2.49440196371312e-05 2.60337114669514e-06 -1.86632541440138e-05 -1.6972854256631e-05 6.63601492133914e-06 -2.49440196371312e-05 5.66415778610911e-05 -1.12398094279541e-06 1.77384828413258e-05 1.46015610603894e-05 -2.77208641456757e-06 2.60337114669514e-06 -1.12398094279541e-06 0.000104610934155385 1726 1732 0 15 14 1691 1704 0 25 4 0 0 0 0 0 4 12 0 436 0 116 97 0 0 2630 +356 411 0.993817555718551 0.0012049811539194 0.111018980206193 -0.0340126466033428 -0.017389677364851 0.989288938358945 0.144931002762619 -0.0140438235746773 -0.10965520993893 -0.145965559160546 0.983193668852784 -0.0064300212433569 0.000128475707845274 7.16462465500917e-05 -1.35204100329019e-05 2.275324561199e-05 -4.0172234764537e-05 4.86853482086824e-05 7.16462465500917e-05 7.85432364955163e-05 -1.11001247882852e-05 2.67927218944505e-05 -2.48114507714663e-05 3.7025979702023e-05 -1.35204100329019e-05 -1.11001247882852e-05 1.31330403336564e-05 3.31872232728729e-06 9.28120572500034e-06 -5.80300230372631e-06 2.275324561199e-05 2.67927218944505e-05 3.31872232728729e-06 5.39947423030161e-05 -1.61141540063827e-05 1.95292038494781e-05 -4.0172234764537e-05 -2.48114507714663e-05 9.28120572500034e-06 -1.61141540063827e-05 5.79778328223497e-05 -1.35337951364381e-05 4.86853482086824e-05 3.7025979702023e-05 -5.80300230372631e-06 1.95292038494781e-05 -1.35337951364381e-05 9.64780321789581e-05 1372 1377 0 17 5 1352 1365 0 27 3 0 0 0 0 0 4 17 0 317 0 52 60 0 0 2082 +356 385 0.992956282012221 0.00104048831139487 0.118476746227018 -0.0253295113473026 -0.0180299713423697 0.989642326975451 0.142418344295979 -0.0238016264007579 -0.117101418206018 -0.143551321981682 0.982690325489903 -0.00348918838627841 0.000107214600003498 3.58125470098129e-05 -1.56207796237146e-05 4.13944374897819e-06 -6.90185709814514e-06 4.29666487621946e-05 3.58125470098129e-05 6.39678513979639e-05 -9.97102502569075e-06 1.17040713127745e-05 5.7753743050006e-06 1.79595549654806e-05 -1.56207796237146e-05 -9.97102502569075e-06 1.31960220095891e-05 1.02116635565912e-06 2.95684818835754e-06 -6.5603910918911e-06 4.13944374897819e-06 1.17040713127745e-05 1.02116635565912e-06 4.41907817965808e-05 -5.73024851474717e-07 1.63080592280495e-06 -6.90185709814514e-06 5.7753743050006e-06 2.95684818835754e-06 -5.73024851474717e-07 4.24804975483656e-05 -5.37185423865208e-06 4.29666487621946e-05 1.79595549654806e-05 -6.5603910918911e-06 1.63080592280495e-06 -5.37185423865208e-06 9.30875000973572e-05 1763 1762 0 18 5 1730 1738 0 25 2 0 0 0 0 0 0 9 0 414 0 125 108 0 0 2575 +356 382 0.992733178574734 0.000792482504842804 0.120333736451527 -0.0263909012412667 -0.0182789154517874 0.989367725798731 0.144282307985956 -0.0171942974203476 -0.118939973965074 -0.145433404413592 0.982192652932132 -0.00391893586786286 9.19922253124988e-05 3.5890037102473e-05 -1.18471638744537e-05 2.59145647690378e-06 3.65174403305412e-06 3.23604816381681e-05 3.5890037102473e-05 5.30023257312448e-05 -8.64433330808204e-06 1.25958045682264e-05 1.33509701369265e-06 1.66328691684032e-05 -1.18471638744537e-05 -8.64433330808204e-06 1.27012650654656e-05 2.45584290644286e-06 2.21014869973121e-06 -4.33082275450681e-06 2.59145647690378e-06 1.25958045682264e-05 2.45584290644286e-06 5.9091433129703e-05 -1.2481667046287e-05 1.17964104698438e-05 3.65174403305412e-06 1.33509701369265e-06 2.21014869973121e-06 -1.2481667046287e-05 4.51191121907913e-05 -3.68303358200231e-06 3.23604816381681e-05 1.66328691684032e-05 -4.33082275450681e-06 1.17964104698438e-05 -3.68303358200231e-06 8.40001455619274e-05 1700 1706 0 19 8 1671 1682 0 29 5 0 0 0 0 0 4 15 0 433 0 123 107 0 0 2606 +356 386 0.992833672724936 0.000866488700929232 0.119501244766931 -0.0262342196191814 -0.0181550550809727 0.989460504798161 0.143660375259062 -0.0166728464420757 -0.118117281879163 -0.144800409674485 0.98238543814512 0.00461488669919894 0.000102979988531063 6.73371063378564e-05 -1.35192139537716e-05 -3.24830404615357e-06 -5.15933722904385e-06 6.47457168423151e-05 6.73371063378564e-05 0.000105562740438163 -1.4176009919087e-05 2.10066886244627e-05 3.48784213190352e-06 5.50859766978859e-05 -1.35192139537716e-05 -1.4176009919087e-05 1.33379865633696e-05 3.3781464739213e-06 2.17997397463421e-06 -9.77600853712373e-06 -3.24830404615357e-06 2.10066886244627e-05 3.3781464739213e-06 5.26461384341309e-05 7.89852861554002e-06 4.85404218606284e-06 -5.15933722904385e-06 3.48784213190352e-06 2.17997397463421e-06 7.89852861554002e-06 4.20555892513083e-05 -6.02809655409203e-06 6.47457168423151e-05 5.50859766978859e-05 -9.77600853712373e-06 4.85404218606284e-06 -6.02809655409203e-06 0.000112335247805032 1445 1446 0 17 16 1416 1438 0 26 6 0 0 0 0 0 4 14 0 411 0 99 77 0 0 2580 +356 410 0.993074248748906 0.00219585691565138 0.11746793044998 -0.0339635051163702 -0.0184509668551166 0.990333790749129 0.137471977953954 -0.0128421991303214 -0.116030592060485 -0.138687278121921 0.983515500942017 0.00310626188543306 8.81107375344296e-05 6.21218339131859e-05 -8.65991437662863e-06 1.36674193878712e-05 -1.55391188969837e-05 6.36809052946771e-05 6.21218339131859e-05 0.000102040187791535 -6.93422184116393e-06 3.30469337869795e-05 -1.82991233208325e-05 6.86903939567193e-05 -8.65991437662863e-06 -6.93422184116393e-06 1.1280103287416e-05 5.15762616399021e-06 6.42514309124671e-06 -5.91588921506973e-06 1.36674193878712e-05 3.30469337869795e-05 5.15762616399021e-06 7.03013721199636e-05 -2.66173065716974e-05 3.01836280787891e-05 -1.55391188969837e-05 -1.82991233208325e-05 6.42514309124671e-06 -2.66173065716974e-05 5.73759821343916e-05 -1.67372310833291e-05 6.36809052946771e-05 6.86903939567193e-05 -5.91588921506973e-06 3.01836280787891e-05 -1.67372310833291e-05 0.000150077966116867 1456 1458 0 15 4 1435 1452 0 28 3 0 0 0 0 0 3 17 0 294 0 49 56 0 0 2092 +356 395 0.990864400238426 0.00260496480433545 0.134836769831203 -0.0185424430992112 -0.0200064275573239 0.991590067068027 0.127862745740967 -0.0244414619802839 -0.133369723687718 -0.129392244939153 0.982583413127388 0.0117574788374679 0.000118496495347961 9.61016266675237e-05 -1.01093454794331e-05 2.75367146867689e-05 -1.88708006638606e-05 6.42324564058036e-05 9.61016266675237e-05 0.000165178938307475 -1.57935583923337e-05 5.46572636143637e-05 -2.58734753968261e-05 9.32435193784828e-05 -1.01093454794331e-05 -1.57935583923337e-05 1.38943259440397e-05 -1.46110079794655e-06 7.86200037095862e-06 -8.88990829565228e-06 2.75367146867689e-05 5.46572636143637e-05 -1.46110079794655e-06 7.57207907450978e-05 -3.17104905850659e-05 5.30058766635665e-05 -1.88708006638606e-05 -2.58734753968261e-05 7.86200037095862e-06 -3.17104905850659e-05 6.05852195653451e-05 -3.48271037936891e-05 6.42324564058036e-05 9.32435193784828e-05 -8.88990829565228e-06 5.30058766635665e-05 -3.48271037936891e-05 0.000203143590451726 1759 1765 0 21 20 1715 1730 0 27 4 0 0 0 0 0 5 16 0 229 0 118 103 0 0 2286 +356 387 0.992808392944988 0.000968322983512214 0.119710305523748 -0.0319387727460507 -0.017805635442418 0.990039220451421 0.139661380898348 -0.0166605648901504 -0.1183826602357 -0.140788509185023 0.98293648901492 -0.00291506940878663 0.000108154074105436 5.79414883629386e-05 -1.25424141207029e-05 1.92202182580582e-06 5.333820231807e-06 4.9526410913205e-05 5.79414883629386e-05 7.71875654229723e-05 -9.85578098065399e-06 1.53363148107145e-05 -5.07971140997431e-06 3.45097004126561e-05 -1.25424141207029e-05 -9.85578098065399e-06 1.53789641623574e-05 1.03095022118717e-06 -1.41541390624299e-07 -1.30651761338561e-06 1.92202182580582e-06 1.53363148107145e-05 1.03095022118717e-06 5.98253873043695e-05 -1.19055434881987e-05 1.16223885735022e-05 5.333820231807e-06 -5.07971140997431e-06 -1.41541390624299e-07 -1.19055434881987e-05 4.99885564016871e-05 -1.44997048816967e-05 4.9526410913205e-05 3.45097004126561e-05 -1.30651761338561e-06 1.16223885735022e-05 -1.44997048816967e-05 0.000131047993449536 1688 1692 0 12 9 1660 1675 0 25 4 0 0 0 0 0 3 16 0 424 0 113 93 0 0 2554 +356 388 0.993140646012634 0.00048705031517298 0.116924847742461 -0.0262917267230928 -0.0176146100249721 0.989202152012 0.145495113211734 -0.0229084333790863 -0.115591447569772 -0.146556696321995 0.982425443487651 -0.00555719342700442 7.63852314625857e-05 3.30617280532923e-05 -7.14547340527611e-06 6.40556244665144e-06 -1.83353150216283e-05 2.16918117957962e-05 3.30617280532923e-05 5.437381656584e-05 -2.90889813083607e-06 1.00773057670538e-05 -1.1938969050582e-05 1.62369806512519e-05 -7.14547340527611e-06 -2.90889813083607e-06 1.24596383637603e-05 3.1666261499152e-06 7.96773149386864e-06 -2.40500346670798e-06 6.40556244665144e-06 1.00773057670538e-05 3.1666261499152e-06 4.18206097136759e-05 -1.3638115755714e-05 1.35071042583787e-05 -1.83353150216283e-05 -1.1938969050582e-05 7.96773149386864e-06 -1.3638115755714e-05 4.29286910229013e-05 -1.51174171278628e-05 2.16918117957962e-05 1.62369806512519e-05 -2.40500346670798e-06 1.35071042583787e-05 -1.51174171278628e-05 7.73593864198849e-05 1752 1755 0 18 6 1719 1728 0 26 3 0 0 0 0 0 4 12 0 426 0 123 106 0 0 2473 +356 358 0.999903141252821 0.0020357170636749 0.0137682231525235 0.00198252555463248 -0.00207893793349345 0.999992954320728 0.00312559209911363 -0.00574478573463153 -0.0137617633248687 -0.0031539126395673 0.999900328385411 0.00148354746520408 4.6584677729096e-05 2.62978823359208e-05 -6.7829835661451e-06 9.80723740201878e-06 1.51515587145742e-06 1.6424598704292e-05 2.62978823359208e-05 7.95096375954805e-05 -1.49442273391951e-05 2.82298355997981e-05 1.14930840931272e-05 4.63726040138633e-05 -6.7829835661451e-06 -1.49442273391951e-05 1.45443722793745e-05 -2.7205045856677e-06 -1.00569444783968e-06 -1.16950238303031e-05 9.80723740201878e-06 2.82298355997981e-05 -2.7205045856677e-06 4.50270252566563e-05 -1.00449364924561e-05 2.43626806648428e-05 1.51515587145742e-06 1.14930840931272e-05 -1.00569444783968e-06 -1.00449364924561e-05 4.33702615042532e-05 1.21088831643948e-05 1.6424598704292e-05 4.63726040138633e-05 -1.16950238303031e-05 2.43626806648428e-05 1.21088831643948e-05 8.03422916633203e-05 2050 2027 0 6 43 2018 2030 0 20 6 0 0 0 0 0 8 21 0 306 0 74 51 0 0 3290 +356 360 0.999254738496652 0.00723290237870314 0.0379163911147638 -0.00470896390241762 -0.00757711836465455 0.999931307463402 0.00894246229059641 0.000498100227791171 -0.0378491065849064 -0.00922309480114319 0.999240901711401 -0.00287608108968586 7.15323503015978e-05 5.42526701010274e-05 -1.29515872023339e-05 1.80098765997506e-05 -2.45755602018363e-06 3.9171368657384e-05 5.42526701010274e-05 0.000105880955167476 -1.67951984801979e-05 3.37948288387134e-05 -7.51679629652177e-06 4.80932609376834e-05 -1.29515872023339e-05 -1.67951984801979e-05 1.61070054613514e-05 -3.25943983812736e-06 1.59301586042772e-06 -1.05995313967691e-05 1.80098765997506e-05 3.37948288387134e-05 -3.25943983812736e-06 5.7209205903695e-05 -2.28667757885982e-05 3.9619968097725e-05 -2.45755602018363e-06 -7.51679629652177e-06 1.59301586042772e-06 -2.28667757885982e-05 5.07395393613285e-05 -1.53969292065831e-05 3.9171368657384e-05 4.80932609376834e-05 -1.05995313967691e-05 3.9619968097725e-05 -1.53969292065831e-05 9.99356915953482e-05 1791 1779 0 11 42 1754 1779 0 22 12 0 0 0 0 0 5 19 0 309 0 79 51 0 0 3228 +356 389 0.993363606661539 0.00119828053866646 0.115010039058034 -0.0302462884115082 -0.0177747949740879 0.98953205257354 0.143214432209979 -0.020551784425401 -0.113634508948686 -0.144308284770307 0.982986427842543 -0.0017792781323027 6.87088745966341e-05 3.15444656546478e-05 -1.9861321698532e-06 5.8311842413327e-06 -1.70932131739101e-05 3.8350374514901e-06 3.15444656546478e-05 6.53204045054043e-05 -3.70051450914961e-06 1.83300736614053e-05 -1.80142092626804e-05 4.3048796126666e-06 -1.9861321698532e-06 -3.70051450914961e-06 1.00271413185531e-05 5.27343181117478e-06 5.34544863201628e-06 -5.97713961827546e-07 5.8311842413327e-06 1.83300736614053e-05 5.27343181117478e-06 5.58599722498491e-05 -2.54587038887737e-05 -1.71766018150421e-06 -1.70932131739101e-05 -1.80142092626804e-05 5.34544863201628e-06 -2.54587038887737e-05 6.23206824305713e-05 -4.09754851465562e-07 3.8350374514901e-06 4.3048796126666e-06 -5.97713961827546e-07 -1.71766018150421e-06 -4.09754851465562e-07 6.73284140187582e-05 1512 1514 0 14 5 1479 1487 0 26 2 0 0 0 0 0 1 12 0 290 0 97 86 0 0 2370 +356 383 0.992690461133345 0.0016163443279873 0.120677403874461 -0.0284887006525882 -0.0179603821335188 0.990754650911012 0.134471730753408 -0.0214130675086886 -0.119344346529211 -0.135656216699466 0.983541721444649 -0.00461495771691118 0.000115915110039366 6.10082038819449e-05 -1.37376920859794e-05 1.3209355034486e-06 -6.59761665741489e-06 1.65351096957274e-05 6.10082038819449e-05 7.43514883079945e-05 -1.22795888708592e-05 1.05790008944095e-05 -8.71809178545569e-06 4.41229895210001e-06 -1.37376920859794e-05 -1.22795888708592e-05 1.41949857089743e-05 -4.74973726009409e-07 4.01592097867032e-06 -7.5520994999938e-07 1.3209355034486e-06 1.05790008944095e-05 -4.74973726009409e-07 6.53423068335566e-05 -2.16154295628543e-05 3.46100426606852e-06 -6.59761665741489e-06 -8.71809178545569e-06 4.01592097867032e-06 -2.16154295628543e-05 5.90536500948792e-05 -6.8869259699205e-06 1.65351096957274e-05 4.41229895210001e-06 -7.5520994999938e-07 3.46100426606852e-06 -6.8869259699205e-06 0.00010893009262718 1735 1742 0 17 14 1699 1714 0 27 4 0 0 0 0 0 1 15 0 418 0 119 99 0 0 2529 +356 396 0.992203197267073 0.0015329333516192 0.124621288102546 -0.0192848525544175 -0.0188737268069116 0.990240232751972 0.138087160430423 -0.0317604388149531 -0.123193334922862 -0.13936259022657 0.982548457164289 0.00712503000135756 9.64740925479487e-05 4.46846889961809e-05 -8.52268929258451e-06 6.78130257034607e-06 -1.90175849145518e-05 3.57508172114215e-05 4.46846889961809e-05 9.31667356103331e-05 -7.35033191121071e-06 2.61438840661238e-05 -1.12732481566103e-05 2.61933977535843e-05 -8.52268929258451e-06 -7.35033191121071e-06 1.27217391665073e-05 4.28966227135407e-06 8.56422972873808e-06 -5.16359113561381e-06 6.78130257034607e-06 2.61438840661238e-05 4.28966227135407e-06 5.7824054152803e-05 -5.52786410119786e-06 1.32399155102752e-05 -1.90175849145518e-05 -1.12732481566103e-05 8.56422972873808e-06 -5.52786410119786e-06 5.0691901037065e-05 -2.16728524351105e-06 3.57508172114215e-05 2.61933977535843e-05 -5.16359113561381e-06 1.32399155102752e-05 -2.16728524351105e-06 0.000111900660652774 1532 1536 0 18 14 1509 1530 0 27 4 0 0 0 0 0 2 12 0 240 0 105 89 0 0 2308 +356 397 0.993611435000145 0.00148325412489502 0.112845541312687 -0.029522015079016 -0.0177326923758701 0.989544925406501 0.143130682326838 -0.0240930894587084 -0.111453433585759 -0.144217337929406 0.983249455419376 -0.00160747411405634 7.71935525950803e-05 3.22533271204676e-05 -9.39148829912486e-06 6.19433803450531e-06 -1.02538311538203e-05 1.36581891382592e-05 3.22533271204676e-05 7.87396448780946e-05 -5.6648508411413e-06 2.86620590015259e-05 -7.28226239143173e-06 3.76413357657446e-05 -9.39148829912486e-06 -5.6648508411413e-06 1.20269628793037e-05 4.13388568048791e-06 5.69534122585493e-06 6.9916058096012e-08 6.19433803450531e-06 2.86620590015259e-05 4.13388568048791e-06 8.16035171067686e-05 -3.26315446850324e-05 1.73363899174664e-05 -1.02538311538203e-05 -7.28226239143173e-06 5.69534122585493e-06 -3.26315446850324e-05 6.23382283654968e-05 -1.93141004474438e-06 1.36581891382592e-05 3.76413357657446e-05 6.9916058096012e-08 1.73363899174664e-05 -1.93141004474438e-06 8.2333771970579e-05 1432 1435 0 17 9 1402 1416 0 27 3 0 0 0 0 0 2 13 0 243 0 94 86 0 0 2225 +356 409 0.993843573715104 0.00170168321235437 0.110779308805549 -0.0411854965554766 -0.0175808191358816 0.98963542124431 0.142522446713171 -0.0112939602555526 -0.109388599879977 -0.143592608768147 0.98357272070928 -0.00358912366240983 8.21985207226695e-05 2.72201641707352e-05 -8.77590084463152e-06 -4.33397565145851e-06 -1.08957712756282e-06 -2.35505251134966e-06 2.72201641707352e-05 5.92031453571787e-05 -4.89409920019289e-06 1.38297063744876e-05 -5.92403557679881e-06 1.41461566528461e-05 -8.77590084463152e-06 -4.89409920019289e-06 1.14654874863212e-05 5.10438230363918e-06 5.21956196523628e-06 1.07044712581253e-06 -4.33397565145851e-06 1.38297063744876e-05 5.10438230363918e-06 6.78906373611765e-05 -1.64689808165709e-05 2.82413444898648e-06 -1.08957712756282e-06 -5.92403557679881e-06 5.21956196523628e-06 -1.64689808165709e-05 4.65389643228477e-05 5.64619691836348e-06 -2.35505251134966e-06 1.41461566528461e-05 1.07044712581253e-06 2.82413444898648e-06 5.64619691836348e-06 9.14247157050576e-05 1566 1567 0 16 7 1542 1562 0 30 3 0 0 0 0 0 2 16 0 284 0 51 55 0 0 2057 +356 408 0.991812787202371 0.0020379135728389 0.127684149564984 -0.0244944415513868 -0.0191810747983018 0.990906577408479 0.133177480146589 -0.021924451475637 -0.126251659440364 -0.134536247000141 0.982832903769339 0.0019113058415998 0.000187846277598049 0.00014730897597408 -2.04401397246332e-05 5.53458666338297e-05 -6.23659409609687e-05 0.000133453075973345 0.00014730897597408 0.000168106995578192 -2.05209555182356e-05 6.31925301584821e-05 -5.73046663546959e-05 0.000127029472300026 -2.04401397246332e-05 -2.05209555182356e-05 1.35552302823557e-05 -2.1286367199905e-06 1.41623570953835e-05 -1.81715514982446e-05 5.53458666338297e-05 6.31925301584821e-05 -2.1286367199905e-06 7.72230009062143e-05 -3.85373461161606e-05 5.98368322149356e-05 -6.23659409609687e-05 -5.73046663546959e-05 1.41623570953835e-05 -3.85373461161606e-05 7.8492761282228e-05 -6.34907921459785e-05 0.000133453075973345 0.000127029472300026 -1.81715514982446e-05 5.98368322149356e-05 -6.34907921459785e-05 0.000244992383130513 1682 1688 0 16 8 1654 1668 0 26 2 0 0 0 0 0 5 15 0 272 0 68 72 0 0 2114 +356 412 0.992901708941292 0.0006242017319865 0.118936145698689 -0.0304328297128489 -0.018129405999813 0.98909530504957 0.14615677256628 -0.0154155372598882 -0.117547952000687 -0.147275550927828 0.982085735096152 -0.00115898729379534 9.86344498179448e-05 6.80435338442745e-05 -1.51966270889088e-05 8.7144698333888e-06 6.95472724500966e-06 3.25467404592475e-05 6.80435338442745e-05 9.48377958739886e-05 -1.34326931286138e-05 2.19987481881954e-05 5.05612558190305e-06 4.56281788880702e-05 -1.51966270889088e-05 -1.34326931286138e-05 1.32898802339219e-05 4.16858329262679e-06 1.0851704635925e-06 -3.11966045530983e-06 8.7144698333888e-06 2.19987481881954e-05 4.16858329262679e-06 5.64770396978469e-05 -1.17363741303903e-05 2.33800546743969e-05 6.95472724500966e-06 5.05612558190305e-06 1.0851704635925e-06 -1.17363741303903e-05 4.75982970503448e-05 -2.86872493329643e-06 3.25467404592475e-05 4.56281788880702e-05 -3.11966045530983e-06 2.33800546743969e-05 -2.86872493329643e-06 0.000102138531300086 1500 1501 0 13 4 1464 1476 0 25 2 0 0 0 0 0 2 14 0 345 0 51 59 0 0 2043 +356 390 0.99232853122813 0.0012392154420506 0.123622613043532 -0.0217916577117541 -0.0187782039479496 0.98985830704376 0.140811615404947 -0.0236089254152002 -0.122194374531366 -0.142052794134961 0.982287910193004 0.0113222011381954 7.17743364069806e-05 2.1609673424844e-05 -6.04523940987552e-06 -4.76464807465341e-06 -3.10296080094016e-06 1.53656045075603e-05 2.1609673424844e-05 9.36559469710744e-05 -4.02326964128456e-06 2.80378554458826e-05 3.67579826690516e-06 3.83291579202577e-05 -6.04523940987552e-06 -4.02326964128456e-06 1.23756530565023e-05 6.23295399513537e-06 4.20057533056327e-06 -1.99192919565864e-06 -4.76464807465341e-06 2.80378554458826e-05 6.23295399513537e-06 5.96604965593043e-05 -4.85545354798013e-06 2.42870126668146e-05 -3.10296080094016e-06 3.67579826690516e-06 4.20057533056327e-06 -4.85545354798013e-06 4.6733512134121e-05 4.98483303873858e-06 1.53656045075603e-05 3.83291579202577e-05 -1.99192919565864e-06 2.42870126668146e-05 4.98483303873858e-06 0.000102819421585581 1497 1501 0 18 4 1459 1468 0 24 1 0 0 0 0 0 2 13 0 198 0 99 85 0 0 2305 +356 413 0.993428335713578 0.00180406123138484 0.114441632129323 -0.0302373008242949 -0.0179962455058794 0.989900870303389 0.14061437380398 -0.0222174961958561 -0.113032194303402 -0.141749823053388 0.983428040435746 -0.0039521558258395 7.20722545384699e-05 4.50613991162128e-05 -1.18307197656965e-05 6.35925484757124e-06 4.74865400229363e-06 1.93659615326213e-05 4.50613991162128e-05 5.9246545190145e-05 -1.15000425613271e-05 1.2216210236518e-05 9.39005659499356e-06 2.8565971073873e-05 -1.18307197656965e-05 -1.15000425613271e-05 1.30226086583897e-05 3.06265157936037e-06 5.31256248468375e-07 -3.99195765388753e-06 6.35925484757124e-06 1.2216210236518e-05 3.06265157936037e-06 4.83813463934961e-05 5.88576032438356e-06 2.76221147697371e-06 4.74865400229363e-06 9.39005659499356e-06 5.31256248468375e-07 5.88576032438356e-06 4.36262142758859e-05 1.28256143624609e-05 1.93659615326213e-05 2.8565971073873e-05 -3.99195765388753e-06 2.76221147697371e-06 1.28256143624609e-05 0.000105206359418803 1524 1526 0 16 3 1506 1524 0 25 1 0 0 0 0 0 1 13 0 377 0 58 67 0 0 2037 +356 391 0.991309163812926 0.00190323073615299 0.131539041555281 -0.0177373989959871 -0.0191845787468429 0.991297338040736 0.130236475427036 -0.024176806913105 -0.130146431679179 -0.131628132654519 0.982718647943073 0.00919286737082848 6.05699022528013e-05 3.47001572478538e-05 -1.33484712293887e-06 1.23080988061273e-05 -1.18062441039565e-05 -1.00966930044848e-05 3.47001572478538e-05 7.42967654506554e-05 -8.43572540828525e-06 2.42650911495795e-05 -1.40454232075211e-05 -1.66018807545849e-05 -1.33484712293887e-06 -8.43572540828525e-06 1.24725274662448e-05 1.11730305939871e-06 9.19386601897357e-06 1.49128994271416e-06 1.23080988061273e-05 2.42650911495795e-05 1.11730305939871e-06 6.30491805175628e-05 -1.93618431867611e-05 1.00622485871301e-05 -1.18062441039565e-05 -1.40454232075211e-05 9.19386601897357e-06 -1.93618431867611e-05 4.86242929799719e-05 -1.30523219796592e-06 -1.00966930044848e-05 -1.66018807545849e-05 1.49128994271416e-06 1.00622485871301e-05 -1.30523219796592e-06 6.99592288056441e-05 1761 1768 0 19 20 1717 1729 0 25 6 0 0 0 0 0 2 11 0 193 0 118 102 0 0 2232 +357 359 0.999972386353123 0.00471599191670216 0.00574333974989392 0.00674722420385934 -0.00468299809540098 0.9999725337567 -0.00574467240530956 -0.00507415867594997 -0.00577027383055454 0.00571761772484434 0.99996700584943 0.00450364771443256 4.8751402175964e-05 3.51865982792521e-05 -1.3283917508667e-05 1.13179754796089e-05 1.12788188776901e-05 3.77296852912543e-05 3.51865982792521e-05 5.24145431003771e-05 -1.41947076869883e-05 1.20573061314895e-05 1.22429334128137e-05 4.0271938512458e-05 -1.3283917508667e-05 -1.41947076869883e-05 1.40612114289413e-05 -1.75548920626522e-06 -2.00955154582603e-06 -1.30559720804496e-05 1.13179754796089e-05 1.20573061314895e-05 -1.75548920626522e-06 3.22486542843193e-05 -1.99658962605925e-06 1.89356176230544e-05 1.12788188776901e-05 1.22429334128137e-05 -2.00955154582603e-06 -1.99658962605925e-06 3.07421129810964e-05 7.47405126872698e-06 3.77296852912543e-05 4.0271938512458e-05 -1.30559720804496e-05 1.89356176230544e-05 7.47405126872698e-06 8.27265801799026e-05 2196 2169 0 13 58 2167 2185 0 27 28 0 0 0 0 0 3 15 0 304 0 78 48 0 0 3328 +356 394 0.992628959402288 0.000796579043467667 0.121190405634098 -0.020592682142465 -0.0181298689240172 0.989702012881868 0.141990258646069 -0.0284855804635237 -0.119829281933623 -0.143140808854104 0.982421321038924 0.00832875130346537 0.000118192405607746 7.624660870315e-05 -1.01397314637701e-05 1.41633417361435e-05 -3.26633716342572e-05 5.25747579219395e-05 7.624660870315e-05 9.35148212998314e-05 -1.12250693021255e-05 1.87643876853585e-05 -1.88369118463934e-05 5.09164330501428e-05 -1.01397314637701e-05 -1.12250693021255e-05 1.16037989147422e-05 3.92279387427853e-06 8.78185465760835e-06 -7.31562676423601e-06 1.41633417361435e-05 1.87643876853585e-05 3.92279387427853e-06 4.87955217407384e-05 -8.45081833804162e-06 2.28387010036015e-05 -3.26633716342572e-05 -1.88369118463934e-05 8.78185465760835e-06 -8.45081833804162e-06 5.84270426678419e-05 -1.58837656127328e-05 5.25747579219395e-05 5.09164330501428e-05 -7.31562676423601e-06 2.28387010036015e-05 -1.58837656127328e-05 0.000121030866707988 1534 1536 0 19 15 1511 1528 0 18 6 0 0 0 0 0 2 9 0 235 0 104 85 0 0 2264 +357 385 0.994021131529222 0.000262978019195485 0.109187549271548 -0.0172566314675529 -0.0156941019264821 0.989957478687063 0.140491585357535 -0.0261846091441205 -0.108054084782051 -0.141365205174802 0.984042780334168 -0.00314027436117487 5.57137760489192e-05 2.04178763169616e-05 -5.80444994324619e-06 3.03267184552274e-06 -3.94237354717793e-06 2.42349704211761e-05 2.04178763169616e-05 5.1396952940335e-05 -8.9889703170646e-06 1.53550574884044e-05 -2.98593875206274e-07 1.98569606102725e-05 -5.80444994324619e-06 -8.9889703170646e-06 1.13760205627434e-05 1.91279804900337e-06 4.00940701249255e-06 -4.80938221318167e-06 3.03267184552274e-06 1.53550574884044e-05 1.91279804900337e-06 3.94556383906185e-05 -2.90850291669485e-06 1.98564646113171e-05 -3.94237354717793e-06 -2.98593875206274e-07 4.00940701249255e-06 -2.90850291669485e-06 3.8288135148144e-05 -1.13091914921172e-05 2.42349704211761e-05 1.98569606102725e-05 -4.80938221318167e-06 1.98564646113171e-05 -1.13091914921172e-05 8.19097682629809e-05 1944 1938 0 13 19 1922 1950 0 35 8 0 0 0 0 0 2 18 0 444 0 111 94 0 0 2624 +357 360 0.999814379319266 0.00643567516086164 0.018160093382318 -0.00431185538913495 -0.00652069847234503 0.999968037237957 0.00462655313378752 0.00213747690906511 -0.0181297379424911 -0.0047441108430211 0.999824387587363 -0.00463763007659092 6.1091818409648e-05 2.70836451871025e-05 -4.74069468850538e-06 1.20131137234801e-05 -5.44268970679122e-06 3.39570491558644e-05 2.70836451871025e-05 4.53400934026427e-05 -8.29403193130742e-06 1.37574592220564e-05 -3.80016485952413e-07 2.60980919070799e-05 -4.74069468850538e-06 -8.29403193130742e-06 1.30190696228857e-05 1.21046774942725e-06 4.42306909457277e-06 -6.0075797109331e-06 1.20131137234801e-05 1.37574592220564e-05 1.21046774942725e-06 4.14805174850424e-05 -1.21404104571275e-05 2.32863919384285e-05 -5.44268970679122e-06 -3.80016485952413e-07 4.42306909457277e-06 -1.21404104571275e-05 4.11070589197147e-05 -1.31330270255402e-05 3.39570491558644e-05 2.60980919070799e-05 -6.0075797109331e-06 2.32863919384285e-05 -1.31330270255402e-05 7.50048762146577e-05 2317 2297 0 10 55 2288 2310 0 24 21 0 0 0 0 0 10 24 0 300 0 90 60 0 0 3279 +357 387 0.993404406311447 0.000717828284805943 0.114661110423524 -0.0193506267714389 -0.016733945255133 0.990181691702754 0.138781095588952 -0.0175136000904111 -0.113435711295871 -0.139784484615515 0.983662867685659 -0.0019153241787249 8.6878919877431e-05 5.28460050523935e-05 -9.75708363439722e-06 5.45600943349936e-06 -5.85391796542956e-06 6.13600979230461e-05 5.28460050523935e-05 8.81395739953401e-05 -1.30998762737089e-05 1.89295600738834e-05 4.81563084075334e-06 4.18457771128717e-05 -9.75708363439722e-06 -1.30998762737089e-05 1.42952062940216e-05 -1.87420743049093e-07 7.46229631898266e-07 -8.27068031188627e-06 5.45600943349936e-06 1.89295600738834e-05 -1.87420743049093e-07 4.95923457264295e-05 4.42983776885393e-06 5.92117009816082e-06 -5.85391796542956e-06 4.81563084075334e-06 7.46229631898266e-07 4.42983776885393e-06 5.00222156151461e-05 -7.1979074632654e-06 6.13600979230461e-05 4.18457771128717e-05 -8.27068031188627e-06 5.92117009816082e-06 -7.1979074632654e-06 0.00014617261973624 1611 1621 0 21 29 1561 1587 0 38 4 0 0 0 0 0 4 18 0 433 0 112 89 0 0 2545 +357 412 0.993803383863392 0.000677148255750006 0.111150239279596 -0.0209638157670099 -0.0161922213882989 0.990195964895476 0.138743515420464 -0.0182659886696647 -0.109966568502359 -0.139683544395738 0.984071065135471 0.0026450466199264 8.10271898016855e-05 6.61362944751066e-05 -1.03352443436625e-05 1.60208322514365e-05 -6.43488986228733e-06 6.46596012033259e-05 6.61362944751066e-05 0.000117909535398885 -1.14579745633386e-05 4.65942211778395e-05 -2.05753488684959e-05 9.70491587658199e-05 -1.03352443436625e-05 -1.14579745633386e-05 1.20962237656395e-05 3.16606919104747e-06 3.68616852860114e-06 -6.5635865006428e-06 1.60208322514365e-05 4.65942211778395e-05 3.16606919104747e-06 5.66462937041012e-05 -1.55698828422216e-05 4.72400662268933e-05 -6.43488986228733e-06 -2.05753488684959e-05 3.68616852860114e-06 -1.55698828422216e-05 4.35853397584953e-05 -3.1750668880943e-05 6.46596012033259e-05 9.70491587658199e-05 -6.5635865006428e-06 4.72400662268933e-05 -3.1750668880943e-05 0.000171033942618712 1743 1744 0 23 9 1756 1774 0 40 4 0 0 0 0 0 6 22 0 364 0 65 67 0 0 2076 +357 383 0.993704579910027 0.000608163365710569 0.112030522640743 -0.0170592340081107 -0.0161133769952184 0.990363954119921 0.137548527661205 -0.0240931753229394 -0.110867339409076 -0.138487791943102 0.984138996552355 -0.00722510776658434 8.07384110534034e-05 5.96071908017111e-05 -9.191207504004e-06 1.1161713242122e-05 3.05922827189136e-07 4.44971888597311e-05 5.96071908017111e-05 9.86413626310709e-05 -1.00568291280412e-05 1.82813155843938e-05 -2.93018935958854e-06 4.87392566576064e-05 -9.191207504004e-06 -1.00568291280412e-05 1.27154793095212e-05 9.05289314879898e-07 2.7018807427835e-06 -3.78141592922609e-06 1.1161713242122e-05 1.82813155843938e-05 9.05289314879898e-07 4.06861413498129e-05 -9.78306249772446e-07 1.40878686132482e-05 3.05922827189136e-07 -2.93018935958854e-06 2.7018807427835e-06 -9.78306249772446e-07 3.85526193603791e-05 -9.29506864460567e-07 4.44971888597311e-05 4.87392566576064e-05 -3.78141592922609e-06 1.40878686132482e-05 -9.29506864460567e-07 0.000134299307724781 1755 1762 0 19 30 1706 1734 0 40 5 0 0 0 0 0 5 21 0 435 0 112 89 0 0 2579 +357 361 0.999322277828626 0.00668668572718984 0.0361976970177899 -0.0108234368687883 -0.00759380066390727 0.999659088394751 0.0249808162647239 0.00936015029385043 -0.0360183179352223 -0.0252387643073279 0.999032374625245 -0.00224465258963145 7.83841574397307e-05 5.00534372793827e-05 -1.15132432015893e-05 1.19718875661732e-05 -1.55507565856375e-06 4.74516509496444e-05 5.00534372793827e-05 0.000107463181395939 -1.66228341599544e-05 2.26557342574017e-05 1.94407647099035e-05 7.5619612745542e-05 -1.15132432015893e-05 -1.66228341599544e-05 1.4195947044532e-05 1.15234864516436e-06 2.97023421230245e-06 -1.38869618733491e-05 1.19718875661732e-05 2.26557342574017e-05 1.15234864516436e-06 4.6979256848096e-05 -1.15477194394203e-05 3.30124117604351e-05 -1.55507565856375e-06 1.94407647099035e-05 2.97023421230245e-06 -1.15477194394203e-05 5.70168692731037e-05 -1.36678018029927e-06 4.74516509496444e-05 7.5619612745542e-05 -1.38869618733491e-05 3.30124117604351e-05 -1.36678018029927e-06 0.000126625583239358 2132 2115 0 13 56 2132 2143 0 29 27 0 0 0 0 0 5 18 0 345 0 113 86 0 0 3219 +357 389 0.994456197944599 0.000469659834601953 0.105150605272689 -0.0210316041797912 -0.0149786100054004 0.990425174114205 0.13723562118908 -0.0247395077339488 -0.104079352476268 -0.138049823978469 0.984941487849727 -0.00383159409913953 7.91175203431971e-05 2.83223869057958e-05 -6.11714803385901e-06 -2.25384186378004e-06 -1.07160919849944e-05 3.68239136412128e-05 2.83223869057958e-05 4.36194965254011e-05 -5.29083900513384e-06 6.19994013659702e-06 -4.0837116002978e-06 1.7115128562007e-05 -6.11714803385901e-06 -5.29083900513384e-06 1.08595493096664e-05 5.51544772176291e-06 6.62945646824249e-06 -3.85831220406531e-06 -2.25384186378004e-06 6.19994013659702e-06 5.51544772176291e-06 3.79690092190401e-05 -9.28841690056607e-06 1.83675220048276e-06 -1.07160919849944e-05 -4.0837116002978e-06 6.62945646824249e-06 -9.28841690056607e-06 4.14540357189489e-05 -8.94420790475852e-06 3.68239136412128e-05 1.7115128562007e-05 -3.85831220406531e-06 1.83675220048276e-06 -8.94420790475852e-06 8.75837784190665e-05 1716 1710 0 16 26 1721 1736 0 36 12 0 0 0 0 0 5 22 0 316 0 113 90 0 0 2411 +357 409 0.994407236050813 0.000993552152787674 0.105609004085361 -0.0283861469307725 -0.0153675415492481 0.990674616189281 0.135379627363031 -0.0170069296485712 -0.104489652868187 -0.136245431821917 0.985149275364472 0.000958545819019819 7.41438433908983e-05 4.48089453393076e-05 -5.05565028488878e-06 3.12494227043522e-06 -7.70187571386761e-06 4.29125789740475e-05 4.48089453393076e-05 7.69312103794435e-05 -5.13403381234779e-06 2.21356179464906e-05 -1.23317974896302e-05 4.68380210113808e-05 -5.05565028488878e-06 -5.13403381234779e-06 1.08224581520019e-05 4.58816778150203e-06 6.16022518218226e-06 -1.95927964686784e-06 3.12494227043522e-06 2.21356179464906e-05 4.58816778150203e-06 6.17691669862185e-05 -1.57691982647225e-05 1.6790349151525e-05 -7.70187571386761e-06 -1.23317974896302e-05 6.16022518218226e-06 -1.57691982647225e-05 4.06378414058549e-05 -1.00130776805035e-05 4.29125789740475e-05 4.68380210113808e-05 -1.95927964686784e-06 1.6790349151525e-05 -1.00130776805035e-05 0.000102167495006174 1733 1732 0 19 10 1742 1766 0 39 5 0 0 0 0 0 8 25 0 315 0 77 80 0 0 2077 +357 386 0.993876022925188 0.000439431767485066 0.11050003599155 -0.0165475296779841 -0.0159834255214835 0.990047454017844 0.139823348913491 -0.0201117459594966 -0.109338836480966 -0.140733243025613 0.98399144973139 0.00620138919813938 8.50102630458107e-05 5.16440807611302e-05 -8.35943916853363e-06 8.67889936223692e-06 -1.20444608835445e-05 4.99913606364821e-05 5.16440807611302e-05 7.96550162223189e-05 -7.92939554917242e-06 8.2841664714797e-06 -3.84501518494227e-06 4.64067714884514e-05 -8.35943916853363e-06 -7.92939554917242e-06 1.22218221786894e-05 1.2792414496794e-06 4.28803252090445e-06 -3.7988906700144e-06 8.67889936223692e-06 8.2841664714797e-06 1.2792414496794e-06 4.05676568607159e-05 -2.44018163102153e-06 1.10852640456233e-05 -1.20444608835445e-05 -3.84501518494227e-06 4.28803252090445e-06 -2.44018163102153e-06 4.23327104616853e-05 -9.23636888890181e-06 4.99913606364821e-05 4.64067714884514e-05 -3.7988906700144e-06 1.10852640456233e-05 -9.23636888890181e-06 9.8368099349944e-05 1658 1656 0 19 20 1653 1677 0 38 4 0 0 0 0 0 4 21 0 431 0 117 95 0 0 2629 +357 411 0.994740150745719 0.000124806851274155 0.102430546799451 -0.0292677269762063 -0.0150056502557553 0.989388125471976 0.144519782851522 -0.00880987198353862 -0.101325529629934 -0.14529666754024 0.984185965885977 -0.0059891466004985 7.83359284973133e-05 3.39537277211353e-05 -8.48081395009028e-06 6.64093998071911e-06 -2.10653492353189e-06 3.1109967262523e-05 3.39537277211353e-05 6.58507827108474e-05 -4.99736080246156e-06 1.23971605792915e-05 9.70129973202277e-06 2.69551448214837e-05 -8.48081395009028e-06 -4.99736080246156e-06 1.19638631666541e-05 3.9197194848841e-06 5.5395577060766e-06 -2.89274111122753e-06 6.64093998071911e-06 1.23971605792915e-05 3.9197194848841e-06 4.58444786471859e-05 -7.92412638068239e-06 7.94094918578138e-06 -2.10653492353189e-06 9.70129973202277e-06 5.5395577060766e-06 -7.92412638068239e-06 4.82645391689022e-05 6.33754227440608e-06 3.1109967262523e-05 2.69551448214837e-05 -2.89274111122753e-06 7.94094918578138e-06 6.33754227440608e-06 8.16252456975291e-05 1370 1374 0 17 10 1382 1406 0 35 5 0 0 0 0 0 7 23 0 341 0 66 67 0 0 2061 +357 410 0.994989186007684 0.00104162086384275 0.0999771711629298 -0.0282642381755235 -0.0150878703866499 0.990058880621498 0.139841943170503 -0.0152071690658229 -0.0988376238836275 -0.140649663805082 0.985113595569849 -0.00574640397552414 7.30987981317291e-05 4.73179124787478e-05 -5.50677433586563e-06 -1.73454709290338e-06 -1.57185780063034e-06 3.57434525444579e-05 4.73179124787478e-05 8.71483527416611e-05 -5.77688453529618e-06 7.63234343614625e-06 8.43801073406394e-06 4.4981726546756e-05 -5.50677433586563e-06 -5.77688453529618e-06 1.04730811219188e-05 3.80018559467719e-06 5.5929203025133e-06 -1.68982614077955e-06 -1.73454709290338e-06 7.63234343614625e-06 3.80018559467719e-06 3.64170263836214e-05 -3.35413708556276e-06 2.3656617734059e-06 -1.57185780063034e-06 8.43801073406394e-06 5.5929203025133e-06 -3.35413708556276e-06 3.89031763543709e-05 5.28325922780886e-06 3.57434525444579e-05 4.4981726546756e-05 -1.68982614077955e-06 2.3656617734059e-06 5.28325922780886e-06 9.75618456532121e-05 1758 1764 0 26 9 1773 1795 0 41 6 0 0 0 0 0 4 18 0 312 0 62 64 0 0 2075 +357 384 0.993595256006426 0.000399493305145368 0.112996936447955 -0.0158972274560412 -0.0161139288722157 0.990274556603557 0.138190606916424 -0.0229347797354187 -0.111842784916262 -0.139126356053509 0.983938538991866 -0.00539689826616183 8.65496658973821e-05 5.04047922177005e-05 -9.25794339639817e-06 1.32636309736717e-05 -8.50410254145763e-06 3.20611903330064e-05 5.04047922177005e-05 8.94033207293106e-05 -7.94076563905473e-06 2.36132468212368e-05 -7.39709340768498e-06 3.10863433808199e-05 -9.25794339639817e-06 -7.94076563905473e-06 1.24864688803929e-05 1.08679535828857e-06 2.91361634377408e-06 -6.18846725111381e-06 1.32636309736717e-05 2.36132468212368e-05 1.08679535828857e-06 3.98089501111745e-05 -3.10156047997775e-06 2.16131680241517e-05 -8.50410254145763e-06 -7.39709340768498e-06 2.91361634377408e-06 -3.10156047997775e-06 3.90552244125986e-05 4.62307362672859e-06 3.20611903330064e-05 3.10863433808199e-05 -6.18846725111381e-06 2.16131680241517e-05 4.62307362672859e-06 0.000127519983548708 1594 1607 0 22 28 1548 1575 0 40 4 0 0 0 0 0 4 17 0 448 0 111 89 0 0 2663 +357 396 0.993140539794406 6.11032131556713e-05 0.116926748365264 -0.0110680759971884 -0.0164702280297642 0.99010258720621 0.139375745365603 -0.0266937886987432 -0.115760959764179 -0.140345513194997 0.983312024293667 0.00822738255982607 8.26424108990954e-05 5.58368940723643e-05 -6.38334259662282e-06 7.15340318863737e-06 -1.00837870246179e-05 5.74319095132082e-05 5.58368940723643e-05 9.80383502873482e-05 -7.36818777276004e-06 2.58206455140598e-05 -8.29886005876297e-06 6.17437012783346e-05 -6.38334259662282e-06 -7.36818777276004e-06 1.20583365482973e-05 4.59650086138042e-06 7.14521704644835e-06 -5.69722223742483e-06 7.15340318863737e-06 2.58206455140598e-05 4.59650086138042e-06 4.74892794649924e-05 -1.78761732326545e-06 2.32799546179969e-05 -1.00837870246179e-05 -8.29886005876297e-06 7.14521704644835e-06 -1.78761732326545e-06 4.14601776408834e-05 4.27760637213405e-07 5.74319095132082e-05 6.17437012783346e-05 -5.69722223742483e-06 2.32799546179969e-05 4.27760637213405e-07 0.000113719580572649 1522 1522 0 20 22 1529 1545 0 36 5 0 0 0 0 0 3 16 0 259 0 123 105 0 0 2322 +357 388 0.993793139285841 0.000210215720019283 0.11124366102275 -0.0143162693222952 -0.0157533290757015 0.99018658664953 0.138860924101727 -0.0276021255750337 -0.110122790245372 -0.139751491686865 0.984043948022582 -0.00175188750364013 6.54373243309553e-05 3.31601597936019e-05 -4.50091576360507e-06 3.93241513790718e-06 -1.31754593635131e-05 3.27323150894733e-05 3.31601597936019e-05 6.21301195555155e-05 -3.82666023949602e-06 1.71937163389496e-05 -1.29096051360202e-05 2.94891645186953e-05 -4.50091576360507e-06 -3.82666023949602e-06 1.07273426018557e-05 2.495504008454e-06 6.67533594172404e-06 -2.65767041485471e-06 3.93241513790718e-06 1.71937163389496e-05 2.495504008454e-06 4.72498377712249e-05 -1.09309980744197e-05 2.07136357591347e-05 -1.31754593635131e-05 -1.29096051360202e-05 6.67533594172404e-06 -1.09309980744197e-05 3.9146229599836e-05 -1.92908452649522e-05 3.27323150894733e-05 2.94891645186953e-05 -2.65767041485471e-06 2.07136357591347e-05 -1.92908452649522e-05 8.56404597372436e-05 1946 1947 0 25 17 1935 1962 0 39 9 0 0 0 0 0 5 21 0 442 0 114 97 0 0 2528 +357 395 0.992104000080079 0.000662779227296386 0.125416162231195 -0.00538212408677385 -0.0175207939140012 0.990912569031602 0.133361547365847 -0.0297653710086894 -0.124188062251283 -0.134505915330463 0.983099935884132 0.00887877028650425 0.000103178569030621 6.42937253009145e-05 -5.95027048091692e-06 2.02344256396727e-05 -3.27217295720873e-05 5.87772216791487e-05 6.42937253009145e-05 0.000109301629306001 -4.12057261355293e-06 3.53337585641882e-05 -3.08605051442303e-05 5.6884575800179e-05 -5.95027048091692e-06 -4.12057261355293e-06 1.1783522729026e-05 4.5520427312062e-06 7.12676106581127e-06 -3.78218503232085e-06 2.02344256396727e-05 3.53337585641882e-05 4.5520427312062e-06 4.86893918930638e-05 -1.61600146312249e-05 2.75755003616606e-05 -3.27217295720873e-05 -3.08605051442303e-05 7.12676106581127e-06 -1.61600146312249e-05 5.30102030078734e-05 -2.86231232770162e-05 5.87772216791487e-05 5.6884575800179e-05 -3.78218503232085e-06 2.75755003616606e-05 -2.86231232770162e-05 0.000146499867827013 1950 1956 0 25 28 1913 1940 0 37 5 0 0 0 0 0 4 17 0 236 0 114 97 0 0 2335 +357 408 0.993281872218148 0.000579388200640517 0.115718566497011 -0.0118227399096027 -0.0164415795993072 0.990549264378199 0.136168385831989 -0.0262999647888537 -0.114546046562463 -0.137156185238299 0.983904153903106 -0.00437058184691838 0.000119392040106275 0.000106409689922806 -7.98479317702216e-06 2.12220694494908e-05 -2.52084827395355e-05 9.53069050118173e-05 0.000106409689922806 0.000175834937006826 -7.38476852370392e-06 4.93958052652791e-05 -3.64995375409344e-05 0.000122220957680013 -7.98479317702216e-06 -7.38476852370392e-06 1.29189540211909e-05 4.80567284842317e-06 6.06181229115113e-06 -6.11516057140062e-06 2.12220694494908e-05 4.93958052652791e-05 4.80567284842317e-06 5.67060246937016e-05 -1.13938493290928e-05 5.01630947146358e-05 -2.52084827395355e-05 -3.64995375409344e-05 6.06181229115113e-06 -1.13938493290928e-05 4.31472810218005e-05 -4.56133841950621e-05 9.53069050118173e-05 0.000122220957680013 -6.11516057140062e-06 5.01630947146358e-05 -4.56133841950621e-05 0.00023440405748966 1607 1620 0 17 14 1578 1605 0 37 5 0 0 0 0 0 5 21 0 296 0 58 61 0 0 2156 +357 413 0.993393873670951 0.00151608771146856 0.114744556433297 -0.0168197319937417 -0.0168974359472615 0.990945739362781 0.13319541394943 -0.0234941627919305 -0.113503693382335 -0.134254397011059 0.984425044618312 0.00539174745894376 8.71234203813136e-05 6.80394450636151e-05 -1.13447357518099e-05 5.07093117036116e-06 -6.73098252645379e-07 6.66040840663274e-05 6.80394450636151e-05 0.000121267940968538 -9.36869834121227e-06 3.21248752175325e-05 -1.25369885334188e-05 9.56191930968699e-05 -1.13447357518099e-05 -9.36869834121227e-06 1.20369147186168e-05 4.17149862498862e-06 1.79909504842861e-06 -6.21101497033459e-06 5.07093117036116e-06 3.21248752175325e-05 4.17149862498862e-06 5.37148750490846e-05 -7.45129555438378e-06 3.1631590747547e-05 -6.73098252645379e-07 -1.25369885334188e-05 1.79909504842861e-06 -7.45129555438378e-06 4.57271198553185e-05 -1.72402851016951e-05 6.66040840663274e-05 9.56191930968699e-05 -6.21101497033459e-06 3.1631590747547e-05 -1.72402851016951e-05 0.000161792485865535 1359 1361 0 23 13 1365 1384 0 43 7 0 0 0 0 0 4 19 0 394 0 84 86 0 0 2050 +357 414 0.994145656334046 -0.000428494888790779 0.108047352509345 -0.0299868888308167 -0.0150816361886618 0.989652348950225 0.142691178659283 -0.0148648848167596 -0.106990458649457 -0.143485346323006 0.98385212158563 -0.00760701043763835 9.51413073226389e-05 5.88744038332298e-05 -1.24249830149338e-05 8.47644660219381e-06 -4.8392156429001e-06 5.35443216933608e-05 5.88744038332298e-05 7.92205632873154e-05 -1.17447314726065e-05 1.48776303043104e-05 -2.52470143875553e-06 3.90205105987683e-05 -1.24249830149338e-05 -1.17447314726065e-05 1.40679700191747e-05 2.18446034393501e-06 2.40977435222232e-06 -5.78001288117093e-06 8.47644660219381e-06 1.48776303043104e-05 2.18446034393501e-06 7.07653229062921e-05 -2.71909812069727e-05 2.0969394531039e-05 -4.8392156429001e-06 -2.52470143875553e-06 2.40977435222232e-06 -2.71909812069727e-05 5.71548819499998e-05 -1.57778949729306e-05 5.35443216933608e-05 3.90205105987683e-05 -5.78001288117093e-06 2.0969394531039e-05 -1.57778949729306e-05 0.00013518828580411 1821 1830 0 20 11 1795 1819 0 39 5 0 0 0 0 0 6 22 0 399 0 55 58 0 0 2163 +357 394 0.993843057765007 0.000199349477325053 0.110796826633646 -0.0186473885735581 -0.0160077952514788 0.9897646749594 0.14180845776504 -0.020641157286903 -0.109634515657648 -0.142708964197413 0.983673942175056 0.0038507753605512 7.2130595350641e-05 8.94842450890152e-06 -4.31215032181213e-06 -5.20092329386049e-06 -2.24305298167566e-05 1.76933390655528e-05 8.94842450890152e-06 6.44787160239001e-05 3.39508634675476e-08 1.40863736742308e-05 1.4313610728154e-07 2.35228240913459e-05 -4.31215032181213e-06 3.39508634675476e-08 1.20036522561713e-05 6.35057676914131e-06 6.70766584032462e-06 3.00334710777562e-07 -5.20092329386049e-06 1.40863736742308e-05 6.35057676914131e-06 5.66869514202418e-05 -1.7822579596414e-05 2.32508766336734e-05 -2.24305298167566e-05 1.4313610728154e-07 6.70766584032462e-06 -1.7822579596414e-05 6.8571280375989e-05 -9.46577671204845e-06 1.76933390655528e-05 2.35228240913459e-05 3.00334710777562e-07 2.32508766336734e-05 -9.46577671204845e-06 9.14387089758598e-05 1448 1446 0 19 22 1444 1463 0 38 5 0 0 0 0 0 5 22 0 269 0 115 96 0 0 2300 +357 390 0.992827673119298 0.000820260413044263 0.119551405936426 -0.00792423015031727 -0.0171221971043895 0.990643579149193 0.13539619439554 -0.0251188028621966 -0.118321772530839 -0.136472071367483 0.983552404237735 0.0177436154067972 7.25588328292102e-05 1.13863529207519e-05 -3.67578090141853e-06 1.07503751775353e-05 -2.06620777262828e-05 2.31832535061604e-05 1.13863529207519e-05 5.90833425309994e-05 -4.53482893279243e-06 1.41079411238488e-05 2.74718709853637e-06 1.74803880516556e-05 -3.67578090141853e-06 -4.53482893279243e-06 1.25655057198451e-05 4.3750096021183e-06 3.84293158889917e-06 -5.08068729484039e-06 1.07503751775353e-05 1.41079411238488e-05 4.3750096021183e-06 4.54674053985841e-05 -8.0816662182865e-06 2.28582650268423e-05 -2.06620777262828e-05 2.74718709853637e-06 3.84293158889917e-06 -8.0816662182865e-06 6.64380750765294e-05 -3.88233850390896e-06 2.31832535061604e-05 1.74803880516556e-05 -5.08068729484039e-06 2.28582650268423e-05 -3.88233850390896e-06 9.32281368496721e-05 1570 1567 0 20 25 1573 1588 0 39 10 0 0 0 0 0 4 22 0 220 0 104 86 0 0 2334 +357 397 0.994190876483142 0.000395357216581338 0.107630594211655 -0.0151199651341654 -0.0154388669596612 0.990175866980873 0.1389726370034 -0.0286642420227439 -0.106518273102245 -0.139827022214407 0.984429916933637 0.00387725753229287 0.000106106767997651 5.59408916764492e-05 -1.18224242629897e-05 -2.27915507715457e-07 -1.03404540656936e-05 5.63777697550803e-05 5.59408916764492e-05 9.39770938140352e-05 -9.0164729572505e-06 3.51801417214817e-05 -1.78726200484882e-05 5.89115939168867e-05 -1.18224242629897e-05 -9.0164729572505e-06 1.25712702834107e-05 3.15013081754716e-06 6.14355950749389e-06 -6.59740546154583e-06 -2.27915507715457e-07 3.51801417214817e-05 3.15013081754716e-06 6.43495261220276e-05 -1.83017560081939e-05 2.32001710160627e-05 -1.03404540656936e-05 -1.78726200484882e-05 6.14355950749389e-06 -1.83017560081939e-05 4.22462904781382e-05 -1.31247416263401e-05 5.63777697550803e-05 5.89115939168867e-05 -6.59740546154583e-06 2.32001710160627e-05 -1.31247416263401e-05 0.000115255152782735 1425 1422 0 22 25 1432 1447 0 44 9 0 0 0 0 0 6 21 0 264 0 107 94 0 0 2272 +357 415 0.992584550995716 0.000949778260353692 0.121552486794341 -0.00914320619434444 -0.017333143706444 0.990856991062732 0.133798301152744 -0.0266908867750988 -0.120314052603526 -0.134913013395168 0.983525804218045 0.00853576055037678 7.40914603439922e-05 3.49619691885972e-05 -1.24511638414484e-05 -4.34976530292588e-07 2.04342317556314e-06 4.37432467227345e-05 3.49619691885972e-05 8.78835547657098e-05 -9.56896990886882e-06 8.91646790830079e-06 1.125778432351e-05 3.97872370564322e-05 -1.24511638414484e-05 -9.56896990886882e-06 1.38823007683985e-05 2.36288587999322e-06 1.16616566983326e-06 -6.05692815777681e-06 -4.34976530292588e-07 8.91646790830079e-06 2.36288587999322e-06 3.67803393373198e-05 -4.86059834487653e-06 1.27125609696504e-05 2.04342317556314e-06 1.125778432351e-05 1.16616566983326e-06 -4.86059834487653e-06 4.44052719503396e-05 -8.29462830047426e-06 4.37432467227345e-05 3.97872370564322e-05 -6.05692815777681e-06 1.27125609696504e-05 -8.29462830047426e-06 0.000118128185616771 1560 1570 0 22 13 1531 1561 0 42 5 0 0 0 0 0 5 20 0 363 0 70 73 0 0 2162 +357 391 0.992162513633674 0.000483864794771145 0.124953240914234 -0.00745446545643051 -0.0174855860281753 0.99069076128272 0.135003962128212 -0.0250202718460274 -0.123724697701637 -0.136130751059137 0.982934696607416 0.00859228796398982 0.000117002785093149 5.34191887560707e-05 -7.58878520896723e-06 1.25573421064355e-05 -3.1527346218087e-05 5.61663773920481e-05 5.34191887560707e-05 9.04696535155296e-05 -5.86408198282397e-06 2.50563838866481e-05 -1.27918372362421e-05 3.81791183580524e-05 -7.58878520896723e-06 -5.86408198282397e-06 1.1279282398745e-05 3.55005436830706e-06 8.98047738130379e-06 -8.20664563298666e-06 1.25573421064355e-05 2.50563838866481e-05 3.55005436830706e-06 4.48869867921286e-05 -9.7625106176561e-06 2.19752480554157e-05 -3.1527346218087e-05 -1.27918372362421e-05 8.98047738130379e-06 -9.7625106176561e-06 5.47681809058575e-05 -2.65781216119463e-05 5.61663773920481e-05 3.81791183580524e-05 -8.20664563298666e-06 2.19752480554157e-05 -2.65781216119463e-05 0.000129093787650823 1663 1673 0 19 27 1621 1647 0 30 7 0 0 0 0 0 3 16 0 205 0 114 94 0 0 2269 +358 387 0.994080299770882 0.00165080579163556 0.108635318601599 -0.0280760930338702 -0.0166626442857715 0.99037215980448 0.137423947584167 -0.0162439533618974 -0.107362534865932 -0.138420590680897 0.984536960292864 -0.00422960299185001 5.11659828506697e-05 2.35525553414744e-05 -5.99063641822721e-06 -1.47585555879406e-06 3.8789064870885e-06 2.15395247661109e-05 2.35525553414744e-05 8.08346661418158e-05 -9.07992714950524e-06 3.31098043166538e-05 -1.37357294594795e-07 2.24066360339638e-05 -5.99063641822721e-06 -9.07992714950524e-06 1.36758417189752e-05 -3.33379713008708e-07 5.27379773218241e-07 -2.59318258093352e-06 -1.47585555879406e-06 3.31098043166538e-05 -3.33379713008708e-07 6.24153379819708e-05 -1.57615983848197e-06 3.33317591125215e-06 3.8789064870885e-06 -1.37357294594795e-07 5.27379773218241e-07 -1.57615983848197e-06 3.47977569806804e-05 2.15280506338091e-06 2.15395247661109e-05 2.24066360339638e-05 -2.59318258093352e-06 3.33317591125215e-06 2.15280506338091e-06 9.98396400229314e-05 1677 1677 0 16 24 1657 1676 0 31 8 0 0 0 0 0 4 17 0 440 0 153 133 0 0 2649 +358 361 0.999013217393826 0.00818146560802007 0.0436538096039931 -0.000779655747694319 -0.00895450768087101 0.999806021539156 0.0175424082222745 -0.00228675021966926 -0.0435018190956437 -0.0179159960523686 0.998892691344181 0.0123551324518481 0.000115118473717937 9.50576020041324e-05 -1.67500794203482e-05 2.11902190041955e-05 -5.25719580775275e-07 8.72233042040039e-05 9.50576020041324e-05 0.000217067126303863 -2.30664091235862e-05 5.5319975600614e-05 1.92687672686657e-05 0.000163432963915357 -1.67500794203482e-05 -2.30664091235862e-05 1.41643054390168e-05 -2.05104802603793e-06 2.29675650449721e-06 -2.39604423324442e-05 2.11902190041955e-05 5.5319975600614e-05 -2.05104802603793e-06 6.61577016674744e-05 -1.52961329665296e-05 6.15828046630768e-05 -5.25719580775275e-07 1.92687672686657e-05 2.29675650449721e-06 -1.52961329665296e-05 5.29006970283002e-05 -6.05976911839175e-06 8.72233042040039e-05 0.000163432963915357 -2.39604423324442e-05 6.15828046630768e-05 -6.05976911839175e-06 0.000214736031068954 2131 2116 0 12 53 2073 2092 0 26 14 0 0 0 0 0 4 16 0 336 0 97 66 0 0 3230 +358 411 0.99413766797852 0.000496341907384318 0.108120538062573 -0.0230642491594716 -0.0159324131516023 0.989745535862394 0.141950457736596 -0.0173104429755608 -0.106941363921524 -0.142840918105329 0.983951226838724 -0.000465817508286994 4.73338659200672e-05 2.19942463303096e-05 -4.04043139868929e-06 3.76685588503378e-06 -1.1365845044304e-06 1.81914223973325e-05 2.19942463303096e-05 7.22534203223172e-05 -3.57247765068606e-06 2.68558811068371e-05 -8.5927354440313e-06 3.61840043669366e-05 -4.04043139868929e-06 -3.57247765068606e-06 1.04046692731998e-05 3.82594954181496e-06 5.1613342038511e-06 -5.39925927160281e-07 3.76685588503378e-06 2.68558811068371e-05 3.82594954181496e-06 5.46422948038698e-05 -1.24146203680167e-05 1.40435796913369e-05 -1.1365845044304e-06 -8.5927354440313e-06 5.1613342038511e-06 -1.24146203680167e-05 3.99707875071686e-05 -5.07193412863292e-06 1.81914223973325e-05 3.61840043669366e-05 -5.39925927160281e-07 1.40435796913369e-05 -5.07193412863292e-06 9.75840771737683e-05 1518 1528 0 19 10 1493 1510 0 32 5 0 0 0 0 0 4 15 0 323 0 47 50 0 0 2149 +358 395 0.992890655545542 0.000816524129303917 0.119027221334826 -0.0139418762069991 -0.0169681836841521 0.990734705161321 0.134747262426257 -0.0254989099312642 -0.117814374644201 -0.135808973478397 0.983705085810752 0.0035772099591263 8.23004122128427e-05 7.51075634384597e-05 -5.94785132463283e-06 2.32145127777093e-05 -1.43839374073214e-05 5.70718630198974e-05 7.51075634384597e-05 0.000169219717042377 -8.01644414167492e-06 5.64964874817155e-05 -2.65176852901045e-05 0.000100712223631279 -5.94785132463283e-06 -8.01644414167492e-06 1.24075692431258e-05 1.72984841520056e-06 6.06416560784747e-06 -5.81636043790392e-06 2.32145127777093e-05 5.64964874817155e-05 1.72984841520056e-06 6.21632289884981e-05 -1.5385953512322e-05 4.94322463142131e-05 -1.43839374073214e-05 -2.65176852901045e-05 6.06416560784747e-06 -1.5385953512322e-05 4.78409342780681e-05 -2.3726641459327e-05 5.70718630198974e-05 0.000100712223631279 -5.81636043790392e-06 4.94322463142131e-05 -2.3726641459327e-05 0.000182691881668415 1743 1743 0 20 22 1690 1702 0 34 8 0 0 0 0 0 2 15 0 242 0 134 119 0 0 2371 +358 360 0.999572444015055 0.00685383083933593 0.0284245346240953 -0.000592898313988055 -0.00697349109459006 0.99996722727262 0.00411276095374265 0.00086866092768409 -0.0283954149067116 -0.00430922075725122 0.999587480428172 0.00367343642849407 8.38725783465428e-05 4.14681942321079e-05 -1.24711253500049e-05 2.20450934791609e-05 -6.81765533185045e-06 6.17661534767753e-05 4.14681942321079e-05 5.26377221851526e-05 -1.21635755570548e-05 1.6276309038982e-05 -3.4083527454974e-06 4.14902906627255e-05 -1.24711253500049e-05 -1.21635755570548e-05 1.44430150597185e-05 -1.54937967876533e-06 3.37783940631936e-06 -1.37234729928737e-05 2.20450934791609e-05 1.6276309038982e-05 -1.54937967876533e-06 4.58501465933596e-05 -2.10675517152941e-05 2.69841026642313e-05 -6.81765533185045e-06 -3.4083527454974e-06 3.37783940631936e-06 -2.10675517152941e-05 5.16808682766388e-05 -9.93997100847626e-06 6.17661534767753e-05 4.14902906627255e-05 -1.37234729928737e-05 2.69841026642313e-05 -9.93997100847626e-06 0.000101708127422031 2319 2292 0 14 63 2264 2275 0 23 9 0 0 0 0 0 5 18 0 307 0 113 83 0 0 3318 +358 388 0.993765854761457 0.000312732959050433 0.111486896576808 -0.0233060959896469 -0.0159691440525295 0.990083770335346 0.139567597087485 -0.0201579184236506 -0.110337719518128 -0.140477862728051 0.983916438390424 -0.003758115696433 9.3222085737987e-05 2.56892662943262e-05 -7.74207316019111e-06 4.09173188766575e-06 -1.95367267733166e-05 2.68472331217392e-05 2.56892662943262e-05 7.16634921276648e-05 -1.09807494391971e-06 2.55074414316737e-05 -1.05704529976196e-05 3.48467660195138e-05 -7.74207316019111e-06 -1.09807494391971e-06 1.31088138255123e-05 4.22703233996048e-06 8.32698903170489e-06 -1.33586454827827e-06 4.09173188766575e-06 2.55074414316737e-05 4.22703233996048e-06 5.95717832341703e-05 -2.27709543438133e-05 1.51893611817297e-05 -1.95367267733166e-05 -1.05704529976196e-05 8.32698903170489e-06 -2.27709543438133e-05 5.17434205627004e-05 -9.36230553038046e-06 2.68472331217392e-05 3.48467660195138e-05 -1.33586454827827e-06 1.51893611817297e-05 -9.36230553038046e-06 9.03074786519632e-05 1654 1653 0 15 20 1670 1700 0 32 8 0 0 0 0 0 4 14 0 443 0 118 101 0 0 2542 +358 412 0.99400334537866 0.000832407070365014 0.109346497312451 -0.0280307209837711 -0.0163247953124158 0.989894458049448 0.140863277616976 -0.0135738680250595 -0.108124236108471 -0.141803628379032 0.983971991747987 -0.00178484686681316 0.000122654118608424 9.47633126200973e-05 -1.55429875051986e-05 3.22267455768518e-05 -1.10508247630226e-05 9.58171343677023e-05 9.47633126200973e-05 0.000144061046509628 -1.56619698851497e-05 5.15449268379185e-05 -1.61476209766012e-05 0.00011694613752534 -1.55429875051986e-05 -1.56619698851497e-05 1.30194146303141e-05 1.19835967265887e-06 3.55887058727111e-06 -9.92314718295096e-06 3.22267455768518e-05 5.15449268379185e-05 1.19835967265887e-06 7.81390390598634e-05 -3.88451413194119e-05 5.93083288669184e-05 -1.10508247630226e-05 -1.61476209766012e-05 3.55887058727111e-06 -3.88451413194119e-05 6.6113516480527e-05 -3.02924686665811e-05 9.58171343677023e-05 0.00011694613752534 -9.92314718295096e-06 5.93083288669184e-05 -3.02924686665811e-05 0.000210998825331472 1616 1621 0 16 9 1588 1603 0 31 3 0 0 0 0 0 0 12 0 356 0 51 53 0 0 2131 +358 386 0.993719855091463 0.00118383099392278 0.111890339802775 -0.0201390971650398 -0.0171416940018589 0.98975164436929 0.141766867761944 -0.0162295679227099 -0.110575819796867 -0.142794541255833 0.983556153487836 0.00196815093134522 6.34380794263837e-05 3.06985210244154e-05 -7.74184492357849e-06 1.30450785483568e-06 4.00200011740012e-06 2.26178160403183e-05 3.06985210244154e-05 5.47741384299948e-05 -1.03005686849316e-05 1.21885727508374e-05 4.66052399334749e-06 1.67985331891879e-05 -7.74184492357849e-06 -1.03005686849316e-05 1.32282786336592e-05 1.32028015733048e-06 1.137596460257e-06 -2.03758484432233e-06 1.30450785483568e-06 1.21885727508374e-05 1.32028015733048e-06 4.15814334883179e-05 -3.39315630055059e-06 8.71870457579443e-06 4.00200011740012e-06 4.66052399334749e-06 1.137596460257e-06 -3.39315630055059e-06 4.44064276604143e-05 2.37857163279787e-06 2.26178160403183e-05 1.67985331891879e-05 -2.03758484432233e-06 8.71870457579443e-06 2.37857163279787e-06 7.62269258730628e-05 1809 1807 0 16 22 1751 1763 0 32 0 0 0 0 0 0 4 13 0 420 0 108 86 0 0 2644 +358 396 0.993874797864042 0.00076762120839509 0.110509261731267 -0.0153894033057442 -0.0162085685362081 0.990174428316804 0.138895226028463 -0.0297398261252479 -0.109316826137225 -0.139835661635976 0.984121851834473 0.00483178762156013 9.67328053860856e-05 4.69603315857369e-05 -7.48407332330042e-06 4.56243509548639e-06 -1.28200130841915e-05 3.97344870056498e-05 4.69603315857369e-05 8.13771437069525e-05 -5.1839096194135e-06 2.53674309663567e-05 -1.19508587835342e-05 5.23564384085678e-05 -7.48407332330042e-06 -5.1839096194135e-06 1.11556543726539e-05 4.38310778768611e-06 6.70102078591376e-06 -2.21578564937181e-06 4.56243509548639e-06 2.53674309663567e-05 4.38310778768611e-06 5.22836269025075e-05 -7.88561979946777e-06 3.36326476962917e-05 -1.28200130841915e-05 -1.19508587835342e-05 6.70102078591376e-06 -7.88561979946777e-06 3.63685303545084e-05 -1.14648091388008e-05 3.97344870056498e-05 5.23564384085678e-05 -2.21578564937181e-06 3.36326476962917e-05 -1.14648091388008e-05 0.000138863380985712 1819 1820 0 16 21 1775 1787 0 32 1 0 0 0 0 0 2 14 0 250 0 104 86 0 0 2355 +358 410 0.994321420082522 0.00145294597586813 0.106408658073809 -0.0279659449179565 -0.0161592164292776 0.990373461339276 0.137474676938166 -0.013506078933784 -0.105184567734384 -0.138413496534307 0.984773024959395 -0.00468769201257716 0.000114148755751314 7.83956684638533e-05 -8.95762303607221e-06 1.36037865565438e-05 -9.23625512500483e-06 7.95096325037776e-05 7.83956684638533e-05 0.000145052864821049 -6.00872167639209e-06 3.32298347394429e-05 -9.5506776012433e-06 0.000108220772402514 -8.95762303607221e-06 -6.00872167639209e-06 1.12807762808453e-05 4.00343676244116e-06 6.29280574878751e-06 -5.61071423469877e-06 1.36037865565438e-05 3.32298347394429e-05 4.00343676244116e-06 4.80257080540322e-05 -1.2831006505975e-05 2.6526656231743e-05 -9.23625512500483e-06 -9.5506776012433e-06 6.29280574878751e-06 -1.2831006505975e-05 3.85098952928895e-05 -8.45533670091417e-06 7.95096325037776e-05 0.000108220772402514 -5.61071423469877e-06 2.6526656231743e-05 -8.45533670091417e-06 0.000170617576094292 1748 1752 0 14 9 1716 1732 0 32 3 0 0 0 0 0 2 15 0 305 0 55 57 0 0 2116 +358 362 0.998891893220752 0.00611117253400691 0.0466651821824402 -0.0151592925455902 -0.00792402244856429 0.999217036910388 0.038762391776802 0.0073816489069974 -0.0463917614032425 -0.0390892148588742 0.998158222806195 0.000314418049465302 7.15635958167027e-05 2.53125490339545e-05 -9.72166833963987e-06 1.04883576884456e-06 -3.92055533760172e-06 2.0493054692863e-05 2.53125490339545e-05 9.05099734913628e-05 -1.29179377328208e-05 3.75078087025463e-05 3.72361371685416e-06 6.0991920560091e-05 -9.72166833963987e-06 -1.29179377328208e-05 1.50219530789804e-05 2.23841726122969e-06 4.67155098791513e-07 -9.66157749900476e-06 1.04883576884456e-06 3.75078087025463e-05 2.23841726122969e-06 7.05438994251814e-05 -2.91517764654515e-05 3.27474039653019e-05 -3.92055533760172e-06 3.72361371685416e-06 4.67155098791513e-07 -2.91517764654515e-05 6.78107864541808e-05 -7.92034853766228e-06 2.0493054692863e-05 6.0991920560091e-05 -9.66157749900476e-06 3.27474039653019e-05 -7.92034853766228e-06 0.000108177162102826 1924 1901 0 9 49 1874 1880 0 27 7 0 0 0 0 0 10 21 0 368 0 116 90 0 0 3202 +358 384 0.994134322826338 0.000862556550462623 0.108148990632439 -0.0209806237838047 -0.0156108285880201 0.990640959145689 0.135597905934067 -0.0231695265898806 -0.107019858948765 -0.136490827747163 0.984843644306791 -0.00809130433061966 6.34873196697452e-05 3.99424119377136e-05 -5.06255401044451e-06 7.25934395504372e-06 -9.90798787796004e-07 2.19411867741357e-05 3.99424119377136e-05 7.18307615367569e-05 -6.52970936681149e-06 1.05026524145287e-05 3.52617223309308e-06 1.91744505317782e-05 -5.06255401044451e-06 -6.52970936681149e-06 1.16461062925734e-05 -7.58451764451653e-07 2.18631674463686e-06 -3.83845265586034e-07 7.25934395504372e-06 1.05026524145287e-05 -7.58451764451653e-07 4.36938830847108e-05 -6.23768423156181e-06 2.01024471889656e-07 -9.90798787796004e-07 3.52617223309308e-06 2.18631674463686e-06 -6.23768423156181e-06 4.39721800029464e-05 5.10548548948222e-06 2.19411867741357e-05 1.91744505317782e-05 -3.83845265586034e-07 2.01024471889656e-07 5.10548548948222e-06 8.18377362645256e-05 1618 1616 0 16 26 1592 1607 0 33 8 0 0 0 0 0 2 12 0 454 0 146 127 0 0 2705 +358 409 0.993998193542447 0.00159004069600036 0.109384930428908 -0.0264862136161548 -0.0163316070128622 0.990846103452656 0.134004768143029 -0.0202927776206327 -0.108170559057118 -0.134986929157139 0.984925204830294 0.00135403862934287 0.00010554194507323 6.56150848293536e-05 -1.21560957054262e-05 1.25338255445391e-05 -1.54746841243306e-05 5.86483495258529e-05 6.56150848293536e-05 8.14191444847628e-05 -9.42449455671309e-06 1.92505318444668e-05 -1.57629877203732e-05 6.2121530499735e-05 -1.21560957054262e-05 -9.42449455671309e-06 1.1652484646154e-05 2.75407313227693e-06 7.10598313226572e-06 -6.7327658399871e-06 1.25338255445391e-05 1.92505318444668e-05 2.75407313227693e-06 4.99146237614299e-05 -1.09241996964483e-05 1.61069942298775e-05 -1.54746841243306e-05 -1.57629877203732e-05 7.10598313226572e-06 -1.09241996964483e-05 4.09221221911903e-05 -1.61252014428174e-05 5.86483495258529e-05 6.2121530499735e-05 -6.7327658399871e-06 1.61069942298775e-05 -1.61252014428174e-05 0.000134408424839113 1793 1794 0 15 10 1756 1771 0 32 1 0 0 0 0 0 2 15 0 296 0 65 68 0 0 2115 +358 397 0.993813198762059 0.00112327789769974 0.111058832215582 -0.0194304724258323 -0.016324077744419 0.990566425456155 0.136057639420984 -0.0263386164040315 -0.109858319903949 -0.137028810860275 0.98445632434461 0.00735068150541133 9.22527027400564e-05 2.99472813701109e-05 -1.04851407631161e-05 -3.1098682565695e-06 -5.62718110711751e-06 2.8911958048589e-05 2.99472813701109e-05 0.000101356134199455 -4.3694349484815e-06 1.66242917156749e-05 4.84328213712723e-06 5.20973653460345e-05 -1.04851407631161e-05 -4.3694349484815e-06 1.28163401419078e-05 3.3913189509149e-06 4.48505750218808e-06 -1.61882278724578e-06 -3.1098682565695e-06 1.66242917156749e-05 3.3913189509149e-06 5.35536844649084e-05 -2.15962404262959e-05 3.94682893127677e-06 -5.62718110711751e-06 4.84328213712723e-06 4.48505750218808e-06 -2.15962404262959e-05 6.67116778186703e-05 2.06495718610473e-06 2.8911958048589e-05 5.20973653460345e-05 -1.61882278724578e-06 3.94682893127677e-06 2.06495718610473e-06 0.00010455704836899 1570 1570 0 17 27 1535 1550 0 32 5 0 0 0 0 0 2 12 0 250 0 93 77 0 0 2279 +358 385 0.994154758069263 0.00101697983372598 0.107959634865368 -0.0253354186323368 -0.0159791517308044 0.990328891979378 0.137816372107456 -0.0216957464577637 -0.106775389103527 -0.138735905456788 0.98455643048983 -0.00787055672258962 6.5019018043322e-05 1.80445176231264e-05 -6.02679193742464e-06 -6.43914521273711e-06 3.39269384607407e-06 2.58595512868121e-05 1.80445176231264e-05 5.54099928978576e-05 -5.68688713506371e-06 1.18845452722653e-05 5.07940653477921e-06 5.69251007674394e-06 -6.02679193742464e-06 -5.68688713506371e-06 1.32195898568869e-05 3.01818726040648e-06 1.1435165548656e-06 -3.86683612578729e-07 -6.43914521273711e-06 1.18845452722653e-05 3.01818726040648e-06 4.47309619001446e-05 -7.12658734913567e-06 -7.84217679414001e-06 3.39269384607407e-06 5.07940653477921e-06 1.1435165548656e-06 -7.12658734913567e-06 4.45653928281241e-05 2.5196532894067e-06 2.58595512868121e-05 5.69251007674394e-06 -3.86683612578729e-07 -7.84217679414001e-06 2.5196532894067e-06 9.67331343449979e-05 1709 1704 0 16 21 1721 1750 0 31 7 0 0 0 0 0 2 11 0 432 0 120 103 0 0 2638 +358 394 0.993639688380887 0.000545425707025983 0.112604938546811 -0.0171173756016858 -0.0165489211014962 0.989837738915547 0.141235207469433 -0.024301505443918 -0.111383584449008 -0.142200397781988 0.983551088650679 0.0016641204375618 6.05819066051905e-05 2.76822789982312e-05 -5.12704028224382e-06 1.62649468096106e-06 -7.27407417474671e-06 2.213845052693e-05 2.76822789982312e-05 6.70153845596031e-05 -2.20462946737279e-06 2.02234988142026e-05 -9.16327721099372e-06 1.29498043169003e-05 -5.12704028224382e-06 -2.20462946737279e-06 1.18695399238074e-05 5.18727640298332e-06 4.23874464209317e-06 -2.71999471561115e-06 1.62649468096106e-06 2.02234988142026e-05 5.18727640298332e-06 4.94996735290742e-05 -8.72227509402958e-06 1.12428185537117e-05 -7.27407417474671e-06 -9.16327721099372e-06 4.23874464209317e-06 -8.72227509402958e-06 4.7437275871726e-05 -6.84766457145764e-06 2.213845052693e-05 1.29498043169003e-05 -2.71999471561115e-06 1.12428185537117e-05 -6.84766457145764e-06 7.92205522286225e-05 1634 1635 0 19 21 1581 1593 0 32 0 0 0 0 0 0 2 13 0 249 0 103 83 0 0 2329 +358 390 0.993904733785362 0.000368576227343142 0.110241753934763 -0.0185349435676151 -0.0158209980477955 0.990120063683295 0.139326793950621 -0.0229895712942692 -0.109101219882364 -0.140221694624447 0.984090849554465 0.00979783968549239 7.08857527042311e-05 2.36024428958995e-05 -6.63309367495408e-06 5.35639082109603e-06 -7.34895992738303e-06 1.96858813497963e-05 2.36024428958995e-05 7.12706944576496e-05 -6.20378945195305e-06 2.61760853070115e-05 -9.81143621332967e-07 2.79444995690015e-05 -6.63309367495408e-06 -6.20378945195305e-06 1.25424104453738e-05 4.18714975449234e-06 5.24378393153609e-06 -2.55840668283802e-06 5.35639082109603e-06 2.61760853070115e-05 4.18714975449234e-06 6.35753445871172e-05 -1.48682502493925e-05 2.74931849180511e-05 -7.34895992738303e-06 -9.81143621332967e-07 5.24378393153609e-06 -1.48682502493925e-05 4.85304923996679e-05 -5.37950290866535e-06 1.96858813497963e-05 2.79444995690015e-05 -2.55840668283802e-06 2.74931849180511e-05 -5.37950290866535e-06 9.10497600495022e-05 1684 1684 0 16 28 1646 1665 0 33 6 0 0 0 0 0 4 13 0 217 0 98 74 0 0 2374 +358 413 0.993743637725177 0.0019558467021942 0.11166806680699 -0.0209967818710094 -0.0166427353479213 0.991276583806579 0.130743083017412 -0.0243412749910246 -0.110438226356964 -0.131783569007811 0.985107349022781 0.00120722813876431 0.000156958779786829 7.37396722382442e-05 -2.08091833309352e-05 2.40555809881672e-05 -2.67134746805078e-05 8.83800433316511e-05 7.37396722382442e-05 9.23796635055565e-05 -1.35601624391638e-05 2.41268164024333e-05 -2.40172190564781e-06 6.87779744908253e-05 -2.08091833309352e-05 -1.35601624391638e-05 1.33304323057856e-05 -5.16180967351495e-07 5.55293555803227e-06 -1.32053589866714e-05 2.40555809881672e-05 2.41268164024333e-05 -5.16180967351495e-07 4.86149585551711e-05 -7.89607411701795e-06 2.43000093103471e-05 -2.67134746805078e-05 -2.40172190564781e-06 5.55293555803227e-06 -7.89607411701795e-06 5.06225769471598e-05 -1.73597507604255e-05 8.83800433316511e-05 6.87779744908253e-05 -1.32053589866714e-05 2.43000093103471e-05 -1.73597507604255e-05 0.000156393011356157 1667 1673 0 19 11 1634 1646 0 31 4 0 0 0 0 0 4 15 0 389 0 62 65 0 0 2122 +358 389 0.993974488760629 -0.000148067164672833 0.109611558556389 -0.0203701035084248 -0.0157716033451712 0.989400144953857 0.144355843987038 -0.0217920875291786 -0.108471066284833 -0.145214776250223 0.983436168003612 -0.00034026919745926 5.40417033703851e-05 9.39673220621956e-06 -3.06270189642132e-06 -2.68104296717681e-06 -1.71170086184921e-06 1.72289742385344e-05 9.39673220621956e-06 5.01936984121836e-05 -2.4113218881814e-06 7.92054829731631e-06 3.93356890899966e-06 7.62669975759813e-06 -3.06270189642132e-06 -2.4113218881814e-06 1.08057567661503e-05 3.62855738049789e-06 5.47700811219978e-06 -1.66989288915355e-06 -2.68104296717681e-06 7.92054829731631e-06 3.62855738049789e-06 4.05453839302187e-05 -1.2076568179094e-05 -9.2446907122814e-06 -1.71170086184921e-06 3.93356890899966e-06 5.47700811219978e-06 -1.2076568179094e-05 4.7270653986431e-05 5.48028063797991e-06 1.72289742385344e-05 7.62669975759813e-06 -1.66989288915355e-06 -9.2446907122814e-06 5.48028063797991e-06 8.06324723097761e-05 1659 1663 0 19 26 1622 1637 0 32 7 0 0 0 0 0 2 12 0 291 0 96 73 0 0 2470 +359 387 0.994501091530094 -0.00270782082532004 0.10469119663004 -0.0290712632651168 -0.0120407344462942 0.990080025274701 0.1399877289838 -0.0172524505387108 -0.10403172429334 -0.140478508172696 0.984603061686347 -0.000948114015456364 7.85265824014128e-05 4.67290740550505e-05 -1.07064635594767e-05 7.28779329522971e-06 3.86247583681216e-06 4.32194651897323e-05 4.67290740550505e-05 7.10659089751345e-05 -1.01816765724868e-05 1.54838717507233e-05 4.15332212905256e-06 3.4040291366211e-05 -1.07064635594767e-05 -1.01816765724868e-05 1.42248000009477e-05 -8.4657014925867e-07 -2.2943265076832e-08 -6.45999854076529e-06 7.28779329522971e-06 1.54838717507233e-05 -8.4657014925867e-07 4.82722832433282e-05 -6.86700522021345e-06 4.47241074434893e-06 3.86247583681216e-06 4.15332212905256e-06 -2.2943265076832e-08 -6.86700522021345e-06 4.75132304261064e-05 -4.08738301284587e-06 4.32194651897323e-05 3.4040291366211e-05 -6.45999854076529e-06 4.47241074434893e-06 -4.08738301284587e-06 0.000100044606142408 1604 1608 0 10 26 1571 1599 0 26 8 0 0 0 0 0 3 16 0 446 0 98 78 0 0 2616 +358 391 0.992473745296788 0.00133261679148775 0.122450353323514 -0.0130211455356671 -0.0174104784142255 0.991318393374724 0.130325431893948 -0.023372207086755 -0.121213613665933 -0.131476488732562 0.983880680150089 0.00803863649756678 0.00012830371373432 7.91427090491828e-05 -1.32907860800638e-05 2.6111981916921e-05 -3.13023851449106e-05 6.3845488966073e-05 7.91427090491828e-05 0.000125735698714178 -1.24470199604221e-05 4.49402074852032e-05 -3.22618888514677e-05 7.40761550161196e-05 -1.32907860800638e-05 -1.24470199604221e-05 1.27207266066157e-05 1.59775829816403e-07 8.7057616134643e-06 -9.02228284142307e-06 2.6111981916921e-05 4.49402074852032e-05 1.59775829816403e-07 6.06420717763932e-05 -2.27902663155375e-05 3.79769900786848e-05 -3.13023851449106e-05 -3.22618888514677e-05 8.7057616134643e-06 -2.27902663155375e-05 4.98848133770463e-05 -2.70609547439291e-05 6.3845488966073e-05 7.40761550161196e-05 -9.02228284142307e-06 3.79769900786848e-05 -2.70609547439291e-05 0.000157238398179834 1626 1627 0 19 21 1559 1572 0 31 0 0 0 0 0 0 4 14 0 204 0 137 121 0 0 2302 +358 414 0.993904730224088 -0.00021699287231471 0.110242188622486 -0.0294892564848126 -0.0155702783501533 0.989697625667577 0.14232419393785 -0.0170646232939556 -0.109137315663714 -0.143173191142942 0.983661773003132 -0.00419625871675501 5.40945184510451e-05 1.3814542958784e-05 -8.27833208675162e-06 -4.65376833840086e-06 1.0484705801353e-05 1.43998130553257e-05 1.3814542958784e-05 4.29709377533572e-05 -6.09493123996316e-06 1.14821634575481e-05 4.43240777807878e-06 2.36637105568105e-06 -8.27833208675162e-06 -6.09493123996316e-06 1.27250954948819e-05 2.22886592892112e-06 1.86433889766317e-06 -4.94456761287161e-06 -4.65376833840086e-06 1.14821634575481e-05 2.22886592892112e-06 5.53644040135793e-05 -1.29605777268411e-05 -3.56525515140623e-06 1.0484705801353e-05 4.43240777807878e-06 1.86433889766317e-06 -1.29605777268411e-05 4.44618316927631e-05 1.14895994903091e-05 1.43998130553257e-05 2.36637105568105e-06 -4.94456761287161e-06 -3.56525515140623e-06 1.14895994903091e-05 6.77217585508931e-05 1736 1737 0 12 11 1728 1748 0 31 6 0 0 0 0 0 2 15 0 386 0 98 101 0 0 2232 +358 408 0.994102001935595 0.000781148483820553 0.108446298022055 -0.0231675566446507 -0.0160249389892458 0.990054960371782 0.139765434831432 -0.0211829898764687 -0.107258617733183 -0.140678943876739 0.98422813598865 -0.00983227051990813 5.61690118288573e-05 1.7526939938292e-05 -5.12267881255515e-06 7.71704437145988e-07 -1.01221208470441e-05 1.42185267004765e-05 1.7526939938292e-05 6.49184514014057e-05 -1.90261222029918e-06 1.46710742095571e-05 2.03869996369635e-06 2.74185388373138e-05 -5.12267881255515e-06 -1.90261222029918e-06 1.11089466030381e-05 4.62811734287051e-06 6.51721274265527e-06 1.38294505080931e-06 7.71704437145988e-07 1.46710742095571e-05 4.62811734287051e-06 4.86416124064554e-05 -1.4236848532228e-05 4.9911517371889e-06 -1.01221208470441e-05 2.03869996369635e-06 6.51721274265527e-06 -1.4236848532228e-05 4.63269856211652e-05 -1.03218577904546e-07 1.42185267004765e-05 2.74185388373138e-05 1.38294505080931e-06 4.9911517371889e-06 -1.03218577904546e-07 8.98278049383778e-05 1637 1641 0 15 14 1622 1636 0 31 5 0 0 0 0 0 4 15 0 290 0 97 101 0 0 2175 +359 396 0.993317130377467 -0.00346764444903574 0.115364873079503 -0.0152859167974821 -0.0128414034020229 0.990022150756104 0.14032547655691 -0.0292675247434462 -0.114700378627715 -0.140869146565998 0.983361432377956 0.00627442761696024 9.21338113154417e-05 6.01129416186267e-05 -6.6993862266855e-06 2.44494465281549e-05 -2.44922839734455e-05 5.45714597285649e-05 6.01129416186267e-05 0.000115108823729272 -4.0274642431296e-06 4.4698615000722e-05 -2.93012501392914e-05 5.82168479190843e-05 -6.6993862266855e-06 -4.0274642431296e-06 1.22648579941558e-05 2.74873741950949e-06 5.47416572994204e-06 -4.43049414467515e-06 2.44494465281549e-05 4.4698615000722e-05 2.74873741950949e-06 7.43864149550376e-05 -2.58630208350294e-05 3.23167172667075e-05 -2.44922839734455e-05 -2.93012501392914e-05 5.47416572994204e-06 -2.58630208350294e-05 6.13676388794687e-05 -2.64383438809113e-05 5.45714597285649e-05 5.82168479190843e-05 -4.43049414467515e-06 3.23167172667075e-05 -2.64383438809113e-05 0.000138727146585111 1494 1487 0 10 26 1473 1492 0 27 6 0 0 0 0 0 4 18 0 259 0 108 91 0 0 2319 +359 362 0.999571050297096 0.000874467892291501 0.0292737205333646 -0.026727836068984 -0.00219527891669911 0.998979267516158 0.0451176664218989 0.0144414285172831 -0.0292043859452323 -0.0451625771937918 0.998552675357077 -0.00759856879855857 0.000103763710364735 4.52055724422731e-05 -1.66363280258173e-05 1.39777085208409e-05 2.02349825673361e-06 5.40881367352064e-05 4.52055724422731e-05 9.04958845258343e-05 -1.68074947975332e-05 2.76922657512946e-05 9.10673905295574e-06 4.9623915772141e-05 -1.66363280258173e-05 -1.68074947975332e-05 1.80477985464205e-05 -2.51740107857413e-06 -2.60710010597582e-06 -1.50295018975221e-05 1.39777085208409e-05 2.76922657512946e-05 -2.51740107857413e-06 5.86486151057986e-05 -2.28043886421381e-05 2.7547619492862e-05 2.02349825673361e-06 9.10673905295574e-06 -2.60710010597582e-06 -2.28043886421381e-05 6.5403342651216e-05 -5.9319291336975e-06 5.40881367352064e-05 4.9623915772141e-05 -1.50295018975221e-05 2.7547619492862e-05 -5.9319291336975e-06 9.87927531965805e-05 2318 2294 0 2 52 2282 2299 0 17 23 0 0 0 0 0 13 25 0 353 0 74 48 0 0 3178 +359 386 0.994032395296276 -0.002792260548623 0.109049531785225 -0.0196480904665323 -0.0127433555266224 0.989855269144384 0.141506724352665 -0.0207103202437543 -0.108338377279108 -0.14205192511236 0.983912621415338 0.00530452577239854 8.32451269011132e-05 4.41182225112208e-05 -8.49580022654506e-06 2.64067759352316e-06 -5.02193832428827e-06 3.59388368105042e-05 4.41182225112208e-05 7.18784475362638e-05 -8.37845820317784e-06 1.6666890214294e-05 -4.65334031960536e-06 2.02323548979761e-05 -8.49580022654506e-06 -8.37845820317784e-06 1.25515580387212e-05 2.70568488757159e-06 3.54751886119628e-06 -3.50692341677777e-06 2.64067759352316e-06 1.6666890214294e-05 2.70568488757159e-06 4.35518174884224e-05 -2.09605722088655e-06 4.47432365195329e-06 -5.02193832428827e-06 -4.65334031960536e-06 3.54751886119628e-06 -2.09605722088655e-06 3.74061736904247e-05 -8.44783022621609e-06 3.59388368105042e-05 2.02323548979761e-05 -3.50692341677777e-06 4.47432365195329e-06 -8.44783022621609e-06 8.72024657667922e-05 1649 1641 0 8 24 1619 1640 0 28 4 0 0 0 0 0 3 17 0 436 0 109 87 0 0 2676 +359 388 0.994240194583756 -0.00349264921476958 0.107117864408871 -0.0209762342607078 -0.0120876321856807 0.989437461058281 0.144455528806225 -0.0228014406000134 -0.106490960283952 -0.14491829441449 0.983696275951981 -0.00502458463672659 8.22917302101353e-05 5.55980670503755e-05 -7.65290898199105e-06 3.51295732678638e-06 -7.61981365414877e-06 5.06068531507597e-05 5.55980670503755e-05 7.38053183354723e-05 -6.87797593763588e-06 7.38165838549176e-06 -8.47578608920691e-06 4.46003322982912e-05 -7.65290898199105e-06 -6.87797593763588e-06 1.19514705672189e-05 2.8853119941136e-06 7.08061782681605e-06 -5.90229601829692e-06 3.51295732678638e-06 7.38165838549176e-06 2.8853119941136e-06 4.53206946939077e-05 -1.51636161272233e-05 9.81455442083876e-06 -7.61981365414877e-06 -8.47578608920691e-06 7.08061782681605e-06 -1.51636161272233e-05 3.87683625713951e-05 -1.2772866688567e-05 5.06068531507597e-05 4.46003322982912e-05 -5.90229601829692e-06 9.81455442083876e-06 -1.2772866688567e-05 8.5074094998366e-05 1792 1786 0 10 29 1767 1799 0 27 11 0 0 0 0 0 3 16 0 450 0 112 95 0 0 2498 +359 361 0.999666890540714 0.00306957045686415 0.0256258793775076 -0.014462970407684 -0.00369168662843566 0.999698745999462 0.0242649685130687 0.00691195010349021 -0.0255436764483433 -0.0243514883387676 0.999377068782944 -0.00263791690123934 5.84515624398897e-05 2.15154113867925e-05 -9.30434946985286e-06 1.26620166387626e-05 -9.40228437967461e-06 2.32275541207161e-05 2.15154113867925e-05 5.59958442978125e-05 -9.21785091294903e-06 1.53913375282389e-05 5.00389254994081e-06 2.49136143992248e-05 -9.30434946985286e-06 -9.21785091294903e-06 1.40551343864872e-05 -8.02544318334792e-09 2.36098106878912e-06 -7.83924020517344e-06 1.26620166387626e-05 1.53913375282389e-05 -8.02544318334792e-09 4.50247103143435e-05 -1.29312312590767e-05 2.10994546706862e-05 -9.40228437967461e-06 5.00389254994081e-06 2.36098106878912e-06 -1.29312312590767e-05 4.87898853882912e-05 -9.23445319214497e-06 2.32275541207161e-05 2.49136143992248e-05 -7.83924020517344e-06 2.10994546706862e-05 -9.23445319214497e-06 7.01247706281369e-05 2002 1973 0 5 65 1980 1994 0 23 22 0 0 0 0 0 8 22 0 369 0 85 59 0 0 3279 +359 395 0.993473899452047 -0.00238195197865157 0.114034807897921 -0.0151487427558767 -0.0132231497944951 0.990635310121737 0.135892717426367 -0.0245754597509474 -0.113290597213787 -0.136513767235329 0.984138827573713 0.0063908147298834 9.4681242490566e-05 7.39512558259338e-05 -7.02679123385314e-06 2.21472005316834e-05 -1.83766576539527e-05 7.45313871899915e-05 7.39512558259338e-05 0.000112729946857056 -7.74725535626039e-06 2.53460184951625e-05 -1.68221094710047e-05 7.50095963571841e-05 -7.02679123385314e-06 -7.74725535626039e-06 1.18653066859448e-05 2.25514054584569e-06 6.59105352152545e-06 -7.15885366042145e-06 2.21472005316834e-05 2.53460184951625e-05 2.25514054584569e-06 4.55148303151032e-05 -1.41664762939331e-05 2.98068044381526e-05 -1.83766576539527e-05 -1.68221094710047e-05 6.59105352152545e-06 -1.41664762939331e-05 4.50721819359517e-05 -2.36054131447672e-05 7.45313871899915e-05 7.50095963571841e-05 -7.15885366042145e-06 2.98068044381526e-05 -2.36054131447672e-05 0.000158298085841189 1883 1888 0 11 26 1856 1881 0 28 9 0 0 0 0 0 5 19 0 255 0 100 85 0 0 2326 +359 363 0.998355371976259 5.89674927807989e-05 0.0573284202553986 -0.0211791326967683 -0.00470256027480025 0.996713701099803 0.0808683125012203 -0.000621330579441297 -0.0571352533293296 -0.0810049045599582 0.995074755113517 -0.00449458252742616 0.00010650493646988 4.47970438916297e-05 -1.52795090875425e-05 9.95507506821074e-06 -6.39657411980069e-06 4.87931772512762e-05 4.47970438916297e-05 0.000101724671595422 -1.1799183774112e-05 2.73368093427413e-05 1.0537272513183e-05 6.90912025873297e-05 -1.52795090875425e-05 -1.1799183774112e-05 1.45715751451959e-05 1.82689810172663e-06 1.83285542847388e-06 -1.16386199100661e-05 9.95507506821074e-06 2.73368093427413e-05 1.82689810172663e-06 5.53708988578424e-05 -1.56924772170307e-05 4.62552107441869e-05 -6.39657411980069e-06 1.0537272513183e-05 1.83285542847388e-06 -1.56924772170307e-05 5.42423089565021e-05 -8.45270218837759e-06 4.87931772512762e-05 6.90912025873297e-05 -1.16386199100661e-05 4.62552107441869e-05 -8.45270218837759e-06 0.000133278584041813 2002 1988 0 6 42 1973 2002 0 23 16 0 0 0 0 0 11 22 0 381 0 87 59 0 0 3119 +359 410 0.993436188942371 -0.00222026052812654 0.114366117984499 -0.0229149738072007 -0.0133348210384076 0.99074682623623 0.135066312790094 -0.0176726128679968 -0.113607750825068 -0.13570481474887 0.984214144486069 0.0058544940795082 0.00013436187587241 8.84679981809375e-05 -1.39113010310888e-05 3.86400626590511e-06 -1.54016890729165e-05 9.88201440724461e-05 8.84679981809375e-05 0.000113538504191713 -1.07993630214802e-05 1.23198194830201e-05 -8.54523838099004e-06 8.15364324195114e-05 -1.39113010310888e-05 -1.07993630214802e-05 1.17972441305957e-05 3.77227444622378e-06 6.99082511743745e-06 -1.28141732246392e-05 3.86400626590511e-06 1.23198194830201e-05 3.77227444622378e-06 4.37452275092112e-05 -1.01521408905511e-05 3.00798816351088e-06 -1.54016890729165e-05 -8.54523838099004e-06 6.99082511743745e-06 -1.01521408905511e-05 4.10357045703623e-05 -1.22271136613286e-05 9.88201440724461e-05 8.15364324195114e-05 -1.28141732246392e-05 3.00798816351088e-06 -1.22271136613286e-05 0.000166156937393345 1554 1554 0 8 19 1546 1568 0 28 16 0 0 0 0 0 8 20 0 311 0 60 63 0 0 2122 +359 412 0.994473331698941 -0.00281959170397897 0.10495161953124 -0.0293884287771928 -0.0122452098385079 0.98970191950821 0.142618951608037 -0.0131704704998812 -0.104272946518348 -0.143115898573106 0.984197638790093 -0.00134330182850455 5.84263386710971e-05 3.55241816529188e-05 -6.85775740192313e-06 1.60325148380858e-05 -7.86231581316561e-06 3.52639214248665e-05 3.55241816529188e-05 5.74480907616543e-05 -7.11432689005816e-06 2.5225307872861e-05 -8.13356032644641e-06 2.67247342778968e-05 -6.85775740192313e-06 -7.11432689005816e-06 1.14655445977523e-05 4.12462202613142e-06 3.49596339887865e-07 -6.82859656297654e-06 1.60325148380858e-05 2.5225307872861e-05 4.12462202613142e-06 6.44498894271734e-05 -3.53390392461975e-05 1.44195950954408e-05 -7.86231581316561e-06 -8.13356032644641e-06 3.49596339887865e-07 -3.53390392461975e-05 6.96230966409256e-05 -1.29029009560571e-05 3.52639214248665e-05 2.67247342778968e-05 -6.82859656297654e-06 1.44195950954408e-05 -1.29029009560571e-05 8.86498996397663e-05 1556 1554 0 6 21 1573 1594 0 28 19 0 0 0 0 0 6 19 0 377 0 57 59 0 0 2105 +359 411 0.994485793641976 -0.00270468066391939 0.104836496253911 -0.0254944440855047 -0.0122092557913123 0.989883559956799 0.141355833980336 -0.0158634588006874 -0.104158246516118 -0.141856344340887 0.984392115598722 0.00255413511389792 0.000154725663777865 0.000152986341001546 -1.44526633790546e-05 6.60452359337378e-05 -5.83331443334056e-05 0.000166949939684731 0.000152986341001546 0.000198912205591345 -1.73749489588792e-05 8.6696166491181e-05 -7.55629190504462e-05 0.000189150966669315 -1.44526633790546e-05 -1.73749489588792e-05 1.18792197409998e-05 -2.25921975521582e-06 8.44421523661205e-06 -1.49325350868538e-05 6.60452359337378e-05 8.6696166491181e-05 -2.25921975521582e-06 8.56828199560657e-05 -5.33184500594759e-05 9.61349804070102e-05 -5.83331443334056e-05 -7.55629190504462e-05 8.44421523661205e-06 -5.33184500594759e-05 8.28803756660968e-05 -9.42088622348677e-05 0.000166949939684731 0.000189150966669315 -1.49325350868538e-05 9.61349804070102e-05 -9.42088622348677e-05 0.000275938227531521 1347 1349 0 7 24 1369 1393 0 29 20 0 0 0 0 0 6 19 0 353 0 54 56 0 0 2163 +359 385 0.994269753273796 -0.00304169203976922 0.106856940974368 -0.023713026075318 -0.0123728640221565 0.989602721739183 0.143294680160465 -0.0212997788724195 -0.106181777912943 -0.143795692689093 0.98389441954069 -0.00353380033918827 6.60867067731732e-05 4.02642084986854e-05 -8.18723694521889e-06 1.63254257851955e-05 -7.99022734360099e-06 3.68172629845782e-05 4.02642084986854e-05 8.14265965753912e-05 -7.77090826248462e-06 3.3659227464928e-05 -1.39555789870132e-05 3.75227039485429e-05 -8.18723694521889e-06 -7.77090826248462e-06 1.24013500146321e-05 1.76545534974978e-06 1.75424013234846e-06 -5.34348242754399e-06 1.63254257851955e-05 3.3659227464928e-05 1.76545534974978e-06 5.54413357546507e-05 -1.86405369151592e-05 1.7592051943657e-05 -7.99022734360099e-06 -1.39555789870132e-05 1.75424013234846e-06 -1.86405369151592e-05 4.94585454498491e-05 -1.12538710142893e-05 3.68172629845782e-05 3.75227039485429e-05 -5.34348242754399e-06 1.7592051943657e-05 -1.12538710142893e-05 9.83665625849366e-05 1782 1771 0 9 28 1764 1796 0 28 11 0 0 0 0 0 4 19 0 442 0 111 94 0 0 2576 +359 409 0.993846882730501 -0.00224624331029409 0.110739911855915 -0.026234660994943 -0.0129494251441555 0.99058174898221 0.1363088807517 -0.0196529700872465 -0.11000311847989 -0.136904174422609 0.984457495756096 0.00524656808913564 0.000102078294790515 9.51607692365589e-05 -6.49200672585224e-06 2.23391284605942e-05 -1.86853245222133e-05 9.33749572204489e-05 9.51607692365589e-05 0.000171074074259452 -6.42094097186631e-06 5.29512861986889e-05 -3.08216633838005e-05 0.000121773660820319 -6.49200672585224e-06 -6.42094097186631e-06 1.08469461229707e-05 2.46674401774811e-06 5.85805568073661e-06 -7.17158535219899e-06 2.23391284605942e-05 5.29512861986889e-05 2.46674401774811e-06 6.72636535507301e-05 -1.35110204649095e-05 4.61684186801636e-05 -1.86853245222133e-05 -3.08216633838005e-05 5.85805568073661e-06 -1.35110204649095e-05 4.59898811911629e-05 -3.81670127050519e-05 9.33749572204489e-05 0.000121773660820319 -7.17158535219899e-06 4.61684186801636e-05 -3.81670127050519e-05 0.000212659718045955 1632 1632 0 9 22 1618 1639 0 28 17 0 0 0 0 0 4 17 0 305 0 67 70 0 0 2143 +359 408 0.993317247415158 -0.00269978186780834 0.115384388742323 -0.0202149327808937 -0.0132237044169254 0.990480675129952 0.137015202936058 -0.0180006571032454 -0.114655918421453 -0.137625373285531 0.983825836720581 0.00614581957208782 0.000147010071138243 0.000127068367627643 -1.21140964042581e-05 4.51220108033748e-05 -5.78031644810296e-05 0.000157818165757408 0.000127068367627643 0.000167702420368374 -1.30835453855478e-05 6.59974879609949e-05 -6.92479627838155e-05 0.000176665565641349 -1.21140964042581e-05 -1.30835453855478e-05 1.2642017330444e-05 -4.64006100075809e-07 1.11046797424307e-05 -1.55004332406391e-05 4.51220108033748e-05 6.59974879609949e-05 -4.64006100075809e-07 6.4506403610707e-05 -3.66111775133226e-05 8.29179196758244e-05 -5.78031644810296e-05 -6.92479627838155e-05 1.11046797424307e-05 -3.66111775133226e-05 7.58898761753209e-05 -9.35613337274201e-05 0.000157818165757408 0.000176665565641349 -1.55004332406391e-05 8.29179196758244e-05 -9.35613337274201e-05 0.000294271340893896 1565 1576 0 7 29 1541 1569 0 28 22 0 0 0 0 0 5 20 0 295 0 53 57 0 0 2138 +359 414 0.995056751172048 -0.00345785636788039 0.0992476960753671 -0.0352240888676069 -0.0113040501964974 0.988954138077415 0.147790159444775 -0.012898777624134 -0.0986624568723301 -0.14818149685064 0.984026403911511 -0.00990558436540142 0.000140667236340223 8.76999555793597e-05 -1.85588808980142e-05 3.49917788351642e-05 -2.86775563710877e-05 0.000103782479978587 8.76999555793597e-05 0.000111704830112049 -1.64172828442389e-05 3.86895169072187e-05 -1.84959295423974e-05 8.92090726414761e-05 -1.85588808980142e-05 -1.64172828442389e-05 1.35023616448382e-05 3.71416793199623e-07 4.69090301926137e-06 -1.31223444669695e-05 3.49917788351642e-05 3.86895169072187e-05 3.71416793199623e-07 7.21472727524805e-05 -3.07136166751411e-05 4.15598073236648e-05 -2.86775563710877e-05 -1.84959295423974e-05 4.69090301926137e-06 -3.07136166751411e-05 5.90819667871816e-05 -3.1240427079044e-05 0.000103782479978587 8.92090726414761e-05 -1.31223444669695e-05 4.15598073236648e-05 -3.1240427079044e-05 0.000165144300791358 1746 1754 0 9 25 1726 1754 0 28 23 0 0 0 0 0 7 19 0 401 0 45 48 0 0 2189 +359 394 0.993910782350673 -0.00319013219972194 0.110141635105087 -0.0191487909709719 -0.0125648773787825 0.989779375559448 0.142052495837301 -0.0242705814556662 -0.109469085058431 -0.142571423411911 0.983712309896939 0.00426049909975646 6.32908201618014e-05 2.70760839291069e-05 -7.65345810286623e-07 3.20335070456341e-07 -9.96607786487466e-06 1.85320891895516e-05 2.70760839291069e-05 6.72890181767829e-05 -2.97593233528857e-06 1.00240683938613e-05 -2.73931467191205e-06 4.30467418503251e-06 -7.65345810286623e-07 -2.97593233528857e-06 1.07484306250353e-05 6.09409842296582e-06 6.12821350615245e-06 -1.39991282073618e-06 3.20335070456341e-07 1.00240683938613e-05 6.09409842296582e-06 4.1645069925781e-05 -1.94096474567343e-06 8.23693403033813e-06 -9.96607786487466e-06 -2.73931467191205e-06 6.12821350615245e-06 -1.94096474567343e-06 4.38215387295131e-05 -1.01801970985288e-05 1.85320891895516e-05 4.30467418503251e-06 -1.39991282073618e-06 8.23693403033813e-06 -1.01801970985288e-05 6.72423640743373e-05 1472 1467 0 9 24 1451 1468 0 29 5 0 0 0 0 0 3 16 0 260 0 109 89 0 0 2331 +359 397 0.99508214992535 -0.00249289193999671 0.0990217167580831 -0.0298580770751325 -0.0117523788744209 0.989650620008083 0.143015844955757 -0.019523101022305 -0.0983534264310837 -0.143476255204102 0.984754369222027 0.00102490884542571 8.77831596582863e-05 4.41913080229713e-05 -9.29112185439773e-06 1.02046151017996e-05 -1.48622446015524e-05 5.14062312013107e-05 4.41913080229713e-05 8.16359737933725e-05 -7.19711206165025e-06 4.24644687141443e-05 -2.28855494840581e-05 4.59884052359547e-05 -9.29112185439773e-06 -7.19711206165025e-06 1.15983350648111e-05 4.17910021399286e-06 3.20247466365415e-06 -5.75939863646203e-06 1.02046151017996e-05 4.24644687141443e-05 4.17910021399286e-06 9.95609758400534e-05 -5.79051746462704e-05 2.78057609360363e-05 -1.48622446015524e-05 -2.28855494840581e-05 3.20247466365415e-06 -5.79051746462704e-05 8.91278549502914e-05 -2.34335930786054e-05 5.14062312013107e-05 4.59884052359547e-05 -5.75939863646203e-06 2.78057609360363e-05 -2.34335930786054e-05 0.00010751009288317 1392 1387 0 7 30 1397 1415 0 28 8 0 0 0 0 0 6 19 0 270 0 89 74 0 0 2270 +359 389 0.99488526287702 -0.00282715521686039 0.100971881746867 -0.0288734854551669 -0.0118002926083696 0.989510949630326 0.143975114711007 -0.0168475831261331 -0.100319822589957 -0.14443021759684 0.984416499983848 -0.00280750468814398 4.45473681350122e-05 1.90108402457775e-06 8.48965547582687e-07 -3.41542687981463e-06 -5.83419165333992e-06 1.35214784383745e-05 1.90108402457775e-06 4.37229851652304e-05 -2.85731915904645e-06 5.58517715948667e-06 -9.37670224514047e-07 -1.82133556895591e-06 8.48965547582687e-07 -2.85731915904645e-06 1.02510747407518e-05 2.2652605286227e-06 5.05567751289065e-06 -1.42344549008979e-06 -3.41542687981463e-06 5.58517715948667e-06 2.2652605286227e-06 4.62125003894945e-05 -1.41493448503982e-05 -5.30571614268623e-07 -5.83419165333992e-06 -9.37670224514047e-07 5.05567751289065e-06 -1.41493448503982e-05 5.13721216694771e-05 -1.80264549517472e-06 1.35214784383745e-05 -1.82133556895591e-06 -1.42344549008979e-06 -5.30571614268623e-07 -1.80264549517472e-06 5.51676330622576e-05 1620 1609 0 7 30 1620 1636 0 27 10 0 0 0 0 0 6 20 0 312 0 96 73 0 0 2364 +359 413 0.993934426859007 -0.00222722033615505 0.109951783041618 -0.0246823775866674 -0.0130724306184025 0.990313687610378 0.138231370134504 -0.0209185180156244 -0.109194627441939 -0.138830254703754 0.984277752322334 0.000834840356300731 0.000134325229345113 0.000108768239349748 -1.47263031956595e-05 3.34115339155355e-05 -2.66533805289701e-05 0.000108657046161151 0.000108768239349748 0.000141752682869469 -1.49874602164087e-05 4.27649763072229e-05 -3.14988291037286e-05 0.000111658348330677 -1.47263031956595e-05 -1.49874602164087e-05 1.25407978401337e-05 1.22529687971238e-06 4.08933833175204e-06 -1.00797642726696e-05 3.34115339155355e-05 4.27649763072229e-05 1.22529687971238e-06 5.38456443857162e-05 -1.72636535761923e-05 4.68459617982068e-05 -2.66533805289701e-05 -3.14988291037286e-05 4.08933833175204e-06 -1.72636535761923e-05 5.70366486308606e-05 -4.1840325301417e-05 0.000108657046161151 0.000111658348330677 -1.00797642726696e-05 4.68459617982068e-05 -4.1840325301417e-05 0.000216518692855473 1473 1472 0 8 24 1457 1477 0 28 20 0 0 0 0 0 3 18 0 401 0 65 69 0 0 2099 +360 362 0.999818841441082 0.000199251292510663 0.0190327244065329 -0.0218280532629872 -0.00094154582416564 0.999238768264701 0.0389999677987609 0.0179035573625648 -0.0190104652987137 -0.0390108228029841 0.999057935213649 -0.00721016374210648 6.06049758551964e-05 2.23768984334188e-05 -7.6213601587052e-06 9.43892874817594e-06 -4.38170068914008e-06 1.92268702274178e-05 2.23768984334188e-05 6.27149694428832e-05 -7.64286280931242e-06 1.56912623972436e-05 2.64288689409929e-06 4.32598498632208e-05 -7.6213601587052e-06 -7.64286280931242e-06 1.2163797692797e-05 -7.77511510872813e-07 1.37943757657522e-06 -7.28026284629655e-06 9.43892874817594e-06 1.56912623972436e-05 -7.77511510872813e-07 4.87266648913471e-05 -2.55918092816414e-05 1.83822924133816e-05 -4.38170068914008e-06 2.64288689409929e-06 1.37943757657522e-06 -2.55918092816414e-05 5.63555673372463e-05 -7.57192054736042e-07 1.92268702274178e-05 4.32598498632208e-05 -7.28026284629655e-06 1.83822924133816e-05 -7.57192054736042e-07 8.46143636301796e-05 2356 2331 0 11 62 2323 2345 0 32 38 0 0 0 0 0 8 19 0 352 0 69 41 0 0 3186 +360 387 0.996365193370514 -0.00189345092945474 0.0851634680089805 -0.0229641758473118 -0.00990322015632119 0.990399173581102 0.137881845071807 -0.0159683176937182 -0.084606900843101 -0.138224063800223 0.986780512837722 -0.00713989579184366 6.51918961311103e-05 3.01897310768562e-05 -1.24893307471488e-05 9.5799268629398e-06 6.23038709721605e-06 1.88952269811975e-05 3.01897310768562e-05 7.36708457593891e-05 -7.73396338810611e-06 2.66792238953706e-05 -3.98339757387605e-06 2.34872424633877e-05 -1.24893307471488e-05 -7.73396338810611e-06 1.3583608048871e-05 -1.8711444363533e-06 -1.85590368162635e-06 -3.15304272034697e-07 9.5799268629398e-06 2.66792238953706e-05 -1.8711444363533e-06 5.52139171872441e-05 -6.3206407657911e-06 1.0560408118276e-05 6.23038709721605e-06 -3.98339757387605e-06 -1.85590368162635e-06 -6.3206407657911e-06 4.69474003465182e-05 -1.09899304080792e-05 1.88952269811975e-05 2.34872424633877e-05 -3.15304272034697e-07 1.0560408118276e-05 -1.09899304080792e-05 7.74079605871251e-05 1719 1723 0 20 32 1686 1706 0 37 11 0 0 0 0 0 1 17 0 438 0 107 87 0 0 2653 +360 364 0.997972582800576 -0.00109704515391191 0.0636358426539499 -0.0254790456672235 -0.00595499602547612 0.993855720729052 0.110523049163842 -0.011965938607466 -0.0633660950405227 -0.110677924023116 0.991834227647568 -0.0088613363358627 0.000116042227031191 4.00880627316322e-05 -1.04201367229855e-05 2.54221992226492e-05 -3.45465127239779e-05 5.17248365172623e-05 4.00880627316322e-05 7.26715561064652e-05 -7.48465514858286e-06 2.57815255037415e-05 -4.05064136545496e-06 5.32936655184129e-05 -1.04201367229855e-05 -7.48465514858286e-06 1.36471585060558e-05 9.03418725363962e-07 5.30725460937608e-06 -6.34861471808137e-06 2.54221992226492e-05 2.57815255037415e-05 9.03418725363962e-07 5.4945652945538e-05 -2.94146926755434e-05 3.57315887762327e-05 -3.45465127239779e-05 -4.05064136545496e-06 5.30725460937608e-06 -2.94146926755434e-05 6.68876275857168e-05 -1.62281290581004e-05 5.17248365172623e-05 5.32936655184129e-05 -6.34861471808137e-06 3.57315887762327e-05 -1.62281290581004e-05 0.000117383520951761 2309 2302 0 14 37 2282 2312 0 36 16 0 0 0 0 0 8 24 0 437 0 93 64 0 0 2912 +360 410 0.995623582849026 -0.00168839689171175 0.0934389136859189 -0.0190986545109292 -0.010726775465672 0.991164042565911 0.132207325865517 -0.0143979730545838 -0.0928365098599555 -0.13263102970398 0.986808184196242 0.00427851633816975 8.97865990899048e-05 5.72242245306587e-05 -8.19868751430885e-06 1.924917756344e-05 -2.08635003475718e-05 5.07397574293358e-05 5.72242245306587e-05 6.78656806458807e-05 -7.898248768092e-06 2.2735719494128e-05 -1.74957256186977e-05 3.60653143967645e-05 -8.19868751430885e-06 -7.898248768092e-06 1.08299765350145e-05 2.72943130855558e-06 7.24884295898973e-06 -4.5462555135368e-06 1.924917756344e-05 2.2735719494128e-05 2.72943130855558e-06 5.46873484599959e-05 -2.11132626770187e-05 2.23545840509368e-05 -2.08635003475718e-05 -1.74957256186977e-05 7.24884295898973e-06 -2.11132626770187e-05 5.27462239592126e-05 -2.47305931763424e-05 5.07397574293358e-05 3.60653143967645e-05 -4.5462555135368e-06 2.23545840509368e-05 -2.47305931763424e-05 0.000103364245634562 1814 1816 0 21 22 1810 1832 0 36 17 0 0 0 0 0 1 16 0 311 0 47 49 0 0 2140 +359 390 0.994068609136383 -0.00293981901796318 0.108715030211088 -0.0224045153453231 -0.0127432095224321 0.98959990835924 0.143281652651171 -0.0170202193381298 -0.108005606061554 -0.143817171573929 0.983692741774458 0.00843431286046238 6.53529745276944e-05 9.05523567042295e-06 -4.20598519134573e-06 -4.49354811020503e-06 -1.77957699605224e-06 2.49498420784694e-05 9.05523567042295e-06 4.73544755116329e-05 -4.38165505885586e-06 1.01335303678067e-05 6.58208701299991e-06 3.15165877571061e-06 -4.20598519134573e-06 -4.38165505885586e-06 1.2123779052706e-05 6.9661506529429e-06 3.96906657498459e-06 -4.78898636798934e-06 -4.49354811020503e-06 1.01335303678067e-05 6.9661506529429e-06 4.54988091874154e-05 -6.42307319831414e-06 6.56550591021111e-06 -1.77957699605224e-06 6.58208701299991e-06 3.96906657498459e-06 -6.42307319831414e-06 4.37085491597743e-05 -2.80308476052699e-06 2.49498420784694e-05 3.15165877571061e-06 -4.78898636798934e-06 6.56550591021111e-06 -2.80308476052699e-06 8.62352671618447e-05 1377 1370 0 6 28 1384 1399 0 27 12 0 0 0 0 0 3 18 0 228 0 106 84 0 0 2355 +359 391 0.9937497210057 -0.00262716175764431 0.111600134507947 -0.0175795647928587 -0.0130433968240449 0.99014257708166 0.1394544615614 -0.01834802769415 -0.110866414212706 -0.140038477109645 0.983919642617439 0.00477243743562191 5.89925640785031e-05 2.64070886306261e-05 -1.64423674200381e-06 -3.73053583748705e-07 -8.32410084740406e-07 3.09798363203785e-05 2.64070886306261e-05 7.02075077764597e-05 -4.36767483580452e-06 1.02233321231569e-05 -9.66569175267766e-06 2.7921973517491e-05 -1.64423674200381e-06 -4.36767483580452e-06 1.20424569976687e-05 4.48817141084936e-06 3.44385982259684e-06 -4.02802986106417e-06 -3.73053583748705e-07 1.02233321231569e-05 4.48817141084936e-06 4.71546380708565e-05 -1.3769643254122e-05 5.77547145874167e-06 -8.32410084740406e-07 -9.66569175267766e-06 3.44385982259684e-06 -1.3769643254122e-05 4.52977565233261e-05 -9.61935651519677e-06 3.09798363203785e-05 2.7921973517491e-05 -4.02802986106417e-06 5.77547145874167e-06 -9.61935651519677e-06 0.000108124746444151 1619 1620 0 7 25 1585 1613 0 30 8 0 0 0 0 0 4 19 0 224 0 98 82 0 0 2267 +360 411 0.997055803030113 -0.00229337112757022 0.0766450656784138 -0.0277354505193339 -0.00872483168632339 0.989668057601858 0.143111890053238 -0.0116888686321267 -0.0761813819513828 -0.143359255757819 0.98673427062839 -0.0126560716908924 0.000115908768307758 8.26176452057462e-05 -1.02819209259363e-05 1.90391025223909e-05 -1.49768675558255e-05 8.68205352362995e-05 8.26176452057462e-05 0.000117207256611208 -7.77039282501551e-06 3.9180264431795e-05 -2.18584929089815e-05 8.66203768421296e-05 -1.02819209259363e-05 -7.77039282501551e-06 1.11288809051958e-05 2.67796894601655e-06 4.33517537344972e-06 -5.60334301275557e-06 1.90391025223909e-05 3.9180264431795e-05 2.67796894601655e-06 5.89961315270786e-05 -2.71758386753467e-05 3.2525692555427e-05 -1.49768675558255e-05 -2.18584929089815e-05 4.33517537344972e-06 -2.71758386753467e-05 5.46775042292285e-05 -3.23613997608788e-05 8.68205352362995e-05 8.66203768421296e-05 -5.60334301275557e-06 3.2525692555427e-05 -3.23613997608788e-05 0.000161970581069248 1574 1578 0 17 12 1596 1618 0 35 8 0 0 0 0 0 1 17 0 337 0 48 51 0 0 2169 +360 412 0.996436533921321 -0.00191010170911541 0.0843242870015772 -0.0255785337708508 -0.00957959265355119 0.990711762558217 0.13564083062774 -0.0142284912491545 -0.0838001507842053 -0.135965271449191 0.987163096802292 -0.00597739594103923 8.85513228887659e-05 4.73546200999818e-05 -8.38840009080748e-06 2.02999847577905e-06 3.74766505247099e-06 4.06098555154421e-05 4.73546200999818e-05 5.75066684889738e-05 -7.53599287616164e-06 1.0176468775662e-05 3.4293117670785e-06 3.10385300427781e-05 -8.38840009080748e-06 -7.53599287616164e-06 1.24234679461099e-05 5.18670998335277e-06 -1.35893226697925e-06 -2.3234362688286e-06 2.02999847577905e-06 1.0176468775662e-05 5.18670998335277e-06 4.09831723978287e-05 -1.24589688424711e-05 1.09942692103811e-05 3.74766505247099e-06 3.4293117670785e-06 -1.35893226697925e-06 -1.24589688424711e-05 4.87088872199252e-05 -8.9587906509157e-06 4.06098555154421e-05 3.10385300427781e-05 -2.3234362688286e-06 1.09942692103811e-05 -8.9587906509157e-06 9.14800498004685e-05 1610 1613 0 19 21 1630 1652 0 35 18 0 0 0 0 0 2 18 0 371 0 60 62 0 0 2141 +360 388 0.996482029071055 -0.00240739134853826 0.0837721326297057 -0.0251933493582505 -0.00938608751010233 0.990092646734978 0.140101578301524 -0.0153459760688464 -0.0832794518454986 -0.14039499758973 0.986586933600934 -0.00871373675566046 4.86528441543458e-05 2.89128907525901e-05 -1.42448185856956e-06 4.80276204718323e-06 -6.66683746119251e-06 2.82763516069079e-05 2.89128907525901e-05 5.21666320253572e-05 -2.41165488013136e-06 1.27534983233267e-05 -7.184795303464e-06 2.55021619852166e-05 -1.42448185856956e-06 -2.41165488013136e-06 1.01169099362164e-05 2.84053028003134e-06 4.76893670833985e-06 -6.04458531453019e-07 4.80276204718323e-06 1.27534983233267e-05 2.84053028003134e-06 4.96590670985744e-05 -2.99349526442141e-05 6.43719708776063e-06 -6.66683746119251e-06 -7.184795303464e-06 4.76893670833985e-06 -2.99349526442141e-05 5.47698211648652e-05 -3.63440268800743e-06 2.82763516069079e-05 2.55021619852166e-05 -6.04458531453019e-07 6.43719708776063e-06 -3.63440268800743e-06 7.71108282478503e-05 1817 1814 0 21 36 1757 1772 0 36 6 0 0 0 0 0 1 17 0 452 0 113 96 0 0 2533 +360 363 0.999010914292448 -0.00021333752551656 0.0444651280405963 -0.0159529125730225 -0.0030350018001361 0.997329275830936 0.0729733124821261 0.000687950324162985 -0.0443619418943714 -0.0730360873653638 0.996342184218715 0.000391343417342271 8.40048428796673e-05 7.60438713005799e-06 -9.53007752406288e-06 2.92524905465943e-06 -7.44716121936008e-06 2.24240976300885e-05 7.60438713005799e-06 4.53070924253412e-05 -8.48995512249283e-06 1.21862459183069e-05 7.92636355549274e-06 1.55224074590509e-05 -9.53007752406288e-06 -8.48995512249283e-06 1.35357001643731e-05 1.27407618461907e-06 2.91923577486895e-06 -4.41875109153009e-06 2.92524905465943e-06 1.21862459183069e-05 1.27407618461907e-06 4.39476748010969e-05 -8.28615846866009e-06 1.95024295128792e-05 -7.44716121936008e-06 7.92636355549274e-06 2.91923577486895e-06 -8.28615846866009e-06 3.82775439604378e-05 -1.78324231238371e-06 2.24240976300885e-05 1.55224074590509e-05 -4.41875109153009e-06 1.95024295128792e-05 -1.78324231238371e-06 5.7746335302524e-05 2200 2188 0 12 53 2170 2193 0 35 24 0 0 0 0 0 5 21 0 398 0 94 68 0 0 3147 +360 394 0.995619882438846 -0.00217113062395854 0.093468368362091 -0.0131440231970739 -0.0106109739564237 0.99064669064658 0.136038750151108 -0.023117676389173 -0.0928894876945391 -0.136434674855013 0.986284503869473 0.00166394456828914 7.22753846762177e-05 5.19645740474824e-05 -3.2769152577312e-06 3.85916491324119e-06 -9.20408765266556e-06 4.33871789893699e-05 5.19645740474824e-05 8.80404351300308e-05 -3.84416517401087e-06 2.18656639389575e-05 -1.38265789887028e-05 3.3551273863337e-05 -3.2769152577312e-06 -3.84416517401087e-06 1.05292951128257e-05 4.23431876482549e-06 4.14261396761068e-06 -5.93682288560849e-06 3.85916491324119e-06 2.18656639389575e-05 4.23431876482549e-06 5.45601443281291e-05 -1.27895819064247e-05 1.82107453998768e-05 -9.20408765266556e-06 -1.38265789887028e-05 4.14261396761068e-06 -1.27895819064247e-05 4.21063452962653e-05 -1.4952060135684e-05 4.33871789893699e-05 3.3551273863337e-05 -5.93682288560849e-06 1.82107453998768e-05 -1.4952060135684e-05 0.000109896561789165 1571 1568 0 16 32 1562 1587 0 32 15 0 0 0 0 0 0 14 0 254 0 86 65 0 0 2340 +360 386 0.995895670467107 -0.00211632591771429 0.0904838919890289 -0.0166787181563793 -0.0103884602979245 0.990446681031695 0.137504370570316 -0.0171443257220558 -0.089910474570601 -0.137879995640812 0.986359576100206 0.00291999693901303 7.32390844409634e-05 5.64300919870278e-05 -7.22038255902401e-06 1.28777791710998e-05 2.40839327737473e-06 4.29772395490259e-05 5.64300919870278e-05 8.38883785362775e-05 -9.49185314230014e-06 2.1871555716123e-05 -5.45214477039323e-06 4.68492826372365e-05 -7.22038255902401e-06 -9.49185314230014e-06 1.13250971719624e-05 5.74663820981219e-07 2.33310692690968e-06 -3.02796029465873e-06 1.28777791710998e-05 2.1871555716123e-05 5.74663820981219e-07 3.6832001818404e-05 -2.15090483201847e-06 1.75424243664827e-05 2.40839327737473e-06 -5.45214477039323e-06 2.33310692690968e-06 -2.15090483201847e-06 3.29188962532457e-05 6.78390857097143e-07 4.29772395490259e-05 4.68492826372365e-05 -3.02796029465873e-06 1.75424243664827e-05 6.78390857097143e-07 0.000117708317669025 1874 1870 0 17 33 1854 1882 0 35 14 0 0 0 0 0 0 14 0 431 0 83 60 0 0 2668 +360 413 0.996335243075641 -0.00186682902820674 0.0855137319661737 -0.0237045459367522 -0.00985838286552447 0.99059279352994 0.136487104496457 -0.0177246448462488 -0.0849640847221924 -0.13682993954515 0.986944107815326 -0.00499629442592629 6.81506991612445e-05 3.97827571771943e-05 -6.57501305171309e-06 8.60836418075719e-06 -3.45880516342839e-06 3.75838140831826e-05 3.97827571771943e-05 5.76980014925178e-05 -8.29641261482744e-06 7.55516672175649e-06 2.69810872609533e-06 2.4570441966396e-05 -6.57501305171309e-06 -8.29641261482744e-06 1.1344077913887e-05 2.50907063860082e-06 1.59634544220082e-06 -5.39206540504409e-06 8.60836418075719e-06 7.55516672175649e-06 2.50907063860082e-06 4.61842871430808e-05 -1.32440175791376e-05 2.26916175176854e-06 -3.45880516342839e-06 2.69810872609533e-06 1.59634544220082e-06 -1.32440175791376e-05 5.43296361375213e-05 2.49085951704827e-06 3.75838140831826e-05 2.4570441966396e-05 -5.39206540504409e-06 2.26916175176854e-06 2.49085951704827e-06 8.69350351506896e-05 1640 1644 0 19 13 1638 1664 0 39 8 0 0 0 0 0 0 17 0 402 0 40 43 0 0 2124 +360 396 0.996028862207216 -0.00220981848341824 0.0890034962935135 -0.0153845329834984 -0.00997709749018413 0.990624475426083 0.136248325540054 -0.0263455656851408 -0.0884701258949624 -0.136595261224786 0.986668521558817 0.00170035272478481 5.92206647603713e-05 2.90971296573753e-05 -3.15070914402401e-06 -2.3519229851933e-06 -3.69939325830514e-06 1.97571335423137e-05 2.90971296573753e-05 5.71630985507545e-05 -4.34053103164751e-06 9.74090769312296e-06 1.48624689359617e-06 2.46631819157852e-05 -3.15070914402401e-06 -4.34053103164751e-06 1.13619157467537e-05 3.59711476066321e-06 3.41811158631238e-06 -2.17532938336331e-06 -2.3519229851933e-06 9.74090769312296e-06 3.59711476066321e-06 6.40899866427292e-05 -2.34371508700194e-05 5.7724634826923e-06 -3.69939325830514e-06 1.48624689359617e-06 3.41811158631238e-06 -2.34371508700194e-05 6.15230044848501e-05 5.16758388761253e-06 1.97571335423137e-05 2.46631819157852e-05 -2.17532938336331e-06 5.7724634826923e-06 5.16758388761253e-06 9.65939372925801e-05 1778 1775 0 25 30 1766 1789 0 41 13 0 0 0 0 0 0 14 0 254 0 83 65 0 0 2350 +360 395 0.995237959637027 -0.00165548311978491 0.0974610849168399 -0.0101508950646231 -0.0110012199819245 0.991559708108614 0.1291832745152 -0.0230447086193069 -0.0968523456424091 -0.129640289382584 0.986819648422326 0.00996522324695786 0.000111199440969299 7.25603490366277e-05 -8.58980876273864e-06 1.88399253440694e-05 -2.4877594957684e-05 8.39426953312739e-05 7.25603490366277e-05 0.000107454964412906 -6.68938359126351e-06 3.85039948839771e-05 -3.06322763440695e-05 8.33828898769677e-05 -8.58980876273864e-06 -6.68938359126351e-06 1.13293608880107e-05 3.0314889503616e-06 6.57447090157022e-06 -8.54934979655133e-06 1.88399253440694e-05 3.85039948839771e-05 3.0314889503616e-06 6.77584146834645e-05 -2.82204884427529e-05 3.85745360572854e-05 -2.4877594957684e-05 -3.06322763440695e-05 6.57447090157022e-06 -2.82204884427529e-05 5.7555606327386e-05 -3.86179732767109e-05 8.39426953312739e-05 8.33828898769677e-05 -8.54934979655133e-06 3.85745360572854e-05 -3.86179732767109e-05 0.00016799008276695 1820 1828 0 24 30 1802 1826 0 39 16 0 0 0 0 0 1 17 0 253 0 98 82 0 0 2349 +360 390 0.995507695381454 -0.00195402848281032 0.0946604997292692 -0.0162989218214994 -0.0110419810501461 0.99056860235064 0.136572027485822 -0.0160693848957074 -0.0940345845462978 -0.137003743780191 0.986097090097835 0.012406608088185 5.45652234649872e-05 2.35588081108476e-05 -8.70486009509037e-07 8.02522166308399e-06 -3.78377325016594e-07 3.25769686542881e-05 2.35588081108476e-05 8.43337253557195e-05 -3.2728226941622e-06 2.58783823509591e-05 3.68765882468433e-06 2.59963014023743e-05 -8.70486009509037e-07 -3.2728226941622e-06 1.07992731930322e-05 1.75754678734673e-06 4.01473692874415e-06 -3.17612368474384e-06 8.02522166308399e-06 2.58783823509591e-05 1.75754678734673e-06 7.4383862153494e-05 -2.25698667956913e-05 1.11301148391994e-05 -3.78377325016594e-07 3.68765882468433e-06 4.01473692874415e-06 -2.25698667956913e-05 5.65695713223052e-05 2.0642057837349e-07 3.25769686542881e-05 2.59963014023743e-05 -3.17612368474384e-06 1.11301148391994e-05 2.0642057837349e-07 9.10965363112662e-05 1623 1619 0 18 36 1614 1637 0 36 15 0 0 0 0 0 0 14 0 217 0 110 86 0 0 2375 +360 414 0.996474231797086 -0.00240106007551221 0.0838650122215484 -0.0265892676454355 -0.00932271340698516 0.990231397576297 0.139121767774943 -0.0161313425361041 -0.0833798079821361 -0.139413106143604 0.986717686806239 -0.00906091863628142 0.000106785902469305 7.20072677357211e-05 -1.29856763873974e-05 2.5247568516001e-05 -7.04899785458259e-06 6.72635710839141e-05 7.20072677357211e-05 0.000100980569121829 -1.34255016762857e-05 4.216030641614e-05 -2.11712886239043e-05 7.17459716204368e-05 -1.29856763873974e-05 -1.34255016762857e-05 1.28128578919245e-05 1.77033372830521e-06 3.93286693609795e-06 -8.27379743898181e-06 2.5247568516001e-05 4.216030641614e-05 1.77033372830521e-06 6.53046404367379e-05 -2.80557809555653e-05 4.77648534342823e-05 -7.04899785458259e-06 -2.11712886239043e-05 3.93286693609795e-06 -2.80557809555653e-05 4.86537487472025e-05 -3.37761702326219e-05 6.72635710839141e-05 7.17459716204368e-05 -8.27379743898181e-06 4.77648534342823e-05 -3.37761702326219e-05 0.000142895057976379 1799 1808 0 21 15 1781 1800 0 37 10 0 0 0 0 0 2 17 0 400 0 53 55 0 0 2230 +360 409 0.996965755738183 -0.00185945455887605 0.0778191770332804 -0.0345602588828327 -0.00914174648101847 0.989999640272519 0.140773366556175 -0.0115105204556191 -0.0773027189474623 -0.141057628964285 0.986978740882651 -0.0120309646902701 6.39330634632193e-05 4.72974466903128e-05 -4.47551617036691e-06 1.79965601424757e-05 -9.24666164306047e-06 3.55998746718415e-05 4.72974466903128e-05 7.12090458064257e-05 -5.17552850801006e-06 2.49785922950948e-05 -1.85519116122581e-05 3.62152545038346e-05 -4.47551617036691e-06 -5.17552850801006e-06 1.06808747893669e-05 2.19726661746656e-06 4.25782177439461e-06 -1.49708637902715e-06 1.79965601424757e-05 2.49785922950948e-05 2.19726661746656e-06 5.80202282528373e-05 -2.2793658172218e-05 2.34798896016499e-05 -9.24666164306047e-06 -1.85519116122581e-05 4.25782177439461e-06 -2.2793658172218e-05 5.52939860240096e-05 -2.56897603851457e-05 3.55998746718415e-05 3.62152545038346e-05 -1.49708637902715e-06 2.34798896016499e-05 -2.56897603851457e-05 9.68748244817825e-05 1738 1741 0 17 23 1736 1761 0 33 21 0 0 0 0 0 1 16 0 307 0 35 37 0 0 2132 +360 416 0.995374690596841 -0.00175106142422899 0.0960528974218448 -0.0198588857234456 -0.011001626354744 0.991178437859108 0.132076752461324 -0.0147816857378796 -0.0954368353246977 -0.132522594703952 0.986574666386756 0.00333313429571572 8.23243718332723e-05 5.47155348128324e-05 -9.62047214527288e-06 1.85742786463135e-05 -4.20801690423759e-06 5.80916440439326e-05 5.47155348128324e-05 0.000121221876997719 -9.4311625781481e-06 2.84946677073644e-05 6.28702584712407e-06 8.49168068596075e-05 -9.62047214527288e-06 -9.4311625781481e-06 1.21178060955778e-05 2.15806855985996e-06 -1.18946645791664e-06 -6.45929680539041e-06 1.85742786463135e-05 2.84946677073644e-05 2.15806855985996e-06 9.3826252612932e-05 -7.37607699568074e-05 3.98940986660398e-05 -4.20801690423759e-06 6.28702584712407e-06 -1.18946645791664e-06 -7.37607699568074e-05 0.000122731041179256 -2.29118488035278e-05 5.80916440439326e-05 8.49168068596075e-05 -6.45929680539041e-06 3.98940986660398e-05 -2.29118488035278e-05 0.000152006650884466 1851 1860 0 18 15 1834 1859 0 33 10 0 0 0 0 0 1 15 0 400 0 51 54 0 0 2177 +360 391 0.99451890502667 -0.00242267132604227 0.104528839122032 -0.00433811832688084 -0.0116138983745802 0.990985305094585 0.133466259598208 -0.0203633172085696 -0.103909888408652 -0.133948705668391 0.985525483861612 0.013977041996472 6.75756401970823e-05 4.28193003105338e-05 -3.1366032400056e-06 1.02286884688284e-05 -7.16504909972958e-06 4.16592485275035e-05 4.28193003105338e-05 0.000111580683284895 -4.14273618477512e-06 4.06460297537575e-05 -1.66974213740652e-05 5.90141563102271e-05 -3.1366032400056e-06 -4.14273618477512e-06 1.05952844832949e-05 2.88490342972762e-06 4.85553757249977e-06 -5.02822362663194e-06 1.02286884688284e-05 4.06460297537575e-05 2.88490342972762e-06 4.8044990433993e-05 -9.12607985015787e-06 3.38356561669124e-05 -7.16504909972958e-06 -1.66974213740652e-05 4.85553757249977e-06 -9.12607985015787e-06 3.41536578386286e-05 -1.73339812879984e-05 4.16592485275035e-05 5.90141563102271e-05 -5.02822362663194e-06 3.38356561669124e-05 -1.73339812879984e-05 0.000124301818601954 1733 1740 0 16 32 1713 1734 0 32 22 0 0 0 0 0 0 13 0 208 0 102 86 0 0 2267 +360 389 0.996394992312854 -0.00171918878085162 0.0848178264505988 -0.0242324311012725 -0.00979871575862299 0.990770931249409 0.135192259248303 -0.0153112116903674 -0.0842674579143682 -0.135535995887124 0.987182348583855 -0.00385085176982206 6.92556736988297e-05 3.47405956359861e-05 -1.69881338445785e-06 9.52456995231805e-06 -1.19102504304318e-05 2.07227274050382e-05 3.47405956359861e-05 8.08475932112815e-05 -2.70170021388371e-06 1.90519268985128e-05 -5.43745461273673e-06 2.25981936661352e-05 -1.69881338445785e-06 -2.70170021388371e-06 1.02061510998693e-05 4.5035822845427e-06 3.08803134173883e-06 -1.45356484353548e-06 9.52456995231805e-06 1.90519268985128e-05 4.5035822845427e-06 5.74729668548403e-05 -3.99493962621361e-05 8.42838244062599e-06 -1.19102504304318e-05 -5.43745461273673e-06 3.08803134173883e-06 -3.99493962621361e-05 7.25245249908365e-05 -1.60840383661499e-05 2.07227274050382e-05 2.25981936661352e-05 -1.45356484353548e-06 8.42838244062599e-06 -1.60840383661499e-05 7.40527586470799e-05 1625 1620 0 17 34 1628 1652 0 39 15 0 0 0 0 0 1 18 0 312 0 110 87 0 0 2419 +360 408 0.995903754924194 -0.00224237647018476 0.090391828588969 -0.0171479286676336 -0.0103420445061904 0.9903068029613 0.138511653387 -0.0181925655904727 -0.0898262380561692 -0.138879112023135 0.986227072838878 -0.00587051124067804 9.65918743663704e-05 8.07501764650223e-05 -6.99745348321594e-06 2.65781029681933e-05 -2.44778673681439e-05 7.68222466447945e-05 8.07501764650223e-05 0.0001164530048066 -9.3943294405542e-06 4.0239991352834e-05 -2.88638289437391e-05 8.65368419448335e-05 -6.99745348321594e-06 -9.3943294405542e-06 1.09363028074901e-05 2.19675602734855e-06 7.88574990099879e-06 -6.77881744285328e-06 2.65781029681933e-05 4.0239991352834e-05 2.19675602734855e-06 5.20732821279693e-05 -2.50936998955414e-05 4.44711153809307e-05 -2.44778673681439e-05 -2.88638289437391e-05 7.88574990099879e-06 -2.50936998955414e-05 5.92684057084985e-05 -4.5907322189375e-05 7.68222466447945e-05 8.65368419448335e-05 -6.77881744285328e-06 4.44711153809307e-05 -4.5907322189375e-05 0.000172219439811071 1630 1639 0 20 26 1607 1626 0 35 21 0 0 0 0 0 0 14 0 283 0 53 57 0 0 2156 +361 363 0.999752642344386 -6.75285215854914e-05 0.0222407186330971 -0.0215544335865958 -0.00103336015750387 0.998774402856731 0.0494835767196159 0.0049596686294531 -0.0222168020246548 -0.0494943192505969 0.998527278580669 -0.00499565579233416 0.000121896548665917 2.96347089560169e-05 -1.22627077371081e-05 9.19687408749335e-06 -1.62115615425317e-05 3.81822504119299e-05 2.96347089560169e-05 6.33237628804498e-05 -7.73046636027325e-06 9.04033512906629e-06 1.10577675978002e-05 3.30422917787847e-05 -1.22627077371081e-05 -7.73046636027325e-06 1.29301712579279e-05 1.57714682814578e-06 3.06993866317339e-06 -9.57971766335743e-06 9.19687408749335e-06 9.04033512906629e-06 1.57714682814578e-06 3.64992361519013e-05 -1.22161677175626e-05 1.92236570096115e-05 -1.62115615425317e-05 1.10577675978002e-05 3.06993866317339e-06 -1.22161677175626e-05 4.87524054215089e-05 -5.28158588955179e-06 3.81822504119299e-05 3.30422917787847e-05 -9.57971766335743e-06 1.92236570096115e-05 -5.28158588955179e-06 8.55473892851928e-05 2314 2293 0 12 52 2253 2273 0 33 10 0 0 0 0 0 11 29 0 434 0 108 86 0 0 3261 +360 397 0.996648193862698 -0.00210676169712115 0.0817798216271785 -0.0244418593940795 -0.00941909005439573 0.990064858012478 0.140295608168176 -0.0198578638830623 -0.0812628969011613 -0.14059565599222 0.986726508766917 -0.00215228043279015 5.58868692766209e-05 4.09160528898574e-05 -4.17568200013654e-06 -3.26676250970122e-07 2.82103894457531e-06 3.0234778603491e-05 4.09160528898574e-05 6.94152716853231e-05 -5.71832081927525e-06 1.09019273755676e-05 -1.13012778767508e-06 3.58128871218663e-05 -4.17568200013654e-06 -5.71832081927525e-06 1.00709091842824e-05 3.81487593839795e-06 2.24721774171246e-06 -1.86276629118358e-06 -3.26676250970122e-07 1.09019273755676e-05 3.81487593839795e-06 5.71277298036186e-05 -2.9997068085475e-05 1.81044094424404e-07 2.82103894457531e-06 -1.13012778767508e-06 2.24721774171246e-06 -2.9997068085475e-05 5.90842482154884e-05 8.65931758645575e-06 3.0234778603491e-05 3.58128871218663e-05 -1.86276629118358e-06 1.81044094424404e-07 8.65931758645575e-06 7.21199062850447e-05 1542 1541 0 18 40 1548 1573 0 34 18 0 0 0 0 0 0 16 0 265 0 99 81 0 0 2264 +361 387 0.997289806337129 -0.0013330682931144 0.0735613016808265 -0.0245885196892487 -0.00725643323714271 0.993178765114649 0.116375619018832 -0.0112614981243549 -0.073214659411395 -0.116594011228138 0.990477384998267 -0.00642073224878411 0.000100430289727482 3.86320603082756e-05 -1.07992827473433e-05 -3.03016498971551e-06 -3.8190849702359e-06 5.94492514196774e-05 3.86320603082756e-05 7.28016954781571e-05 -5.78507372925331e-06 6.29572808524699e-06 1.40822184328737e-06 2.0264376215116e-05 -1.07992827473433e-05 -5.78507372925331e-06 1.28736210003408e-05 2.55330932521696e-06 7.50922644379956e-07 -7.30030439435019e-06 -3.03016498971551e-06 6.29572808524699e-06 2.55330932521696e-06 5.05499115740452e-05 -1.77300056024698e-07 -2.94175435454921e-06 -3.8190849702359e-06 1.40822184328737e-06 7.50922644379956e-07 -1.77300056024698e-07 3.64391453198046e-05 -1.02657847096964e-05 5.94492514196774e-05 2.0264376215116e-05 -7.30030439435019e-06 -2.94175435454921e-06 -1.02657847096964e-05 0.000118337139216262 1746 1740 0 13 37 1686 1706 0 36 0 0 0 0 0 0 2 21 0 472 0 126 111 0 0 2724 +361 396 0.997043491076128 -0.00136532616285744 0.0768271617801733 -0.020442369140152 -0.00743988203025607 0.993429055095189 0.114207533236893 -0.019483734725302 -0.0764782652660465 -0.114441462666068 0.990481815362981 0.00171505659648506 7.39069650239132e-05 5.28549549132129e-05 -3.72933388855083e-06 1.03464166993976e-05 -1.41652044478795e-05 4.76515248172424e-05 5.28549549132129e-05 8.93764691473191e-05 -4.09490872612085e-06 2.48014048629945e-05 -9.2774769340286e-06 5.28554714525605e-05 -3.72933388855083e-06 -4.09490872612085e-06 1.07171842960673e-05 3.49186130738324e-06 3.22977956202053e-06 -2.93528026402334e-06 1.03464166993976e-05 2.48014048629945e-05 3.49186130738324e-06 6.07730883953185e-05 -1.67801056313806e-05 1.44134070613706e-05 -1.41652044478795e-05 -9.2774769340286e-06 3.22977956202053e-06 -1.67801056313806e-05 5.76581005244884e-05 -8.74933508776991e-06 4.76515248172424e-05 5.28554714525605e-05 -2.93528026402334e-06 1.44134070613706e-05 -8.74933508776991e-06 0.000111173290303913 1793 1786 0 14 30 1774 1790 0 34 11 0 0 0 0 0 5 20 0 302 0 81 65 0 0 2441 +361 410 0.997313442488656 -0.000667110793587583 0.0732492484235576 -0.0274515107477645 -0.00759653549041538 0.993625090324795 0.112478764776224 -0.00936294926618225 -0.0728573268791124 -0.112733024621143 0.990950591644103 0.001123384335582 0.000112914654910723 7.02971928123141e-05 -7.17692548449274e-06 1.89063243650337e-05 -2.12835894558917e-05 6.85057334610392e-05 7.02971928123141e-05 9.61161594416427e-05 -5.61535295061383e-06 2.40720724216972e-05 -9.44903655699193e-06 5.35993165929484e-05 -7.17692548449274e-06 -5.61535295061383e-06 1.007938855198e-05 1.91726262160132e-06 5.36426879608321e-06 -5.83308598374411e-06 1.89063243650337e-05 2.40720724216972e-05 1.91726262160132e-06 5.45360290614203e-05 -2.00555066247088e-05 2.21717652626457e-05 -2.12835894558917e-05 -9.44903655699193e-06 5.36426879608321e-06 -2.00555066247088e-05 5.02626614005227e-05 -2.20587636374344e-05 6.85057334610392e-05 5.35993165929484e-05 -5.83308598374411e-06 2.21717652626457e-05 -2.20587636374344e-05 0.000117126921050814 1602 1609 0 14 9 1595 1620 0 34 5 0 0 0 0 0 8 24 0 353 0 32 35 0 0 2230 +360 417 0.99572908282321 -0.00164439154786044 0.0923086647963624 -0.0134325889275421 -0.0105706823881217 0.991235468224178 0.131683359648229 -0.0219164969605021 -0.0917161615741703 -0.132096716502844 0.986984601295921 0.000353717549400757 8.45782624044623e-05 5.84315487912579e-05 -1.0280460755165e-05 2.15955292315858e-05 -1.08018903181386e-05 5.29862705105596e-05 5.84315487912579e-05 9.09633091206444e-05 -1.04314654812755e-05 3.36552483898734e-05 -1.21194032878137e-05 6.04766363814555e-05 -1.0280460755165e-05 -1.04314654812755e-05 1.21142508055086e-05 2.23829292978778e-07 2.01165397954212e-06 -4.25056149553959e-06 2.15955292315858e-05 3.36552483898734e-05 2.23829292978778e-07 4.42087758535465e-05 -7.05763876545655e-06 3.19375282933916e-05 -1.08018903181386e-05 -1.21194032878137e-05 2.01165397954212e-06 -7.05763876545655e-06 4.24774719267738e-05 -2.66339187572414e-05 5.29862705105596e-05 6.04766363814555e-05 -4.25056149553959e-06 3.19375282933916e-05 -2.66339187572414e-05 0.000120200151187267 1911 1923 0 23 16 1895 1920 0 41 9 0 0 0 0 0 0 17 0 406 0 56 59 0 0 2229 +361 412 0.997360809972929 -0.00103495735270284 0.0725971321294492 -0.021575428162205 -0.00709416897174556 0.993724685873271 0.111628497493559 -0.0170918141180024 -0.0722570930548894 -0.111848904998428 0.991094715430321 0.0010019482505742 7.74197828535486e-05 5.89386246274931e-05 -8.44067933315971e-06 2.68459234280109e-05 -1.30132771999233e-05 4.87622216825454e-05 5.89386246274931e-05 8.41003963163366e-05 -1.02421583157356e-05 3.90066907051807e-05 -1.46515347357032e-05 5.00385373048731e-05 -8.44067933315971e-06 -1.02421583157356e-05 1.08614789749694e-05 -3.94226024312273e-08 3.10036433731292e-06 -6.04376202488166e-06 2.68459234280109e-05 3.90066907051807e-05 -3.94226024312273e-08 6.44780954472981e-05 -2.93362763615404e-05 2.52074151858625e-05 -1.30132771999233e-05 -1.46515347357032e-05 3.10036433731292e-06 -2.93362763615404e-05 5.34074064612521e-05 -1.63223606099941e-05 4.87622216825454e-05 5.00385373048731e-05 -6.04376202488166e-06 2.52074151858625e-05 -1.63223606099941e-05 8.78991991385862e-05 1759 1764 0 11 9 1753 1776 0 33 5 0 0 0 0 0 4 22 0 416 0 34 37 0 0 2207 +361 364 0.998562841215347 -0.00131453249827792 0.0535772726839005 -0.0201133656874181 -0.00367427133176947 0.995667794086583 0.0929093297195607 -0.012985851072065 -0.0534672972396641 -0.0929726616972349 0.994232031420642 -0.00238773885302798 9.24450457060825e-05 4.94228316560431e-05 -7.22551400644777e-06 2.3002111864397e-05 -1.81407250973278e-05 4.59037004596312e-05 4.94228316560431e-05 0.000120521000715652 -5.54752816395756e-06 3.54557378910467e-05 3.46484612031789e-06 7.25318865625329e-05 -7.22551400644777e-06 -5.54752816395756e-06 1.23778515892717e-05 2.19193607629065e-06 2.67420732285701e-06 -3.63216602235751e-06 2.3002111864397e-05 3.54557378910467e-05 2.19193607629065e-06 5.5845281504863e-05 -2.99522738359669e-05 3.58495996109356e-05 -1.81407250973278e-05 3.46484612031789e-06 2.67420732285701e-06 -2.99522738359669e-05 6.39553395644105e-05 -1.47421318546141e-05 4.59037004596312e-05 7.25318865625329e-05 -3.63216602235751e-06 3.58495996109356e-05 -1.47421318546141e-05 0.000100003191339757 2331 2314 0 13 37 2285 2304 0 36 7 0 0 0 0 0 8 27 0 453 0 108 82 0 0 3010 +361 413 0.997119688711692 -0.000975169241892851 0.0758378232048339 -0.0190099622357125 -0.00765838072544006 0.993512137063467 0.113467981000138 -0.021135750546827 -0.0754564482874869 -0.113721952817093 0.990643044622686 -0.00248201819917223 6.02847010983565e-05 3.50361511960895e-05 -6.35413112870755e-06 5.13120912158453e-06 1.77940656013425e-07 3.65528687672338e-05 3.50361511960895e-05 7.76215182658955e-05 -5.69252538691817e-06 2.67336144798452e-05 -1.29355941727285e-06 4.0498716699802e-05 -6.35413112870755e-06 -5.69252538691817e-06 1.17297460793512e-05 2.85631234608692e-06 1.17637198468536e-06 -3.38237510195145e-06 5.13120912158453e-06 2.67336144798452e-05 2.85631234608692e-06 4.53122654340723e-05 -5.09599908424943e-06 8.50446959419465e-06 1.77940656013425e-07 -1.29355941727285e-06 1.17637198468536e-06 -5.09599908424943e-06 4.16710816997001e-05 1.43723618168005e-06 3.65528687672338e-05 4.0498716699802e-05 -3.38237510195145e-06 8.50446959419465e-06 1.43723618168005e-06 9.55589022313362e-05 1526 1530 0 15 11 1521 1543 0 37 7 0 0 0 0 0 3 22 0 432 0 34 37 0 0 2210 +361 395 0.996330570810058 -0.00144173710127399 0.0855763697724695 -0.0142191859317786 -0.00796767451939944 0.993953773063813 0.109509877065786 -0.0196989461340512 -0.0852168400731718 -0.109789882987192 0.990295042783514 0.00624847849689775 9.81373370071687e-05 6.32290213188045e-05 -4.70037455282056e-06 1.25981314725848e-05 -1.07134208236048e-05 6.28213071141298e-05 6.32290213188045e-05 9.29722863607316e-05 -5.40833942798496e-06 2.76216791009969e-05 -1.67284423144006e-05 5.46158813913787e-05 -4.70037455282056e-06 -5.40833942798496e-06 1.11926835492225e-05 1.12831207494343e-06 6.2187191605754e-06 -4.03112394005879e-06 1.25981314725848e-05 2.76216791009969e-05 1.12831207494343e-06 6.34855585029276e-05 -2.6505152930264e-05 2.80704856663424e-05 -1.07134208236048e-05 -1.67284423144006e-05 6.2187191605754e-06 -2.6505152930264e-05 4.94819386534353e-05 -1.77841957451897e-05 6.28213071141298e-05 5.46158813913787e-05 -4.03112394005879e-06 2.80704856663424e-05 -1.77841957451897e-05 0.000136222606401548 1902 1893 0 15 30 1873 1890 0 32 7 0 0 0 0 0 3 22 0 284 0 122 118 0 0 2415 +361 389 0.99757724118754 -0.000800111879396359 0.0695629764000772 -0.0250429379152292 -0.00697056732058572 0.993752045344758 0.111392475348828 -0.0173590572871244 -0.0692174765206478 -0.111607491657552 0.991338846585779 -0.000603538406913262 7.28206598589902e-05 1.41355254264884e-05 -3.32738059977058e-06 7.15380724030741e-06 -2.10782436665243e-05 1.08955636916273e-05 1.41355254264884e-05 4.56911007440171e-05 -4.80360685936427e-06 9.67898830420842e-06 -5.68574876591025e-06 2.47129327379214e-07 -3.32738059977058e-06 -4.80360685936427e-06 1.0258581004956e-05 3.89201046794767e-07 7.55654268756471e-06 -1.00871044104932e-06 7.15380724030741e-06 9.67898830420842e-06 3.89201046794767e-07 4.60414970680168e-05 -2.30249331708535e-05 -3.04905510836799e-06 -2.10782436665243e-05 -5.68574876591025e-06 7.55654268756471e-06 -2.30249331708535e-05 5.54517966720387e-05 -3.57230791757536e-06 1.08955636916273e-05 2.47129327379214e-07 -1.00871044104932e-06 -3.04905510836799e-06 -3.57230791757536e-06 5.25643608236316e-05 1755 1749 0 13 37 1730 1755 0 32 12 0 0 0 0 0 3 21 0 350 0 80 57 0 0 2556 +361 388 0.997111243101514 -0.00174801989976769 0.0759349281094251 -0.0169510026017689 -0.00721396196061779 0.993036367262918 0.117587125341585 -0.0217896404838278 -0.075611689793208 -0.117795236404945 0.990155116457477 -0.00347102843117243 6.99058410356533e-05 4.12335018409943e-05 -3.28767012118302e-06 3.25596278347523e-06 -8.92442952050372e-06 2.75180076520611e-05 4.12335018409943e-05 7.41939433400045e-05 -1.63530022792163e-06 2.30969500670952e-05 -1.8643624469399e-05 3.96521442866582e-05 -3.28767012118302e-06 -1.63530022792163e-06 9.94768461320035e-06 3.36998252896311e-06 4.34720824963185e-06 -1.67391209508524e-07 3.25596278347523e-06 2.30969500670952e-05 3.36998252896311e-06 5.76208629944246e-05 -2.33474015416338e-05 1.74034886039853e-05 -8.92442952050372e-06 -1.8643624469399e-05 4.34720824963185e-06 -2.33474015416338e-05 3.61429378081645e-05 -1.62833708134931e-05 2.75180076520611e-05 3.96521442866582e-05 -1.67391209508524e-07 1.74034886039853e-05 -1.62833708134931e-05 8.01266088470638e-05 1891 1880 0 16 44 1824 1839 0 32 1 0 0 0 0 0 3 20 0 486 0 130 113 0 0 2600 +361 397 0.99759216720725 -0.00130425174075921 0.0693409464468147 -0.0232094191416139 -0.00685417604307674 0.993074238476659 0.117288435682188 -0.0192834568408848 -0.0690136812343307 -0.117481299794482 0.990674142188583 -0.00057868830015067 5.09104356000139e-05 3.72730206068406e-05 -3.22645361855053e-06 1.57834186767989e-05 -1.27762674601253e-05 2.85660865942391e-05 3.72730206068406e-05 5.68749076908381e-05 -5.83152643889169e-06 1.97325909919846e-05 -9.31629206111452e-06 2.41089619698499e-05 -3.22645361855053e-06 -5.83152643889169e-06 1.11763194966912e-05 1.94323035901545e-06 2.89321009186044e-06 3.00485522793808e-07 1.57834186767989e-05 1.97325909919846e-05 1.94323035901545e-06 8.61087690686877e-05 -5.7689112114385e-05 1.37593540350274e-05 -1.27762674601253e-05 -9.31629206111452e-06 2.89321009186044e-06 -5.7689112114385e-05 9.12628787349273e-05 -9.94543272026997e-06 2.85660865942391e-05 2.41089619698499e-05 3.00485522793808e-07 1.37593540350274e-05 -9.94543272026997e-06 7.5569715145393e-05 1432 1433 0 12 31 1414 1438 0 30 13 0 0 0 0 0 4 21 0 301 0 75 59 0 0 2374 +361 409 0.997742470596372 -0.00102637442891878 0.0671484096891306 -0.0372082485086364 -0.00692727981968309 0.992976516950606 0.118108634650237 -0.00848601082383893 -0.0667980176543247 -0.118307156758055 0.990727733283609 -0.00789466164699586 7.31587196014397e-05 5.32896147561458e-05 -3.61757664372614e-06 8.48558198719993e-06 -4.64326923285563e-06 4.45363123694257e-05 5.32896147561458e-05 7.487519283223e-05 -4.6625367692912e-06 2.75484702431571e-05 -1.23308874020945e-05 3.14209617254134e-05 -3.61757664372614e-06 -4.6625367692912e-06 1.02325904753918e-05 2.63831490795014e-06 3.97903792130841e-06 -2.33831941464172e-06 8.48558198719993e-06 2.75484702431571e-05 2.63831490795014e-06 7.24284741851119e-05 -2.08045759512394e-05 1.91962748057094e-05 -4.64326923285563e-06 -1.23308874020945e-05 3.97903792130841e-06 -2.08045759512394e-05 5.00688131128244e-05 -1.41471179008189e-05 4.45363123694257e-05 3.14209617254134e-05 -2.33831941464172e-06 1.91962748057094e-05 -1.41471179008189e-05 9.35722383452818e-05 1612 1613 0 12 10 1600 1617 0 32 5 0 0 0 0 0 5 21 0 336 0 39 43 0 0 2207 +361 408 0.996996941457862 -0.00153186605265549 0.0774257845298607 -0.0175343925829321 -0.00770062982342091 0.9928878903911 0.118803776939259 -0.015157402726296 -0.0770571153365498 -0.119043229547536 0.989894393597066 -0.00639970296301682 6.54390785378005e-05 4.33390836144439e-05 -3.67861185153424e-06 -2.4323510745244e-06 -2.28573165542977e-06 2.77484313212507e-05 4.33390836144439e-05 9.884376813639e-05 -1.69870778894695e-06 2.01631374371775e-05 -6.71474591156083e-06 4.23107926133891e-05 -3.67861185153424e-06 -1.69870778894695e-06 1.09601145960903e-05 5.24201457389208e-06 3.31760798725516e-06 3.23802528180515e-07 -2.4323510745244e-06 2.01631374371775e-05 5.24201457389208e-06 5.23630594471526e-05 -1.48371929394299e-05 2.24598765762473e-05 -2.28573165542977e-06 -6.71474591156083e-06 3.31760798725516e-06 -1.48371929394299e-05 3.59523442982206e-05 -1.17991403734571e-05 2.77484313212507e-05 4.23107926133891e-05 3.23802528180515e-07 2.24598765762473e-05 -1.17991403734571e-05 9.42367320276911e-05 1695 1697 0 13 15 1658 1673 0 31 5 0 0 0 0 0 4 21 0 331 0 74 84 0 0 2271 +361 394 0.99664971287565 -0.00186751654880209 0.0817671217961366 -0.0169939966334529 -0.00771366987734257 0.993136820286611 0.11670370811599 -0.0189436645202258 -0.0814238854508163 -0.116943441769681 0.989795121378739 0.0010296866957156 8.95937344475019e-05 6.4285697606898e-05 -5.08976010009174e-06 5.38774440731259e-06 -5.66440214793745e-06 6.10202865653528e-05 6.4285697606898e-05 0.000110892428268354 -5.48508639991824e-06 1.96210638803697e-05 -1.34422898876402e-06 4.80840846301745e-05 -5.08976010009174e-06 -5.48508639991824e-06 1.05474766614586e-05 2.61593790849197e-06 4.49924933919522e-06 -5.17053189551895e-06 5.38774440731259e-06 1.96210638803697e-05 2.61593790849197e-06 4.689284473241e-05 -9.75222504814688e-06 4.98780428893684e-06 -5.66440214793745e-06 -1.34422898876402e-06 4.49924933919522e-06 -9.75222504814688e-06 4.28077865365456e-05 4.3748251848901e-07 6.10202865653528e-05 4.80840846301745e-05 -5.17053189551895e-06 4.98780428893684e-06 4.3748251848901e-07 0.000100986689635356 1555 1556 0 12 27 1539 1560 0 28 12 0 0 0 0 0 4 18 0 289 0 79 61 0 0 2405 +361 390 0.996784848821413 -0.00101122841938769 0.0801183036337893 -0.0138847601894272 -0.00798253950444185 0.993692348004705 0.111856142343445 -0.0198570990659532 -0.0797260573660347 -0.112136055459343 0.990489404710059 0.0127461876261813 7.06468863366757e-05 5.08768828955088e-05 -4.63364637827578e-06 1.37539680811903e-05 -6.41599813261108e-06 3.40733949162305e-05 5.08768828955088e-05 0.000112044313229109 -8.2102046791165e-06 3.94402781477108e-05 -1.8899750338871e-05 4.07036190160053e-05 -4.63364637827578e-06 -8.2102046791165e-06 1.13857471069978e-05 2.5524633415329e-06 3.44353085679534e-06 -5.72042589848926e-06 1.37539680811903e-05 3.94402781477108e-05 2.5524633415329e-06 7.01397102141466e-05 -2.72022362890451e-05 1.93988901932093e-05 -6.41599813261108e-06 -1.8899750338871e-05 3.44353085679534e-06 -2.72022362890451e-05 6.17265447168121e-05 -6.45160069728062e-06 3.40733949162305e-05 4.07036190160053e-05 -5.72042589848926e-06 1.93988901932093e-05 -6.45160069728062e-06 8.54533704789155e-05 1729 1724 0 13 34 1702 1726 0 31 12 0 0 0 0 0 3 20 0 255 0 82 58 0 0 2461 +361 417 0.99689995821231 -0.00128108503772648 0.0786691307783464 -0.0187333538310226 -0.00760239880093343 0.993620531012995 0.112518637931346 -0.0141705100643813 -0.0783114094418305 -0.112767899557364 0.990530526526393 -0.00187875451022485 9.34719160336928e-05 7.69668621713521e-05 -8.70872686191392e-06 2.39301910834702e-05 2.63055720738453e-06 5.55385339677089e-05 7.69668621713521e-05 0.000104490855034068 -1.08209486031913e-05 3.3171606485931e-05 -4.83572663538403e-06 5.76319990743568e-05 -8.70872686191392e-06 -1.08209486031913e-05 1.21585142567366e-05 3.39680333030986e-07 1.864068643884e-06 -4.61906036778572e-06 2.39301910834702e-05 3.3171606485931e-05 3.39680333030986e-07 6.02276070537467e-05 -2.23502543072339e-05 2.7767111844776e-05 2.63055720738453e-06 -4.83572663538403e-06 1.864068643884e-06 -2.23502543072339e-05 5.11063792388841e-05 -1.05425607132643e-05 5.55385339677089e-05 5.76319990743568e-05 -4.61906036778572e-06 2.7767111844776e-05 -1.05425607132643e-05 0.00011241044973697 1998 1999 0 15 13 1969 1986 0 31 5 0 0 0 0 0 6 26 0 435 0 73 83 0 0 2273 +361 416 0.997111462204118 -0.00109496162402293 0.0759442756250102 -0.0272491419144943 -0.00778600045092186 0.993154813881297 0.116545672855683 -0.00804023657162833 -0.0755520359629299 -0.116800328438954 0.990277523292541 -0.00303616655276027 6.89653058298375e-05 4.6138709940101e-05 -8.90811140792619e-06 -1.15005562590495e-07 1.55785685173981e-05 3.50686021362858e-05 4.6138709940101e-05 0.000101839208741484 -8.18647750700091e-06 2.576040611464e-05 4.08094867199601e-06 3.43895600165514e-05 -8.90811140792619e-06 -8.18647750700091e-06 1.20519591006787e-05 7.85529917205138e-07 1.01437195022714e-06 -3.45706747634377e-06 -1.15005562590495e-07 2.576040611464e-05 7.85529917205138e-07 6.51274933867946e-05 -2.79450210135966e-05 -2.56668581692591e-06 1.55785685173981e-05 4.08094867199601e-06 1.01437195022714e-06 -2.79450210135966e-05 4.89636803719729e-05 7.29231562321595e-06 3.50686021362858e-05 3.43895600165514e-05 -3.45706747634377e-06 -2.56668581692591e-06 7.29231562321595e-06 0.000105468551861826 1745 1748 0 14 12 1718 1738 0 35 8 0 0 0 0 0 5 24 0 441 0 71 76 0 0 2230 +362 410 0.997866865059299 -0.000370202931266501 0.0652807978391471 -0.0236567552633558 -0.00640289262250714 0.994607443889659 0.103513455769496 -0.00678357996584677 -0.0649670884586231 -0.103710633539037 0.9924834416292 -0.00757757020536904 7.7808041633395e-05 5.99443770810857e-05 -2.03752562210015e-06 1.57302449911368e-05 -1.2372536878476e-05 5.59678281683856e-05 5.99443770810857e-05 7.43037341911872e-05 -2.22585246496665e-06 2.20542660377532e-05 -1.81991220461653e-05 5.04559623775075e-05 -2.03752562210015e-06 -2.22585246496665e-06 1.00745997950674e-05 2.50926214266828e-06 3.24781627259492e-06 -2.12875266332883e-06 1.57302449911368e-05 2.20542660377532e-05 2.50926214266828e-06 4.77233958708312e-05 -2.04105328896179e-05 2.6894998765318e-05 -1.2372536878476e-05 -1.81991220461653e-05 3.24781627259492e-06 -2.04105328896179e-05 5.19133283840146e-05 -2.98604478524195e-05 5.59678281683856e-05 5.04559623775075e-05 -2.12875266332883e-06 2.6894998765318e-05 -2.98604478524195e-05 0.000121434382833878 1737 1740 0 17 9 1732 1757 0 38 5 0 0 0 0 0 16 34 0 371 0 31 41 0 0 2264 +362 411 0.997937811343303 -0.000470962854643144 0.0641864696437514 -0.0185377746135267 -0.00592321390848176 0.995030726025979 0.0993920006902325 -0.0133295338140739 -0.0639143194310402 -0.0995672258235729 0.992975995335972 -0.000585616252399219 0.000134623024726597 8.8759263723355e-05 -1.11115227128799e-05 2.13294045719227e-05 -1.74177218060433e-05 9.27559388690088e-05 8.8759263723355e-05 9.1619677532586e-05 -9.38398275093566e-06 2.07888437983226e-05 -8.35402583528037e-06 7.44779935948554e-05 -1.11115227128799e-05 -9.38398275093566e-06 1.13335500590758e-05 1.67887335713069e-06 3.78034771485776e-06 -6.49052995271222e-06 2.13294045719227e-05 2.07888437983226e-05 1.67887335713069e-06 3.56963617112722e-05 -8.06391341459702e-06 2.24281937836535e-05 -1.74177218060433e-05 -8.35402583528037e-06 3.78034771485776e-06 -8.06391341459702e-06 4.07592677826846e-05 -1.99603062334334e-05 9.27559388690088e-05 7.44779935948554e-05 -6.49052995271222e-06 2.24281937836535e-05 -1.99603062334334e-05 0.000123495230909707 1691 1696 0 17 10 1677 1694 0 37 4 0 0 0 0 0 12 31 0 400 0 69 80 0 0 2243 +362 364 0.999084561076503 -1.73024725395625e-05 0.0427789611748125 -0.0224769191248457 -0.00346818122669472 0.996675395967536 0.08140102451403 -0.00197739900035919 -0.0426381465069775 -0.0814748720378213 0.995762940507865 -0.00322801885381279 8.68780604615279e-05 5.85985759287452e-05 -9.15575080886968e-06 1.55231899284283e-05 -4.5458442866696e-06 5.54031191457902e-05 5.85985759287452e-05 0.000106645094959616 -7.64387512927557e-06 3.4720656684246e-05 -1.01799279928109e-05 8.45076039335731e-05 -9.15575080886968e-06 -7.64387512927557e-06 1.41023254105705e-05 -4.94252110674776e-08 -1.09168591749022e-06 -4.92319320561967e-06 1.55231899284283e-05 3.4720656684246e-05 -4.94252110674776e-08 5.81445389678277e-05 -3.27485273615128e-05 3.44709204090333e-05 -4.5458442866696e-06 -1.01799279928109e-05 -1.09168591749022e-06 -3.27485273615128e-05 5.98172737533734e-05 -1.63279545982081e-05 5.54031191457902e-05 8.45076039335731e-05 -4.92319320561967e-06 3.44709204090333e-05 -1.63279545982081e-05 0.000133870644755804 2597 2585 0 15 38 2561 2593 0 31 15 0 0 0 0 0 10 29 0 462 0 84 58 0 0 2983 +361 415 0.996987555961478 -0.00150077620259752 0.0775471529377351 -0.011864420471002 -0.00766622255624943 0.993010257268869 0.117778852051341 -0.0234530582855495 -0.0771818779874966 -0.118018543583639 0.990007364154792 -0.0075985162031788 5.54727140131937e-05 3.54848557571581e-05 -6.76779040913395e-06 7.68304366369646e-06 -1.5767068850935e-07 2.77640938782968e-05 3.54848557571581e-05 6.31183395532266e-05 -7.57932614382783e-06 1.50943372427281e-05 2.26820888740715e-06 1.83642515967685e-05 -6.76779040913395e-06 -7.57932614382783e-06 1.19665816156863e-05 9.53666785845829e-07 3.06371961906941e-07 -3.61147945619054e-06 7.68304366369646e-06 1.50943372427281e-05 9.53666785845829e-07 3.88888825379856e-05 -8.28714428597471e-06 6.9561844718639e-06 -1.5767068850935e-07 2.26820888740715e-06 3.06371961906941e-07 -8.28714428597471e-06 4.32892902394022e-05 -6.89469064923561e-06 2.77640938782968e-05 1.83642515967685e-05 -3.61147945619054e-06 6.9561844718639e-06 -6.89469064923561e-06 7.84737547281025e-05 1603 1607 0 14 14 1558 1577 0 35 2 0 0 0 0 0 6 24 0 412 0 87 94 0 0 2190 +361 414 0.997681373668652 -0.0022608066559243 0.0680203306952939 -0.0340509441834391 -0.00618155587499837 0.992306780018169 0.123648868563111 -0.00701673668741146 -0.0677765815130631 -0.123782644515448 0.989992016086577 -0.0124863558461572 9.23151188562573e-05 7.82281775177024e-05 -8.25533718661423e-06 1.26125564748753e-05 2.85962972515636e-06 7.43318264663216e-05 7.82281775177024e-05 0.000131504428075161 -9.01462012780769e-06 3.58717747638215e-05 -9.21181283387582e-07 8.33840971712337e-05 -8.25533718661423e-06 -9.01462012780769e-06 1.09492454762354e-05 1.40922638753458e-06 8.90854486108715e-07 -6.68176329376701e-06 1.26125564748753e-05 3.58717747638215e-05 1.40922638753458e-06 7.13341663746568e-05 -2.92827304749403e-05 2.34557926457404e-05 2.85962972515636e-06 -9.21181283387582e-07 8.90854486108715e-07 -2.92827304749403e-05 5.56192715585726e-05 1.95728899328098e-06 7.43318264663216e-05 8.33840971712337e-05 -6.68176329376701e-06 2.34557926457404e-05 1.95728899328098e-06 0.000151354087755148 1739 1744 0 14 12 1689 1706 0 30 2 0 0 0 0 0 6 22 0 432 0 72 75 0 0 2326 +361 391 0.996210108799691 -0.00188984444532361 0.0869588846138224 -0.0125657158571348 -0.00818122729631203 0.993295640575301 0.115311915837125 -0.0161073879532258 -0.0865938025798249 -0.115586326622463 0.989515696920818 0.00339456091754435 7.3842059769821e-05 4.16027479377959e-05 -7.13535109660215e-07 8.63504867199199e-06 -8.6957458229692e-06 2.2019985294295e-05 4.16027479377959e-05 8.29304699284632e-05 -3.31866162370853e-06 2.02054319768496e-05 -7.55735300394331e-06 1.56049676908844e-05 -7.13535109660215e-07 -3.31866162370853e-06 1.07898196682659e-05 1.24948300904401e-06 5.75185075399925e-06 -1.21184390648641e-06 8.63504867199199e-06 2.02054319768496e-05 1.24948300904401e-06 4.34065029707656e-05 -9.02606616172813e-06 5.9476691334215e-06 -8.6957458229692e-06 -7.55735300394331e-06 5.75185075399925e-06 -9.02606616172813e-06 3.45668083873397e-05 -1.47793670376062e-06 2.2019985294295e-05 1.56049676908844e-05 -1.21184390648641e-06 5.9476691334215e-06 -1.47793670376062e-06 0.000106641563799958 1728 1721 0 16 34 1686 1700 0 29 5 0 0 0 0 0 2 17 0 241 0 120 113 0 0 2397 +362 412 0.99785053660042 0.000463815484075325 0.0655293177245885 -0.0193016651318545 -0.00680502759754155 0.995302047062922 0.0965791215105711 -0.0116335529639093 -0.0651766691819246 -0.0968174570392844 0.993165838018403 -0.00126137648804856 0.000161142059953281 0.00011320808893424 -1.48366653596306e-05 4.80356765598343e-05 -3.87899321024658e-05 0.000119325845345473 0.00011320808893424 0.000118587999331578 -1.30359022695933e-05 4.52297308791362e-05 -3.0876973131879e-05 0.000102778927687642 -1.48366653596306e-05 -1.30359022695933e-05 1.22878096282772e-05 -3.77368812383283e-07 2.69298512317323e-06 -1.049494115017e-05 4.80356765598343e-05 4.52297308791362e-05 -3.77368812383283e-07 5.70456228929488e-05 -2.92621349342559e-05 4.68088012038179e-05 -3.87899321024658e-05 -3.0876973131879e-05 2.69298512317323e-06 -2.92621349342559e-05 6.70749032385382e-05 -4.67020303477843e-05 0.000119325845345473 0.000102778927687642 -1.049494115017e-05 4.68088012038179e-05 -4.67020303477843e-05 0.000154497451916969 1862 1864 0 15 9 1848 1864 0 31 3 0 0 0 0 0 14 33 0 436 0 72 82 0 0 2212 +362 396 0.997481926567814 -0.000771404526841696 0.0709169310222785 -0.0131914613239926 -0.00621844953807152 0.995138357738629 0.0982902835615368 -0.0220316913255596 -0.0706479798430578 -0.0984837747668154 0.992627729338534 0.00183091692984913 0.000123503932160246 8.34135430922757e-05 -5.05936296297915e-06 1.79745263228446e-05 -2.54003830310715e-05 6.54382158834429e-05 8.34135430922757e-05 0.000114029539097663 -5.03319088453791e-06 2.98890563624258e-05 -1.60216304135061e-05 6.23650836835074e-05 -5.05936296297915e-06 -5.03319088453791e-06 1.07783829988541e-05 1.96521582510087e-06 3.44678191094054e-06 -1.27965877255051e-06 1.79745263228446e-05 2.98890563624258e-05 1.96521582510087e-06 5.2176992164471e-05 -1.21028418235025e-05 2.19150866511203e-05 -2.54003830310715e-05 -1.60216304135061e-05 3.44678191094054e-06 -1.21028418235025e-05 5.20387520518736e-05 -1.84374551713087e-05 6.54382158834429e-05 6.23650836835074e-05 -1.27965877255051e-06 2.19150866511203e-05 -1.84374551713087e-05 0.000123416464686654 1932 1928 0 18 31 1918 1948 0 42 7 0 0 0 0 0 8 27 0 320 0 88 71 0 0 2472 +362 394 0.997612544699973 -0.000716986219242489 0.0690557498547767 -0.0126229770998431 -0.00617230957094123 0.995018503796489 0.099499144203135 -0.019643227148169 -0.0687830884142646 -0.0996878279097162 0.992638516135072 0.000402156073550785 0.000103830815845807 5.43724375794043e-05 -1.74553775734727e-06 9.56688289318307e-06 -2.85068853235602e-05 5.01843325586813e-05 5.43724375794043e-05 7.69768682724588e-05 -3.45497425672789e-06 1.47518776916764e-05 -9.56676119169993e-06 3.49463099953671e-05 -1.74553775734727e-06 -3.45497425672789e-06 1.04375179670901e-05 3.22526437572144e-06 5.77119063699799e-06 -5.37247890203599e-06 9.56688289318307e-06 1.47518776916764e-05 3.22526437572144e-06 4.32173542758586e-05 -1.00966435896324e-05 8.3257253874744e-06 -2.85068853235602e-05 -9.56676119169993e-06 5.77119063699799e-06 -1.00966435896324e-05 5.13987541435839e-05 -1.57895125228327e-05 5.01843325586813e-05 3.49463099953671e-05 -5.37247890203599e-06 8.3257253874744e-06 -1.57895125228327e-05 0.000104638012905409 1754 1746 0 16 32 1743 1773 0 34 11 0 0 0 0 0 10 29 0 323 0 85 65 0 0 2415 +362 395 0.997712072301805 -0.000683570944913568 0.0676029105438579 -0.0132134760599077 -0.00613773675808982 0.994903638831191 0.100643318844039 -0.0144142270067282 -0.0673271785442252 -0.100827983076217 0.992623175660359 0.00365686547268474 8.44689064316842e-05 4.40967608312393e-05 -2.62315908493864e-06 1.37270587394234e-05 -2.43855226355028e-05 4.95671571089246e-05 4.40967608312393e-05 6.44758838625831e-05 -4.03908884937661e-06 2.02023171803349e-05 -1.86292877250594e-05 4.1526781813735e-05 -2.62315908493864e-06 -4.03908884937661e-06 1.03416047985925e-05 2.4001517750196e-06 3.92407589991053e-06 -2.17902482044458e-06 1.37270587394234e-05 2.02023171803349e-05 2.4001517750196e-06 4.75921202492451e-05 -1.72634988203984e-05 2.0436663401836e-05 -2.43855226355028e-05 -1.86292877250594e-05 3.92407589991053e-06 -1.72634988203984e-05 5.02305764027674e-05 -2.17122735356886e-05 4.95671571089246e-05 4.1526781813735e-05 -2.17902482044458e-06 2.0436663401836e-05 -2.17122735356886e-05 9.31263299461181e-05 2094 2089 0 18 39 2070 2096 0 40 13 0 0 0 0 0 13 33 0 319 0 92 77 0 0 2460 +362 413 0.997427130378802 -7.96847882975792e-05 0.0716876086547907 -0.0207661090239439 -0.00680008320760899 0.995385116212201 0.0957195345349811 -0.0125723998234285 -0.0713644060626689 -0.095960742356228 0.992823578222115 0.000115514856366612 0.000156245729870508 0.000123050712001388 -1.46898558968652e-05 2.54492999931547e-05 -1.56462277053189e-05 0.000128182230268954 0.000123050712001388 0.000175450241498199 -1.35763727616729e-05 4.84056312061689e-05 -2.68112166027435e-05 0.000116794083432189 -1.46898558968652e-05 -1.35763727616729e-05 1.32261469246697e-05 1.9514253428253e-06 3.13874313755115e-06 -1.09399480899885e-05 2.54492999931547e-05 4.84056312061689e-05 1.9514253428253e-06 6.31161506036214e-05 -1.4618462546824e-05 3.26671286732544e-05 -1.56462277053189e-05 -2.68112166027435e-05 3.13874313755115e-06 -1.4618462546824e-05 4.5181594890083e-05 -2.22538816071824e-05 0.000128182230268954 0.000116794083432189 -1.09399480899885e-05 3.26671286732544e-05 -2.22538816071824e-05 0.000198984881585649 1746 1747 0 16 11 1736 1760 0 35 3 0 0 0 0 0 12 33 0 452 0 38 46 0 0 2256 +362 389 0.997981318989089 -0.000616293607257681 0.0635051740489595 -0.015028507424849 -0.0058788548340738 0.99476294885972 0.10203976990249 -0.0173634305169891 -0.0632354806626697 -0.102207121856076 0.992751216683847 -0.00176587094843819 4.1579328350756e-05 1.79932505654789e-05 3.39964183646187e-07 2.11189513721541e-08 -5.26463683838774e-06 1.56039801440879e-05 1.79932505654789e-05 6.23899120971676e-05 -3.02717199761644e-06 1.50234873828192e-05 -5.82903295736886e-06 2.08258645991154e-05 3.39964183646187e-07 -3.02717199761644e-06 9.40044505542167e-06 3.50805782270657e-06 4.28186791851481e-06 4.31564599608965e-07 2.11189513721541e-08 1.50234873828192e-05 3.50805782270657e-06 4.3029353036129e-05 -1.3163928941817e-05 3.93015489112748e-06 -5.26463683838774e-06 -5.82903295736886e-06 4.28186791851481e-06 -1.3163928941817e-05 3.71287833040591e-05 -8.01610402287003e-06 1.56039801440879e-05 2.08258645991154e-05 4.31564599608965e-07 3.93015489112748e-06 -8.01610402287003e-06 6.17447257249696e-05 1866 1855 0 14 36 1821 1836 0 30 1 0 0 0 0 0 11 31 0 369 0 115 102 0 0 2556 +362 391 0.997210533479535 -0.000419984835498727 0.0746389679068421 -0.00883482398859376 -0.00666419977785751 0.99548942318275 0.0946382415971229 -0.0168828651302354 -0.0743420497348671 -0.0948716603839764 0.992709739902458 0.0095033293183752 0.000131004269852559 6.81028772803551e-05 -5.06675674544276e-06 9.96932922382843e-06 -1.27214373638177e-05 6.89693779940754e-05 6.81028772803551e-05 8.86110193548096e-05 -4.82082518353415e-06 1.85917262894536e-05 -1.20609606711314e-05 5.08684260668823e-05 -5.06675674544276e-06 -4.82082518353415e-06 1.01680501841123e-05 1.90913031976676e-06 5.12200939648786e-06 -3.67419242081315e-06 9.96932922382843e-06 1.85917262894536e-05 1.90913031976676e-06 4.24034394550052e-05 -1.18039623917867e-05 1.80515761971897e-05 -1.27214373638177e-05 -1.20609606711314e-05 5.12200939648786e-06 -1.18039623917867e-05 4.08905912406051e-05 -1.6113105687281e-05 6.89693779940754e-05 5.08684260668823e-05 -3.67419242081315e-06 1.80515761971897e-05 -1.6113105687281e-05 0.000117408712141194 1925 1920 0 15 33 1903 1925 0 37 12 0 0 0 0 0 15 34 0 272 0 99 83 0 0 2393 +362 388 0.997864071008509 -0.00128219181354718 0.0653119573621778 -0.011949992023067 -0.00557170255187435 0.994493446771543 0.104650563587254 -0.0181329290422511 -0.0650864956884229 -0.104790936214015 0.992362135395336 -0.00306507015877712 4.65416893932371e-05 2.57413445547581e-05 -7.04837404075064e-07 -6.17441190145335e-06 2.26745993771652e-06 2.556101003996e-05 2.57413445547581e-05 5.49384834961792e-05 -3.56106028933985e-07 7.84249378717816e-06 -7.19609738903207e-06 2.48744766311304e-05 -7.04837404075064e-07 -3.56106028933985e-07 1.01453747836662e-05 5.03072467431052e-06 2.46212086636156e-06 -1.28738939108963e-06 -6.17441190145335e-06 7.84249378717816e-06 5.03072467431052e-06 4.31926954163323e-05 -1.34681676305426e-05 3.12988016600862e-06 2.26745993771652e-06 -7.19609738903207e-06 2.46212086636156e-06 -1.34681676305426e-05 3.45197534018452e-05 -4.43371165009632e-06 2.556101003996e-05 2.48744766311304e-05 -1.28738939108963e-06 3.12988016600862e-06 -4.43371165009632e-06 6.96307547368025e-05 2102 2093 0 18 39 2055 2074 0 38 5 0 0 0 0 0 8 28 0 519 0 111 113 0 0 2643 +362 390 0.997071574127439 -4.26922505588019e-05 0.0764740102544825 -0.00911690585676395 -0.00680279527660385 0.99598591914278 0.0892511671953691 -0.0197948161902699 -0.0761708477270378 -0.0895100388039401 0.993068957781816 0.0148959573065925 0.000114102749743194 4.30468131494167e-05 -1.01566994718497e-05 1.5954896891523e-05 -2.23236150271228e-05 4.55981168530624e-05 4.30468131494167e-05 7.92813445443983e-05 -7.09272539379649e-06 1.31736443835285e-05 6.39042255858064e-06 3.9344463087892e-05 -1.01566994718497e-05 -7.09272539379649e-06 1.1749906049969e-05 1.15177819880882e-06 4.72629150970053e-06 -6.25708699982009e-06 1.5954896891523e-05 1.31736443835285e-05 1.15177819880882e-06 4.03084305187516e-05 -5.74889715156646e-06 2.01431888744592e-05 -2.23236150271228e-05 6.39042255858064e-06 4.72629150970053e-06 -5.74889715156646e-06 5.98953999353226e-05 -9.10656375152719e-06 4.55981168530624e-05 3.9344463087892e-05 -6.25708699982009e-06 2.01431888744592e-05 -9.10656375152719e-06 9.56009941829228e-05 1948 1937 0 13 37 1908 1925 0 36 0 0 0 0 0 0 14 36 0 268 0 124 110 0 0 2455 +362 409 0.997437406646017 -0.000376457581645632 0.0715435399107283 -0.0243830679702584 -0.00639389803230516 0.995515708161505 0.094380044880526 -0.0116929709084884 -0.0712582478820609 -0.0945956293038258 0.992962199192594 0.00112762734966833 0.00011761489099661 6.44691929400418e-05 -7.81534994121157e-06 1.22900901361316e-05 -2.01128881862172e-05 5.42588651926129e-05 6.44691929400418e-05 7.61680556207548e-05 -5.90817516786143e-06 1.75406480765793e-05 -1.27263108365612e-05 3.83618737647192e-05 -7.81534994121157e-06 -5.90817516786143e-06 1.13068704027128e-05 1.80700266026129e-06 4.51390822649312e-06 -3.45442820697621e-06 1.22900901361316e-05 1.75406480765793e-05 1.80700266026129e-06 5.66275112244578e-05 -1.44043734850792e-05 1.35584274158485e-05 -2.01128881862172e-05 -1.27263108365612e-05 4.51390822649312e-06 -1.44043734850792e-05 4.94761225790503e-05 -1.80238555933764e-05 5.42588651926129e-05 3.83618737647192e-05 -3.45442820697621e-06 1.35584274158485e-05 -1.80238555933764e-05 9.869336402349e-05 1674 1674 0 14 10 1669 1696 0 34 5 0 0 0 0 0 11 31 0 360 0 39 44 0 0 2249 +362 415 0.997746045115165 -0.000408421826857395 0.0671018826014457 -0.0144610387809566 -0.00633688361622419 0.994939108381089 0.100279681490705 -0.0154922422553949 -0.066803243656886 -0.100478872433234 0.992693972396058 -0.00230699689032756 0.000137636175231151 0.000117410264000211 -1.32060399374202e-05 2.64918431618362e-05 -8.82190739466733e-06 0.00011601134390821 0.000117410264000211 0.00014943514007095 -1.56539309036479e-05 3.73501177786045e-05 -9.25109862595716e-06 0.000116427982283479 -1.32060399374202e-05 -1.56539309036479e-05 1.41771965252217e-05 1.67035404972434e-06 -7.92776650691125e-07 -9.07328769402071e-06 2.64918431618362e-05 3.73501177786045e-05 1.67035404972434e-06 5.0087834320838e-05 -1.37247358423008e-05 3.84883223513758e-05 -8.82190739466733e-06 -9.25109862595716e-06 -7.92776650691125e-07 -1.37247358423008e-05 4.62832586962771e-05 -1.8814955506481e-05 0.00011601134390821 0.000116427982283479 -9.07328769402071e-06 3.84883223513758e-05 -1.8814955506481e-05 0.000174029454304854 1811 1815 0 14 14 1801 1824 0 41 7 0 0 0 0 0 10 31 0 436 0 74 93 0 0 2256 +362 414 0.998027323024714 -0.000622055061719094 0.0627779861386406 -0.0283333447488304 -0.00576896153834565 0.994811588373044 0.101570776906893 -0.00598986592943722 -0.0625154507213397 -0.101732574361416 0.992845557846187 -0.00774515568148052 0.00013857344558508 0.000106052614966463 -1.16630746326e-05 1.94642445911512e-05 -1.69291235395213e-05 0.000119818123509082 0.000106052614966463 0.000125896323645896 -1.20699193465207e-05 1.79946630018916e-05 -5.94919972160452e-06 0.000107981079561806 -1.16630746326e-05 -1.20699193465207e-05 1.207656968167e-05 -1.86413097570269e-06 3.35850781363647e-06 -8.06666006386664e-06 1.94642445911512e-05 1.79946630018916e-05 -1.86413097570269e-06 5.02491896236021e-05 -1.84238780595821e-05 2.2598947162089e-05 -1.69291235395213e-05 -5.94919972160452e-06 3.35850781363647e-06 -1.84238780595821e-05 5.00069950342507e-05 -2.23780613068887e-05 0.000119818123509082 0.000107981079561806 -8.06666006386664e-06 2.2598947162089e-05 -2.23780613068887e-05 0.000173808438066935 1795 1797 0 12 11 1794 1813 0 38 6 0 0 0 0 0 20 38 0 461 0 52 57 0 0 2372 +362 416 0.997783146467683 -0.000747106257719741 0.0665449807069628 -0.0217870896773889 -0.00612300673483704 0.994664967874353 0.102976261691891 -0.00814527864661993 -0.0662668953065972 -0.103155433767453 0.992455366790201 -0.00425456908081494 5.87877399506501e-05 3.95822420335033e-05 -7.94241147192893e-06 7.22767064124826e-06 1.12621997665604e-05 3.88040212517728e-05 3.95822420335033e-05 5.98027998224967e-05 -9.92826083082896e-06 1.06469089992939e-05 5.63603785708174e-06 3.20233392980288e-05 -7.94241147192893e-06 -9.92826083082896e-06 1.22465201348271e-05 -1.72422946340574e-06 -1.3705843791519e-06 -4.05694316381859e-06 7.22767064124826e-06 1.06469089992939e-05 -1.72422946340574e-06 5.78699714301749e-05 -2.19824900421923e-05 2.69990811049837e-06 1.12621997665604e-05 5.63603785708174e-06 -1.3705843791519e-06 -2.19824900421923e-05 5.49879727585447e-05 8.6158902842106e-06 3.88040212517728e-05 3.20233392980288e-05 -4.05694316381859e-06 2.69990811049837e-06 8.6158902842106e-06 9.23608858371802e-05 1744 1748 0 15 12 1735 1761 0 35 8 0 0 0 0 0 11 32 0 463 0 51 55 0 0 2247 +362 397 0.997916680284959 -0.000147493278168992 0.0645157147893366 -0.0165907876093869 -0.00600700938888576 0.995440901542044 0.0951910046977337 -0.0218720537887252 -0.0642356213268617 -0.0953802379054226 0.993366193893197 0.0041737821026711 9.79525713380036e-05 6.24464273953013e-05 -7.46570942280977e-06 1.31250028191322e-05 -1.73780734331892e-05 5.89758771429393e-05 6.24464273953013e-05 8.56699472334015e-05 -6.68206421646512e-06 2.84691390002571e-05 -2.29675455328668e-05 5.88694608875164e-05 -7.46570942280977e-06 -6.68206421646512e-06 1.06573632064327e-05 2.43247710478069e-06 2.28459103202488e-06 -3.39882789843398e-06 1.31250028191322e-05 2.84691390002571e-05 2.43247710478069e-06 6.80479952753974e-05 -3.86442498968842e-05 2.81433589351933e-05 -1.73780734331892e-05 -2.29675455328668e-05 2.28459103202488e-06 -3.86442498968842e-05 6.82711913062792e-05 -2.34335202582857e-05 5.89758771429393e-05 5.88694608875164e-05 -3.39882789843398e-06 2.81433589351933e-05 -2.34335202582857e-05 0.000102584878305532 1621 1615 0 16 31 1573 1591 0 38 0 0 0 0 0 0 11 32 0 325 0 115 107 0 0 2379 +362 408 0.997838239966931 -0.000987187312428439 0.0657105191039266 -0.0178479376714366 -0.00584774795158202 0.994587035464734 0.103742145386371 -0.0115745373287057 -0.0654572433241126 -0.103902138316217 0.992431204139474 -0.00423075382830693 6.63511857564381e-05 4.62259100687125e-05 -3.57079741073565e-06 5.90993806504126e-06 -7.96403194026312e-06 3.28717136622765e-05 4.62259100687125e-05 7.79490412721728e-05 -2.98592178438024e-06 1.67426487783399e-05 -7.89501411586192e-06 4.25676716100318e-05 -3.57079741073565e-06 -2.98592178438024e-06 1.01815573326129e-05 2.25526774371056e-06 4.47397189205395e-06 -5.33166947956529e-07 5.90993806504126e-06 1.67426487783399e-05 2.25526774371056e-06 3.11331130137899e-05 -2.88885067341278e-06 1.11828999155589e-05 -7.96403194026312e-06 -7.89501411586192e-06 4.47397189205395e-06 -2.88885067341278e-06 2.7474089805194e-05 -8.07662389532269e-06 3.28717136622765e-05 4.25676716100318e-05 -5.33166947956529e-07 1.11828999155589e-05 -8.07662389532269e-06 8.92391505644355e-05 1826 1827 0 14 15 1818 1840 0 39 8 0 0 0 0 0 10 32 0 356 0 50 56 0 0 2326 +363 395 0.998438913150724 0.000841114764810893 0.0558482697346398 0.000832179624434191 -0.00424270286264769 0.99813991036387 0.060817093084312 -0.013128154753725 -0.0556932327919644 -0.060959099933964 0.996585295876084 0.00555907784756959 0.000152916049546121 7.30791272809274e-05 -6.65473174245715e-06 1.82740916867354e-05 -3.31855488783814e-05 9.80644773309603e-05 7.30791272809274e-05 8.63862668410079e-05 -5.14953212508818e-06 2.56220908177887e-05 -1.92858648485198e-05 5.8569979579615e-05 -6.65473174245715e-06 -5.14953212508818e-06 1.04906664299693e-05 1.97407487829054e-06 5.4140084554288e-06 -5.66578258286494e-06 1.82740916867354e-05 2.56220908177887e-05 1.97407487829054e-06 4.24831193700139e-05 -1.07197708391097e-05 2.20571361453435e-05 -3.31855488783814e-05 -1.92858648485198e-05 5.4140084554288e-06 -1.07197708391097e-05 5.20514962524942e-05 -2.94728779888037e-05 9.80644773309603e-05 5.8569979579615e-05 -5.66578258286494e-06 2.20571361453435e-05 -2.94728779888037e-05 0.000149323404134487 2286 2277 0 22 38 2270 2302 0 42 24 0 0 0 0 0 9 30 0 318 0 75 57 0 0 2439 +363 412 0.999251942561932 0.000905305276171089 0.0386618120186203 -0.0173128147572732 -0.00370638974949222 0.997365819587968 0.0724409041401674 -0.00197919157756604 -0.0384943886979785 -0.0725300099267675 0.996623088082346 -0.00862210075753728 9.46967280637756e-05 7.17003359265432e-05 -5.84949255057267e-06 2.99468890116035e-05 -1.70700410510987e-05 7.15265431937692e-05 7.17003359265432e-05 9.8400747102332e-05 -7.27898491242817e-06 4.01351833442542e-05 -1.76063878173799e-05 8.46081300693254e-05 -5.84949255057267e-06 -7.27898491242817e-06 1.07636596325561e-05 1.73411674462811e-06 2.58215512966463e-06 -1.72498331637587e-06 2.99468890116035e-05 4.01351833442542e-05 1.73411674462811e-06 5.00349404324276e-05 -1.14575552943242e-05 4.32605334471199e-05 -1.70700410510987e-05 -1.76063878173799e-05 2.58215512966463e-06 -1.14575552943242e-05 4.3644332844782e-05 -2.68273557909588e-05 7.15265431937692e-05 8.46081300693254e-05 -1.72498331637587e-06 4.32605334471199e-05 -2.68273557909588e-05 0.00014771341827112 2222 2224 0 18 9 2243 2271 0 35 16 0 0 0 0 0 12 31 0 430 0 44 46 0 0 2210 +362 417 0.997831253404971 -0.000762278902150871 0.0658195157923545 -0.0177817764131397 -0.00611153547166342 0.99454076079002 0.104169689744126 -0.0118714988757967 -0.0655395976676945 -0.104346030389681 0.992379195206889 -0.005524067936229 0.000153540933334147 8.73006446402332e-05 -1.61155225169137e-05 1.54762376510712e-05 -8.63438653523948e-06 0.000108079049950912 8.73006446402332e-05 8.70886901955634e-05 -1.24390958712486e-05 1.75127324388167e-05 -1.26110900526678e-06 7.1608084120712e-05 -1.61155225169137e-05 -1.24390958712486e-05 1.23510912203088e-05 7.77310246813372e-07 1.62695737690016e-06 -9.76053644778202e-06 1.54762376510712e-05 1.75127324388167e-05 7.77310246813372e-07 3.96530286639498e-05 -1.05191407284163e-05 1.55659402532949e-05 -8.63438653523948e-06 -1.26110900526678e-06 1.62695737690016e-06 -1.05191407284163e-05 4.38482614440827e-05 -1.33005315249864e-05 0.000108079049950912 7.1608084120712e-05 -9.76053644778202e-06 1.55659402532949e-05 -1.33005315249864e-05 0.000142021858516619 2111 2113 0 14 13 2101 2127 0 39 7 0 0 0 0 0 10 32 0 460 0 51 56 0 0 2348 +363 394 0.998517144874841 0.000480311856008446 0.0544360238400685 -0.00778077866788181 -0.00413896322025344 0.997736504188594 0.0671173389891484 -0.00884224728422714 -0.0542805708744567 -0.0672431223995722 0.996258993492907 -0.00471829053972045 8.61273539585943e-05 4.09404892639092e-05 -1.05087211957498e-07 4.86810397030252e-06 -1.86725660311363e-05 4.21240058720127e-05 4.09404892639092e-05 0.000100106022668294 1.41016870424094e-06 3.32404342497728e-05 -9.63332870941916e-06 4.05792022031553e-05 -1.05087211957498e-07 1.41016870424094e-06 1.13895195860725e-05 4.6687049116769e-06 5.29958384049674e-06 -4.41651960260101e-07 4.86810397030252e-06 3.32404342497728e-05 4.6687049116769e-06 5.79952117064253e-05 -1.07036939165216e-05 1.56566244623146e-05 -1.86725660311363e-05 -9.63332870941916e-06 5.29958384049674e-06 -1.07036939165216e-05 4.33534790966758e-05 -1.38987613277911e-05 4.21240058720127e-05 4.05792022031553e-05 -4.41651960260101e-07 1.56566244623146e-05 -1.38987613277911e-05 0.000109025862091239 1865 1853 0 14 37 1888 1914 0 32 19 0 0 0 0 0 11 26 0 321 0 94 74 0 0 2430 +363 396 0.998181546789191 0.00114298685616712 0.0602685094438534 -0.00584179255255745 -0.00456092754430897 0.998386241002343 0.0566048736165633 -0.0109088088645563 -0.0601065519679242 -0.0567768206071648 0.996575935417 0.00615350486854118 0.000126214743430425 9.69792158378879e-05 -5.45900989349685e-06 3.72852195658418e-05 -4.35901561127011e-05 6.51310970572532e-05 9.69792158378879e-05 0.000150888910813501 -6.48108839252372e-06 5.83653396665746e-05 -4.79525470340462e-05 6.99483330764911e-05 -5.45900989349685e-06 -6.48108839252372e-06 1.13361816356647e-05 2.41280116830236e-06 3.56376833911611e-06 -2.98000604870597e-06 3.72852195658418e-05 5.83653396665746e-05 2.41280116830236e-06 6.79270164738236e-05 -3.40726450121366e-05 3.78986117826943e-05 -4.35901561127011e-05 -4.79525470340462e-05 3.56376833911611e-06 -3.40726450121366e-05 7.77200283091579e-05 -2.9508389165559e-05 6.51310970572532e-05 6.99483330764911e-05 -2.98000604870597e-06 3.78986117826943e-05 -2.9508389165559e-05 0.000122104231646598 2031 2020 0 21 34 2054 2084 0 41 18 0 0 0 0 0 6 27 0 325 0 90 72 0 0 2450 +363 410 0.998827991817959 0.00125431280190506 0.048384599412388 -0.0146241642099327 -0.00425244835315843 0.998072576122062 0.0619116263400871 -0.0027287419199214 -0.048213685234651 -0.0620448184175425 0.996908160796986 -0.00210129657901829 6.78990471919655e-05 4.50614575685055e-05 -3.66654707013218e-06 1.38867067654059e-05 -9.5317988913327e-06 3.17041397233945e-05 4.50614575685055e-05 0.000100180496520237 -4.33072057979244e-06 4.75678951177498e-05 -1.918481718676e-05 4.18532956065888e-05 -3.66654707013218e-06 -4.33072057979244e-06 9.64919534205106e-06 2.89936324043851e-06 5.21895554033112e-06 -7.92481506489434e-07 1.38867067654059e-05 4.75678951177498e-05 2.89936324043851e-06 7.39843140114675e-05 -2.95782808784091e-05 2.89614827442713e-05 -9.5317988913327e-06 -1.918481718676e-05 5.21895554033112e-06 -2.95782808784091e-05 4.95306475462625e-05 -1.4902380411852e-05 3.17041397233945e-05 4.18532956065888e-05 -7.92481506489434e-07 2.89614827442713e-05 -1.4902380411852e-05 9.24799547985131e-05 1708 1707 0 17 9 1761 1789 0 38 16 0 0 0 0 0 9 30 0 378 0 39 41 0 0 2221 +363 397 0.998820793845481 0.00073514303114369 0.0485436025301602 -0.00511255797356275 -0.00398215782385591 0.997756707022016 0.0668258633438292 -0.0143779878707763 -0.0483855784397409 -0.0669403701611067 0.996583073627957 0.000523424260593637 0.000162294806261045 9.94291269116326e-05 -1.18018827582245e-05 2.22717363985284e-05 -2.8805266869915e-05 0.000107969697832228 9.94291269116326e-05 0.000111279461861353 -8.5905718211439e-06 3.35661694254273e-05 -1.85056132959937e-05 7.69845402974629e-05 -1.18018827582245e-05 -8.5905718211439e-06 1.11583708065296e-05 6.30771111786147e-07 6.70263078664693e-06 -8.20110265341939e-06 2.22717363985284e-05 3.35661694254273e-05 6.30771111786147e-07 5.39457171946923e-05 -2.39593889089155e-05 2.07032040321977e-05 -2.8805266869915e-05 -1.85056132959937e-05 6.70263078664693e-06 -2.39593889089155e-05 5.62321645144044e-05 -1.80260249907412e-05 0.000107969697832228 7.69845402974629e-05 -8.20110265341939e-06 2.07032040321977e-05 -1.80260249907412e-05 0.00016193458943114 1780 1773 0 21 39 1772 1800 0 40 22 0 0 0 0 0 11 31 0 326 0 77 60 0 0 2394 +363 389 0.999160921585875 0.00135696640863327 0.0409342328354913 -0.0117398489334238 -0.00404410616053774 0.997835559498942 0.0656341481608203 -0.00794539602032009 -0.0407565697897489 -0.065744618347056 0.997003784936333 -0.00584078784976987 7.91756007504261e-05 1.96826739316337e-05 -3.73726367072155e-06 7.52217098771181e-07 -1.56272857300348e-05 1.5678236310964e-05 1.96826739316337e-05 4.99630586142874e-05 -3.28067449173011e-06 8.59931177666851e-06 1.55640175628018e-06 1.02597909753651e-05 -3.73726367072155e-06 -3.28067449173011e-06 9.38445770890803e-06 3.28118477205896e-06 5.68351677340616e-06 -8.25567492803164e-07 7.52217098771181e-07 8.59931177666851e-06 3.28118477205896e-06 3.24249926890861e-05 -4.80435508666884e-06 -2.59426825238483e-06 -1.56272857300348e-05 1.55640175628018e-06 5.68351677340616e-06 -4.80435508666884e-06 3.80895340819912e-05 -1.33602007736597e-06 1.5678236310964e-05 1.02597909753651e-05 -8.25567492803164e-07 -2.59426825238483e-06 -1.33602007736597e-06 5.32799716775728e-05 2147 2130 0 18 45 2135 2161 0 38 24 0 0 0 0 0 6 27 0 368 0 85 62 0 0 2540 +363 411 0.998711488784483 0.000888547316728455 0.0507402468810343 -0.0112941095768208 -0.00440230255751657 0.997594466770362 0.0691801965980816 0.00210415717134599 -0.050556719653024 -0.0693144310574867 0.996312966765515 0.00034276506778536 9.82595649034315e-05 6.29014009370959e-05 -4.18388379975449e-06 1.48968145189558e-05 -9.21560032945435e-06 6.24970444099703e-05 6.29014009370959e-05 8.14537371577259e-05 -5.96072323677308e-06 2.41097662170175e-05 -1.01227001683431e-05 5.40477726717252e-05 -4.18388379975449e-06 -5.96072323677308e-06 1.07478347628128e-05 2.7633639082889e-06 4.74029305489175e-06 -1.55941769018739e-06 1.48968145189558e-05 2.41097662170175e-05 2.7633639082889e-06 4.80331692717461e-05 -7.4655917677834e-06 1.86039410596744e-05 -9.21560032945435e-06 -1.01227001683431e-05 4.74029305489175e-06 -7.4655917677834e-06 4.69382823474627e-05 -8.95553886181162e-06 6.24970444099703e-05 5.40477726717252e-05 -1.55941769018739e-06 1.86039410596744e-05 -8.95553886181162e-06 0.000118576554745027 1841 1843 0 19 10 1860 1888 0 36 11 0 0 0 0 0 8 26 0 397 0 33 34 0 0 2226 +363 391 0.998557643350486 0.00103663476990138 0.0536801480500746 -0.00078526641208474 -0.00438350391218583 0.998049824178101 0.0622682370997726 -0.0133166236365281 -0.0535109129035933 -0.0624137312329224 0.996614824470221 0.00289463245887205 7.00003406874094e-05 3.35103629202332e-05 1.19488295606026e-06 5.07746015482819e-06 -1.41335377996684e-05 3.47432126663259e-05 3.35103629202332e-05 6.91770096921461e-05 -1.823662481669e-06 1.69732888669302e-05 -8.32123032377777e-06 3.11515047458813e-05 1.19488295606026e-06 -1.823662481669e-06 1.01319292387821e-05 1.28268691778519e-06 5.80994106458404e-06 6.54166832366295e-07 5.07746015482819e-06 1.69732888669302e-05 1.28268691778519e-06 3.92957785673556e-05 -6.93623968157473e-06 1.47917806458148e-05 -1.41335377996684e-05 -8.32123032377777e-06 5.80994106458404e-06 -6.93623968157473e-06 3.61212074805428e-05 -1.09098842988e-05 3.47432126663259e-05 3.11515047458813e-05 6.54166832366295e-07 1.47917806458148e-05 -1.09098842988e-05 9.22003027087286e-05 1870 1860 0 17 38 1857 1886 0 41 21 0 0 0 0 0 9 30 0 288 0 78 61 0 0 2423 +363 390 0.998881213697569 0.00137033870957192 0.0472698962754527 -0.0080541971515525 -0.00435226941378434 0.998001637216832 0.0630380033271354 -0.00656905601565936 -0.0470890504578384 -0.0631732085962328 0.996891050738563 0.00692098346316255 6.20494068752496e-05 1.49911469493034e-05 -3.15950831296134e-06 -1.11983927927568e-06 -9.70614669178087e-06 1.61789878857244e-05 1.49911469493034e-05 5.24640445382673e-05 -4.04969973426809e-06 4.75803029331136e-06 7.68404968278575e-06 1.31112982210642e-05 -3.15950831296134e-06 -4.04969973426809e-06 1.01412689729773e-05 2.5739274974712e-06 4.81641784511955e-06 -2.89448676721329e-06 -1.11983927927568e-06 4.75803029331136e-06 2.5739274974712e-06 3.56021429422543e-05 5.18687542112968e-06 6.36503659719803e-06 -9.70614669178087e-06 7.68404968278575e-06 4.81641784511955e-06 5.18687542112968e-06 3.60618419901852e-05 4.85314060279907e-07 1.61789878857244e-05 1.31112982210642e-05 -2.89448676721329e-06 6.36503659719803e-06 4.85314060279907e-07 6.46513352522801e-05 2052 2041 0 19 44 2043 2071 0 40 22 0 0 0 0 0 7 28 0 284 0 83 59 0 0 2490 +363 409 0.998689355086917 0.00133721795384159 0.0511642832865037 -0.0186454432360655 -0.00439261948731054 0.998209584586549 0.0596517404070346 -0.00322371157908185 -0.0509929105868392 -0.0597983033847321 0.996907160161963 -0.00225644850276869 0.000106348193382464 8.13614182071132e-05 -4.91838113376777e-06 2.88876732351138e-05 -2.17405711400131e-05 6.42052608284747e-05 8.13614182071132e-05 0.000143940787643452 -6.13956796250562e-06 5.51463755729367e-05 -2.85221716777406e-05 7.23271220525805e-05 -4.91838113376777e-06 -6.13956796250562e-06 1.18869050918562e-05 -8.67791432804506e-07 9.0949586899333e-06 -3.45928492299805e-06 2.88876732351138e-05 5.51463755729367e-05 -8.67791432804506e-07 8.4696454836235e-05 -2.77886035027712e-05 2.88416828989843e-05 -2.17405711400131e-05 -2.85221716777406e-05 9.0949586899333e-06 -2.77886035027712e-05 5.17803963923724e-05 -1.58211069087282e-05 6.42052608284747e-05 7.23271220525805e-05 -3.45928492299805e-06 2.88416828989843e-05 -1.58211069087282e-05 0.000140171462320093 1550 1549 0 16 10 1606 1635 0 36 11 0 0 0 0 0 11 30 0 373 0 53 56 0 0 2220 +363 413 0.998523838209654 0.000972936595247943 0.0543065182224272 -0.0077851415089101 -0.00442608352010042 0.997971879858807 0.063502258194118 -0.00815966791559841 -0.0541345944081443 -0.0636488837723095 0.99650301820055 -0.00671385990539853 0.000114622864023697 9.38674796097407e-05 -7.35751861286889e-06 2.46522018344408e-05 -1.55989329172989e-05 6.98779999214533e-05 9.38674796097407e-05 0.00015667600515686 -8.45160139020364e-06 4.77031553795379e-05 -1.91709013227562e-05 9.3481121114652e-05 -7.35751861286889e-06 -8.45160139020364e-06 1.19943204393003e-05 1.66693455289269e-06 3.84786615367905e-06 -6.06509804900834e-06 2.46522018344408e-05 4.77031553795379e-05 1.66693455289269e-06 5.18198625172948e-05 -9.65623873008327e-06 3.10058128600624e-05 -1.55989329172989e-05 -1.91709013227562e-05 3.84786615367905e-06 -9.65623873008327e-06 4.55597003920595e-05 -2.00722375301876e-05 6.98779999214533e-05 9.3481121114652e-05 -6.06509804900834e-06 3.10058128600624e-05 -2.00722375301876e-05 0.000135975187693821 1861 1862 0 21 13 1910 1940 0 37 12 0 0 0 0 0 8 28 0 453 0 50 51 0 0 2202 +363 415 0.99897185959621 0.00056496650789004 0.0453310550035407 -0.0095177948146131 -0.00378707436210025 0.997467335717927 0.0710251521895972 -0.00433622652714688 -0.0451761198274596 -0.0711238004371566 0.996443938818793 -0.00910565402205235 6.57059623568891e-05 2.93351908073296e-05 -7.46169909750915e-06 6.51115682053379e-06 -2.79981705895464e-06 2.30448765882457e-05 2.93351908073296e-05 7.66922525386374e-05 -8.77129069411452e-06 2.8267359687734e-05 5.57084080088228e-06 2.75802520040217e-05 -7.46169909750915e-06 -8.77129069411452e-06 1.2713981696493e-05 8.3002118637656e-07 -9.91260799034375e-07 -2.34891471062798e-06 6.51115682053379e-06 2.8267359687734e-05 8.3002118637656e-07 5.40941291087153e-05 -7.36632254427279e-06 8.81110690341922e-06 -2.79981705895464e-06 5.57084080088228e-06 -9.91260799034375e-07 -7.36632254427279e-06 5.54771567931448e-05 -6.71371779248415e-07 2.30448765882457e-05 2.75802520040217e-05 -2.34891471062798e-06 8.81110690341922e-06 -6.71371779248415e-07 8.09420063132346e-05 1842 1849 0 18 14 1836 1873 0 36 23 0 0 0 0 0 7 27 0 433 0 33 34 0 0 2245 +363 417 0.998952124762478 0.00111234927835459 0.0457538535165437 -0.0113377841169804 -0.00427613128557197 0.99759999914758 0.0691082947407647 0.000554930327436258 -0.0455671716673193 -0.0692315273544561 0.996559395363071 -0.00831869826081498 7.54865347335055e-05 3.82713337270973e-05 -8.268773604862e-06 8.57634137978047e-06 -4.71063263294808e-06 3.4820637299344e-05 3.82713337270973e-05 6.85349018850144e-05 -8.84310507380768e-06 2.8218964449958e-05 -1.01929493239922e-06 3.59431525710976e-05 -8.268773604862e-06 -8.84310507380768e-06 1.24529958443248e-05 1.50738379633783e-07 1.58153496193433e-06 -1.68590152493307e-06 8.57634137978047e-06 2.8218964449958e-05 1.50738379633783e-07 5.05703614452095e-05 -3.2395941506276e-06 2.13425282921472e-05 -4.71063263294808e-06 -1.01929493239922e-06 1.58153496193433e-06 -3.2395941506276e-06 4.16877954989242e-05 -6.57795208070393e-06 3.4820637299344e-05 3.59431525710976e-05 -1.68590152493307e-06 2.13425282921472e-05 -6.57795208070393e-06 9.5782791627499e-05 2076 2078 0 19 14 2075 2106 0 37 12 0 0 0 0 0 11 32 0 463 0 33 35 0 0 2318 +363 416 0.99902945664248 0.00115066980690105 0.0440320419652106 -0.0152617500303399 -0.00414823267236791 0.997673546183465 0.0680462152614311 -0.00257353240486186 -0.0438513047277556 -0.0681628286143159 0.996710033996332 -0.00667819620656058 9.2069946450688e-05 3.38354497714364e-05 -8.92081532032464e-06 1.02807541489268e-05 -1.2428839682094e-05 3.11553464515308e-05 3.38354497714364e-05 5.78424855479979e-05 -8.89270749372688e-06 2.18111263242693e-05 -2.86200341899878e-06 2.23710843532058e-05 -8.92081532032464e-06 -8.89270749372688e-06 1.25578373912169e-05 -1.29048547367717e-07 1.13097119841294e-06 -3.73133078781342e-06 1.02807541489268e-05 2.18111263242693e-05 -1.29048547367717e-07 6.83742894387757e-05 -3.28809992930451e-05 1.30580207550546e-05 -1.2428839682094e-05 -2.86200341899878e-06 1.13097119841294e-06 -3.28809992930451e-05 6.83058688914446e-05 -1.13810234594838e-05 3.11553464515308e-05 2.23710843532058e-05 -3.73133078781342e-06 1.30580207550546e-05 -1.13810234594838e-05 7.91402689889794e-05 1553 1554 0 21 13 1558 1589 0 39 13 0 0 0 0 0 9 29 0 467 0 36 39 0 0 2239 +363 414 0.999128238482083 0.00144973173335579 0.0417212337496205 -0.0276300880146409 -0.00415890487457664 0.997881686576317 0.0649218230323945 0.00610526078585208 -0.0415387358730787 -0.0650387413278165 0.997017801018898 -0.00657237208682264 8.23984269608974e-05 4.49961793113268e-05 -8.60129529320937e-06 2.60298424238058e-05 -1.38898483130782e-05 3.55347654403386e-05 4.49961793113268e-05 8.52008170441143e-05 -9.80442325310744e-06 3.06647338460495e-05 3.45586817662141e-06 3.37788899204403e-05 -8.60129529320937e-06 -9.80442325310744e-06 1.17201999854301e-05 -8.91267904695388e-07 2.84024609398911e-06 -3.80208996408374e-06 2.60298424238058e-05 3.06647338460495e-05 -8.91267904695388e-07 8.25726339692714e-05 -4.38845770686739e-05 1.91263133568142e-05 -1.38898483130782e-05 3.45586817662141e-06 2.84024609398911e-06 -4.38845770686739e-05 8.22452316354924e-05 -7.82793999974593e-06 3.55347654403386e-05 3.37788899204403e-05 -3.80208996408374e-06 1.91263133568142e-05 -7.82793999974593e-06 8.95393309562893e-05 1643 1643 0 13 11 1641 1670 0 36 10 0 0 0 0 0 14 33 0 464 0 31 34 0 0 2342 +363 427 0.998982668542103 0.00102457467851899 0.0450841235827746 -0.0147572069236688 -0.00415484002828892 0.997580756356598 0.0693928804081298 -0.00147350990672957 -0.0449039559152429 -0.0695096021692386 0.99657014301525 -0.00774379179132096 9.10536010630607e-05 3.50341030229585e-05 -6.09778033970315e-06 1.38419890995331e-05 -1.84887792999691e-05 5.17143817864609e-05 3.50341030229585e-05 6.9263005451562e-05 -7.39156921255572e-06 2.26142857120415e-05 -7.23841380698261e-06 1.8590494526779e-05 -6.09778033970315e-06 -7.39156921255572e-06 1.16973633899348e-05 7.09549725523628e-07 3.32222653731856e-06 -4.79355846371537e-06 1.38419890995331e-05 2.26142857120415e-05 7.09549725523628e-07 4.68229649323399e-05 -1.4011354150188e-05 1.37501720804262e-05 -1.84887792999691e-05 -7.23841380698261e-06 3.32222653731856e-06 -1.4011354150188e-05 4.8185117982659e-05 -2.36660146465614e-05 5.17143817864609e-05 1.8590494526779e-05 -4.79355846371537e-06 1.37501720804262e-05 -2.36660146465614e-05 0.00010021286207858 1867 1868 0 16 17 1854 1889 0 37 21 0 0 0 0 0 9 30 0 498 0 38 40 0 0 2360 +363 398 0.999048582212317 0.00112620703969596 0.0435965828622321 -0.00688867575632871 -0.00396792070565789 0.997867558959286 0.065150520964221 -0.012366457653756 -0.043430242744352 -0.0652615233835338 0.996922638714172 -0.0069245460068723 0.000105754059906678 5.092064113295e-05 -8.91649883702737e-06 1.76124626174409e-05 -1.84415573899398e-05 4.38939666313897e-05 5.092064113295e-05 9.9040294004869e-05 -6.4580825259224e-06 3.97635790800277e-05 -8.69000973257021e-06 5.50307380848456e-05 -8.91649883702737e-06 -6.4580825259224e-06 1.08875294893505e-05 2.49505385554202e-06 5.22441958271752e-06 -2.71176253339748e-06 1.76124626174409e-05 3.97635790800277e-05 2.49505385554202e-06 5.39118286567943e-05 -1.6173617049778e-05 3.29632228501608e-05 -1.84415573899398e-05 -8.69000973257021e-06 5.22441958271752e-06 -1.6173617049778e-05 5.06956435735361e-05 -2.05496050808819e-05 4.38939666313897e-05 5.50307380848456e-05 -2.71176253339748e-06 3.29632228501608e-05 -2.05496050808819e-05 0.000104492596556501 2213 2208 0 23 38 2162 2201 0 41 9 0 0 0 0 0 9 30 0 338 0 72 57 0 0 2355 +363 408 0.998526736941511 0.000785915756514445 0.0542562249826005 -0.00331210850740881 -0.00416410853891291 0.998056341277955 0.0621787731861803 -0.0117978430797415 -0.0541019021201201 -0.0623130963063621 0.996589214378572 -0.000734376417990667 0.000112990547488011 5.80039221542814e-05 -3.57647094982437e-06 -8.57137892842392e-07 -1.29350755087742e-05 6.08523185565107e-05 5.80039221542814e-05 8.7575113675403e-05 -1.62142593022492e-06 8.94338856858358e-06 -6.71954570201809e-07 5.01388136598484e-05 -3.57647094982437e-06 -1.62142593022492e-06 1.20986214878943e-05 4.21745665904365e-06 6.24206150542523e-06 4.13523342506782e-07 -8.57137892842392e-07 8.94338856858358e-06 4.21745665904365e-06 3.50133396653529e-05 -1.48671160346718e-06 9.94384918777675e-06 -1.29350755087742e-05 -6.71954570201809e-07 6.24206150542523e-06 -1.48671160346718e-06 3.49337584213974e-05 -1.6823908656982e-05 6.08523185565107e-05 5.01388136598484e-05 4.13523342506782e-07 9.94384918777675e-06 -1.6823908656982e-05 0.000119607546254739 1829 1833 0 20 16 1843 1875 0 39 16 0 0 0 0 0 10 30 0 355 0 35 37 0 0 2282 +363 393 0.998586130938588 0.00191774197117096 0.0531230774977711 -0.00601405697744027 -0.00490916562351095 0.998405316612579 0.0562380996533135 -0.00485663567027317 -0.0529305128445127 -0.0564193763300082 0.997003116737631 0.0125528996356573 0.000111668301072022 6.4832064839577e-05 -5.48312691158219e-06 1.97108120567891e-05 -1.63230753576297e-05 6.34151009862058e-05 6.4832064839577e-05 9.05929974163139e-05 -5.82229738206674e-06 3.48487266063311e-05 -1.7704119076525e-05 5.72015456312701e-05 -5.48312691158219e-06 -5.82229738206674e-06 9.93730894293427e-06 1.48424920882363e-06 3.58411168648325e-06 -4.64963225895056e-06 1.97108120567891e-05 3.48487266063311e-05 1.48424920882363e-06 5.72492444389386e-05 -1.40480711079987e-05 2.1761950596282e-05 -1.63230753576297e-05 -1.7704119076525e-05 3.58411168648325e-06 -1.40480711079987e-05 4.13132220333766e-05 -1.18596067679343e-05 6.34151009862058e-05 5.72015456312701e-05 -4.64963225895056e-06 2.1761950596282e-05 -1.18596067679343e-05 0.000107171661935106 2156 2144 0 20 41 2143 2172 0 39 23 0 0 0 0 0 9 30 0 316 0 76 56 0 0 2348 +363 426 0.999166356073654 0.00153290447042635 0.0407951356705871 -0.0186988020843636 -0.00439761404352391 0.997521475952634 0.0702251094979825 0.00514219101607494 -0.0405863755615264 -0.0703459680235049 0.996696639355032 -0.00871518447443059 6.89975193354541e-05 2.94400656976697e-05 -5.77366478743162e-06 1.22340478307772e-05 -5.4491782584568e-06 3.73453581860759e-05 2.94400656976697e-05 5.81392157998298e-05 -7.3094037643981e-06 2.28620580125682e-05 3.4623273634549e-06 2.26347174433535e-05 -5.77366478743162e-06 -7.3094037643981e-06 1.17188418516214e-05 4.25139911450377e-07 9.41287114841173e-07 -3.02448117405842e-06 1.22340478307772e-05 2.28620580125682e-05 4.25139911450377e-07 4.67333243000357e-05 -5.00596427947021e-06 1.30106525772913e-05 -5.4491782584568e-06 3.4623273634549e-06 9.41287114841173e-07 -5.00596427947021e-06 4.49922701056964e-05 -6.73952431360714e-06 3.73453581860759e-05 2.26347174433535e-05 -3.02448117405842e-06 1.30106525772913e-05 -6.73952431360714e-06 8.49502366332251e-05 2105 2105 0 19 17 2121 2148 0 37 15 0 0 0 0 0 11 30 0 495 0 47 50 0 0 2123 +363 418 0.999107575909226 0.000832328738500203 0.0422298353023137 -0.0200436861212532 -0.00377772309838085 0.997559794651948 0.069715026372767 0.00179740187506327 -0.0420687600124063 -0.0698123436280054 0.996672692566714 -0.00785963376271323 6.71358137539056e-05 3.04660520188167e-05 -8.47379905873781e-06 9.26021088590614e-06 -7.57513522732353e-06 3.0599455353767e-05 3.04660520188167e-05 5.20604946632777e-05 -7.48926610924295e-06 1.10968742802205e-05 1.47365350578155e-06 1.3759956956299e-05 -8.47379905873781e-06 -7.48926610924295e-06 1.16483972413004e-05 -5.00180298642366e-07 3.53242471021785e-06 -4.25543854735699e-06 9.26021088590614e-06 1.10968742802205e-05 -5.00180298642366e-07 4.51968767913211e-05 -1.01810879549255e-05 6.01262094949964e-06 -7.57513522732353e-06 1.47365350578155e-06 3.53242471021785e-06 -1.01810879549255e-05 4.64818684361591e-05 -1.17583981563744e-05 3.0599455353767e-05 1.3759956956299e-05 -4.25543854735699e-06 6.01262094949964e-06 -1.17583981563744e-05 7.60226844283873e-05 1994 1996 0 16 13 2013 2043 0 36 12 0 0 0 0 0 11 31 0 473 0 46 48 0 0 2192 +363 392 0.998366317795401 0.0017816436590283 0.0571097297973319 -0.00677004878481357 -0.00505589877799798 0.99834766676806 0.057239620424291 -0.00308740029570496 -0.0569133848861465 -0.0574348500880999 0.996725691760857 0.00887296875650015 0.00011425887554949 7.04707945376404e-05 -5.03350974119845e-06 2.50131188034027e-05 -2.82622361339923e-05 7.94620218727863e-05 7.04707945376404e-05 0.000109870563193465 -7.35331608812219e-06 3.65018876184367e-05 -1.46963221187625e-05 7.19331489438987e-05 -5.03350974119845e-06 -7.35331608812219e-06 1.05067238278274e-05 1.73592710429278e-06 5.24328200458799e-06 -6.74319065707314e-06 2.50131188034027e-05 3.65018876184367e-05 1.73592710429278e-06 5.8601862202404e-05 -2.66412573970688e-05 3.31748643953006e-05 -2.82622361339923e-05 -1.46963221187625e-05 5.24328200458799e-06 -2.66412573970688e-05 6.53026695765997e-05 -2.29842979427705e-05 7.94620218727863e-05 7.19331489438987e-05 -6.74319065707314e-06 3.31748643953006e-05 -2.29842979427705e-05 0.000149969980542059 1761 1751 0 19 43 1726 1767 0 40 24 0 0 0 0 0 9 30 0 304 0 75 55 0 0 2253 +363 420 0.999125983596337 0.00075746748242262 0.0417934820954801 -0.0145187290971526 -0.00357478276293263 0.99772118786555 0.0673769412511002 -0.00211345780306386 -0.0416472067592772 -0.0674674553186159 0.996851870962773 -0.00899073019751104 0.00010566153108756 4.17578411882435e-05 -1.00945924667323e-05 1.39553367320674e-05 1.03886868527722e-06 5.37587520520578e-05 4.17578411882435e-05 6.2301647076521e-05 -8.7757007366211e-06 1.86945713187445e-05 6.49675455520523e-06 3.247472220924e-05 -1.00945924667323e-05 -8.7757007366211e-06 1.25677822090444e-05 6.14251465403776e-07 1.20042915660797e-06 -3.43789144666069e-06 1.39553367320674e-05 1.86945713187445e-05 6.14251465403776e-07 4.75953965896571e-05 -3.65159029448687e-06 1.12403840880015e-05 1.03886868527722e-06 6.49675455520523e-06 1.20042915660797e-06 -3.65159029448687e-06 4.92029601857028e-05 -8.5091110737939e-06 5.37587520520578e-05 3.247472220924e-05 -3.43789144666069e-06 1.12403840880015e-05 -8.5091110737939e-06 9.20883786086081e-05 1768 1768 0 15 11 1791 1818 0 35 11 0 0 0 0 0 9 29 0 481 0 40 42 0 0 2289 +363 407 0.998733145667093 0.00142624475001941 0.0502997969362276 -0.0145685387311134 -0.00433589909911796 0.998319653226766 0.0577846862083041 -0.00849850052158638 -0.0501328607294154 -0.057929576272427 0.997061111701776 -0.00139581552539449 8.49244014421208e-05 5.07233365576393e-05 -4.38425170848857e-06 1.11069308200826e-05 -8.15695736261857e-06 4.53167452463577e-05 5.07233365576393e-05 9.70732614562772e-05 -4.12869987296303e-06 3.91623170303063e-05 -1.46723624833368e-05 4.1433132387439e-05 -4.38425170848857e-06 -4.12869987296303e-06 1.18785878253709e-05 3.87302656265675e-06 5.04040873663816e-06 -1.50735542337208e-06 1.11069308200826e-05 3.91623170303063e-05 3.87302656265675e-06 7.82106971744422e-05 -2.26888034368894e-05 1.94300615527689e-05 -8.15695736261857e-06 -1.46723624833368e-05 5.04040873663816e-06 -2.26888034368894e-05 4.08312693278239e-05 -1.87678104225071e-05 4.53167452463577e-05 4.1433132387439e-05 -1.50735542337208e-06 1.94300615527689e-05 -1.87678104225071e-05 0.000110622293905199 2286 2286 0 18 17 2334 2361 0 38 14 0 0 0 0 0 15 35 0 350 0 62 64 0 0 2274 +363 365 0.999419456312413 0.00232347013586608 0.0339904667624327 -0.0178333974368118 -0.00433534439202547 0.998234592244909 0.0592359994820961 -0.00749660071458756 -0.0337928266530463 -0.0593489707759797 0.997665146496874 0.00381633309585339 4.69199878781161e-05 2.11135988738007e-05 -1.70151588651888e-06 -1.66759662033287e-07 -2.53245653769434e-06 1.55186472171027e-05 2.11135988738007e-05 5.26420881670318e-05 -3.27786440332669e-06 1.47338911982001e-05 -6.03421819259297e-07 2.89786479195789e-05 -1.70151588651888e-06 -3.27786440332669e-06 9.78553850267707e-06 2.97103769625603e-06 4.19891305713013e-06 -7.55138889819914e-07 -1.66759662033287e-07 1.47338911982001e-05 2.97103769625603e-06 4.74665521459943e-05 -1.96961280494396e-05 2.69040269683803e-07 -2.53245653769434e-06 -6.03421819259297e-07 4.19891305713013e-06 -1.96961280494396e-05 4.32095312152091e-05 1.98091063026663e-06 1.55186472171027e-05 2.89786479195789e-05 -7.55138889819914e-07 2.69040269683803e-07 1.98091063026663e-06 6.13774228070278e-05 2736 2730 0 16 39 2706 2739 0 36 15 0 0 0 0 0 8 28 0 477 0 79 62 0 0 2747 +364 396 0.999508422248008 0.00179646114837659 0.0312999454095473 0.0013789641653152 -0.00202289933995214 0.999972002605859 0.00720429612722478 -0.00740214589977109 -0.0312861268545451 -0.00726407129443938 0.999484072676834 0.00971066323687673 0.000146912151129269 5.21919584385855e-05 -5.59059145414711e-06 -8.37218923571872e-06 -2.11739738249212e-05 6.73999007201581e-05 5.21919584385855e-05 7.34481572138422e-05 -3.98472877344675e-06 1.38085290186236e-05 -7.52482382176021e-06 2.15516940142905e-05 -5.59059145414711e-06 -3.98472877344675e-06 9.66462373841409e-06 3.45921335331396e-06 4.69812225728259e-06 -3.67828593636796e-06 -8.37218923571872e-06 1.38085290186236e-05 3.45921335331396e-06 5.68915765698146e-05 -1.53727909569118e-05 8.62325887510042e-06 -2.11739738249212e-05 -7.52482382176021e-06 4.69812225728259e-06 -1.53727909569118e-05 4.67359492234534e-05 -1.97876438177006e-05 6.73999007201581e-05 2.15516940142905e-05 -3.67828593636796e-06 8.62325887510042e-06 -1.97876438177006e-05 0.000103083296152095 2256 2240 0 20 43 2240 2271 0 41 21 0 0 0 0 0 12 40 0 363 0 74 57 0 0 2436 +363 428 0.99912761502061 0.00152833524433705 0.0417333570972657 -0.0152537457998319 -0.00440085134507994 0.997619012515276 0.0688254195445574 0.00322162202337597 -0.0415288021819254 -0.0689490395830627 0.99675543064982 -0.00961525103146441 6.66512604778706e-05 2.74529467995723e-05 -4.38150434394574e-06 1.21421868146238e-05 -8.54344718782863e-06 2.20462447112712e-05 2.74529467995723e-05 5.7857749165562e-05 -5.07605590627015e-06 1.90418435500228e-05 5.26233157092091e-07 1.45236794432787e-05 -4.38150434394574e-06 -5.07605590627015e-06 1.12313194759642e-05 7.24775005905677e-07 2.62003413593547e-06 -2.62070259781029e-06 1.21421868146238e-05 1.90418435500228e-05 7.24775005905677e-07 4.52954529102936e-05 -7.07454814276282e-06 1.35224629927627e-05 -8.54344718782863e-06 5.26233157092091e-07 2.62003413593547e-06 -7.07454814276282e-06 4.92348026319948e-05 -8.19497189574523e-06 2.20462447112712e-05 1.45236794432787e-05 -2.62070259781029e-06 1.35224629927627e-05 -8.19497189574523e-06 7.19437122178129e-05 2113 2118 0 16 17 2107 2143 0 40 15 0 0 0 0 0 11 30 0 489 0 36 39 0 0 2272 +363 419 0.999200699612522 0.000670803903724484 0.0399688868492666 -0.0133163264442797 -0.00331289695814555 0.99780920861578 0.0660742606110379 -0.00868449509901205 -0.0398370004843668 -0.0661538602325926 0.997013881632916 -0.00874654941869622 6.46856769488122e-05 3.53651477466842e-05 -7.90298511684496e-06 9.30001490038544e-06 4.10304842262419e-06 1.6958536571326e-05 3.53651477466842e-05 6.0612760179386e-05 -8.34557849896483e-06 2.05067428594507e-05 3.92668907572286e-07 1.16035235305243e-05 -7.90298511684496e-06 -8.34557849896483e-06 1.2264246668907e-05 5.02714102371629e-07 -1.4159544446684e-07 -1.63434276172005e-06 9.30001490038544e-06 2.05067428594507e-05 5.02714102371629e-07 4.0849059274962e-05 -3.77548857607306e-06 1.16138409352288e-05 4.10304842262419e-06 3.92668907572286e-07 -1.4159544446684e-07 -3.77548857607306e-06 3.57504555023459e-05 -4.80687534190098e-06 1.6958536571326e-05 1.16035235305243e-05 -1.63434276172005e-06 1.16138409352288e-05 -4.80687534190098e-06 7.04123498594475e-05 2264 2266 0 18 14 2260 2295 0 40 22 0 0 0 0 0 7 28 0 453 0 32 35 0 0 2213 +364 394 0.999473877540048 0.00129106477916594 0.0324083518062378 -0.0010074520442082 -0.00175060099865844 0.999898277760556 0.0141551943687862 -0.000429467902204475 -0.0323867798832236 -0.0142044810961407 0.99937446895825 0.00358575674129831 5.69935328182971e-05 2.78473245090173e-05 1.06210680292556e-07 9.99380127251936e-06 -1.3292282746451e-05 9.01123522093026e-06 2.78473245090173e-05 6.6817787626336e-05 -1.68115255371332e-06 7.90832254686153e-06 4.36670490484372e-07 1.03867954443566e-05 1.06210680292556e-07 -1.68115255371332e-06 1.12529160244019e-05 2.37651056093619e-06 5.42871674211072e-06 1.24714429748676e-06 9.99380127251936e-06 7.90832254686153e-06 2.37651056093619e-06 4.53774137702246e-05 -1.37509888024744e-05 8.67223538953395e-06 -1.3292282746451e-05 4.36670490484372e-07 5.42871674211072e-06 -1.37509888024744e-05 4.63621966466257e-05 1.54733517395861e-06 9.01123522093026e-06 1.03867954443566e-05 1.24714429748676e-06 8.67223538953395e-06 1.54733517395861e-06 6.68607610305616e-05 2093 2079 0 21 39 2079 2112 0 41 24 0 0 0 0 0 11 34 0 352 0 66 46 0 0 2399 +363 424 0.999069660601517 0.000828153160783677 0.0431175999785636 -0.0184014394110991 -0.00360347249372002 0.997922275506738 0.0643284309884917 -0.00505353967780602 -0.0429747396915461 -0.0644239568002185 0.996996853324346 -0.00833584762440896 5.84826671480166e-05 3.00032917916877e-05 -4.45777788739877e-06 2.69716181763718e-06 -7.18284846655886e-07 2.11289495192468e-05 3.00032917916877e-05 7.44773646331455e-05 -7.30831018973791e-06 2.74900582310351e-05 7.36797701028641e-06 3.0765681782436e-05 -4.45777788739877e-06 -7.30831018973791e-06 1.15407867489499e-05 7.36683447542808e-07 2.86762510650258e-06 -2.51241899386313e-06 2.69716181763718e-06 2.74900582310351e-05 7.36683447542808e-07 5.31190411015225e-05 -3.3039665489989e-06 1.80109661535066e-05 -7.18284846655886e-07 7.36797701028641e-06 2.86762510650258e-06 -3.3039665489989e-06 4.25352226869423e-05 2.17792309236323e-06 2.11289495192468e-05 3.0765681782436e-05 -2.51241899386313e-06 1.80109661535066e-05 2.17792309236323e-06 8.71031949730215e-05 2113 2115 0 20 15 2165 2194 0 37 12 0 0 0 0 0 13 34 0 486 0 48 51 0 0 2224 +364 412 0.999801622012478 0.00167227056237528 0.0198474213031221 -0.00839065081059727 -0.00208481096582602 0.999781833612458 0.0207831359940791 0.00671597020170577 -0.0198083362363976 -0.0208203911989623 0.999586985272351 -0.00754377865959737 8.91730042072119e-05 4.21163212379288e-05 -4.26825106925023e-06 1.51061798626532e-05 -1.1810970234728e-05 5.42094079559254e-05 4.21163212379288e-05 6.8033079285486e-05 -4.82276597163014e-06 1.61188927009835e-05 -5.54408028171191e-06 3.43350705521388e-05 -4.26825106925023e-06 -4.82276597163014e-06 9.92156737204586e-06 1.08010334118785e-06 4.06857504386802e-06 -2.74365020871295e-06 1.51061798626532e-05 1.61188927009835e-05 1.08010334118785e-06 4.28169050156574e-05 -1.63039357173035e-05 1.84707083043767e-05 -1.1810970234728e-05 -5.54408028171191e-06 4.06857504386802e-06 -1.63039357173035e-05 4.20028958677182e-05 -1.68539647450132e-05 5.42094079559254e-05 3.43350705521388e-05 -2.74365020871295e-06 1.84707083043767e-05 -1.68539647450132e-05 9.77111297872046e-05 1535 1530 0 16 9 1530 1551 0 39 7 0 0 0 0 0 14 40 0 454 0 26 28 0 0 2191 +364 409 0.999751524049025 0.00189164460412938 0.0222106245374405 -0.0173025480508837 -0.00215759502681606 0.999926194709255 0.0119561665248508 0.00619655269030244 -0.022186368457946 -0.012001117238048 0.99968181850011 -0.00170348898674387 9.60828539117788e-05 4.22014696673391e-05 -3.57536750979098e-06 -1.71451422985433e-05 5.37633123067593e-06 4.32500312690465e-05 4.22014696673391e-05 7.73818489163262e-05 -3.26445099663685e-06 1.46216450323009e-05 2.2451238632823e-07 1.47220578484769e-05 -3.57536750979098e-06 -3.26445099663685e-06 1.07202201066509e-05 2.99998453472567e-06 4.70860623449379e-06 -3.28512737389487e-06 -1.71451422985433e-05 1.46216450323009e-05 2.99998453472567e-06 9.82655149597689e-05 -3.65630221295654e-05 1.35493539521394e-07 5.37633123067593e-06 2.2451238632823e-07 4.70860623449379e-06 -3.65630221295654e-05 5.57405808476134e-05 -6.16394389596781e-06 4.32500312690465e-05 1.47220578484769e-05 -3.28512737389487e-06 1.35493539521394e-07 -6.16394389596781e-06 0.000103712288269688 1871 1865 0 15 10 1872 1899 0 40 10 0 0 0 0 0 16 44 0 412 0 19 22 0 0 2194 +364 411 0.999787603440721 0.00160482820320624 0.0205468375351786 -0.00243691807129494 -0.00206126202905248 0.999751148402373 0.022212439464924 0.00264724548127489 -0.0205060772725164 -0.0222500740352368 0.999542112669756 -0.00512124430297569 9.0808278454444e-05 5.85485715508101e-05 -2.49672658965237e-06 1.02773985940874e-05 -1.07880664466532e-05 4.91864339479499e-05 5.85485715508101e-05 9.93156689165488e-05 -4.78711304968281e-06 2.71300359795354e-05 -9.3054332791022e-06 5.346843792698e-05 -2.49672658965237e-06 -4.78711304968281e-06 9.60169537144909e-06 3.36374846267357e-06 4.17283700581597e-06 -5.5899012438863e-07 1.02773985940874e-05 2.71300359795354e-05 3.36374846267357e-06 4.07183033366568e-05 -7.54896562994528e-06 1.98090402596618e-05 -1.07880664466532e-05 -9.3054332791022e-06 4.17283700581597e-06 -7.54896562994528e-06 3.4437237258574e-05 -1.48442982376237e-05 4.91864339479499e-05 5.346843792698e-05 -5.5899012438863e-07 1.98090402596618e-05 -1.48442982376237e-05 9.70241875674601e-05 1894 1893 0 21 11 1890 1907 0 35 9 0 0 0 0 0 9 35 0 428 0 24 27 0 0 2210 +364 390 0.99962237982332 0.00223774291256093 0.027387775795407 0.00496852002880147 -0.00238990565489125 0.999981884559135 0.00552439177844617 -0.0077871682562099 -0.0273749174852257 -0.00558775985689508 0.999609619217652 0.0138420537425963 7.2161188775766e-05 1.85474118448946e-05 -1.04529801864643e-06 8.89932322557213e-06 -6.72449399782448e-06 2.22414244163248e-05 1.85474118448946e-05 4.73837983586125e-05 -3.99081151255343e-06 9.89476671193741e-06 -1.43722825845342e-06 1.23270266914268e-05 -1.04529801864643e-06 -3.99081151255343e-06 1.03419294761863e-05 3.12159763145292e-06 3.81512689540007e-06 -1.41069501612414e-06 8.89932322557213e-06 9.89476671193741e-06 3.12159763145292e-06 2.96211766376403e-05 8.43524049767005e-07 4.50793316312779e-06 -6.72449399782448e-06 -1.43722825845342e-06 3.81512689540007e-06 8.43524049767005e-07 3.25535566666869e-05 1.86597109988407e-06 2.22414244163248e-05 1.23270266914268e-05 -1.41069501612414e-06 4.50793316312779e-06 1.86597109988407e-06 6.93894859945042e-05 2110 2090 0 24 50 2059 2082 0 46 6 0 0 0 0 0 12 40 0 321 0 66 42 0 0 2454 +364 395 0.999716146463838 0.00193951714748466 0.0237458369557575 0.001249411378626 -0.0023114915794628 0.999874899896476 0.0156474139617702 0.000484512574196515 -0.0237125179214034 -0.0156978606901559 0.999595565047975 0.00908779964785649 7.22904513565684e-05 2.45896889460861e-05 -2.94337337876599e-06 6.37385294373389e-06 -1.48154524344014e-05 2.8511324468782e-05 2.45896889460861e-05 7.80784550459383e-05 -4.06612425781804e-06 2.288284846316e-05 -9.11699110168712e-06 2.41415928830736e-05 -2.94337337876599e-06 -4.06612425781804e-06 9.82209541503906e-06 3.94018312178897e-06 3.98023161505024e-06 -3.06666700944942e-06 6.37385294373389e-06 2.288284846316e-05 3.94018312178897e-06 4.89154454150844e-05 -1.08624360013631e-05 1.66136678796213e-05 -1.48154524344014e-05 -9.11699110168712e-06 3.98023161505024e-06 -1.08624360013631e-05 4.19989911494341e-05 -3.33763469908156e-06 2.8511324468782e-05 2.41415928830736e-05 -3.06666700944942e-06 1.66136678796213e-05 -3.33763469908156e-06 7.74702690519145e-05 1691 1676 0 25 46 1666 1689 0 43 27 0 0 0 0 0 12 39 0 349 0 78 63 0 0 2417 +364 410 0.999745031351553 0.0020491530982572 0.0224871798912671 -0.00890343634287344 -0.00239088059940865 0.999881915646257 0.0151801993903344 0.00776432362741309 -0.0224534179545493 -0.0152300930775502 0.999631876386006 -0.00738601510066453 9.94307299965764e-05 5.38293675570277e-05 -9.07290708559398e-07 1.79658798566034e-05 -2.42122753554694e-05 4.12813637421986e-05 5.38293675570277e-05 9.22188463610439e-05 1.47809660493563e-06 3.14224504652972e-05 -1.99487840073413e-05 2.39541583478668e-05 -9.07290708559398e-07 1.47809660493563e-06 1.01899147702282e-05 4.62713755693587e-06 3.59577490666544e-06 7.71431644595077e-07 1.79658798566034e-05 3.14224504652972e-05 4.62713755693587e-06 5.52501240437653e-05 -2.23441904378973e-05 1.18126597502739e-05 -2.42122753554694e-05 -1.99487840073413e-05 3.59577490666544e-06 -2.23441904378973e-05 6.15631989005628e-05 -2.0201141786568e-05 4.12813637421986e-05 2.39541583478668e-05 7.71431644595077e-07 1.18126597502739e-05 -2.0201141786568e-05 0.000104550899695761 1904 1899 0 18 9 1898 1919 0 39 9 0 0 0 0 0 12 39 0 405 0 24 26 0 0 2206 +364 408 0.999820678098682 0.00147180489400329 0.018879762621539 -0.00337841149503523 -0.0018789553600321 0.999765664025154 0.0215658656932086 0.000619409379566831 -0.0188435976672896 -0.0215974726923428 0.999589149601103 -0.00613828571292568 0.00010580204207904 5.023342738473e-05 -7.18558783368738e-06 1.13818935454136e-05 -2.18028471534085e-05 5.58179341048187e-05 5.023342738473e-05 6.71183158169215e-05 -5.46797404821701e-06 1.89820274487351e-05 -1.39454002931596e-05 3.3883499378984e-05 -7.18558783368738e-06 -5.46797404821701e-06 9.95236976245785e-06 3.91132621644444e-06 4.87109474138836e-06 -2.26432337558084e-06 1.13818935454136e-05 1.89820274487351e-05 3.91132621644444e-06 3.9421410019652e-05 -1.34621049576752e-05 1.60496997593234e-05 -2.18028471534085e-05 -1.39454002931596e-05 4.87109474138836e-06 -1.34621049576752e-05 4.59777960229648e-05 -2.12940637249892e-05 5.58179341048187e-05 3.3883499378984e-05 -2.26432337558084e-06 1.60496997593234e-05 -2.12940637249892e-05 9.14197274209346e-05 1926 1925 0 20 15 1922 1939 0 37 13 0 0 0 0 0 15 40 0 394 0 38 43 0 0 2272 +364 366 0.999994456911832 0.0032642417171842 -0.000656408121025241 -0.0151767429480945 -0.00325179589173852 0.99983011198049 0.0181431254352475 0.00168894526532624 0.00071552015207541 -0.0181408903610723 0.999835184481832 -0.00375904987515334 8.15745673815544e-05 1.78071136325778e-05 -6.27667302613632e-06 6.46258601511979e-07 -1.10026596488371e-05 2.54970878520409e-05 1.78071136325778e-05 4.05191625711137e-05 -1.27275477144073e-06 1.05299895415766e-05 -2.41086330652792e-06 1.402972564847e-05 -6.27667302613632e-06 -1.27275477144073e-06 1.07121345157948e-05 4.3981185439996e-06 4.95052372265164e-06 -2.96462053505528e-06 6.46258601511979e-07 1.05299895415766e-05 4.3981185439996e-06 3.74835412572711e-05 -5.14878393473229e-06 3.48413748110803e-06 -1.10026596488371e-05 -2.41086330652792e-06 4.95052372265164e-06 -5.14878393473229e-06 3.44147747525039e-05 -1.1603040703386e-05 2.54970878520409e-05 1.402972564847e-05 -2.96462053505528e-06 3.48413748110803e-06 -1.1603040703386e-05 6.00742391000596e-05 2536 2518 0 26 51 2488 2513 0 50 8 0 0 0 0 0 14 42 0 533 0 108 91 0 0 2625 +364 428 0.999865890265232 0.00210587319479737 0.0162408984420005 -0.00435518277500177 -0.00239858304041651 0.999834665911545 0.0180246398285327 0.00166959294798213 -0.0162002556620001 -0.0180611776924301 0.999705629461417 -0.00556811021078161 8.64633579772053e-05 2.66038126726636e-05 -5.24978436318861e-06 1.42867721463169e-05 -1.97368211564124e-05 4.03682893392786e-05 2.66038126726636e-05 4.7713122579397e-05 -6.92067445621358e-06 8.88420090417391e-06 -7.58103774299566e-07 1.55097213403247e-05 -5.24978436318861e-06 -6.92067445621358e-06 1.12391736043334e-05 -2.60599394181086e-07 1.77220356045651e-06 -3.8945742686711e-06 1.42867721463169e-05 8.88420090417391e-06 -2.60599394181086e-07 3.21894788908365e-05 -4.08892809429023e-06 1.05681443485993e-05 -1.97368211564124e-05 -7.58103774299566e-07 1.77220356045651e-06 -4.08892809429023e-06 3.98818188029062e-05 -1.09691080973668e-05 4.03682893392786e-05 1.55097213403247e-05 -3.8945742686711e-06 1.05681443485993e-05 -1.09691080973668e-05 8.10023297048119e-05 2302 2299 0 17 16 2290 2314 0 41 9 0 0 0 0 0 17 45 0 522 0 42 48 0 0 2245 +364 413 0.999645687110086 0.00173625761249046 0.026560979870996 -0.00979529477951431 -0.00209027803448326 0.999909277955053 0.0133066373341438 0.00512789855014373 -0.0265354664542183 -0.0133574424538136 0.999558626470279 -0.00373607961205877 8.46077436410655e-05 4.08015676594588e-05 -8.49153512674152e-07 -3.56385698733168e-06 -6.94712756824054e-07 2.00982209987318e-05 4.08015676594588e-05 0.000105022146267161 -2.25516896269565e-06 3.65930599616383e-05 -7.89723943701048e-06 1.99748603240195e-05 -8.49153512674152e-07 -2.25516896269565e-06 1.07931820842071e-05 2.55495426969177e-06 4.38798520690615e-06 3.81799462690322e-07 -3.56385698733168e-06 3.65930599616383e-05 2.55495426969177e-06 6.7026249857069e-05 -1.73525386468854e-05 9.8399713018917e-06 -6.94712756824054e-07 -7.89723943701048e-06 4.38798520690615e-06 -1.73525386468854e-05 3.98266228424181e-05 -8.49520909258332e-06 2.00982209987318e-05 1.99748603240195e-05 3.81799462690322e-07 9.8399713018917e-06 -8.49520909258332e-06 7.5512262905226e-05 2041 2039 0 22 11 2030 2056 0 40 4 0 0 0 0 0 15 42 0 494 0 21 26 0 0 2190 +364 393 0.999667010827502 0.00200347953282631 0.0257265142016542 -0.00240905897526723 -0.00245398094669091 0.999843999524643 0.0174915577373629 0.00488863527782609 -0.0256874568752854 -0.0175488656137019 0.999515978799215 0.00778617667881382 5.63983740535269e-05 2.14635505614106e-05 -9.23419779017773e-07 4.75491505989273e-06 -3.30054809017041e-06 3.03140270684824e-05 2.14635505614106e-05 7.01864277767152e-05 -2.6063743411674e-06 1.51507584561104e-05 -3.97139292956611e-08 1.76385301268965e-05 -9.23419779017773e-07 -2.6063743411674e-06 1.05195753888814e-05 1.32481565147385e-06 2.41283303222438e-06 -1.856165759778e-06 4.75491505989273e-06 1.51507584561104e-05 1.32481565147385e-06 4.12352173920002e-05 -9.24642858253498e-06 6.26268640505791e-06 -3.30054809017041e-06 -3.97139292956611e-08 2.41283303222438e-06 -9.24642858253498e-06 4.48907197175186e-05 3.83252977951912e-06 3.03140270684824e-05 1.76385301268965e-05 -1.856165759778e-06 6.26268640505791e-06 3.83252977951912e-06 8.36543029475348e-05 1447 1427 0 18 46 1406 1429 0 42 10 0 0 0 0 0 12 38 0 345 0 74 54 0 0 2322 +364 398 0.999820420189502 0.00212120699417642 0.0188315653352716 0.00413389899088718 -0.00237596523268547 0.999905829046171 0.013516206150531 -0.0128353625078693 -0.0188011212777806 -0.0135585220573055 0.999731306060944 1.11753134326813e-05 0.000105913206802474 4.93889182848002e-05 -6.76984647606038e-06 1.31592511425139e-05 -1.46536240399304e-05 4.13167367233471e-05 4.93889182848002e-05 6.9329151358874e-05 -5.79225834673438e-06 1.87344041398387e-05 -1.06544069475579e-05 3.58737673033646e-05 -6.76984647606038e-06 -5.79225834673438e-06 9.74637423815859e-06 2.73142695092121e-06 5.08709320933323e-06 -2.01172180385933e-06 1.31592511425139e-05 1.87344041398387e-05 2.73142695092121e-06 4.05343003092339e-05 -1.68992761404575e-05 1.83003613032779e-05 -1.46536240399304e-05 -1.06544069475579e-05 5.08709320933323e-06 -1.68992761404575e-05 4.66779428060522e-05 -1.59681965437333e-05 4.13167367233471e-05 3.58737673033646e-05 -2.01172180385933e-06 1.83003613032779e-05 -1.59681965437333e-05 8.15430424532654e-05 2242 2227 0 27 40 2210 2235 0 50 11 0 0 0 0 0 16 44 0 379 0 89 79 0 0 2336 +364 397 0.999779743636335 0.0020528626518935 0.0208865978416084 -0.0079875827741313 -0.00234416932898964 0.999900195032303 0.0139321514677171 -0.00259318756072028 -0.0208559124619769 -0.013978044544744 0.999684772908982 0.000761596462138997 0.000122861379821082 4.77479719763517e-05 -5.49167469188819e-06 4.84294463922284e-06 -2.17579834566941e-05 5.6368594458264e-05 4.77479719763517e-05 7.29734460586115e-05 -4.15997673362749e-06 2.65571599618137e-05 -9.11263841976149e-06 4.30991979567272e-05 -5.49167469188819e-06 -4.15997673362749e-06 9.80425194478498e-06 3.17289374931059e-06 3.70738944130744e-06 -3.09486465333273e-06 4.84294463922284e-06 2.65571599618137e-05 3.17289374931059e-06 6.79488134431616e-05 -2.37356760860809e-05 1.52053605431267e-05 -2.17579834566941e-05 -9.11263841976149e-06 3.70738944130744e-06 -2.37356760860809e-05 5.72615972638389e-05 -2.02671439989541e-05 5.6368594458264e-05 4.30991979567272e-05 -3.09486465333273e-06 1.52053605431267e-05 -2.02671439989541e-05 9.8809289159943e-05 1926 1913 0 20 40 1897 1920 0 45 13 0 0 0 0 0 15 43 0 363 0 78 61 0 0 2365 +364 392 0.999627495247159 0.00216164543310725 0.0272065807280654 -0.000225297623620133 -0.00257676185197743 0.999880663940186 0.0152321428857314 0.00371077762942401 -0.0271704075098149 -0.0152965737194534 0.999513773686084 0.007625867899379 5.82595897051767e-05 2.73315944993356e-05 -1.74769058553847e-06 5.19877885812951e-06 -3.07151623790674e-06 1.68983482447878e-05 2.73315944993356e-05 7.26876351821164e-05 -3.30735851457981e-06 1.4593334725212e-05 3.43098956369579e-06 1.76873165036764e-05 -1.74769058553847e-06 -3.30735851457981e-06 9.2442190089017e-06 2.84044454516055e-06 3.43097124998286e-06 -1.11240430440751e-06 5.19877885812951e-06 1.4593334725212e-05 2.84044454516055e-06 3.68835302057055e-05 -2.41198603930112e-06 4.1242557524145e-06 -3.07151623790674e-06 3.43098956369579e-06 3.43097124998286e-06 -2.41198603930112e-06 3.23134994480923e-05 7.22609609351183e-06 1.68983482447878e-05 1.76873165036764e-05 -1.11240430440751e-06 4.1242557524145e-06 7.22609609351183e-06 7.92216783781361e-05 2056 2035 0 20 49 2024 2044 0 42 19 0 0 0 0 0 12 38 0 339 0 87 72 0 0 2245 +364 415 0.999818479970695 0.00113257997091937 0.0190190528601747 -0.00345708986307551 -0.00157277542977668 0.999730858561265 0.0231459892379738 0.00121725684227437 -0.0189877193611065 -0.0231717004763652 0.999551168680472 -0.00593329888788502 0.000109375566695592 5.33259334036073e-05 -8.13837190124594e-06 2.11368436889562e-05 -2.56749566295107e-05 6.50876365580924e-05 5.33259334036073e-05 9.80963952660683e-05 -6.02946198499658e-06 3.70316697509732e-05 -1.08253323938972e-05 5.74802957831724e-05 -8.13837190124594e-06 -6.02946198499658e-06 1.12015387348762e-05 1.34206022122184e-06 3.74918233822911e-06 -3.42456899721384e-06 2.11368436889562e-05 3.70316697509732e-05 1.34206022122184e-06 4.52847781559725e-05 -7.66966895426065e-06 3.71120137539554e-05 -2.56749566295107e-05 -1.08253323938972e-05 3.74918233822911e-06 -7.66966895426065e-06 3.81383997028455e-05 -2.74093560365851e-05 6.50876365580924e-05 5.74802957831724e-05 -3.42456899721384e-06 3.71120137539554e-05 -2.74093560365851e-05 0.00011884662836026 2123 2125 0 24 14 2112 2134 0 42 11 0 0 0 0 0 11 38 0 467 0 45 49 0 0 2215 +364 417 0.999827964446598 0.00181581262072892 0.0184592614992912 -0.00390078106999071 -0.00216835639358689 0.999815295100486 0.0190964371985851 0.000707080918319134 -0.0184211764315747 -0.0191331781901365 0.999647228651799 -0.00115274069990319 0.000106802377309587 8.09356653583535e-05 -7.06990555325131e-06 2.67346923178366e-05 -1.40038343193147e-05 7.40637321821324e-05 8.09356653583535e-05 0.000106512073620204 -7.9464959215226e-06 3.38501515211681e-05 -1.64952616206423e-05 7.49601377278745e-05 -7.06990555325131e-06 -7.9464959215226e-06 1.07306876876069e-05 3.31971476140215e-07 2.41576926169871e-06 -4.86488866878906e-06 2.67346923178366e-05 3.38501515211681e-05 3.31971476140215e-07 4.09202677453293e-05 -4.95087503545237e-06 3.01507553652198e-05 -1.40038343193147e-05 -1.64952616206423e-05 2.41576926169871e-06 -4.95087503545237e-06 3.51151562327028e-05 -2.33795828248908e-05 7.40637321821324e-05 7.49601377278745e-05 -4.86488866878906e-06 3.01507553652198e-05 -2.33795828248908e-05 0.000123627428628958 2015 2012 0 21 13 2008 2033 0 42 10 0 0 0 0 0 15 42 0 494 0 40 44 0 0 2298 +364 414 0.999928513039838 0.00170731989447711 0.0118344357160158 -0.0191532722906434 -0.0019967519366201 0.99969812356735 0.0244882567289444 0.0112915336697329 -0.0117890538908851 -0.0245101365703459 0.999630067281722 -0.0087142069024459 0.000111944919156616 6.85646486621209e-05 -6.24938922424036e-06 3.68090572457038e-05 -3.29794974886469e-05 7.10017530976828e-05 6.85646486621209e-05 8.99910638353462e-05 -7.26975512224396e-06 4.20714052420233e-05 -2.43553255076011e-05 5.2213391030603e-05 -6.24938922424036e-06 -7.26975512224396e-06 1.14384967590493e-05 1.7915906356554e-06 1.44895753239996e-06 -1.43843072779942e-06 3.68090572457038e-05 4.20714052420233e-05 1.7915906356554e-06 7.61246646952428e-05 -3.42777316879176e-05 3.55526449406006e-05 -3.29794974886469e-05 -2.43553255076011e-05 1.44895753239996e-06 -3.42777316879176e-05 6.23257011858649e-05 -3.39835748520919e-05 7.10017530976828e-05 5.2213391030603e-05 -1.43843072779942e-06 3.55526449406006e-05 -3.39835748520919e-05 0.000110800525404017 1774 1772 0 17 11 1769 1793 0 42 10 0 0 0 0 0 17 42 0 488 0 39 49 0 0 2327 +364 416 0.999894676564935 0.00164921580059033 0.0144192879278818 -0.0147247458278035 -0.00198272702501321 0.999730131523766 0.0231459049729874 0.0112758349853888 -0.0143772240244199 -0.0231720566786241 0.999628106456913 -0.0079737444023146 8.1391066725125e-05 3.70829797864203e-05 -1.13332309475332e-05 1.01706538622729e-05 4.52825954389833e-07 3.70095671120631e-05 3.70829797864203e-05 8.69053509517509e-05 -6.55957174443646e-06 3.47685853922456e-05 8.16017993521704e-07 3.37410142089436e-05 -1.13332309475332e-05 -6.55957174443646e-06 1.3500038407559e-05 2.70585249568165e-06 -2.28261990386046e-06 -3.92324602304362e-06 1.01706538622729e-05 3.47685853922456e-05 2.70585249568165e-06 6.98650067784461e-05 -3.33293179245498e-05 1.67636550117118e-05 4.52825954389833e-07 8.16017993521704e-07 -2.28261990386046e-06 -3.33293179245498e-05 6.76912061911332e-05 -7.09146245205064e-06 3.70095671120631e-05 3.37410142089436e-05 -3.92324602304362e-06 1.67636550117118e-05 -7.09146245205064e-06 9.37702172214344e-05 1797 1794 0 19 12 1789 1816 0 42 11 0 0 0 0 0 14 42 0 506 0 37 42 0 0 2217 +364 391 0.99960084655304 0.00172070546966786 0.0281990557134816 0.00543274312997657 -0.00223788491600216 0.999829688070006 0.0183190263097605 0.00072879747682892 -0.0281627314291088 -0.0183748204486907 0.999434453344455 0.00938745498891299 9.81227285529084e-05 3.76012141238187e-05 -1.60276784153079e-06 1.56002318383823e-05 -2.2095684601609e-05 1.99373529860801e-05 3.76012141238187e-05 6.44220939654049e-05 -3.15494900668342e-06 1.95945685005832e-05 -1.07516044312652e-05 2.25338162842311e-05 -1.60276784153079e-06 -3.15494900668342e-06 9.62315935294509e-06 2.761391532153e-06 4.36052862508075e-06 -1.88223645636459e-06 1.56002318383823e-05 1.95945685005832e-05 2.761391532153e-06 3.65327540465327e-05 -6.49908358431805e-06 2.07380386638858e-05 -2.2095684601609e-05 -1.07516044312652e-05 4.36052862508075e-06 -6.49908358431805e-06 4.18922761615373e-05 -9.98964062631616e-06 1.99373529860801e-05 2.25338162842311e-05 -1.88223645636459e-06 2.07380386638858e-05 -9.98964062631616e-06 8.80510170042445e-05 1977 1958 0 17 52 1951 1972 0 40 30 0 0 0 0 0 11 34 0 309 0 78 62 0 0 2372 +364 423 0.999865006581235 0.0019310915777463 0.0163168471104064 -0.0109392853866044 -0.00230165360583679 0.999739167507487 0.0227222213288041 0.0079325177559487 -0.0162687124562689 -0.0227567097084525 0.999608654003286 -0.00528728759604241 9.0050211573275e-05 3.9951465369897e-05 -8.47936554452385e-06 8.48653368555708e-06 -7.96323505782716e-06 5.08183998582449e-05 3.9951465369897e-05 9.64518773828118e-05 -7.14787775571952e-06 2.9229138467632e-05 -1.21502643903069e-05 5.78512282440991e-05 -8.47936554452385e-06 -7.14787775571952e-06 1.23316146313997e-05 1.06588452794247e-06 4.14726764987631e-06 -2.4777002524791e-06 8.48653368555708e-06 2.9229138467632e-05 1.06588452794247e-06 5.26817733308434e-05 -1.61992144584667e-05 2.05392919298656e-05 -7.96323505782716e-06 -1.21502643903069e-05 4.14726764987631e-06 -1.61992144584667e-05 4.0463292640368e-05 -1.77343186542907e-05 5.08183998582449e-05 5.78512282440991e-05 -2.4777002524791e-06 2.05392919298656e-05 -1.77343186542907e-05 0.000106054857264781 1796 1793 0 16 12 1795 1820 0 42 11 0 0 0 0 0 15 43 0 496 0 27 31 0 0 2203 +364 419 0.999847057281087 0.00160987701525935 0.0174146588352311 -0.00778958262156966 -0.00201533457805866 0.999726717308211 0.0232901079148943 0.0079163529005153 -0.017372405500973 -0.0233216422265817 0.99957706082671 -0.0095134472949559 9.84952954680047e-05 2.37194391650445e-05 -8.45089789352462e-06 1.46722595345188e-05 -2.21401714446868e-05 4.94237284600771e-05 2.37194391650445e-05 5.58881131401586e-05 -4.47838473385661e-06 1.29822140620362e-05 -7.03310504916751e-07 1.74821107697374e-05 -8.45089789352462e-06 -4.47838473385661e-06 1.12119732324182e-05 2.80366726408273e-07 4.11090394344586e-06 -3.94371235179264e-06 1.46722595345188e-05 1.29822140620362e-05 2.80366726408273e-07 3.87209526611263e-05 -6.18134761087711e-06 7.64826674933322e-06 -2.21401714446868e-05 -7.03310504916751e-07 4.11090394344586e-06 -6.18134761087711e-06 4.3434115877132e-05 -1.92114753855271e-05 4.94237284600771e-05 1.74821107697374e-05 -3.94371235179264e-06 7.64826674933322e-06 -1.92114753855271e-05 8.93984975382128e-05 1927 1922 0 19 14 1911 1936 0 42 6 0 0 0 0 0 15 43 0 479 0 42 48 0 0 2189 +364 427 0.999769335656908 0.00176495910156692 0.0214046817195249 -0.000618645935172515 -0.00217211060281967 0.999816871364724 0.0190133024481175 0.00107367809362273 -0.0213672042081665 -0.0190554100933112 0.999590082949257 -0.00354603500680705 0.00011561775403836 4.56781920453676e-05 -7.33887649813011e-06 1.80469672742802e-05 -1.9559009359534e-05 3.96325152655843e-05 4.56781920453676e-05 6.40707565480643e-05 -7.85828892363355e-06 2.32323569494459e-05 -1.12273317748761e-05 2.33934587040173e-05 -7.33887649813011e-06 -7.85828892363355e-06 1.06530722940194e-05 1.43994301731496e-06 2.1154553525671e-06 -1.13477834317394e-06 1.80469672742802e-05 2.32323569494459e-05 1.43994301731496e-06 4.40676543357309e-05 -9.53631771098873e-06 2.11494853569547e-05 -1.9559009359534e-05 -1.12273317748761e-05 2.1154553525671e-06 -9.53631771098873e-06 4.11400358119765e-05 -1.7755391241527e-05 3.96325152655843e-05 2.33934587040173e-05 -1.13477834317394e-06 2.11494853569547e-05 -1.7755391241527e-05 7.39764495223561e-05 2135 2132 0 21 17 2126 2146 0 42 12 0 0 0 0 0 15 42 0 527 0 44 48 0 0 2316 +364 426 0.999824863282681 0.00232477354215806 0.0185698193245416 -0.00427724459449279 -0.00261012696065946 0.999878666170509 0.0153570887323284 0.00108836232964698 -0.0185318644236805 -0.0154028687282938 0.999709618657299 -0.0022823687408555 0.000105334305246086 5.66824818146658e-05 -4.37812567482057e-06 1.68395456595046e-05 -1.59299661421166e-05 4.8952953144823e-05 5.66824818146658e-05 6.97391701710467e-05 -6.71277630890539e-06 1.75843268096971e-05 -9.54122362124004e-06 3.88143862178895e-05 -4.37812567482057e-06 -6.71277630890539e-06 1.0848239016226e-05 1.84871290650797e-06 2.60018269945389e-06 -1.08694999406164e-06 1.68395456595046e-05 1.75843268096971e-05 1.84871290650797e-06 4.15735739017373e-05 -9.8303027052254e-06 1.4028614763478e-05 -1.59299661421166e-05 -9.54122362124004e-06 2.60018269945389e-06 -9.8303027052254e-06 4.90706440267033e-05 -1.62551075569073e-05 4.8952953144823e-05 3.88143862178895e-05 -1.08694999406164e-06 1.4028614763478e-05 -1.62551075569073e-05 0.000101127494858817 1984 1979 0 21 17 1978 2000 0 44 14 0 0 0 0 0 16 44 0 537 0 37 40 0 0 2086 +364 407 0.999745155409258 0.00213779992718472 0.0224734075562859 -0.018219214841563 -0.00246311922847367 0.999892443214118 0.0144580443687709 0.0101298183217506 -0.0224400819826025 -0.014509714496652 0.999642891689747 -0.000871791006714778 0.000106362284734258 5.60541016488366e-05 -2.10246281665584e-06 2.20816383926205e-06 -1.86223122547445e-05 6.16518188613777e-05 5.60541016488366e-05 0.000110474866229391 3.36165179648933e-07 3.43633942585617e-05 -1.75043781781556e-05 5.24933203382123e-05 -2.10246281665584e-06 3.36165179648933e-07 1.02596764547305e-05 2.97833581168824e-06 4.66483721288823e-06 5.75749076138421e-07 2.20816383926205e-06 3.43633942585617e-05 2.97833581168824e-06 7.77875753825643e-05 -2.35094763996291e-05 5.6515635061285e-06 -1.86223122547445e-05 -1.75043781781556e-05 4.66483721288823e-06 -2.35094763996291e-05 4.84043641928974e-05 -1.23580272982924e-05 6.16518188613777e-05 5.24933203382123e-05 5.75749076138421e-07 5.6515635061285e-06 -1.23580272982924e-05 0.000145586481712275 1813 1809 0 20 17 1805 1830 0 40 13 0 0 0 0 0 19 47 0 389 0 27 32 0 0 2260 +364 420 0.99991269685102 0.00161874174800796 0.0131140516726391 -0.00589119548713728 -0.00199081784520785 0.999594396599497 0.0284091346435504 0.00517429995521554 -0.013062745516414 -0.0284327621247291 0.99951035148093 -0.0147248880188463 7.16029307087909e-05 1.52377049703425e-05 -4.78960418320452e-06 -6.57761686111402e-07 7.79399816766069e-06 1.92624113618333e-05 1.52377049703425e-05 9.27915628220117e-05 -4.73054162801301e-06 3.16463210954724e-05 3.35369733962675e-06 3.2053368391226e-05 -4.78960418320452e-06 -4.73054162801301e-06 1.19244220738387e-05 2.54896740779881e-06 2.08444478764332e-06 -1.63672214398107e-06 -6.57761686111402e-07 3.16463210954724e-05 2.54896740779881e-06 4.43952811823079e-05 -9.2762674878456e-07 1.59381216887716e-05 7.79399816766069e-06 3.35369733962675e-06 2.08444478764332e-06 -9.2762674878456e-07 3.81060830745716e-05 -4.54713746828572e-07 1.92624113618333e-05 3.2053368391226e-05 -1.63672214398107e-06 1.59381216887716e-05 -4.54713746828572e-07 9.03783065913833e-05 1796 1794 0 20 11 1793 1814 0 40 11 0 0 0 0 0 11 38 0 505 0 23 25 0 0 2235 +364 424 0.999741184667314 0.00177139097163003 0.0226809579608304 -0.00500714107166708 -0.00196487704314129 0.999961847533531 0.00851132983332009 -0.00374934418393034 -0.022665015733519 -0.00855369226427137 0.999706522640744 -0.0022340691509689 7.23060864400628e-05 4.7478726817494e-05 -4.27269984549744e-06 3.1743076888983e-06 -5.9372815514762e-07 3.20053069136877e-05 4.7478726817494e-05 6.70704133734213e-05 -7.65454450777903e-06 1.28108763789033e-05 -2.36626004524708e-07 2.04105602612817e-05 -4.27269984549744e-06 -7.65454450777903e-06 1.06657240569093e-05 1.38332842054993e-06 3.76406318344573e-06 -4.24541946347464e-07 3.1743076888983e-06 1.28108763789033e-05 1.38332842054993e-06 3.70377164411712e-05 -1.61276466043617e-06 1.4785897564776e-06 -5.9372815514762e-07 -2.36626004524708e-07 3.76406318344573e-06 -1.61276466043617e-06 3.05116640941328e-05 -4.83686336422711e-06 3.20053069136877e-05 2.04105602612817e-05 -4.24541946347464e-07 1.4785897564776e-06 -4.83686336422711e-06 9.42886047404058e-05 2154 2153 0 22 15 2155 2185 0 41 14 0 0 0 0 0 18 46 0 517 0 28 31 0 0 2202 +364 425 0.999608749218552 0.00166430238074845 0.0279209344991858 -0.0105065750376623 -0.00211572897584682 0.999867401718181 0.016146289735843 0.00725333049756632 -0.0278903599227969 -0.016199045617519 0.999479724028686 -0.00285674955907882 6.12580500580894e-05 2.97339196739742e-05 -5.22142698352863e-06 5.07702740268978e-06 1.19708253675215e-06 2.21568294607054e-05 2.97339196739742e-05 0.000105481231822282 -6.52788238562807e-06 2.91901865727802e-05 3.03365569365281e-06 1.39762124891002e-05 -5.22142698352863e-06 -6.52788238562807e-06 1.30317243247411e-05 9.24311774180045e-07 1.48690426509721e-06 -2.68163854648579e-06 5.07702740268978e-06 2.91901865727802e-05 9.24311774180045e-07 5.02549395552965e-05 -1.46229596629037e-05 1.18420980394483e-05 1.19708253675215e-06 3.03365569365281e-06 1.48690426509721e-06 -1.46229596629037e-05 4.4274730675538e-05 -1.59835137190241e-05 2.21568294607054e-05 1.39762124891002e-05 -2.68163854648579e-06 1.18420980394483e-05 -1.59835137190241e-05 9.93443148677033e-05 1627 1622 0 20 16 1623 1653 0 39 15 0 0 0 0 0 13 40 0 504 0 26 29 0 0 2007 +364 421 0.999855799391064 0.00213341252597 0.01684722455035 -0.0045417573241556 -0.00239604138421135 0.999875689938818 0.0155840833884345 -0.000616622387952323 -0.0168118829921288 -0.0156222028013519 0.999736619000171 -0.00380345287521413 9.53365054448775e-05 5.18415044648242e-05 -7.26127115205579e-06 7.74446639080025e-06 -3.63616058903999e-06 4.808711818139e-05 5.18415044648242e-05 7.36478856855149e-05 -9.73519139783523e-06 2.53768649858555e-05 -2.21721946746279e-06 3.76152218997762e-05 -7.26127115205579e-06 -9.73519139783523e-06 1.16123504154241e-05 5.68582618582716e-07 2.79685553546658e-06 -4.04489107882711e-06 7.74446639080025e-06 2.53768649858555e-05 5.68582618582716e-07 5.06456922885975e-05 -3.31475362588315e-06 8.87498845052575e-06 -3.63616058903999e-06 -2.21721946746279e-06 2.79685553546658e-06 -3.31475362588315e-06 3.17898441773307e-05 -4.3460248992818e-06 4.808711818139e-05 3.76152218997762e-05 -4.04489107882711e-06 8.87498845052575e-06 -4.3460248992818e-06 8.26238587026599e-05 2052 2049 0 19 14 2046 2067 0 41 10 0 0 0 0 0 12 40 0 517 0 32 37 0 0 2287 +365 369 0.999999521516595 0.000977960120290834 2.36766754802947e-05 -0.00866138959523528 -0.000977950778828639 0.999999445212563 -0.000391390904231171 0.00778543140914427 -2.40594270405553e-05 0.000391367562333892 0.999999923126285 -0.00459988301738871 3.56856977517079e-05 1.93006392174809e-05 -7.44183158792725e-06 6.68855723239593e-06 3.35313039007598e-06 2.05310720560325e-05 1.93006392174809e-05 2.97942273274098e-05 -8.08315169087587e-06 5.37444999592764e-06 4.14035430942646e-06 1.15357955758649e-05 -7.44183158792725e-06 -8.08315169087587e-06 1.52958656736368e-05 1.49730139178596e-06 -2.92176991996178e-06 -2.59829066783233e-06 6.68855723239593e-06 5.37444999592764e-06 1.49730139178596e-06 3.76654201252412e-05 -1.81370016170691e-06 6.95687435835994e-06 3.35313039007598e-06 4.14035430942646e-06 -2.92176991996178e-06 -1.81370016170691e-06 4.53312383294136e-05 2.94208533184568e-07 2.05310720560325e-05 1.15357955758649e-05 -2.59829066783233e-06 6.95687435835994e-06 2.94208533184568e-07 4.4099852443671e-05 2643 2621 0 13 53 2619 2650 0 56 28 0 0 0 0 0 18 50 0 635 0 55 31 0 0 2374 +365 398 0.999999237261607 0.000244817712031286 -0.00121059509819041 -0.00127220011128283 -0.00024377490401795 0.999999599218355 0.000861473694158558 -0.000505330091468088 0.00121080551702489 -0.000861177924375631 0.999998896160682 -0.0120425268128799 3.00749183117405e-05 1.43169313436344e-05 -4.35319688256025e-06 3.97799915204448e-06 -6.70180935480833e-07 1.06424159294608e-05 1.43169313436344e-05 2.50024841895942e-05 -4.76232188958651e-06 4.1965464499755e-06 5.05764019425642e-06 9.46821350156178e-06 -4.35319688256025e-06 -4.76232188958651e-06 1.10077021256915e-05 3.76050796735266e-06 1.39201063210828e-06 -1.60666808600239e-06 3.97799915204448e-06 4.1965464499755e-06 3.76050796735266e-06 3.31035991314287e-05 -1.10367029533935e-05 -1.75596928649385e-06 -6.70180935480833e-07 5.05764019425642e-06 1.39201063210828e-06 -1.10367029533935e-05 5.03857064922223e-05 3.74345722562473e-06 1.06424159294608e-05 9.46821350156178e-06 -1.60666808600239e-06 -1.75596928649385e-06 3.74345722562473e-06 4.16152899917309e-05 1947 1931 0 16 41 1931 1979 0 46 24 0 0 0 0 0 16 46 0 477 0 45 29 0 0 2358 +364 418 0.999850183936241 0.00188692857372377 0.0172060798331199 -0.00457997917692175 -0.00220076724794834 0.999831227429142 0.0182393333500962 -0.0010160606075077 -0.0171687595995281 -0.0182744673819305 0.999685589340829 -0.00449780806823711 0.000155904005250348 7.72156932152814e-05 -5.8298459427765e-06 2.52053641009915e-05 -4.57010156107032e-05 9.74709685740073e-05 7.72156932152814e-05 7.20392700585252e-05 -7.30446791948785e-06 2.39466659702776e-05 -2.50508033978245e-05 5.78717889038722e-05 -5.8298459427765e-06 -7.30446791948785e-06 9.96664210649722e-06 7.05703703047428e-07 6.49085040488072e-06 -4.40787401071035e-06 2.52053641009915e-05 2.39466659702776e-05 7.05703703047428e-07 4.01309023935463e-05 -1.24263786079922e-05 2.68799677747033e-05 -4.57010156107032e-05 -2.50508033978245e-05 6.49085040488072e-06 -1.24263786079922e-05 4.94602439399859e-05 -4.00999838808545e-05 9.74709685740073e-05 5.78717889038722e-05 -4.40787401071035e-06 2.68799677747033e-05 -4.00999838808545e-05 0.000115695250517776 2072 2071 0 22 13 2067 2091 0 43 12 0 0 0 0 0 12 39 0 513 0 32 35 0 0 2167 +365 406 0.999997974355721 0.00026861212509163 0.00199477617323272 -0.00569943228801928 -0.000272952754104113 0.999997595160284 0.00217604467842099 0.00927364296989049 -0.00199418686413039 -0.00217658475017885 0.999995642839296 -0.0061366995308646 2.71995283210175e-05 1.73326681637231e-05 -1.25147279264255e-06 3.26244096439573e-06 -1.82702058017346e-07 1.62162086656399e-05 1.73326681637231e-05 2.40077390293296e-05 -2.16677821626032e-06 4.45040109763496e-06 -1.25588994028687e-06 1.42574457187794e-05 -1.25147279264255e-06 -2.16677821626032e-06 1.08025811753618e-05 3.13462935512996e-06 2.67739066063295e-06 -9.9459015659878e-07 3.26244096439573e-06 4.45040109763496e-06 3.13462935512996e-06 3.19253094781535e-05 -7.03219481579851e-06 7.80901706432646e-06 -1.82702058017346e-07 -1.25588994028687e-06 2.67739066063295e-06 -7.03219481579851e-06 2.95341681959063e-05 -2.09057974474534e-06 1.62162086656399e-05 1.42574457187794e-05 -9.9459015659878e-07 7.80901706432646e-06 -2.09057974474534e-06 5.17580639781553e-05 2579 2583 0 15 17 2581 2627 0 48 14 0 0 0 0 0 22 52 0 469 0 18 19 0 0 2361 +365 399 0.999995343278491 -0.000682977325021832 0.00297438452556584 0.00515131960648041 0.000678719974394818 0.999998744195563 0.00143211259820281 -0.00837443575044179 -0.00297535889075201 -0.00143008715506424 0.999994551030254 -0.0118264219891198 5.08463543074807e-05 2.78582603055861e-05 -4.93393567786184e-06 1.62923980690081e-06 1.55999709507755e-06 2.93790515189914e-05 2.78582603055861e-05 5.12592638066241e-05 -5.23584257545243e-06 1.57793757876114e-05 3.70288122464338e-06 3.60440420854729e-05 -4.93393567786184e-06 -5.23584257545243e-06 1.15647322864158e-05 3.67499383399548e-06 1.13767412619406e-06 -1.34611598067229e-06 1.62923980690081e-06 1.57793757876114e-05 3.67499383399548e-06 5.0806200843163e-05 -1.58365883158129e-05 5.64507532143773e-06 1.55999709507755e-06 3.70288122464338e-06 1.13767412619406e-06 -1.58365883158129e-05 5.28489511036247e-05 -4.38186749955357e-06 2.93790515189914e-05 3.60440420854729e-05 -1.34611598067229e-06 5.64507532143773e-06 -4.38186749955357e-06 7.7369610135932e-05 2111 2092 0 18 40 2094 2120 0 46 28 0 0 0 0 0 15 47 0 484 0 51 35 0 0 2417 +365 368 0.999997852434552 0.00035980083181469 0.00204099721836264 -0.012431212868148 -0.000359835038360046 0.999999935125013 1.63925349014026e-05 0.0100387407872373 -0.00204099118790528 -1.71269220097233e-05 0.99999791702865 -0.00595903384222514 6.50217071378586e-05 5.95222280982887e-05 -1.85646714578295e-06 1.14794870857179e-05 -5.39670840274188e-06 5.17670595582018e-05 5.95222280982887e-05 0.000150815414560111 5.1959008400357e-06 4.34699528706825e-05 -7.39387120870594e-06 8.07659443281191e-05 -1.85646714578295e-06 5.1959008400357e-06 1.08903483401501e-05 5.18962941454564e-06 5.84576528124129e-06 -2.16376868636033e-06 1.14794870857179e-05 4.34699528706825e-05 5.18962941454564e-06 5.05375973689887e-05 -1.40522736252251e-05 3.56878372272347e-05 -5.39670840274188e-06 -7.39387120870594e-06 5.84576528124129e-06 -1.40522736252251e-05 3.75624295970205e-05 -2.13559244936006e-05 5.17670595582018e-05 8.07659443281191e-05 -2.16376868636033e-06 3.56878372272347e-05 -2.13559244936006e-05 0.000107009219761391 2375 2356 0 13 43 2335 2359 0 42 4 0 0 0 0 0 22 53 0 515 0 80 59 0 0 2825 +365 367 0.999989612845194 -0.000315984083313356 0.00454690617645055 -0.00567267968501282 0.000304861870109642 0.999996960621388 0.00244659093990186 0.00541906256096736 -0.00454766544047656 -0.00244517934846286 0.999986669829651 -0.00466940584484428 2.7764525112477e-05 7.72862046480078e-06 9.86898388790909e-07 -2.56106060482865e-06 -1.35239018850182e-06 6.97366279668857e-06 7.72862046480078e-06 3.28548225036423e-05 2.53832077731436e-06 1.10664555820574e-06 3.97555384060344e-06 7.30485954337226e-06 9.86898388790909e-07 2.53832077731436e-06 1.17575507419846e-05 3.53382107860561e-06 3.27236368398143e-06 -4.35535903939026e-07 -2.56106060482865e-06 1.10664555820574e-06 3.53382107860561e-06 2.57773164567e-05 1.67604842099515e-06 7.06641585301492e-07 -1.35239018850182e-06 3.97555384060344e-06 3.27236368398143e-06 1.67604842099515e-06 2.85274555340273e-05 -3.22877631962512e-07 6.97366279668857e-06 7.30485954337226e-06 -4.35535903939026e-07 7.06641585301492e-07 -3.22877631962512e-07 3.85580256176763e-05 2968 2941 0 15 61 2950 2992 0 39 36 0 0 0 0 0 20 48 0 595 0 57 31 0 0 2816 +365 428 0.999998800106236 0.000400167835941986 0.00149654662196262 -0.00496201444394223 -0.000403254505752768 0.999997791127507 0.00206279565409853 0.00953841373374461 -0.00149571785180906 -0.00206339666813127 0.999996752605876 -0.00955231295347949 3.03882157978928e-05 9.94011791915563e-06 -8.33393005524607e-06 1.84973416114787e-06 3.13286470919112e-06 1.4712910973358e-05 9.94011791915563e-06 2.02428000129681e-05 -8.56409293201432e-06 4.522985821251e-06 1.30549657941094e-06 4.85516588212961e-06 -8.33393005524607e-06 -8.56409293201432e-06 1.43523599520308e-05 1.36922185693379e-06 1.83234107923737e-06 -3.49644047159514e-06 1.84973416114787e-06 4.522985821251e-06 1.36922185693379e-06 3.4926817513999e-05 -2.43948405052071e-07 5.70638610737668e-06 3.13286470919112e-06 1.30549657941094e-06 1.83234107923737e-06 -2.43948405052071e-07 3.48841566913711e-05 5.7738561874991e-07 1.4712910973358e-05 4.85516588212961e-06 -3.49644047159514e-06 5.70638610737668e-06 5.7738561874991e-07 5.05626444689575e-05 1919 1923 0 16 16 1914 1965 0 48 11 0 0 0 0 0 20 52 0 650 0 13 15 0 0 2339 +365 407 0.999999132160839 0.000659775489915199 0.00114033936691918 -0.0146775054073274 -0.000658981239111183 0.999999540148905 -0.000696739337699303 0.0110544867868926 -0.00114079853407074 0.000695987270792601 0.999999107089813 -0.00773385775703827 4.09223911545495e-05 2.97352688841076e-05 -1.23123550954699e-06 4.24271865792377e-06 -2.22234156296151e-06 2.84622385045619e-05 2.97352688841076e-05 5.00857849399686e-05 -3.401910647984e-06 1.59988687062822e-05 -3.65423719074464e-06 2.32198076326051e-05 -1.23123550954699e-06 -3.401910647984e-06 1.10548703572722e-05 4.53854088412832e-06 3.51584013509962e-06 -2.11994949685437e-06 4.24271865792377e-06 1.59988687062822e-05 4.53854088412832e-06 5.92632394418984e-05 -1.18921047746974e-05 9.91160190085166e-06 -2.22234156296151e-06 -3.65423719074464e-06 3.51584013509962e-06 -1.18921047746974e-05 4.28452969791496e-05 -1.18397081727914e-05 2.84622385045619e-05 2.32198076326051e-05 -2.11994949685437e-06 9.91160190085166e-06 -1.18397081727914e-05 8.53939148319038e-05 1958 1956 0 15 17 1949 1968 0 34 9 0 0 0 0 0 19 47 0 478 0 44 46 0 0 2350 +365 391 0.999999002026833 4.08923783344365e-05 0.0014121873642003 -0.00338635005493975 -4.16807574537763e-05 0.999999843313635 0.000558243155494371 0.00775650150077115 -0.00141216431503948 -0.000558301459421687 0.999998847045049 0.00170376279494119 2.89928221619169e-05 6.64688546334346e-06 6.49115008369364e-07 -5.61819586183974e-08 -3.98530800877392e-06 6.24341061705532e-06 6.64688546334346e-06 2.68721655672759e-05 -1.69600861271966e-06 8.2919063514208e-07 6.18450249754984e-06 7.38459120821196e-06 6.49115008369364e-07 -1.69600861271966e-06 9.66173251240275e-06 2.96650974192544e-06 2.95827436207917e-06 -1.80036462097212e-06 -5.61819586183974e-08 8.2919063514208e-07 2.96650974192544e-06 4.52499475119077e-05 -1.18196558535166e-05 8.20522185186231e-07 -3.98530800877392e-06 6.18450249754984e-06 2.95827436207917e-06 -1.18196558535166e-05 4.301341860607e-05 1.12649762919932e-05 6.24341061705532e-06 7.38459120821196e-06 -1.80036462097212e-06 8.20522185186231e-07 1.12649762919932e-05 4.96578401117388e-05 2199 2176 0 12 51 2176 2203 0 45 24 0 0 0 0 0 18 50 0 420 0 94 78 0 0 2446 +365 408 0.999999590926283 0.000522187254616189 -0.000738557877242799 -0.00726470070083125 -0.000521660002537165 0.999999609104016 0.000713906616888674 0.0104501823851937 0.000738930381479816 -0.000713521048744125 0.999999472434663 -0.00560236206778983 2.66298449779299e-05 1.32583104477911e-05 -2.17334068326459e-06 -1.28364309446246e-07 -5.1155671465102e-07 1.20541129762156e-05 1.32583104477911e-05 3.35271106324376e-05 -3.21572321800328e-06 8.82723528642516e-06 -3.90913664680917e-07 1.24436009079653e-05 -2.17334068326459e-06 -3.21572321800328e-06 1.08213495090523e-05 4.1609627245444e-06 2.85680405868922e-06 -2.38543617575454e-07 -1.28364309446246e-07 8.82723528642516e-06 4.1609627245444e-06 3.5138453357014e-05 -9.01790372501e-06 6.32578344514718e-06 -5.1155671465102e-07 -3.90913664680917e-07 2.85680405868922e-06 -9.01790372501e-06 3.45903932011527e-05 -7.83252505186238e-07 1.20541129762156e-05 1.24436009079653e-05 -2.38543617575454e-07 6.32578344514718e-06 -7.83252505186238e-07 5.7691766242549e-05 2153 2152 0 12 15 2152 2181 0 37 10 0 0 0 0 0 25 56 0 493 0 56 58 0 0 2367 +365 400 0.999999889531435 6.42046066142001e-05 0.000465633853345244 0.00301736592688863 -6.38551964072742e-05 0.999999716431424 -0.000750372963646785 -0.00792942050793245 -0.00046568189870706 0.000750343147613001 0.999999610062689 -0.00831125412251727 3.39356210261918e-05 1.79779213545086e-05 -2.98157869984611e-06 1.49279753648424e-07 8.82797451562315e-07 2.25276674091074e-05 1.79779213545086e-05 2.99170301178702e-05 -6.06631370318126e-06 6.68105129968264e-06 1.75903594555281e-06 2.30651188862444e-05 -2.98157869984611e-06 -6.06631370318126e-06 1.14874989638173e-05 4.0110121518979e-06 3.3721228415043e-06 5.98019374528751e-08 1.49279753648424e-07 6.68105129968264e-06 4.0110121518979e-06 4.47240982752611e-05 -1.4280807833304e-05 1.19158444197151e-05 8.82797451562315e-07 1.75903594555281e-06 3.3721228415043e-06 -1.4280807833304e-05 4.17561268993466e-05 2.28003180986719e-06 2.25276674091074e-05 2.30651188862444e-05 5.98019374528751e-08 1.19158444197151e-05 2.28003180986719e-06 7.28703143993401e-05 2525 2510 0 18 40 2502 2549 0 47 17 0 0 0 0 0 19 52 0 498 0 48 32 0 0 2414 +365 429 0.999976812874537 -0.00680582478087982 0.000233371666483219 -0.00379823656458512 0.00680446721211858 0.999962301939984 0.00539387846056543 0.00793857673246492 -0.0002700726605161 -0.00539216542217601 0.999985425700204 -0.0122585238567522 4.37221454921275e-05 2.19608500164343e-05 -6.44609307274751e-06 7.65031895300856e-06 3.59685745488864e-06 2.07648626289207e-05 2.19608500164343e-05 3.50259766840275e-05 -7.76322431078086e-06 1.12787238633388e-05 4.52096299425462e-06 8.678219322932e-06 -6.44609307274751e-06 -7.76322431078086e-06 1.42411241854674e-05 3.5609264981856e-07 2.2906373978724e-07 -3.20428622559284e-06 7.65031895300856e-06 1.12787238633388e-05 3.5609264981856e-07 4.09508362267841e-05 -8.94188624327533e-06 -2.09051017836612e-06 3.59685745488864e-06 4.52096299425462e-06 2.2906373978724e-07 -8.94188624327533e-06 4.53979382835976e-05 4.68181155957173e-06 2.07648626289207e-05 8.678219322932e-06 -3.20428622559284e-06 -2.09051017836612e-06 4.68181155957173e-06 5.974119964438e-05 2081 2078 0 7 24 2084 2105 0 39 23 0 0 0 0 0 29 60 0 606 0 13 13 0 0 2443 +365 397 0.999997150201388 0.00015721781514708 0.00238219891295 -0.00195438716577521 -0.000154860892774202 0.999999498412673 -0.000989541563451111 0.000440878166402481 -0.00238235329163182 0.000989169834006512 0.999996672962382 -0.00554845511591771 3.12897996462091e-05 2.08881660747748e-05 -1.82354026532897e-06 -2.31392712217618e-07 9.46868544588839e-07 2.14167439048233e-05 2.08881660747748e-05 3.61387792472842e-05 -3.03184983161989e-06 1.40708672175955e-05 -4.9390941879943e-06 2.36074354793413e-05 -1.82354026532897e-06 -3.03184983161989e-06 1.15553175258305e-05 5.0040185621657e-06 4.00357971997445e-07 1.97490611878462e-06 -2.31392712217618e-07 1.40708672175955e-05 5.0040185621657e-06 6.24243118741597e-05 -3.34159563020166e-05 8.65996693615824e-06 9.46868544588839e-07 -4.9390941879943e-06 4.00357971997445e-07 -3.34159563020166e-05 5.93351961094292e-05 -1.01720916596229e-06 2.14167439048233e-05 2.36074354793413e-05 1.97490611878462e-06 8.65996693615824e-06 -1.01720916596229e-06 5.90432052663228e-05 2084 2075 0 17 41 2070 2102 0 48 25 0 0 0 0 0 21 51 0 464 0 46 28 0 0 2478 +365 427 0.999999751102895 3.78973323472495e-05 0.000704526749015323 -0.00450562502158443 -3.95059521587234e-05 0.999997392283009 0.00228338924863053 0.00763957160824935 -0.000704438377447715 -0.0022834165133016 0.999997144883724 -0.0105882653624702 4.3915958592316e-05 2.11718032645388e-05 -7.253052207012e-06 5.20583061912493e-06 7.19795304172405e-06 2.83888906088925e-05 2.11718032645388e-05 3.18731219602036e-05 -1.00759342899768e-05 8.26846852453589e-06 9.54856960906285e-06 1.67276462041636e-05 -7.253052207012e-06 -1.00759342899768e-05 1.53468615840806e-05 -1.10795078838731e-06 -4.72220171161941e-06 -3.19353893984133e-06 5.20583061912493e-06 8.26846852453589e-06 -1.10795078838731e-06 3.83923300790223e-05 -5.43568643059341e-08 2.41770233846082e-06 7.19795304172405e-06 9.54856960906285e-06 -4.72220171161941e-06 -5.43568643059341e-08 4.37477704276264e-05 6.83835108298693e-06 2.83888906088925e-05 1.67276462041636e-05 -3.19353893984133e-06 2.41770233846082e-06 6.83835108298693e-06 6.78661384644108e-05 2449 2448 0 15 17 2447 2489 0 39 14 0 0 0 0 0 18 48 0 630 0 16 16 0 0 2322 +365 405 0.999998731050179 0.000878941562171735 -0.00132866841699052 -0.00486364154605167 -0.000879132171547187 0.999999603355641 -0.00014288171949071 0.0100444920161787 0.00132854230529995 0.000144049613331672 0.999999107112127 -0.00547507400493468 2.54124837075424e-05 1.08778242480635e-05 -1.25669911340761e-06 -1.09050830495116e-06 -3.1899727870892e-07 1.10839014513417e-05 1.08778242480635e-05 2.6184755449899e-05 -3.13432128244214e-06 2.25144279353728e-06 2.89424329299228e-06 7.07222527316208e-06 -1.25669911340761e-06 -3.13432128244214e-06 1.05366368288955e-05 3.42998802562407e-06 1.69148951276058e-06 -1.60781764504851e-06 -1.09050830495116e-06 2.25144279353728e-06 3.42998802562407e-06 3.00285859960968e-05 6.66015908854982e-07 -7.82902533142885e-07 -3.1899727870892e-07 2.89424329299228e-06 1.69148951276058e-06 6.66015908854982e-07 3.15171015654195e-05 7.46744424233194e-06 1.10839014513417e-05 7.07222527316208e-06 -1.60781764504851e-06 -7.82902533142885e-07 7.46744424233194e-06 4.6835868295068e-05 2153 2156 0 19 19 2148 2180 0 44 9 0 0 0 0 0 21 52 0 459 0 59 62 0 0 2339 +365 402 0.999999511103236 0.000448428963963844 0.000881308545725905 -0.0045203730031085 -0.000449016012546793 0.999999677397456 0.000666025227651822 0.00833433249080471 -0.000881009596410717 -0.000666420623683269 0.999999389852636 -0.00643958726536137 3.10214116238132e-05 1.9868450427446e-05 -9.90307336102893e-07 2.95557312015243e-06 3.59122019704047e-07 2.37073190523031e-05 1.9868450427446e-05 2.86972796706537e-05 -3.0167788275923e-06 8.04747892810824e-06 -1.60372304852219e-06 1.62916164779068e-05 -9.90307336102893e-07 -3.0167788275923e-06 1.11739251129369e-05 5.57098544282524e-06 2.67668682091689e-06 2.77667657105023e-07 2.95557312015243e-06 8.04747892810824e-06 5.57098544282524e-06 3.62720591670656e-05 -1.34644515743979e-05 7.27666521602478e-06 3.59122019704047e-07 -1.60372304852219e-06 2.67668682091689e-06 -1.34644515743979e-05 4.20193560397693e-05 -3.79707977701432e-06 2.37073190523031e-05 1.62916164779068e-05 2.77667657105023e-07 7.27666521602478e-06 -3.79707977701432e-06 6.32332321448779e-05 2505 2494 0 19 39 2491 2536 0 39 27 0 0 0 0 0 19 47 0 472 0 33 24 0 0 2365 +365 409 0.999999990933998 6.51737800113338e-05 0.000117832009249978 -0.0118047351415535 -6.51196768378237e-05 0.999999892492984 -0.000459100694208075 0.00878622735768741 -0.000117861917909858 0.000459093016863504 0.999999887671079 -0.00801908876847909 4.19310474362783e-05 2.79739151335554e-05 -8.44439864000657e-07 2.05536292220492e-06 -3.56935338155096e-06 2.6445098723794e-05 2.79739151335554e-05 3.74836839091502e-05 -1.56323172136304e-06 4.78569750479649e-06 -1.96796417660976e-06 1.80985229368655e-05 -8.44439864000657e-07 -1.56323172136304e-06 1.03205566942253e-05 4.88789924835884e-06 3.58033205504553e-06 -1.30059021120245e-06 2.05536292220492e-06 4.78569750479649e-06 4.88789924835884e-06 4.65471083071629e-05 -7.30002750917783e-06 1.84227695786691e-06 -3.56935338155096e-06 -1.96796417660976e-06 3.58033205504553e-06 -7.30002750917783e-06 3.78410249648036e-05 -4.24675485482568e-06 2.6445098723794e-05 1.80985229368655e-05 -1.30059021120245e-06 1.84227695786691e-06 -4.24675485482568e-06 6.52671358581784e-05 2030 2025 0 18 10 2016 2044 0 42 2 0 0 0 0 0 24 55 0 502 0 39 40 0 0 2318 +365 401 0.999999300874013 -3.71520963860402e-05 0.00118189306089493 -0.00417156248641911 3.50391560820191e-05 0.999998401395987 0.00178772976948986 -0.0032234809098256 -0.00118195758942465 -0.00178768710710609 0.999997703572895 -0.00821928177959423 3.81775838929088e-05 1.77763467350573e-05 -4.21598095479157e-06 2.49927217602403e-06 4.65095980570173e-06 1.52879524128621e-05 1.77763467350573e-05 3.20169611744679e-05 -4.4914594630398e-06 8.81131536860171e-06 5.5064604709254e-06 1.14672498185811e-05 -4.21598095479157e-06 -4.4914594630398e-06 1.19585463180309e-05 2.50136574895674e-06 4.26135839928951e-06 -2.77939690541272e-06 2.49927217602403e-06 8.81131536860171e-06 2.50136574895674e-06 4.45284176574132e-05 -9.99382851053843e-06 4.94237258956065e-06 4.65095980570173e-06 5.5064604709254e-06 4.26135839928951e-06 -9.99382851053843e-06 4.73817126414759e-05 4.40545278597143e-06 1.52879524128621e-05 1.14672498185811e-05 -2.77939690541272e-06 4.94237258956065e-06 4.40545278597143e-06 5.66192216492098e-05 1963 1949 0 17 37 1935 1962 0 43 11 0 0 0 0 0 18 47 0 508 0 69 56 0 0 2501 +365 421 0.999997614990607 0.000669692860427665 0.00207882769124223 -0.00305108748430556 -0.000672339418293305 0.99999896414318 0.00127266345684868 0.00491199844899596 -0.0020779732442436 -0.00127405809933505 0.999997029397166 -0.00962092737901327 3.70678852698447e-05 1.68130083604627e-05 -5.19388524936644e-06 8.67856062587844e-06 2.6805575615891e-06 1.64380279719272e-05 1.68130083604627e-05 2.87031361837445e-05 -7.06084064709601e-06 1.0400360858516e-05 4.52261245411432e-06 1.35531368069093e-05 -5.19388524936644e-06 -7.06084064709601e-06 1.32081393482509e-05 2.21439080095847e-07 -1.52056023217152e-06 -2.92499903395582e-06 8.67856062587844e-06 1.0400360858516e-05 2.21439080095847e-07 4.74224447078769e-05 -5.89857414196334e-06 3.9993420924817e-06 2.6805575615891e-06 4.52261245411432e-06 -1.52056023217152e-06 -5.89857414196334e-06 4.51917546182158e-05 -9.48080489674749e-07 1.64380279719272e-05 1.35531368069093e-05 -2.92499903395582e-06 3.9993420924817e-06 -9.48080489674749e-07 4.72800098899894e-05 1505 1508 0 18 14 1501 1537 0 45 8 0 0 0 0 0 14 46 0 608 0 14 15 0 0 2388 +365 410 0.999995285076681 -0.000219195555389994 0.00306296877501914 -0.00670772197073975 0.000213702725696485 0.999998368816627 0.00179351476976565 0.00755184723097701 -0.00306335690922146 -0.0017928517487051 0.999993700743687 -0.00790063267057253 3.82057262989391e-05 2.78888202148025e-05 -2.14359619135763e-06 6.20365108396708e-06 -3.98923130392492e-06 3.04257629218179e-05 2.78888202148025e-05 3.91976612747821e-05 -3.98051989457561e-06 1.27079905865524e-05 3.14670965744169e-07 2.7717343427533e-05 -2.14359619135763e-06 -3.98051989457561e-06 1.02756251828122e-05 3.09927032653715e-06 2.57441897673848e-06 -2.09606304394264e-07 6.20365108396708e-06 1.27079905865524e-05 3.09927032653715e-06 4.05689428913579e-05 -3.36737233981649e-06 8.80993589465112e-06 -3.98923130392492e-06 3.14670965744169e-07 2.57441897673848e-06 -3.36737233981649e-06 4.06932510082724e-05 -1.07157907675488e-05 3.04257629218179e-05 2.7717343427533e-05 -2.09606304394264e-07 8.80993589465112e-06 -1.07157907675488e-05 8.01051144571202e-05 2008 2006 0 16 9 2009 2030 0 35 7 0 0 0 0 0 21 49 0 503 0 30 30 0 0 2229 +365 423 0.999999942375302 9.98941551199808e-05 0.000324454234177142 -0.00664839592550876 -0.000100043147947917 0.999999889551028 0.000459226850790162 0.00801623275446867 -0.000324408324263237 -0.000459259283750306 0.999999841920062 -0.0136512053072571 3.97935228060649e-05 2.49058114707764e-05 -5.63360408988247e-06 7.45683532549285e-06 -1.90151446645645e-07 2.65048638358561e-05 2.49058114707764e-05 3.39183873356462e-05 -6.40449551867169e-06 1.03215519455945e-05 -2.85020573980397e-06 2.16642646486317e-05 -5.63360408988247e-06 -6.40449551867169e-06 1.16618505922053e-05 4.22356740826933e-07 1.29119488944303e-06 -5.05850722206695e-07 7.45683532549285e-06 1.03215519455945e-05 4.22356740826933e-07 4.32181911358028e-05 -2.92090891617608e-06 4.40978978590266e-07 -1.90151446645645e-07 -2.85020573980397e-06 1.29119488944303e-06 -2.92090891617608e-06 3.43824317070143e-05 -2.07567440507754e-06 2.65048638358561e-05 2.16642646486317e-05 -5.05850722206695e-07 4.40978978590266e-07 -2.07567440507754e-06 6.60639501245278e-05 2040 2037 0 16 12 2037 2068 0 52 12 0 0 0 0 0 22 52 0 612 0 10 13 0 0 2293 +365 396 0.999998976071919 0.000179154161585275 0.00141977424291941 -0.00593206190812131 -0.000180431060068386 0.999999579360776 0.000899290221890379 0.00362861443488465 -0.00141961253412095 -0.000899545472453575 0.999998587758101 -0.00762633956956545 3.3119919995826e-05 7.52734917210998e-06 -1.16853443888742e-06 -6.81684922068962e-06 -9.45853269116554e-07 4.83662957607256e-06 7.52734917210998e-06 3.49604605752923e-05 -2.51546878416026e-06 1.30213422780259e-05 4.09289340316591e-06 5.82177735556139e-06 -1.16853443888742e-06 -2.51546878416026e-06 1.17243383157298e-05 4.50106285955249e-06 1.2995312895392e-06 -2.12098374931143e-06 -6.81684922068962e-06 1.30213422780259e-05 4.50106285955249e-06 5.00715787692905e-05 -5.32465286861648e-06 -2.87586772941768e-06 -9.45853269116554e-07 4.09289340316591e-06 1.2995312895392e-06 -5.32465286861648e-06 4.6539274731196e-05 1.12920323497326e-05 4.83662957607256e-06 5.82177735556139e-06 -2.12098374931143e-06 -2.87586772941768e-06 1.12920323497326e-05 5.60435368854043e-05 1399 1384 0 14 46 1360 1382 0 39 11 0 0 0 0 0 17 45 0 455 0 87 69 0 0 2454 +365 395 0.999999715223707 0.00017923083631278 -0.000733095363834718 -0.00305152620807655 -0.000179996511707708 0.999999438300796 -0.00104450914271363 0.00469910150223418 0.000732907743808451 0.00104464079987043 0.999999185785588 -0.00442634932724827 2.10998803305234e-05 1.36526125943491e-05 3.51692025226686e-07 1.64315451376002e-06 -1.86417068797933e-07 1.01607733986258e-05 1.36526125943491e-05 2.75956671286808e-05 -9.07382092510999e-07 5.56102616995935e-06 1.67338757468645e-06 9.33055346715843e-06 3.51692025226686e-07 -9.07382092510999e-07 9.57843048036851e-06 3.16839971760639e-06 3.85194688873464e-06 -2.87481822518943e-07 1.64315451376002e-06 5.56102616995935e-06 3.16839971760639e-06 4.10436983752905e-05 -1.43808670000485e-05 1.3141310969443e-06 -1.86417068797933e-07 1.67338757468645e-06 3.85194688873464e-06 -1.43808670000485e-05 3.98705534873395e-05 9.52651008773224e-06 1.01607733986258e-05 9.33055346715843e-06 -2.87481822518943e-07 1.3141310969443e-06 9.52651008773224e-06 5.56076895731756e-05 2183 2164 0 17 48 2162 2181 0 38 20 0 0 0 0 0 17 47 0 445 0 91 76 0 0 2515 +365 392 0.99999980607857 0.000578196300622342 0.000231369529892297 -0.00266890317836113 -0.000578466037870368 0.999999151200821 0.00116746506653786 0.0101954957258542 -0.000230694309523452 -0.0011675986795566 0.999999291746479 -0.00444615720286944 2.17077402666834e-05 9.7986374445197e-06 -6.46171935457636e-07 4.60994679370619e-07 -1.98157184791463e-06 9.66418790527932e-06 9.7986374445197e-06 2.20383923471319e-05 -2.07713118736689e-06 5.16880985358624e-06 1.23945069196656e-06 6.88880360735295e-06 -6.46171935457636e-07 -2.07713118736689e-06 9.39082713322152e-06 2.27717239778171e-06 4.14367855559094e-06 -2.36427488556295e-07 4.60994679370619e-07 5.16880985358624e-06 2.27717239778171e-06 3.17769084172488e-05 1.88856818584507e-06 2.7868280487815e-07 -1.98157184791463e-06 1.23945069196656e-06 4.14367855559094e-06 1.88856818584507e-06 3.25316598465635e-05 -1.42875903187771e-06 9.66418790527932e-06 6.88880360735295e-06 -2.36427488556295e-07 2.7868280487815e-07 -1.42875903187771e-06 5.24548312423245e-05 2398 2380 0 12 50 2388 2436 0 51 36 0 0 0 0 0 19 50 0 438 0 52 30 0 0 2359 +365 394 0.999995772786918 0.000217311582863326 0.00289951443713782 -0.00217424046557809 -0.000220927360865277 0.99999919838152 0.00124676678605178 0.00289434049008244 -0.00289924117596972 -0.0012474020977753 0.999995019181901 -0.00472770144720554 4.16328063400843e-05 2.27254668682359e-05 -8.70187604378653e-09 4.63118905320926e-06 -8.34164227256545e-06 2.37189976575935e-05 2.27254668682359e-05 3.39645440914975e-05 -1.16308922880925e-06 1.40506967114353e-05 -8.1929123622525e-06 8.4675131624932e-06 -8.70187604378653e-09 -1.16308922880925e-06 1.11966293971271e-05 3.64829848307341e-06 3.379010330678e-06 -5.79876481223461e-07 4.63118905320926e-06 1.40506967114353e-05 3.64829848307341e-06 4.68076896983337e-05 -8.40443093992682e-06 -1.71669997700961e-07 -8.34164227256545e-06 -8.1929123622525e-06 3.379010330678e-06 -8.40443093992682e-06 4.39362656808916e-05 -2.98670612666446e-06 2.37189976575935e-05 8.4675131624932e-06 -5.79876481223461e-07 -1.71669997700961e-07 -2.98670612666446e-06 7.05880859665465e-05 1951 1931 0 16 43 1904 1932 0 44 6 0 0 0 0 0 21 53 0 466 0 83 63 0 0 2471 +365 411 0.999999213621811 -0.000118700411747004 0.00124846544698884 -0.00534275541353428 0.000117857734295505 0.999999765227063 0.000675022497930579 0.00581072219373055 -0.00124854527933138 -0.000674874825798681 0.99999899283882 -0.0101946173777169 6.32761635888571e-05 5.65203109776098e-05 -3.62307599464258e-06 1.98867387623404e-05 -1.11019933512783e-05 5.76397229220657e-05 5.65203109776098e-05 7.06343303904649e-05 -5.52423288344175e-06 2.82695755473202e-05 -1.46990039718759e-05 6.2641398231762e-05 -3.62307599464258e-06 -5.52423288344175e-06 1.052715844168e-05 2.89277454389827e-06 3.17476893346335e-06 -2.33787427102047e-06 1.98867387623404e-05 2.82695755473202e-05 2.89277454389827e-06 4.653582245315e-05 -1.45076657593551e-05 2.81907223807282e-05 -1.11019933512783e-05 -1.46990039718759e-05 3.17476893346335e-06 -1.45076657593551e-05 3.95674469535129e-05 -2.20953765078662e-05 5.76397229220657e-05 6.2641398231762e-05 -2.33787427102047e-06 2.81907223807282e-05 -2.20953765078662e-05 0.000108604542463452 2039 2041 0 16 11 2038 2063 0 39 9 0 0 0 0 0 17 47 0 531 0 9 11 0 0 2299 +365 393 0.999994116724537 0.00100692905324207 0.00327911728899083 -0.00139374335194935 -0.0010061597146158 0.999999465912059 -0.00023625881116442 0.00696935136010698 -0.00327935343351487 0.000232958105473071 0.999994595771187 -0.00394644271480852 3.79682096486317e-05 2.33607335034763e-05 -8.07981801467395e-07 2.69506169708677e-06 -3.92807291207813e-06 2.28377522282827e-05 2.33607335034763e-05 4.11417072257633e-05 -2.08112543373442e-06 1.23273737580398e-05 -1.76786673967982e-06 2.20550061255348e-05 -8.07981801467395e-07 -2.08112543373442e-06 1.06791330816949e-05 2.45271567548722e-06 4.20107328547393e-06 -1.41311709468523e-06 2.69506169708677e-06 1.23273737580398e-05 2.45271567548722e-06 3.77796679350423e-05 -4.09550746105708e-06 8.55731908161891e-06 -3.92807291207813e-06 -1.76786673967982e-06 4.20107328547393e-06 -4.09550746105708e-06 3.66085098914803e-05 -1.48222238832351e-06 2.28377522282827e-05 2.20550061255348e-05 -1.41311709468523e-06 8.55731908161891e-06 -1.48222238832351e-06 6.20750561291159e-05 2103 2082 0 14 50 2087 2115 0 48 30 0 0 0 0 0 17 47 0 454 0 48 28 0 0 2352 +365 420 0.999999844393199 -4.36198474243161e-05 0.000556157250552802 -0.00372204366273885 4.30626004324842e-05 0.999999497138793 0.0010019320208132 0.00410698303051469 -0.000556200675004773 -0.0010019079153283 0.999999343410454 -0.0102660178456455 3.69808130836757e-05 2.00319720678216e-05 -1.13361413540604e-05 1.11897210294504e-05 8.40836684668746e-06 1.35831017826769e-05 2.00319720678216e-05 3.08327646241834e-05 -1.12798809583621e-05 1.13003252973303e-05 8.7539443403771e-06 1.57669479128265e-05 -1.13361413540604e-05 -1.12798809583621e-05 1.52588759837986e-05 -3.33453374272138e-06 -4.22173286894061e-06 -4.19614799020625e-06 1.11897210294504e-05 1.13003252973303e-05 -3.33453374272138e-06 4.3243176303785e-05 -7.22070888552368e-06 3.32804370522978e-06 8.40836684668746e-06 8.7539443403771e-06 -4.22173286894061e-06 -7.22070888552368e-06 4.7784211619159e-05 1.07158870496516e-07 1.35831017826769e-05 1.57669479128265e-05 -4.19614799020625e-06 3.32804370522978e-06 1.07158870496516e-07 6.0536101212299e-05 2067 2064 0 16 11 2066 2088 0 38 9 0 0 0 0 0 22 53 0 615 0 10 12 0 0 2256 +365 426 0.999998973802832 0.000856187314155624 0.00114862377027035 -0.00347291764092146 -0.000858411135342753 0.999997755615819 0.00193698054916103 0.0104168665607262 -0.00114696277414337 -0.00193796455287179 0.999997464381679 -0.0110719741233209 3.04198966019754e-05 1.02710140241352e-05 -5.87912127735936e-06 -1.20276496892235e-06 5.88168070411543e-06 8.44049385747657e-06 1.02710140241352e-05 2.97915297088785e-05 -7.59680155731342e-06 7.01319271682266e-06 2.37069211033039e-06 1.27749949877985e-05 -5.87912127735936e-06 -7.59680155731342e-06 1.42888485056274e-05 2.71254321741957e-06 1.14538440015593e-06 -2.37348873579185e-06 -1.20276496892235e-06 7.01319271682266e-06 2.71254321741957e-06 3.88831342405135e-05 -3.24527225739677e-07 8.28583170805594e-07 5.88168070411543e-06 2.37069211033039e-06 1.14538440015593e-06 -3.24527225739677e-07 3.832676107023e-05 7.74363710199694e-06 8.44049385747657e-06 1.27749949877985e-05 -2.37348873579185e-06 8.28583170805594e-07 7.74363710199694e-06 5.73401114671677e-05 1529 1530 0 20 17 1526 1548 0 40 16 0 0 0 0 0 16 44 0 640 0 14 16 0 0 2096 +365 403 0.999996964599248 0.000973327461838793 0.00226349860677228 -0.00162381320029172 -0.000973209787007167 0.999999525022028 -5.30888792605933e-05 0.00917308606944657 -0.0022635492045244 5.08858591175814e-05 0.999997436874529 -0.00355239419452295 2.49466416191682e-05 1.57494407987033e-05 -1.77135780735905e-06 -3.26695674701288e-07 2.76256230084084e-06 1.29967913360101e-05 1.57494407987033e-05 2.59083004506469e-05 -3.68443284581186e-06 3.83807910448825e-06 2.14819702532155e-06 1.28988727335707e-05 -1.77135780735905e-06 -3.68443284581186e-06 1.10634575002666e-05 2.42041175290736e-06 2.13934957061829e-06 -1.0328956773427e-06 -3.26695674701288e-07 3.83807910448825e-06 2.42041175290736e-06 3.14132757245112e-05 -3.16192467345415e-06 6.81052945885853e-07 2.76256230084084e-06 2.14819702532155e-06 2.13934957061829e-06 -3.16192467345415e-06 3.11526928654453e-05 5.05869582295656e-06 1.29967913360101e-05 1.28988727335707e-05 -1.0328956773427e-06 6.81052945885853e-07 5.05869582295656e-06 4.5760778321226e-05 2140 2135 0 17 28 2130 2163 0 52 19 0 0 0 0 0 21 51 0 449 0 26 20 0 0 2330 +365 425 0.999992957837518 0.00049398377194251 0.0037202493740057 -0.00874597464124372 -0.000505478891959441 0.999995099503625 0.00308957275779354 0.00978067357901001 -0.00371870494413254 -0.00309143150805156 0.999988307074023 -0.0095192460624263 3.19937573515296e-05 1.63531080409223e-05 -1.03040172322529e-05 4.18932583876731e-06 6.53161809255053e-06 8.8375324531259e-06 1.63531080409223e-05 3.06927195163796e-05 -1.24993300036115e-05 7.4577624614499e-06 9.05270642864525e-06 2.39987589895891e-06 -1.03040172322529e-05 -1.24993300036115e-05 1.69273740814274e-05 -5.58677501136582e-08 -4.84601711163826e-06 -4.42181920536604e-06 4.18932583876731e-06 7.4577624614499e-06 -5.58677501136582e-08 3.86134650274151e-05 -8.12383649123351e-06 -6.9860021350713e-06 6.53161809255053e-06 9.05270642864525e-06 -4.84601711163826e-06 -8.12383649123351e-06 5.78183691087148e-05 1.55172442765947e-05 8.8375324531259e-06 2.39987589895891e-06 -4.42181920536604e-06 -6.9860021350713e-06 1.55172442765947e-05 4.97504494040984e-05 1954 1950 0 14 16 1948 1982 0 50 9 0 0 0 0 0 21 51 0 630 0 42 43 0 0 2011 +365 413 0.999997376943368 -0.000128902834806537 0.00228680791544565 -0.00863683218982446 0.00012503251152543 0.999998559872289 0.00169251889753376 0.00745929674771986 -0.00228702279263406 -0.0016922285326238 0.99999595293648 -0.00737334024140369 4.75760793058647e-05 3.57971441602912e-05 -8.94671120920234e-06 9.23837538768224e-06 8.57185675724293e-06 3.17200716356775e-05 3.57971441602912e-05 4.84634012399689e-05 -9.2986079556558e-06 1.7425281506557e-05 9.69698328127662e-06 2.25776315283312e-05 -8.94671120920234e-06 -9.2986079556558e-06 1.36331981415548e-05 8.1239422795509e-07 -2.15160390675952e-06 -6.7314963213697e-06 9.23837538768224e-06 1.7425281506557e-05 8.1239422795509e-07 4.43034281047855e-05 -2.96731218276432e-06 1.63914776548139e-06 8.57185675724293e-06 9.69698328127662e-06 -2.15160390675952e-06 -2.96731218276432e-06 4.94140788851494e-05 8.87211202586649e-06 3.17200716356775e-05 2.25776315283312e-05 -6.7314963213697e-06 1.63914776548139e-06 8.87211202586649e-06 7.30096647386725e-05 1926 1922 0 14 11 1921 1950 0 44 10 0 0 0 0 0 20 52 0 601 0 34 36 0 0 2208 +365 424 0.999998584384303 0.000179189436811505 0.00167305724220337 -0.0122903095343255 -0.000181958367127087 0.999998613920871 0.00165500679436008 0.011669619077705 -0.00167275836347825 -0.00165530887827039 0.999997230912154 -0.00903506079745788 2.97005169581795e-05 1.5795281908692e-05 -8.14808933580207e-06 4.63537056911397e-06 4.01004655535296e-06 1.09165553298566e-05 1.5795281908692e-05 2.87928747717704e-05 -9.46851292689813e-06 1.04312562042041e-05 8.05540098473185e-06 7.85194084299349e-06 -8.14808933580207e-06 -9.46851292689813e-06 1.38500392187503e-05 -7.60534308977713e-07 -2.03863176070082e-07 -5.12217733974876e-06 4.63537056911397e-06 1.04312562042041e-05 -7.60534308977713e-07 4.43161176003355e-05 -4.07740935371263e-07 1.94039862729146e-06 4.01004655535296e-06 8.05540098473185e-06 -2.03863176070082e-07 -4.07740935371263e-07 4.00380828690843e-05 6.63585649538603e-06 1.09165553298566e-05 7.85194084299349e-06 -5.12217733974876e-06 1.94039862729146e-06 6.63585649538603e-06 6.25237758947847e-05 1395 1393 0 13 15 1385 1407 0 33 6 0 0 0 0 0 22 52 0 622 0 42 43 0 0 2282 +366 407 0.999995321990759 -5.82783478112623e-05 0.00305820212407795 -0.0112266333224949 4.69490523411928e-05 0.999993137207706 0.00370450175832954 0.0102791015976164 -0.00305839702851391 -0.00370434084894449 0.999988461966682 -0.00796937640305098 2.68149229811652e-05 1.04760158052348e-05 -2.35838560892166e-06 -4.37237839842913e-06 1.91556097276926e-06 7.44993810968715e-06 1.04760158052348e-05 3.09234219808839e-05 -1.91971912382564e-06 9.95642326344404e-06 -1.58971448374878e-06 4.47115215390389e-06 -2.35838560892166e-06 -1.91971912382564e-06 1.18786324414185e-05 5.87135602836662e-06 2.12504476031347e-06 1.51987841108463e-07 -4.37237839842913e-06 9.95642326344404e-06 5.87135602836662e-06 4.89344551371723e-05 -1.0750764475283e-05 5.9993332490511e-06 1.91556097276926e-06 -1.58971448374878e-06 2.12504476031347e-06 -1.0750764475283e-05 3.37058962982975e-05 -4.87090708338969e-06 7.44993810968715e-06 4.47115215390389e-06 1.51987841108463e-07 5.9993332490511e-06 -4.87090708338969e-06 6.1693749358902e-05 1924 1924 0 14 17 1911 1941 0 50 9 0 0 0 0 0 24 51 0 485 0 47 58 0 0 2288 +365 412 0.99999485767916 -0.00021214220652077 0.00319993920581236 -0.00345792647807388 0.000208132645757208 0.999999192969016 0.00125329251124073 0.00675011968448579 -0.00320020249960103 -0.00125262005459537 0.999994094806045 -0.0124041651601554 5.39144674839638e-05 4.28466513356624e-05 -4.6547355275634e-06 1.86806897720409e-05 -6.24204598343432e-06 4.3330477880369e-05 4.28466513356624e-05 4.71866332946872e-05 -6.72953536335894e-06 1.89823781004084e-05 -3.93941546965991e-06 3.60627634269135e-05 -4.6547355275634e-06 -6.72953536335894e-06 1.14101793988743e-05 2.35043261569705e-06 -1.56757369104326e-07 -2.4543962177974e-06 1.86806897720409e-05 1.89823781004084e-05 2.35043261569705e-06 4.83708690609158e-05 -2.08151738353233e-05 1.13918521695794e-05 -6.24204598343432e-06 -3.93941546965991e-06 -1.56757369104326e-07 -2.08151738353233e-05 5.08459191099553e-05 -4.16412574098907e-06 4.3330477880369e-05 3.60627634269135e-05 -2.4543962177974e-06 1.13918521695794e-05 -4.16412574098907e-06 7.63394388613995e-05 2094 2091 0 19 9 2087 2117 0 43 6 0 0 0 0 0 18 49 0 565 0 9 9 0 0 2192 +366 406 0.999998017863058 0.000679315109813408 0.00187157712573522 -0.00621314583429947 -0.000683177529124744 0.999997636875368 0.0020638585570814 0.0101412552365131 -0.00187017069266287 -0.00206513308566743 0.999996118835928 -0.00546090522678423 2.42950617983783e-05 1.35543505124385e-05 1.76919776298245e-08 -9.12546173929365e-07 6.85738875728906e-07 1.32078663735678e-05 1.35543505124385e-05 1.96782575443612e-05 -1.85014396727419e-06 1.10057849919091e-06 7.81922589835286e-07 8.68398414313025e-06 1.76919776298245e-08 -1.85014396727419e-06 1.01671746323493e-05 2.33911154826875e-06 3.1351249678034e-06 -5.71055151283577e-07 -9.12546173929365e-07 1.10057849919091e-06 2.33911154826875e-06 2.73837981892188e-05 -2.71536323245463e-06 5.40200427377872e-06 6.85738875728906e-07 7.81922589835286e-07 3.1351249678034e-06 -2.71536323245463e-06 2.50277187915299e-05 -1.27601982779424e-06 1.32078663735678e-05 8.68398414313025e-06 -5.71055151283577e-07 5.40200427377872e-06 -1.27601982779424e-06 4.76118394960078e-05 2607 2610 0 21 17 2603 2639 0 37 14 0 0 0 0 0 9 40 0 458 0 18 21 0 0 2390 +366 370 0.999998704271143 0.000259612583747754 -0.00158872821518209 -0.0108410426901817 -0.000260062508597256 0.999999926139783 -0.000282998092279176 0.00399271806206872 0.00158865462797234 0.0002834108942355 0.999998697926521 -0.00168216731141333 2.36169235325021e-05 1.30812361873425e-05 -5.15670389298111e-06 4.71808601942538e-06 7.47153530627386e-06 1.55261722987589e-05 1.30812361873425e-05 1.91586346008645e-05 -5.82176463202547e-06 3.2625090194791e-06 9.84446040217019e-07 1.68389536304314e-05 -5.15670389298111e-06 -5.82176463202547e-06 1.1236146357371e-05 1.55440369812992e-06 -4.64130312822529e-07 -1.44452253151119e-06 4.71808601942538e-06 3.2625090194791e-06 1.55440369812992e-06 3.11420559290804e-05 3.20853546532981e-06 4.74065270894361e-06 7.47153530627386e-06 9.84446040217019e-07 -4.64130312822529e-07 3.20853546532981e-06 3.18309390468626e-05 3.55600654192109e-06 1.55261722987589e-05 1.68389536304314e-05 -1.44452253151119e-06 4.74065270894361e-06 3.55600654192109e-06 4.76586534438549e-05 2973 2948 0 11 53 2952 2999 0 45 32 0 0 0 0 0 18 48 0 655 0 55 33 0 0 2308 +365 422 0.999995753525873 0.000180920985236593 -0.00290864192000417 -0.0103538211444517 -0.000181473793486261 0.999999965522679 -0.000189794370965368 0.0100957860817766 0.0029086074819374 0.000190321407291598 0.999995751881116 -0.0110740968612655 2.79413782243731e-05 1.49707372810398e-05 -8.74870224047378e-06 3.91415992632663e-06 1.00556691721652e-05 1.44835240349198e-05 1.49707372810398e-05 2.6591585897979e-05 -9.11079957043708e-06 8.55382046585914e-06 8.82528588432902e-06 7.84626492208241e-06 -8.74870224047378e-06 -9.11079957043708e-06 1.38550710825259e-05 -4.43696790192035e-07 -2.70009606222105e-06 -3.77620099614404e-06 3.91415992632663e-06 8.55382046585914e-06 -4.43696790192035e-07 4.01294747063184e-05 -3.34052266740737e-06 2.47393020013127e-06 1.00556691721652e-05 8.82528588432902e-06 -2.70009606222105e-06 -3.34052266740737e-06 4.21240391189158e-05 3.18419083341401e-06 1.44835240349198e-05 7.84626492208241e-06 -3.77620099614404e-06 2.47393020013127e-06 3.18419083341401e-06 4.70624245816007e-05 2172 2171 0 14 14 2171 2207 0 49 12 0 0 0 0 0 20 53 0 601 0 57 58 0 0 2365 +366 368 0.999989429884982 0.000203466844720126 0.00459333425216697 -0.00870348996178537 -0.000201686693693025 0.999999904385033 -0.000388010827501757 0.00926877739462829 -0.00459341276031425 0.000387080311784336 0.999989375307581 -0.00120365820573652 7.02875060981662e-05 6.12890621949366e-05 -2.42122467489912e-06 1.37790955894851e-05 -9.38089164222752e-06 5.6482943224253e-05 6.12890621949366e-05 9.52101893363497e-05 -8.92570197161709e-07 1.89222156658983e-05 -8.68517579851519e-07 6.16416574385286e-05 -2.42122467489912e-06 -8.92570197161709e-07 1.06407355807515e-05 2.63310712076406e-06 2.7090613665502e-06 -3.07502136770351e-06 1.37790955894851e-05 1.89222156658983e-05 2.63310712076406e-06 3.37949937577564e-05 -1.27542618130362e-05 2.05288895453796e-05 -9.38089164222752e-06 -8.68517579851519e-07 2.7090613665502e-06 -1.27542618130362e-05 3.94690353452384e-05 -1.1529479096885e-05 5.6482943224253e-05 6.16416574385286e-05 -3.07502136770351e-06 2.05288895453796e-05 -1.1529479096885e-05 8.71687529287651e-05 2414 2395 0 16 44 2362 2376 0 30 0 0 0 0 0 0 21 52 0 517 0 77 70 0 0 2756 +366 399 0.99999081438644 -0.000277351401752902 0.00427717417737898 0.00369637748428505 0.000275515181820055 0.999999869642963 0.000429890034372304 -0.0100459068574792 -0.00427729285042286 -0.000428707659147419 0.999990760445123 -0.00798938782907191 4.84785714920723e-05 2.55422745799092e-05 -2.77301150300025e-06 1.28140751620796e-05 -1.49735675564128e-05 2.95060977002566e-05 2.55422745799092e-05 3.66265495331268e-05 -3.64899043805128e-06 1.00474515775326e-05 -4.22630978789041e-07 2.30368554564392e-05 -2.77301150300025e-06 -3.64899043805128e-06 1.03661962909408e-05 4.64684665190221e-06 2.31919502338702e-06 1.90430686948919e-07 1.28140751620796e-05 1.00474515775326e-05 4.64684665190221e-06 4.44922323935269e-05 -2.27801203900909e-05 1.09567578217243e-05 -1.49735675564128e-05 -4.22630978789041e-07 2.31919502338702e-06 -2.27801203900909e-05 5.92196335477873e-05 -8.45384112195556e-06 2.95060977002566e-05 2.30368554564392e-05 1.90430686948919e-07 1.09567578217243e-05 -8.45384112195556e-06 5.99171087170482e-05 2143 2122 0 18 42 2119 2147 0 49 26 0 0 0 0 0 13 46 0 491 0 48 32 0 0 2509 +365 404 0.999995681703018 0.00139464300976073 0.00258680231031443 -0.00996868371539644 -0.00139665909900809 0.999998722236987 0.000777732443571883 0.0160184483141199 -0.00258571434587823 -0.000781341966076254 0.999996351786372 -0.000502640825352205 2.52222169279675e-05 1.66208088392954e-05 3.46194540660219e-07 -3.05780247035248e-06 1.40225839013783e-06 1.1304925088535e-05 1.66208088392954e-05 3.015161589366e-05 -1.98463844151509e-06 6.43612658688476e-06 -2.70130274761851e-06 1.01072491264503e-05 3.46194540660219e-07 -1.98463844151509e-06 1.37890148693803e-05 4.41764735706482e-06 8.676342435688e-07 3.43100295770605e-07 -3.05780247035248e-06 6.43612658688476e-06 4.41764735706482e-06 3.82015639445242e-05 1.58004791119867e-06 2.6479567402281e-06 1.40225839013783e-06 -2.70130274761851e-06 8.676342435688e-07 1.58004791119867e-06 3.50099081461134e-05 5.96561419650704e-06 1.1304925088535e-05 1.01072491264503e-05 3.43100295770605e-07 2.6479567402281e-06 5.96561419650704e-06 5.39050475877248e-05 1934 1930 0 14 21 1926 1945 0 36 12 0 0 0 0 0 22 51 0 446 0 48 48 0 0 2294 +366 398 0.999999792207558 0.000219225343291787 0.000606238475919455 -0.000610403463855153 -0.000219168056729515 0.999999971511892 -9.4559914454891e-05 -0.00159742055905152 -0.000606259188578577 9.44270266973735e-05 0.999999811766649 -0.00806256018865323 2.45143167165834e-05 1.25838062357189e-05 -1.79090362684384e-06 3.31989891168206e-08 1.02373369840361e-06 1.32982102560992e-05 1.25838062357189e-05 2.30282696378928e-05 -3.60294943342053e-06 3.06541529671546e-06 1.81228151688117e-06 1.42761328813793e-05 -1.79090362684384e-06 -3.60294943342053e-06 1.07805056016972e-05 4.84244922165083e-06 2.47685142525876e-06 1.1182626036645e-06 3.31989891168206e-08 3.06541529671546e-06 4.84244922165083e-06 3.30953348533287e-05 -8.02181921189389e-06 6.0486788209195e-06 1.02373369840361e-06 1.81228151688117e-06 2.47685142525876e-06 -8.02181921189389e-06 3.99982083579213e-05 -3.09576521235684e-06 1.32982102560992e-05 1.42761328813793e-05 1.1182626036645e-06 6.0486788209195e-06 -3.09576521235684e-06 5.48629529861224e-05 2047 2027 0 19 45 2022 2065 0 41 25 0 0 0 0 0 13 44 0 476 0 45 30 0 0 2455 +366 405 0.999996370727511 0.00097604205794726 0.00251114987746035 -0.00508087625588451 -0.000980681101208464 0.999997813775396 0.00184681049548313 0.0112465950965984 -0.00250934182280606 -0.00184926643013173 0.999995141696842 -0.000877722259396573 2.50538597037252e-05 1.14494460724276e-05 -1.9226967604343e-06 3.9265940978221e-06 -2.83403147155713e-06 1.25052146848659e-05 1.14494460724276e-05 2.56352666759194e-05 -3.14986388869113e-06 4.04780968541348e-06 -3.53497181396556e-07 7.13704102515015e-06 -1.9226967604343e-06 -3.14986388869113e-06 1.17221657710055e-05 3.95251633173024e-06 1.32168555440533e-06 -1.38035162233091e-06 3.9265940978221e-06 4.04780968541348e-06 3.95251633173024e-06 3.06054560335871e-05 -5.01344294509972e-06 4.69763961760657e-06 -2.83403147155713e-06 -3.53497181396556e-07 1.32168555440533e-06 -5.01344294509972e-06 3.87152637647189e-05 5.45264797831879e-06 1.25052146848659e-05 7.13704102515015e-06 -1.38035162233091e-06 4.69763961760657e-06 5.45264797831879e-06 4.96396804999767e-05 2175 2178 0 17 19 2168 2196 0 46 13 0 0 0 0 0 22 52 0 451 0 58 62 0 0 2368 +366 408 0.999999570277725 9.22488435532362e-05 0.000922461118866079 -0.00571318063666107 -9.33754949712464e-05 0.999999249749133 0.00122138535620878 0.00791680044811872 -0.000922347755402181 -0.00122147096661586 0.999998828640962 -0.00247821370528836 2.62444298713517e-05 2.09449421213659e-05 -2.8567748174788e-06 1.07165932847254e-06 -2.64832934776045e-07 1.75793815876028e-05 2.09449421213659e-05 3.24465050342619e-05 -3.75818517463193e-06 7.57353683935415e-06 -3.0397199348769e-06 1.54102810076758e-05 -2.8567748174788e-06 -3.75818517463193e-06 9.92316832377406e-06 3.79124481792636e-06 4.33010251004071e-06 -6.67872498820608e-07 1.07165932847254e-06 7.57353683935415e-06 3.79124481792636e-06 2.63279236716416e-05 -2.74875794263556e-06 3.42407080653314e-06 -2.64832934776045e-07 -3.0397199348769e-06 4.33010251004071e-06 -2.74875794263556e-06 2.27092189185361e-05 3.31637441264196e-07 1.75793815876028e-05 1.54102810076758e-05 -6.67872498820608e-07 3.42407080653314e-06 3.31637441264196e-07 5.34811678984448e-05 2160 2158 0 10 15 2151 2181 0 44 10 0 0 0 0 0 11 43 0 499 0 55 58 0 0 2300 +366 401 0.999998337772136 0.000274258706383711 0.00180256348738006 -0.00265975661311076 -0.000275498691802865 0.999999725592249 0.000687688808158796 -0.00488633195846437 -0.00180237438809974 -0.000688184268945963 0.999998138922757 -0.00800176862980526 3.59102284534305e-05 2.19612573529289e-05 -3.55676536827595e-06 -1.59381637496098e-06 2.03984311956986e-06 1.64851579281747e-05 2.19612573529289e-05 3.84860667918509e-05 -3.65150445807167e-06 6.76730159896164e-06 4.18555104241678e-06 1.23659038854581e-05 -3.55676536827595e-06 -3.65150445807167e-06 1.080893214859e-05 6.32877444968561e-06 2.42702712578284e-06 -1.05251576968797e-06 -1.59381637496098e-06 6.76730159896164e-06 6.32877444968561e-06 7.75719372779761e-05 -4.90202742253885e-05 4.31874804818924e-07 2.03984311956986e-06 4.18555104241678e-06 2.42702712578284e-06 -4.90202742253885e-05 9.05379025951185e-05 7.66356226007997e-06 1.64851579281747e-05 1.23659038854581e-05 -1.05251576968797e-06 4.31874804818924e-07 7.66356226007997e-06 6.38141925328014e-05 1929 1918 0 20 37 1888 1915 0 47 10 0 0 0 0 0 11 42 0 505 0 74 73 0 0 2421 +366 369 0.999986010719105 0.000363600147159044 0.00527694618345183 -0.00431084421758991 -0.000365817264792574 0.999999845227666 0.000419192523743623 0.00425303332406263 -0.00527679294826324 -0.000421117057560948 0.999985988960148 -0.0013499091493193 4.19058049381331e-05 2.10164492925251e-05 -4.86643329621245e-06 4.4698477864277e-06 5.58314275705979e-07 2.94485080250042e-05 2.10164492925251e-05 3.28785154843086e-05 -8.16073512480273e-06 4.57476740992672e-06 9.20681726391013e-06 2.36595373134569e-05 -4.86643329621245e-06 -8.16073512480273e-06 1.57053204739878e-05 1.02606893734967e-06 -4.46085484173961e-06 -6.21591241386313e-06 4.4698477864277e-06 4.57476740992672e-06 1.02606893734967e-06 3.18325537825991e-05 -3.71996646189265e-06 1.94352254876722e-06 5.58314275705979e-07 9.20681726391013e-06 -4.46085484173961e-06 -3.71996646189265e-06 5.36480541857787e-05 9.35393233784261e-06 2.94485080250042e-05 2.36595373134569e-05 -6.21591241386313e-06 1.94352254876722e-06 9.35393233784261e-06 5.84472727656848e-05 2653 2630 0 17 53 2619 2637 0 36 27 0 0 0 0 0 18 50 0 647 0 54 30 0 0 2292 +366 397 0.999998758103455 0.000598552576305799 0.00145791850313202 -0.00262227709599118 -0.000600543344294417 0.999998887471417 0.00136543166060799 0.00143843993189078 -0.00145709959851778 -0.00136630550813671 0.999998005033019 -0.00754587673769229 2.63770154965654e-05 1.7995721208056e-05 -2.20573524142824e-06 3.56728723309922e-06 1.57316844724904e-06 1.27131034695941e-05 1.7995721208056e-05 3.38875012550009e-05 -2.78486456690822e-06 1.76013711548957e-05 -4.65567343270791e-06 1.85400089863811e-05 -2.20573524142824e-06 -2.78486456690822e-06 1.15810897902919e-05 6.32204289666118e-06 4.8035826589469e-07 1.24798947311294e-07 3.56728723309922e-06 1.76013711548957e-05 6.32204289666118e-06 5.8553588430831e-05 -2.89963676995893e-05 1.00530102662401e-05 1.57316844724904e-06 -4.65567343270791e-06 4.8035826589469e-07 -2.89963676995893e-05 5.37304728500355e-05 -3.29725446287562e-06 1.27131034695941e-05 1.85400089863811e-05 1.24798947311294e-07 1.00530102662401e-05 -3.29725446287562e-06 5.79958897874203e-05 2058 2046 0 16 42 2034 2057 0 38 25 0 0 0 0 0 8 38 0 455 0 47 29 0 0 2384 +366 429 0.999973740756706 -0.00723741019642824 0.000371066959174692 -0.00294373600545021 0.00723625805243413 0.999969264948391 0.0030175698785949 0.00388545000399265 -0.000392894945420329 -0.00301480550322198 0.99999537827999 -0.0117890115994475 4.14369848232182e-05 1.74819341865177e-05 -4.54442113892092e-06 6.68381011633791e-06 -3.62126484897395e-06 2.66300080672501e-05 1.74819341865177e-05 3.98890661270086e-05 -4.22601163156028e-06 1.29044052417748e-05 -3.91878260068526e-06 1.42606320841804e-05 -4.54442113892092e-06 -4.22601163156028e-06 1.17380691400743e-05 2.95719156607802e-06 1.80871242939406e-06 -7.89975080498933e-07 6.68381011633791e-06 1.29044052417748e-05 2.95719156607802e-06 4.23393772543393e-05 -1.20451703414936e-05 8.00786331163504e-06 -3.62126484897395e-06 -3.91878260068526e-06 1.80871242939406e-06 -1.20451703414936e-05 3.73964739517271e-05 -6.746607260021e-06 2.66300080672501e-05 1.42606320841804e-05 -7.89975080498933e-07 8.00786331163504e-06 -6.746607260021e-06 6.72865489920431e-05 2084 2081 0 7 24 2085 2093 0 26 22 0 0 0 0 0 32 63 0 605 0 15 15 0 0 2342 +366 409 0.999999887565954 0.000474161101165002 6.27139316012556e-06 -0.0111823042341768 -0.000474167801798346 0.999999265432508 0.00111548166274366 0.00745905666000165 -5.74247053982811e-06 -0.00111548451101826 0.999999377830471 -0.0076043861835787 2.43844399910104e-05 1.7963881188962e-05 -2.31112441366649e-06 -1.5551904494814e-06 2.83686515184799e-06 1.10928805083795e-05 1.7963881188962e-05 2.57961638172338e-05 -2.45945784599984e-06 1.65256155615392e-06 -5.17927237289847e-07 1.24743779766961e-05 -2.31112441366649e-06 -2.45945784599984e-06 9.42546327059379e-06 3.73268814148896e-06 3.87050019243665e-06 -2.01349051449901e-06 -1.5551904494814e-06 1.65256155615392e-06 3.73268814148896e-06 3.69466757237426e-05 -4.36909242308623e-06 -5.52201011888374e-06 2.83686515184799e-06 -5.17927237289847e-07 3.87050019243665e-06 -4.36909242308623e-06 2.81122117795774e-05 2.75590403803132e-06 1.10928805083795e-05 1.24743779766961e-05 -2.01349051449901e-06 -5.52201011888374e-06 2.75590403803132e-06 5.36456542884472e-05 1986 1982 0 13 10 1971 1995 0 38 2 0 0 0 0 0 12 42 0 507 0 43 54 0 0 2217 +366 392 0.999997300307913 0.000617289009411065 0.00224016320054311 -0.00349720083019308 -0.000620648019295562 0.999998683801522 0.0014990634610869 0.00913973033931532 -0.00223923489664477 -0.00150044976693045 0.999996367232189 -0.000220521277849319 2.24572127118674e-05 1.12485543671827e-05 -1.62302324638496e-06 -6.66739527327569e-07 1.61123511620053e-06 1.13237057299542e-05 1.12485543671827e-05 1.9811309162561e-05 -2.14921978920937e-06 2.19999004143179e-06 2.96452330524758e-06 8.93902115992691e-06 -1.62302324638496e-06 -2.14921978920937e-06 9.04264954238057e-06 1.93560398416817e-06 2.68707314798289e-06 -2.23742980919368e-06 -6.66739527327569e-07 2.19999004143179e-06 1.93560398416817e-06 3.43575546605148e-05 -2.58767055050797e-06 -2.99770450744152e-07 1.61123511620053e-06 2.96452330524758e-06 2.68707314798289e-06 -2.58767055050797e-06 2.61018983953517e-05 1.23496050609094e-05 1.13237057299542e-05 8.93902115992691e-06 -2.23742980919368e-06 -2.99770450744152e-07 1.23496050609094e-05 6.40662743733244e-05 2406 2384 0 17 56 2381 2429 0 40 33 0 0 0 0 0 13 45 0 445 0 55 33 0 0 2269 +366 400 0.999999967223303 -0.000188748470474367 0.000172995397172489 2.63103417161199e-05 0.000188610230528209 0.999999663200782 0.000798764360788551 -0.00770860721050331 -0.000173146104459143 -0.000798731705905953 0.999999666023988 -0.0104125313072552 2.41138112496931e-05 1.86970290570004e-05 -3.27286309359811e-06 3.57723707347226e-06 1.45497055721931e-06 1.60506976977884e-05 1.86970290570004e-05 2.53734618288263e-05 -5.702370127879e-06 4.41794239754853e-06 8.33910867548957e-07 1.70473969629155e-05 -3.27286309359811e-06 -5.702370127879e-06 1.15335092163523e-05 3.39707579428013e-06 3.86882748864543e-06 -8.52218323745627e-07 3.57723707347226e-06 4.41794239754853e-06 3.39707579428013e-06 4.22449517378345e-05 -1.49431454804978e-05 1.15288569186059e-05 1.45497055721931e-06 8.33910867548957e-07 3.86882748864543e-06 -1.49431454804978e-05 4.07100650772089e-05 2.58763673318829e-06 1.60506976977884e-05 1.70473969629155e-05 -8.52218323745627e-07 1.15288569186059e-05 2.58763673318829e-06 5.4775586392966e-05 2579 2562 0 18 41 2553 2589 0 33 17 0 0 0 0 0 4 35 0 491 0 49 34 0 0 2357 +366 428 0.99999953655982 0.000826479427796266 0.000493773125796049 -0.00760846804612472 -0.000826904892514 0.99999928652427 0.000862078447687153 0.00916500729982638 -0.000493060283398748 -0.000862486351578875 0.999999506504303 -0.0102929571982593 3.17037893681081e-05 1.83803907935782e-05 -9.44365254069397e-06 2.06453283507729e-06 9.39856998734362e-06 1.87327129783716e-05 1.83803907935782e-05 3.20971711152578e-05 -8.5387822176236e-06 8.04946900056533e-06 4.74725841406549e-06 2.00282999443388e-05 -9.44365254069397e-06 -8.5387822176236e-06 1.52624075768667e-05 2.61031653532191e-06 -4.56234707295106e-06 -1.07803747476565e-06 2.06453283507729e-06 8.04946900056533e-06 2.61031653532191e-06 3.99406082494977e-05 -2.67617898148688e-06 5.98999315694112e-06 9.39856998734362e-06 4.74725841406549e-06 -4.56234707295106e-06 -2.67617898148688e-06 3.94284284270241e-05 3.508119702784e-06 1.87327129783716e-05 2.00282999443388e-05 -1.07803747476565e-06 5.98999315694112e-06 3.508119702784e-06 7.05904192114501e-05 1979 1982 0 16 16 1975 2014 0 35 11 0 0 0 0 0 17 47 0 624 0 15 18 0 0 2265 +366 396 0.999993535725272 8.37641346892348e-05 0.00359464758191713 -0.00434689767042077 -8.5948786310252e-05 0.999999811716842 0.000607601091915947 0.00253446407687659 -0.00359459600992583 -0.000607906119812443 0.999993354642757 -0.00486507824566507 3.11167786949584e-05 1.98662741521715e-05 -1.16150956272245e-06 -3.69920642825546e-06 3.53365789857011e-06 1.93479836721196e-05 1.98662741521715e-05 3.66584643571737e-05 -1.87487733465634e-06 3.59981243228685e-06 2.44588645212327e-06 1.17994108007569e-05 -1.16150956272245e-06 -1.87487733465634e-06 1.1201113990303e-05 3.88946369359145e-06 2.73706397885533e-06 -2.52432957881494e-06 -3.69920642825546e-06 3.59981243228685e-06 3.88946369359145e-06 5.19049436293312e-05 -1.51992917359267e-05 -3.79029574413841e-06 3.53365789857011e-06 2.44588645212327e-06 2.73706397885533e-06 -1.51992917359267e-05 5.52629218282355e-05 9.65964490913095e-06 1.93479836721196e-05 1.17994108007569e-05 -2.52432957881494e-06 -3.79029574413841e-06 9.65964490913095e-06 7.40671236481657e-05 1390 1373 0 17 42 1347 1375 0 47 9 0 0 0 0 0 17 47 0 467 0 88 81 0 0 2548 +366 410 0.999996717477948 4.08395165504413e-05 0.00256190660695185 -0.00878173553300283 -4.51062263412329e-05 0.999998612190727 0.00166540747211123 0.010112481021171 -0.00256183503707808 -0.00166551756331376 0.999995331515347 -0.0060956720265412 3.41001852203577e-05 2.30275656394988e-05 -1.36494909320877e-06 5.12035970736459e-06 1.216793095495e-06 1.4580646326719e-05 2.30275656394988e-05 3.70548588976089e-05 -2.44494685822843e-06 8.78461612948481e-06 3.82119455799802e-07 1.43924687130328e-05 -1.36494909320877e-06 -2.44494685822843e-06 9.48062614827388e-06 3.3607833561663e-06 3.86046188883471e-06 -4.788426052591e-07 5.12035970736459e-06 8.78461612948481e-06 3.3607833561663e-06 3.89566789773809e-05 -1.03414548621896e-05 3.19367497923127e-06 1.216793095495e-06 3.82119455799802e-07 3.86046188883471e-06 -1.03414548621896e-05 3.71221180257827e-05 5.13367665751501e-06 1.4580646326719e-05 1.43924687130328e-05 -4.788426052591e-07 3.19367497923127e-06 5.13367665751501e-06 5.81689992970943e-05 1964 1960 0 17 9 1956 1985 0 42 7 0 0 0 0 0 19 48 0 506 0 36 40 0 0 2326 +366 403 0.999980798547693 0.000415604887671518 0.0061830258365446 2.79650138362846e-05 -0.000430933246228777 0.999996836957147 0.00247797744893719 0.00815327456782571 -0.0061819764198296 -0.00248059433956664 0.999977814663539 0.00159146794437873 4.07589542092898e-05 2.88053815987456e-05 -1.54950500810526e-06 7.28665510321228e-06 -4.19957022574656e-06 2.40443982877093e-05 2.88053815987456e-05 4.40857389518447e-05 -2.34370462400492e-06 9.99097726910666e-06 -5.16213352147242e-06 2.73825935380262e-05 -1.54950500810526e-06 -2.34370462400492e-06 9.37924294669764e-06 3.65549611875269e-06 3.45946302475686e-06 -3.29485785860056e-07 7.28665510321228e-06 9.99097726910666e-06 3.65549611875269e-06 3.70703444825769e-05 -1.09525003530601e-05 1.5304128995506e-05 -4.19957022574656e-06 -5.16213352147242e-06 3.45946302475686e-06 -1.09525003530601e-05 3.51453252617871e-05 -3.09507950934317e-06 2.40443982877093e-05 2.73825935380262e-05 -3.29485785860056e-07 1.5304128995506e-05 -3.09507950934317e-06 6.53720885779704e-05 2114 2108 0 16 28 2104 2130 0 38 19 0 0 0 0 0 19 49 0 445 0 28 22 0 0 2411 +366 402 0.999997174313493 4.69964221488745e-06 0.00237725533812513 -0.00359648671641052 -6.52709589289235e-06 0.999999704515732 0.000768717013204686 0.00646520446096689 -0.00237725102298865 -0.000768730357624948 0.999996878860735 -0.00456798082870341 2.80944441621029e-05 1.8857474056529e-05 -1.32943220931797e-06 4.75696797710955e-06 -2.57035925971516e-06 1.84959977573776e-05 1.8857474056529e-05 2.5665755524886e-05 -3.70493700255015e-06 3.95556210329612e-06 -9.23598071317109e-07 1.79239639097048e-05 -1.32943220931797e-06 -3.70493700255015e-06 9.85962128281142e-06 3.71335741240913e-06 3.88694871585748e-06 -3.48893484165229e-08 4.75696797710955e-06 3.95556210329612e-06 3.71335741240913e-06 2.68577933058234e-05 -5.15827933496094e-06 6.65366534432871e-06 -2.57035925971516e-06 -9.23598071317109e-07 3.88694871585748e-06 -5.15827933496094e-06 3.2382907119811e-05 6.45296331623624e-07 1.84959977573776e-05 1.79239639097048e-05 -3.48893484165229e-08 6.65366534432871e-06 6.45296331623624e-07 6.17535614744498e-05 2534 2524 0 21 39 2509 2562 0 47 27 0 0 0 0 0 18 49 0 472 0 35 27 0 0 2445 +366 427 0.99999606690383 6.34081228378274e-05 0.00280395368725802 -0.00562463301377912 -7.19840130603225e-05 0.999995320174544 0.0030585040973993 0.00851049762730575 -0.00280374663124067 -0.00305869390784739 0.999991391661151 -0.00764820244840211 4.17415342067908e-05 8.31680207994542e-06 -1.06115069799621e-05 -2.50544085714919e-06 8.24929565157332e-06 1.72671288770256e-05 8.31680207994542e-06 2.54828272916927e-05 -8.58694749925836e-06 5.36212785734652e-06 4.94623744349209e-06 7.08510960518349e-06 -1.06115069799621e-05 -8.58694749925836e-06 1.52129627411266e-05 9.63615325872879e-07 -4.21551078814889e-06 -3.31117576094538e-06 -2.50544085714919e-06 5.36212785734652e-06 9.63615325872879e-07 3.75338954356273e-05 -4.62711297778167e-06 2.53312859393256e-06 8.24929565157332e-06 4.94623744349209e-06 -4.21551078814889e-06 -4.62711297778167e-06 4.3584181407555e-05 1.1901398738375e-06 1.72671288770256e-05 7.08510960518349e-06 -3.31117576094538e-06 2.53312859393256e-06 1.1901398738375e-06 5.0220495868865e-05 2465 2463 0 17 17 2454 2504 0 47 14 0 0 0 0 0 19 48 0 655 0 17 18 0 0 2348 +366 411 0.999995272627413 -9.36607485959069e-05 0.00307342650643168 -0.00388935562634737 7.76178780325099e-05 0.999986374945246 0.00521956888366367 0.00568099225367485 -0.00307387349955624 -0.0052193056559731 0.999981654906818 -0.00988712128741484 5.74760444790327e-05 3.82065296318452e-05 -3.89737338198574e-06 1.4160748334346e-05 -1.05146876407309e-05 3.90545096935914e-05 3.82065296318452e-05 5.70215966158536e-05 -3.90570744414706e-06 2.17140337658314e-05 -7.01020773481124e-06 4.26864263322767e-05 -3.89737338198574e-06 -3.90570744414706e-06 1.15733948459065e-05 1.68677600057535e-06 3.99162211326244e-06 -4.03142610214593e-07 1.4160748334346e-05 2.17140337658314e-05 1.68677600057535e-06 4.48309014836907e-05 -1.48700842202822e-05 1.90335823578194e-05 -1.05146876407309e-05 -7.01020773481124e-06 3.99162211326244e-06 -1.48700842202822e-05 3.96107605611292e-05 -1.32922706384115e-05 3.90545096935914e-05 4.26864263322767e-05 -4.03142610214593e-07 1.90335823578194e-05 -1.32922706384115e-05 8.07793910764916e-05 2032 2036 0 18 11 2024 2057 0 47 9 0 0 0 0 0 17 47 0 547 0 10 12 0 0 2228 +366 404 0.999995204300567 0.00113687890732154 0.00288077805763328 -0.00864265466155689 -0.00114381636153944 0.99999644736087 0.00240768556277255 0.0138791295724641 -0.00287803057633665 -0.00241096909731255 0.99999295205917 0.00183771357441755 2.06295450234151e-05 9.86991260470399e-06 -8.9336013592119e-08 -1.02577748750573e-06 7.83172782949151e-07 6.87360161318817e-06 9.86991260470399e-06 2.47968036918383e-05 -9.7881988276284e-07 4.22601121753382e-06 1.91097171682626e-06 3.78854045944217e-06 -8.9336013592119e-08 -9.7881988276284e-07 1.15317423655367e-05 2.81110665675093e-06 3.59310938685155e-06 8.58571974374034e-07 -1.02577748750573e-06 4.22601121753382e-06 2.81110665675093e-06 3.83556609008031e-05 1.41285772028248e-06 2.30587822103068e-06 7.83172782949151e-07 1.91097171682626e-06 3.59310938685155e-06 1.41285772028248e-06 3.3446807719148e-05 9.8438486092945e-06 6.87360161318817e-06 3.78854045944217e-06 8.58571974374034e-07 2.30587822103068e-06 9.8438486092945e-06 5.6097493497901e-05 1886 1883 0 17 21 1854 1885 0 46 11 0 0 0 0 0 19 47 0 444 0 52 62 0 0 2326 +366 393 0.999988768890422 0.000797656507419012 0.00467181304356193 -0.00120538161676948 -0.000802969503322438 0.999999032962408 0.00113547973330931 0.00595758855694649 -0.00467090280294478 -0.0011392183040112 0.999988442357541 -0.00235918189506061 4.52500583725248e-05 2.56143197778318e-05 -7.72138111793674e-08 7.68386012187899e-06 -1.01595418324663e-05 2.58307541564858e-05 2.56143197778318e-05 3.35223779892254e-05 -6.38809243266815e-07 1.22938779008576e-05 -5.22203287051691e-06 1.81687673560237e-05 -7.72138111793674e-08 -6.38809243266815e-07 9.90490694735795e-06 1.99525829106165e-06 2.19746781558026e-06 -1.76654432269643e-06 7.68386012187899e-06 1.22938779008576e-05 1.99525829106165e-06 4.27659342667475e-05 -1.46615679275543e-05 5.33125047280481e-06 -1.01595418324663e-05 -5.22203287051691e-06 2.19746781558026e-06 -1.46615679275543e-05 4.57085154375152e-05 3.02251617282157e-06 2.58307541564858e-05 1.81687673560237e-05 -1.76654432269643e-06 5.33125047280481e-06 3.02251617282157e-06 5.86430407951202e-05 2158 2138 0 17 48 2133 2155 0 39 28 0 0 0 0 0 17 49 0 458 0 50 30 0 0 2351 +366 421 0.999993447083145 0.000756608587532045 0.00354024493717938 -0.0040100413144783 -0.000760939110163719 0.999998963794645 0.00122203981351349 0.00760269141636984 -0.00353931666294141 -0.00122472571642045 0.999992986617646 -0.00928609219611498 5.18204210930478e-05 3.70868149222704e-05 -9.27055921188497e-06 1.23263665268144e-05 7.56985120607647e-06 3.02917839758404e-05 3.70868149222704e-05 4.87742904448352e-05 -1.06445923331767e-05 2.02550063409286e-05 6.78644383756622e-06 2.92950588833427e-05 -9.27055921188497e-06 -1.06445923331767e-05 1.5914465030175e-05 4.02341660123604e-07 -2.22390541330718e-06 -4.06519940982898e-06 1.23263665268144e-05 2.02550063409286e-05 4.02341660123604e-07 5.09269173831557e-05 -4.88631284893566e-06 1.0471714533302e-05 7.56985120607647e-06 6.78644383756622e-06 -2.22390541330718e-06 -4.88631284893566e-06 4.45645255368491e-05 6.85954632243646e-06 3.02917839758404e-05 2.92950588833427e-05 -4.06519940982898e-06 1.0471714533302e-05 6.85954632243646e-06 6.67678761324606e-05 1532 1534 0 17 14 1526 1548 0 33 8 0 0 0 0 0 13 44 0 625 0 14 16 0 0 2296 +366 423 0.999997649357586 0.000212453338274614 0.00215780974154886 -0.00376464228494167 -0.000216793649796907 0.999997953616251 0.00201140841818988 0.00382368161443482 -0.00215737799540899 -0.00201187148953738 0.999995649037182 -0.0113256878390631 3.05578829337188e-05 2.07292805608135e-05 -8.73029767977069e-06 1.14362451547018e-05 3.58083322763493e-06 1.40947793122192e-05 2.07292805608135e-05 2.93709721494694e-05 -9.24818370170102e-06 1.45488990792501e-05 3.03170884828816e-06 1.45657889774809e-05 -8.73029767977069e-06 -9.24818370170102e-06 1.36347003297475e-05 -7.48366110623544e-07 -4.76898252566574e-07 -1.04652556314186e-06 1.14362451547018e-05 1.45488990792501e-05 -7.48366110623544e-07 4.5603039792515e-05 -3.15830819937679e-06 7.04010798108615e-06 3.58083322763493e-06 3.03170884828816e-06 -4.76898252566574e-07 -3.15830819937679e-06 3.56449973327152e-05 -3.87675220828941e-06 1.40947793122192e-05 1.45657889774809e-05 -1.04652556314186e-06 7.04010798108615e-06 -3.87675220828941e-06 5.05386387488141e-05 2098 2094 0 16 12 2093 2116 0 39 12 0 0 0 0 0 12 44 0 620 0 11 13 0 0 2204 +366 420 0.999997291082391 0.000134716449957112 0.00232372101542894 -0.00206370547686466 -0.0001342657746334 0.999999972148859 -0.000194100446495997 0.00462000098632898 -0.00232374709923374 0.000193787924491711 0.999997281319134 -0.0091614709474996 4.39344819719606e-05 1.72171218562962e-05 -7.87104404109711e-06 7.4273575395126e-06 2.84262097813378e-07 1.79051903116406e-05 1.72171218562962e-05 3.24249480054042e-05 -8.54038363823293e-06 1.18222919583448e-05 4.75080311531224e-06 1.64646672388912e-05 -7.87104404109711e-06 -8.54038363823293e-06 1.20875082926144e-05 -2.90564590605773e-06 2.49867736845352e-07 -2.29086648759024e-06 7.4273575395126e-06 1.18222919583448e-05 -2.90564590605773e-06 4.19140560356258e-05 -8.73366001478969e-06 4.41782529226723e-06 2.84262097813378e-07 4.75080311531224e-06 2.49867736845352e-07 -8.73366001478969e-06 4.23705927459631e-05 1.99205776961637e-07 1.79051903116406e-05 1.64646672388912e-05 -2.29086648759024e-06 4.41782529226723e-06 1.99205776961637e-07 5.67763179567235e-05 2056 2052 0 11 11 2049 2078 0 49 9 0 0 0 0 0 7 38 0 629 0 11 14 0 0 2235 +366 425 0.99999820042653 -4.37060597098078e-05 0.00189663741443785 -0.00991910412790581 3.95732714247766e-05 0.99999762521344 0.00217899092152113 0.00909001078165263 -0.00189672814543613 -0.00217891194411968 0.999995827373836 -0.0106121567262171 3.28063362580929e-05 1.98650573016619e-05 -6.5940190126816e-06 1.79715880649636e-06 6.30627814978104e-06 8.35292201615269e-06 1.98650573016619e-05 3.72253769277186e-05 -6.77789448434293e-06 1.071316167954e-05 4.79338291296065e-06 1.32847834603684e-05 -6.5940190126816e-06 -6.77789448434293e-06 1.28636337732133e-05 1.50905093570725e-07 1.20154334779346e-07 -2.66632459627247e-06 1.79715880649636e-06 1.071316167954e-05 1.50905093570725e-07 3.6703092933533e-05 9.94637721636383e-07 7.49730848323595e-06 6.30627814978104e-06 4.79338291296065e-06 1.20154334779346e-07 9.94637721636383e-07 2.86673995371418e-05 5.66202472018263e-06 8.35292201615269e-06 1.32847834603684e-05 -2.66632459627247e-06 7.49730848323595e-06 5.66202472018263e-06 7.13179089378011e-05 1929 1925 0 18 16 1907 1932 0 38 6 0 0 0 0 0 18 48 0 618 0 46 57 0 0 2108 +367 370 0.999999582569926 0.000866120570122373 -0.000291024279545799 -0.00618903291944876 -0.000866356358882586 0.999999295807039 -0.000811056154462117 0.00265760466968758 0.000290321602189646 0.00081130794663806 0.999999628746323 0.00169487621183484 2.66533459226353e-05 1.66507202778368e-05 -9.68444521266207e-06 7.46126257030394e-06 8.81241879851441e-06 2.27788021689298e-05 1.66507202778368e-05 2.28912193838253e-05 -1.21070889242787e-05 3.35906908579884e-06 8.80028559393185e-06 1.89261361563695e-05 -9.68444521266207e-06 -1.21070889242787e-05 1.76260740974277e-05 5.39470413695628e-07 -3.35489777251963e-06 -7.18501551028196e-06 7.46126257030394e-06 3.35906908579884e-06 5.39470413695628e-07 3.00085177664882e-05 1.0304534146799e-05 8.42829381194269e-06 8.81241879851441e-06 8.80028559393185e-06 -3.35489777251963e-06 1.0304534146799e-05 3.74947115928234e-05 8.94109714346128e-06 2.27788021689298e-05 1.89261361563695e-05 -7.18501551028196e-06 8.42829381194269e-06 8.94109714346128e-06 5.40748530674812e-05 2070 2049 0 19 56 2047 2099 0 45 30 0 0 0 0 0 15 45 0 637 0 55 33 0 0 2250 +367 371 0.999987579326582 0.00103074924931144 -0.00487634581919439 -0.0147310082866765 -0.00103611557955837 0.999998860337733 -0.0010980836672094 0.00507033405812083 0.0048752084128914 0.00110312248614537 0.999987507653826 -0.00358002654064804 3.03683952135901e-05 2.13923507657729e-05 -8.58702630612602e-06 6.3246870093403e-06 8.90750446632283e-06 1.77708296745727e-05 2.13923507657729e-05 2.82423375452096e-05 -1.07740169494347e-05 5.35017132601407e-06 1.15947468359269e-05 2.24718399071156e-05 -8.58702630612602e-06 -1.07740169494347e-05 1.44271970404327e-05 3.9209713809971e-07 -3.22299162571563e-06 -5.85883231843264e-06 6.3246870093403e-06 5.35017132601407e-06 3.9209713809971e-07 3.44283912796909e-05 2.22602331210328e-06 4.06865846543855e-06 8.90750446632283e-06 1.15947468359269e-05 -3.22299162571563e-06 2.22602331210328e-06 4.41554332667635e-05 1.49742026850465e-05 1.77708296745727e-05 2.24718399071156e-05 -5.85883231843264e-06 4.06865846543855e-06 1.49742026850465e-05 4.32877141378936e-05 2940 2920 0 20 56 2905 2940 0 43 26 0 0 0 0 0 18 48 0 646 0 100 88 0 0 2474 +366 422 0.999998801018368 0.000329011555369005 -0.00151317983831117 -0.010957745003469 -0.000323348230236032 0.999992948706078 0.00374138798379643 0.0122573501665766 0.00151440012831516 -0.00374089421391821 0.999991856118204 -0.0109601024818736 5.98995203417126e-05 4.07116025527109e-05 -8.6893707209711e-06 6.42656942280061e-06 3.06855434601976e-06 4.78567363141807e-05 4.07116025527109e-05 4.76139793906897e-05 -9.51221415539126e-06 1.23147828331536e-05 -1.71979302064408e-06 3.460120577594e-05 -8.6893707209711e-06 -9.51221415539126e-06 1.23552659565222e-05 2.5298476939503e-08 -1.63647892407762e-06 -2.982199571066e-06 6.42656942280061e-06 1.23147828331536e-05 2.5298476939503e-08 4.5923137844909e-05 -1.20530116381089e-05 5.01640051356436e-06 3.06855434601976e-06 -1.71979302064408e-06 -1.63647892407762e-06 -1.20530116381089e-05 4.23761508972495e-05 -4.17912504817095e-06 4.78567363141807e-05 3.460120577594e-05 -2.982199571066e-06 5.01640051356436e-06 -4.17912504817095e-06 8.70632768766263e-05 2216 2214 0 14 14 2213 2233 0 30 14 0 0 0 0 0 18 51 0 595 0 55 57 0 0 2245 +367 407 0.999998456243083 0.000564813556238823 0.00166388013326348 -0.00873919339237339 -0.000565462040143684 0.999999764350113 0.000389297314286955 0.00632464444028027 -0.0016636598607698 -0.000390237574361243 0.999998539974186 -0.00625354187133595 1.97906794782023e-05 1.31684975296049e-05 -2.3635500881579e-06 -9.21721931613334e-07 1.22075463258902e-06 7.68168181935228e-06 1.31684975296049e-05 2.46235959826911e-05 -4.39160853613384e-06 4.33648483454563e-06 8.14034343839524e-07 3.08022083398513e-07 -2.3635500881579e-06 -4.39160853613384e-06 1.12058091776652e-05 1.89017566397027e-06 2.83966954978835e-06 -1.38721947115382e-06 -9.21721931613334e-07 4.33648483454563e-06 1.89017566397027e-06 4.42089906576884e-05 -4.10376850984419e-06 -2.1060611670684e-06 1.22075463258902e-06 8.14034343839524e-07 2.83966954978835e-06 -4.10376850984419e-06 2.86691438740739e-05 2.44015645959395e-06 7.68168181935228e-06 3.08022083398513e-07 -1.38721947115382e-06 -2.1060611670684e-06 2.44015645959395e-06 4.30388762424401e-05 2204 2201 0 16 17 2189 2216 0 42 9 0 0 0 0 0 20 48 0 485 0 45 49 0 0 2327 +366 394 0.99999383831388 -0.000111950041632619 0.00350867517193533 -0.00377357293833927 0.000103317174242216 0.99999696757949 0.00246051973914634 0.00457814617674378 -0.003508939987444 -0.00246014207179192 0.999990817478416 -0.00386129481177855 3.13258953467218e-05 6.08071144347272e-06 -7.41337178476463e-07 -5.11404548245655e-06 -2.50207374892815e-06 3.80444280994939e-06 6.08071144347272e-06 3.08975567026983e-05 2.53799109534619e-07 7.7441468633317e-06 3.56351795526306e-06 2.73915799708877e-06 -7.41337178476463e-07 2.53799109534619e-07 1.13070391962471e-05 5.14931302864255e-06 1.63231111576591e-06 -1.16399869139105e-07 -5.11404548245655e-06 7.7441468633317e-06 5.14931302864255e-06 4.32633248285573e-05 -8.41667216096436e-06 -4.69006496710888e-06 -2.50207374892815e-06 3.56351795526306e-06 1.63231111576591e-06 -8.41667216096436e-06 4.29547479062628e-05 6.78921912959639e-06 3.80444280994939e-06 2.73915799708877e-06 -1.16399869139105e-07 -4.69006496710888e-06 6.78921912959639e-06 6.24003470435464e-05 1878 1863 0 16 42 1824 1841 0 32 3 0 0 0 0 0 15 48 0 464 0 85 77 0 0 2403 +367 401 0.999995451075039 0.000275303593390245 0.00300367061463679 0.00213647166367976 -0.000280209667205713 0.999998627296358 0.00163306091189265 -0.00726156257118032 -0.00300321690394993 -0.00163389514076443 0.999994155520369 -0.0102325582787649 3.83358093007543e-05 2.41546653489228e-05 -3.48453887179636e-06 -1.59957266549735e-06 3.63655547918116e-06 3.02309867537445e-05 2.41546653489228e-05 3.45359114344222e-05 -3.23942606614155e-06 6.64781609656091e-06 -1.59585591577875e-06 2.07539390060387e-05 -3.48453887179636e-06 -3.23942606614155e-06 1.22760849355371e-05 6.30683034426872e-06 1.96011530886856e-06 -9.27296872607383e-07 -1.59957266549735e-06 6.64781609656091e-06 6.30683034426872e-06 5.26353827039218e-05 -2.61920023065873e-05 -5.5759056180585e-06 3.63655547918116e-06 -1.59585591577875e-06 1.96011530886856e-06 -2.61920023065873e-05 7.0312396954872e-05 9.49827187463461e-06 3.02309867537445e-05 2.07539390060387e-05 -9.27296872607383e-07 -5.5759056180585e-06 9.49827187463461e-06 7.04876640371809e-05 1282 1266 0 15 36 1248 1278 0 46 7 0 0 0 0 0 15 46 0 506 0 65 54 0 0 2520 +366 412 0.999993394309131 9.98873551724739e-05 0.00363336766922817 -0.00386133135219374 -0.00010866869136319 0.99999707377139 0.00241674156087693 0.00596274812041681 -0.00363311563524109 -0.00241712042993913 0.999990478954479 -0.0108767723604118 3.4409911148177e-05 1.91803590295336e-05 -5.17489603426654e-06 4.13497568159372e-06 4.23014262238959e-07 2.01776189273993e-05 1.91803590295336e-05 3.40531590593777e-05 -6.20917018718298e-06 1.2325314009253e-05 1.70528554022343e-06 2.04413127826242e-05 -5.17489603426654e-06 -6.20917018718298e-06 1.19099991473924e-05 2.30765946557492e-06 8.84549198387118e-07 -2.26125857955356e-06 4.13497568159372e-06 1.2325314009253e-05 2.30765946557492e-06 4.55858029697862e-05 -1.72117605979849e-05 1.0364848559171e-05 4.23014262238959e-07 1.70528554022343e-06 8.84549198387118e-07 -1.72117605979849e-05 4.37019598601432e-05 -2.87878171536502e-06 2.01776189273993e-05 2.04413127826242e-05 -2.26125857955356e-06 1.0364848559171e-05 -2.87878171536502e-06 5.75814654717398e-05 2103 2099 0 16 9 2093 2122 0 41 6 0 0 0 0 0 21 53 0 568 0 9 11 0 0 2215 +367 408 0.999996563286293 0.000511838201846121 0.00257127152539975 -0.00253486539195611 -0.000517042422225569 0.999997818589113 0.00202373025590342 0.00759182215792305 -0.00257023009394485 -0.0020250527573796 0.999994646524967 -0.00567595740482285 2.58858974820012e-05 1.68137554316147e-05 -1.10928517351618e-06 -1.74749654858298e-07 -1.6091103601857e-06 1.41258954716382e-05 1.68137554316147e-05 2.89130864951104e-05 -2.77685258824314e-06 5.16939434542617e-06 -1.82633771072639e-06 1.17882964598161e-05 -1.10928517351618e-06 -2.77685258824314e-06 1.1860958694602e-05 2.33782143811123e-06 2.85272515500186e-06 1.73312084584034e-06 -1.74749654858298e-07 5.16939434542617e-06 2.33782143811123e-06 3.24170191007415e-05 -5.39428268273933e-06 -3.29642624753788e-06 -1.6091103601857e-06 -1.82633771072639e-06 2.85272515500186e-06 -5.39428268273933e-06 3.23462741627139e-05 -2.17723572536573e-07 1.41258954716382e-05 1.17882964598161e-05 1.73312084584034e-06 -3.29642624753788e-06 -2.17723572536573e-07 5.119214937522e-05 1450 1459 0 15 15 1446 1483 0 42 10 0 0 0 0 0 18 49 0 490 0 49 57 0 0 2352 +366 395 0.999994774442316 -0.000240004234787127 0.00322389299271647 -0.00332740405452723 0.000233672850813213 0.999998043798982 0.00196412708568559 0.00889386250982216 -0.00322435808495194 -0.00196336348575988 0.999992874333994 -0.00084199454503995 3.06127302469931e-05 1.90153043273272e-05 -1.38726798026928e-06 2.39229211807589e-06 -1.09749233050813e-06 1.78258212860018e-05 1.90153043273272e-05 3.26448706242177e-05 -1.81789177679777e-06 4.87267718363833e-06 7.03767588175025e-07 1.55257102676212e-05 -1.38726798026928e-06 -1.81789177679777e-06 9.53928480582351e-06 2.15754442450743e-06 2.68356381519283e-06 -2.85223621813171e-06 2.39229211807589e-06 4.87267718363833e-06 2.15754442450743e-06 4.10665054454834e-05 -1.27732673487458e-05 3.62648239015155e-06 -1.09749233050813e-06 7.03767588175025e-07 2.68356381519283e-06 -1.27732673487458e-05 3.58287130149688e-05 5.43023381349253e-06 1.78258212860018e-05 1.55257102676212e-05 -2.85223621813171e-06 3.62648239015155e-06 5.43023381349253e-06 5.80951547701872e-05 2237 2219 0 17 49 2212 2242 0 46 24 0 0 0 0 0 18 49 0 462 0 91 76 0 0 2431 +366 424 0.999996267969049 0.000526578253993855 0.00268081392781609 -0.00968148856557706 -0.000527999385112669 0.999999720459336 0.000529431675236864 0.00841440665578832 -0.00268053439121243 -0.000530845167486954 0.999996266462423 -0.00820815253280663 3.3882905965301e-05 1.85410503539978e-05 -7.63932756615808e-06 2.96664803053264e-06 9.72513730536858e-06 1.69054739009093e-05 1.85410503539978e-05 2.91992612172391e-05 -8.57865370983775e-06 9.67765624020613e-06 7.18956727719746e-06 6.24550973471755e-06 -7.63932756615808e-06 -8.57865370983775e-06 1.37075635502582e-05 2.34143949289528e-06 -7.08764204302857e-07 -3.42135179053271e-06 2.96664803053264e-06 9.67765624020613e-06 2.34143949289528e-06 4.29600438750612e-05 -4.86859118809291e-06 -3.00150541185087e-06 9.72513730536858e-06 7.18956727719746e-06 -7.08764204302857e-07 -4.86859118809291e-06 4.28288735622591e-05 8.23746305988994e-06 1.69054739009093e-05 6.24550973471755e-06 -3.42135179053271e-06 -3.00150541185087e-06 8.23746305988994e-06 5.65046179818058e-05 1370 1373 0 15 14 1360 1392 0 49 5 0 0 0 0 0 22 52 0 626 0 45 55 0 0 2210 +366 413 0.999997716772999 0.000141924910017184 0.00213220686373524 -0.00759142621304247 -0.000142694479583983 0.999999924738568 0.000360778523634684 0.00422264375260652 -0.0021321554998028 -0.000361081954044204 0.99999766176364 -0.00698293299829155 5.48322672204467e-05 4.04107402716314e-05 -1.00983861659473e-05 6.50599530441553e-06 8.15348942048517e-06 3.97543183160455e-05 4.04107402716314e-05 5.66472654311874e-05 -9.02879608358658e-06 1.34523551958828e-05 9.49307475701419e-06 3.03071157445072e-05 -1.00983861659473e-05 -9.02879608358658e-06 1.30129590257724e-05 2.46687857184301e-06 -1.97207537808746e-06 -6.13491848744661e-06 6.50599530441553e-06 1.34523551958828e-05 2.46687857184301e-06 4.01646658444294e-05 -8.60463703183209e-07 1.00457424923708e-05 8.15348942048517e-06 9.49307475701419e-06 -1.97207537808746e-06 -8.60463703183209e-07 4.38794173836563e-05 1.21477550390936e-05 3.97543183160455e-05 3.03071157445072e-05 -6.13491848744661e-06 1.00457424923708e-05 1.21477550390936e-05 9.26293299750015e-05 1853 1854 0 13 11 1849 1872 0 39 10 0 0 0 0 0 17 49 0 601 0 39 47 0 0 2313 +367 369 0.999998466791295 0.00060574646016659 0.00164301134660764 -0.000346418389117438 -0.000607339990001598 0.999999345547323 0.000969558178481024 0.0028167687431913 -0.00164242296489993 -0.000970554558440806 0.999998180233671 -0.000625705673677833 2.86130263599268e-05 1.23070444294895e-05 -5.1804076300149e-06 5.61216788223747e-06 2.43247536238173e-06 1.54938067693172e-05 1.23070444294895e-05 2.57177712078124e-05 -7.75016173154014e-06 3.18813043676624e-06 6.35228980445556e-06 1.5988437372037e-05 -5.1804076300149e-06 -7.75016173154014e-06 1.55400513831092e-05 9.53374626130374e-07 -4.89861019264814e-06 -3.27303720961054e-06 5.61216788223747e-06 3.18813043676624e-06 9.53374626130374e-07 2.86013594590553e-05 2.28178956990017e-06 5.60937681892002e-06 2.43247536238173e-06 6.35228980445556e-06 -4.89861019264814e-06 2.28178956990017e-06 4.10312397565873e-05 5.44354032097546e-06 1.54938067693172e-05 1.5988437372037e-05 -3.27303720961054e-06 5.60937681892002e-06 5.44354032097546e-06 4.11417119181914e-05 1842 1823 0 24 53 1816 1843 0 46 28 0 0 0 0 0 12 44 0 639 0 57 35 0 0 2352 +367 406 0.999996517170759 0.000837574805969848 0.00250282136709222 -0.00625713817221943 -0.000841757347581153 0.99999825036069 0.00167054485908606 0.00998341218888766 -0.00250141778177135 -0.00167264580913901 0.99999547257229 -0.00402062271959951 1.97351033635345e-05 1.22736215809575e-05 -1.77889727509104e-06 6.68081094226464e-07 7.08691357470976e-07 1.13830681702725e-05 1.22736215809575e-05 1.87907412167289e-05 -1.98599879401252e-06 4.43449203739766e-06 -5.09775350707139e-06 5.60459393156109e-06 -1.77889727509104e-06 -1.98599879401252e-06 1.13737115363716e-05 4.48062934156085e-06 4.68188890094595e-07 3.95875364910282e-07 6.68081094226464e-07 4.43449203739766e-06 4.48062934156085e-06 3.4088165956218e-05 -1.24203804526008e-05 -2.01006367079792e-06 7.08691357470976e-07 -5.09775350707139e-06 4.68188890094595e-07 -1.24203804526008e-05 3.8847817253935e-05 -2.18040226752019e-06 1.13830681702725e-05 5.60459393156109e-06 3.95875364910282e-07 -2.01006367079792e-06 -2.18040226752019e-06 4.40729383718255e-05 2554 2553 0 12 17 2555 2595 0 42 14 0 0 0 0 0 19 50 0 461 0 21 23 0 0 2394 +366 426 0.999997418412983 0.000314302131150517 0.0022504180809557 -0.0062188062119558 -0.000318803384308394 0.999997948968024 0.00200010603407925 0.00850576612446115 -0.00224978482768722 -0.0020008183115318 0.999995467586885 -0.0075641307523048 2.26623047817908e-05 1.52434653307483e-05 -9.47922946705876e-06 7.08682430984672e-06 6.72147668988435e-06 1.20977674799605e-05 1.52434653307483e-05 2.51249471331589e-05 -9.34659247689676e-06 7.24350224782601e-06 4.99800919037675e-06 7.33581162001802e-06 -9.47922946705876e-06 -9.34659247689676e-06 1.68841258886757e-05 -1.95031408870306e-06 -3.66051610216341e-06 -4.50191954480391e-06 7.08682430984672e-06 7.24350224782601e-06 -1.95031408870306e-06 4.73484430586318e-05 -4.65515247087387e-06 2.49955217787985e-06 6.72147668988435e-06 4.99800919037675e-06 -3.66051610216341e-06 -4.65515247087387e-06 4.95491181360731e-05 3.00047875416559e-06 1.20977674799605e-05 7.33581162001802e-06 -4.50191954480391e-06 2.49955217787985e-06 3.00047875416559e-06 4.77165247898714e-05 1574 1574 0 18 17 1566 1596 0 52 16 0 0 0 0 0 15 43 0 648 0 15 17 0 0 2128 +367 399 0.99999908224832 9.88066890444345e-05 0.00135119937695153 0.00433561120992588 -9.84221665454429e-05 0.99999995464595 -0.000284642186325294 -0.00747579077245496 -0.00135122744022116 0.000284508937124334 0.99999904661908 -0.00861971077786356 3.75697250343495e-05 2.59166713799886e-05 -5.2136873395018e-06 7.30408961869788e-06 -1.14145055783964e-06 1.87719647361045e-05 2.59166713799886e-05 3.4595972336656e-05 -5.99220598117029e-06 1.16261043872972e-05 -1.57176958053273e-06 2.43117398266852e-05 -5.2136873395018e-06 -5.99220598117029e-06 1.10998117461289e-05 3.05383198108102e-06 1.71838256239858e-06 -2.53873156619195e-06 7.30408961869788e-06 1.16261043872972e-05 3.05383198108102e-06 4.23052389716203e-05 -1.74568939463866e-05 1.13582979597441e-05 -1.14145055783964e-06 -1.57176958053273e-06 1.71838256239858e-06 -1.74568939463866e-05 5.27479466117427e-05 -7.00330127245047e-06 1.87719647361045e-05 2.43117398266852e-05 -2.53873156619195e-06 1.13582979597441e-05 -7.00330127245047e-06 5.71673434973762e-05 2496 2481 0 25 44 2470 2500 0 50 27 0 0 0 0 0 9 41 0 478 0 56 43 0 0 2439 +367 400 0.999999653648313 0.000825271983979001 -0.000107839726155901 -0.000646235427646105 -0.000825360399454604 0.999999321200585 -0.000822422384931406 -0.00552366164177046 0.000107160930801077 0.000822511106723483 0.999999655995948 -0.00951195430468763 2.23533806038263e-05 1.42943211514302e-05 -3.79125515273371e-06 2.22495612779e-06 9.44287721829617e-07 1.23028648511583e-05 1.42943211514302e-05 2.17560922084968e-05 -5.55315081124526e-06 4.29603220172927e-07 3.206565372846e-06 8.04452078616902e-06 -3.79125515273371e-06 -5.55315081124526e-06 1.28288031446956e-05 2.80359696351938e-06 1.80000799176346e-06 -3.095200998793e-06 2.22495612779e-06 4.29603220172927e-07 2.80359696351938e-06 5.30157832233053e-05 -2.55771064070802e-05 1.54496106774015e-05 9.44287721829617e-07 3.206565372846e-06 1.80000799176346e-06 -2.55771064070802e-05 6.28808461776366e-05 -1.41873513844071e-06 1.23028648511583e-05 8.04452078616902e-06 -3.095200998793e-06 1.54496106774015e-05 -1.41873513844071e-06 5.38538345861843e-05 2857 2844 0 22 39 2830 2875 0 45 17 0 0 0 0 0 11 44 0 496 0 57 42 0 0 2389 +367 402 0.999997953702664 0.00026161444022609 0.00200602800808776 0.000857730655340557 -0.000264490264232332 0.999998937618238 0.0014334599035183 0.00194208577742707 -0.00200565086310994 -0.00143398754511103 0.999996960517549 -0.00770630569707009 2.05909184594971e-05 1.30987410094491e-05 -1.33046225652448e-06 2.88578326196102e-06 -2.63505680320172e-06 1.13696885272477e-05 1.30987410094491e-05 1.99479129423052e-05 -3.84366949221816e-06 -6.6830416258914e-07 1.96683016389029e-06 4.80762913962259e-06 -1.33046225652448e-06 -3.84366949221816e-06 1.24547912029767e-05 4.99336444646075e-06 4.56333575591391e-06 7.56930548666103e-08 2.88578326196102e-06 -6.6830416258914e-07 4.99336444646075e-06 3.17200532121647e-05 -3.71773118679196e-06 3.63898717819025e-06 -2.63505680320172e-06 1.96683016389029e-06 4.56333575591391e-06 -3.71773118679196e-06 4.01873155217972e-05 -2.81403199836387e-06 1.13696885272477e-05 4.80762913962259e-06 7.56930548666103e-08 3.63898717819025e-06 -2.81403199836387e-06 4.31521019856591e-05 1862 1848 0 17 39 1849 1896 0 46 27 0 0 0 0 0 17 48 0 470 0 36 27 0 0 2383 +367 405 0.999996548183834 0.0006976204203846 0.00253316919404575 -0.00327742496653276 -0.000698118043727128 0.999999737192909 0.000195564081600798 0.00930366456878313 -0.00253303209881411 -0.000197331857671716 0.999996772399053 -0.00216254896305759 3.17397836532865e-05 2.17112977131676e-05 -1.56614363341747e-06 9.06324283778681e-06 -8.52728542751508e-06 1.9465563626922e-05 2.17112977131676e-05 3.37281130391803e-05 -1.55174238974511e-06 9.60290957863576e-06 -5.88453573976075e-06 2.14264298975477e-05 -1.56614363341747e-06 -1.55174238974511e-06 1.14609920764052e-05 3.96302989921319e-06 1.4578098062667e-06 -1.20771905088203e-06 9.06324283778681e-06 9.60290957863576e-06 3.96302989921319e-06 3.44788067987522e-05 -1.19548870876489e-05 1.1335692806078e-05 -8.52728542751508e-06 -5.88453573976075e-06 1.4578098062667e-06 -1.19548870876489e-05 4.2848764024192e-05 -2.55744378396799e-06 1.9465563626922e-05 2.14264298975477e-05 -1.20771905088203e-06 1.1335692806078e-05 -2.55744378396799e-06 5.87936423315126e-05 2495 2499 0 13 19 2488 2519 0 38 13 0 0 0 0 0 19 50 0 452 0 51 59 0 0 2397 +367 428 0.999995055185576 0.0010651015880446 0.00295891246995956 -0.00464539046010393 -0.00106987855380271 0.999998126278321 0.00161331947450615 0.0132417312013897 -0.0029571885766468 -0.00161647717393493 0.999994321002509 -0.00814738074460056 3.00170930949761e-05 1.61986285821031e-05 -9.88440763217851e-06 2.23567987458847e-06 9.7253724539956e-06 1.76932389564443e-05 1.61986285821031e-05 2.42611828583667e-05 -1.03719624507129e-05 6.56298366790806e-06 7.7710610001706e-06 7.12315904840793e-06 -9.88440763217851e-06 -1.03719624507129e-05 1.62718921447075e-05 -2.35253889797271e-10 -5.30764192757109e-06 -4.50350231575532e-06 2.23567987458847e-06 6.56298366790806e-06 -2.35253889797271e-10 3.13497880892623e-05 1.70170474115618e-06 6.0232171869902e-08 9.7253724539956e-06 7.7710610001706e-06 -5.30764192757109e-06 1.70170474115618e-06 5.09125406541068e-05 1.02938849838117e-05 1.76932389564443e-05 7.12315904840793e-06 -4.50350231575532e-06 6.0232171869902e-08 1.02938849838117e-05 4.95798335017969e-05 2458 2461 0 11 16 2456 2502 0 43 11 0 0 0 0 0 14 44 0 622 0 16 19 0 0 2319 +367 429 0.999974284418555 -0.00716330439574194 -0.000342887347561652 -0.0018225354577164 0.0071643192232709 0.999969666054753 0.00305605962205799 0.00365815716541152 0.000320985461111288 -0.00305843758812343 0.999995271452747 -0.010480988650569 2.39553357045199e-05 1.4940698355915e-05 -3.4750791294891e-06 3.08371947856193e-06 1.42287013990908e-06 9.7449103991803e-06 1.4940698355915e-05 2.70882535710653e-05 -6.17408528857002e-06 5.41972600694511e-06 1.76412793535066e-06 5.76097023530456e-06 -3.4750791294891e-06 -6.17408528857002e-06 1.22808057192466e-05 9.79660029440404e-07 1.77027601761587e-06 -1.24677584382104e-06 3.08371947856193e-06 5.41972600694511e-06 9.79660029440404e-07 3.67073605385671e-05 -8.28688852663747e-06 1.2504155259729e-06 1.42287013990908e-06 1.76412793535066e-06 1.77027601761587e-06 -8.28688852663747e-06 4.03261205826685e-05 -1.18629981236989e-06 9.7449103991803e-06 5.76097023530456e-06 -1.24677584382104e-06 1.2504155259729e-06 -1.18629981236989e-06 4.42882354410167e-05 2340 2337 0 7 24 2345 2364 0 36 23 0 0 0 0 0 29 60 0 613 0 15 16 0 0 2419 +367 397 0.999996355131907 0.000290656135896461 0.00268425816774129 0.00143261189002056 -0.000295319551437278 0.999998447656114 0.00173708713800996 -0.00103816741613953 -0.00268374910581429 -0.00173787352047451 0.999994888630119 -0.00765366131850087 2.38729234682957e-05 1.61067833456459e-05 -2.63510127878039e-06 -2.96472592183801e-07 3.85181508403204e-06 1.58386931059883e-05 1.61067833456459e-05 2.40665584605283e-05 -3.55368602343925e-06 6.33869270967515e-06 -7.83687921969048e-07 1.10304954640361e-05 -2.63510127878039e-06 -3.55368602343925e-06 1.14259482188295e-05 2.87746174624788e-06 1.96493531395987e-06 -1.78259617425152e-06 -2.96472592183801e-07 6.33869270967515e-06 2.87746174624788e-06 4.85187888936763e-05 -1.49844020973923e-05 -1.55552865627254e-06 3.85181508403204e-06 -7.83687921969048e-07 1.96493531395987e-06 -1.49844020973923e-05 4.15170627120922e-05 7.96167672896768e-06 1.58386931059883e-05 1.10304954640361e-05 -1.78259617425152e-06 -1.55552865627254e-06 7.96167672896768e-06 5.46160384685964e-05 1458 1443 0 12 45 1439 1467 0 42 25 0 0 0 0 0 18 47 0 461 0 51 35 0 0 2509 +367 403 0.999984908292403 0.000143061230613196 0.0054920598065463 -0.00368265503262155 -0.000155176777466805 0.999997555513958 0.00220564871995754 0.0107983341029791 -0.00549173083846259 -0.00220646767309443 0.999982486043033 0.000829621559534844 2.81834707732043e-05 1.60729761659191e-05 -1.46489931673794e-06 1.15614749877317e-06 -8.03322026612707e-07 1.6066591670103e-05 1.60729761659191e-05 2.71518204799019e-05 -4.04506309594078e-06 3.9825818214786e-06 -1.43782749007425e-06 1.12287757943857e-05 -1.46489931673794e-06 -4.04506309594078e-06 1.19879067442052e-05 2.51361159557578e-06 2.01246108705558e-06 -2.09955322211929e-06 1.15614749877317e-06 3.9825818214786e-06 2.51361159557578e-06 3.97834202730514e-05 -1.69819600457204e-05 3.86241254930943e-06 -8.03322026612707e-07 -1.43782749007425e-06 2.01246108705558e-06 -1.69819600457204e-05 4.7260662154207e-05 7.73909304285105e-06 1.6066591670103e-05 1.12287757943857e-05 -2.09955322211929e-06 3.86241254930943e-06 7.73909304285105e-06 5.17724225468409e-05 2152 2143 0 11 28 2146 2177 0 44 20 0 0 0 0 0 16 45 0 435 0 31 26 0 0 2329 +367 404 0.999981724473168 0.00105539092812168 0.00595288750587906 -0.00189479465594428 -0.0010788788129096 0.999991641201555 0.00394379861640157 0.0112350323486966 -0.00594867549761015 -0.00395014898560986 0.999974504466397 -0.00193888556507542 2.7555666901024e-05 1.29671263003816e-05 2.1733419788231e-07 -2.23776748243253e-06 -2.00705035298549e-06 5.4042017372658e-06 1.29671263003816e-05 3.19406670609845e-05 -6.90805487220688e-07 7.04428409454174e-06 7.14868025544734e-06 2.88509159210802e-06 2.1733419788231e-07 -6.90805487220688e-07 1.2984559522628e-05 1.15700769308594e-06 4.02464383344991e-07 1.24589010799389e-07 -2.23776748243253e-06 7.04428409454174e-06 1.15700769308594e-06 3.56454067347616e-05 4.7876340217141e-06 -7.9987249452412e-07 -2.00705035298549e-06 7.14868025544734e-06 4.02464383344991e-07 4.7876340217141e-06 4.19263942710785e-05 1.0540686651565e-05 5.4042017372658e-06 2.88509159210802e-06 1.24589010799389e-07 -7.9987249452412e-07 1.0540686651565e-05 5.43063002536151e-05 1352 1352 0 16 21 1336 1362 0 42 11 0 0 0 0 0 17 46 0 443 0 47 48 0 0 2329 +367 427 0.999991969235163 7.95051662801436e-05 0.00400688708479334 -0.00116548014838521 -8.7916819474678e-05 0.999997792883148 0.00209916637390296 0.00724273837898257 -0.00400671134655373 -0.00209950178875994 0.999989769125877 -0.00737831422673347 3.72244897466404e-05 1.52283454897682e-05 -7.21943712299249e-06 3.37603115475707e-06 5.27647470885219e-06 2.72721328218792e-05 1.52283454897682e-05 2.54455231622385e-05 -7.93852198636704e-06 5.77245590673765e-06 4.44738194453672e-06 9.5292067439174e-06 -7.21943712299249e-06 -7.93852198636704e-06 1.60910984068355e-05 -1.08269214023966e-06 -3.24450408819042e-06 -3.90148673762277e-06 3.37603115475707e-06 5.77245590673765e-06 -1.08269214023966e-06 3.72355367788155e-05 -2.4618147825192e-06 3.70627046649925e-06 5.27647470885219e-06 4.44738194453672e-06 -3.24450408819042e-06 -2.4618147825192e-06 4.38341183859517e-05 4.34443180028051e-06 2.72721328218792e-05 9.5292067439174e-06 -3.90148673762277e-06 3.70627046649925e-06 4.34443180028051e-06 5.63558960495907e-05 1866 1871 0 18 17 1864 1909 0 44 14 0 0 0 0 0 17 47 0 632 0 19 20 0 0 2358 +367 410 0.999997813492094 0.000195881150831811 0.00208198021273556 -0.00902775645151998 -0.000200238444716307 0.999997789922506 0.00209285801441436 0.0129627514870358 -0.00208156565996156 -0.0020932703308435 0.999995642642369 -0.00555981281364988 2.57569408129241e-05 1.41387491354299e-05 -1.27982029842641e-06 8.4791905739295e-07 -1.00141330489406e-06 1.12107350286157e-05 1.41387491354299e-05 2.96879499895874e-05 -2.41976463037218e-06 4.04270498409855e-06 3.48281207051644e-06 4.68128452685328e-06 -1.27982029842641e-06 -2.41976463037218e-06 1.17164782668679e-05 2.37664853197616e-06 2.7828127182375e-06 -3.51235741003084e-07 8.4791905739295e-07 4.04270498409855e-06 2.37664853197616e-06 3.43653816209191e-05 -8.24476688946662e-06 -1.73889798067439e-06 -1.00141330489406e-06 3.48281207051644e-06 2.7828127182375e-06 -8.24476688946662e-06 4.09909676070497e-05 2.60987971638566e-06 1.12107350286157e-05 4.68128452685328e-06 -3.51235741003084e-07 -1.73889798067439e-06 2.60987971638566e-06 5.44885300590249e-05 1938 1935 0 12 9 1934 1963 0 43 7 0 0 0 0 0 21 50 0 504 0 27 29 0 0 2260 +367 398 0.999998512790531 0.000239032905351615 0.00170800468282552 0.000352997263170133 -0.000240741971434594 0.99999947053549 0.00100048590373477 0.000771267433607224 -0.00170776462944533 -0.00100089560421722 0.999998040872061 -0.00919308368444662 2.32149753011816e-05 1.42088654107585e-05 -3.05965602878943e-06 3.70735389175525e-06 -2.03855610576472e-06 1.18018547502862e-05 1.42088654107585e-05 1.98379579314033e-05 -4.09863429574971e-06 4.14780660962394e-06 -2.97466494353097e-07 8.10998629666178e-06 -3.05965602878943e-06 -4.09863429574971e-06 1.09154987703384e-05 4.17831513527698e-06 1.1380983190431e-06 -1.75325804568918e-06 3.70735389175525e-06 4.14780660962394e-06 4.17831513527698e-06 3.02345613984484e-05 -9.51076170677405e-06 2.20467404922283e-06 -2.03855610576472e-06 -2.97466494353097e-07 1.1380983190431e-06 -9.51076170677405e-06 4.73713285490996e-05 1.20220403218131e-06 1.18018547502862e-05 8.10998629666178e-06 -1.75325804568918e-06 2.20467404922283e-06 1.20220403218131e-06 5.06335496693654e-05 2569 2556 0 24 43 2548 2599 0 50 25 0 0 0 0 0 12 43 0 467 0 54 38 0 0 2386 +367 409 0.999996682009831 0.000226802018365014 0.00256603393845868 -0.0101069425943105 -0.000230731440923316 0.999998801202832 0.00153112896302005 0.00949814509056978 -0.00256568359916527 -0.00153171594745728 0.999995535546997 -0.00758749371014035 2.28343250561674e-05 1.35775687632633e-05 -6.09139258740412e-07 4.9147303738036e-07 -1.3799024463189e-06 8.41799760518012e-06 1.35775687632633e-05 2.74322648534288e-05 -2.14499232617222e-06 6.56809651001051e-06 -4.41577721869233e-06 2.77577607299847e-06 -6.09139258740412e-07 -2.14499232617222e-06 9.9550383773255e-06 2.16563674742371e-06 2.23636159757311e-06 -3.62279660055408e-09 4.9147303738036e-07 6.56809651001051e-06 2.16563674742371e-06 4.69219447725021e-05 -3.32192355497106e-06 -6.07699293716614e-07 -1.3799024463189e-06 -4.41577721869233e-06 2.23636159757311e-06 -3.32192355497106e-06 3.4977013873649e-05 -3.28483554391007e-06 8.41799760518012e-06 2.77577607299847e-06 -3.62279660055408e-09 -6.07699293716614e-07 -3.28483554391007e-06 4.06791113568962e-05 1828 1825 0 8 10 1822 1851 0 45 2 0 0 0 0 0 19 48 0 498 0 37 39 0 0 2353 +367 411 0.999996021290414 0.000152861312701772 0.00281674222467041 -0.000800899268859625 -0.000160400976297107 0.999996404766843 0.00267670037835121 0.00779178452520668 -0.00281632293389182 -0.00267714153674057 0.999992450590665 -0.00935081601747825 3.37230608577416e-05 2.1436468296177e-05 -5.35789822992336e-06 7.39805090857327e-06 -3.61975590747011e-06 2.07234817777352e-05 2.1436468296177e-05 2.97231996663065e-05 -6.14443553661722e-06 1.08300059338147e-05 -2.35112695820925e-06 1.67339481705868e-05 -5.35789822992336e-06 -6.14443553661722e-06 1.29625253822254e-05 4.52086221990861e-06 1.05771426027376e-06 -2.46732704217482e-06 7.39805090857327e-06 1.08300059338147e-05 4.52086221990861e-06 4.2946795437128e-05 -1.10941443119681e-05 1.02163662230393e-05 -3.61975590747011e-06 -2.35112695820925e-06 1.05771426027376e-06 -1.10941443119681e-05 4.97734606713934e-05 -6.1293546756226e-06 2.07234817777352e-05 1.67339481705868e-05 -2.46732704217482e-06 1.02163662230393e-05 -6.1293546756226e-06 6.09312781938606e-05 1514 1513 0 14 11 1512 1542 0 44 9 0 0 0 0 0 15 46 0 538 0 11 15 0 0 2296 +367 422 0.999999417359731 0.000811645696175088 0.00071169618674269 -0.00838514109501451 -0.000812283224471019 0.999999268729022 0.000895956128239172 0.0112099305844132 -0.000710968467364476 -0.000896533705092464 0.999999345375363 -0.00756097390106354 2.80751658923864e-05 1.59648958896608e-05 -9.36246726497868e-06 5.60711961783892e-06 9.39234064687378e-06 1.64930461875532e-05 1.59648958896608e-05 2.1775808435093e-05 -7.59868469862879e-06 5.05844672712998e-06 -3.42007558309737e-07 7.8377417864121e-06 -9.36246726497868e-06 -7.59868469862879e-06 1.41759676585521e-05 -2.99005504082793e-07 -1.94280759062348e-06 -2.15059821432957e-06 5.60711961783892e-06 5.05844672712998e-06 -2.99005504082793e-07 3.62832911793661e-05 -1.53262956268011e-06 5.07841576906774e-06 9.39234064687378e-06 -3.42007558309737e-07 -1.94280759062348e-06 -1.53262956268011e-06 3.5228213550361e-05 -1.81670907574612e-06 1.64930461875532e-05 7.8377417864121e-06 -2.15059821432957e-06 5.07841576906774e-06 -1.81670907574612e-06 5.15133497937265e-05 2537 2543 0 13 14 2540 2574 0 41 12 0 0 0 0 0 14 47 0 600 0 51 56 0 0 2395 +367 393 0.999995879906503 0.000598536387041735 0.00280747648462723 0.00121974616673131 -0.000599773391922746 0.999999723428402 0.000439789719873144 0.00546773114769908 -0.00280721247800898 -0.000441471757592308 0.999995962322244 -0.00153125864970138 2.80881882029064e-05 1.39492638133997e-05 -1.52772601113173e-06 2.22930197370351e-06 -3.40791434706741e-07 1.28751932347574e-05 1.39492638133997e-05 2.76049737370627e-05 -1.70756631928566e-06 6.32247854853193e-06 2.29940905164046e-06 9.65604468489788e-06 -1.52772601113173e-06 -1.70756631928566e-06 1.03845127251164e-05 2.49931204241012e-06 2.64477738818112e-06 -1.96971563366511e-08 2.22930197370351e-06 6.32247854853193e-06 2.49931204241012e-06 2.92416902554387e-05 3.09605637638867e-06 6.38867447603839e-06 -3.40791434706741e-07 2.29940905164046e-06 2.64477738818112e-06 3.09605637638867e-06 2.94658393314488e-05 1.4851488826886e-06 1.28751932347574e-05 9.65604468489788e-06 -1.96971563366511e-08 6.38867447603839e-06 1.4851488826886e-06 4.20582965439871e-05 2450 2432 0 21 50 2427 2454 0 45 28 0 0 0 0 0 16 47 0 453 0 54 35 0 0 2382 +367 421 0.999992065998371 0.000573336475913651 0.00394198244473675 -0.00383685356022893 -0.000585112968550542 0.999995367874275 0.00298695041932673 0.0101337236158887 -0.00394025165735131 -0.00298923322590746 0.999987769376005 -0.00928678779244813 3.70954446145352e-05 1.98606106051788e-05 -6.08318490234967e-06 7.20471641656619e-06 5.82868782009412e-06 1.52747683747631e-05 1.98606106051788e-05 2.2784962130092e-05 -6.49472588510674e-06 6.28285358736621e-06 3.95819551826328e-06 5.85057139052619e-06 -6.08318490234967e-06 -6.49472588510674e-06 1.14078020139223e-05 1.06308325946124e-06 6.36361673957709e-07 -1.98920152443129e-06 7.20471641656619e-06 6.28285358736621e-06 1.06308325946124e-06 3.10623236286274e-05 5.81164473218001e-07 5.53414305412018e-07 5.82868782009412e-06 3.95819551826328e-06 6.36361673957709e-07 5.81164473218001e-07 3.67574838601332e-05 4.34627811356915e-08 1.52747683747631e-05 5.85057139052619e-06 -1.98920152443129e-06 5.53414305412018e-07 4.34627811356915e-08 4.64159589091027e-05 2081 2079 0 12 14 2074 2111 0 47 8 0 0 0 0 0 18 50 0 624 0 17 18 0 0 2402 +367 420 0.999998784418117 0.000827582670964426 0.00132146479730348 -0.000145368108395971 -0.00082604199060503 0.999998979038561 -0.00116600877618802 0.00433580417268316 -0.00132242841679624 0.00116491577339719 0.999998447075956 -0.014289460620892 3.29941272537127e-05 1.37615540237724e-05 -9.11322820010689e-06 3.4202509050081e-06 8.1475946349374e-06 1.02529283871479e-05 1.37615540237724e-05 3.28636842989862e-05 -1.05420226251741e-05 1.00388502323492e-05 9.32421571811897e-06 1.48371485507343e-05 -9.11322820010689e-06 -1.05420226251741e-05 1.63307409794943e-05 1.33220573792786e-06 -2.19766769284337e-06 -4.18082998609924e-06 3.4202509050081e-06 1.00388502323492e-05 1.33220573792786e-06 3.98109203389481e-05 -1.71845866402035e-07 2.29657616095893e-06 8.1475946349374e-06 9.32421571811897e-06 -2.19766769284337e-06 -1.71845866402035e-07 4.16510996516301e-05 2.72601937174034e-06 1.02529283871479e-05 1.48371485507343e-05 -4.18082998609924e-06 2.29657616095893e-06 2.72601937174034e-06 5.37101405974467e-05 1467 1469 0 17 11 1465 1495 0 46 9 0 0 0 0 0 12 42 0 627 0 13 16 0 0 2298 +367 424 0.99999471076015 3.46086588795403e-05 0.00325226904874495 -0.0077956434989436 -3.91141365373499e-05 0.999999039733927 0.00138528022735987 0.0129493149553308 -0.00325221798301049 -0.00138540010997611 0.999993751852843 -0.00916959809946677 2.46585835224634e-05 1.42048509365379e-05 -6.52822844632613e-06 1.70844604144814e-07 4.98366129441078e-06 1.26526232520744e-05 1.42048509365379e-05 2.42890179932441e-05 -7.94988909361633e-06 3.16064332706417e-06 3.09230217390593e-06 4.9305546616108e-06 -6.52822844632613e-06 -7.94988909361633e-06 1.44312115497387e-05 2.89296569943875e-06 -3.27369498255575e-06 -3.93306104186289e-06 1.70844604144814e-07 3.16064332706417e-06 2.89296569943875e-06 3.79357750910123e-05 -3.85235795924532e-06 -2.19202390219784e-06 4.98366129441078e-06 3.09230217390593e-06 -3.27369498255575e-06 -3.85235795924532e-06 4.73224307984207e-05 1.33092446898003e-05 1.26526232520744e-05 4.9305546616108e-06 -3.93306104186289e-06 -2.19202390219784e-06 1.33092446898003e-05 4.81776122291972e-05 1908 1907 0 12 15 1898 1929 0 42 6 0 0 0 0 0 17 47 0 614 0 39 40 0 0 2311 +367 413 0.999984993169069 -0.000159991612989424 0.00547611535130168 -0.00206411546236646 0.000141406841642367 0.999994230345829 0.00339400635797901 0.00728755155949606 -0.00547662676856161 -0.00339318106452311 0.999979246225391 -0.0104579236770319 2.86979717561508e-05 1.63749734710465e-05 -7.25264549134721e-06 3.12864285152039e-06 1.88521326440711e-06 8.9502510400291e-06 1.63749734710465e-05 2.58680606429923e-05 -8.84297683028175e-06 3.74014872518855e-06 6.16361591731825e-06 3.11013431470635e-07 -7.25264549134721e-06 -8.84297683028175e-06 1.50025976854595e-05 3.36455374104504e-06 -2.73948171291026e-07 -2.20238342805588e-06 3.12864285152039e-06 3.74014872518855e-06 3.36455374104504e-06 3.54071445735259e-05 2.92368035685453e-06 1.05126925414495e-06 1.88521326440711e-06 6.16361591731825e-06 -2.73948171291026e-07 2.92368035685453e-06 3.75452707060657e-05 5.02423568126213e-06 8.9502510400291e-06 3.11013431470635e-07 -2.20238342805588e-06 1.05126925414495e-06 5.02423568126213e-06 4.21210353159002e-05 1380 1375 0 12 11 1376 1403 0 43 10 0 0 0 0 0 17 50 0 606 0 30 33 0 0 2227 +367 426 0.999984991207735 0.00060127128050162 0.00544571685936974 -0.00106442788455664 -0.000609117174861911 0.999998778836215 0.00143920198208181 0.0118285181452295 -0.00544484485843887 -0.00144249746106671 0.999984136306943 -0.00882439243487466 4.28342750077214e-05 2.38392707776929e-05 -7.47631665640662e-06 7.58293496119814e-06 -3.90302184963534e-06 2.48697423152434e-05 2.38392707776929e-05 3.51739998083996e-05 -7.95512636810187e-06 8.62914964231273e-06 -6.75634036209412e-07 2.37673286561409e-05 -7.47631665640662e-06 -7.95512636810187e-06 1.53564443112482e-05 2.52079235878715e-06 -6.38504176465919e-07 -7.28045347263214e-07 7.58293496119814e-06 8.62914964231273e-06 2.52079235878715e-06 4.20722762363646e-05 -1.11628147672213e-05 1.14364935411166e-05 -3.90302184963534e-06 -6.75634036209412e-07 -6.38504176465919e-07 -1.11628147672213e-05 5.4293553145909e-05 -9.62507587841851e-06 2.48697423152434e-05 2.37673286561409e-05 -7.28045347263214e-07 1.14364935411166e-05 -9.62507587841851e-06 6.55339557490452e-05 2115 2111 0 13 17 2114 2139 0 42 16 0 0 0 0 0 16 44 0 638 0 16 19 0 0 2148 +367 395 0.999997781587597 0.000320702778551589 0.00208181882331462 -0.00234740661351063 -0.000324279827989575 0.999998471447252 0.00171812274086956 0.00797830224107334 -0.00208126463440785 -0.00171879402121469 0.999996357035681 -0.0020669275049042 2.62697473268995e-05 1.09407937311749e-05 -7.41679457139223e-07 1.09536267352282e-07 -1.96230406778418e-06 9.30909458306408e-06 1.09407937311749e-05 2.69342927782266e-05 -3.43658712327794e-07 1.05161029532498e-05 -1.22415633264273e-06 1.06091680904182e-05 -7.41679457139223e-07 -3.43658712327794e-07 1.09283733458313e-05 3.19312257903346e-06 1.22321710669096e-06 -6.63475711328558e-07 1.09536267352282e-07 1.05161029532498e-05 3.19312257903346e-06 5.85865932446109e-05 -2.03726533291934e-05 4.86107044842437e-06 -1.96230406778418e-06 -1.22415633264273e-06 1.22321710669096e-06 -2.03726533291934e-05 4.58872925584927e-05 2.80890884935148e-06 9.30909458306408e-06 1.06091680904182e-05 -6.63475711328558e-07 4.86107044842437e-06 2.80890884935148e-06 3.82873289018369e-05 2593 2578 0 15 47 2567 2599 0 43 24 0 0 0 0 0 17 48 0 454 0 83 76 0 0 2481 +367 425 0.999996245316199 0.00153777599845703 0.00226817073495792 -0.00797791483164043 -0.00154298274306592 0.999996174683941 0.00229560923062349 0.0108826388534167 -0.0022646319257113 -0.00229910035963907 0.999994792776331 -0.00786970715739579 3.24378377311756e-05 1.97462331421045e-05 -8.67714810318971e-06 4.14538335883835e-06 7.30186854077726e-06 5.68232421631767e-06 1.97462331421045e-05 3.68552815992493e-05 -1.13781316395926e-05 5.52487194809392e-06 1.37169131316587e-05 9.17471878008917e-06 -8.67714810318971e-06 -1.13781316395926e-05 1.8140195222342e-05 -2.13425308086848e-06 -7.44618379427255e-06 -1.19810908651422e-06 4.14538335883835e-06 5.52487194809392e-06 -2.13425308086848e-06 3.33910569696162e-05 -2.69957851008691e-07 1.64024609807833e-06 7.30186854077726e-06 1.37169131316587e-05 -7.44618379427255e-06 -2.69957851008691e-07 5.53164739591268e-05 8.72044317473296e-06 5.68232421631767e-06 9.17471878008917e-06 -1.19810908651422e-06 1.64024609807833e-06 8.72044317473296e-06 4.72072061312848e-05 2183 2184 0 19 16 2170 2197 0 43 6 0 0 0 0 0 15 45 0 629 0 45 46 0 0 2048 +367 396 0.999994234469156 0.000551873530910843 0.00335059159741706 -0.00570051036672226 -0.000558148365134091 0.999998091839238 0.0018721079793449 0.00906913200000228 -0.00334955203710884 -0.00187396731287094 0.999992634346704 -0.00613894276163279 2.24584690579884e-05 1.16911252086029e-05 -6.23057650252143e-07 -1.08902487961805e-06 -2.00089964336943e-07 9.89952422077e-06 1.16911252086029e-05 2.69414703390249e-05 -2.62902828143446e-06 5.13545094662936e-06 2.58158778627816e-06 6.17003935498927e-06 -6.23057650252143e-07 -2.62902828143446e-06 1.24549253505086e-05 3.44859001797641e-06 3.41054720674264e-06 4.00056876377469e-07 -1.08902487961805e-06 5.13545094662936e-06 3.44859001797641e-06 4.09155818563488e-05 -3.59786259996967e-06 4.04055509362269e-06 -2.00089964336943e-07 2.58158778627816e-06 3.41054720674264e-06 -3.59786259996967e-06 4.43855545933499e-05 4.16120850316019e-06 9.89952422077e-06 6.17003935498927e-06 4.00056876377469e-07 4.04055509362269e-06 4.16120850316019e-06 5.59149645524169e-05 1928 1911 0 13 46 1885 1912 0 43 11 0 0 0 0 0 15 44 0 458 0 84 67 0 0 2478 +367 423 0.999998815133361 0.00027841664421146 0.00151400662023791 -0.00283954881486015 -0.000277941964369455 0.999999912161822 -0.000313726970679401 0.00287202369204301 -0.0015140938340607 0.000313305792980682 0.999998804678957 -0.00767895392038107 3.0589127559985e-05 1.90685518503836e-05 -6.34235255193137e-06 6.43876291422149e-06 1.35380479360852e-06 1.5182364823192e-05 1.90685518503836e-05 2.68972559706053e-05 -7.62011010906743e-06 5.91381314027303e-06 2.81864383074812e-06 1.41676402182578e-05 -6.34235255193137e-06 -7.62011010906743e-06 1.09622403277767e-05 7.38454598526857e-08 1.60791573983595e-06 -3.8422553713768e-06 6.43876291422149e-06 5.91381314027303e-06 7.38454598526857e-08 3.07079905877329e-05 -1.73542990000042e-06 5.10927256132943e-06 1.35380479360852e-06 2.81864383074812e-06 1.60791573983595e-06 -1.73542990000042e-06 3.06700793669529e-05 -1.06843972679555e-06 1.5182364823192e-05 1.41676402182578e-05 -3.8422553713768e-06 5.10927256132943e-06 -1.06843972679555e-06 5.2857469552391e-05 2402 2404 0 19 12 2401 2424 0 40 12 0 0 0 0 0 19 49 0 608 0 12 18 0 0 2325 +368 370 0.999995654954876 0.000467994388095551 0.00291050727920376 -0.000752385506089107 -0.00047464318133163 0.999997278706753 0.00228413943078176 0.00170375798984753 -0.00290943039442472 -0.00228551095852715 0.999993155803798 -0.00684774463486054 4.13069850071191e-05 2.8848751086072e-05 -1.110590371878e-05 1.26766312898571e-05 8.79330960718803e-06 2.76562758949062e-05 2.8848751086072e-05 6.15664508067042e-05 -1.1767060101742e-05 1.9108421679576e-05 1.1601566789794e-05 2.51614677076114e-05 -1.110590371878e-05 -1.1767060101742e-05 1.61769609256643e-05 -4.2193918510346e-06 -2.52415690671656e-06 -6.4757412943019e-06 1.26766312898571e-05 1.9108421679576e-05 -4.2193918510346e-06 3.88923557305578e-05 7.22909070790306e-06 9.23684451422074e-06 8.79330960718803e-06 1.1601566789794e-05 -2.52415690671656e-06 7.22909070790306e-06 4.01746616456041e-05 3.39645340903056e-06 2.76562758949062e-05 2.51614677076114e-05 -6.4757412943019e-06 9.23684451422074e-06 3.39645340903056e-06 5.1007458152952e-05 1552 1536 0 20 55 1496 1526 0 47 7 0 0 0 0 0 17 48 0 613 0 105 90 0 0 2220 +367 419 0.99999999009135 -2.64032476913858e-05 0.000138275694213343 -0.00119049295130419 2.65003327380402e-05 0.999999753136328 -0.000702157401030916 0.00136095197715565 -0.00013825712084232 0.000702161058425391 0.999999743927375 -0.00902279934805826 2.39915381314436e-05 1.19888631142432e-05 -6.27117017054679e-06 4.79411382572794e-06 6.79438594682121e-06 1.10532904679752e-05 1.19888631142432e-05 1.94580604380095e-05 -6.8033037447053e-06 2.76465636373698e-06 4.865439499272e-06 4.5685200941035e-06 -6.27117017054679e-06 -6.8033037447053e-06 1.11208406653068e-05 1.0059423093617e-06 4.52096947407204e-07 -1.18364243482838e-06 4.79411382572794e-06 2.76465636373698e-06 1.0059423093617e-06 2.84685218391059e-05 4.64499290915529e-07 -1.42283257058632e-06 6.79438594682121e-06 4.865439499272e-06 4.52096947407204e-07 4.64499290915529e-07 2.9548859157317e-05 2.96760173014286e-06 1.10532904679752e-05 4.5685200941035e-06 -1.18364243482838e-06 -1.42283257058632e-06 2.96760173014286e-06 4.63065148145369e-05 2702 2704 0 18 14 2697 2740 0 39 8 0 0 0 0 0 12 44 0 578 0 15 17 0 0 2334 +367 412 0.999998950826199 0.000206952334793309 0.00143370751306247 -0.00106952992281227 -0.00020610855796107 0.999999805504833 -0.000588650625751818 0.00280531363400685 -0.00143382905683466 0.000588354508766948 0.999998798985883 -0.010268032299699 3.08801940284822e-05 2.1246028641354e-05 -7.36163586444555e-06 6.38858467549679e-06 7.1573249072336e-06 1.79110055037378e-05 2.1246028641354e-05 2.88218079362825e-05 -8.27272752023166e-06 7.59339147243433e-06 5.20977416826328e-06 1.53079128191279e-05 -7.36163586444555e-06 -8.27272752023166e-06 1.2309471521811e-05 1.42163890283455e-06 -6.46296386137974e-07 -6.09787643303704e-06 6.38858467549679e-06 7.59339147243433e-06 1.42163890283455e-06 4.15290825334628e-05 -9.63326976807692e-06 -3.29160261008089e-06 7.1573249072336e-06 5.20977416826328e-06 -6.46296386137974e-07 -9.63326976807692e-06 4.0521212963797e-05 9.333853202407e-06 1.79110055037378e-05 1.53079128191279e-05 -6.09787643303704e-06 -3.29160261008089e-06 9.333853202407e-06 4.79763843884096e-05 2398 2395 0 14 9 2396 2423 0 40 6 0 0 0 0 0 19 49 0 565 0 12 13 0 0 2246 +367 394 0.999987718377783 -1.9072657382749e-05 0.00495608008709303 0.000116388054914987 8.12082549088513e-06 0.999997558383097 0.00220978774922819 0.00316320106204705 -0.00495611013276875 -0.00220972036198837 0.999985276945753 -0.00546161677834028 3.13365536348936e-05 1.49497132952668e-05 2.439296048529e-07 3.27922808185629e-06 -6.89759001210512e-06 1.29090581276208e-05 1.49497132952668e-05 2.85639268303187e-05 -1.43975258840283e-06 5.32110320250825e-06 2.51523343984596e-06 4.86178224083004e-06 2.439296048529e-07 -1.43975258840283e-06 1.20907896094204e-05 3.1382347164972e-06 3.52933996045861e-06 -1.84066005943805e-06 3.27922808185629e-06 5.32110320250825e-06 3.1382347164972e-06 3.58605630849673e-05 -7.90784455368645e-06 4.26599971959294e-06 -6.89759001210512e-06 2.51523343984596e-06 3.52933996045861e-06 -7.90784455368645e-06 4.59745537255717e-05 -2.77524476709787e-06 1.29090581276208e-05 4.86178224083004e-06 -1.84066005943805e-06 4.26599971959294e-06 -2.77524476709787e-06 4.96300578912287e-05 1259 1235 0 7 47 1213 1245 0 48 3 0 0 0 0 0 14 46 0 464 0 80 60 0 0 2459 +368 407 0.99999965410733 0.000323622048347197 0.000766194486114546 -0.010003845959163 -0.000324917668659862 0.999998516693295 0.001691460823937 0.00688182336044547 -0.000765645955596586 -0.00169170918899927 0.999998275951659 -0.00703050599754227 3.41971858198704e-05 2.30035814512877e-05 -1.38392036483312e-06 5.96521038033778e-06 7.55355057997585e-07 2.61246788124354e-05 2.30035814512877e-05 2.81581833571506e-05 -2.35225218870956e-06 7.91073994437409e-06 -3.0145387216802e-06 1.81836679327087e-05 -1.38392036483312e-06 -2.35225218870956e-06 9.83821749435868e-06 1.85439204240824e-06 4.79657669894346e-06 5.95938553925739e-07 5.96521038033778e-06 7.91073994437409e-06 1.85439204240824e-06 4.62947855720213e-05 -1.13609567293533e-05 9.61494728171252e-06 7.55355057997585e-07 -3.0145387216802e-06 4.79657669894346e-06 -1.13609567293533e-05 2.95144068068123e-05 -3.14952622276181e-06 2.61246788124354e-05 1.81836679327087e-05 5.95938553925739e-07 9.61494728171252e-06 -3.14952622276181e-06 6.0944825283731e-05 2614 2611 0 16 17 2607 2642 0 43 15 0 0 0 0 0 17 47 0 490 0 18 22 0 0 2358 +368 371 0.999998135113759 0.00108004844643262 -0.00160101978653081 -0.00778003376836893 -0.00108261168795925 0.999998132366687 -0.00160100439420205 0.00173441160493134 0.00159928763410424 0.00160273469124454 0.999997436757001 -0.00639816359635382 3.15635794216919e-05 1.92165826190246e-05 -8.72397545073211e-06 1.07161203455942e-05 8.09437246849471e-06 1.69877676433634e-05 1.92165826190246e-05 2.4651744227614e-05 -9.00283706583688e-06 7.2942845890395e-06 4.40483838442298e-06 1.81830518594154e-05 -8.72397545073211e-06 -9.00283706583688e-06 1.39024586632979e-05 -3.69888190156554e-07 -1.66196965529985e-06 -2.4877353625788e-06 1.07161203455942e-05 7.2942845890395e-06 -3.69888190156554e-07 3.43553006051964e-05 3.04458854995909e-06 9.64334354750779e-06 8.09437246849471e-06 4.40483838442298e-06 -1.66196965529985e-06 3.04458854995909e-06 3.60002565422149e-05 2.39452365611737e-06 1.69877676433634e-05 1.81830518594154e-05 -2.4877353625788e-06 9.64334354750779e-06 2.39452365611737e-06 4.11803650870648e-05 2945 2920 0 21 59 2899 2922 0 44 22 0 0 0 0 0 17 49 0 632 0 97 77 0 0 2497 +368 406 0.999986092207356 0.000408977416808362 0.00525814885048422 -0.00263499620036954 -0.000418287104149874 0.999998346866789 0.0017695478484783 0.0077807260146305 -0.00525741645295573 -0.0017717226538296 0.999984610167116 -0.00732543780787943 2.4933693495926e-05 1.65210468486332e-05 -6.94990954025569e-07 -2.50432717596311e-06 -3.05485273898629e-06 1.56153412016919e-05 1.65210468486332e-05 2.53562110695245e-05 -1.8231782545916e-06 3.74376847039674e-06 -4.57213248971704e-06 1.06841208166173e-05 -6.94990954025569e-07 -1.8231782545916e-06 1.09658656959847e-05 1.64550417429945e-06 3.92248830944246e-06 1.74471988207435e-06 -2.50432717596311e-06 3.74376847039674e-06 1.64550417429945e-06 3.81070656299283e-05 -1.07790581052097e-05 -5.8599691207351e-07 -3.05485273898629e-06 -4.57213248971704e-06 3.92248830944246e-06 -1.07790581052097e-05 3.40559513177315e-05 -3.07742712266745e-06 1.56153412016919e-05 1.06841208166173e-05 1.74471988207435e-06 -5.8599691207351e-07 -3.07742712266745e-06 4.73279543036748e-05 1980 1976 0 11 17 1975 1998 0 35 26 0 0 0 0 0 20 53 0 471 0 62 66 0 0 2411 +368 400 0.999996142570703 0.000430309246243227 0.00274402581375796 0.00266387987819612 -0.000429809104280718 0.999999890914476 -0.000182852864471798 -0.00806304046947128 -0.00274410419770275 0.000181672751852668 0.999996218436432 -0.011400519501771 4.97200030930632e-05 4.1002440796682e-05 -4.68313118040396e-06 1.29443290232397e-05 -1.08737339126366e-06 4.35830449408805e-05 4.1002440796682e-05 4.6607555795444e-05 -6.25597343175329e-06 8.91858287158695e-06 3.51599592003597e-06 4.35417958504878e-05 -4.68313118040396e-06 -6.25597343175329e-06 1.26785253734779e-05 1.83453483319442e-06 2.48593972961695e-06 -1.77771522654597e-06 1.29443290232397e-05 8.91858287158695e-06 1.83453483319442e-06 5.49887676427084e-05 -3.09479966958808e-05 1.92806536133928e-05 -1.08737339126366e-06 3.51599592003597e-06 2.48593972961695e-06 -3.09479966958808e-05 6.6844538664042e-05 3.08771805437205e-06 4.35830449408805e-05 4.35417958504878e-05 -1.77771522654597e-06 1.92806536133928e-05 3.08771805437205e-06 9.38772632281318e-05 2293 2281 0 16 38 2267 2296 0 49 12 0 0 0 0 0 17 50 0 494 0 99 88 0 0 2388 +368 401 0.999993621096051 0.000226247281977213 0.00356462892528295 -0.00109213858069938 -0.000234062242871863 0.999997569956622 0.00219209847324394 -0.00376690286927362 -0.00356412430675864 -0.00219291883509959 0.999991244024121 -0.00683321880159645 3.50379691752852e-05 1.89373416978852e-05 -4.09157625295171e-06 1.59798010219196e-06 4.05272588234764e-06 2.19739658202887e-05 1.89373416978852e-05 2.73039231803681e-05 -4.35359652058805e-06 5.22764385041041e-06 -2.43856639986836e-06 1.39889398033743e-05 -4.09157625295171e-06 -4.35359652058805e-06 1.10560574818841e-05 2.64578204101236e-06 3.1715893147418e-06 -1.61624807021605e-06 1.59798010219196e-06 5.22764385041041e-06 2.64578204101236e-06 4.31797457901769e-05 -1.06778211210913e-05 1.60129391471497e-06 4.05272588234764e-06 -2.43856639986836e-06 3.1715893147418e-06 -1.06778211210913e-05 4.44936720873214e-05 8.92012074038461e-06 2.19739658202887e-05 1.39889398033743e-05 -1.61624807021605e-06 1.60129391471497e-06 8.92012074038461e-06 5.85681188989124e-05 1732 1719 0 12 37 1714 1752 0 43 20 0 0 0 0 0 17 47 0 511 0 39 29 0 0 2499 +368 405 0.999995866406371 0.000488716317727079 0.00283343017079431 -0.00270901110136359 -0.000490124066882675 0.999999756800515 0.000496162584814437 0.00623719059397075 -0.00283318699895411 -0.000497549266198475 0.99999586273952 -0.00778478489556121 2.59166707823044e-05 1.41812849734967e-05 -1.93812495706906e-06 4.93848651325627e-06 -2.39583739244455e-06 1.52398300532587e-05 1.41812849734967e-05 2.40061915548813e-05 -1.65879632918132e-06 4.59794451769475e-06 -9.18339116349392e-07 9.85874261577794e-06 -1.93812495706906e-06 -1.65879632918132e-06 1.12915554333175e-05 1.60446497691484e-06 4.86300648322112e-06 -6.34921478820517e-07 4.93848651325627e-06 4.59794451769475e-06 1.60446497691484e-06 3.61780807046969e-05 -1.52215194175146e-05 6.75696188774682e-06 -2.39583739244455e-06 -9.18339116349392e-07 4.86300648322112e-06 -1.52215194175146e-05 3.66815616061582e-05 -6.34742663717669e-06 1.52398300532587e-05 9.85874261577794e-06 -6.34921478820517e-07 6.75696188774682e-06 -6.34742663717669e-06 4.3753420571261e-05 2499 2500 0 21 19 2492 2515 0 37 17 0 0 0 0 0 17 49 0 444 0 50 55 0 0 2388 +368 402 0.999985454678844 0.000604837102995088 0.00535953382538364 0.00121384862007478 -0.000623166817273171 0.99999396099673 0.00341901055704669 0.00451444207479768 -0.0053574335147009 -0.00342230071007613 0.999979792677825 -0.0124988473843183 3.06333988049603e-05 1.48353492497343e-05 -3.78872947717049e-06 1.37243678047769e-06 -2.82776278846291e-06 1.7103643986378e-05 1.48353492497343e-05 2.79512246626732e-05 -3.69681591064387e-06 4.23460323553646e-06 1.16325674668042e-06 9.25730311813145e-06 -3.78872947717049e-06 -3.69681591064387e-06 1.28534716094645e-05 4.99178549581289e-06 2.46600630992631e-06 -2.23590330990887e-06 1.37243678047769e-06 4.23460323553646e-06 4.99178549581289e-06 4.47293850651787e-05 -1.6601934802043e-05 4.23362492854075e-06 -2.82776278846291e-06 1.16325674668042e-06 2.46600630992631e-06 -1.6601934802043e-05 4.8079783128919e-05 -1.23116159935322e-06 1.7103643986378e-05 9.25730311813145e-06 -2.23590330990887e-06 4.23362492854075e-06 -1.23116159935322e-06 5.64590252788419e-05 1434 1422 0 12 34 1408 1438 0 48 9 0 0 0 0 0 17 48 0 470 0 75 73 0 0 2322 +368 398 0.999995662537355 0.000219185845638666 0.00293715236946361 0.00105461459419495 -0.000223999536242128 0.999998632294094 0.00163866840741916 0.000384333241339039 -0.00293678917938236 -0.00163931922052478 0.999994343934909 -0.0119819280564211 2.27630532226888e-05 1.65762044491797e-05 -4.20325725888916e-06 5.28355672053482e-06 -4.14097299075862e-06 1.5960038214706e-05 1.65762044491797e-05 2.69622566938888e-05 -4.35490849886042e-06 6.6428534055816e-06 1.19218623837392e-07 9.71100008330687e-06 -4.20325725888916e-06 -4.35490849886042e-06 1.0663321172356e-05 3.71393085269317e-06 3.17724589347083e-06 -1.99274494101133e-06 5.28355672053482e-06 6.6428534055816e-06 3.71393085269317e-06 3.96300983922251e-05 -1.78967777810835e-05 5.32929151746447e-06 -4.14097299075862e-06 1.19218623837392e-07 3.17724589347083e-06 -1.78967777810835e-05 5.17017433028698e-05 -5.46032788583092e-06 1.5960038214706e-05 9.71100008330687e-06 -1.99274494101133e-06 5.32929151746447e-06 -5.46032788583092e-06 4.45946221850339e-05 2030 2018 0 25 42 1990 2015 0 46 9 0 0 0 0 0 19 51 0 478 0 91 81 0 0 2326 +368 372 0.999999536451955 0.000900716463687169 0.000340302406196071 -0.00978321936219033 -0.000900696331935563 0.999999592614313 -5.93070406431083e-05 -5.1590284590241e-05 -0.000340355686389661 5.90005040224359e-05 0.999999940338472 -0.00385481261047463 3.297475762539e-05 2.09509221763847e-05 -8.32097001680412e-06 9.36336431563649e-06 8.73345082319072e-06 1.78950364100185e-05 2.09509221763847e-05 3.18352336884559e-05 -1.03250194305351e-05 1.11999229762961e-05 7.30576582658884e-06 2.02774660102711e-05 -8.32097001680412e-06 -1.03250194305351e-05 1.45070301455199e-05 -1.00047111707259e-06 2.10038472053016e-07 -4.25904737902888e-06 9.36336431563649e-06 1.11999229762961e-05 -1.00047111707259e-06 4.38483948271285e-05 5.81904518384716e-06 7.91675133341054e-06 8.73345082319072e-06 7.30576582658884e-06 2.10038472053016e-07 5.81904518384716e-06 4.43937165516376e-05 4.42482252227067e-06 1.78950364100185e-05 2.02774660102711e-05 -4.25904737902888e-06 7.91675133341054e-06 4.42482252227067e-06 3.76133336608732e-05 1744 1723 0 22 61 1697 1725 0 45 22 0 0 0 0 0 13 45 0 646 0 99 79 0 0 2736 +368 408 0.999979479840353 6.61359180756975e-05 0.00640589761524007 0.00169737094440666 -9.67495371180252e-05 0.999988576875081 0.00477878215418322 0.00800382263598714 -0.00640550839072635 -0.0047793038604396 0.999968063348458 -0.00870250028661487 3.46567455625819e-05 1.65342792969844e-05 -1.04089933852253e-06 1.15402237837812e-06 -4.57069799777413e-06 2.18504892482141e-05 1.65342792969844e-05 3.77177400987512e-05 -1.60598937732505e-06 4.58713933871549e-06 3.375493670893e-06 1.89122563763739e-05 -1.04089933852253e-06 -1.60598937732505e-06 1.1130483635166e-05 3.43896447649472e-06 3.73642621405519e-06 7.05843431290065e-07 1.15402237837812e-06 4.58713933871549e-06 3.43896447649472e-06 2.94640545061499e-05 -6.06709029102624e-06 7.9748124831474e-06 -4.57069799777413e-06 3.375493670893e-06 3.73642621405519e-06 -6.06709029102624e-06 3.36518929666063e-05 -4.49497329490258e-06 2.18504892482141e-05 1.89122563763739e-05 7.05843431290065e-07 7.9748124831474e-06 -4.49497329490258e-06 6.18541617494566e-05 1791 1790 0 15 15 1789 1822 0 46 16 0 0 0 0 0 18 49 0 494 0 46 50 0 0 2334 +368 428 0.999996958390592 -1.88772206852553e-05 0.00246634409913991 -0.00644184607018074 9.28424914966438e-06 0.999992435804858 0.0038895047073986 0.0127856710997351 -0.00246639886627058 -0.00388946997889138 0.999989394393718 -0.0130254186711998 3.62414471866147e-05 2.51007038857967e-05 -1.09167382490595e-05 1.31782023111067e-05 7.53835412491894e-06 2.53052863344789e-05 2.51007038857967e-05 3.44671574624596e-05 -1.17472461170795e-05 1.14455919158102e-05 1.14539130547032e-05 1.91497863942447e-05 -1.09167382490595e-05 -1.17472461170795e-05 1.52448731432474e-05 -1.8096848704042e-06 -6.42722518248656e-06 -5.11087001523769e-06 1.31782023111067e-05 1.14455919158102e-05 -1.8096848704042e-06 4.93453606395384e-05 -7.04079801685598e-06 1.28714183600299e-05 7.53835412491894e-06 1.14539130547032e-05 -6.42722518248656e-06 -7.04079801685598e-06 6.1039150246337e-05 2.50678846690498e-06 2.53052863344789e-05 1.91497863942447e-05 -5.11087001523769e-06 1.28714183600299e-05 2.50678846690498e-06 6.88274391166189e-05 1925 1923 0 7 16 1918 1948 0 43 19 0 0 0 0 0 16 48 0 609 0 58 64 0 0 2289 +368 409 0.999999927144566 0.000347612742295246 0.00015772204877622 -0.0102660918133858 -0.00034767792262744 0.999999854101268 0.000413421704399963 0.00829889871131043 -0.000157578315112382 -0.000413476510754217 0.99999990210312 -0.00802692833407394 2.87404338332862e-05 2.17302591144931e-05 -1.40297300091734e-06 2.00209547288437e-06 1.74322519724208e-07 1.93265821433425e-05 2.17302591144931e-05 3.21243147355432e-05 -2.41856795135961e-06 6.87416887342551e-06 -3.34379438203314e-06 2.03773005183875e-05 -1.40297300091734e-06 -2.41856795135961e-06 9.79096938036727e-06 3.16749885290511e-06 4.28855560935366e-06 1.79459530232657e-06 2.00209547288437e-06 6.87416887342551e-06 3.16749885290511e-06 4.93474241812856e-05 -6.20416118014614e-06 9.4581255839092e-06 1.74322519724208e-07 -3.34379438203314e-06 4.28855560935366e-06 -6.20416118014614e-06 2.96847855621529e-05 -7.11343194731943e-06 1.93265821433425e-05 2.03773005183875e-05 1.79459530232657e-06 9.4581255839092e-06 -7.11343194731943e-06 6.28788868333115e-05 2232 2228 0 12 10 2234 2272 0 45 15 0 0 0 0 0 20 50 0 505 0 12 15 0 0 2357 +368 399 0.999999403290383 0.000159148590107369 0.00108078240423499 0.000764380748956083 -0.000159383318295761 0.999999963732073 0.000217100920502972 -0.00209999380930072 -0.00108074781373184 -0.000217273049642707 0.999999392388108 -0.00489258642655789 2.34545934216633e-05 1.83022938230245e-05 -4.87727761034128e-06 4.61273378919588e-06 5.46391855934903e-06 1.43973885214703e-05 1.83022938230245e-05 2.63226075854413e-05 -5.91310563313299e-06 5.47524199061029e-06 5.80873837736778e-06 1.73781084648546e-05 -4.87727761034128e-06 -5.91310563313299e-06 1.11627368718696e-05 2.50087641796728e-06 3.2214872934386e-06 -2.15173994187094e-06 4.61273378919588e-06 5.47524199061029e-06 2.50087641796728e-06 3.88065087591797e-05 -1.05077789098391e-05 1.53082820966604e-06 5.46391855934903e-06 5.80873837736778e-06 3.2214872934386e-06 -1.05077789098391e-05 4.48505084401685e-05 7.21706013485745e-06 1.43973885214703e-05 1.73781084648546e-05 -2.15173994187094e-06 1.53082820966604e-06 7.21706013485745e-06 4.97174464844132e-05 2438 2426 0 28 41 2415 2440 0 46 20 0 0 0 0 0 18 51 0 484 0 61 55 0 0 2430 +368 429 0.999973316928387 -0.00726017864637466 -0.000809467270858512 -0.0038161175454759 0.00726347963562952 0.999964998796516 0.0041524746196959 0.00703555956953534 0.000779291230966322 -0.00415824336795584 0.999991050818591 -0.00577336699872595 2.96155500498296e-05 1.1371353394692e-05 -2.59240564391362e-06 -6.23086649071951e-06 3.47648029603085e-06 1.31305697981318e-05 1.1371353394692e-05 3.20073867901926e-05 -5.67427374386798e-06 5.82564660746154e-06 6.04065207122944e-06 1.02188040372728e-07 -2.59240564391362e-06 -5.67427374386798e-06 1.12262768222539e-05 5.23973370624459e-07 2.22195700894599e-06 -1.32166747941537e-06 -6.23086649071951e-06 5.82564660746154e-06 5.23973370624459e-07 4.75966524230203e-05 -1.16950804767003e-05 -5.58695575621607e-06 3.47648029603085e-06 6.04065207122944e-06 2.22195700894599e-06 -1.16950804767003e-05 4.24583612845762e-05 8.27393215379246e-06 1.31305697981318e-05 1.02188040372728e-07 -1.32166747941537e-06 -5.58695575621607e-06 8.27393215379246e-06 5.64638363827024e-05 2308 2310 0 17 24 2312 2331 0 35 36 0 0 0 0 0 29 60 0 595 0 20 28 0 0 2410 +368 427 0.999984768585458 8.59926923384675e-05 0.0055186232291325 0.00233294105331478 -0.000105664649904558 0.999993641720612 0.00356445694747325 0.00432221674993186 -0.00551828162293453 -0.00356498577914333 0.999978419489303 -0.0140875873569378 5.66906437466203e-05 3.53748378558967e-05 -1.10815747490057e-05 1.30328181571102e-05 -7.0435874968824e-07 3.87667691970471e-05 3.53748378558967e-05 4.46687812564153e-05 -1.13506706212959e-05 1.03322903144179e-05 4.58084666284167e-06 2.323931442062e-05 -1.10815747490057e-05 -1.13506706212959e-05 1.60524199122723e-05 -3.32473285382403e-06 -3.9659548945409e-06 -5.51742423090261e-06 1.30328181571102e-05 1.03322903144179e-05 -3.32473285382403e-06 4.99953563754152e-05 -1.22634367086156e-05 6.64779287278495e-06 -7.0435874968824e-07 4.58084666284167e-06 -3.9659548945409e-06 -1.22634367086156e-05 5.83194105448851e-05 -6.26848225678989e-07 3.87667691970471e-05 2.323931442062e-05 -5.51742423090261e-06 6.64779287278495e-06 -6.26848225678989e-07 8.01111269806277e-05 1581 1584 0 22 16 1572 1600 0 46 23 0 0 0 0 0 13 43 0 617 0 59 64 0 0 2348 +368 404 0.999986914969054 0.000675016747987771 0.00507092132298452 -0.00284530562202598 -0.000693363056779352 0.999993218048329 0.0036170575083371 0.00701880459509592 -0.00506844535784462 -0.00362052616853686 0.999980601137801 -0.00510879110905303 3.24266742263872e-05 1.05342448675538e-05 -2.49530156867219e-06 -5.02324781703829e-06 -2.57671686011004e-06 1.54133049317424e-05 1.05342448675538e-05 3.37686248807263e-05 -2.00180492307555e-06 9.08584407924941e-06 7.64186747119006e-07 8.95947353641318e-06 -2.49530156867219e-06 -2.00180492307555e-06 1.22507571980643e-05 3.34200561606397e-06 2.92122127024064e-06 5.28960542825845e-07 -5.02324781703829e-06 9.08584407924941e-06 3.34200561606397e-06 4.26020363141325e-05 1.44443628993464e-06 -4.68711585954469e-07 -2.57671686011004e-06 7.64186747119006e-07 2.92122127024064e-06 1.44443628993464e-06 3.38835748427017e-05 1.33989626085807e-07 1.54133049317424e-05 8.95947353641318e-06 5.28960542825845e-07 -4.68711585954469e-07 1.33989626085807e-07 4.27136706302742e-05 1770 1772 0 22 22 1754 1793 0 46 15 0 0 0 0 0 15 44 0 437 0 20 22 0 0 2335 +368 397 0.9999995954403 -0.000209798981251631 0.000874702019841953 -0.00264944241137215 0.000208165584013831 0.999998235396623 0.00186704866819757 0.00137429041192731 -0.00087509218124835 -0.00186686583000812 0.999997874510565 -0.00545983583341319 2.71567346512577e-05 1.79272667312429e-05 -3.18314382610094e-06 1.80639435894265e-06 5.37982811283556e-08 1.51215478153857e-05 1.79272667312429e-05 3.11971394939809e-05 -4.89884194448557e-06 1.19604680194992e-05 -2.97858610782788e-06 1.88434790297021e-05 -3.18314382610094e-06 -4.89884194448557e-06 1.04672292584113e-05 2.11533546355317e-06 4.20298108154893e-06 -1.25097950495378e-06 1.80639435894265e-06 1.19604680194992e-05 2.11533546355317e-06 6.41069511809263e-05 -2.97777469001254e-05 -4.22084776108262e-06 5.37982811283556e-08 -2.97858610782788e-06 4.20298108154893e-06 -2.97777469001254e-05 4.87443435806163e-05 9.97387085244963e-06 1.51215478153857e-05 1.88434790297021e-05 -1.25097950495378e-06 -4.22084776108262e-06 9.97387085244963e-06 6.06381728966878e-05 1458 1447 0 15 40 1446 1471 0 41 24 0 0 0 0 0 16 47 0 464 0 54 46 0 0 2502 +368 423 0.999999731547178 3.90448456917067e-05 -0.000731697390708302 -0.0046094649082124 -3.92648669945974e-05 0.999999954022525 -0.000300687907465197 0.00572486950275108 0.000731685616753756 0.000300716556745407 0.999999687102806 -0.00563014622177385 2.30087442350424e-05 1.38791157237829e-05 -6.3140625009851e-06 3.1595523044336e-06 7.2622681891109e-06 1.37500880161985e-05 1.38791157237829e-05 2.32278002257712e-05 -6.95630283501895e-06 8.19557941921257e-06 4.06283849479525e-06 9.97231692101941e-06 -6.3140625009851e-06 -6.95630283501895e-06 1.19409140287384e-05 5.60333986388901e-07 -2.5143326260589e-07 -1.08856777220372e-06 3.1595523044336e-06 8.19557941921257e-06 5.60333986388901e-07 4.28215168963612e-05 -3.46889731478732e-06 6.36088393285834e-06 7.2622681891109e-06 4.06283849479525e-06 -2.5143326260589e-07 -3.46889731478732e-06 4.06183972640194e-05 7.62216461034088e-06 1.37500880161985e-05 9.97231692101941e-06 -1.08856777220372e-06 6.36088393285834e-06 7.62216461034088e-06 5.77205640649032e-05 2365 2372 0 21 12 2369 2388 0 35 22 0 0 0 0 0 23 54 0 608 0 23 34 0 0 2302 +368 410 0.999997069501809 0.000493903067192775 0.0023700311291936 -0.00734889363257931 -0.000495831318005682 0.99999954652709 0.000813078667217362 0.0106799027794471 -0.00236962847240108 -0.000814251420150302 0.999996860922837 -0.00370192463107191 3.69788110566052e-05 2.43530975097391e-05 -3.79879593979351e-06 5.84031773718087e-06 -5.27526694990521e-07 2.10650743103648e-05 2.43530975097391e-05 3.30460504021489e-05 -4.32432276396686e-06 8.13668456476907e-06 -1.87031909302302e-06 1.64089327379843e-05 -3.79879593979351e-06 -4.32432276396686e-06 1.11908365764758e-05 3.16104063805076e-06 2.37733773895003e-06 -3.71320738933257e-06 5.84031773718087e-06 8.13668456476907e-06 3.16104063805076e-06 4.04215451462818e-05 -1.41545637922914e-05 1.99540203273031e-06 -5.27526694990521e-07 -1.87031909302302e-06 2.37733773895003e-06 -1.41545637922914e-05 4.05454327609905e-05 9.41312368319328e-07 2.10650743103648e-05 1.64089327379843e-05 -3.71320738933257e-06 1.99540203273031e-06 9.41312368319328e-07 4.98309973905202e-05 2340 2336 0 17 10 2333 2364 0 43 19 0 0 0 0 0 23 52 0 507 0 11 18 0 0 2242 +368 422 0.999997085831885 0.000119176260064716 0.00241124962566617 -0.00488105714877126 -0.000123941553382524 0.999998039589637 0.00197622250095473 0.00783271319707769 -0.0024110093798207 -0.00197651559593433 0.999995140198126 -0.00956031747588391 2.7080055737864e-05 1.77530657926673e-05 -7.43932513393169e-06 5.02023013299373e-06 1.02475705917149e-05 1.51738596323525e-05 1.77530657926673e-05 2.58284021808236e-05 -8.45338109004715e-06 3.33627881383096e-06 2.81683744050146e-06 1.07096441459903e-05 -7.43932513393169e-06 -8.45338109004715e-06 1.25536970328704e-05 4.9708313174908e-07 -1.27846126385664e-06 -8.51210260727723e-07 5.02023013299373e-06 3.33627881383096e-06 4.9708313174908e-07 3.73846616514272e-05 -6.01607083434228e-06 4.72805102427402e-07 1.02475705917149e-05 2.81683744050146e-06 -1.27846126385664e-06 -6.01607083434228e-06 4.13346470152515e-05 6.91767169180051e-06 1.51738596323525e-05 1.07096441459903e-05 -8.51210260727723e-07 4.72805102427402e-07 6.91767169180051e-06 5.12569451765633e-05 2499 2502 0 23 15 2494 2520 0 42 25 0 0 0 0 0 11 45 0 589 0 48 51 0 0 2410 +368 421 0.999997060194381 0.000715488455995118 0.00231682516931549 -0.00478000645907061 -0.000720026432973167 0.999997822988673 0.00195846364536363 0.0121606841951308 -0.00231541886743111 -0.00196012606322369 0.999995398360055 -0.00470530075310755 3.36662082344215e-05 2.13423631822013e-05 -8.97065815095296e-06 1.10777120532979e-05 7.03554927070863e-06 1.88202366105574e-05 2.13423631822013e-05 2.51807844154416e-05 -9.67177301684456e-06 9.60551462928545e-06 5.11590612414924e-06 1.1389777199288e-05 -8.97065815095296e-06 -9.67177301684456e-06 1.33457599676384e-05 -2.17836244569001e-06 -1.4908019241981e-06 -2.99830261574587e-06 1.10777120532979e-05 9.60551462928545e-06 -2.17836244569001e-06 4.31566499035287e-05 -2.14447071568157e-06 6.47244046813898e-06 7.03554927070863e-06 5.11590612414924e-06 -1.4908019241981e-06 -2.14447071568157e-06 4.36256401587538e-05 3.81877504641195e-06 1.88202366105574e-05 1.1389777199288e-05 -2.99830261574587e-06 6.47244046813898e-06 3.81877504641195e-06 5.20829957541445e-05 2066 2064 0 16 14 2062 2096 0 48 23 0 0 0 0 0 21 54 0 613 0 23 32 0 0 2410 +368 411 0.999997665943669 0.000412292244581657 0.00212087772392659 -0.00221782746520349 -0.000416836498260872 0.999997617682369 0.00214263317454118 0.0117857553012467 -0.00211998928028135 -0.00214351223275834 0.999995455490054 -0.0049758082380331 3.56283617821996e-05 1.98177591260191e-05 -3.29494985648652e-06 4.14891013166436e-06 -1.94846722808771e-06 2.17204243915751e-05 1.98177591260191e-05 2.93447729447921e-05 -4.9539384744189e-06 7.83991899087182e-06 1.74515071554496e-06 1.44290982666694e-05 -3.29494985648652e-06 -4.9539384744189e-06 1.2282812767236e-05 3.6679823455556e-06 2.51509217361168e-06 -1.38467805075113e-06 4.14891013166436e-06 7.83991899087182e-06 3.6679823455556e-06 4.44340233038069e-05 -1.22065289312892e-05 -2.79204156439683e-07 -1.94846722808771e-06 1.74515071554496e-06 2.51509217361168e-06 -1.22065289312892e-05 4.7720438160383e-05 6.5122234113559e-06 2.17204243915751e-05 1.44290982666694e-05 -1.38467805075113e-06 -2.79204156439683e-07 6.5122234113559e-06 5.41275994538574e-05 1520 1520 0 17 12 1517 1536 0 35 21 0 0 0 0 0 23 54 0 546 0 19 29 0 0 2288 +368 426 0.999997602544995 0.00148936627869507 0.00160520788360298 -0.00555823483603635 -0.00149308160730011 0.999996203791409 0.00231583895899282 0.0159821589992505 -0.00160175265744661 -0.00231823011324001 0.999996030090903 -0.00552935837006591 3.89921733949137e-05 1.9367266537161e-05 -9.27908349688698e-06 6.23745338495131e-06 4.80089917534484e-06 2.13469115796892e-05 1.9367266537161e-05 2.72582932619167e-05 -9.58802140756722e-06 5.43145755352883e-06 7.41165375667147e-06 1.53347764373526e-05 -9.27908349688698e-06 -9.58802140756722e-06 1.65764714139093e-05 2.36088947928942e-06 -4.14567362662062e-06 -5.07479829570309e-06 6.23745338495131e-06 5.43145755352883e-06 2.36088947928942e-06 4.2489765039872e-05 -9.45098343788339e-06 2.98688530116931e-06 4.80089917534484e-06 7.41165375667147e-06 -4.14567362662062e-06 -9.45098343788339e-06 6.25414437408394e-05 9.26371305627914e-06 2.13469115796892e-05 1.53347764373526e-05 -5.07479829570309e-06 2.98688530116931e-06 9.26371305627914e-06 5.66610588597435e-05 2147 2147 0 16 17 2146 2173 0 43 20 0 0 0 0 0 22 51 0 633 0 27 37 0 0 2112 +368 424 0.99999866849436 0.000517456147783162 0.00154765908482549 -0.00745543988929357 -0.000518788603512598 0.999999495051248 0.000860671617787392 0.0121210177351721 -0.00154721294351712 -0.000861473379693608 0.999998431996632 -0.00748642044285798 2.37682170226054e-05 1.55502169503356e-05 -5.72377415368753e-06 2.8423527430676e-06 6.53015858238425e-06 1.59200932089934e-05 1.55502169503356e-05 2.04417544907243e-05 -7.20532496566807e-06 2.70380584930298e-06 5.01225801846887e-06 8.70010325467422e-06 -5.72377415368753e-06 -7.20532496566807e-06 1.193630412886e-05 2.34962555040389e-06 -1.05349340240019e-06 -2.6934291973258e-06 2.8423527430676e-06 2.70380584930298e-06 2.34962555040389e-06 3.87929929952873e-05 -6.89118473501383e-06 -1.49816227094772e-06 6.53015858238425e-06 5.01225801846887e-06 -1.05349340240019e-06 -6.89118473501383e-06 5.04111126095739e-05 8.03565141452629e-06 1.59200932089934e-05 8.70010325467422e-06 -2.6934291973258e-06 -1.49816227094772e-06 8.03565141452629e-06 4.69688914752372e-05 2361 2359 0 15 15 2355 2389 0 38 15 0 0 0 0 0 16 47 0 614 0 14 18 0 0 2309 +368 396 0.999997758743486 -5.14690218283546e-05 0.00211656772719165 -0.00650201609622919 4.52148167345086e-05 0.999995633480625 0.00295482238107525 0.00661766925161062 -0.00211671056697529 -0.00295472005833845 0.99999339456106 -0.00832000204267933 2.30371578809954e-05 1.03428372883209e-05 -6.64676905163275e-07 -3.3161249078283e-06 -7.27751144231478e-07 6.41335145316071e-06 1.03428372883209e-05 2.32694347659028e-05 -1.94036176620536e-06 2.38023032144867e-06 7.38304974794758e-07 8.57966239057806e-07 -6.64676905163275e-07 -1.94036176620536e-06 1.09148355758192e-05 4.82795843726121e-06 2.32145287369325e-06 -1.04061654656185e-06 -3.3161249078283e-06 2.38023032144867e-06 4.82795843726121e-06 4.19912250095719e-05 -3.79430481703085e-06 -1.65315781757629e-06 -7.27751144231478e-07 7.38304974794758e-07 2.32145287369325e-06 -3.79430481703085e-06 3.43107172445565e-05 4.5521611205372e-07 6.41335145316071e-06 8.57966239057806e-07 -1.04061654656185e-06 -1.65315781757629e-06 4.5521611205372e-07 3.93262793003688e-05 2330 2314 0 17 44 2309 2342 0 39 24 0 0 0 0 0 23 52 0 460 0 47 30 0 0 2472 +368 394 0.999991428282248 0.000137129905474911 0.00413818286430161 -0.00242185556699854 -0.00014877662354059 0.999996028851097 0.00281427567113886 0.00428993498113356 -0.00413778050960451 -0.00281486721283627 0.999987477569109 -0.00752117246105476 2.70212698373001e-05 6.65515350597868e-06 8.98127220376993e-07 -5.01632309314656e-07 -3.36073670930795e-06 6.82476260821283e-06 6.65515350597868e-06 2.85025729214384e-05 -1.70413727953306e-06 9.90543767928074e-06 1.86994692331488e-06 3.62940492962352e-06 8.98127220376993e-07 -1.70413727953306e-06 1.07603386123564e-05 2.73518392604925e-06 4.80111355842957e-06 -1.15771222609135e-06 -5.01632309314656e-07 9.90543767928074e-06 2.73518392604925e-06 4.70151290212005e-05 -1.11278694175778e-05 5.80083570200465e-06 -3.36073670930795e-06 1.86994692331488e-06 4.80111355842957e-06 -1.11278694175778e-05 3.85338485295671e-05 -7.11552978548733e-06 6.82476260821283e-06 3.62940492962352e-06 -1.15771222609135e-06 5.80083570200465e-06 -7.11552978548733e-06 4.43255836431314e-05 1663 1646 0 10 42 1645 1691 0 48 24 0 0 0 0 0 17 50 0 461 0 46 27 0 0 2447 +368 395 0.999997979615787 0.000151346827577868 0.00200445964836142 -0.0048368967402366 -0.000152894400471809 0.999999690370439 0.000771934147551751 0.00574508776163321 -0.00200434219793713 -0.000772239058604392 0.999997693126934 -0.0081278906448718 3.9812872303163e-05 1.89112949641794e-05 -1.17612489469944e-06 -5.37798628681626e-06 -1.59718436137341e-06 1.43518013746828e-05 1.89112949641794e-05 3.25736254911616e-05 -1.74836130419555e-06 2.77129789449876e-06 2.98070681341782e-06 1.86781710540541e-05 -1.17612489469944e-06 -1.74836130419555e-06 1.03531135451968e-05 3.80776775027974e-06 3.01072282675039e-06 -7.60079393914392e-07 -5.37798628681626e-06 2.77129789449876e-06 3.80776775027974e-06 5.14023949333923e-05 -2.36818992305515e-05 6.47134202826822e-06 -1.59718436137341e-06 2.98070681341782e-06 3.01072282675039e-06 -2.36818992305515e-05 4.27220222925868e-05 -2.83072986956656e-06 1.43518013746828e-05 1.86781710540541e-05 -7.60079393914392e-07 6.47134202826822e-06 -2.83072986956656e-06 5.18113643717639e-05 2577 2557 0 18 49 2541 2572 0 47 26 0 0 0 0 0 17 48 0 456 0 93 78 0 0 2435 +368 425 0.999997256400539 0.00119841951792145 0.00201270515798027 -0.00666962221179573 -0.00119699003365868 0.999999030643911 -0.00071128482135307 0.00827583641715083 -0.00201355562456498 0.000708873681857622 0.999997721543329 -0.00571436338472234 5.46851579294413e-05 9.41094579169164e-06 -9.03443660188208e-06 3.47618951167877e-06 -1.04182286879546e-06 1.13967201458484e-05 9.41094579169164e-06 3.63475633278091e-05 -7.67325534022207e-06 1.65773260035694e-05 8.70555880092964e-06 1.42644263604388e-05 -9.03443660188208e-06 -7.67325534022207e-06 1.40676091743094e-05 -7.45207594666923e-07 -1.15730101175185e-06 -2.52311233986677e-06 3.47618951167877e-06 1.65773260035694e-05 -7.45207594666923e-07 4.51035152459574e-05 -3.55288711321361e-06 8.83709852890848e-06 -1.04182286879546e-06 8.70555880092964e-06 -1.15730101175185e-06 -3.55288711321361e-06 4.63621314103463e-05 3.04819600433636e-06 1.13967201458484e-05 1.42644263604388e-05 -2.52311233986677e-06 8.83709852890848e-06 3.04819600433636e-06 5.22359118678895e-05 2599 2600 0 23 16 2590 2623 0 40 23 0 0 0 0 0 13 43 0 608 0 16 19 0 0 2024 +368 413 0.999999280118208 6.73868808503479e-06 0.00119988235093418 -0.00514863145189086 -1.13854146380308e-05 0.999992501054421 0.00387268708993072 0.00684536775023882 -0.00119984725625138 -0.00387269796321188 0.99999178125475 -0.0108151856551184 4.89035988748029e-05 3.80692056819053e-05 -6.55757773454146e-06 9.89242438876247e-06 1.92030945907263e-06 4.24023685015128e-05 3.80692056819053e-05 4.97880078570468e-05 -9.19372433189952e-06 1.02223012090474e-05 9.78859634703677e-06 3.90600804178822e-05 -6.55757773454146e-06 -9.19372433189952e-06 1.44916285925749e-05 3.21063240896737e-06 -2.61922253525667e-06 -3.99694764041897e-06 9.89242438876247e-06 1.02223012090474e-05 3.21063240896737e-06 3.85735561962993e-05 -5.92691988814211e-06 3.22281638788937e-06 1.92030945907263e-06 9.78859634703677e-06 -2.61922253525667e-06 -5.92691988814211e-06 4.91779269074549e-05 7.98613529937091e-06 4.24023685015128e-05 3.90600804178822e-05 -3.99694764041897e-06 3.22281638788937e-06 7.98613529937091e-06 8.64650636213203e-05 1622 1623 0 21 11 1614 1643 0 39 20 0 0 0 0 0 13 46 0 592 0 12 19 0 0 2225 +368 420 0.999998855889453 0.000905937502086544 0.00121140291683437 -0.0027889577949691 -0.000906958891435654 0.999999233503898 0.000842862495418797 0.00819417972675075 -0.00121063840755505 -0.000843960223737461 0.999998911042301 -0.00832207163772024 3.64217493878803e-05 2.08992210783626e-05 -8.94162331142304e-06 2.29878012353578e-06 1.18400954688864e-05 1.47152311500344e-05 2.08992210783626e-05 3.8275444280828e-05 -1.01019888857984e-05 1.12980566099698e-05 1.06495850223494e-05 8.31809148870974e-06 -8.94162331142304e-06 -1.01019888857984e-05 1.47930825953808e-05 1.57808042470869e-06 -2.56026943403213e-06 -2.04828157101298e-06 2.29878012353578e-06 1.12980566099698e-05 1.57808042470869e-06 5.20028968513453e-05 -1.20456918599702e-05 -1.12215137201911e-05 1.18400954688864e-05 1.06495850223494e-05 -2.56026943403213e-06 -1.20456918599702e-05 5.19694521927836e-05 1.08285964716659e-05 1.47152311500344e-05 8.31809148870974e-06 -2.04828157101298e-06 -1.12215137201911e-05 1.08285964716659e-05 6.2053360415492e-05 1474 1475 0 17 11 1477 1511 0 50 23 0 0 0 0 0 19 50 0 618 0 19 28 0 0 2258 +369 429 0.999973559017266 -0.0070843050190729 -0.00164130702165937 -0.010820478120677 0.00708690803889732 0.999973630467062 0.00158559293996973 0.00893964598854705 0.00163003091713697 -0.00159718280726027 0.999997395999754 -0.00770453749334943 2.43499394952541e-05 8.31131325144002e-06 -3.01674100240193e-06 -7.00254628101376e-07 1.40028867659942e-06 1.09984012323563e-05 8.31131325144002e-06 2.20917547113373e-05 -4.86001259737822e-06 5.32867877350707e-06 3.75334299774948e-06 4.45510983505379e-06 -3.01674100240193e-06 -4.86001259737822e-06 1.04849769695387e-05 3.3192464850642e-06 2.55326598281684e-06 -1.14256566200083e-06 -7.00254628101376e-07 5.32867877350707e-06 3.3192464850642e-06 4.12654792151509e-05 -1.10579386446083e-05 -2.55123631481263e-06 1.40028867659942e-06 3.75334299774948e-06 2.55326598281684e-06 -1.10579386446083e-05 4.5548301412564e-05 4.168214782035e-06 1.09984012323563e-05 4.45510983505379e-06 -1.14256566200083e-06 -2.55123631481263e-06 4.168214782035e-06 5.03847100166572e-05 1799 1800 0 6 25 1799 1824 0 33 21 0 0 0 0 0 30 61 0 617 0 15 15 0 0 2457 +368 412 0.999999738820314 0.000279220139208293 0.000666629895996362 -0.00285197444487396 -0.000278582482885565 0.99999950380842 -0.000956438557527272 0.00529770890740444 -0.000666896622127397 0.000956252596313358 0.999999320414703 -0.00520331135644698 4.2469777214059e-05 2.47560547644371e-05 -4.98762317474011e-06 2.44805658692345e-06 6.46471679925716e-06 2.22098759851512e-05 2.47560547644371e-05 3.13494425418498e-05 -6.14469902881755e-06 4.9325771118763e-06 6.00221200775598e-06 1.9806239666336e-05 -4.98762317474011e-06 -6.14469902881755e-06 1.0365787640799e-05 9.26255605819321e-07 1.62724421886019e-06 -3.12095787084785e-06 2.44805658692345e-06 4.9325771118763e-06 9.26255605819321e-07 4.28473375266242e-05 -1.56327873410202e-05 4.4731416922844e-06 6.46471679925716e-06 6.00221200775598e-06 1.62724421886019e-06 -1.56327873410202e-05 4.20558808149104e-05 4.66148779497086e-06 2.22098759851512e-05 1.9806239666336e-05 -3.12095787084785e-06 4.4731416922844e-06 4.66148779497086e-06 5.60209934580604e-05 2355 2352 0 11 9 2358 2382 0 38 21 0 0 0 0 0 18 49 0 577 0 23 31 0 0 2227 +368 419 0.999997515021214 -0.000488978696590799 0.00217505200633067 0.000367954017522288 0.000484993846239152 0.999998203870863 0.00183222160692361 0.00298412329149114 -0.00217594401698961 -0.00183116216705347 0.9999959560482 -0.0109248198955482 4.15782865633074e-05 2.65416502824942e-05 -8.46264886192031e-06 6.93596957737713e-06 1.14442594470246e-05 1.99323049347194e-05 2.65416502824942e-05 3.69548495911965e-05 -9.44067888298286e-06 9.07960313984033e-06 1.08583047948741e-05 1.58317183066712e-05 -8.46264886192031e-06 -9.44067888298286e-06 1.31247163755167e-05 -7.76388796640416e-07 -2.29788010031344e-06 -3.64969775795155e-06 6.93596957737713e-06 9.07960313984033e-06 -7.76388796640416e-07 3.77024042167397e-05 -1.37746884009173e-06 3.69634864680379e-06 1.14442594470246e-05 1.08583047948741e-05 -2.29788010031344e-06 -1.37746884009173e-06 4.32206604634859e-05 8.89256359021026e-06 1.99323049347194e-05 1.58317183066712e-05 -3.64969775795155e-06 3.69634864680379e-06 8.89256359021026e-06 5.7393130713074e-05 2138 2139 0 17 14 2128 2146 0 34 21 0 0 0 0 0 19 51 0 590 0 57 63 0 0 2318 +369 371 0.999999293473623 -8.67414712522881e-05 0.0011855497343724 -0.00905634532405919 8.51354098739941e-05 0.99999907879534 0.00135468093450281 0.000463431856729581 -0.0011856661492558 -0.00135457904512243 0.999998379654384 -0.00716615862832867 2.5790286580411e-05 1.32630705492235e-05 -9.39282230746797e-06 3.08408891696314e-06 6.16522639545514e-06 8.38185157135691e-06 1.32630705492235e-05 2.94604746793185e-05 -1.2471611315871e-05 1.48107878828219e-05 5.65847664465585e-06 1.80940616650852e-05 -9.39282230746797e-06 -1.2471611315871e-05 1.68034293090883e-05 -1.3789684395287e-06 -3.62546560464518e-06 -6.6110983974711e-06 3.08408891696314e-06 1.48107878828219e-05 -1.3789684395287e-06 4.36353156343521e-05 2.11125068552845e-06 1.07369439320804e-05 6.16522639545514e-06 5.65847664465585e-06 -3.62546560464518e-06 2.11125068552845e-06 4.07806516533902e-05 9.25103240873112e-06 8.38185157135691e-06 1.80940616650852e-05 -6.6110983974711e-06 1.07369439320804e-05 9.25103240873112e-06 4.0488848737075e-05 1571 1543 0 11 57 1513 1541 0 48 7 0 0 0 0 0 22 54 0 671 0 103 83 0 0 2370 +369 407 0.999993263541591 -0.000128404110545269 0.00366829440251522 -0.0149723136471408 0.000117391043701046 0.9999954862314 0.00300228848865379 0.0123158937957091 -0.00366866335086612 -0.00300183763895374 0.99998876487689 -0.0134912098894484 2.93015346134752e-05 1.01466754484787e-05 -4.38459649771383e-07 -5.02846389808175e-06 2.37951539406951e-06 1.23586799095208e-05 1.01466754484787e-05 3.41333441625121e-05 7.72162904010925e-07 6.86790396648398e-06 2.41983290619868e-06 1.52746890205437e-05 -4.38459649771383e-07 7.72162904010925e-07 1.21972753481097e-05 2.87820250828135e-06 4.2176089115363e-06 2.06246994993997e-06 -5.02846389808175e-06 6.86790396648398e-06 2.87820250828135e-06 4.72520157718784e-05 -1.22335540282252e-05 3.23242185096927e-06 2.37951539406951e-06 2.41983290619868e-06 4.2176089115363e-06 -1.22335540282252e-05 3.86730758267534e-05 1.0003556544036e-05 1.23586799095208e-05 1.52746890205437e-05 2.06246994993997e-06 3.23242185096927e-06 1.0003556544036e-05 6.44272517506318e-05 1671 1668 0 12 17 1667 1691 0 41 13 0 0 0 0 0 23 51 0 490 0 43 47 0 0 2243 +369 400 0.999995993164658 -0.000102981236020891 0.00282896615272515 -0.00132550804199466 0.000103182604692473 0.999999992153679 -7.10351531441739e-05 -0.00743829047828844 -0.0028289588152403 7.13267686142368e-05 0.999995995944241 -0.00921948185722938 5.24258575094534e-05 4.71982785921538e-05 -4.06430000400796e-06 1.8084030435235e-05 -1.23397082585921e-05 4.0105761701873e-05 4.71982785921538e-05 7.27521764945939e-05 -4.923962621978e-06 2.83056733385244e-05 -1.60301166914593e-05 4.66327333356358e-05 -4.06430000400796e-06 -4.923962621978e-06 1.04350047171336e-05 2.6982204731519e-06 3.87681140673591e-06 -1.36004241912362e-06 1.8084030435235e-05 2.83056733385244e-05 2.6982204731519e-06 6.31193533890575e-05 -2.85753851851078e-05 3.4591230777931e-05 -1.23397082585921e-05 -1.60301166914593e-05 3.87681140673591e-06 -2.85753851851078e-05 5.97537268380316e-05 -1.47760039395268e-05 4.0105761701873e-05 4.66327333356358e-05 -1.36004241912362e-06 3.4591230777931e-05 -1.47760039395268e-05 0.000105178267026278 1655 1637 0 18 42 1633 1663 0 50 22 0 0 0 0 0 17 49 0 500 0 82 70 0 0 2359 +369 399 0.999987614111714 -4.45040779589242e-05 0.00497691094443307 0.00143255349187022 3.7538013177296e-05 0.999999019629469 0.00139976105069183 -0.00428244422018398 -0.00497696836029117 -0.00139955689005922 0.99998663542392 -0.00329416977666293 3.74274224113844e-05 2.13891564639936e-05 -6.43643515250527e-06 4.89099262012625e-06 5.26635040715741e-06 1.68981700052341e-05 2.13891564639936e-05 3.0032630910297e-05 -6.72940322590374e-06 8.28620494759407e-06 8.79712534994172e-06 1.91589432502479e-05 -6.43643515250527e-06 -6.72940322590374e-06 1.15764404602419e-05 2.17497203819746e-06 2.94588159752642e-07 -3.51143380904026e-06 4.89099262012625e-06 8.28620494759407e-06 2.17497203819746e-06 4.8136470176775e-05 -2.14202871485461e-05 8.8463672657974e-06 5.26635040715741e-06 8.79712534994172e-06 2.94588159752642e-07 -2.14202871485461e-05 6.42965410788233e-05 6.81459380433998e-06 1.68981700052341e-05 1.91589432502479e-05 -3.51143380904026e-06 8.8463672657974e-06 6.81459380433998e-06 5.47434637151342e-05 1705 1683 0 19 46 1683 1713 0 46 25 0 0 0 0 0 13 45 0 487 0 52 38 0 0 2330 +369 406 0.99999319636021 -0.000211403546452685 0.00368273564503553 -0.00539180038805468 0.000212346478600731 0.999999944775487 -0.000255652097923957 0.00760627637359269 -0.00368268139589809 0.000256432374505012 0.999993186026872 -0.00636430466814412 5.39224615955403e-05 2.78982718431386e-05 -2.35729503948723e-06 -4.71042661344795e-07 -3.16267324094686e-06 2.59367099736982e-05 2.78982718431386e-05 3.98097348353619e-05 -3.13100220305125e-06 3.95817850057044e-06 1.91867286393638e-06 1.47817655215752e-05 -2.35729503948723e-06 -3.13100220305125e-06 1.14924684815082e-05 4.20381729875692e-06 1.24033088093683e-06 -5.60921670248084e-07 -4.71042661344795e-07 3.95817850057044e-06 4.20381729875692e-06 4.19175113521977e-05 -1.63623609947968e-05 -3.54362408111997e-07 -3.16267324094686e-06 1.91867286393638e-06 1.24033088093683e-06 -1.63623609947968e-05 4.57141288827283e-05 1.04629812643328e-06 2.59367099736982e-05 1.47817655215752e-05 -5.60921670248084e-07 -3.54362408111997e-07 1.04629812643328e-06 5.98273933249767e-05 2176 2175 0 17 17 2169 2200 0 47 11 0 0 0 0 0 24 55 0 470 0 39 42 0 0 2212 +369 402 0.999999545698791 0.000456677779619555 0.000836688482375965 -0.0077122991912786 -0.000457307604928464 0.99999961213883 0.000752723019803918 0.00784115166066161 -0.000836344405979639 -0.000753105301846887 0.999999366680019 -0.00613293930892324 2.79590148761543e-05 1.49497913694866e-05 -1.5206928154323e-06 -4.87880205202026e-07 -1.47685595123247e-07 1.1270015842631e-05 1.49497913694866e-05 2.63555564710574e-05 -4.58905523866812e-06 2.37874927442626e-06 -4.73526968318098e-07 1.53876701086316e-05 -1.5206928154323e-06 -4.58905523866812e-06 1.24323915483841e-05 3.48904791719671e-06 1.88859463369955e-06 1.03258218220717e-07 -4.87880205202026e-07 2.37874927442626e-06 3.48904791719671e-06 3.16176056214394e-05 -1.03178929396244e-05 6.18886049105584e-06 -1.47685595123247e-07 -4.73526968318098e-07 1.88859463369955e-06 -1.03178929396244e-05 4.07627097625311e-05 -7.81939935908468e-07 1.1270015842631e-05 1.53876701086316e-05 1.03258218220717e-07 6.18886049105584e-06 -7.81939935908468e-07 5.14828159738126e-05 2440 2432 0 17 39 2430 2456 0 43 28 0 0 0 0 0 26 56 0 476 0 56 57 0 0 2267 +369 372 0.99999851437506 0.000662318599673059 -0.00159140872983247 -0.00808661509792384 -0.000665512412040591 0.999997764081677 -0.00200721819360885 -0.00395829025658521 0.00159007575362931 0.00200827431389777 0.999996719241307 -0.00448509692805712 2.84402224985609e-05 1.51243913143165e-05 -8.87731625649485e-06 5.26344411016279e-06 6.22610693267229e-06 1.23442784172026e-05 1.51243913143165e-05 2.26055440438284e-05 -9.77172048584067e-06 5.71700902811138e-06 5.93865222619103e-06 1.57453354874155e-05 -8.87731625649485e-06 -9.77172048584067e-06 1.42286839513626e-05 6.53491793788728e-08 -8.19160107405569e-07 -5.24180753655686e-06 5.26344411016279e-06 5.71700902811138e-06 6.53491793788728e-08 3.54531470022411e-05 7.59905412614497e-06 7.92785289900483e-06 6.22610693267229e-06 5.93865222619103e-06 -8.19160107405569e-07 7.59905412614497e-06 3.25235959325123e-05 5.47652325413225e-06 1.23442784172026e-05 1.57453354874155e-05 -5.24180753655686e-06 7.92785289900483e-06 5.47652325413225e-06 3.44421914717748e-05 2486 2467 0 23 55 2424 2454 0 50 7 0 0 0 0 0 12 44 0 675 0 107 87 0 0 2626 +369 405 0.999962057069859 0.000479409486482413 0.00869796454126337 0.000344799583723991 -0.000479208362282067 0.999999884861964 -2.52072275591162e-05 0.00872533457364145 -0.00869797562438084 2.10381337800355e-05 0.999962171673226 -0.00278972585197075 7.80946027598629e-05 4.19914755917656e-05 1.19198986543271e-06 1.02928736767706e-05 -1.61598133689541e-05 5.31420627438659e-05 4.19914755917656e-05 7.34891804258619e-05 -1.24052088384734e-07 1.17423602966946e-05 1.19968150442445e-06 4.94731927444007e-05 1.19198986543271e-06 -1.24052088384734e-07 1.23485273226481e-05 3.99900494469819e-06 4.51515072353331e-06 1.66683386332939e-06 1.02928736767706e-05 1.17423602966946e-05 3.99900494469819e-06 3.61074520548682e-05 -1.03176416934052e-05 1.37116343986269e-05 -1.61598133689541e-05 1.19968150442445e-06 4.51515072353331e-06 -1.03176416934052e-05 5.1869090481451e-05 -1.1184515377112e-05 5.31420627438659e-05 4.94731927444007e-05 1.66683386332939e-06 1.37116343986269e-05 -1.1184515377112e-05 0.000104776966213771 1637 1636 0 14 19 1631 1658 0 43 10 0 0 0 0 0 21 52 0 454 0 51 55 0 0 2221 +369 404 0.999994158455509 0.000587826892683242 0.00336712257003902 -0.0110567758119293 -0.00058785188458014 0.999999827194377 6.43264784762552e-06 0.0133573517568104 -0.00336711820689791 -8.41197961943668e-06 0.999994331206042 -0.00239607923723041 2.90148456701754e-05 2.0420447920672e-05 3.45265906728843e-07 3.62410734717932e-06 -1.47042089805369e-07 2.01470243105037e-05 2.0420447920672e-05 2.66309552908478e-05 -1.92742248084577e-06 5.32382448837794e-06 -3.76588760597981e-06 1.54917957581494e-05 3.45265906728843e-07 -1.92742248084577e-06 1.2563487898135e-05 3.33322600411281e-06 1.02093120681957e-06 6.93705480182635e-07 3.62410734717932e-06 5.32382448837794e-06 3.33322600411281e-06 5.61390505633124e-05 -2.07739820073853e-05 5.27386890559218e-06 -1.47042089805369e-07 -3.76588760597981e-06 1.02093120681957e-06 -2.07739820073853e-05 5.77952872233446e-05 8.49517248984424e-06 2.01470243105037e-05 1.54917957581494e-05 6.93705480182635e-07 5.27386890559218e-06 8.49517248984424e-06 6.08265354515578e-05 2290 2287 0 17 28 2285 2305 0 38 24 0 0 0 0 0 20 49 0 452 0 45 46 0 0 2165 +369 373 0.999997679631701 0.000592758656795921 -0.00207107903974498 -0.0109418869710696 -0.000594065992199944 0.999999624666745 -0.000630675801887533 0.0076299016103329 0.00207070442385894 0.000631904696112066 0.999997656437076 -0.00387216239379507 3.24114280295542e-05 1.61916994527861e-05 -7.37051229203513e-06 2.76804421929649e-06 6.27727076545865e-06 1.9733664912724e-05 1.61916994527861e-05 3.45148975711192e-05 -1.11713111867121e-05 1.07052245954348e-05 8.91156074072355e-06 1.02950228126745e-05 -7.37051229203513e-06 -1.11713111867121e-05 1.59227989294743e-05 -9.36653617345697e-07 -3.37091764548042e-06 -3.91272604605028e-06 2.76804421929649e-06 1.07052245954348e-05 -9.36653617345697e-07 6.44584985745583e-05 -3.83752137856622e-05 2.55289031299601e-06 6.27727076545865e-06 8.91156074072355e-06 -3.37091764548042e-06 -3.83752137856622e-05 7.1388187506196e-05 1.38200627254306e-06 1.9733664912724e-05 1.02950228126745e-05 -3.91272604605028e-06 2.55289031299601e-06 1.38200627254306e-06 6.18186889154119e-05 1949 1927 0 16 59 1922 1942 0 37 29 0 0 0 0 0 23 52 0 668 0 81 65 0 0 2534 +369 408 0.999998483440826 -7.13030484698802e-05 0.00174012411130215 -0.00611640040884193 7.03440959724645e-05 0.999999845649405 0.000551137799024129 0.00574104674104208 -0.00174016314051816 -0.000551014555733555 0.999998334106214 -0.00705038942417956 4.68036183854133e-05 3.0976172461296e-05 -3.77100752802587e-06 5.21629075564762e-06 -4.24926406132358e-06 2.95093360847635e-05 3.0976172461296e-05 3.84667341279082e-05 -3.40047325743624e-06 8.31606113505335e-06 -3.70609736088945e-06 3.33799503143201e-05 -3.77100752802587e-06 -3.40047325743624e-06 1.00984248753526e-05 3.13630677217374e-06 3.92439635898289e-06 -1.48126173684182e-06 5.21629075564762e-06 8.31606113505335e-06 3.13630677217374e-06 4.02078874952698e-05 -1.75772978911305e-05 1.29943936977137e-05 -4.24926406132358e-06 -3.70609736088945e-06 3.92439635898289e-06 -1.75772978911305e-05 4.07022605129159e-05 -5.88728624385438e-06 2.95093360847635e-05 3.33799503143201e-05 -1.48126173684182e-06 1.29943936977137e-05 -5.88728624385438e-06 7.04373862336932e-05 2081 2080 0 15 15 2069 2095 0 42 8 0 0 0 0 0 16 47 0 489 0 52 56 0 0 2238 +369 401 0.999999846054441 -0.000490081264237578 0.000260214234957361 -0.00791855682823234 0.000490181049670866 0.99999980630635 -0.000383548954336694 -0.00354937352791073 -0.000260026214399078 0.000383676447377867 0.99999989258937 -0.0125227392698479 3.5428645215863e-05 1.90586291299396e-05 -4.90714752652695e-06 -6.49300867343901e-07 2.86688607879453e-06 1.47367767205552e-05 1.90586291299396e-05 4.12658871068061e-05 -5.08365444157158e-06 5.16384728909856e-06 1.02579427937956e-05 2.9186387948498e-05 -4.90714752652695e-06 -5.08365444157158e-06 1.32341327479666e-05 3.7745523912821e-06 2.68563370187666e-08 -1.81754751849732e-06 -6.49300867343901e-07 5.16384728909856e-06 3.7745523912821e-06 6.77204021545561e-05 -3.84535474864803e-05 -5.99955343620826e-06 2.86688607879453e-06 1.02579427937956e-05 2.68563370187666e-08 -3.84535474864803e-05 8.71351062542905e-05 2.73988536454766e-05 1.47367767205552e-05 2.9186387948498e-05 -1.81754751849732e-06 -5.99955343620826e-06 2.73988536454766e-05 7.30935340444002e-05 2293 2283 0 15 39 2280 2305 0 42 21 0 0 0 0 0 22 53 0 513 0 63 53 0 0 2288 +369 409 0.999999963921308 0.000245841580269699 -0.000108255717292667 -0.0140855435487173 -0.000245736278272947 0.999999497748386 0.00097165665607039 0.00940250704884236 0.000108494536528866 -0.000971630018657219 0.999999522081907 -0.0158154353801 4.2501468300893e-05 2.14487719669722e-05 -9.95543494049399e-07 -1.98223576465444e-06 -1.25035485469582e-06 1.91808629455795e-05 2.14487719669722e-05 3.44471025352293e-05 -2.98950208054046e-06 2.54716645894536e-06 2.99028386983322e-06 1.76465413085855e-05 -9.95543494049399e-07 -2.98950208054046e-06 1.22889944993222e-05 1.06724336425839e-06 4.04555622562271e-06 1.32934111659861e-06 -1.98223576465444e-06 2.54716645894536e-06 1.06724336425839e-06 4.84018794851457e-05 -1.45183011811002e-05 1.1974628389213e-06 -1.25035485469582e-06 2.99028386983322e-06 4.04555622562271e-06 -1.45183011811002e-05 4.86273432456782e-05 1.60987432422623e-06 1.91808629455795e-05 1.76465413085855e-05 1.32934111659861e-06 1.1974628389213e-06 1.60987432422623e-06 6.33660634075205e-05 2152 2148 0 12 10 2152 2178 0 45 9 0 0 0 0 0 13 45 0 505 0 37 42 0 0 2148 +369 421 0.999999998193875 -1.99683082634552e-05 5.66878897941586e-05 -0.00947161958011142 1.99323267415698e-05 0.999999798404715 0.000634659933533656 0.00873556293718519 -5.67005514513426e-05 -0.000634658802465839 0.999999796996605 -0.00928174174977686 3.03083524046142e-05 1.17895942777466e-05 -7.57502785217081e-06 1.84999647870358e-06 7.18505878403838e-06 1.31116845636175e-05 1.17895942777466e-05 2.43061096114756e-05 -8.0576416876111e-06 7.67442256483693e-06 4.25562134100014e-06 7.9091904704373e-06 -7.57502785217081e-06 -8.0576416876111e-06 1.42893520241927e-05 -5.78443656094902e-07 -2.08698128169284e-06 -2.57946943464007e-06 1.84999647870358e-06 7.67442256483693e-06 -5.78443656094902e-07 4.57371656003087e-05 -8.86836828586726e-06 -2.60183966617802e-06 7.18505878403838e-06 4.25562134100014e-06 -2.08698128169284e-06 -8.86836828586726e-06 4.85873045604889e-05 2.72603100095818e-06 1.31116845636175e-05 7.9091904704373e-06 -2.57946943464007e-06 -2.60183966617802e-06 2.72603100095818e-06 4.87463972292831e-05 2458 2457 0 16 14 2452 2485 0 44 11 0 0 0 0 0 18 50 0 627 0 15 21 0 0 2197 +369 410 0.999987515409549 -0.000210460846505058 0.00499246745300567 -0.00846631615556933 0.00021551564927212 0.999999464735224 -0.00101196950050842 0.011487022752479 -0.00499225180075599 0.00101303282134826 0.999987025509062 -0.0121259089489428 3.97624941710191e-05 2.67393930882319e-05 -1.96231314412068e-06 -2.43017030522846e-06 9.53927307838157e-07 2.04548186830454e-05 2.67393930882319e-05 4.70688845095026e-05 -1.34190486982405e-06 3.0676560865043e-06 5.63520035503069e-06 2.72219028890347e-05 -1.96231314412068e-06 -1.34190486982405e-06 1.01130466338951e-05 2.34948781119906e-06 4.75522408338667e-06 4.80932454022419e-07 -2.43017030522846e-06 3.0676560865043e-06 2.34948781119906e-06 5.17759537205992e-05 -2.68535200444017e-05 -5.45194436775019e-06 9.53927307838157e-07 5.63520035503069e-06 4.75522408338667e-06 -2.68535200444017e-05 5.02378224231897e-05 8.16732167511552e-06 2.04548186830454e-05 2.72219028890347e-05 4.80932454022419e-07 -5.45194436775019e-06 8.16732167511552e-06 6.8699771169684e-05 2080 2079 0 17 9 2077 2102 0 39 8 0 0 0 0 0 18 47 0 514 0 29 33 0 0 2158 +369 427 0.999999703377141 0.000751702274362366 -0.000167896756293518 -0.00955058086036586 -0.000751620377705135 0.999999598797075 0.000487311498272988 0.0108722130974971 0.000168263002094423 -0.000487185159101878 0.999999867169083 -0.00899051153004168 3.58841272751313e-05 1.46385270487619e-05 -9.67466638191744e-06 3.69002320395619e-06 1.15535480116267e-05 4.64890868091361e-06 1.46385270487619e-05 3.06610900903937e-05 -1.11470432940225e-05 1.03653857801294e-05 9.3237898548899e-06 1.37487106096475e-05 -9.67466638191744e-06 -1.11470432940225e-05 1.51743255981657e-05 -3.48403681712513e-06 -4.97810911141524e-06 -3.21170889002715e-06 3.69002320395619e-06 1.03653857801294e-05 -3.48403681712513e-06 5.26686962122183e-05 -1.02911168809731e-05 8.90621925470831e-06 1.15535480116267e-05 9.3237898548899e-06 -4.97810911141524e-06 -1.02911168809731e-05 5.08590377114277e-05 6.83112855134082e-06 4.64890868091361e-06 1.37487106096475e-05 -3.21170889002715e-06 8.90621925470831e-06 6.83112855134082e-06 5.02332439386848e-05 2465 2464 0 18 17 2458 2479 0 39 13 0 0 0 0 0 18 47 0 664 0 39 45 0 0 2343 +369 398 0.999998994064005 -9.72695087515622e-05 0.00141506523551219 -0.00324177400615677 9.81592331735053e-05 0.999999797553246 -0.000628695659823501 -0.0017703596031254 -0.00141500379611884 0.000628833929114315 0.999998801165355 -0.00700030451810911 3.67584678468785e-05 2.62039839354054e-05 -5.30327776582695e-06 7.04830373990993e-06 -4.09644280861595e-06 2.359935390915e-05 2.62039839354054e-05 3.1234623619979e-05 -5.26626095306899e-06 9.2191974669059e-06 -4.55850744119593e-06 1.86212023765408e-05 -5.30327776582695e-06 -5.26626095306899e-06 1.01142531997246e-05 3.85024368461944e-06 2.01769814469555e-06 -2.03466718124944e-06 7.04830373990993e-06 9.2191974669059e-06 3.85024368461944e-06 4.17295671752274e-05 -2.10896065178307e-05 5.11069758571695e-06 -4.09644280861595e-06 -4.55850744119593e-06 2.01769814469555e-06 -2.10896065178307e-05 4.7813024668549e-05 -6.80222585890122e-06 2.359935390915e-05 1.86212023765408e-05 -2.03466718124944e-06 5.11069758571695e-06 -6.80222585890122e-06 6.18975320529834e-05 2421 2401 0 19 45 2403 2426 0 47 27 0 0 0 0 0 13 45 0 477 0 71 61 0 0 2264 +369 428 0.999999280544301 2.77065144406976e-05 0.00119922609588711 -0.00983704508572407 -2.81728906011527e-05 0.999999923988356 0.000388882462552761 0.00757375972390903 -0.00119921523015439 -0.000388915968434663 0.999999205313285 -0.00653103204249593 4.3835992953689e-05 2.86221316507627e-05 -8.27754857424617e-06 1.33595916303624e-05 2.25308787513077e-06 2.76209936830267e-05 2.86221316507627e-05 3.74815782237265e-05 -9.22233805062176e-06 1.57836000990227e-05 2.08575390952932e-06 2.21116420740416e-05 -8.27754857424617e-06 -9.22233805062176e-06 1.3460454506676e-05 -1.39257681732084e-06 -2.38221822280061e-06 -3.15090416526725e-06 1.33595916303624e-05 1.57836000990227e-05 -1.39257681732084e-06 4.88271538073291e-05 -6.5861161399834e-06 1.3231377927878e-05 2.25308787513077e-06 2.08575390952932e-06 -2.38221822280061e-06 -6.5861161399834e-06 4.87187091837874e-05 -2.06024853499455e-06 2.76209936830267e-05 2.21116420740416e-05 -3.15090416526725e-06 1.3231377927878e-05 -2.06024853499455e-06 6.72294824205565e-05 2433 2430 0 15 16 2430 2458 0 45 14 0 0 0 0 0 14 46 0 634 0 37 45 0 0 2360 +369 426 0.999998567115728 0.000573330673514878 0.00159281462526216 -0.0103060566403818 -0.000573455772513499 0.99999983252567 7.80839898514271e-05 0.0116484153253219 -0.0015927695905601 -7.89972867075066e-05 0.999998728421422 -0.00759102994382229 3.18945729171652e-05 1.5873417405648e-05 -9.15808613512157e-06 5.0629229142492e-06 6.0160552510384e-06 1.46918902975509e-05 1.5873417405648e-05 2.49249853109674e-05 -9.01139561858276e-06 8.85776596032109e-06 2.07664205075221e-06 1.33937497604916e-05 -9.15808613512157e-06 -9.01139561858276e-06 1.38162634790436e-05 -1.6502719450699e-06 -1.15311489199623e-06 -3.66524165888229e-06 5.0629229142492e-06 8.85776596032109e-06 -1.6502719450699e-06 4.30379418387295e-05 -9.95558603207736e-06 5.78258969554569e-07 6.0160552510384e-06 2.07664205075221e-06 -1.15311489199623e-06 -9.95558603207736e-06 4.64300467913742e-05 7.54975117198672e-06 1.46918902975509e-05 1.33937497604916e-05 -3.66524165888229e-06 5.78258969554569e-07 7.54975117198672e-06 5.45209850807706e-05 2452 2450 0 17 17 2443 2474 0 43 13 0 0 0 0 0 11 39 0 653 0 16 19 0 0 2003 +369 397 0.999999971684149 0.000233121705723697 -4.78118231939669e-05 -0.00638670740303127 -0.000233075589980789 0.999999509852055 0.000962274087101427 0.00352830751119461 4.80361267356588e-05 -0.000962262916084919 0.999999535871198 -0.00420917792284674 3.29653094530896e-05 1.87605308351385e-05 -3.2853060601536e-06 7.12498403113911e-07 3.38016894492395e-06 1.7070870550067e-05 1.87605308351385e-05 2.51466730084517e-05 -3.84601628801927e-06 2.79121027476621e-06 2.2378108903924e-06 2.28908128121696e-05 -3.2853060601536e-06 -3.84601628801927e-06 1.09895359641619e-05 2.4207665304551e-06 1.9330354060438e-06 -7.74479348707343e-07 7.12498403113911e-07 2.79121027476621e-06 2.4207665304551e-06 4.16929608907744e-05 -1.93432588426757e-05 8.66825715556763e-06 3.38016894492395e-06 2.2378108903924e-06 1.9330354060438e-06 -1.93432588426757e-05 4.75003247996024e-05 3.90785713235377e-07 1.7070870550067e-05 2.28908128121696e-05 -7.74479348707343e-07 8.66825715556763e-06 3.90785713235377e-07 6.72338638621315e-05 2485 2469 0 15 45 2468 2504 0 46 31 0 0 0 0 0 18 48 0 465 0 48 31 0 0 2310 +369 423 0.999999494779643 0.000216785530568481 0.000981552082926562 -0.00925579457789185 -0.000217788973866963 0.999999453723733 0.00102231120416734 0.00780194895333107 -0.000981329924451153 -0.00102252445889584 0.999998995717151 -0.00904575217127747 2.58937207826818e-05 1.52547917361246e-05 -6.73805153145595e-06 1.92396033874217e-06 6.89236415585624e-06 1.49922474321769e-05 1.52547917361246e-05 2.20271256625366e-05 -8.18813914198808e-06 6.83652632665039e-06 3.80414063560823e-06 1.16974673484896e-05 -6.73805153145595e-06 -8.18813914198808e-06 1.33085865449335e-05 1.67059014647838e-06 -3.02167622050154e-06 -3.88069243324641e-06 1.92396033874217e-06 6.83652632665039e-06 1.67059014647838e-06 4.20230911450255e-05 -1.30412207983582e-05 -1.76812089239777e-06 6.89236415585624e-06 3.80414063560823e-06 -3.02167622050154e-06 -1.30412207983582e-05 5.12367179621933e-05 5.98709090720145e-06 1.49922474321769e-05 1.16974673484896e-05 -3.88069243324641e-06 -1.76812089239777e-06 5.98709090720145e-06 5.91054454098471e-05 1818 1816 0 11 12 1817 1853 0 47 10 0 0 0 0 0 23 54 0 628 0 12 15 0 0 2119 +369 403 0.999996993711168 0.000874727576771156 0.00229072484001508 -0.0064352971929142 -0.000875769699566184 0.999999513470168 0.000453967906252486 0.012327185006506 -0.00229032662726254 -0.000455972688898768 0.999997273242706 -0.000205538830404359 2.34621321212567e-05 1.1067869005354e-05 -4.80120080048762e-07 1.3655182288951e-06 -1.07199968985248e-06 1.0439229669817e-05 1.1067869005354e-05 2.44653358239321e-05 -2.60937884460121e-06 1.80946431372204e-06 3.20894676439294e-06 9.99420490655508e-06 -4.80120080048762e-07 -2.60937884460121e-06 1.06375417988707e-05 2.32265863152133e-06 2.49966834263073e-06 -1.60506396449997e-06 1.3655182288951e-06 1.80946431372204e-06 2.32265863152133e-06 3.24814853339043e-05 -6.84121967086292e-06 3.11380649951115e-06 -1.07199968985248e-06 3.20894676439294e-06 2.49966834263073e-06 -6.84121967086292e-06 3.78250306649548e-05 1.06142767200422e-05 1.0439229669817e-05 9.99420490655508e-06 -1.60506396449997e-06 3.11380649951115e-06 1.06142767200422e-05 5.80745622556684e-05 2342 2336 0 15 32 2330 2362 0 42 24 0 0 0 0 0 14 44 0 448 0 29 25 0 0 2204 +369 420 0.999998475364283 0.000340062977442713 -0.00171278319732647 -0.0111646619985784 -0.000341054201479118 0.9999997745316 -0.000578462427696266 0.00941293241335358 0.00171258609749248 0.000579045697657458 0.999998365876134 -0.0113926846791225 3.08928463005155e-05 1.76752215629586e-05 -8.13452722066197e-06 5.64822381591361e-06 4.06237642345396e-06 1.79094933445193e-05 1.76752215629586e-05 2.1400346628046e-05 -9.20494423104512e-06 7.80374026886342e-06 2.90530892098474e-06 1.31556421382854e-05 -8.13452722066197e-06 -9.20494423104512e-06 1.296888866367e-05 -1.3921668987324e-06 -1.14325498746338e-06 -3.51650779502606e-06 5.64822381591361e-06 7.80374026886342e-06 -1.3921668987324e-06 4.25422057903656e-05 -1.33368519662494e-05 6.38672346488848e-06 4.06237642345396e-06 2.90530892098474e-06 -1.14325498746338e-06 -1.33368519662494e-05 4.74548053604719e-05 -1.59202606181216e-06 1.79094933445193e-05 1.31556421382854e-05 -3.51650779502606e-06 6.38672346488848e-06 -1.59202606181216e-06 5.2879585910043e-05 2446 2444 0 15 11 2443 2469 0 36 9 0 0 0 0 0 18 48 0 634 0 13 15 0 0 2122 +369 425 0.999990370037237 -0.00040177907605925 0.00437017234941288 -0.012481170596325 0.000391619475361219 0.999997219647212 0.00232536707454743 0.011471155742138 -0.00437109448262672 -0.00232363323674638 0.999987747055735 -0.0128660870066517 2.84759652915412e-05 9.64749649827595e-06 -8.27889656854145e-06 1.89984305654366e-06 9.18737143285397e-06 1.17686412615264e-05 9.64749649827595e-06 2.71556920982699e-05 -7.99932952318066e-06 1.01367793946824e-05 3.14360422510827e-06 5.28695284847053e-06 -8.27889656854145e-06 -7.99932952318066e-06 1.61053950087818e-05 -2.44559684529603e-06 -8.77869424685047e-07 -2.89246909684584e-06 1.89984305654366e-06 1.01367793946824e-05 -2.44559684529603e-06 5.25087449586572e-05 -1.51809856631829e-05 -6.65155058064431e-06 9.18737143285397e-06 3.14360422510827e-06 -8.77869424685047e-07 -1.51809856631829e-05 5.0575504058925e-05 1.5288182353536e-05 1.17686412615264e-05 5.28695284847053e-06 -2.89246909684584e-06 -6.65155058064431e-06 1.5288182353536e-05 6.27365910829165e-05 1717 1714 0 18 16 1712 1735 0 42 14 0 0 0 0 0 18 48 0 639 0 40 45 0 0 1917 +369 411 0.999999796068131 -0.000200146941446037 0.000606469206218561 -0.00824844630268729 0.000199588277722079 0.999999555874492 0.00092109464137463 0.00659943194305601 -0.00060665329114537 -0.000920973409389717 0.999999391889697 -0.00602610591742333 3.06088784375188e-05 1.74600402025206e-05 -2.91044049193033e-06 4.55518968079168e-06 2.97545417785531e-06 2.11474948999582e-05 1.74600402025206e-05 2.92296924333678e-05 -4.63444440020383e-06 5.5219951128462e-06 3.68029869635732e-06 2.68527010356256e-05 -2.91044049193033e-06 -4.63444440020383e-06 1.06936744343419e-05 2.10925819480146e-06 2.96911788237194e-06 2.49003568482129e-07 4.55518968079168e-06 5.5219951128462e-06 2.10925819480146e-06 3.38485753585003e-05 -1.26957514466887e-05 1.02227760996848e-05 2.97545417785531e-06 3.68029869635732e-06 2.96911788237194e-06 -1.26957514466887e-05 3.83559423722735e-05 3.77177044655473e-07 2.11474948999582e-05 2.68527010356256e-05 2.49003568482129e-07 1.02227760996848e-05 3.77177044655473e-07 7.68898775274747e-05 2354 2355 0 18 11 2349 2384 0 46 7 0 0 0 0 0 7 39 0 541 0 12 15 0 0 2218 +369 396 0.999989486061572 -3.32627021695534e-05 0.00458548360652504 -0.00653736422754129 2.08708322491895e-05 0.999996348200137 0.00270243423586649 0.0047309173204141 -0.00458555675152175 -0.00270231011978019 0.999985834994324 -0.00744060033399019 2.63503179124368e-05 9.6028632334286e-06 5.57960909258112e-07 -5.25820322038897e-06 4.01190010856192e-06 4.68403660933011e-06 9.6028632334286e-06 3.19008387099434e-05 -1.22425863414153e-06 8.39900244925139e-06 5.0738990407011e-06 9.20214501490395e-06 5.57960909258112e-07 -1.22425863414153e-06 1.10044458521262e-05 7.68438226063881e-07 3.77289683267597e-06 8.14449544150554e-07 -5.25820322038897e-06 8.39900244925139e-06 7.68438226063881e-07 4.55445511013457e-05 -1.03452057401838e-05 -3.04059845681006e-06 4.01190010856192e-06 5.0738990407011e-06 3.77289683267597e-06 -1.03452057401838e-05 4.2706305867223e-05 9.85477270760873e-06 4.68403660933011e-06 9.20214501490395e-06 8.14449544150554e-07 -3.04059845681006e-06 9.85477270760873e-06 5.13407896491988e-05 2330 2312 0 17 42 2311 2335 0 43 23 0 0 0 0 0 12 42 0 462 0 74 56 0 0 2317 +369 413 0.999999925768844 -0.00017411795768768 0.000343722624884866 -0.0113630801196413 0.000174240092545801 0.999999921689868 -0.000355331742619426 0.00692213335982628 -0.000343660728330576 0.00035539160650471 0.999999877797048 -0.0115264521279358 2.59404555509953e-05 1.53971777041304e-05 -6.97207900434299e-06 3.02039421852613e-06 5.98913695380645e-06 1.21629577615611e-05 1.53971777041304e-05 2.83139788333175e-05 -7.22306479620776e-06 6.97760391321638e-06 7.85046629359767e-06 1.60110882828148e-05 -6.97207900434299e-06 -7.22306479620776e-06 1.27132363081392e-05 -7.04323344345521e-07 4.21939465390549e-07 -2.81575856297293e-06 3.02039421852613e-06 6.97760391321638e-06 -7.04323344345521e-07 5.10571324423785e-05 -2.23764828423572e-05 -5.8574973909209e-06 5.98913695380645e-06 7.85046629359767e-06 4.21939465390549e-07 -2.23764828423572e-05 5.52171611390862e-05 1.24984347351246e-05 1.21629577615611e-05 1.60110882828148e-05 -2.81575856297293e-06 -5.8574973909209e-06 1.24984347351246e-05 5.63501771904595e-05 2298 2294 0 17 11 2291 2320 0 44 8 0 0 0 0 0 12 44 0 605 0 34 37 0 0 2128 +370 429 0.999963374417033 -0.0075306424786997 0.00406684747188632 -0.00224221833328192 0.00753261179370374 0.999971519429786 -0.000469136280839146 0.00358958539216304 -0.00406319874814656 0.000499753081679294 0.999991620296286 -0.00503782474709196 5.2553356314857e-05 3.4909965836641e-05 -4.79493798319497e-06 7.76380026731425e-06 2.84192956748829e-06 4.29736554634821e-05 3.4909965836641e-05 4.44952373390178e-05 -5.56089099234091e-06 1.01086349301488e-05 -3.1510234734624e-07 3.56877844772036e-05 -4.79493798319497e-06 -5.56089099234091e-06 1.27399796112421e-05 -1.61341134147345e-06 -2.5177518489391e-06 -1.21211433198269e-06 7.76380026731425e-06 1.01086349301488e-05 -1.61341134147345e-06 4.63743641523136e-05 -1.11835699204018e-05 8.83974955499438e-06 2.84192956748829e-06 -3.1510234734624e-07 -2.5177518489391e-06 -1.11835699204018e-05 5.0399905679649e-05 -2.80138447419644e-07 4.29736554634821e-05 3.56877844772036e-05 -1.21211433198269e-06 8.83974955499438e-06 -2.80138447419644e-07 8.325601284015e-05 1721 1717 0 7 24 1722 1745 0 42 22 0 0 0 0 0 21 53 0 612 0 44 52 0 0 2331 +370 407 0.999983675226856 -0.000138580649367878 0.00571227408243584 -0.00701235398112147 0.000126290892716053 0.9999976769669 0.00215176936841266 0.00627200015632243 -0.00571255900623043 -0.00215101283307256 0.999981369733153 -0.00729992122849799 3.29388312227033e-05 2.19214336575819e-05 -3.46708699725103e-06 1.47691990820129e-06 4.50415553067327e-07 2.44110797128754e-05 2.19214336575819e-05 4.4734085070792e-05 -3.21661954472358e-06 7.86381258001023e-06 1.55248943239783e-06 2.48616379408868e-05 -3.46708699725103e-06 -3.21661954472358e-06 1.32552643844067e-05 1.03521290105175e-06 2.7930096984937e-06 -1.50388691959998e-06 1.47691990820129e-06 7.86381258001023e-06 1.03521290105175e-06 5.47304996855982e-05 -1.50830348059393e-05 1.78643575404082e-06 4.50415553067327e-07 1.55248943239783e-06 2.7930096984937e-06 -1.50830348059393e-05 4.20065651589988e-05 -1.11810281833479e-06 2.44110797128754e-05 2.48616379408868e-05 -1.50388691959998e-06 1.78643575404082e-06 -1.11810281833479e-06 8.63553840017109e-05 1513 1514 0 16 17 1506 1533 0 45 9 0 0 0 0 0 15 45 0 492 0 44 47 0 0 2308 +369 422 0.999995258827008 1.86008859086186e-05 0.00307928198006127 -0.0058807957448786 -2.10759528621671e-05 0.999999676770779 0.000803750048610555 0.00763729075848648 -0.00307926603428441 -0.000803811136694394 0.999994935991351 -0.0154645624131306 2.69595059618027e-05 1.17059018741629e-05 -9.48330727976649e-06 7.37543830800395e-06 9.24001791606071e-06 1.26288695984548e-05 1.17059018741629e-05 2.50627113525345e-05 -9.28587936623329e-06 6.70287046818551e-06 8.9634010205714e-06 1.10186009083961e-05 -9.48330727976649e-06 -9.28587936623329e-06 1.54117277563954e-05 -4.80474799957187e-06 -5.21882077565198e-06 -5.4772833036825e-06 7.37543830800395e-06 6.70287046818551e-06 -4.80474799957187e-06 4.97695899261575e-05 -1.55342728732579e-05 5.36786053269964e-06 9.24001791606071e-06 8.9634010205714e-06 -5.21882077565198e-06 -1.55342728732579e-05 6.14511587779584e-05 1.04881990161588e-07 1.26288695984548e-05 1.10186009083961e-05 -5.4772833036825e-06 5.36786053269964e-06 1.04881990161588e-07 5.80577397825735e-05 1408 1407 0 18 14 1398 1431 0 51 6 0 0 0 0 0 14 47 0 610 0 50 52 0 0 2220 +369 412 0.999997937804088 -0.000180140752203508 0.00202285364775622 -0.00896017166948661 0.000177637109060888 0.99999921815981 0.00123779030017179 0.0078342998028907 -0.00202307504268368 -0.00123742841373165 0.999997187965192 -0.00835879747416138 1.86707923920426e-05 1.22085406071066e-05 -5.10032516944747e-06 2.28765567860726e-06 5.15948999016847e-06 9.6927776618702e-06 1.22085406071066e-05 2.19780088438573e-05 -6.3619341090803e-06 4.6795390890622e-06 4.04946848997097e-06 1.19284502617128e-05 -5.10032516944747e-06 -6.3619341090803e-06 1.18694239135185e-05 -1.54784192778861e-07 7.71797999440413e-07 -2.94909517525277e-06 2.28765567860726e-06 4.6795390890622e-06 -1.54784192778861e-07 4.21793550369921e-05 -1.74991419763181e-05 3.8699628172801e-06 5.15948999016847e-06 4.04946848997097e-06 7.71797999440413e-07 -1.74991419763181e-05 4.68214609221334e-05 6.19128525925379e-06 9.6927776618702e-06 1.19284502617128e-05 -2.94909517525277e-06 3.8699628172801e-06 6.19128525925379e-06 4.29813443968041e-05 1755 1753 0 11 9 1759 1790 0 43 9 0 0 0 0 0 23 54 0 585 0 13 16 0 0 2094 +369 419 0.999999033917662 4.3609242970509e-05 0.00138933868349769 -0.00902290514184725 -4.39705354935938e-05 0.999999965228897 0.000260016916364171 0.00855990948697078 -0.00138932729604797 -0.000260077755132316 0.999999001064114 -0.00971377460929821 2.84557978696784e-05 1.17621288169006e-05 -7.0087859239564e-06 3.71875676669522e-06 6.41332465395387e-06 7.17724328305545e-06 1.17621288169006e-05 2.77128693384078e-05 -8.13909571651994e-06 1.05026763692989e-05 5.35747233146693e-06 1.17074553156873e-05 -7.0087859239564e-06 -8.13909571651994e-06 1.45872536709858e-05 -1.15652999272851e-06 -3.32697339516757e-06 -1.06466148291385e-06 3.71875676669522e-06 1.05026763692989e-05 -1.15652999272851e-06 4.27584231327014e-05 -9.81652506485789e-06 -3.27466148961126e-06 6.41332465395387e-06 5.35747233146693e-06 -3.32697339516757e-06 -9.81652506485789e-06 4.1337104963125e-05 8.6729872979091e-06 7.17724328305545e-06 1.17074553156873e-05 -1.06466148291385e-06 -3.27466148961126e-06 8.6729872979091e-06 6.54084167322413e-05 1792 1789 0 15 14 1788 1815 0 44 11 0 0 0 0 0 17 49 0 599 0 33 42 0 0 2123 +369 418 0.999999822848943 0.000329889295409247 -0.000495454473468259 -0.00879351429009722 -0.000330068305024419 0.999999880271045 -0.000361265565471432 0.00575628609273716 0.000495335236505164 0.000361429035291129 0.99999981200601 -0.00695337455595372 2.50197404713976e-05 1.29112570045674e-05 -7.76511845349476e-06 1.26258880810175e-07 6.57226887755257e-06 1.32828585743388e-05 1.29112570045674e-05 2.306319627197e-05 -9.92477744552961e-06 4.54748259711711e-06 7.18097844495599e-06 1.29454460577562e-05 -7.76511845349476e-06 -9.92477744552961e-06 1.38170694444927e-05 -7.4585479818046e-07 -2.79141584186379e-06 -3.27929231991911e-06 1.26258880810175e-07 4.54748259711711e-06 -7.4585479818046e-07 4.77831952674412e-05 -1.77527835209888e-05 2.67891564539847e-06 6.57226887755257e-06 7.18097844495599e-06 -2.79141584186379e-06 -1.77527835209888e-05 5.33141918137726e-05 9.68986291902723e-06 1.32828585743388e-05 1.29454460577562e-05 -3.27929231991911e-06 2.67891564539847e-06 9.68986291902723e-06 5.15845688969664e-05 2472 2472 0 16 13 2467 2502 0 44 11 0 0 0 0 0 18 50 0 622 0 15 17 0 0 2102 +370 406 0.999988393517366 0.000870412935192141 0.00473869305602246 -0.00436965587357769 -0.000883789039096642 0.999995629358346 0.00282137929748492 0.0118466116908718 -0.00473621657985759 -0.00282553455617765 0.999984792187852 -0.00509012692954071 2.96929201077819e-05 1.98184088918863e-05 -1.16691479326785e-06 5.57099556210873e-06 -4.80274143818158e-06 2.10772506214245e-05 1.98184088918863e-05 2.76020975489637e-05 -7.72315719684323e-07 7.09746277959525e-06 -6.96779692621241e-06 1.77333105533575e-05 -1.16691479326785e-06 -7.72315719684323e-07 1.14684795915714e-05 4.07727028669978e-06 2.08670720322431e-06 6.08828587245698e-07 5.57099556210873e-06 7.09746277959525e-06 4.07727028669978e-06 3.49531676701953e-05 -1.6255528975547e-05 7.61351475223967e-06 -4.80274143818158e-06 -6.96779692621241e-06 2.08670720322431e-06 -1.6255528975547e-05 4.13520717243041e-05 -7.27741798612826e-06 2.10772506214245e-05 1.77333105533575e-05 6.08828587245698e-07 7.61351475223967e-06 -7.27741798612826e-06 5.26348168651276e-05 2512 2517 0 18 17 2511 2558 0 52 14 0 0 0 0 0 20 52 0 473 0 21 23 0 0 2402 +369 424 0.999998012596317 -0.000580134912549418 0.0019074189100407 -0.0140096747716327 0.000580686809805879 0.999999789698276 -0.000288801373327045 0.0109177552153297 -0.00190725096514775 0.000289908412363967 0.999998139171703 -0.0119642800675183 2.90003626997318e-05 1.26676898343041e-05 -7.22209400684067e-06 1.26102093101919e-06 1.16663313677398e-06 8.36014338281276e-06 1.26676898343041e-05 2.24994368479162e-05 -8.62862760561025e-06 4.68279125598262e-06 6.44237629553335e-06 4.76108027280821e-06 -7.22209400684067e-06 -8.62862760561025e-06 1.4104538608344e-05 -8.39204844270054e-09 -1.60895753804081e-06 -4.58259566367614e-06 1.26102093101919e-06 4.68279125598262e-06 -8.39204844270054e-09 4.53099544335771e-05 -1.88744137006862e-05 -2.600204493667e-06 1.16663313677398e-06 6.44237629553335e-06 -1.60895753804081e-06 -1.88744137006862e-05 5.85318940282074e-05 9.49361005096923e-06 8.36014338281276e-06 4.76108027280821e-06 -4.58259566367614e-06 -2.600204493667e-06 9.49361005096923e-06 5.2343401717781e-05 2267 2265 0 10 15 2269 2294 0 40 14 0 0 0 0 0 18 48 0 627 0 39 43 0 0 2088 +370 399 0.999979836108726 -0.000563602588740197 0.00632532434644462 0.00495357510211382 0.000564261068463566 0.999999835570221 -0.00010231802546969 -0.00887617205637746 -0.0063252656396689 0.000105885096614253 0.999979989701261 -0.00683977894340333 4.27111062682676e-05 4.21045717896866e-05 -2.59859150150142e-06 1.01735905938187e-05 -3.33121504994063e-07 4.44047430163424e-05 4.21045717896866e-05 6.90797409052336e-05 -3.86011426159623e-06 1.81738083415402e-05 -9.47929547814405e-07 6.22983281875619e-05 -2.59859150150142e-06 -3.86011426159623e-06 1.07995425441884e-05 3.5343244064132e-06 2.53059923346344e-06 -1.45675959297666e-07 1.01735905938187e-05 1.81738083415402e-05 3.5343244064132e-06 4.16129974166792e-05 -1.65060511476196e-05 1.45531876352116e-05 -3.33121504994063e-07 -9.47929547814405e-07 2.53059923346344e-06 -1.65060511476196e-05 4.9620826467685e-05 -2.45218257024034e-06 4.44047430163424e-05 6.22983281875619e-05 -1.45675959297666e-07 1.45531876352116e-05 -2.45218257024034e-06 0.000111733612148929 1641 1620 0 18 41 1620 1653 0 52 28 0 0 0 0 0 11 44 0 482 0 86 78 0 0 2529 +370 373 0.999997552273414 0.000522866257084204 0.00214989722040468 -0.00604807268369544 -0.000523385849300247 0.999999833962536 0.000241126841344619 0.00380837277527486 -0.00214977078635218 -0.000242251476914649 0.999997659897156 -0.00555550745492476 2.88641413835266e-05 2.06348213332933e-05 -8.53932861896272e-06 8.03512565668428e-06 5.02743294445619e-06 2.62954886042704e-05 2.06348213332933e-05 2.533304588563e-05 -9.24772658088569e-06 6.3054187840235e-06 6.45604417683207e-06 2.00941218436505e-05 -8.53932861896272e-06 -9.24772658088569e-06 1.19052302316164e-05 -8.79149750781578e-07 -1.85017227940304e-06 -6.19244745240847e-06 8.03512565668428e-06 6.3054187840235e-06 -8.79149750781578e-07 5.80090693119202e-05 -3.01150634167825e-05 1.38889850105691e-05 5.02743294445619e-06 6.45604417683207e-06 -1.85017227940304e-06 -3.01150634167825e-05 5.75351507266307e-05 -2.91870902807008e-06 2.62954886042704e-05 2.00941218436505e-05 -6.19244745240847e-06 1.38889850105691e-05 -2.91870902807008e-06 6.81375602527335e-05 2243 2221 0 11 55 2225 2278 0 48 31 0 0 0 0 0 12 41 0 664 0 59 34 0 0 2656 +370 398 0.999998580940924 -0.000141597207148191 0.00167870973318994 -0.00200448684455724 0.00013926525495498 0.999999025406618 0.00138916917739075 -0.00130620157068521 -0.00167890479960632 -0.00138893342013864 0.999997626068496 -0.00709403507049242 3.19242690757162e-05 2.69620873663222e-05 -4.5596652747032e-06 4.5786151038055e-06 2.31144060707901e-06 2.66368696535405e-05 2.69620873663222e-05 3.77363425721883e-05 -5.03152966136995e-06 8.77284054744611e-06 -7.45330555528584e-07 3.12795035778986e-05 -4.5596652747032e-06 -5.03152966136995e-06 1.01882492762262e-05 4.20564565628485e-06 2.61367785842197e-06 -2.12479370413426e-08 4.5786151038055e-06 8.77284054744611e-06 4.20564565628485e-06 4.05884263839607e-05 -1.94404093672459e-05 7.97678447405248e-06 2.31144060707901e-06 -7.45330555528584e-07 2.61367785842197e-06 -1.94404093672459e-05 4.80247035175493e-05 -2.99713691417287e-07 2.66368696535405e-05 3.12795035778986e-05 -2.12479370413426e-08 7.97678447405248e-06 -2.99713691417287e-07 6.97681170465541e-05 2756 2737 0 20 41 2738 2787 0 51 24 0 0 0 0 0 15 47 0 461 0 57 42 0 0 2474 +369 395 0.999983023529802 0.000126153898418599 0.00582552464497535 -1.61188847373648e-05 -0.000144681699969112 0.999994932875195 0.00318014011312637 0.00713816251086045 -0.00582509393924213 -0.00318092897238137 0.99997797474318 -0.00656906403170315 3.78710980360148e-05 1.09385888566404e-05 1.08513213237051e-06 -9.53624334554875e-08 -4.88831951410464e-06 1.55935328164361e-05 1.09385888566404e-05 3.49192817340581e-05 -2.97968397867666e-07 2.6097620379135e-06 7.96437516549642e-06 1.89261545372302e-05 1.08513213237051e-06 -2.97968397867666e-07 1.15453775308267e-05 4.11274935823224e-06 2.80649213109733e-06 1.11156852989602e-06 -9.53624334554875e-08 2.6097620379135e-06 4.11274935823224e-06 3.77567145392499e-05 -1.21158849541041e-05 8.52764504962987e-06 -4.88831951410464e-06 7.96437516549642e-06 2.80649213109733e-06 -1.21158849541041e-05 4.5646364963922e-05 3.95979747619334e-06 1.55935328164361e-05 1.89261545372302e-05 1.11156852989602e-06 8.52764504962987e-06 3.95979747619334e-06 7.86725590160725e-05 1502 1486 0 20 49 1463 1485 0 44 12 0 0 0 0 0 16 46 0 459 0 85 70 0 0 2411 +370 408 0.999999709325259 0.000518723909627692 0.000558815625445904 -0.0108269235657579 -0.000519432380248531 0.999999060663586 0.00126840921933467 0.0131330080178982 -0.000558157146340778 -0.00126869911757059 0.999999039431113 -0.00376063242363535 3.35033822793029e-05 2.42850188497978e-05 -2.45629522240369e-06 6.9424320843485e-06 -3.77872819120608e-06 2.09237110230974e-05 2.42850188497978e-05 3.42620468070674e-05 -3.33444479063724e-06 7.40751888885976e-06 -3.33534674521082e-06 2.43123707737684e-05 -2.45629522240369e-06 -3.33444479063724e-06 1.07781425686938e-05 2.55089743217252e-06 3.30140077407527e-06 2.16980032843065e-08 6.9424320843485e-06 7.40751888885976e-06 2.55089743217252e-06 3.44225911830395e-05 -1.88947262669541e-05 5.26111384048095e-06 -3.77872819120608e-06 -3.33534674521082e-06 3.30140077407527e-06 -1.88947262669541e-05 4.22109881183683e-05 -5.48232584669638e-07 2.09237110230974e-05 2.43123707737684e-05 2.16980032843065e-08 5.26111384048095e-06 -5.48232584669638e-07 5.88589512168896e-05 2382 2380 0 10 15 2386 2421 0 42 12 0 0 0 0 0 20 51 0 497 0 58 60 0 0 2300 +370 372 0.999996568720143 0.000113230754116282 -0.00261719826071043 -0.00783460024285084 -0.000112673459609405 0.999999970950377 0.000213081996924273 -0.00030370136905623 0.002617222312117 -0.000212786376997792 0.99999655242872 -0.00114398844440626 3.80210049581067e-05 2.78220086142033e-05 -7.36885925023172e-06 6.79451820175769e-06 7.17299859385657e-06 2.82521214144917e-05 2.78220086142033e-05 3.01954910575378e-05 -7.84922757813654e-06 7.24834883472311e-06 5.71251751626193e-06 2.82832978284248e-05 -7.36885925023172e-06 -7.84922757813654e-06 1.14472794733045e-05 6.26096119141431e-07 -1.16144522931651e-06 -2.9380905473144e-06 6.79451820175769e-06 7.24834883472311e-06 6.26096119141431e-07 2.65204099917865e-05 5.5482515261956e-06 8.4867092605926e-06 7.17299859385657e-06 5.71251751626193e-06 -1.16144522931651e-06 5.5482515261956e-06 3.4882931039379e-05 9.45240523324641e-06 2.82521214144917e-05 2.82832978284248e-05 -2.9380905473144e-06 8.4867092605926e-06 9.45240523324641e-06 5.15471458976698e-05 2800 2778 0 13 53 2788 2820 0 51 31 0 0 0 0 0 17 48 0 659 0 102 82 0 0 2795 +370 400 0.999999015836015 9.0823973741949e-05 0.00140002785930354 -0.00420891761272696 -9.2248992962341e-05 0.999999477766507 0.00101781964845002 -0.00518490666162151 -0.00139993468573708 -0.00101794779790872 0.999998501981456 -0.0103279106744437 3.7131884891759e-05 2.67116166824188e-05 -6.54142847508658e-06 8.37685658432738e-06 6.51055443182937e-06 3.22826527392475e-05 2.67116166824188e-05 3.40367145598955e-05 -6.47302465708299e-06 7.60729391940914e-06 2.0450108734207e-06 2.81773423175298e-05 -6.54142847508658e-06 -6.47302465708299e-06 1.22915816231336e-05 2.19259014581154e-06 1.1786372324463e-06 -6.7141327484331e-07 8.37685658432738e-06 7.60729391940914e-06 2.19259014581154e-06 5.77625007218004e-05 -3.13488040284383e-05 2.88179096374759e-05 6.51055443182937e-06 2.0450108734207e-06 1.1786372324463e-06 -3.13488040284383e-05 7.20147682186943e-05 -3.70534761482869e-06 3.22826527392475e-05 2.81773423175298e-05 -6.7141327484331e-07 2.88179096374759e-05 -3.70534761482869e-06 8.84342429269117e-05 1997 1986 0 22 37 1978 2030 0 57 20 0 0 0 0 0 17 50 0 503 0 58 42 0 0 2359 +370 405 0.999996168703556 0.000882922779346146 0.00262355209122909 -0.0043057911028745 -0.000887104587631055 0.999998337357383 0.00159321308056802 0.0138683649145453 -0.00262214104507839 -0.00159553434159243 0.999995289312157 0.000195012640795051 2.57739110150692e-05 1.39878397187296e-05 -1.37994889505834e-06 6.16350247252443e-07 2.12476633153995e-06 1.38298973954824e-05 1.39878397187296e-05 2.59401943347498e-05 -1.25341416440715e-06 4.07826205605119e-06 -7.78177682260485e-07 1.18559956563616e-05 -1.37994889505834e-06 -1.25341416440715e-06 1.3710739969107e-05 1.43057212064752e-06 9.54851330598851e-07 -5.53826326862752e-07 6.16350247252443e-07 4.07826205605119e-06 1.43057212064752e-06 3.86909691569688e-05 -1.38710092322477e-05 -4.73553942622905e-07 2.12476633153995e-06 -7.78177682260485e-07 9.54851330598851e-07 -1.38710092322477e-05 4.66620305672342e-05 1.07919066912931e-05 1.38298973954824e-05 1.18559956563616e-05 -5.53826326862752e-07 -4.73553942622905e-07 1.07919066912931e-05 5.8252759276509e-05 1732 1735 0 17 19 1734 1769 0 48 16 0 0 0 0 0 15 47 0 459 0 58 62 0 0 2379 +370 397 0.999998299732263 0.000356057246680376 0.00180935232055072 -0.00129875268370281 -0.000357193293614428 0.999999739271483 0.000627590564424461 0.00124736072724573 -0.00180912839063256 -0.000628235785867158 0.99999816618545 -0.00612743160862665 3.11527765054308e-05 2.04528789840962e-05 -4.0456362702523e-06 4.74919575722163e-06 -8.70809638749459e-07 1.65496532587634e-05 2.04528789840962e-05 2.5462355736208e-05 -4.53627812910854e-06 6.24292618141417e-06 -1.45709519316932e-06 1.7430051182173e-05 -4.0456362702523e-06 -4.53627812910854e-06 1.14037663217302e-05 2.85497969599711e-06 1.31315440379033e-06 -5.53697562105403e-07 4.74919575722163e-06 6.24292618141417e-06 2.85497969599711e-06 4.35554198425291e-05 -2.14161634912841e-05 3.73232440095887e-06 -8.70809638749459e-07 -1.45709519316932e-06 1.31315440379033e-06 -2.14161634912841e-05 5.01617090602453e-05 4.47051844577412e-06 1.65496532587634e-05 1.7430051182173e-05 -5.53697562105403e-07 3.73232440095887e-06 4.47051844577412e-06 5.19087523994702e-05 2363 2354 0 20 42 2346 2378 0 54 25 0 0 0 0 0 15 46 0 471 0 85 75 0 0 2422 +370 374 0.999993881345247 0.000203516287073028 0.00349225617465421 0.00330283770369039 -0.000208146000253897 0.999999099999783 0.00132539611659981 0.00114944168165873 -0.00349198329192634 -0.00132611490611318 0.999993023711638 -0.00147974482016045 3.48701139701059e-05 2.59043136135591e-05 -8.54495651688452e-06 9.01774590863904e-06 7.59627225608139e-06 2.26275040499715e-05 2.59043136135591e-05 3.31533019636904e-05 -9.77852275331904e-06 7.05419082448151e-06 6.18242282455354e-06 2.28138348905324e-05 -8.54495651688452e-06 -9.77852275331904e-06 1.34016489269262e-05 -4.09034182765744e-07 -3.15464758383616e-06 -3.52087782225865e-06 9.01774590863904e-06 7.05419082448151e-06 -4.09034182765744e-07 6.78959897053432e-05 -3.32373412603957e-05 9.63022561294501e-06 7.59627225608139e-06 6.18242282455354e-06 -3.15464758383616e-06 -3.32373412603957e-05 6.19893360656824e-05 1.4767470576383e-06 2.26275040499715e-05 2.28138348905324e-05 -3.52087782225865e-06 9.63022561294501e-06 1.4767470576383e-06 4.7428642657593e-05 2573 2547 0 18 52 2547 2576 0 52 28 0 0 0 0 0 12 43 0 656 0 85 72 0 0 2665 +370 427 0.999999860926991 -0.00023206466620272 0.000473594751234562 -0.00598224938782304 0.000232217693018197 0.999999920844467 -0.000323088229054359 0.00613289417063616 -0.000473519736384888 0.000323198161202064 0.99999983566099 -0.0070116977526776 3.69993300111148e-05 2.12328769526992e-05 -1.14585295984508e-05 7.77330467386055e-06 1.4026694812473e-05 2.40472367461264e-05 2.12328769526992e-05 2.95606474995239e-05 -9.3477676969916e-06 8.40281374537989e-06 5.99337916154116e-06 2.46635165976643e-05 -1.14585295984508e-05 -9.3477676969916e-06 1.67465000009507e-05 -3.04619641196734e-06 -7.99726788086646e-06 -4.03198577293473e-06 7.77330467386055e-06 8.40281374537989e-06 -3.04619641196734e-06 4.06753052150304e-05 -5.29022174182298e-06 1.83625910748121e-05 1.4026694812473e-05 5.99337916154116e-06 -7.99726788086646e-06 -5.29022174182298e-06 5.41578199315564e-05 8.49056260487773e-06 2.40472367461264e-05 2.46635165976643e-05 -4.03198577293473e-06 1.83625910748121e-05 8.49056260487773e-06 7.0222750422334e-05 2779 2778 0 17 17 2773 2823 0 48 14 0 0 0 0 0 8 38 0 652 0 19 20 0 0 2329 +370 409 0.999995997868178 -0.000131214712701016 0.00282613345856224 -0.00842817851040877 0.000126515401715197 0.999998609343913 0.00166292035089727 0.00528259198574044 -0.00282634772799863 -0.00166255614626101 0.999994623818339 -0.00748816263967304 3.68665506752167e-05 2.57371622537412e-05 -2.09106645001883e-06 2.95248268827545e-06 3.33361058749653e-06 2.2443115407905e-05 2.57371622537412e-05 4.48373918893e-05 -2.08707371972645e-06 1.75442846521883e-05 -5.10402161968925e-06 3.21815403442084e-05 -2.09106645001883e-06 -2.08707371972645e-06 1.17952521624474e-05 4.58414621144823e-06 -4.90197460673259e-07 1.77522130988443e-06 2.95248268827545e-06 1.75442846521883e-05 4.58414621144823e-06 4.60111126633361e-05 -1.29029574217935e-05 1.98479435061001e-05 3.33361058749653e-06 -5.10402161968925e-06 -4.90197460673259e-07 -1.29029574217935e-05 4.30383136889659e-05 -7.23667789613413e-06 2.2443115407905e-05 3.21815403442084e-05 1.77522130988443e-06 1.98479435061001e-05 -7.23667789613413e-06 8.25355471573483e-05 1945 1939 0 17 10 1927 1958 0 45 2 0 0 0 0 0 23 55 0 510 0 41 43 0 0 2260 +370 426 0.999994960222196 0.000704813222725588 0.00309560471136521 -0.00558756393479651 -0.000707240516105164 0.999999443294263 0.000783084936260165 0.00992592354853348 -0.00309505105940671 -0.000785270326759808 0.999994901991732 -0.00926991941162145 3.56473436418978e-05 2.516706624128e-05 -9.69021182687591e-06 8.69994759025594e-06 1.01302144938773e-05 2.77455091465625e-05 2.516706624128e-05 3.42359186372982e-05 -9.63600753832717e-06 1.47462593835341e-05 2.26314837554659e-06 2.41981990464461e-05 -9.69021182687591e-06 -9.63600753832717e-06 1.64791950793563e-05 -2.31900790598133e-06 -4.71527835447579e-06 -4.34789701971655e-06 8.69994759025594e-06 1.47462593835341e-05 -2.31900790598133e-06 4.6035523861801e-05 -6.36610976393654e-06 7.13244444664034e-06 1.01302144938773e-05 2.26314837554659e-06 -4.71527835447579e-06 -6.36610976393654e-06 5.06693210708801e-05 8.20613677704512e-06 2.77455091465625e-05 2.41981990464461e-05 -4.34789701971655e-06 7.13244444664034e-06 8.20613677704512e-06 6.53632955484372e-05 2341 2341 0 18 17 2335 2364 0 50 16 0 0 0 0 0 19 49 0 639 0 46 55 0 0 2101 +370 402 0.999998319385324 0.000186125864214987 0.00182389245562762 -0.00510555833961552 -0.000187652289848607 0.999999632301128 0.000836770115468507 0.00655085442406098 -0.00182373604042353 -0.000837110966776107 0.999997986614015 -0.00448440442539458 3.00481769724475e-05 2.2533922747336e-05 -1.08535068987431e-06 2.48048350267638e-06 -2.1769114821547e-06 2.45870252205855e-05 2.2533922747336e-05 2.73949499224286e-05 -2.79355102395032e-06 1.80758083529196e-06 -3.88186465794601e-06 2.18818377975973e-05 -1.08535068987431e-06 -2.79355102395032e-06 1.03419357693288e-05 4.40956536942256e-06 2.3895936222244e-06 2.49042293376519e-06 2.48048350267638e-06 1.80758083529196e-06 4.40956536942256e-06 3.54971981939219e-05 -1.56499628633449e-05 7.44019496555062e-06 -2.1769114821547e-06 -3.88186465794601e-06 2.3895936222244e-06 -1.56499628633449e-05 4.25708515333614e-05 -8.24826805278578e-06 2.45870252205855e-05 2.18818377975973e-05 2.49042293376519e-06 7.44019496555062e-06 -8.24826805278578e-06 6.83893069954538e-05 2758 2746 0 17 39 2742 2791 0 44 27 0 0 0 0 0 13 42 0 469 0 36 28 0 0 2487 +370 404 0.999992536676492 0.000997352968165511 0.00373254315069468 -0.00593595388123694 -0.00100725868605905 0.999995973659372 0.00265294081785537 0.0129843434267868 -0.00372988220380549 -0.00265668065460942 0.999989514958355 0.00111586436023314 2.67705360810622e-05 1.64558614265511e-05 -1.01499953502441e-06 -3.53900822497071e-07 2.05436035812008e-06 1.23061178322302e-05 1.64558614265511e-05 2.2200540595733e-05 -1.70561435282473e-06 3.01658023047604e-06 -1.31526730259724e-06 8.92252757708601e-06 -1.01499953502441e-06 -1.70561435282473e-06 1.26886590689898e-05 1.90977854073008e-06 -2.29801062695862e-07 -5.77680817569476e-07 -3.53900822497071e-07 3.01658023047604e-06 1.90977854073008e-06 3.98587138299443e-05 -5.97306911605993e-06 -5.9816700742589e-07 2.05436035812008e-06 -1.31526730259724e-06 -2.29801062695862e-07 -5.97306911605993e-06 4.32086568502406e-05 6.52296944931724e-06 1.23061178322302e-05 8.92252757708601e-06 -5.77680817569476e-07 -5.9816700742589e-07 6.52296944931724e-06 5.47974569737542e-05 2057 2053 0 14 21 2040 2068 0 49 11 0 0 0 0 0 13 42 0 449 0 53 54 0 0 2342 +370 428 0.99999846615169 0.00105891452298624 0.00139513235929838 -0.00767850225178681 -0.00106087515251928 0.999998449771873 0.00140534613615484 0.0118131375576536 -0.00139364205509155 -0.0014068240418215 0.999998039302047 -0.00806567893697717 2.25186201637136e-05 1.43467454494404e-05 -7.4408984573442e-06 6.3024000267443e-06 5.7033897839329e-06 1.50614692305552e-05 1.43467454494404e-05 2.21494424918631e-05 -8.23410861747028e-06 4.63625521524145e-06 1.83773462434599e-06 1.20389064589673e-05 -7.4408984573442e-06 -8.23410861747028e-06 1.37787276523364e-05 -1.4958980424024e-06 -3.53260191432666e-06 -2.60933686403772e-06 6.3024000267443e-06 4.63625521524145e-06 -1.4958980424024e-06 4.05239469518189e-05 -6.51803247806008e-06 3.9607890313526e-06 5.7033897839329e-06 1.83773462434599e-06 -3.53260191432666e-06 -6.51803247806008e-06 4.8415900766383e-05 3.38683081282213e-06 1.50614692305552e-05 1.20389064589673e-05 -2.60933686403772e-06 3.9607890313526e-06 3.38683081282213e-06 5.50892537967648e-05 2745 2751 0 17 16 2741 2793 0 55 13 0 0 0 0 0 15 48 0 646 0 16 18 0 0 2247 +370 420 0.999996761121266 0.000245956043964877 0.00253322967799451 -0.0063141832484895 -0.000248018308856454 0.999999638105511 0.000813803271924176 0.00836317990360318 -0.00253302860139932 -0.000814428923454747 0.999996460229552 -0.0076215159978924 2.63368855447323e-05 1.94133451076761e-05 -1.02211023451253e-05 8.80679944373552e-06 1.37674713222074e-05 1.63997029670059e-05 1.94133451076761e-05 2.35250934269891e-05 -1.11712889547757e-05 8.86952454145777e-06 9.33947460636287e-06 1.41003600815861e-05 -1.02211023451253e-05 -1.11712889547757e-05 1.4760347317521e-05 -2.26196697305939e-06 -5.0336868992888e-06 -4.35669105042993e-06 8.80679944373552e-06 8.86952454145777e-06 -2.26196697305939e-06 4.32360774463105e-05 -1.1593094383387e-05 9.88633766785459e-06 1.37674713222074e-05 9.33947460636287e-06 -5.0336868992888e-06 -1.1593094383387e-05 5.74309711948862e-05 7.679357507559e-06 1.63997029670059e-05 1.41003600815861e-05 -4.35669105042993e-06 9.88633766785459e-06 7.679357507559e-06 4.37012326280691e-05 2332 2329 0 11 11 2330 2359 0 46 9 0 0 0 0 0 19 50 0 637 0 44 53 0 0 2304 +370 401 0.99999977080616 4.84558564931259e-05 0.000675307083313914 -0.00277814012529902 -4.82123346588615e-05 0.999999933814158 -0.000360620646754936 -0.00609038003671801 -0.000675324512800454 0.000360588005971807 0.999999706956503 -0.00784912487825247 3.64624686739483e-05 2.27028788453141e-05 -5.97380060204341e-06 5.63047517537686e-06 5.54077072900395e-06 2.31529242376161e-05 2.27028788453141e-05 3.76068671131442e-05 -5.37014555217316e-06 2.59235421392142e-06 1.15797190285043e-05 2.5274179071447e-05 -5.97380060204341e-06 -5.37014555217316e-06 1.33516252911874e-05 4.6298201858164e-07 3.2818178148398e-06 -1.31441646665366e-06 5.63047517537686e-06 2.59235421392142e-06 4.6298201858164e-07 4.61090248647608e-05 -2.0318674274957e-05 -2.23555727683449e-06 5.54077072900395e-06 1.15797190285043e-05 3.2818178148398e-06 -2.0318674274957e-05 7.03487412728556e-05 2.31896122720342e-05 2.31529242376161e-05 2.5274179071447e-05 -1.31441646665366e-06 -2.23555727683449e-06 2.31896122720342e-05 7.17151286151168e-05 2078 2065 0 16 34 2049 2079 0 49 10 0 0 0 0 0 16 46 0 517 0 71 60 0 0 2430 +370 412 0.999981877606331 -0.000232459479013002 0.00601584753028711 -0.00443326467211066 0.000232464375440917 0.99999997298015 -1.14680102241473e-07 0.00666210270871242 -0.00601584734108134 1.51314826283949e-06 0.999981904625518 -0.00857499645529234 6.8319445242019e-05 4.77114424159206e-05 -9.72019924901109e-06 1.97963778039182e-05 -5.8900120870723e-06 5.14456538503277e-05 4.77114424159206e-05 6.25989627196346e-05 -9.75824050572388e-06 2.45642286962756e-05 1.1882440821365e-06 4.8266754649784e-05 -9.72019924901109e-06 -9.75824050572388e-06 1.35524827298464e-05 1.88031133473936e-06 -2.81948788576312e-06 -5.20408930210589e-06 1.97963778039182e-05 2.45642286962756e-05 1.88031133473936e-06 4.70798076981374e-05 -2.3244170698859e-05 1.8815209673683e-05 -5.8900120870723e-06 1.1882440821365e-06 -2.81948788576312e-06 -2.3244170698859e-05 6.66138015893451e-05 -5.61726970876247e-06 5.14456538503277e-05 4.8266754649784e-05 -5.20408930210589e-06 1.8815209673683e-05 -5.61726970876247e-06 9.39371183064116e-05 1678 1674 0 16 9 1670 1702 0 46 6 0 0 0 0 0 11 43 0 578 0 43 49 0 0 2233 +370 421 0.999994622852063 0.000543309890026043 0.00323405029700319 -0.00523705699229311 -0.000553050451400469 0.99999531175273 0.00301174496898399 0.0082955136101777 -0.00323239882414783 -0.00301351736736235 0.999990235107783 -0.00803845225728839 3.2825941126033e-05 2.2945856522618e-05 -9.33455359351791e-06 1.17770103716848e-05 6.62568938260714e-06 2.25500101289653e-05 2.2945856522618e-05 2.74756501903192e-05 -8.6107196874579e-06 7.8802299497907e-06 4.06038161732107e-06 1.69264649276629e-05 -9.33455359351791e-06 -8.6107196874579e-06 1.35927824067664e-05 -1.34790648027983e-06 -4.37216791564307e-06 -4.1211162123061e-06 1.17770103716848e-05 7.8802299497907e-06 -1.34790648027983e-06 4.43343905944548e-05 -1.18079503833026e-05 5.38926864292373e-06 6.62568938260714e-06 4.06038161732107e-06 -4.37216791564307e-06 -1.18079503833026e-05 5.54324114415446e-05 3.62851398345942e-06 2.25500101289653e-05 1.69264649276629e-05 -4.1211162123061e-06 5.38926864292373e-06 3.62851398345942e-06 5.00296531244968e-05 2338 2342 0 18 14 2335 2371 0 51 10 0 0 0 0 0 15 47 0 625 0 49 55 0 0 2326 +370 410 0.999993820917934 -0.000112080523879753 0.00351362546494102 -0.00761988585371753 0.000102271491048382 0.999996097778156 0.00279176807833256 0.0104990158601966 -0.00351392465682375 -0.00279139148405321 0.999989930182844 -0.00791782740555205 4.83383787184547e-05 3.89079941222758e-05 -2.50127123722596e-06 5.60353308167371e-06 -3.8232555281727e-06 3.35483205007403e-05 3.89079941222758e-05 5.83940094627143e-05 -3.17573067503306e-06 8.76485265327077e-06 5.89584747655017e-07 3.86968043315181e-05 -2.50127123722596e-06 -3.17573067503306e-06 1.0762364736758e-05 4.38845793181857e-06 2.36451396251716e-06 -8.62374051025607e-07 5.60353308167371e-06 8.76485265327077e-06 4.38845793181857e-06 3.84649662288197e-05 -2.03033984902619e-05 1.15606231885234e-06 -3.8232555281727e-06 5.89584747655017e-07 2.36451396251716e-06 -2.03033984902619e-05 5.04215157833251e-05 1.78421685738236e-06 3.35483205007403e-05 3.86968043315181e-05 -8.62374051025607e-07 1.15606231885234e-06 1.78421685738236e-06 8.76113626498755e-05 1817 1815 0 12 9 1815 1845 0 44 7 0 0 0 0 0 22 50 0 508 0 32 38 0 0 2351 +370 425 0.999984660085839 0.000275141499218835 0.00553207828612547 -0.00659500680517591 -0.000292827967063792 0.999994848245762 0.00319651899988705 0.00741588201632097 -0.00553117029118781 -0.00319808991279814 0.999979588979755 -0.0089677543744325 4.08257348953961e-05 2.45589392947448e-05 -6.70111644946156e-06 8.09539814145326e-06 1.20485824759823e-06 2.88241519888421e-05 2.45589392947448e-05 4.228656201197e-05 -6.06229147701847e-06 1.37082765529548e-05 9.45268608088538e-07 2.96495300799199e-05 -6.70111644946156e-06 -6.06229147701847e-06 1.41616344194983e-05 -2.35077498226713e-06 8.62178939586613e-07 -2.51065758108971e-06 8.09539814145326e-06 1.37082765529548e-05 -2.35077498226713e-06 4.6172012114451e-05 -1.38942633452251e-06 7.34654450483705e-06 1.20485824759823e-06 9.45268608088538e-07 8.62178939586613e-07 -1.38942633452251e-06 3.9715621564664e-05 7.14912320260591e-07 2.88241519888421e-05 2.96495300799199e-05 -2.51065758108971e-06 7.34654450483705e-06 7.14912320260591e-07 9.10010973337179e-05 1579 1575 0 15 16 1565 1600 0 50 6 0 0 0 0 0 11 41 0 631 0 44 45 0 0 2107 +370 396 0.999981628089861 0.000203471949444806 0.00605822432044446 -0.00201852575669558 -0.00019652612112398 0.999999322785976 -0.00114708546917837 0.00180038773369172 -0.00605845361744659 0.00114587379570061 0.999980990875831 -0.000256177458641146 5.56946280699703e-05 4.56674663925722e-05 -8.68824565459148e-08 1.03417936075968e-05 -1.45756553916496e-05 4.56848649910534e-05 4.56674663925722e-05 5.74509373227384e-05 -2.78054557293855e-07 1.53824126933792e-05 -1.97707627600994e-05 4.67293043720046e-05 -8.68824565459148e-08 -2.78054557293855e-07 1.03941915100678e-05 4.9216204810039e-06 1.46573748951134e-06 3.70409700742995e-06 1.03417936075968e-05 1.53824126933792e-05 4.9216204810039e-06 4.5217939033745e-05 -2.26706924878163e-05 1.37079621442586e-05 -1.45756553916496e-05 -1.97707627600994e-05 1.46573748951134e-06 -2.26706924878163e-05 5.91699055379691e-05 -1.75777719014515e-05 4.56848649910534e-05 4.67293043720046e-05 3.70409700742995e-06 1.37079621442586e-05 -1.75777719014515e-05 0.000108882228261425 2100 2084 0 19 40 2056 2080 0 47 6 0 0 0 0 0 15 44 0 455 0 81 64 0 0 2553 +370 423 0.999992237282085 8.43960366536938e-05 0.00393932137305416 -0.00612358605263314 -9.00495898938098e-05 0.999998966326936 0.00143500387836556 0.0054484457588131 -0.00393919619244384 -0.00143534747310935 0.999991211216873 -0.0101591744026958 2.89477348630779e-05 1.48569267218294e-05 -9.1425875607589e-06 7.24264381315204e-06 3.13816725141864e-06 1.66842191786902e-05 1.48569267218294e-05 2.79062340332477e-05 -9.85445361032804e-06 1.05647996515612e-05 5.44280785445801e-06 1.8229501056476e-05 -9.1425875607589e-06 -9.85445361032804e-06 1.56308063220611e-05 1.37525108725212e-08 -2.60069127790547e-06 -3.73979733377161e-06 7.24264381315204e-06 1.05647996515612e-05 1.37525108725212e-08 4.57120447219478e-05 -1.26474480008354e-05 1.46779432727132e-05 3.13816725141864e-06 5.44280785445801e-06 -2.60069127790547e-06 -1.26474480008354e-05 5.59531734131358e-05 3.70198721018312e-06 1.66842191786902e-05 1.8229501056476e-05 -3.73979733377161e-06 1.46779432727132e-05 3.70198721018312e-06 6.35683128741162e-05 1711 1707 0 16 12 1705 1736 0 50 12 0 0 0 0 0 15 47 0 617 0 45 56 0 0 2248 +370 413 0.99999921753545 2.87037120213232e-05 0.0012506416691085 -0.0108279266990215 -2.68713158327557e-05 0.999998926295874 -0.00146515699931199 0.006112848012952 -0.00125068238173396 0.00146512224649129 0.99999814460347 -0.00605939475223571 4.34848094117275e-05 3.40313159809192e-05 -8.06026518309124e-06 8.95345878493232e-06 9.03947863788e-06 3.24054267566592e-05 3.40313159809192e-05 3.7804564485622e-05 -9.11074210023514e-06 1.1468438159222e-05 5.28718320733007e-06 2.72535572965063e-05 -8.06026518309124e-06 -9.11074210023514e-06 1.31915013297184e-05 -1.04737354384533e-08 -1.22055905722579e-06 -4.48373430728622e-06 8.95345878493232e-06 1.1468438159222e-05 -1.04737354384533e-08 4.20641911501954e-05 -5.34646356909951e-06 9.21045737978711e-06 9.03947863788e-06 5.28718320733007e-06 -1.22055905722579e-06 -5.34646356909951e-06 4.75292267593061e-05 6.42937678705416e-06 3.24054267566592e-05 2.72535572965063e-05 -4.48373430728622e-06 9.21045737978711e-06 6.42937678705416e-06 6.7647997859998e-05 2071 2067 0 13 11 2068 2097 0 48 10 0 0 0 0 0 16 48 0 599 0 35 41 0 0 2298 +370 411 0.999998005876612 0.000148340791831276 0.00199154156586089 -0.00405277989240032 -0.00014819635386106 0.999999986378232 -7.26730859393353e-05 0.00414940333727951 -0.00199155231911568 7.23778018216116e-05 0.999998014238435 -0.00785186842467795 3.456019432848e-05 2.99314015122701e-05 -4.53827781558129e-06 8.55720352488581e-06 -3.04883381204666e-06 3.1004881073675e-05 2.99314015122701e-05 3.76790014154607e-05 -5.0960649259855e-06 1.08484075378833e-05 -3.23106721575219e-06 3.3838537783564e-05 -4.53827781558129e-06 -5.0960649259855e-06 1.20014594906136e-05 1.82772560283708e-06 2.04832383245699e-06 -1.76418189879356e-06 8.55720352488581e-06 1.08484075378833e-05 1.82772560283708e-06 3.88976262705441e-05 -1.83921352365465e-05 1.51058360528792e-05 -3.04883381204666e-06 -3.23106721575219e-06 2.04832383245699e-06 -1.83921352365465e-05 4.36549961859669e-05 -7.80251609591432e-06 3.1004881073675e-05 3.3838537783564e-05 -1.76418189879356e-06 1.51058360528792e-05 -7.80251609591432e-06 6.95307209823593e-05 2243 2246 0 19 11 2241 2270 0 45 9 0 0 0 0 0 18 50 0 545 0 42 51 0 0 2243 +370 418 0.999996002940363 0.00061649528063057 0.00275935442912141 -0.00528469362522823 -0.000618357459428978 0.999999581639802 0.000674058063808254 0.00555280592327112 -0.00275893772110213 -0.00067576163695243 0.999995965796293 -0.00855019301508597 2.58953836974704e-05 1.67972478533916e-05 -8.32017042469198e-06 3.29740770319251e-06 1.02671693116603e-05 1.68224377123497e-05 1.67972478533916e-05 2.32781643728068e-05 -8.16145528830748e-06 6.99200484598594e-06 4.82189169857688e-06 1.45270144077446e-05 -8.32017042469198e-06 -8.16145528830748e-06 1.28248954019994e-05 -1.30170752806117e-06 -2.22666305065227e-06 -1.62213499377963e-06 3.29740770319251e-06 6.99200484598594e-06 -1.30170752806117e-06 3.83533113410642e-05 -5.64760019636146e-06 3.39581686340548e-06 1.02671693116603e-05 4.82189169857688e-06 -2.22666305065227e-06 -5.64760019636146e-06 4.13032705935141e-05 8.07127328157537e-06 1.68224377123497e-05 1.45270144077446e-05 -1.62213499377963e-06 3.39581686340548e-06 8.07127328157537e-06 5.26148165742813e-05 2357 2356 0 12 13 2353 2386 0 48 11 0 0 0 0 0 20 52 0 627 0 47 56 0 0 2220 +370 424 0.999993584313493 0.000123084351543489 0.00357996956613532 -0.00925874223129495 -0.000122684242541563 0.999999986204233 -0.000111982630052168 0.00639889646799858 -0.0035799833000563 0.000111542705752176 0.999993585618326 -0.00743931332787231 3.74400048896194e-05 2.88915300658287e-05 -9.75513489911915e-06 8.7047682886864e-06 5.89249636453385e-06 2.67946988303851e-05 2.88915300658287e-05 4.10719425500052e-05 -9.26035440598089e-06 8.90998008390309e-06 2.33099543543802e-06 2.48917513203807e-05 -9.75513489911915e-06 -9.26035440598089e-06 1.59540754119044e-05 -1.96476169523015e-06 -2.03687266675813e-06 -5.77426394334768e-06 8.7047682886864e-06 8.90998008390309e-06 -1.96476169523015e-06 3.42129618189647e-05 1.95496659349993e-06 6.40024616043151e-06 5.89249636453385e-06 2.33099543543802e-06 -2.03687266675813e-06 1.95496659349993e-06 3.86955449732765e-05 1.0871369335178e-05 2.67946988303851e-05 2.48917513203807e-05 -5.77426394334768e-06 6.40024616043151e-06 1.0871369335178e-05 7.11905329416927e-05 2035 2032 0 10 15 2028 2055 0 43 6 0 0 0 0 0 15 46 0 626 0 42 44 0 0 2233 +370 422 0.999998869581957 0.000640221568007995 0.00136049665665686 -0.00948151884108771 -0.00064307613746539 0.99999759078216 0.00209878130297385 0.0107613253262458 -0.00135914969386735 -0.0020996538334086 0.999996872078053 -0.00584334121753351 2.50921349438747e-05 1.6620588946579e-05 -8.43364444179313e-06 3.13965462837989e-06 8.61753165362317e-06 1.20284309053197e-05 1.6620588946579e-05 3.04557457526881e-05 -9.51674050851838e-06 5.46805256515574e-06 8.55467887812717e-06 6.42473517648001e-06 -8.43364444179313e-06 -9.51674050851838e-06 1.52972233302993e-05 -1.41662072081384e-06 -5.58395280211367e-06 -2.74773893645019e-06 3.13965462837989e-06 5.46805256515574e-06 -1.41662072081384e-06 5.51971508505292e-05 -1.97150457528725e-05 -7.73890681184223e-06 8.61753165362317e-06 8.55467887812717e-06 -5.58395280211367e-06 -1.97150457528725e-05 6.08150261939267e-05 8.06922751359935e-06 1.20284309053197e-05 6.42473517648001e-06 -2.74773893645019e-06 -7.73890681184223e-06 8.06922751359935e-06 4.63348793627235e-05 1740 1738 0 19 14 1740 1779 0 57 14 0 0 0 0 0 8 41 0 608 0 59 62 0 0 2319 +371 428 0.999983314152406 0.000892803971141074 0.00570739150927302 -0.00433065719363227 -0.000913059448992777 0.999993291219964 0.00354737050602801 0.0169520841878558 -0.00570418611316391 -0.00355252250289103 0.999977420667413 -0.0140143414681417 4.1626702439229e-05 2.61004656275992e-05 -1.02450860935785e-05 1.86254700820763e-05 -4.76730366602248e-06 2.20423608017283e-05 2.61004656275992e-05 3.78540260155862e-05 -1.09677074618239e-05 1.45534142968527e-05 6.75461475837909e-07 1.5421415962019e-05 -1.02450860935785e-05 -1.09677074618239e-05 1.71398247791903e-05 -5.61514523697116e-06 -3.70126649572432e-06 -2.90863347982491e-06 1.86254700820763e-05 1.45534142968527e-05 -5.61514523697116e-06 5.46585543700809e-05 -8.18227488743945e-06 1.7151834013678e-05 -4.76730366602248e-06 6.75461475837909e-07 -3.70126649572432e-06 -8.18227488743945e-06 6.77755935598337e-05 -7.21999339822243e-06 2.20423608017283e-05 1.5421415962019e-05 -2.90863347982491e-06 1.7151834013678e-05 -7.21999339822243e-06 6.33277002528244e-05 2297 2294 0 12 16 2294 2330 0 47 16 0 0 0 0 0 18 49 0 644 0 55 61 0 0 2289 +371 373 0.99999973291305 -3.77851505218136e-05 0.000729894589608435 0.00236547835340452 3.80030877237777e-05 0.999999954704167 -0.000298575666195856 -0.00773659971944322 -0.000729883274820763 0.00029860332469831 0.999999689053181 -0.00570888146143707 3.21629925428931e-05 1.84580138414533e-05 -6.15425904051816e-06 1.11173873674669e-05 -2.18450786872775e-06 1.72551197810644e-05 1.84580138414533e-05 2.76568038734669e-05 -7.22981009908522e-06 1.16774583246305e-05 1.30321599930753e-06 2.06947938433171e-05 -6.15425904051816e-06 -7.22981009908522e-06 1.15372951561201e-05 -7.67200528203642e-07 6.7394688864791e-07 -3.10189741567253e-06 1.11173873674669e-05 1.16774583246305e-05 -7.67200528203642e-07 4.57886742243058e-05 -1.7520432492703e-05 1.31614004642704e-05 -2.18450786872775e-06 1.30321599930753e-06 6.7394688864791e-07 -1.7520432492703e-05 4.68273173187525e-05 2.86190344904555e-06 1.72551197810644e-05 2.06947938433171e-05 -3.10189741567253e-06 1.31614004642704e-05 2.86190344904555e-06 4.40409064962685e-05 2963 2935 0 16 58 2927 2947 0 37 18 0 0 0 0 0 16 46 0 657 0 101 82 0 0 2746 +371 374 0.999997443570207 -5.37817216387714e-05 0.00226052219109204 0.0045707668015425 4.73121920640726e-05 0.999995903583721 0.00286191847094883 0.0038319007262265 -0.00226066684995469 -0.00286180420439512 0.999993349708932 0.000286243465988574 2.75579833277149e-05 1.62749990243563e-05 -9.93628558588673e-06 3.19063763969958e-06 -2.83371571291716e-07 9.09734109459893e-06 1.62749990243563e-05 2.77775952737848e-05 -1.13504425902568e-05 1.22382817657253e-05 3.12438606174719e-06 1.40702756051258e-05 -9.93628558588673e-06 -1.13504425902568e-05 1.43183515046665e-05 -1.71166519924974e-06 -1.71653191360217e-06 -6.42571714599589e-06 3.19063763969958e-06 1.22382817657253e-05 -1.71166519924974e-06 6.14078887975279e-05 -1.69746785004102e-05 6.56520341578439e-06 -2.83371571291716e-07 3.12438606174719e-06 -1.71653191360217e-06 -1.69746785004102e-05 5.42013260771307e-05 1.51018432689621e-06 9.09734109459893e-06 1.40702756051258e-05 -6.42571714599589e-06 6.56520341578439e-06 1.51018432689621e-06 3.42652952512601e-05 2029 2004 0 15 56 1981 2009 0 51 7 0 0 0 0 0 11 43 0 680 0 59 40 0 0 2663 +371 407 0.999993975666172 0.000187561808555375 0.00346604269042434 -0.00783869591816544 -0.0001879013509678 0.999999977580031 9.76371808763099e-05 0.00590764943870611 -0.00346602429970954 -9.8287866781381e-05 0.999993988489455 -0.00594742860286003 3.98171780898755e-05 2.47339980852179e-05 -7.24954194336599e-07 -1.37582613936615e-06 -1.4447915877575e-06 2.36540468353563e-05 2.47339980852179e-05 4.63563936240625e-05 -1.19792672561652e-06 8.69683797335559e-06 -2.89155589114676e-06 2.82141933469072e-05 -7.24954194336599e-07 -1.19792672561652e-06 1.10150333523508e-05 2.01898697857408e-06 5.44806994812809e-06 8.06375734923701e-07 -1.37582613936615e-06 8.69683797335559e-06 2.01898697857408e-06 5.0397274299307e-05 -1.18675265831416e-05 2.78508223070036e-06 -1.4447915877575e-06 -2.89155589114676e-06 5.44806994812809e-06 -1.18675265831416e-05 3.3159293226866e-05 -4.00430307588438e-07 2.36540468353563e-05 2.82141933469072e-05 8.06375734923701e-07 2.78508223070036e-06 -4.00430307588438e-07 6.4585214059142e-05 2428 2425 0 16 17 2422 2449 0 38 13 0 0 0 0 0 17 46 0 486 0 39 47 0 0 2323 +371 375 0.999992847567142 -0.0002240211395296 0.00377553030540578 0.00493661398990497 0.000214668401175536 0.999996908144552 0.00247742180774352 0.00295919977482521 -0.0037760736268683 -0.00247659360109613 0.999989803824069 -0.00415158201731708 4.15656540668391e-05 2.82384732055527e-05 -8.52940670403359e-06 7.77116226652356e-06 -5.56962625099991e-07 2.45816549550516e-05 2.82384732055527e-05 4.08656571073778e-05 -8.03474135302782e-06 8.02621460188338e-06 4.51671581904604e-06 2.55979209079603e-05 -8.52940670403359e-06 -8.03474135302782e-06 1.22307783578836e-05 -1.58950259147108e-06 -3.68263641861928e-07 -4.60122074897003e-06 7.77116226652356e-06 8.02621460188338e-06 -1.58950259147108e-06 4.48185386336672e-05 -1.45008774333088e-05 2.49297971049645e-06 -5.56962625099991e-07 4.51671581904604e-06 -3.68263641861928e-07 -1.45008774333088e-05 4.91807275645408e-05 5.50442414855447e-06 2.45816549550516e-05 2.55979209079603e-05 -4.60122074897003e-06 2.49297971049645e-06 5.50442414855447e-06 4.88423252883483e-05 1881 1853 0 12 59 1847 1880 0 48 22 0 0 0 0 0 15 47 0 660 0 100 81 0 0 2573 +370 419 0.999998194476976 0.000294587133459855 0.00187730157646285 -0.00762833710803277 -0.000296927079534175 0.999999179304373 0.00124628443365071 0.00839424949288432 -0.00187693289641087 -0.00124683960512997 0.999997461253728 -0.00889299647670647 3.00517696998672e-05 1.48134780921171e-05 -9.31333718301385e-06 1.97316370042282e-06 9.30478790803616e-06 1.66214372167499e-05 1.48134780921171e-05 2.2570447683007e-05 -9.40975811282277e-06 4.63904022038139e-06 8.14594883114849e-06 1.17967520428722e-05 -9.31333718301385e-06 -9.40975811282277e-06 1.56542484937833e-05 -1.5692979021923e-07 -5.50812672347868e-06 -3.71805099445944e-06 1.97316370042282e-06 4.63904022038139e-06 -1.5692979021923e-07 4.63309586595405e-05 -1.71467555191846e-05 1.78996748317365e-06 9.30478790803616e-06 8.14594883114849e-06 -5.50812672347868e-06 -1.71467555191846e-05 5.96885667945104e-05 1.12414756081463e-05 1.66214372167499e-05 1.17967520428722e-05 -3.71805099445944e-06 1.78996748317365e-06 1.12414756081463e-05 5.5717582401357e-05 2106 2102 0 11 14 2100 2153 0 49 10 0 0 0 0 0 19 51 0 613 0 15 16 0 0 2231 +371 429 0.999971246946872 -0.0067373946379857 0.00348034380621238 -0.0024158737012976 0.00673013659204523 0.999975162084668 0.00209295847866778 0.00928597763729319 -0.0034943584489593 -0.00206947511051836 0.999991753331895 -0.0110689014044746 3.45477883631211e-05 2.44370911436891e-05 -3.35958448926994e-06 7.86122854932764e-06 -2.52837522723509e-06 2.0059854043526e-05 2.44370911436891e-05 5.8287829686916e-05 -6.11923355810711e-06 2.30803546845941e-05 -1.22394813793985e-05 2.89064736051785e-05 -3.35958448926994e-06 -6.11923355810711e-06 1.20001854498916e-05 2.66390349255444e-06 1.10601482119593e-06 2.31072820142113e-06 7.86122854932764e-06 2.30803546845941e-05 2.66390349255444e-06 5.55292542293626e-05 -2.38894217135603e-05 1.22927225769005e-05 -2.52837522723509e-06 -1.22394813793985e-05 1.10601482119593e-06 -2.38894217135603e-05 5.65754422074817e-05 -8.76110706574677e-06 2.0059854043526e-05 2.89064736051785e-05 2.31072820142113e-06 1.22927225769005e-05 -8.76110706574677e-06 7.70276731949209e-05 2015 2012 0 2 24 2016 2036 0 35 18 0 0 0 0 0 27 59 0 616 0 14 15 0 0 2419 +371 408 0.999990426492727 0.0003680546908382 0.00436021314137105 -0.00567236204986607 -0.000380493243166908 0.999995859928696 0.00285225355809813 0.0114997301291101 -0.00435914530447622 -0.002853885283667 0.999986426503381 -0.00842679235150821 3.00130529650922e-05 2.45178372004491e-05 -2.00457144037559e-06 3.63344956427139e-06 1.81933209957386e-06 1.97550295324414e-05 2.45178372004491e-05 3.8499506565865e-05 -2.10143369426681e-06 3.73914887020048e-06 4.0233253214109e-06 2.09652116091004e-05 -2.00457144037559e-06 -2.10143369426681e-06 1.17087445682217e-05 2.59523593950486e-06 1.85592231273243e-06 -1.78869897035157e-07 3.63344956427139e-06 3.73914887020048e-06 2.59523593950486e-06 3.62622646890341e-05 -1.41561453654068e-05 3.93658993264039e-06 1.81933209957386e-06 4.0233253214109e-06 1.85592231273243e-06 -1.41561453654068e-05 4.50096599697652e-05 -4.76385552299344e-07 1.97550295324414e-05 2.09652116091004e-05 -1.78869897035157e-07 3.93658993264039e-06 -4.76385552299344e-07 5.10399699647156e-05 1966 1968 0 14 15 1967 2012 0 45 14 0 0 0 0 0 21 53 0 495 0 16 19 0 0 2299 +371 427 0.999988868204582 0.000259468550761812 0.00471127827555289 -0.00380090907530692 -0.000272975006279198 0.999995854557914 0.00286641790984573 0.0113369960805041 -0.0047105149999207 -0.00286767206268483 0.999984793637071 -0.0158126451606372 3.9739467203897e-05 1.84268583264403e-05 -6.06787823778853e-06 7.39847965937668e-06 2.57140180718851e-07 2.05919392077186e-05 1.84268583264403e-05 4.15005280024639e-05 -6.44583019197248e-06 1.28648049456329e-05 2.0584966331764e-06 1.80091895925829e-05 -6.06787823778853e-06 -6.44583019197248e-06 1.29495910854424e-05 -1.94906488497221e-06 1.16025908985621e-06 -2.86077600052608e-07 7.39847965937668e-06 1.28648049456329e-05 -1.94906488497221e-06 5.75424684969403e-05 -2.03891962374183e-05 7.65874793772405e-06 2.57140180718851e-07 2.0584966331764e-06 1.16025908985621e-06 -2.03891962374183e-05 5.78244168464292e-05 5.27203593178048e-06 2.05919392077186e-05 1.80091895925829e-05 -2.86077600052608e-07 7.65874793772405e-06 5.27203593178048e-06 5.92416054431374e-05 1923 1921 0 17 17 1915 1938 0 39 13 0 0 0 0 0 13 43 0 644 0 58 63 0 0 2432 +371 397 0.999980865903771 -0.000239037362291562 0.00618147939275598 0.00108304882495117 0.000219604675547484 0.999995032931725 0.00314418282926727 0.00391447870854475 -0.00618220026609587 -0.003142765186394 0.99997595142426 -0.00761287989998867 3.40096210608085e-05 1.59700880738088e-05 -3.92986812704447e-06 -1.87474519882386e-06 2.60688997480697e-06 1.35935251671513e-05 1.59700880738088e-05 4.65280013035501e-05 -6.3466371670003e-06 9.88142335712921e-06 8.23023245887852e-06 2.02259889612788e-05 -3.92986812704447e-06 -6.3466371670003e-06 1.2093037073658e-05 3.3820911543283e-06 3.02356721587892e-07 -3.25756144019414e-06 -1.87474519882386e-06 9.88142335712921e-06 3.3820911543283e-06 6.35727102220374e-05 -3.51490316075278e-05 -6.18601940906595e-06 2.60688997480697e-06 8.23023245887852e-06 3.02356721587892e-07 -3.51490316075278e-05 6.92621377588328e-05 1.35952878513945e-05 1.35935251671513e-05 2.02259889612788e-05 -3.25756144019414e-06 -6.18601940906595e-06 1.35952878513945e-05 6.42624040340269e-05 1339 1323 0 10 39 1300 1331 0 46 8 0 0 0 0 0 16 47 0 462 0 57 44 0 0 2385 +371 426 0.999993600953052 0.000761654682548199 0.00349541629754042 -0.00697944109369824 -0.000771264622528206 0.999995924688543 0.00274877376073713 0.0185183736076797 -0.0034933084362242 -0.00275145206213609 0.999990113104984 -0.0116414671845937 3.96888756623825e-05 2.44197381969454e-05 -1.2067220060227e-05 8.87661184794274e-06 9.30562094209175e-06 1.62212833849203e-05 2.44197381969454e-05 3.78439231700942e-05 -1.12706063017371e-05 1.8383913216604e-05 7.86864049035481e-06 8.10775655544606e-06 -1.2067220060227e-05 -1.12706063017371e-05 1.46046628806309e-05 -2.87050757794892e-06 -5.26010946400556e-06 -3.47300062161394e-06 8.87661184794274e-06 1.8383913216604e-05 -2.87050757794892e-06 5.75218031626272e-05 -7.05387875621182e-06 7.27689947734227e-06 9.30562094209175e-06 7.86864049035481e-06 -5.26010946400556e-06 -7.05387875621182e-06 6.36948037325842e-05 -2.87498933392828e-06 1.62212833849203e-05 8.10775655544606e-06 -3.47300062161394e-06 7.27689947734227e-06 -2.87498933392828e-06 5.25061621526669e-05 1897 1894 0 8 17 1889 1916 0 43 9 0 0 0 0 0 23 52 0 658 0 17 20 0 0 2186 +371 412 0.999996824273966 -7.92496721041922e-05 0.00251896039507295 -0.00589564643025654 7.97414250163292e-05 0.999999977784599 -0.000195120747726808 0.00760194380347841 -0.00251894487585795 0.000195320993568232 0.999996808378118 -0.00830633617336272 4.70688998681232e-05 4.46205505879714e-05 -7.48783780108914e-06 1.92664013161382e-05 -9.85554630806088e-07 2.97759746690728e-05 4.46205505879714e-05 6.31090733141464e-05 -8.89463193570242e-06 2.55684880999306e-05 -1.33939972684634e-06 3.65269660720038e-05 -7.48783780108914e-06 -8.89463193570242e-06 1.30911185563145e-05 -1.85426170288551e-07 9.70402283750404e-08 -3.40848400791564e-06 1.92664013161382e-05 2.55684880999306e-05 -1.85426170288551e-07 5.36585147822246e-05 -2.18828194103903e-05 1.65961064237626e-05 -9.85554630806088e-07 -1.33939972684634e-06 9.70402283750404e-08 -2.18828194103903e-05 5.57874959467866e-05 -7.99026434807247e-06 2.97759746690728e-05 3.65269660720038e-05 -3.40848400791564e-06 1.65961064237626e-05 -7.99026434807247e-06 7.54385520313974e-05 2105 2102 0 11 9 2102 2129 0 43 6 0 0 0 0 0 18 49 0 569 0 13 17 0 0 2299 +371 398 0.999992113364824 0.000301648882790366 0.00396007779031248 0.000100265398127114 -0.000315910062352103 0.999993466097634 0.0036011057847302 0.00323289814049264 -0.00395896564601406 -0.0036023284125443 0.999985674807905 -0.0148407768063269 4.65378986509589e-05 3.70207616812861e-05 -6.77482315389759e-06 5.25553174989746e-06 8.42393593360877e-06 3.53319425909662e-05 3.70207616812861e-05 4.62734852732258e-05 -7.29719697763443e-06 6.0469081907249e-06 1.109146586503e-05 3.29437015709031e-05 -6.77482315389759e-06 -7.29719697763443e-06 1.15703979226135e-05 1.8785537932776e-06 8.69195873427752e-07 -3.16891318488096e-06 5.25553174989746e-06 6.0469081907249e-06 1.8785537932776e-06 4.86915136423552e-05 -2.88965733064567e-05 9.5529745666368e-06 8.42393593360877e-06 1.109146586503e-05 8.69195873427752e-07 -2.88965733064567e-05 7.12904088598002e-05 5.82591977466342e-07 3.53319425909662e-05 3.29437015709031e-05 -3.16891318488096e-06 9.5529745666368e-06 5.82591977466342e-07 7.46970158731898e-05 2423 2409 0 18 40 2403 2431 0 46 20 0 0 0 0 0 21 53 0 478 0 100 91 0 0 2368 +371 423 0.999999172333438 0.00100469042103294 0.000803697453133386 -0.00801204968724458 -0.0010049817577909 0.999999429420711 0.000362173878462233 0.00977185408041663 -0.000803333121933825 -0.000362981279982206 0.999999611450167 -0.0130155668594668 2.95786731257009e-05 2.07899159824918e-05 -1.21375983307658e-05 1.0905730882637e-05 6.33299002173576e-06 1.24191736715186e-05 2.07899159824918e-05 3.71769715863977e-05 -1.54572789541483e-05 1.68123696590904e-05 1.09233679139419e-05 1.33749201034505e-05 -1.21375983307658e-05 -1.54572789541483e-05 1.82935350367765e-05 -7.88419972771072e-06 -5.30656292081896e-06 -8.31332298149788e-06 1.0905730882637e-05 1.68123696590904e-05 -7.88419972771072e-06 5.37240773586515e-05 -5.93622947638871e-06 5.34680913342156e-06 6.33299002173576e-06 1.09233679139419e-05 -5.30656292081896e-06 -5.93622947638871e-06 5.35520965074111e-05 1.02848719107767e-05 1.24191736715186e-05 1.33749201034505e-05 -8.31332298149788e-06 5.34680913342156e-06 1.02848719107767e-05 5.26012850309396e-05 2110 2107 0 11 12 2102 2137 0 47 4 0 0 0 0 0 18 49 0 621 0 13 15 0 0 2194 +371 421 0.999992184666328 0.000339036919713217 0.00393899228628256 -0.00733638228974605 -0.000355664341737522 0.999991027006732 0.00422130417028311 0.0143023303170735 -0.00393752576376823 -0.0042226721384811 0.99998333232653 -0.0126346344749842 4.93297589177027e-05 2.947099077793e-05 -1.14584157359252e-05 8.41409615551474e-06 5.30252567646374e-06 2.47182744384628e-05 2.947099077793e-05 4.65417818050055e-05 -1.18313231842043e-05 1.94723061106563e-05 3.008422060759e-06 2.14059731914713e-05 -1.14584157359252e-05 -1.18313231842043e-05 1.78336698181671e-05 -5.30530607613423e-06 -6.77106122202857e-06 -4.0134761917476e-06 8.41409615551474e-06 1.94723061106563e-05 -5.30530607613423e-06 5.32683732777272e-05 -6.68722094002828e-06 6.23243560280802e-06 5.30252567646374e-06 3.008422060759e-06 -6.77106122202857e-06 -6.68722094002828e-06 6.60699433429566e-05 2.98917415936206e-06 2.47182744384628e-05 2.14059731914713e-05 -4.0134761917476e-06 6.23243560280802e-06 2.98917415936206e-06 6.49332501783342e-05 1788 1786 0 15 14 1782 1816 0 47 12 0 0 0 0 0 22 54 0 623 0 16 20 0 0 2306 +371 406 0.999991227066179 0.000389532014000435 0.00417061811807189 -0.00429837012437356 -0.000390123830567444 0.999999913948668 0.000141088812149948 0.00734774574972644 -0.0041705628005755 -0.000142714631903192 0.999991292981324 -0.00597359778560728 3.34162366345963e-05 2.49534006546218e-05 -1.45116658763404e-06 1.14479619861538e-06 -2.2901317259926e-06 1.70349765521228e-05 2.49534006546218e-05 3.60585560577634e-05 -2.75165278173137e-06 1.05529130519132e-05 -8.67077186776615e-06 1.45361633501401e-05 -1.45116658763404e-06 -2.75165278173137e-06 9.15540368729343e-06 3.81286531905824e-06 3.94451875638179e-06 6.48721488609213e-07 1.14479619861538e-06 1.05529130519132e-05 3.81286531905824e-06 6.1578885090752e-05 -3.95939072065682e-05 6.50982260029768e-06 -2.2901317259926e-06 -8.67077186776615e-06 3.94451875638179e-06 -3.95939072065682e-05 6.39256857430693e-05 -3.51367781115796e-06 1.70349765521228e-05 1.45361633501401e-05 6.48721488609213e-07 6.50982260029768e-06 -3.51367781115796e-06 6.37806818421899e-05 2404 2401 0 11 17 2402 2436 0 49 13 0 0 0 0 0 19 51 0 470 0 60 66 0 0 2468 +371 411 0.999997419944195 0.000162163236028678 0.00226579081981505 -0.00715271681441201 -0.000168096129148813 0.999996557543482 0.00261851959622383 0.0113319034206686 -0.00226535839231735 -0.00261889371096341 0.999994004755571 -0.0122479441484155 4.39516850365335e-05 3.25668245732055e-05 -7.12159705547823e-06 9.81603920582803e-06 1.19765615979651e-06 2.57570947245563e-05 3.25668245732055e-05 4.51805399652075e-05 -7.36224156333646e-06 1.48481048164117e-05 7.70244695444193e-07 2.36874820910977e-05 -7.12159705547823e-06 -7.36224156333646e-06 1.24956774559614e-05 6.2276789240379e-07 3.78119953261526e-06 -3.3224938907208e-06 9.81603920582803e-06 1.48481048164117e-05 6.2276789240379e-07 4.69726677742884e-05 -1.72722883782046e-05 5.54328448479432e-06 1.19765615979651e-06 7.70244695444193e-07 3.78119953261526e-06 -1.72722883782046e-05 4.57555806836298e-05 2.69483177299604e-06 2.57570947245563e-05 2.36874820910977e-05 -3.3224938907208e-06 5.54328448479432e-06 2.69483177299604e-06 6.88236635268375e-05 1247 1248 0 13 11 1239 1275 0 48 4 0 0 0 0 0 23 54 0 538 0 12 13 0 0 2241 +371 409 0.999996705106403 -0.000175458106489899 0.00256105267236117 -0.0108643538259262 0.000175493200404113 0.999999984510237 -1.34782079918143e-05 0.00690315661848333 -0.00256105026783022 1.39276109124292e-05 0.999996720408396 -0.00611284841147434 4.52594919410776e-05 2.74942685454977e-05 -3.24715794508573e-06 2.27710698338416e-06 -4.53561930023528e-06 3.35816965428595e-05 2.74942685454977e-05 6.33569202893974e-05 -3.40933502330029e-06 1.56631176227549e-05 -9.61870758730797e-06 3.27056566796895e-05 -3.24715794508573e-06 -3.40933502330029e-06 1.141364423999e-05 1.06202883483427e-06 3.40718680593506e-06 -3.47751778712708e-07 2.27710698338416e-06 1.56631176227549e-05 1.06202883483427e-06 6.45454276599559e-05 -1.78237478131201e-05 -2.99194087554343e-06 -4.53561930023528e-06 -9.61870758730797e-06 3.40718680593506e-06 -1.78237478131201e-05 4.08065749042893e-05 -1.58969188488099e-06 3.35816965428595e-05 3.27056566796895e-05 -3.47751778712708e-07 -2.99194087554343e-06 -1.58969188488099e-06 0.000107859348059774 2065 2060 0 8 10 2070 2102 0 45 10 0 0 0 0 0 19 50 0 497 0 31 41 0 0 2213 +371 399 0.999982511337538 8.82802389209861e-06 0.0059141306323756 0.00432653822825438 -1.61511617267846e-05 0.999999233302673 0.00123819756378142 -0.00642976009411588 -0.00591411516718977 -0.00123827142944249 0.999981744796202 -0.00806892080540729 7.34162656035353e-05 5.18461331717e-05 -9.36791726100265e-06 1.00220915165455e-05 3.43926679212748e-06 5.86861362258889e-05 5.18461331717e-05 6.55680007419329e-05 -8.1737953674164e-06 1.41612693206764e-05 1.01674862334786e-05 5.11626456963923e-05 -9.36791726100265e-06 -8.1737953674164e-06 1.39737639606593e-05 1.68919222233393e-06 -1.3092064302042e-06 -7.47872203827771e-06 1.00220915165455e-05 1.41612693206764e-05 1.68919222233393e-06 4.77593986291527e-05 -2.37956941812537e-05 1.341668762851e-05 3.43926679212748e-06 1.01674862334786e-05 -1.3092064302042e-06 -2.37956941812537e-05 7.1688252920685e-05 3.19508807365521e-06 5.86861362258889e-05 5.11626456963923e-05 -7.47872203827771e-06 1.341668762851e-05 3.19508807365521e-06 0.000101131615806286 2128 2113 0 24 39 2092 2117 0 47 8 0 0 0 0 0 13 45 0 482 0 57 51 0 0 2448 +371 425 0.999997097072275 0.000395242205888222 0.00237689516423671 -0.00502407063779737 -0.000395067952240794 0.99999991923887 -7.37805283009047e-05 0.00367047546640408 -0.00237692413345472 7.28412790161375e-05 0.999997172458908 -0.00669127847839832 2.86337089137613e-05 1.75092815204652e-05 -1.03036756720173e-05 5.66285716625677e-06 1.23706275438859e-05 1.08619676712541e-05 1.75092815204652e-05 3.8130577796459e-05 -1.10895691032273e-05 8.06351782205807e-06 1.78011824831049e-05 1.1983523269929e-05 -1.03036756720173e-05 -1.10895691032273e-05 1.65103967272785e-05 -1.09696333333359e-06 -9.36849234750931e-06 -5.02581059818107e-06 5.66285716625677e-06 8.06351782205807e-06 -1.09696333333359e-06 3.78997149783843e-05 -6.70215668196254e-06 2.62272413177642e-06 1.23706275438859e-05 1.78011824831049e-05 -9.36849234750931e-06 -6.70215668196254e-06 7.06910730664352e-05 1.07078736668246e-05 1.08619676712541e-05 1.1983523269929e-05 -5.02581059818107e-06 2.62272413177642e-06 1.07078736668246e-05 5.67397111849601e-05 2463 2459 0 18 16 2460 2492 0 47 16 0 0 0 0 0 12 42 0 629 0 38 50 0 0 2048 +371 420 0.999994959504904 0.000543423170920853 0.00312820332507432 -0.0049174708446094 -0.000550119066730954 0.999997558816935 0.00214003018263738 0.0123795525619974 -0.00312703274656962 -0.00214174028011947 0.999992817281591 -0.0148805848429893 3.71338181618216e-05 2.05647319621238e-05 -8.27354635322352e-06 7.79635778471931e-06 8.17375489843692e-06 1.90415933391622e-05 2.05647319621238e-05 3.86083841117717e-05 -1.0143191173784e-05 8.38795112862249e-06 1.10333250598238e-05 9.50844309902123e-06 -8.27354635322352e-06 -1.0143191173784e-05 1.45056001602078e-05 -6.6230920922431e-07 -2.01868833086679e-06 -4.17013813729902e-06 7.79635778471931e-06 8.38795112862249e-06 -6.6230920922431e-07 4.17741099292596e-05 -7.82519078669595e-06 4.25348926386245e-06 8.17375489843692e-06 1.10333250598238e-05 -2.01868833086679e-06 -7.82519078669595e-06 5.42567958892308e-05 -3.16195004161324e-06 1.90415933391622e-05 9.50844309902123e-06 -4.17013813729902e-06 4.25348926386245e-06 -3.16195004161324e-06 7.51636361075811e-05 1221 1221 0 10 11 1220 1244 0 37 5 0 0 0 0 0 19 50 0 624 0 14 17 0 0 2333 +371 422 0.999999455201412 0.000459372885816395 0.000937322479565363 -0.0116160898490585 -0.000459782983518917 0.999999798661472 0.000437351831200177 0.0113780850977789 -0.000937121383273419 -0.000437782557857691 0.999999465074829 -0.00984217621446852 2.73334999902004e-05 1.21585347597746e-05 -1.01100898252808e-05 4.64112112046717e-06 8.11508438481373e-06 9.07587122239165e-06 1.21585347597746e-05 2.27229202036973e-05 -9.88761095679905e-06 8.51628005508367e-06 2.98649205121898e-06 9.71038005912164e-06 -1.01100898252808e-05 -9.88761095679905e-06 1.48949100501919e-05 -2.11713755020064e-07 -8.28757419061838e-06 -4.36310888054646e-06 4.64112112046717e-06 8.51628005508367e-06 -2.11713755020064e-07 6.34336932179509e-05 -2.39844354364046e-05 -9.86642954286533e-07 8.11508438481373e-06 2.98649205121898e-06 -8.28757419061838e-06 -2.39844354364046e-05 7.28963842058335e-05 3.85720640093563e-06 9.07587122239165e-06 9.71038005912164e-06 -4.36310888054646e-06 -9.86642954286533e-07 3.85720640093563e-06 4.62683418464559e-05 2940 2943 0 14 14 2946 2992 0 50 11 0 0 0 0 0 18 52 0 603 0 17 18 0 0 2286 +371 410 0.999995577767114 0.000484629656811731 0.00293420863458538 -0.00715581582355413 -0.000486024514108305 0.999999769227944 0.000474683294687888 0.011339699625532 -0.00293397791184982 -0.000476107292853729 0.999995582537972 -0.00364760636845347 3.97214029292495e-05 1.95339603619954e-05 -1.85245489483588e-06 -2.10172699761195e-06 -1.4472719000355e-06 1.67437809516842e-05 1.95339603619954e-05 3.84050906140742e-05 -2.7097965629188e-06 7.78822994430129e-06 -2.04357773679399e-06 1.02847876629606e-05 -1.85245489483588e-06 -2.7097965629188e-06 1.08622138122399e-05 3.59310180882647e-06 6.20118965581922e-07 1.28749335614291e-07 -2.10172699761195e-06 7.78822994430129e-06 3.59310180882647e-06 4.70030760252639e-05 -2.55532751976896e-05 -2.71591289761027e-06 -1.4472719000355e-06 -2.04357773679399e-06 6.20118965581922e-07 -2.55532751976896e-05 5.84666986342603e-05 1.8430177909884e-06 1.67437809516842e-05 1.02847876629606e-05 1.28749335614291e-07 -2.71591289761027e-06 1.8430177909884e-06 5.83132407254847e-05 2201 2197 0 16 9 2192 2217 0 41 5 0 0 0 0 0 23 52 0 513 0 25 30 0 0 2258 +371 424 0.999996294960186 0.000552086009648533 0.00266557065920996 -0.00583129489315783 -0.000556798289580846 0.9999982831116 0.00176741322773402 0.0074088687369049 -0.00266459031860632 -0.00176889086458145 0.999994885478692 -0.0112039660879686 2.53697514204231e-05 1.81772428296955e-05 -1.09272070163649e-05 9.08440667549487e-06 6.16380097954355e-06 1.32590725788912e-05 1.81772428296955e-05 2.75080873430111e-05 -1.13702733544041e-05 1.3254974586405e-05 5.21186424662702e-06 6.14032842934733e-06 -1.09272070163649e-05 -1.13702733544041e-05 1.72355285412611e-05 -3.1784241391418e-06 -2.87852010715142e-06 -5.03983904935439e-06 9.08440667549487e-06 1.3254974586405e-05 -3.1784241391418e-06 5.67414452518001e-05 -1.69056590240472e-05 1.6797791054287e-07 6.16380097954355e-06 5.21186424662702e-06 -2.87852010715142e-06 -1.69056590240472e-05 6.31069822042436e-05 3.47174436695353e-06 1.32590725788912e-05 6.14032842934733e-06 -5.03983904935439e-06 1.6797791054287e-07 3.47174436695353e-06 5.30527111772103e-05 2196 2194 0 11 15 2196 2231 0 46 14 0 0 0 0 0 16 47 0 633 0 37 46 0 0 2189 +371 413 0.999996743249933 -0.000129399299575004 0.00254887138708746 -0.00330745118524676 0.000126523942447345 0.999999355556287 0.0011282192614817 -0.000391381123754587 -0.00254901573526553 -0.00112789309389686 0.999996115180429 -0.012320838240736 3.48535795068892e-05 2.21969674648127e-05 -9.56287585127904e-06 4.67530158081687e-06 1.08090560353864e-05 1.45242624477456e-05 2.21969674648127e-05 3.32058971005375e-05 -1.03875613536057e-05 8.65757963905727e-06 1.34907118472139e-05 1.28037884292796e-05 -9.56287585127904e-06 -1.03875613536057e-05 1.52532886500385e-05 -3.00839054903801e-08 -4.3740418176442e-06 -6.68708873242856e-06 4.67530158081687e-06 8.65757963905727e-06 -3.00839054903801e-08 4.72278459072598e-05 -9.7389607129888e-06 1.0860214074077e-05 1.08090560353864e-05 1.34907118472139e-05 -4.3740418176442e-06 -9.7389607129888e-06 5.31606070872086e-05 7.58283245112891e-06 1.45242624477456e-05 1.28037884292796e-05 -6.68708873242856e-06 1.0860214074077e-05 7.58283245112891e-06 5.97565025774544e-05 1456 1452 0 8 11 1453 1486 0 44 4 0 0 0 0 0 14 47 0 595 0 31 40 0 0 2225 +371 414 0.999997004792748 0.000499995125920523 0.00239591535885176 -0.0183431018544325 -0.000502758314123 0.999999209110784 0.00115282777735775 0.0184812720455332 -0.00239533705567844 -0.00115402889076623 0.999996465282607 -0.00751970264243832 4.03727790494488e-05 2.84934838957557e-05 -1.05302551510571e-05 -5.20522365018845e-07 1.56347736529934e-05 2.80987929875163e-05 2.84934838957557e-05 3.39453498518035e-05 -1.04220497590219e-05 5.95375992231779e-06 8.45808810128859e-06 2.57708490437783e-05 -1.05302551510571e-05 -1.04220497590219e-05 1.35096102120606e-05 -4.28563415403999e-08 -3.802514519354e-06 -4.74280714372287e-06 -5.20522365018845e-07 5.95375992231779e-06 -4.28563415403999e-08 5.32117529678345e-05 -1.72552675356326e-05 7.94668263987572e-07 1.56347736529934e-05 8.45808810128859e-06 -3.802514519354e-06 -1.72552675356326e-05 5.74966821259996e-05 1.08351891949301e-05 2.80987929875163e-05 2.57708490437783e-05 -4.74280714372287e-06 7.94668263987572e-07 1.08351891949301e-05 6.54737219831133e-05 2671 2670 0 15 11 2667 2709 0 42 9 0 0 0 0 0 19 49 0 599 0 13 15 0 0 2314 +371 418 0.999988223671942 0.000175977354391514 0.00484990199954845 -0.0108876639694033 -0.00019178421273436 0.999994671251629 0.00325893957641876 0.0150224500298497 -0.00484930265607629 -0.00325983133271401 0.999982928736002 -0.0150633797420578 3.06390077134678e-05 1.93143499098518e-05 -1.12432646352921e-05 9.34202155060007e-06 6.89346620993886e-06 1.57038064841903e-05 1.93143499098518e-05 3.66635456021842e-05 -1.30599079378351e-05 1.54339397218921e-05 8.96324067018184e-06 9.29839822464857e-06 -1.12432646352921e-05 -1.30599079378351e-05 1.79979877307762e-05 -5.37340390988971e-06 -4.29965277702202e-06 -7.94883662416269e-06 9.34202155060007e-06 1.54339397218921e-05 -5.37340390988971e-06 6.16930355606409e-05 -2.61125451255717e-05 1.4269819817852e-06 6.89346620993886e-06 8.96324067018184e-06 -4.29965277702202e-06 -2.61125451255717e-05 7.79222976935519e-05 9.40983940260497e-06 1.57038064841903e-05 9.29839822464857e-06 -7.94883662416269e-06 1.4269819817852e-06 9.40983940260497e-06 5.72826777676786e-05 1898 1901 0 12 13 1890 1920 0 41 7 0 0 0 0 0 22 54 0 626 0 15 16 0 0 2177 +372 428 0.999984141724488 0.00049469313894045 0.00560995349695047 -0.00107744079336865 -0.000506216618672896 0.999997764713019 0.00205287936829276 0.00896119323444868 -0.00560892541175588 -0.00205568666485628 0.999982156894842 -0.0119881046946524 4.06385369502849e-05 2.64377155917455e-05 -8.91882303872516e-06 1.43456244537678e-05 6.92470015076228e-08 2.91001982730901e-05 2.64377155917455e-05 4.27876684084706e-05 -8.03662654514638e-06 1.5154331527016e-05 3.70407128702687e-06 2.67539450186411e-05 -8.91882303872516e-06 -8.03662654514638e-06 1.4753561906269e-05 -2.66839209193683e-06 -4.23599614395094e-06 -3.92497488807688e-06 1.43456244537678e-05 1.5154331527016e-05 -2.66839209193683e-06 4.87932698707086e-05 -1.1178015411643e-05 1.29437694630784e-05 6.92470015076228e-08 3.70407128702687e-06 -4.23599614395094e-06 -1.1178015411643e-05 6.32122037400235e-05 -3.21730389963568e-06 2.91001982730901e-05 2.67539450186411e-05 -3.92497488807688e-06 1.29437694630784e-05 -3.21730389963568e-06 7.58929006473852e-05 2465 2462 0 16 16 2462 2491 0 49 17 0 0 0 0 0 21 54 0 651 0 55 62 0 0 2278 +372 427 0.999998357745444 0.000374677237078124 0.0017731676126648 -0.000370274612155743 -0.000377438710890444 0.999998716194182 0.00155728931375188 0.00460915086940366 -0.00177258185540449 -0.00155795601838433 0.999997215359428 -0.0113576544610049 4.61915877141411e-05 2.52342647485492e-05 -9.79244392661904e-06 1.172556969856e-05 2.58983118408379e-06 1.87476874300586e-05 2.52342647485492e-05 3.6109760048699e-05 -9.35636728317844e-06 1.06747980735761e-05 7.1270136534398e-06 2.21337515461505e-05 -9.79244392661904e-06 -9.35636728317844e-06 1.58919721114342e-05 -3.006832423533e-06 -7.30705451710454e-06 -3.6876246502958e-06 1.172556969856e-05 1.06747980735761e-05 -3.006832423533e-06 3.63522311258679e-05 -7.63795303469804e-06 1.16904733099765e-05 2.58983118408379e-06 7.1270136534398e-06 -7.30705451710454e-06 -7.63795303469804e-06 5.87841742896278e-05 2.60689452262986e-06 1.87476874300586e-05 2.21337515461505e-05 -3.6876246502958e-06 1.16904733099765e-05 2.60689452262986e-06 4.98178115376579e-05 2561 2558 0 13 17 2558 2581 0 40 13 0 0 0 0 0 23 53 0 655 0 58 64 0 0 2356 +371 419 0.99999843228473 0.000556904271882829 0.0016808586242094 -0.0058460659670343 -0.000559159451380516 0.999998943843325 0.00134151143978636 0.00823950492453027 -0.00168010975550774 -0.00134244920466455 0.999997687527997 -0.0158294995343524 3.60290722444958e-05 2.00202616332407e-05 -8.59299515359559e-06 6.05497535503824e-06 8.32093903235958e-06 1.79706881621747e-05 2.00202616332407e-05 3.36418217779388e-05 -9.19001584260413e-06 8.3782907356378e-06 6.26262232940406e-06 1.66531569034238e-05 -8.59299515359559e-06 -9.19001584260413e-06 1.49433113876305e-05 4.23938619308988e-07 -7.29524110295553e-06 -2.84847877790215e-06 6.05497535503824e-06 8.3782907356378e-06 4.23938619308988e-07 4.40582133361713e-05 -1.94791856180447e-05 9.88765237269382e-06 8.32093903235958e-06 6.26262232940406e-06 -7.29524110295553e-06 -1.94791856180447e-05 6.96954989994546e-05 -1.6801999708876e-06 1.79706881621747e-05 1.66531569034238e-05 -2.84847877790215e-06 9.88765237269382e-06 -1.6801999708876e-06 6.28058278787694e-05 2527 2526 0 10 14 2529 2562 0 46 14 0 0 0 0 0 17 49 0 585 0 57 63 0 0 2211 +372 429 0.999970551190539 -0.00738187709509349 0.00209872395563294 -0.00037572758932581 0.00737238288209968 0.999962715788424 0.00449610983846191 0.00612370816164117 -0.0021318354365985 -0.0044805048368152 0.999987690101272 -0.010701282674142 4.02199784907249e-05 2.70127358019714e-05 -4.38501286107026e-06 1.42873559059491e-06 -1.03725954084262e-06 2.37301786093544e-05 2.70127358019714e-05 4.59531288775843e-05 -4.49823380627028e-06 1.12098575728913e-05 -3.93314479026519e-06 2.57289556554694e-05 -4.38501286107026e-06 -4.49823380627028e-06 1.26150184615449e-05 1.12231826717818e-06 -3.29775091964303e-07 -2.04104152215076e-06 1.42873559059491e-06 1.12098575728913e-05 1.12231826717818e-06 4.59270622171404e-05 -9.85514703349128e-06 -1.45653857817903e-06 -1.03725954084262e-06 -3.93314479026519e-06 -3.29775091964303e-07 -9.85514703349128e-06 4.71861868098375e-05 2.36133020769587e-06 2.37301786093544e-05 2.57289556554694e-05 -2.04104152215076e-06 -1.45653857817903e-06 2.36133020769587e-06 7.06260556418077e-05 1384 1381 0 4 24 1383 1400 0 35 14 0 0 0 0 0 33 65 0 613 0 54 62 0 0 2369 +371 405 0.999996106780674 0.00093469442960621 0.00262921467698119 -0.00638183973313744 -0.000938388119179876 0.999998574130715 0.00140398157948153 0.012791002733292 -0.00262789863430312 -0.00140644333728897 0.999995558023088 -0.00243787986008545 2.57058621220432e-05 1.57241591971921e-05 -4.25888785431338e-07 -2.08281320970791e-07 3.24766364875051e-06 1.28913828347437e-05 1.57241591971921e-05 2.47348804296583e-05 -1.61269829822701e-06 1.6226509225141e-06 -2.17339842447039e-07 1.50679846128223e-05 -4.25888785431338e-07 -1.61269829822701e-06 1.02864875170807e-05 3.12004206261803e-06 2.0484939990228e-06 -5.36323076380901e-08 -2.08281320970791e-07 1.6226509225141e-06 3.12004206261803e-06 3.60555558246691e-05 -1.51755854856476e-05 7.84968896752539e-06 3.24766364875051e-06 -2.17339842447039e-07 2.0484939990228e-06 -1.51755854856476e-05 3.9328287740301e-05 3.83139581581855e-06 1.28913828347437e-05 1.50679846128223e-05 -5.36323076380901e-08 7.84968896752539e-06 3.83139581581855e-06 5.99478126446352e-05 2937 2936 0 13 19 2935 2979 0 43 16 0 0 0 0 0 17 48 0 458 0 20 21 0 0 2450 +372 426 0.999992653745435 0.000594091747951472 0.00378675456804173 -0.00355296073220291 -0.000601352350641454 0.99999798266492 0.00191651805107809 0.00931458894038089 -0.00378560834132996 -0.0019187811456094 0.999990993683644 -0.00897476754601233 3.0342336962025e-05 1.76506978332608e-05 -1.15070693164887e-05 6.92244605259665e-06 8.57162897176303e-06 1.84222378001253e-05 1.76506978332608e-05 3.09029225651249e-05 -1.0351139500204e-05 1.78776747564031e-05 2.32474561943154e-07 1.25470531062532e-05 -1.15070693164887e-05 -1.0351139500204e-05 1.57139355478484e-05 -3.46348017749448e-06 -6.74595895946849e-06 -5.6179088844702e-06 6.92244605259665e-06 1.78776747564031e-05 -3.46348017749448e-06 5.00314639091749e-05 -1.25800843703472e-05 4.49153863141116e-06 8.57162897176303e-06 2.32474561943154e-07 -6.74595895946849e-06 -1.25800843703472e-05 5.18252051362991e-05 3.41984944952935e-06 1.84222378001253e-05 1.25470531062532e-05 -5.6179088844702e-06 4.49153863141116e-06 3.41984944952935e-06 6.21011124530433e-05 1907 1903 0 18 16 1888 1914 0 43 8 0 0 0 0 0 17 47 0 668 0 59 69 0 0 2152 +371 415 0.9999746105636 -0.000347562505081378 0.00711740321195067 -0.0031600958798922 0.00033729218486434 0.999998900351288 0.00144413648809364 0.00590164967057989 -0.00711789731300288 -0.00144169917780221 0.999973628172924 -0.0108200815941531 7.45735910463113e-05 5.67644655832216e-05 -1.34096947688528e-05 2.17443009004407e-05 -2.50267473509612e-06 6.79280740868133e-05 5.67644655832216e-05 5.74974180368401e-05 -1.19587330284081e-05 1.92276314889747e-05 -2.65733155448181e-06 5.62567807730622e-05 -1.34096947688528e-05 -1.19587330284081e-05 1.35614922415471e-05 -1.90050774215264e-07 -2.36644223231642e-06 -9.03995793291478e-06 2.17443009004407e-05 1.92276314889747e-05 -1.90050774215264e-07 5.41046449681819e-05 -2.90178140170602e-05 1.85908749210154e-05 -2.50267473509612e-06 -2.65733155448181e-06 -2.36644223231642e-06 -2.90178140170602e-05 5.968441593562e-05 -4.66168076582759e-06 6.79280740868133e-05 5.62567807730622e-05 -9.03995793291478e-06 1.85908749210154e-05 -4.66168076582759e-06 0.000118871899860964 1937 1936 0 12 14 1936 1962 0 40 11 0 0 0 0 0 16 48 0 576 0 55 59 0 0 2208 +372 423 0.999983406128676 0.000459305312820249 0.00574251738542099 -0.00282653712933564 -0.000478460846385357 0.999994325044856 0.00333480933519771 0.00905911828615203 -0.00574095310124751 -0.00333750156752933 0.999977951027309 -0.012935288798378 3.38210654163089e-05 1.50574816352875e-05 -1.15224463928128e-05 7.47558877488243e-06 4.31813803248567e-06 1.39475564833776e-05 1.50574816352875e-05 4.12219498665129e-05 -1.37776091054892e-05 2.01141337555307e-05 1.16539683374829e-05 9.91951344461298e-06 -1.15224463928128e-05 -1.37776091054892e-05 1.80673521944108e-05 -3.45989093876242e-06 -6.37458864861157e-06 -5.38877421469362e-06 7.47558877488243e-06 2.01141337555307e-05 -3.45989093876242e-06 5.28741536408343e-05 -1.08673902006805e-05 3.39014951560836e-07 4.31813803248567e-06 1.16539683374829e-05 -6.37458864861157e-06 -1.08673902006805e-05 5.92867221956127e-05 6.51942087239861e-06 1.39475564833776e-05 9.91951344461298e-06 -5.38877421469362e-06 3.39014951560836e-07 6.51942087239861e-06 5.66853611492106e-05 1539 1537 0 12 12 1532 1558 0 39 5 0 0 0 0 0 17 48 0 624 0 51 60 0 0 2210 +371 400 0.999996254345525 0.000533955175749728 0.0026844341658801 -0.0035412601881097 -0.00053118283018711 0.999999325010391 -0.00103335548735956 -0.00196551257148216 -0.00268498411942579 0.00103192569142927 0.999995862986265 -0.00888257942560481 5.17759399411974e-05 3.56553020865994e-05 -3.19075083617303e-06 9.87691024726868e-06 2.47743894837403e-06 3.63650189314179e-05 3.56553020865994e-05 5.69026094741895e-05 -2.47791796481543e-06 1.62796941377194e-05 -1.82413910357402e-06 4.54488054426519e-05 -3.19075083617303e-06 -2.47791796481543e-06 1.14474903984531e-05 1.8679128348144e-06 1.8225715594694e-06 3.37031639609508e-07 9.87691024726868e-06 1.62796941377194e-05 1.8679128348144e-06 5.20539315782985e-05 -2.42715831946125e-05 1.85073365513357e-05 2.47743894837403e-06 -1.82413910357402e-06 1.8225715594694e-06 -2.42715831946125e-05 5.53671196751385e-05 3.6538330392757e-06 3.63650189314179e-05 4.54488054426519e-05 3.37031639609508e-07 1.85073365513357e-05 3.6538330392757e-06 8.82856319489767e-05 2686 2672 0 16 39 2672 2706 0 49 19 0 0 0 0 0 18 51 0 497 0 97 86 0 0 2381 +372 412 0.999985597673746 -7.7386905010255e-05 0.00536641932272725 -0.00302213618778247 5.91364931880706e-05 0.999994215072665 0.003400929884539 0.0075111198093574 -0.00536665146581935 -0.00340056355201752 0.999979817406118 -0.00996329076814122 5.58321217228702e-05 3.2911978909467e-05 -9.35821752775022e-06 1.93844736546516e-05 -2.30652253187727e-06 1.83637512522819e-05 3.2911978909467e-05 4.95400069902009e-05 -9.77421321342148e-06 2.49567849567219e-05 2.23991532820714e-07 2.44690675988055e-05 -9.35821752775022e-06 -9.77421321342148e-06 1.45621328277127e-05 -1.18358364771555e-06 -1.255443238188e-06 -3.73924915918581e-06 1.93844736546516e-05 2.49567849567219e-05 -1.18358364771555e-06 4.64696123118787e-05 -1.42076266620498e-05 1.08904525986606e-05 -2.30652253187727e-06 2.23991532820714e-07 -1.255443238188e-06 -1.42076266620498e-05 4.65840827274877e-05 2.37574910541451e-06 1.83637512522819e-05 2.44690675988055e-05 -3.73924915918581e-06 1.08904525986606e-05 2.37574910541451e-06 6.6013587197781e-05 1429 1426 0 10 9 1426 1448 0 39 5 0 0 0 0 0 24 55 0 577 0 53 63 0 0 2247 +372 420 0.999999707359446 0.000249714440560379 0.00072313464925963 -0.00329751699707033 -0.000249372468440932 0.999999857063947 -0.000472953969358323 0.00748428389527917 -0.000723252649333487 0.000472773501080311 0.999999626695341 -0.013241674253497 2.88021332789206e-05 1.94057232466433e-05 -1.08954436755463e-05 1.39729847168264e-05 7.93750226304841e-06 1.24380321917818e-05 1.94057232466433e-05 2.62427121461573e-05 -1.17422788237598e-05 1.05724947252841e-05 9.17311843557072e-06 1.29907688792007e-05 -1.08954436755463e-05 -1.17422788237598e-05 1.67961942456129e-05 -6.47960356219922e-06 -4.34092719594938e-06 -6.14558281637539e-06 1.39729847168264e-05 1.05724947252841e-05 -6.47960356219922e-06 4.46161276508984e-05 -8.87756974234455e-06 1.79226287950853e-06 7.93750226304841e-06 9.17311843557072e-06 -4.34092719594938e-06 -8.87756974234455e-06 5.82655369289226e-05 8.28729641883323e-06 1.24380321917818e-05 1.29907688792007e-05 -6.14558281637539e-06 1.79226287950853e-06 8.28729641883323e-06 4.99483514388075e-05 1904 1905 0 20 11 1889 1912 0 39 4 0 0 0 0 0 16 47 0 629 0 55 65 0 0 2245 +372 374 0.999999837243335 0.000422928922938098 0.000382941810262474 -0.00654913859565437 -0.000422913059544748 0.999999909710931 -4.15051033480912e-05 0.00698936611817973 -0.00038295932939567 4.13431455002533e-05 0.999999925816445 0.00138917775428254 2.13402821097072e-05 1.56387946394854e-05 -8.87364426496216e-06 5.67389666218521e-06 5.84823699104311e-06 1.16743179699217e-05 1.56387946394854e-05 2.41452038415675e-05 -1.0310778585598e-05 5.55688357484752e-06 3.79275415871436e-06 1.3453636830975e-05 -8.87364426496216e-06 -1.0310778585598e-05 1.37945474693098e-05 -1.65371723577298e-06 -4.8156975834314e-06 -5.23501193305252e-06 5.67389666218521e-06 5.55688357484752e-06 -1.65371723577298e-06 3.41570642945646e-05 -1.47972613063529e-05 3.63674895001373e-06 5.84823699104311e-06 3.79275415871436e-06 -4.8156975834314e-06 -1.47972613063529e-05 4.78329316261364e-05 2.50376937626003e-06 1.16743179699217e-05 1.3453636830975e-05 -5.23501193305252e-06 3.63674895001373e-06 2.50376937626003e-06 3.15294252738028e-05 2195 2169 0 18 49 2139 2164 0 46 4 0 0 0 0 0 19 51 0 691 0 103 90 0 0 2688 +372 425 0.999987447615911 -0.00014191728067794 0.00500843988700702 -0.00347065837392965 0.000127877110626065 0.99999606197899 0.00280351100502916 0.00433584184064866 -0.00500881803032371 -0.00280283534946073 0.999983527792305 -0.00879657557386962 3.7883705956559e-05 1.38201954496576e-05 -8.99299799807256e-06 4.58764030732635e-06 7.95822363533577e-06 4.3901754580114e-06 1.38201954496576e-05 3.97862843043645e-05 -8.80328683183238e-06 5.37488734268154e-06 1.38875791111865e-05 1.53188240928581e-05 -8.99299799807256e-06 -8.80328683183238e-06 1.62015420561464e-05 -1.60140738209936e-06 -3.31255846723701e-06 -1.03591796621684e-06 4.58764030732635e-06 5.37488734268154e-06 -1.60140738209936e-06 3.90254172708971e-05 -4.98050632823888e-06 -1.9100114426845e-08 7.95822363533577e-06 1.38875791111865e-05 -3.31255846723701e-06 -4.98050632823888e-06 5.96354608066392e-05 1.00184222068559e-05 4.3901754580114e-06 1.53188240928581e-05 -1.03591796621684e-06 -1.9100114426845e-08 1.00184222068559e-05 6.35004087059458e-05 1628 1625 0 15 16 1643 1670 0 45 19 0 0 0 0 0 21 51 0 639 0 36 47 0 0 2128 +372 413 0.999998343728285 0.000152804033438286 0.00181361286231856 -0.00273310551663646 -0.000153266924525861 0.999999955717834 0.000255095236700409 0.00148973978531807 -0.00181357380242678 -0.000255372781059072 0.999998322865997 -0.00782975256313679 4.23462110084898e-05 3.29135796451899e-05 -7.75852341991221e-06 7.27206281578456e-06 8.82310304506892e-06 2.5211939668938e-05 3.29135796451899e-05 4.14057749458967e-05 -9.48730161259188e-06 8.67985300308607e-06 1.29381788003455e-05 2.50432314262757e-05 -7.75852341991221e-06 -9.48730161259188e-06 1.15977320554755e-05 6.36540835087546e-07 -2.05911401101373e-06 -3.73781287041061e-06 7.27206281578456e-06 8.67985300308607e-06 6.36540835087546e-07 2.83045597561571e-05 -1.67434682377747e-06 4.56139561398562e-06 8.82310304506892e-06 1.29381788003455e-05 -2.05911401101373e-06 -1.67434682377747e-06 4.67916063398956e-05 1.45233778350582e-05 2.5211939668938e-05 2.50432314262757e-05 -3.73781287041061e-06 4.56139561398562e-06 1.45233778350582e-05 6.51664356936087e-05 2269 2264 0 17 11 2267 2296 0 41 5 0 0 0 0 0 20 53 0 606 0 32 40 0 0 2326 +372 375 0.999998356093302 -0.000236365236124786 0.00179776032023992 -0.00252822436958556 0.000236223169108838 0.999999968960105 7.92363734151863e-05 0.0025871346770131 -0.00179777899316174 -7.88115705178361e-05 0.999998380888403 -0.00298266255419769 2.9281191502165e-05 1.96668351052364e-05 -6.04322227361064e-06 6.92858657410956e-06 4.6342509004916e-06 1.56180770153746e-05 1.96668351052364e-05 2.37452461765668e-05 -6.67328504039557e-06 3.3134678773376e-06 5.70467168562133e-06 1.65672876901009e-05 -6.04322227361064e-06 -6.67328504039557e-06 1.12466227924437e-05 -3.42476267825687e-07 -1.52806602623261e-06 -3.72297650442758e-06 6.92858657410956e-06 3.3134678773376e-06 -3.42476267825687e-07 3.51266255891655e-05 -1.37809771002731e-05 3.15662280339121e-06 4.6342509004916e-06 5.70467168562133e-06 -1.52806602623261e-06 -1.37809771002731e-05 3.94611047204218e-05 5.95945887419804e-06 1.56180770153746e-05 1.65672876901009e-05 -3.72297650442758e-06 3.15662280339121e-06 5.95945887419804e-06 3.07091143183749e-05 2711 2685 0 12 56 2684 2709 0 44 27 0 0 0 0 0 14 46 0 665 0 100 81 0 0 2673 +372 421 0.999996219537939 0.000348107106362275 0.00272758707880488 -0.0005721753327048 -0.000351743659290713 0.999999049849456 0.00133288280960362 0.00526718775079612 -0.00272712050120856 -0.00133383718215086 0.999995391835454 -0.0106388909735901 4.14581574605594e-05 2.56222998523303e-05 -1.01792728342948e-05 1.3486119199334e-05 4.86986687351776e-06 2.13895028779455e-05 2.56222998523303e-05 4.44375385476693e-05 -1.12059185839314e-05 2.03834979330817e-05 3.05272192502588e-06 1.54039181631834e-05 -1.01792728342948e-05 -1.12059185839314e-05 1.57596629008881e-05 -2.43787905029038e-06 -3.52268839586112e-06 -4.7846637001224e-06 1.3486119199334e-05 2.03834979330817e-05 -2.43787905029038e-06 5.29440488995538e-05 -1.49153041053305e-05 6.11005490878763e-06 4.86986687351776e-06 3.05272192502588e-06 -3.52268839586112e-06 -1.49153041053305e-05 5.87102769465932e-05 3.27496456434686e-06 2.13895028779455e-05 1.54039181631834e-05 -4.7846637001224e-06 6.11005490878763e-06 3.27496456434686e-06 6.32585669864858e-05 1903 1901 0 12 14 1899 1932 0 52 12 0 0 0 0 0 14 47 0 628 0 56 65 0 0 2336 +372 424 0.999995292233568 0.000214947250341536 0.00306093259985504 -0.00109835325606806 -0.000220308614236581 0.999998442176207 0.00175131643987867 0.0022943208760503 -0.00306055139080818 -0.00175198254490927 0.99999378177184 -0.00880569229118451 2.55122205742757e-05 1.40171324963154e-05 -9.13607930488303e-06 3.62369257379277e-06 9.05107745073815e-06 1.08134494833242e-05 1.40171324963154e-05 2.52281198883865e-05 -1.06030522517171e-05 7.58983028718395e-06 3.85774974850455e-06 6.6136181091077e-06 -9.13607930488303e-06 -1.06030522517171e-05 1.46148502863638e-05 -1.22577330480647e-07 -5.25580447305744e-06 -1.50267925273928e-06 3.62369257379277e-06 7.58983028718395e-06 -1.22577330480647e-07 4.00740780926465e-05 -1.60886869968841e-05 4.78035274526158e-06 9.05107745073815e-06 3.85774974850455e-06 -5.25580447305744e-06 -1.60886869968841e-05 6.11436493585954e-05 4.26008889306071e-06 1.08134494833242e-05 6.6136181091077e-06 -1.50267925273928e-06 4.78035274526158e-06 4.26008889306071e-06 5.06778002994537e-05 2203 2200 0 16 15 2212 2240 0 43 15 0 0 0 0 0 22 53 0 638 0 36 49 0 0 2238 +372 418 0.999997198316022 0.000266437643932367 0.00235209929393597 -0.00185419366854007 -0.000270810191146059 0.999998235621222 0.00185887500468868 0.00495418579648529 -0.00235159986966527 -0.00185950676916774 0.999995506096217 -0.0109808232058638 3.26040416487589e-05 2.02977089904168e-05 -1.00744581650358e-05 8.49690363464932e-06 1.00616738480589e-05 2.19734629599314e-05 2.02977089904168e-05 3.05722089427323e-05 -1.0095215793733e-05 1.40188899005577e-05 5.60273881300848e-06 1.23146663999745e-05 -1.00744581650358e-05 -1.0095215793733e-05 1.50134571199399e-05 -2.59263223336441e-06 -4.80046500084417e-06 -3.74697375252803e-06 8.49690363464932e-06 1.40188899005577e-05 -2.59263223336441e-06 4.13168520271202e-05 -9.31979473094432e-06 3.59206038621479e-06 1.00616738480589e-05 5.60273881300848e-06 -4.80046500084417e-06 -9.31979473094432e-06 5.18422485877763e-05 7.60084777170655e-06 2.19734629599314e-05 1.23146663999745e-05 -3.74697375252803e-06 3.59206038621479e-06 7.60084777170655e-06 6.26237692022984e-05 1948 1952 0 20 13 1935 1963 0 40 7 0 0 0 0 0 17 49 0 624 0 58 66 0 0 2221 +372 376 0.999999786697906 0.000153865007414251 0.000634767439047536 -0.000961077341862645 -0.000153924147829662 0.999999983817933 9.31208333722905e-05 0.0020966372073838 -0.00063475310073797 -9.32185195465472e-05 0.999999794199383 -0.00122481827265593 2.79798218337962e-05 1.85753238576802e-05 -7.63557360700349e-06 5.40834008280596e-06 6.8754419829189e-06 1.88659178706414e-05 1.85753238576802e-05 2.34428655145203e-05 -7.90301075742502e-06 5.82724392390352e-06 4.12842064409782e-06 1.71068981102411e-05 -7.63557360700349e-06 -7.90301075742502e-06 1.24608684654053e-05 -4.13509582487003e-07 -2.73090357364876e-06 -3.55729368527492e-06 5.40834008280596e-06 5.82724392390352e-06 -4.13509582487003e-07 2.70227821848645e-05 -3.104430141842e-06 5.23867207211847e-06 6.8754419829189e-06 4.12842064409782e-06 -2.73090357364876e-06 -3.104430141842e-06 3.62634326646993e-05 8.16721201707658e-07 1.88659178706414e-05 1.71068981102411e-05 -3.55729368527492e-06 5.23867207211847e-06 8.16721201707658e-07 3.68678180752819e-05 3096 3068 0 17 59 3066 3110 0 44 32 0 0 0 0 0 22 53 0 648 0 55 33 0 0 2658 +372 415 0.999995263124677 0.000450087211485626 0.00304485627076614 -0.00424127095768114 -0.000454784894347585 0.999998707225363 0.00154230940522031 0.00804791230875885 -0.00304415816071374 -0.00154368685413036 0.999994175049029 -0.00848039155404492 3.80158039855309e-05 2.05177703154201e-05 -7.34836440777418e-06 1.05600951734039e-05 -1.46881401180731e-06 1.80898624262909e-05 2.05177703154201e-05 3.11308993903905e-05 -1.00971973724013e-05 1.11432355136008e-05 6.06700781078977e-06 2.18436115021906e-05 -7.34836440777418e-06 -1.00971973724013e-05 1.37522502077268e-05 -1.65061855465847e-06 -1.13948517272475e-06 -4.14495916776361e-06 1.05600951734039e-05 1.11432355136008e-05 -1.65061855465847e-06 4.27774806367785e-05 -1.48052267850614e-05 8.0343806761279e-06 -1.46881401180731e-06 6.06700781078977e-06 -1.13948517272475e-06 -1.48052267850614e-05 5.41483155891499e-05 6.52329998860001e-06 1.80898624262909e-05 2.18436115021906e-05 -4.14495916776361e-06 8.0343806761279e-06 6.52329998860001e-06 5.81948758511321e-05 2537 2536 0 17 14 2529 2556 0 41 11 0 0 0 0 0 22 54 0 587 0 55 60 0 0 2229 +372 419 0.999987191298963 2.79444554099323e-05 0.00506127030686098 -0.00271766362682692 -4.99054930782182e-05 0.999990585413074 0.00433896239437753 0.00856719429819168 -0.00506110140715057 -0.00433915940309568 0.999977778227207 -0.0135705395448725 4.75330638715814e-05 2.28771789978341e-05 -1.09244989655381e-05 9.09872381217713e-06 3.48852096978578e-06 1.87434503091901e-05 2.28771789978341e-05 4.79895028273608e-05 -9.10451525849184e-06 1.94160020556896e-05 2.06579428957679e-06 3.19705408772714e-05 -1.09244989655381e-05 -9.10451525849184e-06 1.5496651961888e-05 -6.65410911198511e-07 -1.97084856802749e-06 -3.6897263216145e-06 9.09872381217713e-06 1.94160020556896e-05 -6.65410911198511e-07 4.82214041565203e-05 -1.47628718918748e-05 1.56551109559714e-05 3.48852096978578e-06 2.06579428957679e-06 -1.97084856802749e-06 -1.47628718918748e-05 5.6313087271668e-05 -4.98201132560743e-06 1.87434503091901e-05 3.19705408772714e-05 -3.6897263216145e-06 1.56551109559714e-05 -4.98201132560743e-06 6.92742176182324e-05 2137 2138 0 20 14 2133 2155 0 38 15 0 0 0 0 0 17 49 0 599 0 56 62 0 0 2247 +372 409 0.999995947860055 0.000122538865363987 0.00284416027963618 -0.00156148337230146 -0.000130005087969127 0.999996546047837 0.00262506972731667 0.00312098830328944 -0.00284382878297675 -0.00262542884547412 0.999992509852564 -0.00873009952700704 3.20879241087745e-05 2.2099048629845e-05 -3.08428824385676e-06 1.04187357833471e-06 1.1812707105819e-07 1.89100074798513e-05 2.2099048629845e-05 2.93755722726378e-05 -2.88343149454912e-06 4.16791788487306e-06 -2.79440444082651e-06 9.66105497010502e-06 -3.08428824385676e-06 -2.88343149454912e-06 1.07512220332728e-05 3.46552925561226e-06 2.50527392552584e-06 -8.22078474475348e-07 1.04187357833471e-06 4.16791788487306e-06 3.46552925561226e-06 3.08517215601196e-05 -1.12815207979273e-05 -4.08236557969477e-06 1.1812707105819e-07 -2.79440444082651e-06 2.50527392552584e-06 -1.12815207979273e-05 4.03181761318896e-05 1.2041083341664e-06 1.89100074798513e-05 9.66105497010502e-06 -8.22078474475348e-07 -4.08236557969477e-06 1.2041083341664e-06 5.51839090881577e-05 2133 2129 0 17 10 2141 2169 0 44 10 0 0 0 0 0 19 50 0 508 0 30 41 0 0 2278 +372 414 0.999998914534899 0.000316364179488096 0.00143904229576856 -0.00812495405951852 -0.000317923850592422 0.999999362230818 0.00108372615661889 0.010126692501103 -0.00143869852585541 -0.00108418248613981 0.999998377346128 -0.00936407650876092 4.37266218414485e-05 3.61783946175522e-05 -1.19646124928772e-05 1.50460854768929e-05 8.73302670497743e-06 3.67262837779719e-05 3.61783946175522e-05 4.24935185348381e-05 -1.13640594696439e-05 1.50862320821748e-05 7.25795212791091e-06 3.58962164282125e-05 -1.19646124928772e-05 -1.13640594696439e-05 1.4750227655014e-05 -1.12600184423486e-06 -4.93229511079659e-06 -5.77579157681999e-06 1.50460854768929e-05 1.50862320821748e-05 -1.12600184423486e-06 6.06391194005435e-05 -2.00797855158057e-05 1.85593357045689e-05 8.73302670497743e-06 7.25795212791091e-06 -4.93229511079659e-06 -2.00797855158057e-05 5.81189126020174e-05 -4.74923932419662e-07 3.67262837779719e-05 3.58962164282125e-05 -5.77579157681999e-06 1.85593357045689e-05 -4.74923932419662e-07 7.79665455368246e-05 2773 2771 0 11 11 2776 2820 0 51 9 0 0 0 0 0 17 48 0 610 0 11 15 0 0 2378 +372 407 0.999988622075031 -5.91470799631233e-05 0.00476992894112655 -0.000151071647266584 4.37545698341563e-05 0.999994792170505 0.00322702919210295 0.00261122537072651 -0.00477009496950358 -0.00322678376901797 0.999983416892745 -0.00816114871683615 2.69325869908548e-05 1.77211031501358e-05 -1.54869397876044e-06 1.72062718801026e-06 2.14465755046948e-06 1.8420326407784e-05 1.77211031501358e-05 3.78200996179619e-05 -2.54871046246716e-06 1.12822105490166e-05 5.93000963265679e-08 1.05069807582728e-05 -1.54869397876044e-06 -2.54871046246716e-06 1.19668561806088e-05 1.43352440160718e-06 3.22813492932382e-06 -6.23228000816977e-07 1.72062718801026e-06 1.12822105490166e-05 1.43352440160718e-06 4.54632810177465e-05 -1.67191563205038e-05 -3.66349291547956e-06 2.14465755046948e-06 5.93000963265679e-08 3.22813492932382e-06 -1.67191563205038e-05 3.79294204615081e-05 2.0334462633955e-06 1.8420326407784e-05 1.05069807582728e-05 -6.23228000816977e-07 -3.66349291547956e-06 2.0334462633955e-06 5.84708847265595e-05 1648 1645 0 12 17 1659 1688 0 41 14 0 0 0 0 0 23 53 0 488 0 37 46 0 0 2323 +372 422 0.999994779189496 0.000149495599731594 0.00322788550242748 -0.00356523746320078 -0.000156163134012521 0.999997854760098 0.00206545110776327 0.00868192770292014 -0.00322756980198662 -0.00206594440115072 0.999992657306495 -0.0104650987355721 3.22180136308303e-05 1.81346286320757e-05 -9.84104150907131e-06 6.32885349821908e-06 1.13740534446465e-05 1.68572491835247e-05 1.81346286320757e-05 2.78217822225786e-05 -1.08294771683943e-05 8.16332580149469e-06 1.09445124840656e-05 1.628282083876e-05 -9.84104150907131e-06 -1.08294771683943e-05 1.58651051289535e-05 -3.48455114852814e-07 -6.61028010679934e-06 -5.29034567853022e-06 6.32885349821908e-06 8.16332580149469e-06 -3.48455114852814e-07 3.64779209794701e-05 -4.88703728588563e-06 3.83863018098425e-06 1.13740534446465e-05 1.09445124840656e-05 -6.61028010679934e-06 -4.88703728588563e-06 5.20231434627454e-05 1.02456354283495e-05 1.68572491835247e-05 1.628282083876e-05 -5.29034567853022e-06 3.83863018098425e-06 1.02456354283495e-05 4.48107612103007e-05 2260 2261 0 17 14 2259 2296 0 47 11 0 0 0 0 0 21 55 0 611 0 16 19 0 0 2322 +372 398 0.999990312892663 -0.000120720123343947 0.00439994857771128 0.00270356913415706 0.000114492352340427 0.999998991422065 0.00141564344163618 -0.0022813395064453 -0.00440011503667111 -0.00141512596768337 0.999989318146029 -0.0102999143497921 3.94201726265627e-05 3.05301676016921e-05 -4.9671739992899e-06 5.76976598603224e-06 2.36925020820917e-06 2.89782098880466e-05 3.05301676016921e-05 4.48561609563848e-05 -5.25467772992536e-06 5.73741114310278e-06 4.1776882125712e-06 2.90860675531768e-05 -4.9671739992899e-06 -5.25467772992536e-06 1.01304320465475e-05 2.31014905437359e-06 3.0851486033194e-06 -2.06156426345202e-06 5.76976598603224e-06 5.73741114310278e-06 2.31014905437359e-06 3.68341051982199e-05 -1.43212518090297e-05 1.03411264101639e-05 2.36925020820917e-06 4.1776882125712e-06 3.0851486033194e-06 -1.43212518090297e-05 4.17697416798225e-05 -1.10131613734374e-06 2.89782098880466e-05 2.90860675531768e-05 -2.06156426345202e-06 1.03411264101639e-05 -1.10131613734374e-06 6.5091331713122e-05 2499 2484 0 18 39 2485 2507 0 42 22 0 0 0 0 0 17 49 0 485 0 95 86 0 0 2459 +372 411 0.999998476376193 -0.000361083938923741 0.0017078828066819 -0.00226261705106837 0.000355546722193262 0.999994683617783 0.00324134581602374 0.00499302258188191 -0.00170904412483879 -0.00324073364529828 0.999993288384287 -0.00866848982863555 4.80573435820714e-05 3.1948856985371e-05 -8.47473982123824e-06 1.44176398665897e-05 -4.92872997909257e-06 2.56385413217931e-05 3.1948856985371e-05 4.8057577625777e-05 -8.90242892128919e-06 1.76457238217198e-05 -9.24209477174148e-07 3.58076418851597e-05 -8.47473982123824e-06 -8.90242892128919e-06 1.34389845651257e-05 1.45299825725601e-06 2.70513554957538e-06 -5.5728969060895e-06 1.44176398665897e-05 1.76457238217198e-05 1.45299825725601e-06 4.35046481335756e-05 -1.4785752401187e-05 1.46713656560648e-05 -4.92872997909257e-06 -9.24209477174148e-07 2.70513554957538e-06 -1.4785752401187e-05 3.9703312185229e-05 -1.41862830644947e-06 2.56385413217931e-05 3.58076418851597e-05 -5.5728969060895e-06 1.46713656560648e-05 -1.41862830644947e-06 7.14921815574755e-05 1839 1838 0 18 11 1825 1857 0 45 4 0 0 0 0 0 17 49 0 545 0 56 64 0 0 2257 +373 427 0.999997667289566 0.000397025561070731 0.00212315475897639 -0.00340006376531659 -0.000401837971429217 0.999997350327107 0.00226668590896485 0.00904642825137787 -0.002122249201066 -0.00226753378564435 0.9999951771628 -0.00654622864901715 3.20218097758227e-05 9.68802246486707e-06 -8.13426623265411e-06 5.73112356319701e-06 3.31684357692797e-06 1.07307455557564e-05 9.68802246486707e-06 2.23013905207049e-05 -9.22813999838219e-06 3.93395144587384e-06 6.73820363906219e-06 1.03428055471348e-05 -8.13426623265411e-06 -9.22813999838219e-06 1.32145260018128e-05 -1.18393040907813e-06 -9.13791155720015e-07 -3.69253374993101e-06 5.73112356319701e-06 3.93395144587384e-06 -1.18393040907813e-06 3.67518117202697e-05 -2.89161053267375e-06 6.25299327715963e-06 3.31684357692797e-06 6.73820363906219e-06 -9.13791155720015e-07 -2.89161053267375e-06 4.74090155546938e-05 1.09945236434522e-05 1.07307455557564e-05 1.03428055471348e-05 -3.69253374993101e-06 6.25299327715963e-06 1.09945236434522e-05 4.40640922892537e-05 2222 2224 0 14 17 2220 2271 0 48 14 0 0 0 0 0 15 44 0 660 0 19 20 0 0 2445 +372 408 0.999999188747623 0.000465515474509064 0.00118566413442652 -0.00708356936472675 -0.000467047345449026 0.999999056242842 0.00129204496937465 0.0104745728796824 -0.0011850615485205 -0.00129259768248668 0.999998462408997 -0.00597000913224969 2.81877877126508e-05 2.1462486777536e-05 -2.01670872608775e-06 2.62600183011312e-06 2.76584031500459e-06 1.93783529390155e-05 2.1462486777536e-05 3.08859197486369e-05 -2.54168488446346e-06 7.31528627296491e-06 -9.83593454796919e-07 2.39156220587296e-05 -2.01670872608775e-06 -2.54168488446346e-06 1.01325932608708e-05 4.81847410605755e-06 1.02053083798229e-06 -3.24917750366761e-07 2.62600183011312e-06 7.31528627296491e-06 4.81847410605755e-06 3.68901471447608e-05 -1.95773199775522e-05 7.38777301360124e-06 2.76584031500459e-06 -9.83593454796919e-07 1.02053083798229e-06 -1.95773199775522e-05 4.08099213550244e-05 1.8205314753584e-06 1.93783529390155e-05 2.39156220587296e-05 -3.24917750366761e-07 7.38777301360124e-06 1.8205314753584e-06 5.86808149703428e-05 2881 2884 0 19 15 2880 2919 0 43 14 0 0 0 0 0 17 48 0 499 0 16 21 0 0 2285 +372 417 0.999999011973813 6.64275500640454e-05 0.00140415055382252 -0.00532196057227909 -7.24363314173566e-05 0.999990839494168 0.00427968231605894 0.00959419406766695 -0.00140385340228187 -0.00427977979913561 0.9999898562888 -0.0102934021386665 5.64320634422784e-05 4.18704412277737e-05 -1.09192657113593e-05 1.9816032973748e-05 5.8933235124621e-06 4.20079765658842e-05 4.18704412277737e-05 4.87200954828957e-05 -1.06203601207656e-05 1.64092211535824e-05 7.8863611719672e-06 3.81649409415749e-05 -1.09192657113593e-05 -1.06203601207656e-05 1.30960492354133e-05 -1.91653392081076e-06 -1.81518430882833e-06 -6.34334484242197e-06 1.9816032973748e-05 1.64092211535824e-05 -1.91653392081076e-06 4.09850306204702e-05 -9.20447723264037e-06 1.68592994540552e-05 5.8933235124621e-06 7.8863611719672e-06 -1.81518430882833e-06 -9.20447723264037e-06 4.69064676638393e-05 5.63090212158579e-06 4.20079765658842e-05 3.81649409415749e-05 -6.34334484242197e-06 1.68592994540552e-05 5.63090212158579e-06 8.59413358370688e-05 2856 2856 0 15 13 2857 2894 0 40 12 0 0 0 0 0 23 57 0 618 0 15 18 0 0 2320 +372 410 0.999994931495669 -0.000148090722830091 0.00318041697120006 0.000372554859724176 0.000137122498600487 0.999994044104416 0.00344861611606921 0.00571492938895487 -0.00318090873702206 -0.00344816253002181 0.999988995936842 -0.00949092399723487 4.36175054207163e-05 3.12779554296483e-05 -1.56384038053374e-06 4.8525175049609e-07 4.02088022936135e-06 3.9160124395682e-05 3.12779554296483e-05 5.01026374441927e-05 -1.89530927117177e-06 7.59776907624814e-06 4.89931370896372e-06 3.55619904593044e-05 -1.56384038053374e-06 -1.89530927117177e-06 9.53538093956032e-06 3.49451094848461e-06 3.87585624621094e-06 1.42468486395768e-07 4.8525175049609e-07 7.59776907624814e-06 3.49451094848461e-06 3.51438049824862e-05 -8.30267750769707e-06 2.43689869796765e-06 4.02088022936135e-06 4.89931370896372e-06 3.87585624621094e-06 -8.30267750769707e-06 3.51146291071542e-05 4.81787506693539e-06 3.9160124395682e-05 3.55619904593044e-05 1.42468486395768e-07 2.43689869796765e-06 4.81787506693539e-06 8.57475753062358e-05 2013 2009 0 12 9 2022 2043 0 43 6 0 0 0 0 0 19 48 0 518 0 28 39 0 0 2364 +373 413 0.99999694363583 -7.84526469632579e-05 0.00247114632940066 0.00159796479377353 7.66577577340294e-05 0.999999733215083 0.000726425048938743 0.000193232023872193 -0.002471202660104 -0.000726233396182606 0.999996682865732 -0.00695509460768829 4.11966355779262e-05 2.19288956300621e-05 -9.10089612670141e-06 1.06508484092724e-05 1.50902436268213e-06 2.18245633838344e-05 2.19288956300621e-05 3.64829893678177e-05 -1.0966931311215e-05 5.07309906721587e-06 1.66277521026907e-05 1.85324892674949e-05 -9.10089612670141e-06 -1.0966931311215e-05 1.52923837166642e-05 -3.5535919155875e-07 -2.32011607766654e-06 -5.47857411862873e-06 1.06508484092724e-05 5.07309906721587e-06 -3.5535919155875e-07 5.38040337129499e-05 -2.91491764351027e-05 6.38975463937079e-06 1.50902436268213e-06 1.66277521026907e-05 -2.32011607766654e-06 -2.91491764351027e-05 6.85735795701727e-05 6.05797788381761e-06 2.18245633838344e-05 1.85324892674949e-05 -5.47857411862873e-06 6.38975463937079e-06 6.05797788381761e-06 5.82896474002012e-05 1253 1248 0 10 11 1257 1280 0 39 10 0 0 0 0 0 13 46 0 593 0 63 73 0 0 2252 +373 375 0.999998906543934 0.000383452227911852 0.00142824204016338 -0.00512802228927197 -0.000385250929427834 0.99999913284793 0.00125931930431299 0.00907365128465792 -0.00142775791286745 -0.00125986815887607 0.999998187118139 0.00150400781382945 3.32018782476684e-05 1.0927455461316e-05 -6.43672583721448e-06 5.11227971182802e-06 -5.53941096506858e-06 1.5921625737972e-05 1.0927455461316e-05 2.37577393626329e-05 -7.89271324507369e-06 3.72298085575657e-06 7.38920928286248e-06 1.81832905450756e-05 -6.43672583721448e-06 -7.89271324507369e-06 1.14508835699223e-05 5.34182209297306e-07 -3.1174915999587e-06 -3.4596662881871e-06 5.11227971182802e-06 3.72298085575657e-06 5.34182209297306e-07 3.10859887955652e-05 -6.44898328000881e-06 1.65594132770518e-06 -5.53941096506858e-06 7.38920928286248e-06 -3.1174915999587e-06 -6.44898328000881e-06 4.19805254265095e-05 2.62265397459242e-06 1.5921625737972e-05 1.81832905450756e-05 -3.4596662881871e-06 1.65594132770518e-06 2.62265397459242e-06 3.80250308852387e-05 2432 2406 0 16 58 2409 2451 0 38 34 0 0 0 0 0 14 43 0 656 0 58 32 0 0 2582 +373 429 0.999971169001682 -0.00727930694272343 0.00216167894065874 0.00354769758127965 0.00727195495446353 0.99996781392481 0.00338965862253601 0.0014519476885743 -0.00218628373024231 -0.00337384126341148 0.999991918646636 -0.00987043366885092 3.09554923499814e-05 1.92733711088505e-05 -2.86169277399836e-06 2.40567691694153e-06 3.15225253468743e-06 1.48860399014172e-05 1.92733711088505e-05 3.46389058081057e-05 -3.73723496384534e-06 7.04358553537981e-06 -2.64093671496056e-06 1.79153281997799e-05 -2.86169277399836e-06 -3.73723496384534e-06 1.06413665403591e-05 -4.72740463392379e-07 1.37579873484554e-06 -5.49591038120938e-07 2.40567691694153e-06 7.04358553537981e-06 -4.72740463392379e-07 3.76495611814575e-05 -7.68990567998764e-06 8.48269086742878e-06 3.15225253468743e-06 -2.64093671496056e-06 1.37579873484554e-06 -7.68990567998764e-06 3.51127300899246e-05 -7.15566568179975e-06 1.48860399014172e-05 1.79153281997799e-05 -5.49591038120938e-07 8.48269086742878e-06 -7.15566568179975e-06 6.09507127162068e-05 2619 2615 0 4 24 2624 2631 0 25 22 0 0 0 0 0 26 58 0 611 0 14 16 0 0 2399 +372 416 0.999997112313863 0.000153694660404562 0.00239827894253982 -0.00702872498979316 -0.000159571893775949 0.999996984529718 0.00245060569697489 0.0102653533217143 -0.00239789506559056 -0.00245098131830745 0.999994121377637 -0.00945974987068038 3.41094263137085e-05 1.76590307858675e-05 -9.19395668905796e-06 4.99872617494267e-06 7.78246933928775e-06 2.00895600411871e-05 1.76590307858675e-05 2.94729753745436e-05 -9.44558434593839e-06 9.93001156609331e-06 8.84905722493465e-06 1.72618045269251e-05 -9.19395668905796e-06 -9.44558434593839e-06 1.39020813718759e-05 1.95336563218311e-07 -3.52356059689186e-06 -4.90583929189924e-06 4.99872617494267e-06 9.93001156609331e-06 1.95336563218311e-07 3.57830814522434e-05 -7.331641952134e-06 1.11759666361525e-05 7.78246933928775e-06 8.84905722493465e-06 -3.52356059689186e-06 -7.331641952134e-06 4.42957993790793e-05 5.90974685222827e-06 2.00895600411871e-05 1.72618045269251e-05 -4.90583929189924e-06 1.11759666361525e-05 5.90974685222827e-06 6.0045280328335e-05 2754 2752 0 17 12 2753 2788 0 45 13 0 0 0 0 0 22 54 0 621 0 18 23 0 0 2261 +373 428 0.999998210617076 0.00118638982568339 0.00147351342952247 -0.00389863530957565 -0.00118737297971782 0.999999072946441 0.00066652206673443 0.0123471331883687 -0.00147272130849803 -0.000668270484102692 0.999998692252399 -0.00635848392049011 2.5732325133706e-05 1.23142525386344e-05 -7.23149487616839e-06 5.16396619785182e-06 4.90562465108341e-07 1.28555106205686e-05 1.23142525386344e-05 2.15147108363134e-05 -7.34557236737051e-06 4.92859197636191e-06 3.25671255009908e-06 1.26465001430336e-05 -7.23149487616839e-06 -7.34557236737051e-06 1.4452171629605e-05 -2.62826728798117e-06 -3.48281656921753e-06 8.77002736022793e-07 5.16396619785182e-06 4.92859197636191e-06 -2.62826728798117e-06 3.48807520974091e-05 4.29323149645615e-07 4.21694767751095e-06 4.90562465108341e-07 3.25671255009908e-06 -3.48281656921753e-06 4.29323149645615e-07 5.57765552720521e-05 -6.70304651608272e-06 1.28555106205686e-05 1.26465001430336e-05 8.77002736022793e-07 4.21694767751095e-06 -6.70304651608272e-06 5.81686806571109e-05 2836 2844 0 16 16 2829 2867 0 33 11 0 0 0 0 0 11 39 0 621 0 16 21 0 0 2297 +373 420 0.999986072518724 -0.000138210826326003 0.0052759517004098 0.00304858460050875 0.000129366271663013 0.999998585978396 0.00167669483697785 0.00375582200599816 -0.00527617597747903 -0.00167598895464095 0.999984676396633 -0.0117917172494005 4.1786045899802e-05 2.06426102062372e-05 -7.62733675433301e-06 5.42495137354566e-06 9.01218573950311e-06 2.20116587840121e-05 2.06426102062372e-05 3.49596039921719e-05 -8.52970285561177e-06 7.03246957791472e-06 1.1876166167571e-05 1.81746758456188e-05 -7.62733675433301e-06 -8.52970285561177e-06 1.31038702178794e-05 -1.26328162631882e-06 -2.21986719536274e-06 -1.37110874648033e-06 5.42495137354566e-06 7.03246957791472e-06 -1.26328162631882e-06 2.9626932930982e-05 -7.70754193908654e-07 4.27603959813335e-06 9.01218573950311e-06 1.1876166167571e-05 -2.21986719536274e-06 -7.70754193908654e-07 5.12886004016704e-05 -1.57081294926505e-06 2.20116587840121e-05 1.81746758456188e-05 -1.37110874648033e-06 4.27603959813335e-06 -1.57081294926505e-06 7.03145390165472e-05 1790 1792 0 18 11 1790 1819 0 46 9 0 0 0 0 0 15 45 0 620 0 12 17 0 0 2358 +373 421 0.9999943275801 0.00013098020685979 0.00336565770819216 0.00156782522869931 -0.00013606544002278 0.999998849584504 0.00151073355200798 0.00553875997697167 -0.00336545596009422 -0.00151118293218994 0.999993194993009 -0.0130650762223224 2.62660094625198e-05 1.39345610848189e-05 -7.6337217246927e-06 6.31842985434049e-06 2.53175865184295e-06 9.3767020395692e-06 1.39345610848189e-05 2.95600356881358e-05 -6.23032153290596e-06 3.9822624206181e-06 6.7278905659305e-06 1.33200749095348e-05 -7.6337217246927e-06 -6.23032153290596e-06 1.35125624620086e-05 -9.14470196535284e-07 -9.76260194234926e-08 -3.15027056483326e-06 6.31842985434049e-06 3.9822624206181e-06 -9.14470196535284e-07 3.67102178055974e-05 -6.565293065863e-06 2.69572316311887e-06 2.53175865184295e-06 6.7278905659305e-06 -9.76260194234926e-08 -6.565293065863e-06 4.55613033662057e-05 2.36717795325677e-06 9.3767020395692e-06 1.33200749095348e-05 -3.15027056483326e-06 2.69572316311887e-06 2.36717795325677e-06 4.58682438297375e-05 2363 2362 0 14 14 2358 2382 0 33 8 0 0 0 0 0 18 48 0 619 0 14 16 0 0 2318 +373 426 0.999982088714452 0.000418621019363422 0.00597051142893864 -0.000157605497617471 -0.000430740277050675 0.999997849394712 0.00202871110923995 0.01006280681078 -0.00596964932761264 -0.00203124651216301 0.999980118464618 -0.0100544305695915 3.09852404875154e-05 1.92290967828358e-05 -6.00781962290005e-06 8.24758497112273e-06 7.50980135935554e-06 1.86075220470139e-05 1.92290967828358e-05 2.93894042876073e-05 -6.82453221152223e-06 8.84684763720922e-06 7.6272753306402e-06 2.28590416754161e-05 -6.00781962290005e-06 -6.82453221152223e-06 1.23161817302486e-05 4.8017612548311e-07 -1.25951904706514e-06 -1.0619967827594e-06 8.24758497112273e-06 8.84684763720922e-06 4.8017612548311e-07 4.14614304573945e-05 -4.6811073050024e-06 1.1974693504372e-05 7.50980135935554e-06 7.6272753306402e-06 -1.25951904706514e-06 -4.6811073050024e-06 5.9293734841962e-05 4.76544496298274e-06 1.86075220470139e-05 2.28590416754161e-05 -1.0619967827594e-06 1.1974693504372e-05 4.76544496298274e-06 6.42700731113715e-05 2358 2353 0 14 17 2354 2384 0 47 16 0 0 0 0 0 20 49 0 641 0 15 19 0 0 2215 +373 376 0.999999953230605 0.000232684487914556 0.000198486060627248 -0.00466238588896408 -0.000233029081745143 0.999998462772042 0.00173785816478605 0.0117447226458488 -0.000198081382871785 -0.00173790433653192 0.999998470224971 0.00263484400135935 3.25294170107853e-05 1.35082356930723e-05 -6.67220216735575e-06 -3.98843447135578e-07 3.74674589652778e-06 1.20519509181302e-05 1.35082356930723e-05 2.82648721128621e-05 -5.91159956099424e-06 1.02299930230254e-05 4.78838357592342e-06 1.51501366846308e-05 -6.67220216735575e-06 -5.91159956099424e-06 1.05677189128843e-05 3.73953553307392e-07 -4.29733717350747e-07 -2.52262474950209e-06 -3.98843447135578e-07 1.02299930230254e-05 3.73953553307392e-07 3.69207031291494e-05 -3.03500754442537e-06 -2.29122336853503e-06 3.74674589652778e-06 4.78838357592342e-06 -4.29733717350747e-07 -3.03500754442537e-06 3.58564669692236e-05 9.69510439726748e-06 1.20519509181302e-05 1.51501366846308e-05 -2.52262474950209e-06 -2.29122336853503e-06 9.69510439726748e-06 2.87121458811266e-05 2626 2599 0 13 60 2600 2624 0 33 28 0 0 0 0 0 12 42 0 643 0 87 76 0 0 2730 +373 377 0.999995979116357 0.000185505199526921 0.0028297241807786 -0.00340039004496892 -0.000185275670118451 0.999999979525466 -8.1375627989955e-05 0.0038364546258178 -0.00282973921844342 8.08510217441794e-05 0.999995993011506 0.000195001430916972 3.63420390355326e-05 2.27618439056634e-05 -7.99238763688068e-06 9.33048140266521e-06 1.15791579102122e-09 2.07283269723414e-05 2.27618439056634e-05 3.47707600442385e-05 -1.0005122765001e-05 1.11077466662504e-05 5.20106263942053e-06 2.70316252973352e-05 -7.99238763688068e-06 -1.0005122765001e-05 1.19990163632216e-05 -1.39370618149688e-06 -3.00599772261217e-06 -4.68792639377935e-06 9.33048140266521e-06 1.11077466662504e-05 -1.39370618149688e-06 3.01911682561866e-05 -9.89581889535687e-06 6.79706173594817e-06 1.15791579102122e-09 5.20106263942053e-06 -3.00599772261217e-06 -9.89581889535687e-06 4.03986272865921e-05 4.31075269320579e-06 2.07283269723414e-05 2.70316252973352e-05 -4.68792639377935e-06 6.79706173594817e-06 4.31075269320579e-06 3.78774527551684e-05 2800 2777 0 11 55 2773 2796 0 38 25 0 0 0 0 0 13 43 0 620 0 56 32 0 0 2716 +373 412 0.999997550862604 -0.000110917685216358 0.00221042214525089 6.49467745111841e-05 0.000105226704638083 0.999996680271996 0.00257456255069379 0.00206639380419834 -0.00221070037176916 -0.00257432364979816 0.999994242814234 -0.0103519295563778 4.80562769760259e-05 2.45195239787483e-05 -5.94730095189868e-06 8.45463853824166e-06 -2.08161907795923e-06 1.85013571992286e-05 2.45195239787483e-05 3.5288346296975e-05 -6.68590576993829e-06 7.68966461332272e-06 5.86973234769423e-06 2.17238600469663e-05 -5.94730095189868e-06 -6.68590576993829e-06 1.041615622733e-05 2.01685156401317e-06 1.10503075976932e-06 -3.95581801478469e-06 8.45463853824166e-06 7.68966461332272e-06 2.01685156401317e-06 3.42949920455539e-05 -1.4081302922074e-05 1.21632997940369e-05 -2.08161907795923e-06 5.86973234769423e-06 1.10503075976932e-06 -1.4081302922074e-05 4.81358714557629e-05 -4.50998102561012e-06 1.85013571992286e-05 2.17238600469663e-05 -3.95581801478469e-06 1.21632997940369e-05 -4.50998102561012e-06 5.83769883835094e-05 2613 2610 0 18 9 2607 2632 0 39 6 0 0 0 0 0 14 44 0 570 0 12 14 0 0 2327 +373 415 0.999999809414918 0.000145306676025502 0.000600046745386892 -0.0022392248167831 -0.000145351551113718 0.999999986643201 7.47430555280559e-05 0.00341935521708233 -0.000600035876707233 -7.48302590083273e-05 0.999999817178673 -0.00582340978574659 2.13030755252081e-05 1.46411065191835e-05 -7.26801370033623e-06 5.1035238722393e-06 4.5575876991405e-06 1.35139080019316e-05 1.46411065191835e-05 2.08417441325454e-05 -7.71083477620333e-06 4.57000928190515e-06 4.20513467291182e-06 1.30120659492721e-05 -7.26801370033623e-06 -7.71083477620333e-06 1.26960166879451e-05 1.59160315081778e-07 -4.06783883801658e-07 -2.94445352956878e-06 5.1035238722393e-06 4.57000928190515e-06 1.59160315081778e-07 3.86170506495732e-05 -1.44804308184848e-05 4.1266347373471e-06 4.5575876991405e-06 4.20513467291182e-06 -4.06783883801658e-07 -1.44804308184848e-05 4.33756314771059e-05 5.76565473575811e-06 1.35139080019316e-05 1.30120659492721e-05 -2.94445352956878e-06 4.1266347373471e-06 5.76565473575811e-06 4.46647734713895e-05 2180 2181 0 17 14 2176 2214 0 38 12 0 0 0 0 0 11 43 0 578 0 16 20 0 0 2254 +373 425 0.999996803036374 0.000538733648685923 0.00247056331370828 -0.00101831305361442 -0.00054262995769828 0.999998609792876 0.00157669434086656 0.00326767284077501 -0.00246971046081845 -0.00157802990189852 0.999995705166711 -0.00537614166888393 5.67254146628135e-05 2.77043100250648e-05 -1.16421823712995e-05 7.79065801222593e-06 4.41319376279101e-06 1.77275650156246e-05 2.77043100250648e-05 4.55249363555651e-05 -1.01149218788755e-05 1.49353527710714e-05 4.72036275847263e-06 2.47156223510216e-05 -1.16421823712995e-05 -1.01149218788755e-05 1.93128950911219e-05 -5.08019352727173e-06 -8.04542396043228e-06 -2.91462825964564e-06 7.79065801222593e-06 1.49353527710714e-05 -5.08019352727173e-06 4.03828221293942e-05 -8.92068299563506e-06 7.89892263071595e-06 4.41319376279101e-06 4.72036275847263e-06 -8.04542396043228e-06 -8.92068299563506e-06 5.23665239871537e-05 -1.57102202169933e-06 1.77275650156246e-05 2.47156223510216e-05 -2.91462825964564e-06 7.89892263071595e-06 -1.57102202169933e-06 5.17566893835333e-05 2214 2210 0 19 16 2196 2222 0 39 6 0 0 0 0 0 14 44 0 616 0 77 89 0 0 2072 +373 409 0.999994431897617 -0.00014794200487224 0.00333380967131895 -0.000669230689499234 0.000143606581269183 0.999999143851966 0.00130064310396939 0.00321463067039999 -0.00333399923683278 -0.00130015710484592 0.999993596999797 -0.00238658194610867 3.21053331991631e-05 2.7535574358091e-05 -3.04828932128846e-06 2.68451537111733e-06 2.30338809830233e-07 2.33167584454395e-05 2.7535574358091e-05 6.62615420671622e-05 -2.18186617191667e-06 1.52151614486605e-05 -4.07970083351814e-06 3.65733277144655e-05 -3.04828932128846e-06 -2.18186617191667e-06 1.11526102267846e-05 2.4014718485352e-06 2.85103707225873e-06 -1.42348116723269e-06 2.68451537111733e-06 1.52151614486605e-05 2.4014718485352e-06 4.0204650064144e-05 -2.08128612832058e-05 6.55760179041731e-06 2.30338809830233e-07 -4.07970083351814e-06 2.85103707225873e-06 -2.08128612832058e-05 4.33088555686323e-05 -7.07772607637785e-07 2.33167584454395e-05 3.65733277144655e-05 -1.42348116723269e-06 6.55760179041731e-06 -7.07772607637785e-07 6.51886219522506e-05 1906 1902 0 14 10 1895 1920 0 39 2 0 0 0 0 0 15 45 0 491 0 71 83 0 0 2264 +373 408 0.999998242285564 0.000215560314546383 0.00186251430399528 -0.00445017075177259 -0.000218049345678726 0.999999083401235 0.00133628259436154 0.00964625790630113 -0.00186222454732061 -0.00133668636558364 0.999997372691196 -0.00138596101641946 3.00576343233666e-05 2.17659081869173e-05 -1.74684086654917e-06 2.05803609147068e-06 -2.34060604050718e-06 1.74887227512072e-05 2.17659081869173e-05 3.47862741409018e-05 -2.54599511922982e-06 8.94403426626133e-06 -2.68057044464732e-06 2.05247548619241e-05 -1.74684086654917e-06 -2.54599511922982e-06 1.01858161207725e-05 3.10466868360392e-06 2.88260266621297e-06 -8.11518698030409e-07 2.05803609147068e-06 8.94403426626133e-06 3.10466868360392e-06 4.31789994766208e-05 -2.25830913622305e-05 5.23004465528816e-06 -2.34060604050718e-06 -2.68057044464732e-06 2.88260266621297e-06 -2.25830913622305e-05 4.29175709778562e-05 3.92369326239757e-07 1.74887227512072e-05 2.05247548619241e-05 -8.11518698030409e-07 5.23004465528816e-06 3.92369326239757e-07 4.7472713220086e-05 1626 1630 0 16 15 1626 1664 0 41 10 0 0 0 0 0 18 47 0 487 0 47 54 0 0 2300 +373 419 0.999999855836582 0.000178092430644409 -0.000506566778782038 -0.00340813373857607 -0.000177895787692817 0.999999908824517 0.000388206191622476 0.00497368795142708 0.000506635869179825 -0.000388116019561215 0.999999796343005 -0.00772726319221892 2.4355283276105e-05 1.27145520281847e-05 -8.4446772020758e-06 7.72943160470717e-06 5.75062030243506e-06 1.29968397269229e-05 1.27145520281847e-05 1.9846190054595e-05 -8.92856425223522e-06 3.89236513602291e-06 5.21057874711448e-06 1.22378397604602e-05 -8.4446772020758e-06 -8.92856425223522e-06 1.48639541465145e-05 -1.30408628685886e-06 -2.77906828712794e-06 -4.2480010826981e-06 7.72943160470717e-06 3.89236513602291e-06 -1.30408628685886e-06 3.61438281608683e-05 -5.16004545017408e-06 5.6209168895799e-06 5.75062030243506e-06 5.21057874711448e-06 -2.77906828712794e-06 -5.16004545017408e-06 4.45632471930506e-05 5.32832624755289e-06 1.29968397269229e-05 1.22378397604602e-05 -4.2480010826981e-06 5.6209168895799e-06 5.32832624755289e-06 4.43898898437098e-05 3069 3071 0 15 14 3064 3102 0 33 10 0 0 0 0 0 14 46 0 597 0 15 18 0 0 2252 +373 410 0.999993455317176 -1.36390788935631e-05 0.0036178912076899 -0.00240197001021872 1.3801049690134e-05 0.999999998903733 -4.47444322499263e-05 0.007125832735956 -0.00361789059345088 4.47940701081399e-05 0.99999345440915 -0.000385414752185155 4.31378926501121e-05 2.99840386962519e-05 -2.95266647041879e-06 2.09972894934301e-06 3.92416673276928e-06 2.47226379098494e-05 2.99840386962519e-05 4.66943515481145e-05 -2.49549711384747e-06 1.10929293929794e-05 3.53677784754098e-07 2.65227706557841e-05 -2.95266647041879e-06 -2.49549711384747e-06 1.09752650712999e-05 3.11810008293732e-06 7.92061648477029e-07 -1.93446644723897e-06 2.09972894934301e-06 1.10929293929794e-05 3.11810008293732e-06 5.5164918634173e-05 -3.28257896192614e-05 -1.96213743008453e-06 3.92416673276928e-06 3.53677784754098e-07 7.92061648477029e-07 -3.28257896192614e-05 5.78402961280762e-05 5.83567698046727e-06 2.47226379098494e-05 2.65227706557841e-05 -1.93446644723897e-06 -1.96213743008453e-06 5.83567698046727e-06 6.67997923503316e-05 1986 1983 0 13 9 1985 2018 0 47 7 0 0 0 0 0 22 50 0 506 0 57 61 0 0 2285 +373 418 0.999982457322636 -0.000462071899953933 0.00590521265845651 -0.000343013599679036 0.000438184588187804 0.999991719807703 0.00404577684744096 0.0040192969754799 -0.00590703320195483 -0.00404311830050614 0.999974379748381 -0.0108709753127606 2.7394087588471e-05 1.75128375960912e-05 -7.72142632657769e-06 1.06192394689097e-05 1.14155167044576e-06 1.55390909897966e-05 1.75128375960912e-05 2.4841014823306e-05 -9.1375520262331e-06 1.15158115918651e-05 1.10732250004179e-06 1.23823130605855e-05 -7.72142632657769e-06 -9.1375520262331e-06 1.31278426641992e-05 -1.96882969421421e-06 -7.88198652810842e-08 -3.42449010273964e-06 1.06192394689097e-05 1.15158115918651e-05 -1.96882969421421e-06 4.43442376457455e-05 -1.49535326024715e-05 1.37693295342746e-05 1.14155167044576e-06 1.10732250004179e-06 -7.88198652810842e-08 -1.49535326024715e-05 4.92794963799569e-05 -5.9792652395547e-06 1.55390909897966e-05 1.23823130605855e-05 -3.42449010273964e-06 1.37693295342746e-05 -5.9792652395547e-06 4.29388438467512e-05 2431 2433 0 18 13 2428 2459 0 45 11 0 0 0 0 0 20 52 0 609 0 14 18 0 0 2212 +373 422 0.99999958465787 0.000105626941864858 -0.000905277325609032 -0.00727715262272654 -0.000104995037221244 0.99999975085641 0.000698042376986818 0.00794805384963329 0.000905350832146562 -0.000697947037433913 0.999999346604688 -0.0070910216126745 4.91922515875436e-05 2.66827797056081e-05 -8.7598832065559e-06 9.340019235286e-06 -2.91722544983365e-06 3.10266149332644e-05 2.66827797056081e-05 3.76775515140781e-05 -8.43180666019934e-06 9.06631145843604e-06 5.04896346453306e-07 2.0937551839005e-05 -8.7598832065559e-06 -8.43180666019934e-06 1.43928265621934e-05 -1.57735211574927e-06 -2.31604102241811e-06 -2.61622835623782e-06 9.340019235286e-06 9.06631145843604e-06 -1.57735211574927e-06 4.00241935092334e-05 -1.64530715143361e-05 8.90239779536299e-06 -2.91722544983365e-06 5.04896346453306e-07 -2.31604102241811e-06 -1.64530715143361e-05 5.52765249385431e-05 -7.17750790561253e-06 3.10266149332644e-05 2.0937551839005e-05 -2.61622835623782e-06 8.90239779536299e-06 -7.17750790561253e-06 6.49220586234906e-05 2694 2700 0 18 14 2702 2725 0 31 14 0 0 0 0 0 14 45 0 590 0 50 57 0 0 2326 +373 411 0.999985349800488 -5.23027543910652e-05 0.00541271178041431 0.00081048295947655 3.43717308988728e-05 0.999994512067157 0.00331280155647444 0.00531370184152335 -0.00541285534446172 -0.00331256697899794 0.99997986374578 -0.00791471454953086 4.13008368757e-05 1.78956559636949e-05 -3.88569799310819e-06 1.40467269850745e-06 7.0382234979368e-08 1.73215650581454e-05 1.78956559636949e-05 4.39230914082008e-05 -3.33645199514813e-06 1.31907893467424e-05 5.94437546413364e-06 2.13603431786496e-05 -3.88569799310819e-06 -3.33645199514813e-06 1.2355399090268e-05 3.24455641125642e-06 4.43679364228596e-06 -4.664165363323e-07 1.40467269850745e-06 1.31907893467424e-05 3.24455641125642e-06 3.66066277773458e-05 -4.78299450798538e-06 9.93568547202976e-06 7.0382234979368e-08 5.94437546413364e-06 4.43679364228596e-06 -4.78299450798538e-06 3.78246383209302e-05 -9.52650020225716e-07 1.73215650581454e-05 2.13603431786496e-05 -4.664165363323e-07 9.93568547202976e-06 -9.52650020225716e-07 5.49588843009485e-05 1914 1914 0 16 11 1913 1946 0 47 9 0 0 0 0 0 23 53 0 534 0 11 15 0 0 2266 +374 428 0.99999983940081 0.000388449565993475 -0.000412680612591457 -0.00460517290909541 -0.000388467878347728 0.999999923565331 -4.42949270789039e-05 0.00530925155761778 0.000412663374703152 4.44552331271831e-05 0.999999913866332 -0.00335770105464597 3.37998623352328e-05 2.38568678910079e-05 -8.23701811931034e-06 6.26830915497096e-06 6.3898203767061e-06 2.36740867486572e-05 2.38568678910079e-05 2.92970940493012e-05 -8.50856210845076e-06 6.38316156535488e-06 4.36612379593291e-06 2.39083136642383e-05 -8.23701811931034e-06 -8.50856210845076e-06 1.32180369653044e-05 -3.11020661961416e-06 -2.15393833079138e-06 -2.00172801085797e-06 6.26830915497096e-06 6.38316156535488e-06 -3.11020661961416e-06 4.58561527442781e-05 -8.45581462025742e-06 3.9008158001677e-06 6.3898203767061e-06 4.36612379593291e-06 -2.15393833079138e-06 -8.45581462025742e-06 5.33184825093988e-05 3.88229919887651e-06 2.36740867486572e-05 2.39083136642383e-05 -2.00172801085797e-06 3.9008158001677e-06 3.88229919887651e-06 6.24353986487072e-05 2751 2753 0 20 16 2744 2777 0 49 14 0 0 0 0 0 22 54 0 650 0 40 46 0 0 2380 +373 407 0.999988669677478 0.000261381253069818 0.00475312492030447 0.00278024402396661 -0.000256945162018819 0.999999530917383 -0.000933886608826745 -0.000133110489106681 -0.00475336679114823 0.000932654735137525 0.999988267760824 -0.00157014622519132 5.25033987692301e-05 3.55538791082032e-05 -1.39428378067572e-06 -3.19744794908826e-06 1.79983618859328e-06 3.1079949459227e-05 3.55538791082032e-05 4.60086237974891e-05 -1.09903778729181e-06 1.14134290430386e-06 1.97000194491621e-06 2.83297665673115e-05 -1.39428378067572e-06 -1.09903778729181e-06 1.09734968816114e-05 2.37676873870825e-06 3.60636980270338e-06 1.55010890507138e-06 -3.19744794908826e-06 1.14134290430386e-06 2.37676873870825e-06 3.37580252471505e-05 -1.24934037653017e-05 5.9485757286053e-06 1.79983618859328e-06 1.97000194491621e-06 3.60636980270338e-06 -1.24934037653017e-05 3.60856901285079e-05 -3.47220445288101e-06 3.1079949459227e-05 2.83297665673115e-05 1.55010890507138e-06 5.9485757286053e-06 -3.47220445288101e-06 6.38580867881104e-05 2221 2221 0 21 17 2210 2240 0 46 9 0 0 0 0 0 16 43 0 480 0 74 87 0 0 2351 +373 414 0.999997412421861 0.000287271282491867 -0.00225668446886193 -0.0167921135287871 -0.000285888552873632 0.999999771234108 0.000613024850581183 0.016255995554037 0.00225686005704451 -0.000612378104074386 0.999997265784132 -0.00295136509953641 4.32569438339142e-05 2.80243601175132e-05 -6.21388670187471e-06 9.75109519172831e-06 -3.30197723260031e-06 2.65022342485229e-05 2.80243601175132e-05 4.03548956871959e-05 -6.55792436775019e-06 5.33328002177922e-06 7.9261101929149e-07 2.49466060041755e-05 -6.21388670187471e-06 -6.55792436775019e-06 1.24925700546061e-05 -6.72936137113091e-07 -3.17712293315306e-07 -1.04861491935693e-06 9.75109519172831e-06 5.33328002177922e-06 -6.72936137113091e-07 6.21142096640918e-05 -3.86044001300785e-05 2.11146013571642e-06 -3.30197723260031e-06 7.9261101929149e-07 -3.17712293315306e-07 -3.86044001300785e-05 7.74350446649195e-05 4.12943749958925e-07 2.65022342485229e-05 2.49466060041755e-05 -1.04861491935693e-06 2.11146013571642e-06 4.12943749958925e-07 5.34312170980146e-05 2434 2437 0 16 11 2435 2470 0 38 11 0 0 0 0 0 23 50 0 593 0 48 52 0 0 2377 +374 426 0.999999864758761 0.0002163322006873 0.000472951200928257 -0.00315964905060462 -0.000216322285774023 0.999999976381519 -2.10149789509186e-05 0.00327853924338011 -0.000472955735974512 2.09126662239824e-05 0.99999988793776 -0.00683461058475082 2.18296745875889e-05 1.24229576153694e-05 -7.32689651938178e-06 5.01036847169031e-06 5.00340833411934e-06 1.13215544670461e-05 1.24229576153694e-05 1.75707985948938e-05 -8.06166474135962e-06 5.40827348777489e-06 3.57091298226916e-06 1.07588199620681e-05 -7.32689651938178e-06 -8.06166474135962e-06 1.30203199432771e-05 -2.31957965977507e-06 -3.13009478782343e-06 -3.45429362233893e-06 5.01036847169031e-06 5.40827348777489e-06 -2.31957965977507e-06 3.48958934265319e-05 -3.37172516386881e-07 5.70158406372714e-06 5.00340833411934e-06 3.57091298226916e-06 -3.13009478782343e-06 -3.37172516386881e-07 4.2794267607469e-05 3.38746506254727e-06 1.13215544670461e-05 1.07588199620681e-05 -3.45429362233893e-06 5.70158406372714e-06 3.38746506254727e-06 5.1134997398289e-05 2877 2878 0 17 17 2870 2902 0 45 11 0 0 0 0 0 17 47 0 661 0 16 19 0 0 2127 +374 376 0.999999975588199 0.000220285320272182 1.72620980888943e-05 -0.00379211045569302 -0.000220270534951699 0.999999612881472 -0.000851890719165748 0.00407197854966068 -1.74497504263246e-05 0.00085188689603798 0.999999636992045 -0.00307307509346437 4.56140675428811e-05 3.22393175961298e-05 -1.06652106027764e-05 3.72663879854017e-06 1.02943066266469e-05 2.25719517140586e-05 3.22393175961298e-05 3.43406258547181e-05 -1.110039681739e-05 7.03243270681514e-06 7.52546480211343e-06 2.58219513652217e-05 -1.06652106027764e-05 -1.110039681739e-05 1.39662666755347e-05 -1.50841761646587e-06 -4.84877937824099e-06 -4.17705772952071e-06 3.72663879854017e-06 7.03243270681514e-06 -1.50841761646587e-06 4.13648883820608e-05 -2.22582635314692e-05 2.65283251941769e-06 1.02943066266469e-05 7.52546480211343e-06 -4.84877937824099e-06 -2.22582635314692e-05 5.21843042179688e-05 9.12504461402753e-06 2.25719517140586e-05 2.58219513652217e-05 -4.17705772952071e-06 2.65283251941769e-06 9.12504461402753e-06 4.32117582381525e-05 2344 2316 0 16 55 2275 2303 0 48 2 0 0 0 0 0 22 53 0 647 0 97 80 0 0 2634 +373 424 0.999996289155448 0.000138870076716671 0.00272073343705078 -0.00288844733706914 -0.00014430026382852 0.999997998058691 0.00199575951535693 0.00789207508229299 -0.00272045083902512 -0.00199614471195638 0.999994307260557 -0.00770957942265931 2.58363150680675e-05 1.66197178570638e-05 -1.03600489130141e-05 5.17821877876381e-06 6.70246673975931e-06 9.94152666382285e-06 1.66197178570638e-05 3.12140676757086e-05 -1.36778809994225e-05 8.64144990719111e-06 9.53005824300776e-06 1.17511713386167e-05 -1.03600489130141e-05 -1.36778809994225e-05 1.84050541523708e-05 -1.7439367118179e-06 -4.894148315433e-06 -5.54400753858467e-06 5.17821877876381e-06 8.64144990719111e-06 -1.7439367118179e-06 4.46275439122252e-05 -1.60407693528515e-05 4.61224542152086e-06 6.70246673975931e-06 9.53005824300776e-06 -4.894148315433e-06 -1.60407693528515e-05 6.94536490622767e-05 8.39678847624901e-06 9.94152666382285e-06 1.17511713386167e-05 -5.54400753858467e-06 4.61224542152086e-06 8.39678847624901e-06 4.30587734741925e-05 1937 1935 0 13 15 1923 1958 0 46 6 0 0 0 0 0 16 46 0 621 0 72 83 0 0 2240 +374 420 0.999999523832773 0.00050937680112563 0.000832387831722143 -0.00295800092030251 -0.000510063508398145 0.99999952962082 0.000824980821511488 0.00694497821815647 -0.000831967214092385 -0.000825404999340453 0.999999313268335 -0.0100307505399597 3.15295071771346e-05 1.65177423051558e-05 -8.66826108079999e-06 6.69849486244296e-06 7.14306410658678e-06 2.01212430865199e-05 1.65177423051558e-05 2.38460614141064e-05 -8.65135370765366e-06 5.27292851868017e-06 6.41721260097819e-06 1.23852134033625e-05 -8.66826108079999e-06 -8.65135370765366e-06 1.29525168834277e-05 4.00755313541976e-07 -2.86578945219336e-06 -4.44191119250215e-06 6.69849486244296e-06 5.27292851868017e-06 4.00755313541976e-07 3.75836073896454e-05 -6.89234623993961e-06 7.37633817933685e-06 7.14306410658678e-06 6.41721260097819e-06 -2.86578945219336e-06 -6.89234623993961e-06 4.76007462891617e-05 3.09310648511809e-07 2.01212430865199e-05 1.23852134033625e-05 -4.44191119250215e-06 7.37633817933685e-06 3.09310648511809e-07 5.79888401892353e-05 2630 2629 0 16 11 2623 2661 0 47 9 0 0 0 0 0 13 44 0 628 0 13 15 0 0 2275 +374 377 0.999999899717493 0.000317649745220087 0.000315695492841434 -0.0053532707767448 -0.000317550031916355 0.999999899699505 -0.000315852745065359 0.00659925786708275 -0.000315795791721017 0.000315752464277026 0.999999900286695 0.00319915825096741 2.64780743416536e-05 1.42862740646067e-05 -7.92036890888189e-06 5.6249418289999e-06 2.3424823410305e-06 1.62494391184391e-05 1.42862740646067e-05 2.02531915212322e-05 -8.62928453303452e-06 6.72576153459792e-06 5.10980091799483e-06 1.35175149475372e-05 -7.92036890888189e-06 -8.62928453303452e-06 1.19382273888705e-05 -2.38875623809667e-06 -3.0095857336733e-06 -4.12596368344669e-06 5.6249418289999e-06 6.72576153459792e-06 -2.38875623809667e-06 2.61638100022192e-05 -3.48219481275038e-06 1.91439322476366e-06 2.3424823410305e-06 5.10980091799483e-06 -3.0095857336733e-06 -3.48219481275038e-06 4.0818982793763e-05 6.18586049329443e-06 1.62494391184391e-05 1.35175149475372e-05 -4.12596368344669e-06 1.91439322476366e-06 6.18586049329443e-06 3.1653462769129e-05 2816 2797 0 10 55 2796 2832 0 42 29 0 0 0 0 0 23 54 0 651 0 54 30 0 0 2718 +373 423 0.999994688134951 0.00052303396535309 0.00321716293541265 0.00198791221296908 -0.000525657265952129 0.999999530042044 0.000814616553518431 0.000713733091740335 -0.00321673535135511 -0.000816303351457984 0.999994493116096 -0.00986924007899046 3.014038533485e-05 2.03447619534222e-05 -7.77647136220005e-06 6.97336817384355e-06 6.40995103864139e-06 1.74069024595016e-05 2.03447619534222e-05 2.73274442291562e-05 -8.07709814321836e-06 8.71540872947564e-06 3.39343551964501e-06 1.61168101833985e-05 -7.77647136220005e-06 -8.07709814321836e-06 1.37792398288202e-05 -6.01156778692238e-07 -1.54085379417522e-06 -2.58034472101061e-06 6.97336817384355e-06 8.71540872947564e-06 -6.01156778692238e-07 3.99028195722227e-05 -1.13229111153879e-05 1.22505748757008e-05 6.40995103864139e-06 3.39343551964501e-06 -1.54085379417522e-06 -1.13229111153879e-05 5.20542727162478e-05 -3.17641550422346e-06 1.74069024595016e-05 1.61168101833985e-05 -2.58034472101061e-06 1.22505748757008e-05 -3.17641550422346e-06 4.79720208174861e-05 2612 2607 0 19 12 2609 2629 0 40 12 0 0 0 0 0 13 45 0 616 0 12 18 0 0 2221 +373 416 0.999999212274354 0.000651257292628118 -0.00107299329469572 -0.0116223375820716 -0.000648550078913447 0.99999661078736 0.00252146715000672 0.0140355139533603 0.00107463178196285 -0.00252076927389643 0.999996245437352 -0.00307867522944663 4.37273547431017e-05 2.21235024081956e-05 -1.37487793538098e-05 4.34813314948289e-06 1.56607329157345e-05 2.65035637238946e-05 2.21235024081956e-05 4.67529384719686e-05 -1.40578432483634e-05 1.80321668903771e-05 1.10224418465026e-05 1.77860098303272e-05 -1.37487793538098e-05 -1.40578432483634e-05 1.92926399871988e-05 -2.3053241318078e-06 -7.96158311837892e-06 -7.66389788082765e-06 4.34813314948289e-06 1.80321668903771e-05 -2.3053241318078e-06 7.10093159377754e-05 -3.94152511999605e-05 -3.14770903399637e-06 1.56607329157345e-05 1.10224418465026e-05 -7.96158311837892e-06 -3.94152511999605e-05 8.19038237315329e-05 1.79106886617359e-05 2.65035637238946e-05 1.77860098303272e-05 -7.66389788082765e-06 -3.14770903399637e-06 1.79106886617359e-05 5.10984800369501e-05 2376 2373 0 13 12 2367 2394 0 39 6 0 0 0 0 0 13 44 0 603 0 51 63 0 0 2250 +373 417 0.999999305134152 0.000372649186729614 0.00111842022369855 -0.00788859873267939 -0.000374275457206967 0.999998872578475 0.00145422132430329 0.0134780708122347 -0.00111787704837369 -0.00145463891105514 0.999998317186856 -0.00503994009232465 5.10124493704301e-05 3.60578643779308e-05 -8.54427030940698e-06 1.44760059337442e-05 1.46353617617869e-06 3.50355904078429e-05 3.60578643779308e-05 5.13437513120817e-05 -1.03619971930014e-05 1.13622612760633e-05 8.8367535948862e-06 3.76720577154942e-05 -8.54427030940698e-06 -1.03619971930014e-05 1.52289720228693e-05 -2.46380995924124e-06 1.53333322476075e-06 -3.41265567224282e-06 1.44760059337442e-05 1.13622612760633e-05 -2.46380995924124e-06 4.81516225646191e-05 -1.62855218968119e-05 1.14192918264036e-05 1.46353617617869e-06 8.8367535948862e-06 1.53333322476075e-06 -1.62855218968119e-05 4.98336807085279e-05 5.04178502641856e-06 3.50355904078429e-05 3.76720577154942e-05 -3.41265567224282e-06 1.14192918264036e-05 5.04178502641856e-06 6.93435546295854e-05 2362 2361 0 14 13 2361 2386 0 30 11 0 0 0 0 0 19 53 0 603 0 47 53 0 0 2319 +374 427 0.999999941122525 0.000107032856245993 0.000326035143785536 -0.00292151329399703 -0.000107514554339165 0.999998902298137 0.001477783184839 0.00378875324762137 -0.000325876614540965 -0.00147781815135404 0.999998854928316 -0.00691422053705167 2.86380633242126e-05 1.69267609476736e-05 -9.94043701027301e-06 6.72726033378263e-06 7.42647559253526e-06 1.2667343158717e-05 1.69267609476736e-05 2.64394669469733e-05 -1.00806839178295e-05 7.69085507588407e-06 7.12001569320435e-06 1.46958794103115e-05 -9.94043701027301e-06 -1.00806839178295e-05 1.46935880390964e-05 -2.84735795442284e-06 -4.52180690931081e-06 -4.7795889169308e-06 6.72726033378263e-06 7.69085507588407e-06 -2.84735795442284e-06 4.96760087627063e-05 -1.46635840076417e-05 8.03016375951023e-06 7.42647559253526e-06 7.12001569320435e-06 -4.52180690931081e-06 -1.46635840076417e-05 5.73246657163935e-05 4.17449358104022e-06 1.2667343158717e-05 1.46958794103115e-05 -4.7795889169308e-06 8.03016375951023e-06 4.17449358104022e-06 4.91625928680054e-05 2529 2530 0 12 17 2527 2558 0 47 11 0 0 0 0 0 19 49 0 656 0 43 47 0 0 2358 +374 412 0.999994360544439 -8.75878383674101e-05 0.00335726193331357 -0.00585101456022186 7.67768912470034e-05 0.99999481231906 0.00322016152961979 0.00903144215725874 -0.0033575265638974 -0.0032198856095276 0.999989179617477 -0.00850156865955721 5.35079717341473e-05 3.51328518949847e-05 -7.73858460473195e-06 6.79567259518495e-06 8.5205115241034e-06 4.48400256206747e-05 3.51328518949847e-05 5.64489143264861e-05 -8.7845700358064e-06 6.95805091246236e-06 2.13931144904353e-05 3.74582129272843e-05 -7.73858460473195e-06 -8.7845700358064e-06 1.19312962266877e-05 -1.51394562044482e-06 -3.95356824276682e-07 -6.73167157359788e-06 6.79567259518495e-06 6.95805091246236e-06 -1.51394562044482e-06 3.62946036182325e-05 -1.4688933430689e-05 5.04423119276665e-06 8.5205115241034e-06 2.13931144904353e-05 -3.95356824276682e-07 -1.4688933430689e-05 5.15793049245508e-05 1.14221926308326e-05 4.48400256206747e-05 3.74582129272843e-05 -6.73167157359788e-06 5.04423119276665e-06 1.14221926308326e-05 9.22440407774419e-05 2613 2615 0 15 9 2612 2648 0 46 9 0 0 0 0 0 20 51 0 571 0 12 14 0 0 2230 +374 425 0.999987743040715 -0.000329749240625741 0.00494014511677048 -0.0105756335120577 0.000306305554033209 0.999988692895596 0.00474555137632697 0.0129695498071612 -0.00494165409999656 -0.00474398001640997 0.999976537078926 -0.0124391125546085 4.53620133484535e-05 1.50488242454672e-05 -5.99892393849028e-06 5.51069059553775e-06 -1.00634415559003e-06 8.04615573798791e-06 1.50488242454672e-05 3.42206267327435e-05 -7.88022926630064e-06 5.90778921032395e-06 7.76593803025191e-06 1.07024557971369e-05 -5.99892393849028e-06 -7.88022926630064e-06 1.33897603294382e-05 -2.88927005910454e-06 1.23484208743238e-06 -1.28426000397168e-06 5.51069059553775e-06 5.90778921032395e-06 -2.88927005910454e-06 5.4851350475393e-05 -2.20261259265531e-05 -1.7322766327716e-06 -1.00634415559003e-06 7.76593803025191e-06 1.23484208743238e-06 -2.20261259265531e-05 5.71898267684918e-05 4.21885809042841e-06 8.04615573798791e-06 1.07024557971369e-05 -1.28426000397168e-06 -1.7322766327716e-06 4.21885809042841e-06 6.68190456670559e-05 2293 2289 0 12 16 2288 2315 0 44 14 0 0 0 0 0 23 53 0 638 0 42 45 0 0 2047 +374 421 0.99999996858094 -0.000148965511638614 0.000201611994159345 -0.00183560354895592 0.000148903782752769 0.999999942047764 0.000306157040087521 0.00154496096505267 -0.000201657589315598 -0.000306127009679775 0.999999932810233 -0.00706736708431047 3.92539695709857e-05 2.27288495434634e-05 -1.02818332424915e-05 1.01980162019042e-05 6.39435561239924e-06 2.30482837532882e-05 2.27288495434634e-05 2.43104579304651e-05 -8.5941974746878e-06 4.67909230962429e-06 2.7210571223793e-06 1.95040857690814e-05 -1.02818332424915e-05 -8.5941974746878e-06 1.43116870346316e-05 -1.48698331330474e-06 -1.39784676177032e-06 -2.92249295551771e-06 1.01980162019042e-05 4.67909230962429e-06 -1.48698331330474e-06 3.95534137726504e-05 -9.54541505085062e-06 9.23781334894866e-06 6.39435561239924e-06 2.7210571223793e-06 -1.39784676177032e-06 -9.54541505085062e-06 4.78944549812055e-05 -3.36742454190178e-06 2.30482837532882e-05 1.95040857690814e-05 -2.92249295551771e-06 9.23781334894866e-06 -3.36742454190178e-06 6.050569340979e-05 2887 2888 0 15 14 2884 2922 0 49 11 0 0 0 0 0 13 46 0 628 0 15 19 0 0 2362 +374 413 0.999999969829961 -3.72237075930948e-05 -0.000242805422168002 -0.010005144527774 3.7931192039834e-05 0.999995752296339 0.00291443828277882 0.0101582389978642 0.000242695904604085 -0.0029144474047492 0.999995723538367 -0.0139554864204156 5.20215753163645e-05 4.07547477476794e-05 -8.45997112939258e-06 9.76138083808816e-06 1.47747234696069e-05 3.18110780961808e-05 4.07547477476794e-05 5.66770794842337e-05 -1.0248054182732e-05 1.86381974360051e-05 1.26325073926624e-05 3.54926042437542e-05 -8.45997112939258e-06 -1.0248054182732e-05 1.32968486722063e-05 -1.22633189194889e-06 -9.43135820848722e-07 -4.92829606495146e-06 9.76138083808816e-06 1.86381974360051e-05 -1.22633189194889e-06 6.09182312658205e-05 -2.76617546922522e-05 6.53775807683162e-06 1.47747234696069e-05 1.26325073926624e-05 -9.43135820848722e-07 -2.76617546922522e-05 7.21828632130236e-05 1.14733155668002e-05 3.18110780961808e-05 3.54926042437542e-05 -4.92829606495146e-06 6.53775807683162e-06 1.14733155668002e-05 8.01954705089775e-05 2354 2350 0 13 11 2345 2380 0 47 8 0 0 0 0 0 20 53 0 606 0 35 38 0 0 2229 +374 415 0.999997879937136 0.000216535779611117 -0.00204773862817738 -0.0101124880972988 -0.000212881644510158 0.999998385078182 0.00178452302690876 0.00746864197914082 0.00204812173432446 -0.00178408331764107 0.999996311115235 -0.00565384502492061 5.39406624563038e-05 3.57534406048994e-05 -9.55695415468696e-06 1.49212058497168e-05 1.23315638378232e-06 3.14251545477907e-05 3.57534406048994e-05 4.46451870911288e-05 -9.82615136038512e-06 1.50121689700652e-05 5.70255076324828e-06 3.13891979785554e-05 -9.55695415468696e-06 -9.82615136038512e-06 1.33868050912054e-05 -8.99855741970271e-07 -2.2503153510687e-06 -3.45029790975727e-06 1.49212058497168e-05 1.50121689700652e-05 -8.99855741970271e-07 5.01196528495601e-05 -2.43225469835053e-05 2.148145775192e-05 1.23315638378232e-06 5.70255076324828e-06 -2.2503153510687e-06 -2.43225469835053e-05 5.99598744703937e-05 -8.3886327384795e-06 3.14251545477907e-05 3.13891979785554e-05 -3.45029790975727e-06 2.148145775192e-05 -8.3886327384795e-06 6.6291869067306e-05 2528 2526 0 12 14 2520 2552 0 48 7 0 0 0 0 0 16 48 0 578 0 39 43 0 0 2292 +374 418 0.999999778274124 -6.37572397894073e-05 0.000662862517214831 -0.00231478495939727 6.33576963973069e-05 0.99999981633424 0.000602758067838822 0.0014572649701007 -0.000662900825660349 -0.000602715936749642 0.999999598647917 -0.00577677146045386 2.75433046376049e-05 1.93317226538507e-05 -1.01583504064609e-05 7.93339452786039e-06 1.22600713376089e-05 1.76829457254088e-05 1.93317226538507e-05 2.35684806593555e-05 -1.03453012138087e-05 5.95235759820695e-06 1.05769294440547e-05 1.61630532058635e-05 -1.01583504064609e-05 -1.03453012138087e-05 1.36734793184001e-05 -2.6941078115553e-06 -4.34392648544703e-06 -4.90129306292089e-06 7.93339452786039e-06 5.95235759820695e-06 -2.6941078115553e-06 3.07350812320558e-05 -3.2037360706017e-06 8.64349701575222e-06 1.22600713376089e-05 1.05769294440547e-05 -4.34392648544703e-06 -3.2037360706017e-06 4.20445483655333e-05 8.3739003384557e-06 1.76829457254088e-05 1.61630532058635e-05 -4.90129306292089e-06 8.64349701575222e-06 8.3739003384557e-06 5.24094305779157e-05 2956 2954 0 15 13 2949 2987 0 46 10 0 0 0 0 0 14 46 0 621 0 15 17 0 0 2249 +374 378 0.999999992233243 -7.19853709336903e-05 0.000101742910634081 -0.00761008821108443 7.19863268713234e-05 0.99999999736488 -9.39198826714346e-06 0.00997705386722871 -0.000101742234280217 9.39931229261992e-06 0.999999994780085 0.0005110209526169 2.94296802835754e-05 1.66089435066433e-05 -7.71266786082441e-06 1.12520375163413e-06 6.94533649214462e-06 1.16553577254252e-05 1.66089435066433e-05 2.30544308903396e-05 -9.30420471781985e-06 5.15840313103251e-06 4.47360981751997e-06 8.94389399753536e-06 -7.71266786082441e-06 -9.30420471781985e-06 1.34530317783158e-05 -3.99088241075582e-09 5.9372832637292e-07 -2.53839025795741e-06 1.12520375163413e-06 5.15840313103251e-06 -3.99088241075582e-09 4.1553237368136e-05 -1.96945167543858e-05 -2.14401133853319e-06 6.94533649214462e-06 4.47360981751997e-06 5.9372832637292e-07 -1.96945167543858e-05 5.00747393950922e-05 8.86971585616314e-06 1.16553577254252e-05 8.94389399753536e-06 -2.53839025795741e-06 -2.14401133853319e-06 8.86971585616314e-06 3.05226402197397e-05 2017 1990 0 7 53 1998 2019 0 40 24 0 0 0 0 0 17 47 0 684 0 80 57 0 0 2821 +374 422 0.999998437814408 0.000445824351101771 0.00171044128544971 -0.00282814202697045 -0.000447177080976825 0.999999587519651 0.000790565105477794 0.00564311108959814 -0.00171008812675113 -0.000791328740609586 0.999998224697136 -0.0129423939606937 3.2606421050955e-05 1.63662559959197e-05 -1.12185572597499e-05 8.77943563436905e-06 1.16729721235933e-05 1.85014880282815e-05 1.63662559959197e-05 3.41595189274707e-05 -1.17805042823879e-05 1.32552040376768e-05 5.35596263661924e-06 1.42229125278014e-05 -1.12185572597499e-05 -1.17805042823879e-05 1.87970728254715e-05 -4.78482113218178e-06 -7.7143113678643e-06 -8.05439948695784e-06 8.77943563436905e-06 1.32552040376768e-05 -4.78482113218178e-06 6.11529337515434e-05 -2.1874320720128e-05 2.10728486448728e-06 1.16729721235933e-05 5.35596263661924e-06 -7.7143113678643e-06 -2.1874320720128e-05 7.0169782357356e-05 6.85590901177682e-06 1.85014880282815e-05 1.42229125278014e-05 -8.05439948695784e-06 2.10728486448728e-06 6.85590901177682e-06 7.60934249211541e-05 1950 1947 0 12 14 1939 1973 0 50 6 0 0 0 0 0 17 51 0 607 0 51 53 0 0 2350 +374 429 0.999971798641284 -0.00749671900976216 0.00044847096184143 -0.00301533444716389 0.00749446584691357 0.999960247094621 0.0048308603927854 0.00742955878032342 -0.00048466873675782 -0.0048273631056517 0.999988230761573 -0.010285136387643 3.07098383455164e-05 8.00615942336831e-06 -1.60089341653179e-06 1.42984463669183e-06 -5.99857693613133e-06 1.94380952649589e-05 8.00615942336831e-06 2.59721782862118e-05 -3.29989840650955e-06 2.83695215859139e-06 -6.46103924514915e-07 -7.7309425282175e-07 -1.60089341653179e-06 -3.29989840650955e-06 9.65621093064018e-06 9.73104932510895e-07 2.13142162374146e-06 9.81921897600362e-07 1.42984463669183e-06 2.83695215859139e-06 9.73104932510895e-07 3.52701866717824e-05 -4.76127031226877e-06 4.28335782720021e-06 -5.99857693613133e-06 -6.46103924514915e-07 2.13142162374146e-06 -4.76127031226877e-06 3.43720650788807e-05 -1.15705905964174e-05 1.94380952649589e-05 -7.7309425282175e-07 9.81921897600362e-07 4.28335782720021e-06 -1.15705905964174e-05 7.47655813110998e-05 2633 2634 0 6 25 2634 2662 0 37 20 0 0 0 0 0 28 60 0 614 0 14 14 0 0 2486 +374 423 0.999999697566946 0.000492915096088867 0.000601581852405865 -0.00747204597522296 -0.000492845714805968 0.999999871884396 -0.000115474204119506 0.00861625431658024 -0.000601638694312263 0.000115177682158226 0.999999812382474 -0.00978033910999619 3.11623535559114e-05 1.79400391575539e-05 -9.34027028128517e-06 3.18551839211077e-06 1.34746199990266e-05 1.87571981947544e-05 1.79400391575539e-05 2.52861557757212e-05 -9.25327548025212e-06 3.3695630651878e-06 1.20048638847023e-05 1.4792043197228e-05 -9.34027028128517e-06 -9.25327548025212e-06 1.29846668313756e-05 1.11030210873992e-06 -3.9185376407679e-06 -4.11926393737176e-06 3.18551839211077e-06 3.3695630651878e-06 1.11030210873992e-06 4.02102564279765e-05 -9.25967742967791e-06 1.78534670683706e-06 1.34746199990266e-05 1.20048638847023e-05 -3.9185376407679e-06 -9.25967742967791e-06 4.81893181607707e-05 5.29484141803234e-06 1.87571981947544e-05 1.4792043197228e-05 -4.11926393737176e-06 1.78534670683706e-06 5.29484141803234e-06 6.1869166289781e-05 2636 2638 0 15 12 2632 2670 0 46 9 0 0 0 0 0 16 46 0 623 0 12 15 0 0 2255 +374 408 0.9999993928496 0.000133076667423982 0.00109388803452185 -0.00921956542615541 -0.000135097172500187 0.999998284762962 0.00184721950159617 0.010317764063168 -0.00109364033642931 -0.00184736616123661 0.999997695591885 -0.00995447245585595 3.50447731042594e-05 3.13017523945979e-05 -2.31082360609101e-06 8.364494363636e-06 -2.53134894837404e-06 1.86726749020909e-05 3.13017523945979e-05 4.81042422173679e-05 -2.62950864189427e-06 1.40474425154436e-05 2.7032742513866e-08 2.44725692791906e-05 -2.31082360609101e-06 -2.62950864189427e-06 1.12554842185609e-05 2.63514154177705e-06 3.87363094441317e-06 -1.40278576127555e-07 8.364494363636e-06 1.40474425154436e-05 2.63514154177705e-06 5.46193033176242e-05 -3.41780520741496e-05 1.05323485974107e-06 -2.53134894837404e-06 2.7032742513866e-08 3.87363094441317e-06 -3.41780520741496e-05 5.73755184384604e-05 1.93203289919179e-06 1.86726749020909e-05 2.44725692791906e-05 -1.40278576127555e-07 1.05323485974107e-06 1.93203289919179e-06 5.07126199611705e-05 1902 1900 0 10 15 1892 1916 0 38 8 0 0 0 0 0 17 48 0 494 0 52 56 0 0 2409 +374 409 0.99999780908529 0.000424504502074714 0.0020497854884446 -0.0122172765831526 -0.000422092077555675 0.999999218013255 -0.00117720480679052 0.0100623034424928 -0.00205028361427986 0.00117633702941983 0.999997206280245 -0.00608448110570991 3.21571877698811e-05 1.88153477751636e-05 -1.39021882592139e-06 -4.34965467053813e-06 3.90922272246915e-06 1.5640298297308e-05 1.88153477751636e-05 3.54197291753517e-05 -2.51870418772213e-06 1.01963412127472e-05 1.52375878895914e-06 2.27612093051246e-05 -1.39021882592139e-06 -2.51870418772213e-06 1.18319267302925e-05 6.76625618789109e-07 6.019862410245e-06 3.67705180547474e-07 -4.34965467053813e-06 1.01963412127472e-05 6.76625618789109e-07 9.06284853289562e-05 -3.74956028128737e-05 6.44495229162538e-07 3.90922272246915e-06 1.52375878895914e-06 6.019862410245e-06 -3.74956028128737e-05 5.20154578027028e-05 3.53967078702079e-06 1.5640298297308e-05 2.27612093051246e-05 3.67705180547474e-07 6.44495229162538e-07 3.53967078702079e-06 5.87059532394302e-05 1849 1846 0 17 10 1844 1871 0 45 8 0 0 0 0 0 18 49 0 506 0 39 42 0 0 2297 +374 424 0.999999966500164 -0.000119452060134493 0.000229632045406626 -0.00304924625669502 0.000119737577613433 0.999999219364047 -0.00124375809925885 0.00025190439869389 -0.00022948329668033 0.00124378555317802 0.999999200167137 -0.0078549991176723 2.96424452433257e-05 1.99636502260494e-05 -1.0140127489283e-05 7.15417020804435e-06 8.360440209128e-06 1.57714599943275e-05 1.99636502260494e-05 2.62734891574649e-05 -1.10109411995358e-05 9.1798117320521e-06 5.65454356350745e-06 1.90315570138316e-05 -1.0140127489283e-05 -1.10109411995358e-05 1.46617498437086e-05 -3.23657649533534e-06 -8.35983054450733e-07 -5.23134401001027e-06 7.15417020804435e-06 9.1798117320521e-06 -3.23657649533534e-06 4.91351977096206e-05 -1.93921956252266e-05 6.92239124091224e-06 8.360440209128e-06 5.65454356350745e-06 -8.35983054450733e-07 -1.93921956252266e-05 5.52122614998436e-05 1.14223888883629e-05 1.57714599943275e-05 1.90315570138316e-05 -5.23134401001027e-06 6.92239124091224e-06 1.14223888883629e-05 5.99341835598288e-05 2581 2578 0 10 15 2581 2604 0 38 14 0 0 0 0 0 17 48 0 633 0 41 44 0 0 2261 +374 419 0.999999937529916 0.000279242660909933 0.000216711100075065 -0.00901190425737286 -0.00027997586722553 0.999994212325079 0.00339071229379244 0.0111405609959862 -0.000215763014298367 -0.00339077275585254 0.999994228036562 -0.00730982916849534 6.32423580174295e-05 4.11223804252864e-05 -1.26102272852218e-05 1.73623552555912e-05 1.77148791375288e-06 4.13603712534329e-05 4.11223804252864e-05 4.92145847618324e-05 -1.1377602158999e-05 1.37589606045447e-05 5.93021844332414e-06 3.31141717443553e-05 -1.26102272852218e-05 -1.1377602158999e-05 1.54592089272421e-05 -3.99212535001165e-06 -2.37631794500781e-06 -7.72544447568031e-06 1.73623552555912e-05 1.37589606045447e-05 -3.99212535001165e-06 4.93571103275904e-05 -2.06103002103813e-05 1.27399373022413e-05 1.77148791375288e-06 5.93021844332414e-06 -2.37631794500781e-06 -2.06103002103813e-05 5.62284805298479e-05 2.86513988507054e-08 4.13603712534329e-05 3.31141717443553e-05 -7.72544447568031e-06 1.27399373022413e-05 2.86513988507054e-08 7.81732716975766e-05 2493 2488 0 15 14 2482 2511 0 45 11 0 0 0 0 0 15 47 0 591 0 35 41 0 0 2254 +374 411 0.999997426936211 -0.000699476383973863 0.00215797445445956 -0.00210047165210979 0.000689428372257538 0.999988934942136 0.00465345912324815 0.0033693529948448 -0.00216120556110786 -0.00465195938078547 0.999986844145683 -0.00901697372373694 4.63468757329136e-05 1.95379136406397e-05 -2.90503325327462e-06 5.413580548646e-06 -2.81726959788674e-08 2.94810398433848e-05 1.95379136406397e-05 3.63131813481851e-05 -3.47143692450964e-06 1.06000118022665e-05 5.49150047213672e-06 1.67213581756837e-05 -2.90503325327462e-06 -3.47143692450964e-06 9.73961402338906e-06 2.76197155743819e-06 2.17838832319223e-06 4.6555258433015e-07 5.413580548646e-06 1.06000118022665e-05 2.76197155743819e-06 3.39026276936261e-05 -6.12639653554225e-06 6.64191815895003e-06 -2.81726959788674e-08 5.49150047213672e-06 2.17838832319223e-06 -6.12639653554225e-06 4.12056533755253e-05 -3.54408805674475e-06 2.94810398433848e-05 1.67213581756837e-05 4.6555258433015e-07 6.64191815895003e-06 -3.54408805674475e-06 6.57459100652993e-05 2657 2661 0 12 11 2659 2692 0 42 7 0 0 0 0 0 17 49 0 542 0 11 14 0 0 2338 +374 414 0.999999963278768 0.00015735596667313 -0.000220638985303782 -0.0143204222275666 -0.000156838647023632 0.999997243567764 0.00234270324909238 0.00994219895465444 0.00022100701546176 -0.0023426685583455 0.99999723152613 -0.0099439482332402 5.75204122622021e-05 5.12382058197212e-05 -1.27290390889743e-05 1.89376161357572e-05 7.23398997373729e-06 3.94347897310143e-05 5.12382058197212e-05 6.54186437574306e-05 -1.32265416671933e-05 2.88160228756568e-05 -1.04166731108975e-06 4.20921148878813e-05 -1.27290390889743e-05 -1.32265416671933e-05 1.64787754588853e-05 -3.15240891527797e-06 -4.69358461676547e-06 -3.71573957978417e-06 1.89376161357572e-05 2.88160228756568e-05 -3.15240891527797e-06 7.35878110556349e-05 -2.43858598346029e-05 1.42639043575406e-05 7.23398997373729e-06 -1.04166731108975e-06 -4.69358461676547e-06 -2.43858598346029e-05 5.44951707432607e-05 -2.92000813002168e-06 3.94347897310143e-05 4.20921148878813e-05 -3.71573957978417e-06 1.42639043575406e-05 -2.92000813002168e-06 7.63006419943427e-05 1470 1468 0 6 11 1459 1487 0 43 4 0 0 0 0 0 19 50 0 608 0 53 56 0 0 2403 +375 428 0.99999978708621 0.000374562554318328 0.000534350472705092 -0.00396636326875206 -0.000375403917065821 0.999998688715619 0.00157532185306886 0.00560339128088878 -0.000533759715442505 -0.00157552211492165 0.999998616414359 -0.00832571757161557 3.16430621975747e-05 1.18899970633999e-05 -7.68259543868717e-06 3.98421203855045e-06 2.03732582705989e-06 1.77934264611014e-05 1.18899970633999e-05 2.34811966094731e-05 -7.39543951938131e-06 2.08311137732867e-06 6.15587732603448e-06 1.19693138161895e-05 -7.68259543868717e-06 -7.39543951938131e-06 1.21099702216896e-05 4.86241925529042e-07 -1.48608493375121e-06 -4.09219499214895e-06 3.98421203855045e-06 2.08311137732867e-06 4.86241925529042e-07 3.21490315550691e-05 -7.66440967246377e-08 1.51539274761518e-06 2.03732582705989e-06 6.15587732603448e-06 -1.48608493375121e-06 -7.66440967246377e-08 4.22098273076931e-05 5.00700676611041e-06 1.77934264611014e-05 1.19693138161895e-05 -4.09219499214895e-06 1.51539274761518e-06 5.00700676611041e-06 5.44886910302963e-05 3031 3031 0 15 16 3021 3068 0 43 12 0 0 0 0 0 13 46 0 659 0 16 21 0 0 2280 +375 377 0.999994039131226 -0.000123757254206071 0.00345056316542015 0.00117274423020685 0.000116495829106349 0.99999777866978 0.00210453895848586 0.000359276749804768 -0.00345081595254278 -0.00210412443738846 0.999991832231451 -0.00417739233090913 2.70128573314531e-05 8.4470893086447e-06 -6.26785814814796e-06 2.62868460266553e-06 1.32513737804562e-06 7.7709039549487e-06 8.4470893086447e-06 2.54408949942598e-05 -8.89152516154799e-06 8.30052290084468e-06 6.24957604312054e-06 1.48171533230344e-05 -6.26785814814796e-06 -8.89152516154799e-06 1.12628975434198e-05 -5.00828036253267e-07 -5.6999544601917e-07 -4.5767559335631e-06 2.62868460266553e-06 8.30052290084468e-06 -5.00828036253267e-07 2.37319803732428e-05 4.992921972947e-06 4.27735418492262e-06 1.32513737804562e-06 6.24957604312054e-06 -5.6999544601917e-07 4.992921972947e-06 2.60195242149456e-05 5.20982930311758e-06 7.7709039549487e-06 1.48171533230344e-05 -4.5767559335631e-06 4.27735418492262e-06 5.20982930311758e-06 3.02950298750274e-05 2168 2143 0 15 53 2138 2164 0 42 26 0 0 0 0 0 11 43 0 647 0 54 34 0 0 2786 +374 416 0.999999704038598 0.000611047438218455 0.000467486625130436 -0.0203948977820395 -0.000611397108830491 0.999999533192801 0.000748203017221116 0.0194928387851087 -0.000467029219367374 -0.000748488615752923 0.999999610824174 -0.00861998214748756 2.94165144455982e-05 1.92468463974855e-05 -7.39675943847453e-06 1.64499581459749e-05 -6.69563577786802e-06 1.05267976548652e-05 1.92468463974855e-05 3.24556570207006e-05 -9.81886635044109e-06 1.3074515241786e-05 4.5098891446594e-06 1.18869361085491e-05 -7.39675943847453e-06 -9.81886635044109e-06 1.56768874198095e-05 2.95083998497014e-06 -3.43498114774745e-06 -2.95626679290723e-06 1.64499581459749e-05 1.3074515241786e-05 2.95083998497014e-06 0.000108500189491676 -7.57180606780621e-05 -3.8747373347615e-06 -6.69563577786802e-06 4.5098891446594e-06 -3.43498114774745e-06 -7.57180606780621e-05 0.000116369417327054 8.01845730496997e-06 1.05267976548652e-05 1.18869361085491e-05 -2.95626679290723e-06 -3.8747373347615e-06 8.01845730496997e-06 5.2775178600516e-05 1387 1386 0 14 12 1382 1408 0 43 10 0 0 0 0 0 25 55 0 611 0 48 51 0 0 2350 +374 410 0.999995594077147 0.000291129174324973 0.00295416148795097 -0.00465709929203025 -0.000294426651916365 0.999999334105788 0.00111584090611001 0.00978516888325245 -0.00295383466695026 -0.00111670577367718 0.999995013902057 -0.00992120550074164 3.07063035864925e-05 2.14278713259801e-05 -1.69305126529e-06 7.20553961951652e-07 2.92317774227562e-07 2.17042052437309e-05 2.14278713259801e-05 2.72971080524241e-05 -2.35923691083352e-06 6.5241437820728e-06 -3.17574974598697e-06 1.42793069004625e-05 -1.69305126529e-06 -2.35923691083352e-06 1.15455367026647e-05 2.9416229205725e-06 2.46395109396439e-06 -1.33243241195199e-06 7.20553961951652e-07 6.5241437820728e-06 2.9416229205725e-06 4.13161561605236e-05 -1.71321364838391e-05 -2.30470450565269e-06 2.92317774227562e-07 -3.17574974598697e-06 2.46395109396439e-06 -1.71321364838391e-05 4.60385138007459e-05 -8.63139729602679e-07 2.17042052437309e-05 1.42793069004625e-05 -1.33243241195199e-06 -2.30470450565269e-06 -8.63139729602679e-07 5.90773668157866e-05 1848 1852 0 8 9 1858 1890 0 43 9 0 0 0 0 0 19 48 0 511 0 31 33 0 0 2291 +375 420 0.999999835640348 0.000153538206151873 0.000552399580377585 -0.000304714896108192 -0.00015334597488277 0.999999927684004 -0.000348018674442674 0.000324921698876335 -0.00055245297459324 0.000347933908990268 0.99999978686883 -0.014259187511056 2.87951103241935e-05 1.57743836802138e-05 -7.7247905213926e-06 8.44899441587239e-06 7.32202602815018e-06 9.18004528279648e-06 1.57743836802138e-05 2.61395103314208e-05 -8.84036853705204e-06 9.18500967242138e-06 3.23518265594109e-06 1.53437770994099e-05 -7.7247905213926e-06 -8.84036853705204e-06 1.37076824717228e-05 -3.3714267249365e-06 -1.88804542287015e-06 -1.55788923572132e-06 8.44899441587239e-06 9.18500967242138e-06 -3.3714267249365e-06 3.6532333048199e-05 -4.03759494977183e-06 6.1966766597872e-06 7.32202602815018e-06 3.23518265594109e-06 -1.88804542287015e-06 -4.03759494977183e-06 4.08594714759064e-05 -9.14594866031669e-07 9.18004528279648e-06 1.53437770994099e-05 -1.55788923572132e-06 6.1966766597872e-06 -9.14594866031669e-07 5.17527496207709e-05 2574 2570 0 16 11 2568 2590 0 37 9 0 0 0 0 0 15 46 0 626 0 13 20 0 0 2269 +374 417 0.999998567468307 -3.64134178329516e-05 0.00169225748551201 -0.00130205355038617 3.69031576428282e-05 0.999999957451588 -0.000289369967903327 -0.000237748159785401 -0.00169224687655959 0.000289432003016437 0.999998526263726 -0.00701466733736995 2.82418082928331e-05 1.94217923276932e-05 -7.6153188516938e-06 7.36560190625668e-06 2.64859717784084e-06 1.59697012029797e-05 1.94217923276932e-05 2.62814081223408e-05 -9.52214760981708e-06 8.94437960184573e-06 3.44269407949409e-06 1.83431827248165e-05 -7.6153188516938e-06 -9.52214760981708e-06 1.39183014353816e-05 -1.19920050872418e-06 -4.59760545286053e-07 -2.78994911781331e-06 7.36560190625668e-06 8.94437960184573e-06 -1.19920050872418e-06 5.66237170363976e-05 -3.00765191674918e-05 1.02986561591224e-05 2.64859717784084e-06 3.44269407949409e-06 -4.59760545286053e-07 -3.00765191674918e-05 6.44441948693011e-05 2.81811247621183e-07 1.59697012029797e-05 1.83431827248165e-05 -2.78994911781331e-06 1.02986561591224e-05 2.81811247621183e-07 5.62150540533927e-05 2145 2140 0 6 13 2140 2171 0 47 7 0 0 0 0 0 14 48 0 607 0 51 54 0 0 2437 +375 426 0.999996043858107 0.000355133700925173 0.00279036703476217 -4.51260047627131e-05 -0.000358010661124744 0.999999404844736 0.00103060105801935 0.000974289019647603 -0.00278999937289263 -0.00103159596196223 0.999995575846849 -0.0125631866543839 3.4841718279913e-05 1.93862873984138e-05 -7.33455544246665e-06 4.4108182222838e-06 5.59684877956252e-06 1.31417304891581e-05 1.93862873984138e-05 3.14592725018247e-05 -8.97328228324271e-06 9.66613349328755e-06 4.96463517071049e-06 1.30185006087705e-05 -7.33455544246665e-06 -8.97328228324271e-06 1.3361141623745e-05 -1.91273205871518e-06 -3.40624253294323e-06 -5.64163694578121e-07 4.4108182222838e-06 9.66613349328755e-06 -1.91273205871518e-06 4.03519273384894e-05 -2.02154570947877e-07 4.60973843737335e-06 5.59684877956252e-06 4.96463517071049e-06 -3.40624253294323e-06 -2.02154570947877e-07 4.9263101732419e-05 4.9502676071351e-06 1.31417304891581e-05 1.30185006087705e-05 -5.64163694578121e-07 4.60973843737335e-06 4.9502676071351e-06 4.31988989749901e-05 2577 2571 0 18 17 2568 2595 0 44 16 0 0 0 0 0 20 50 0 640 0 19 25 0 0 2140 +375 413 0.999999019809458 7.30703843778713e-05 -0.00139822775069965 -0.00728637907197952 -6.98181086673676e-05 0.999997292639686 0.00232590600212828 0.00495839544010112 0.00139839392003893 -0.00232580610068018 0.999996317553433 -0.00755668402395936 4.94599133650208e-05 3.81241005899442e-05 -7.45362407157203e-06 1.19390331605107e-05 3.08513847126947e-06 3.55771070666566e-05 3.81241005899442e-05 3.99642867784307e-05 -8.289977621917e-06 1.13743055545591e-05 2.48580561251107e-06 3.11672572409105e-05 -7.45362407157203e-06 -8.289977621917e-06 1.16271025698182e-05 -1.7747769377755e-07 -7.19696909342153e-07 -2.64289078050974e-06 1.19390331605107e-05 1.13743055545591e-05 -1.7747769377755e-07 3.97662512793587e-05 -1.29390155949981e-05 6.71880869722709e-06 3.08513847126947e-06 2.48580561251107e-06 -7.19696909342153e-07 -1.29390155949981e-05 4.68970483134987e-05 6.14171553835023e-06 3.55771070666566e-05 3.11672572409105e-05 -2.64289078050974e-06 6.71880869722709e-06 6.14171553835023e-06 6.77515817926215e-05 2114 2109 0 16 11 2102 2127 0 39 10 0 0 0 0 0 17 50 0 597 0 66 76 0 0 2327 +374 407 0.999994691517291 -0.000268340807790628 0.00324729586707754 -0.00614542552328265 0.000266808293078939 0.999999852844833 0.000472359659837238 0.00493692997465746 -0.00324742214259386 -0.000471490746856735 0.999994615958458 -0.00497700958535858 3.42518402924837e-05 2.50018974213288e-05 -7.18686927398729e-07 5.94635991834229e-07 3.50812855988705e-06 2.37172838107373e-05 2.50018974213288e-05 3.22754194308095e-05 -2.09510317997605e-06 3.03358624137995e-06 3.38789321402156e-06 2.12280163573423e-05 -7.18686927398729e-07 -2.09510317997605e-06 9.85739844297927e-06 2.35946296318752e-06 4.21599043489043e-06 1.65532650051009e-06 5.94635991834229e-07 3.03358624137995e-06 2.35946296318752e-06 5.67482261827686e-05 -2.1812219643648e-05 8.95616391757888e-06 3.50812855988705e-06 3.38789321402156e-06 4.21599043489043e-06 -2.1812219643648e-05 4.56691524890601e-05 -5.62957566023189e-07 2.37172838107373e-05 2.12280163573423e-05 1.65532650051009e-06 8.95616391757888e-06 -5.62957566023189e-07 5.67772078671358e-05 2346 2346 0 10 17 2346 2376 0 47 13 0 0 0 0 0 18 48 0 480 0 44 47 0 0 2415 +375 427 0.999998532376822 0.000671519375342193 0.0015761681160914 -0.00600158083637405 -0.000675225655755855 0.999997005850871 0.00235209685321249 0.0101999764447737 -0.0015745839181994 -0.0023531576703704 0.999995991659198 -0.00654971712941283 5.28673633667881e-05 1.83430487247491e-05 -9.75518323864302e-06 5.22315589514751e-06 5.11668400437275e-06 2.81009137753253e-05 1.83430487247491e-05 2.48178976510844e-05 -9.27290942538504e-06 1.8733784735866e-06 1.09083792437888e-05 1.85890011361864e-05 -9.75518323864302e-06 -9.27290942538504e-06 1.50323354269732e-05 -5.99153712580237e-07 -7.82374416260757e-06 -4.77590951941782e-06 5.22315589514751e-06 1.8733784735866e-06 -5.99153712580237e-07 3.74807941309165e-05 -7.15945550664373e-06 3.30315358417256e-06 5.11668400437275e-06 1.09083792437888e-05 -7.82374416260757e-06 -7.15945550664373e-06 5.93407923586611e-05 7.146100387915e-06 2.81009137753253e-05 1.85890011361864e-05 -4.77590951941782e-06 3.30315358417256e-06 7.146100387915e-06 6.18065418400143e-05 3046 3048 0 17 17 3036 3077 0 43 14 0 0 0 0 0 19 49 0 640 0 19 21 0 0 2352 +375 415 0.999999090513069 0.000496642570093864 0.00125392152524287 -0.00795514191498257 -0.000497272129499651 0.999999750453258 0.000501810572792451 0.00637652805198346 -0.00125367199183827 -0.000502433656629376 0.999999087933063 -0.00488549837352577 3.08350213112628e-05 2.05800592804478e-05 -7.74155511669761e-06 3.73094396837929e-06 1.27659775405157e-05 1.93626154441547e-05 2.05800592804478e-05 2.47174589755618e-05 -8.70074299428499e-06 4.82058439305475e-06 1.07471355281569e-05 1.65729842556937e-05 -7.74155511669761e-06 -8.70074299428499e-06 1.11168215703162e-05 -2.65741250026939e-07 -1.54269396353085e-06 -4.19054637782996e-06 3.73094396837929e-06 4.82058439305475e-06 -2.65741250026939e-07 3.1018049950058e-05 -2.09682663633019e-06 1.56483690954706e-06 1.27659775405157e-05 1.07471355281569e-05 -1.54269396353085e-06 -2.09682663633019e-06 3.43463159852329e-05 1.33107128589832e-05 1.93626154441547e-05 1.65729842556937e-05 -4.19054637782996e-06 1.56483690954706e-06 1.33107128589832e-05 4.87631241537658e-05 3056 3055 0 16 14 3048 3087 0 39 12 0 0 0 0 0 14 46 0 579 0 16 20 0 0 2248 +375 378 0.999999998768061 4.50466087676501e-05 2.08490091044775e-05 -0.00462985454438836 -4.5069111647448e-05 0.999999415150002 0.00108058707594706 0.00691285267837129 -2.0800320127685e-05 -0.00108058801426216 0.999999415948274 0.00483108092810803 3.24882140549805e-05 2.25420036564862e-05 -9.60623055601297e-06 5.74399255716915e-06 6.32443739238365e-06 1.67570981747862e-05 2.25420036564862e-05 2.81302073950011e-05 -9.96103175765373e-06 4.90093007822284e-06 6.08752281021902e-06 1.68655226305679e-05 -9.60623055601297e-06 -9.96103175765373e-06 1.26678106859691e-05 -2.2528903432037e-06 -2.13293377076871e-06 -3.94861155747479e-06 5.74399255716915e-06 4.90093007822284e-06 -2.2528903432037e-06 2.59451484479304e-05 -1.64734435663596e-06 3.80874620912008e-06 6.32443739238365e-06 6.08752281021902e-06 -2.13293377076871e-06 -1.64734435663596e-06 3.30727644425123e-05 3.74338359150456e-06 1.67570981747862e-05 1.68655226305679e-05 -3.94861155747479e-06 3.80874620912008e-06 3.74338359150456e-06 3.59581103897368e-05 2046 2017 0 15 51 1983 2013 0 47 0 0 0 0 0 0 11 41 0 665 0 112 102 0 0 2771 +375 412 0.999993740589474 -5.63283799016687e-05 0.00353774066098781 -0.000421868986462264 5.33800055784205e-05 0.999999651218351 0.000833494901655238 0.00087853056316227 -0.00353778637650625 -0.000833300839852259 0.999993394816818 -0.0118104766018913 3.20849813538236e-05 1.66742863495752e-05 -6.47185804155312e-06 3.10757840015281e-06 5.67635850531501e-06 1.41244641158208e-05 1.66742863495752e-05 3.47401688091153e-05 -7.78724816669135e-06 9.17487342713973e-06 9.87515514037153e-06 1.74019060541757e-05 -6.47185804155312e-06 -7.78724816669135e-06 1.29264318568665e-05 5.98608195322054e-07 4.4790689472751e-07 -2.82131687804239e-06 3.10757840015281e-06 9.17487342713973e-06 5.98608195322054e-07 3.28345475472859e-05 -5.90561655411814e-06 5.72248769187043e-06 5.67635850531501e-06 9.87515514037153e-06 4.4790689472751e-07 -5.90561655411814e-06 3.74221312161414e-05 3.96734853506534e-06 1.41244641158208e-05 1.74019060541757e-05 -2.82131687804239e-06 5.72248769187043e-06 3.96734853506534e-06 4.52492412239178e-05 1935 1930 0 12 9 1929 1955 0 43 6 0 0 0 0 0 12 44 0 569 0 13 15 0 0 2232 +375 379 0.99999817167951 0.000406663315080222 -0.00186849206196658 -0.0116550397516381 -0.000410696803004623 0.999997585431299 -0.00215880978979795 0.00806341064700274 0.00186760964161838 0.00215957322651806 0.999995924130547 0.00243292304069422 4.05402031679241e-05 2.40455420910048e-05 -7.1292205616828e-06 8.94600145630901e-06 -1.43491931520513e-06 2.15648251383113e-05 2.40455420910048e-05 2.7434660543172e-05 -8.87585117355265e-06 6.54055589553697e-06 4.68965341964428e-06 1.86899632712938e-05 -7.1292205616828e-06 -8.87585117355265e-06 1.15829591058121e-05 -4.10521240828926e-07 -7.63835866217466e-07 -3.23369987674394e-06 8.94600145630901e-06 6.54055589553697e-06 -4.10521240828926e-07 3.29747239240203e-05 -8.61859869615113e-06 7.22700798103499e-07 -1.43491931520513e-06 4.68965341964428e-06 -7.63835866217466e-07 -8.61859869615113e-06 3.99566664178688e-05 4.64286555576708e-06 2.15648251383113e-05 1.86899632712938e-05 -3.23369987674394e-06 7.22700798103499e-07 4.64286555576708e-06 3.77512411892885e-05 2829 2800 0 15 58 2796 2822 0 38 25 0 0 0 0 0 15 46 0 646 0 100 91 0 0 2744 +375 425 0.999999273850889 1.08837190655211e-05 0.00120506399760882 -0.00661876448117863 -1.20858800786959e-05 0.999999502335709 0.000997588224233302 0.00376817555465973 -0.00120505254042153 -0.000997602064094463 0.9999987763185 -0.00707130521833971 3.47853066468501e-05 7.89660596709194e-06 -7.26302211880731e-06 3.42483190282738e-07 4.71543712880881e-06 1.10773588880297e-05 7.89660596709194e-06 3.03336056840217e-05 -7.92313645958767e-06 1.3844901118417e-05 6.61030555272291e-06 1.21398488810079e-05 -7.26302211880731e-06 -7.92313645958767e-06 1.31807915922042e-05 -6.18789956650838e-07 -2.2844489786244e-06 -4.02489535581538e-06 3.42483190282738e-07 1.3844901118417e-05 -6.18789956650838e-07 5.98194621573355e-05 -1.72737495397219e-05 1.91915724804089e-06 4.71543712880881e-06 6.61030555272291e-06 -2.2844489786244e-06 -1.72737495397219e-05 5.61083066576765e-05 1.07019237063547e-05 1.10773588880297e-05 1.21398488810079e-05 -4.02489535581538e-06 1.91915724804089e-06 1.07019237063547e-05 4.39937988298632e-05 1494 1490 0 19 16 1473 1503 0 43 6 0 0 0 0 0 19 49 0 629 0 76 88 0 0 2112 +375 424 0.999999660111507 0.000346690111039985 0.000748052696580135 -0.00276556377240189 -0.0003469726329912 0.999999868521728 0.000377579818531175 0.000619975866013444 -0.000747921695038246 -0.000377839244009888 0.99999964892526 -0.00781511009821189 3.00615281754787e-05 2.19230921486961e-05 -1.01280110687386e-05 6.72877017227247e-06 1.08627165811913e-05 1.97234978540351e-05 2.19230921486961e-05 2.81398372229826e-05 -1.13378068532328e-05 9.52625063143324e-06 7.72727440016279e-06 1.48533969982188e-05 -1.01280110687386e-05 -1.13378068532328e-05 1.59926946880113e-05 -1.20868770318101e-06 -6.09547385189509e-06 -5.18492468417091e-06 6.72877017227247e-06 9.52625063143324e-06 -1.20868770318101e-06 3.8270074328441e-05 -7.72632278952245e-06 5.71281300505125e-06 1.08627165811913e-05 7.72727440016279e-06 -6.09547385189509e-06 -7.72632278952245e-06 4.58828561352028e-05 3.97310344071403e-06 1.97234978540351e-05 1.48533969982188e-05 -5.18492468417091e-06 5.71281300505125e-06 3.97310344071403e-06 5.16951539124391e-05 2091 2093 0 21 15 2074 2109 0 47 6 0 0 0 0 0 8 39 0 614 0 73 84 0 0 2224 +375 421 0.99999305894838 0.000430065431903509 0.0037009591712481 0.000815744749281206 -0.000436610154076062 0.999998342198128 0.0017677591941678 0.00182763496370892 -0.00370019278366972 -0.00176936280041397 0.999991588928949 -0.0114136620714384 3.80426716127221e-05 2.37442830179833e-05 -1.03243417777227e-05 7.6336282352374e-06 9.82942596799886e-06 2.22502269288455e-05 2.37442830179833e-05 3.85245145240093e-05 -9.43617713778669e-06 1.15804196525252e-05 9.42864715872762e-06 2.47666844381547e-05 -1.03243417777227e-05 -9.43617713778669e-06 1.55804310568368e-05 -2.28874109576592e-06 -4.40578534372149e-06 -3.88127140273455e-06 7.6336282352374e-06 1.15804196525252e-05 -2.28874109576592e-06 3.72014837326144e-05 3.72591511080658e-08 7.02044500790138e-06 9.82942596799886e-06 9.42864715872762e-06 -4.40578534372149e-06 3.72591511080658e-08 4.30922444845055e-05 7.17276669366613e-06 2.22502269288455e-05 2.47666844381547e-05 -3.88127140273455e-06 7.02044500790138e-06 7.17276669366613e-06 6.01747672500242e-05 2559 2555 0 16 14 2549 2588 0 55 8 0 0 0 0 0 15 48 0 627 0 15 19 0 0 2320 +375 423 0.999995731012175 0.000749393946930473 0.002824246118398 -0.00359242596800584 -0.00075035434965777 0.999999661019528 0.000339012063216086 0.00366761864857473 -0.0028239911074456 -0.00034112980133716 0.999995954344158 -0.0142449043440734 3.34819015420384e-05 2.012724334991e-05 -7.58208935345685e-06 8.72460636982095e-06 5.88042314470876e-06 2.06858566676221e-05 2.012724334991e-05 3.10555935565107e-05 -1.01342544576992e-05 1.58760775090746e-05 3.19417468465283e-06 1.88425385730876e-05 -7.58208935345685e-06 -1.01342544576992e-05 1.64408790924447e-05 -3.11099990026561e-06 -2.73972423137263e-06 -1.23625809545518e-06 8.72460636982095e-06 1.58760775090746e-05 -3.11099990026561e-06 5.60858747071514e-05 -8.70988070028103e-06 9.51225281957585e-06 5.88042314470876e-06 3.19417468465283e-06 -2.73972423137263e-06 -8.70988070028103e-06 4.70454382876794e-05 6.99027736880262e-07 2.06858566676221e-05 1.88425385730876e-05 -1.23625809545518e-06 9.51225281957585e-06 6.99027736880262e-07 5.73985542644939e-05 1955 1951 0 13 12 1953 1975 0 38 12 0 0 0 0 0 17 48 0 612 0 13 19 0 0 2262 +375 408 0.999999821709837 0.000406965171432207 -0.000436989294025387 -0.0119176437230227 -0.000406018912936295 0.999997577607665 0.00216331399579544 0.0112379561004523 0.000437868628917032 -0.00216313618417971 0.99999756455349 -0.00417149939712548 5.19915079368989e-05 4.02915683185174e-05 -4.80421389210908e-06 1.03650822285389e-05 -6.83888218435323e-06 3.3897014749685e-05 4.02915683185174e-05 4.67443357310326e-05 -3.88754281362005e-06 1.15298405932913e-05 -7.41019637857289e-06 3.6160844103963e-05 -4.80421389210908e-06 -3.88754281362005e-06 1.15922249969576e-05 4.82804562807231e-06 -4.17397615380163e-07 -1.8483957004094e-06 1.03650822285389e-05 1.15298405932913e-05 4.82804562807231e-06 4.84967634579916e-05 -2.84798206381651e-05 7.86178734271279e-06 -6.83888218435323e-06 -7.41019637857289e-06 -4.17397615380163e-07 -2.84798206381651e-05 5.10753582394909e-05 -1.27031543425872e-06 3.3897014749685e-05 3.6160844103963e-05 -1.8483957004094e-06 7.86178734271279e-06 -1.27031543425872e-06 6.37468595504055e-05 2616 2614 0 12 15 2618 2656 0 45 10 0 0 0 0 0 13 45 0 488 0 53 65 0 0 2326 +375 414 0.999999612660041 0.000180803565493509 0.000861388320812521 -0.0165577801170156 -0.000183234468254584 0.999995999012136 0.00282283277026688 0.0151852099569659 -0.000860874496178647 -0.00282298951290188 0.999995644803172 -0.00597245848322389 5.69820122229983e-05 4.41937871539287e-05 -1.08454777131398e-05 2.2123307800243e-05 5.22551208806599e-06 4.48752466510993e-05 4.41937871539287e-05 5.51637804920546e-05 -9.78500225995317e-06 2.26828251891967e-05 3.80769212692959e-06 4.2788737173218e-05 -1.08454777131398e-05 -9.78500225995317e-06 1.47415323830685e-05 -8.60316642226943e-07 -4.37120782145318e-06 -7.35475850806717e-06 2.2123307800243e-05 2.26828251891967e-05 -8.60316642226943e-07 5.87259398128355e-05 -1.66617983688127e-05 1.96395776152171e-05 5.22551208806599e-06 3.80769212692959e-06 -4.37120782145318e-06 -1.66617983688127e-05 5.48902352304633e-05 2.72013828004873e-06 4.48752466510993e-05 4.2788737173218e-05 -7.35475850806717e-06 1.96395776152171e-05 2.72013828004873e-06 7.76970136662216e-05 2450 2448 0 11 11 2454 2493 0 46 11 0 0 0 0 0 18 48 0 605 0 50 60 0 0 2347 +375 419 0.99999961393901 0.000519434525450123 0.000708738036840748 -0.00579436099169621 -0.000520372214516308 0.999998988782282 0.00132349808167475 0.00640617471971549 -0.000708049849554299 -0.00132386637830551 0.999998873020976 -0.00980519901154457 2.97318784028498e-05 9.94725246381204e-06 -9.18626947330696e-06 3.59058261254255e-06 4.92518604372681e-06 9.43947928510499e-06 9.94725246381204e-06 2.31134724860745e-05 -1.02672904140257e-05 4.85828255422568e-06 9.91636456115248e-06 1.40427853241313e-05 -9.18626947330696e-06 -1.02672904140257e-05 1.53041699352844e-05 -1.7292036920368e-06 -5.23429880286178e-06 -3.93267504048154e-06 3.59058261254255e-06 4.85828255422568e-06 -1.7292036920368e-06 3.65782786186537e-05 -4.04917823582841e-06 2.95376899953506e-06 4.92518604372681e-06 9.91636456115248e-06 -5.23429880286178e-06 -4.04917823582841e-06 5.29412823231144e-05 8.97634874104801e-06 9.43947928510499e-06 1.40427853241313e-05 -3.93267504048154e-06 2.95376899953506e-06 8.97634874104801e-06 5.24114361053276e-05 2419 2418 0 15 14 2404 2448 0 37 8 0 0 0 0 0 15 47 0 601 0 15 18 0 0 2221 +375 418 0.999986886723815 0.00046861139363999 0.00509968467387369 -0.000372287475283758 -0.000473692985606655 0.999999392506236 0.000995289964538538 0.00128248534180949 -0.00509921517162969 -0.000997692597885169 0.999986501215948 -0.0107688556097623 4.47675259703488e-05 3.10701054441194e-05 -8.74422106917295e-06 4.8596331412766e-06 7.51933385932233e-06 2.63449170237669e-05 3.10701054441194e-05 3.82466632674085e-05 -8.06744682497143e-06 8.66799306191099e-06 3.87856641325345e-06 2.4232087069897e-05 -8.74422106917295e-06 -8.06744682497143e-06 1.35582617021736e-05 5.32601681352662e-07 -3.68224434403542e-06 -2.11181613514607e-06 4.8596331412766e-06 8.66799306191099e-06 5.32601681352662e-07 4.03926171011067e-05 -1.50675377840174e-05 5.07562670527098e-06 7.51933385932233e-06 3.87856641325345e-06 -3.68224434403542e-06 -1.50675377840174e-05 5.3597395377184e-05 3.65513181938385e-06 2.63449170237669e-05 2.4232087069897e-05 -2.11181613514607e-06 5.07562670527098e-06 3.65513181938385e-06 7.02217963623298e-05 2563 2561 0 15 13 2557 2579 0 37 11 0 0 0 0 0 15 48 0 611 0 16 21 0 0 2222 +375 416 0.999999898908181 0.000440706141768007 8.92285008173859e-05 -0.0163656192550218 -0.000440937632101215 0.999996493669597 0.0026111726324046 0.0147865378783736 -8.80774281364634e-05 -0.00261121171264027 0.999996586902055 -0.00525527998020978 5.00571333063085e-05 2.06775770105186e-05 -1.12894904639747e-05 1.77238351694862e-06 8.38305255803231e-06 2.12027888337672e-05 2.06775770105186e-05 3.84165226679082e-05 -9.32773034453472e-06 8.36844973649484e-06 1.02345216612712e-05 2.09434183758506e-05 -1.12894904639747e-05 -9.32773034453472e-06 1.50462253010369e-05 4.44236028156416e-07 -4.80447983933635e-06 -4.24598909067634e-06 1.77238351694862e-06 8.36844973649484e-06 4.44236028156416e-07 6.79582494377079e-05 -3.09347469219666e-05 7.37154387503266e-06 8.38305255803231e-06 1.02345216612712e-05 -4.80447983933635e-06 -3.09347469219666e-05 6.9740992574512e-05 2.58909750685118e-06 2.12027888337672e-05 2.09434183758506e-05 -4.24598909067634e-06 7.37154387503266e-06 2.58909750685118e-06 5.92959688549325e-05 2496 2494 0 12 12 2488 2512 0 35 5 0 0 0 0 0 27 58 0 616 0 56 68 0 0 2264 +375 409 0.999992927081899 0.000335556787478828 0.00374608967042783 -0.00747098900505943 -0.000335124086924518 0.999999937102326 -0.000116134367317127 0.00791388263136656 -0.00374612840448272 0.000114878141027919 0.999992976637831 -0.00421188191787394 4.31979878525731e-05 4.08597126989442e-05 -1.74722462188355e-06 4.80875885684924e-06 -1.32177418232689e-06 4.19968134061724e-05 4.08597126989442e-05 6.33368162570928e-05 -2.37179365090147e-06 1.66249628117161e-05 -8.81982355462159e-06 5.0236249888376e-05 -1.74722462188355e-06 -2.37179365090147e-06 1.04292739135634e-05 2.21864172058197e-06 1.7369150408476e-06 -5.97055147863445e-07 4.80875885684924e-06 1.66249628117161e-05 2.21864172058197e-06 5.61629256576423e-05 -3.03791016688506e-05 8.27431405866468e-06 -1.32177418232689e-06 -8.81982355462159e-06 1.7369150408476e-06 -3.03791016688506e-05 4.91772415672863e-05 -4.99823603363451e-06 4.19968134061724e-05 5.0236249888376e-05 -5.97055147863445e-07 8.27431405866468e-06 -4.99823603363451e-06 9.23807269486925e-05 1972 1967 0 12 10 1961 1997 0 53 2 0 0 0 0 0 21 52 0 491 0 68 80 0 0 2268 +375 422 0.99999974702496 0.000378792167288601 -0.000602051915938137 -0.0107784772481076 -0.000377503885641178 0.999997642165729 0.00213849334790938 0.0115305465156313 0.000602860540929483 -0.00213826552998631 0.999997532186801 -0.00944960265104374 3.21768306471311e-05 1.82069187557687e-05 -9.42961965498917e-06 6.84753896297857e-06 8.85440571875723e-06 1.60758139256229e-05 1.82069187557687e-05 3.68949506259503e-05 -1.18597534251752e-05 1.74165483941401e-05 7.01848126909221e-06 1.99757048635895e-05 -9.42961965498917e-06 -1.18597534251752e-05 1.46262461344835e-05 -4.27421967894113e-06 -4.2911865990409e-06 -4.4928583296408e-06 6.84753896297857e-06 1.74165483941401e-05 -4.27421967894113e-06 4.99330297108105e-05 -7.39680043437672e-06 6.80561839261339e-06 8.85440571875723e-06 7.01848126909221e-06 -4.2911865990409e-06 -7.39680043437672e-06 4.30433729269904e-05 5.51694583956262e-06 1.60758139256229e-05 1.99757048635895e-05 -4.4928583296408e-06 6.80561839261339e-06 5.51694583956262e-06 5.84890608191252e-05 1993 1990 0 18 14 1994 2024 0 41 14 0 0 0 0 0 21 55 0 604 0 54 64 0 0 2284 +375 410 0.999997360635452 -0.00019809241824111 0.0022889913768997 -0.00311391851484263 0.000192584115380198 0.99999708606561 0.00240640222059262 0.00462366964222395 -0.00228946139696414 -0.00240595504584048 0.999994484858206 -0.00616026080359994 3.95312620784053e-05 3.10780058547311e-05 -9.25650090222067e-07 7.43090894126975e-06 -6.55125403639076e-07 2.43130155698082e-05 3.10780058547311e-05 4.29416280464281e-05 -2.84399631873205e-06 6.29073986073866e-06 4.94542495005778e-06 2.65228530476575e-05 -9.25650090222067e-07 -2.84399631873205e-06 1.00759627036201e-05 3.53854730863736e-06 2.50386789881261e-06 1.12640085116483e-07 7.43090894126975e-06 6.29073986073866e-06 3.53854730863736e-06 4.08325781813206e-05 -1.70552436587096e-05 6.1573022624383e-06 -6.55125403639076e-07 4.94542495005778e-06 2.50386789881261e-06 -1.70552436587096e-05 4.41068502731635e-05 1.63632502227151e-06 2.43130155698082e-05 2.65228530476575e-05 1.12640085116483e-07 6.1573022624383e-06 1.63632502227151e-06 5.23285319692463e-05 2008 2003 0 17 9 2001 2030 0 43 7 0 0 0 0 0 18 48 0 498 0 56 61 0 0 2356 +375 411 0.999998864069735 -0.000163842434440396 0.00149833737738169 0.0003268857261292 0.000162394845268831 0.9999995200417 0.00096620095387209 -0.00194881430120454 -0.00149849496295867 -0.000965956534068624 0.999998410719147 -0.0108182074103211 5.32406854830401e-05 3.65022627120887e-05 -6.84271314289852e-06 7.93055422640484e-06 1.00923216938633e-06 3.66511788112012e-05 3.65022627120887e-05 4.71394264521157e-05 -5.85257613253872e-06 1.01739208414347e-05 3.7718017436851e-06 4.01248243919481e-05 -6.84271314289852e-06 -5.85257613253872e-06 1.10054720640325e-05 2.4275244771137e-06 7.07235557920478e-07 -2.99651293752842e-06 7.93055422640484e-06 1.01739208414347e-05 2.4275244771137e-06 3.7266292026368e-05 -1.10227957188978e-05 1.27515440881471e-05 1.00923216938633e-06 3.7718017436851e-06 7.07235557920478e-07 -1.10227957188978e-05 4.05651730751286e-05 -7.37320450871734e-07 3.66511788112012e-05 4.01248243919481e-05 -2.99651293752842e-06 1.27515440881471e-05 -7.37320450871734e-07 7.90234591032419e-05 2593 2591 0 17 11 2589 2623 0 52 9 0 0 0 0 0 17 49 0 531 0 13 18 0 0 2224 +376 378 0.999999918441131 -0.000101706854681504 0.000390862439122944 -0.00214838118287169 0.00010125538253004 0.999999327961587 0.00115491286355964 0.00244970538307933 -0.000390979639003154 -0.00115487319244046 0.999999256701139 0.00299636432482962 4.09135126371301e-05 1.86069546289601e-05 -8.52250657758694e-06 6.32239628352242e-06 1.425292442732e-06 2.04515243446109e-05 1.86069546289601e-05 2.80041128312942e-05 -9.56183774625389e-06 6.94529409084221e-06 5.28164722403653e-06 1.74131495902847e-05 -8.52250657758694e-06 -9.56183774625389e-06 1.39316319950027e-05 -1.09623091394134e-07 -3.1587934054365e-07 -4.21211948063512e-06 6.32239628352242e-06 6.94529409084221e-06 -1.09623091394134e-07 3.40769802026669e-05 -9.50698570596369e-06 1.94867632915358e-06 1.425292442732e-06 5.28164722403653e-06 -3.1587934054365e-07 -9.50698570596369e-06 4.13498567554705e-05 8.71938429007259e-06 2.04515243446109e-05 1.74131495902847e-05 -4.21211948063512e-06 1.94867632915358e-06 8.71938429007259e-06 3.41395077915709e-05 2009 1987 0 11 43 1985 2010 0 48 9 0 0 0 0 0 12 43 0 668 0 85 62 0 0 2802 +375 417 0.999999379529078 0.000425329471484239 0.00102958064281937 -0.00841651742905066 -0.00042808384493449 0.999996326545283 0.00267649774152758 0.00864500887772441 -0.00102843846733167 -0.00267693682767881 0.999995888153316 -0.00526177879932356 6.53928478781245e-05 3.61073338788221e-05 -1.22083773997596e-05 1.67014141081992e-05 1.2387464389441e-06 3.55019628337708e-05 3.61073338788221e-05 5.36635057657158e-05 -1.20113299992881e-05 2.44221214605446e-05 3.45146606853262e-07 3.16622929887231e-05 -1.22083773997596e-05 -1.20113299992881e-05 1.4922553890287e-05 -8.22258613625931e-07 -1.33605782544628e-06 -7.16623401956865e-06 1.67014141081992e-05 2.44221214605446e-05 -8.22258613625931e-07 6.36041549471171e-05 -2.66215133614588e-05 5.77151625638817e-06 1.2387464389441e-06 3.45146606853262e-07 -1.33605782544628e-06 -2.66215133614588e-05 5.58795236254811e-05 7.78631595578186e-06 3.55019628337708e-05 3.16622929887231e-05 -7.16623401956865e-06 5.77151625638817e-06 7.78631595578186e-06 6.84272496083945e-05 2574 2570 0 15 13 2569 2596 0 42 10 0 0 0 0 0 12 46 0 599 0 52 65 0 0 2332 +375 429 0.999970018387738 -0.00740500032245158 0.00226457409924464 0.000639842089426995 0.00739727843376276 0.999966861495736 0.00339943850387631 0.00256465758148994 -0.00228967189786356 -0.00338258489808318 0.999991657726207 -0.0127071463911508 3.97615711998815e-05 2.55245182977108e-05 -3.0026020676215e-06 8.12130337723949e-06 4.11355075508081e-07 2.82000104892355e-05 2.55245182977108e-05 4.2024944099968e-05 -6.38792318443476e-06 8.01278434618663e-06 1.69729404546477e-06 2.25605675908064e-05 -3.0026020676215e-06 -6.38792318443476e-06 1.21868121893724e-05 1.06288336844564e-06 3.33783672589959e-07 3.83311923936505e-08 8.12130337723949e-06 8.01278434618663e-06 1.06288336844564e-06 5.14968584639683e-05 -1.25414770899222e-05 9.55375358095521e-06 4.11355075508081e-07 1.69729404546477e-06 3.33783672589959e-07 -1.25414770899222e-05 4.45814170580689e-05 -3.7143510998458e-06 2.82000104892355e-05 2.25605675908064e-05 3.83311923936505e-08 9.55375358095521e-06 -3.7143510998458e-06 6.83471276835874e-05 2021 2017 0 6 24 2020 2041 0 37 22 0 0 0 0 0 22 54 0 613 0 15 18 0 0 2352 +375 407 0.999990769343924 -0.000261184319739059 0.00428870722914162 -0.0091652121738383 0.000245727302353917 0.999993474471822 0.0036042519150496 0.00888936732860663 -0.00428962061714635 -0.00360316479298176 0.999984308056099 -0.00461393783361362 5.56632443591536e-05 3.82822986738497e-05 -2.10402215091599e-06 1.48811336958517e-05 -1.57621213804903e-05 3.83745562481265e-05 3.82822986738497e-05 4.65057907035038e-05 -2.9435968973228e-06 1.49167750654472e-05 -9.92000822385967e-06 2.92246817938699e-05 -2.10402215091599e-06 -2.9435968973228e-06 1.12702091059224e-05 2.78198410730668e-06 3.60602201210117e-06 7.44433685777612e-07 1.48811336958517e-05 1.49167750654472e-05 2.78198410730668e-06 7.58665000913244e-05 -4.12782924991331e-05 1.06475977412962e-05 -1.57621213804903e-05 -9.92000822385967e-06 3.60602201210117e-06 -4.12782924991331e-05 5.63958956158997e-05 -1.29236857116928e-05 3.83745562481265e-05 2.92246817938699e-05 7.44433685777612e-07 1.06475977412962e-05 -1.29236857116928e-05 6.67218266614116e-05 1511 1507 0 11 17 1497 1520 0 37 9 0 0 0 0 0 18 47 0 480 0 73 86 0 0 2310 +376 428 0.999999435400058 0.00105433500358747 0.00013257928196201 -0.00105334385268276 -0.00105437590355347 0.999999396465636 0.000308803851032223 0.00228675288418618 -0.000132253619236472 -0.000308943465081797 0.999999943531456 -0.0122991117714219 3.37978581869762e-05 2.47004324241817e-05 -8.35451195180073e-06 5.84426018537013e-06 6.20130042116109e-06 2.1432862622501e-05 2.47004324241817e-05 3.05204115445899e-05 -9.33840812092684e-06 6.00459005012219e-06 3.13573823185765e-06 2.16812052094494e-05 -8.35451195180073e-06 -9.33840812092684e-06 1.56610386813527e-05 -1.67178048856029e-06 -2.87969128952526e-06 -2.98491727338919e-06 5.84426018537013e-06 6.00459005012219e-06 -1.67178048856029e-06 3.87514117887159e-05 -1.77668860322114e-06 5.67158244161763e-06 6.20130042116109e-06 3.13573823185765e-06 -2.87969128952526e-06 -1.77668860322114e-06 4.34603305348201e-05 1.47445481735382e-06 2.1432862622501e-05 2.16812052094494e-05 -2.98491727338919e-06 5.67158244161763e-06 1.47445481735382e-06 6.10182056975034e-05 2812 2814 0 20 16 2806 2841 0 53 18 0 0 0 0 0 16 48 0 651 0 52 57 0 0 2275 +376 412 0.999993893359831 -0.000240974438966103 0.00348642716366839 -0.006945134804004 0.00023058106074064 0.999995529653074 0.00298119208397636 0.00837994809022425 -0.00348712996921933 -0.00298036997483543 0.999989478604346 -0.00850027124292189 5.77522665610798e-05 4.18622216368458e-05 -9.85973708308454e-06 1.41239383037467e-05 6.91546816699109e-06 2.86648149024609e-05 4.18622216368458e-05 5.62590434092921e-05 -1.02094842652525e-05 1.82577945311051e-05 7.53894967437396e-06 1.96523744741266e-05 -9.85973708308454e-06 -1.02094842652525e-05 1.36556480028023e-05 5.70038020437438e-07 -1.32749298765281e-06 -3.37879079504129e-06 1.41239383037467e-05 1.82577945311051e-05 5.70038020437438e-07 6.00453145713937e-05 -3.29872379340796e-05 1.09195915891419e-05 6.91546816699109e-06 7.53894967437396e-06 -1.32749298765281e-06 -3.29872379340796e-05 6.61219427304402e-05 -5.0431687854601e-06 2.86648149024609e-05 1.96523744741266e-05 -3.37879079504129e-06 1.09195915891419e-05 -5.0431687854601e-06 5.64893004593209e-05 2002 1999 0 11 9 1998 2023 0 42 4 0 0 0 0 0 22 52 0 576 0 47 55 0 0 2284 +376 425 0.999997239538751 0.000866086487231604 0.00218421818391978 -0.00753110976620456 -0.000871826874095824 0.999996165344547 0.00262853839669316 0.0057409729319085 -0.00218193326660906 -0.0026304354008264 0.999994159971358 -0.00973546165526367 4.36033971221726e-05 1.04308045663404e-05 -1.01394757764426e-05 5.03670884083115e-06 2.00107045969663e-06 1.02367993312854e-05 1.04308045663404e-05 3.72265038394056e-05 -8.70871465730927e-06 3.93099384963174e-06 1.09883254984269e-05 8.48357955387185e-06 -1.01394757764426e-05 -8.70871465730927e-06 1.61463652384745e-05 -1.46565826347547e-06 -2.9476894206793e-06 -2.40037982427328e-06 5.03670884083115e-06 3.93099384963174e-06 -1.46565826347547e-06 5.64883310500034e-05 -1.86724624731074e-05 -2.03070565618503e-06 2.00107045969663e-06 1.09883254984269e-05 -2.9476894206793e-06 -1.86724624731074e-05 5.7398655386626e-05 1.47762647324674e-09 1.02367993312854e-05 8.48357955387185e-06 -2.40037982427328e-06 -2.03070565618503e-06 1.47762647324674e-09 5.59372467170169e-05 2281 2278 0 12 16 2279 2309 0 52 15 0 0 0 0 0 17 46 0 637 0 46 49 0 0 2042 +376 413 0.999999154505798 0.000408997614801207 0.00123438593638608 -0.00670777433771799 -0.000412041125727123 0.999996873638098 0.00246636091059797 0.00357944500124981 -0.00123337334151925 -0.00246686744307493 0.999996196670377 -0.0103011682573109 4.77864123622695e-05 3.53413106534131e-05 -8.2562517929512e-06 1.47229525669212e-05 -4.93305083840274e-07 3.21321523900558e-05 3.53413106534131e-05 4.57309815776851e-05 -1.09301384928415e-05 2.05189290263498e-05 1.22270423571914e-06 3.24986924781332e-05 -8.2562517929512e-06 -1.09301384928415e-05 1.40154817850226e-05 -6.37626084909384e-07 -1.94639047957956e-06 -6.25251952945421e-06 1.47229525669212e-05 2.05189290263498e-05 -6.37626084909384e-07 6.20326651162635e-05 -1.79197087797291e-05 1.29506311953717e-05 -4.93305083840274e-07 1.22270423571914e-06 -1.94639047957956e-06 -1.79197087797291e-05 5.87697196625557e-05 5.07089722909868e-06 3.21321523900558e-05 3.24986924781332e-05 -6.25251952945421e-06 1.29506311953717e-05 5.07089722909868e-06 6.68031843900142e-05 2281 2276 0 16 11 2269 2297 0 47 4 0 0 0 0 0 16 49 0 606 0 41 46 0 0 2234 +376 418 0.999999610413734 0.000453445446616096 0.000757337181641559 -0.00564354837458895 -0.000453820577547878 0.99999977439682 0.000495230443379703 0.00322777466229322 -0.000757112450794306 -0.000495573945641895 0.999999590593517 -0.00700505050720467 3.18586939135292e-05 2.46690004711254e-05 -1.01826826039542e-05 5.86387838095536e-06 7.48238108779706e-06 1.94444162048473e-05 2.46690004711254e-05 2.78000471490396e-05 -1.0883276844128e-05 6.71803110468222e-06 5.8345281426144e-06 1.77110066280253e-05 -1.01826826039542e-05 -1.0883276844128e-05 1.55791108467829e-05 -4.87114227474194e-06 -2.5742087723636e-06 -4.10250245467576e-06 5.86387838095536e-06 6.71803110468222e-06 -4.87114227474194e-06 3.8452082731012e-05 -4.68299558711055e-06 3.53209142596539e-06 7.48238108779706e-06 5.8345281426144e-06 -2.5742087723636e-06 -4.68299558711055e-06 4.28494895855473e-05 6.88389160301777e-06 1.94444162048473e-05 1.77110066280253e-05 -4.10250245467576e-06 3.53209142596539e-06 6.88389160301777e-06 5.37639179930063e-05 2252 2250 0 15 13 2233 2262 0 40 3 0 0 0 0 0 15 48 0 623 0 56 63 0 0 2199 +376 379 0.999999922456693 -0.000218869754325384 0.000327387597541764 -0.00531236158156447 0.000219278958462628 0.999999194215437 -0.00125039402400134 0.00218351199356032 -0.000327113660305049 0.00125046571625306 0.999999164665724 0.00107738690553561 2.88877103470675e-05 2.16583345768377e-05 -8.87810264098421e-06 7.1609771682269e-06 9.577494391679e-06 1.78378382620539e-05 2.16583345768377e-05 2.34462570865197e-05 -1.02215348125597e-05 4.97382456648469e-06 9.47622933685252e-06 1.91811188983266e-05 -8.87810264098421e-06 -1.02215348125597e-05 1.22120468891324e-05 -5.94732707267466e-07 -3.20415860235977e-06 -5.73727478758283e-06 7.1609771682269e-06 4.97382456648469e-06 -5.94732707267466e-07 2.61516740209772e-05 -1.29092197953854e-07 5.49710758930807e-06 9.577494391679e-06 9.47622933685252e-06 -3.20415860235977e-06 -1.29092197953854e-07 3.16778829604872e-05 7.98836934113553e-06 1.78378382620539e-05 1.91811188983266e-05 -5.73727478758283e-06 5.49710758930807e-06 7.98836934113553e-06 3.32663646969733e-05 3281 3258 0 11 57 3268 3313 0 50 33 0 0 0 0 0 16 48 0 660 0 59 34 0 0 2727 +376 427 0.999968348356796 -0.000334070052411561 0.00794925668106509 0.00153665804757536 0.000315257487873704 0.999997147260465 0.00236771696973472 0.000824121487734845 -0.00795002498723846 -0.00236513596491025 0.99996560102564 -0.00992702172190388 4.64280073232582e-05 2.34678636406863e-05 -9.79409314183734e-06 7.27063478863455e-06 6.20729397955636e-06 2.55251181051134e-05 2.34678636406863e-05 3.36591252703277e-05 -9.31003273336102e-06 9.15064119187882e-06 4.76701260135719e-06 1.62429069257418e-05 -9.79409314183734e-06 -9.31003273336102e-06 1.45683163684653e-05 -1.78743051742064e-06 -3.61504996160383e-06 -4.13393100686989e-06 7.27063478863455e-06 9.15064119187882e-06 -1.78743051742064e-06 4.3342753476278e-05 -8.21353116967593e-06 4.20513678978904e-06 6.20729397955636e-06 4.76701260135719e-06 -3.61504996160383e-06 -8.21353116967593e-06 5.07139975448019e-05 5.23228058430782e-06 2.55251181051134e-05 1.62429069257418e-05 -4.13393100686989e-06 4.20513678978904e-06 5.23228058430782e-06 5.55951962740495e-05 2571 2569 0 13 17 2567 2590 0 38 13 0 0 0 0 0 14 45 0 656 0 53 58 0 0 2415 +376 424 0.999999988529247 0.00011126239340932 -0.000102772495118914 -0.00028420436916509 -0.000111310297021549 0.999999885122079 -0.000466225101897099 -0.00582742192553255 0.000102720609991919 0.000466236536186104 0.999999886035978 -0.00769883454308841 3.42510279372841e-05 2.57358725035424e-05 -1.05330701976546e-05 1.15983856189239e-05 8.10018830595443e-06 2.04230441266912e-05 2.57358725035424e-05 2.87076191358029e-05 -1.13469095092796e-05 1.10153853173937e-05 7.4775990038916e-06 1.72515315632739e-05 -1.05330701976546e-05 -1.13469095092796e-05 1.54831850788035e-05 -3.01664038920584e-06 -5.41028766809422e-06 -3.43187781333102e-06 1.15983856189239e-05 1.10153853173937e-05 -3.01664038920584e-06 3.893844880267e-05 -3.40012315996453e-06 6.74018891333233e-06 8.10018830595443e-06 7.4775990038916e-06 -5.41028766809422e-06 -3.40012315996453e-06 5.14964477129656e-05 5.10964777210757e-06 2.04230441266912e-05 1.72515315632739e-05 -3.43187781333102e-06 6.74018891333233e-06 5.10964777210757e-06 5.92867426363654e-05 2534 2531 0 10 15 2533 2559 0 41 13 0 0 0 0 0 11 42 0 631 0 45 49 0 0 2216 +376 426 0.999999492495804 0.000287589482341942 0.000965557053973283 -0.00350583258454301 -0.000286358426256809 0.999999146357329 -0.00127486605738747 0.00100793718404444 -0.00096592286780208 0.00127458891498916 0.999998721207238 -0.00836811165965631 3.79849139895082e-05 2.56727517935455e-05 -8.64116255176504e-06 9.2373222927337e-06 7.8170814206785e-06 2.09440194219111e-05 2.56727517935455e-05 3.34474872884657e-05 -9.85379106478658e-06 1.39056896857566e-05 4.25068193795859e-06 2.41613491793022e-05 -8.64116255176504e-06 -9.85379106478658e-06 1.43726388462528e-05 -1.30104735162869e-06 -3.29225268859031e-06 -4.83668159533587e-06 9.2373222927337e-06 1.39056896857566e-05 -1.30104735162869e-06 5.16483917035708e-05 -9.1173455117784e-06 9.68698811985842e-06 7.8170814206785e-06 4.25068193795859e-06 -3.29225268859031e-06 -9.1173455117784e-06 4.45782761486387e-05 1.59528648850847e-06 2.09440194219111e-05 2.41613491793022e-05 -4.83668159533587e-06 9.68698811985842e-06 1.59528648850847e-06 6.51627218582976e-05 2207 2206 0 22 17 2191 2212 0 39 6 0 0 0 0 0 15 45 0 637 0 59 68 0 0 2212 +376 423 0.999999869150958 6.93077089985044e-05 -0.000506847618573834 -0.0111581058639252 -6.89573356398705e-05 0.999999758699257 0.000691264286925848 0.00809044628953056 0.000506895406215166 -0.000691229245613226 0.999999632629521 -0.0112823024644929 4.86872629617064e-05 3.32336151293234e-05 -1.17697683769709e-05 1.41747107415237e-05 5.10821223931009e-06 2.83019591699603e-05 3.32336151293234e-05 3.87905659170222e-05 -1.14928721046876e-05 1.04560179925731e-05 3.6574132255616e-06 2.45327021796685e-05 -1.17697683769709e-05 -1.14928721046876e-05 1.58865046475387e-05 -3.53610583220517e-06 -3.14159440009082e-06 -4.65504868528506e-06 1.41747107415237e-05 1.04560179925731e-05 -3.53610583220517e-06 5.99049271683622e-05 -2.12345779526664e-05 6.31122706121225e-06 5.10821223931009e-06 3.6574132255616e-06 -3.14159440009082e-06 -2.12345779526664e-05 5.40412532361406e-05 -4.88018506250049e-08 2.83019591699603e-05 2.45327021796685e-05 -4.65504868528506e-06 6.31122706121225e-06 -4.88018506250049e-08 6.1279159252537e-05 2015 2011 0 11 12 2001 2033 0 46 2 0 0 0 0 0 17 48 0 619 0 50 59 0 0 2234 +376 415 0.999987901863525 -0.000107226749978177 0.00491778700331248 -0.00234411771231318 9.07677403705428e-05 0.999994394882536 0.00334693363062076 0.00179852750125224 -0.00491811831935427 -0.00334644676254701 0.999982306546602 -0.0111774884065031 4.75719648295194e-05 2.66334433543847e-05 -1.00773206268212e-05 1.34807018376446e-05 3.56235727559525e-06 2.42975151642597e-05 2.66334433543847e-05 3.33514252183469e-05 -1.01120733306287e-05 8.86401887889499e-06 1.02807795673423e-05 2.1429031568132e-05 -1.00773206268212e-05 -1.01120733306287e-05 1.31976333547703e-05 -9.40691196289358e-07 -1.10939518693584e-06 -4.99251809931834e-06 1.34807018376446e-05 8.86401887889499e-06 -9.40691196289358e-07 4.83913572888927e-05 -1.66487138769957e-05 1.30007435676103e-05 3.56235727559525e-06 1.02807795673423e-05 -1.10939518693584e-06 -1.66487138769957e-05 4.6566365620238e-05 4.21036059205501e-06 2.42975151642597e-05 2.1429031568132e-05 -4.99251809931834e-06 1.30007435676103e-05 4.21036059205501e-06 5.41322818573582e-05 2571 2569 0 17 14 2564 2590 0 39 11 0 0 0 0 0 14 46 0 589 0 50 54 0 0 2249 +376 416 0.999996444283921 0.000781347668478131 0.00254968926265953 -0.0153885743546127 -0.00078796644549249 0.999996320085065 0.00259594399179828 0.0149082910509953 -0.00254765154523445 -0.0025979438309439 0.999993380057816 -0.00964632064680126 4.56077408855007e-05 1.96342024527822e-05 -1.14710220773781e-05 5.70605957350947e-06 1.00621235152664e-05 2.15199586467173e-05 1.96342024527822e-05 3.31667454023196e-05 -1.04225230434723e-05 7.67334315692706e-06 1.39749880198807e-05 1.69916601960553e-05 -1.14710220773781e-05 -1.04225230434723e-05 1.43485992390327e-05 -2.08669531384215e-06 -3.43151860260684e-06 -6.19454406341536e-06 5.70605957350947e-06 7.67334315692706e-06 -2.08669531384215e-06 7.56715699635508e-05 -3.15216227904108e-05 2.24639227094982e-07 1.00621235152664e-05 1.39749880198807e-05 -3.43151860260684e-06 -3.15216227904108e-05 6.72797459084091e-05 1.12663562747711e-05 2.15199586467173e-05 1.69916601960553e-05 -6.19454406341536e-06 2.24639227094982e-07 1.12663562747711e-05 5.688781688386e-05 2372 2370 0 17 12 2369 2405 0 43 12 0 0 0 0 0 19 49 0 617 0 19 20 0 0 2220 +376 417 0.999999764946961 0.000556366961497948 0.000400701668906766 -0.0070835580167513 -0.000556269530500548 0.999999815703767 -0.00024322138256985 0.0054888836740285 -0.00040083691540055 0.000242998427270691 0.99999989014076 -0.00761987072821466 3.87792858126822e-05 2.97322444801904e-05 -7.98924940763046e-06 4.80103014661992e-06 9.93264479899377e-06 2.68417344940015e-05 2.97322444801904e-05 3.23004306148456e-05 -9.09044167871325e-06 3.60190393776005e-06 9.63712792500946e-06 2.51553903745409e-05 -7.98924940763046e-06 -9.09044167871325e-06 1.22529081038945e-05 1.03296212275439e-06 -2.24058941010989e-06 -4.70493623989248e-06 4.80103014661992e-06 3.60190393776005e-06 1.03296212275439e-06 3.56960040140207e-05 -8.41308434536861e-06 6.1285920825431e-06 9.93264479899377e-06 9.63712792500946e-06 -2.24058941010989e-06 -8.41308434536861e-06 4.55268999725502e-05 7.77339566860267e-06 2.68417344940015e-05 2.51553903745409e-05 -4.70493623989248e-06 6.1285920825431e-06 7.77339566860267e-06 5.9523392507115e-05 3190 3185 0 6 13 3197 3235 0 41 11 0 0 0 0 0 12 46 0 609 0 15 18 0 0 2318 +376 414 0.99999495463834 0.000506259319640005 0.0031359845926038 -0.0106999590874739 -0.00051183158063405 0.999998291338547 0.00177633004241622 0.00996983750774604 -0.00313507995062908 -0.00177792617613961 0.999993505105016 -0.00708108827652187 3.47826623464215e-05 2.64615273746065e-05 -9.57844216395141e-06 2.04131473386382e-06 1.52710886965275e-05 2.62232499400179e-05 2.64615273746065e-05 3.99498172376971e-05 -1.0483770316629e-05 1.0635782619758e-05 1.44563096012822e-05 2.76594226602139e-05 -9.57844216395141e-06 -1.0483770316629e-05 1.27344326684338e-05 -1.56227795132932e-06 -3.42749187997005e-06 -5.31022406634719e-06 2.04131473386382e-06 1.0635782619758e-05 -1.56227795132932e-06 5.87037251518224e-05 -7.33611507348999e-06 2.51114754940016e-06 1.52710886965275e-05 1.44563096012822e-05 -3.42749187997005e-06 -7.33611507348999e-06 4.1046531208211e-05 1.39796727516969e-05 2.62232499400179e-05 2.76594226602139e-05 -5.31022406634719e-06 2.51114754940016e-06 1.39796727516969e-05 5.92710368524518e-05 2385 2388 0 11 11 2392 2437 0 49 9 0 0 0 0 0 17 47 0 609 0 12 15 0 0 2360 +376 419 0.999994027259416 0.000474197958502607 0.00342353352399912 -0.00544891861242332 -0.00048829957607493 0.99999139616456 0.00411936407456431 0.00869708577980608 -0.00342155067444557 -0.00412101118063977 0.999985655026026 -0.014518746863016 4.81790001534814e-05 2.29847594765811e-05 -1.14806226756904e-05 1.1885599921105e-05 6.14992511075189e-06 2.0220852242061e-05 2.29847594765811e-05 5.29502147541386e-05 -1.10452265338972e-05 1.82341795475775e-05 8.70467733693435e-06 3.1730576016102e-05 -1.14806226756904e-05 -1.10452265338972e-05 1.51302909822511e-05 -2.38706757524439e-06 -3.8175800678316e-06 -4.08490198972029e-06 1.1885599921105e-05 1.82341795475775e-05 -2.38706757524439e-06 4.80821966053871e-05 -1.17540072537997e-05 1.91196155139166e-05 6.14992511075189e-06 8.70467733693435e-06 -3.8175800678316e-06 -1.17540072537997e-05 5.65785418283622e-05 -5.62567325455762e-06 2.0220852242061e-05 3.1730576016102e-05 -4.08490198972029e-06 1.91196155139166e-05 -5.62567325455762e-06 6.97829421512014e-05 2613 2611 0 17 14 2607 2637 0 48 11 0 0 0 0 0 18 50 0 602 0 50 55 0 0 2222 +376 410 0.999995558264851 1.0867094343832e-05 0.00298049198545023 -0.00468343726052079 -2.01803574404219e-05 0.999995117822178 0.00312472791785315 0.00648792302780129 -0.00298044347744528 -0.00312477418603294 0.999990676328017 -0.00576000843727841 3.35256864397244e-05 2.485372354789e-05 -1.90976444757356e-06 1.48319601245057e-06 1.71352203810899e-06 1.90373257048348e-05 2.485372354789e-05 3.32858757096808e-05 -3.68456209306655e-06 1.08963510895815e-05 -2.08257296026184e-06 1.346758808948e-05 -1.90976444757356e-06 -3.68456209306655e-06 1.26781155868798e-05 7.19255238004323e-07 2.16609406963087e-06 -8.64807712005375e-07 1.48319601245057e-06 1.08963510895815e-05 7.19255238004323e-07 4.79320506813787e-05 -1.89145409766124e-05 -4.26678421712829e-06 1.71352203810899e-06 -2.08257296026184e-06 2.16609406963087e-06 -1.89145409766124e-05 3.96708316043059e-05 8.02497500865106e-06 1.90373257048348e-05 1.346758808948e-05 -8.64807712005375e-07 -4.26678421712829e-06 8.02497500865106e-06 4.97636030958551e-05 1661 1663 0 17 9 1661 1681 0 43 5 0 0 0 0 0 18 46 0 507 0 36 44 0 0 2258 +376 421 0.999998729992852 -0.000100619474526653 -0.00159056229201126 -0.00442774075908733 0.000102926307745177 0.999998943002563 0.00145031028805976 0.00210891090742388 0.00159041468133191 -0.00145047215685929 0.999997683353148 -0.0110623110237997 5.63034915944672e-05 4.36108533029031e-05 -1.25460928335421e-05 2.84931073985683e-05 -6.65190146906249e-06 3.79698667971135e-05 4.36108533029031e-05 4.43491723819967e-05 -1.12928803222264e-05 2.31893683085509e-05 -8.81365025685274e-06 3.3102196312786e-05 -1.25460928335421e-05 -1.12928803222264e-05 1.53940039066589e-05 -5.24538436531491e-06 -4.22978104747488e-06 -6.95591360600144e-06 2.84931073985683e-05 2.31893683085509e-05 -5.24538436531491e-06 6.26005761639063e-05 -2.25267412548673e-05 1.55259541233144e-05 -6.65190146906249e-06 -8.81365025685274e-06 -4.22978104747488e-06 -2.25267412548673e-05 6.09457675372613e-05 -6.74909914840092e-06 3.79698667971135e-05 3.3102196312786e-05 -6.95591360600144e-06 1.55259541233144e-05 -6.74909914840092e-06 6.74242806502688e-05 2210 2211 0 15 14 2205 2238 0 54 11 0 0 0 0 0 15 48 0 635 0 55 63 0 0 2336 +376 380 0.999999631205232 0.000358546390472211 -0.000780406231298639 -0.0108925625780106 -0.000357968921655816 0.999999662148898 0.000739973202425671 0.00757939701431801 0.000780671282358309 -0.000739693568350354 0.99999942170272 -0.00298609097388056 2.49805462277365e-05 1.82251413647235e-05 -6.438637349097e-06 6.01237342031127e-06 5.92086490442299e-06 1.63772338038652e-05 1.82251413647235e-05 2.29323190174138e-05 -7.91101267351078e-06 6.88770833413215e-06 4.46742866633663e-06 1.87993554867271e-05 -6.438637349097e-06 -7.91101267351078e-06 1.1330804577157e-05 -2.30105027042809e-06 -1.48278524403545e-06 -3.15582628834894e-06 6.01237342031127e-06 6.88770833413215e-06 -2.30105027042809e-06 3.31074441003858e-05 -3.21713301936117e-06 4.6929415433354e-06 5.92086490442299e-06 4.46742866633663e-06 -1.48278524403545e-06 -3.21713301936117e-06 3.15361717119631e-05 5.84085646558512e-06 1.63772338038652e-05 1.87993554867271e-05 -3.15582628834894e-06 4.6929415433354e-06 5.84085646558512e-06 3.3247746788557e-05 3033 3007 0 10 57 3014 3053 0 40 32 0 0 0 0 0 11 42 0 664 0 59 34 0 0 2733 +376 408 0.99999363244924 0.000378635606713925 0.00354847799100066 -0.00713891318792883 -0.000385617722988626 0.99999799078955 0.00196715933157708 0.00726557172807974 -0.00354772602479458 -0.00196851516159315 0.999991769260183 -0.00796293676006495 3.25219659451163e-05 1.82897693976686e-05 -1.23385939698487e-06 -1.39267417795182e-06 2.60573211695744e-06 1.89549760569884e-05 1.82897693976686e-05 3.16996697222685e-05 -8.82572904849128e-07 6.4327044405677e-06 1.81061387253515e-06 2.05522060331637e-05 -1.23385939698487e-06 -8.82572904849128e-07 9.5162077298776e-06 2.94039015379688e-06 4.70679924827287e-06 5.5825485387115e-07 -1.39267417795182e-06 6.4327044405677e-06 2.94039015379688e-06 4.73888543843289e-05 -1.79837692983126e-05 8.6357372138325e-06 2.60573211695744e-06 1.81061387253515e-06 4.70679924827287e-06 -1.79837692983126e-05 3.11733549982891e-05 1.13799794836866e-06 1.89549760569884e-05 2.05522060331637e-05 5.5825485387115e-07 8.6357372138325e-06 1.13799794836866e-06 5.08753966104699e-05 2911 2914 0 19 15 2910 2945 0 37 15 0 0 0 0 0 15 47 0 493 0 16 19 0 0 2314 +376 411 0.999979324974166 4.00179600829184e-05 0.00643024282386181 0.000871990809952908 -7.00935125623854e-05 0.999989060104251 0.00467704593907288 0.00337497761756178 -0.00642998531183798 -0.00467739995933342 0.999968388109599 -0.00819412853026697 4.27659886708208e-05 2.72468318259837e-05 -4.8847725986542e-06 6.06860744789187e-06 2.86866954781732e-06 1.99130251552672e-05 2.72468318259837e-05 4.51548097985496e-05 -4.84911102054273e-06 1.37506513788544e-05 3.91576243435727e-06 2.14152260239918e-05 -4.8847725986542e-06 -4.84911102054273e-06 1.10903102190286e-05 2.5596145914829e-06 2.4607736782864e-06 -1.44429907398152e-06 6.06860744789187e-06 1.37506513788544e-05 2.5596145914829e-06 4.01516089761075e-05 -1.47972375958206e-05 9.31417574145083e-06 2.86866954781732e-06 3.91576243435727e-06 2.4607736782864e-06 -1.47972375958206e-05 3.94302865715479e-05 3.48802236821109e-06 1.99130251552672e-05 2.14152260239918e-05 -1.44429907398152e-06 9.31417574145083e-06 3.48802236821109e-06 5.38180299852424e-05 1940 1941 0 20 11 1932 1963 0 45 9 0 0 0 0 0 19 51 0 538 0 49 57 0 0 2240 +377 427 0.999999286885715 0.000441821595348042 -0.00110951419056344 -0.0101711345027538 -0.000442812394152069 0.999999503309376 -0.000892915552818765 0.00700517573409248 0.00110911913010409 0.000893406222702999 0.999998985839524 -0.00521638466360682 4.54712190260291e-05 2.5137011401896e-05 -9.7693281475084e-06 2.90586644232161e-06 8.02186506784631e-06 2.08877319177919e-05 2.5137011401896e-05 3.92671707290554e-05 -9.39311850362956e-06 9.33662754065532e-06 6.63619390168075e-06 2.15422988208438e-05 -9.7693281475084e-06 -9.39311850362956e-06 1.47134375827731e-05 -1.8098884540876e-06 -3.34292145498871e-06 -3.2170858852171e-06 2.90586644232161e-06 9.33662754065532e-06 -1.8098884540876e-06 6.47622583454192e-05 -1.88034225554049e-05 7.81306525325253e-06 8.02186506784631e-06 6.63619390168075e-06 -3.34292145498871e-06 -1.88034225554049e-05 5.07869908077159e-05 1.23974465248082e-06 2.08877319177919e-05 2.15422988208438e-05 -3.2170858852171e-06 7.81306525325253e-06 1.23974465248082e-06 5.23962105766719e-05 2027 2025 0 17 17 2020 2047 0 49 12 0 0 0 0 0 12 42 0 635 0 101 121 0 0 2373 +376 409 0.999998480860087 4.07619527946868e-05 0.00174258887335505 -0.00745289241759211 -4.13875435587148e-05 0.999999934715158 0.000358966226205705 0.0038209372612501 -0.00174257412742604 -0.000359037802358684 0.999998417262381 -0.00548775919307412 2.20992593218233e-05 1.38605043754797e-05 -1.10814860831812e-06 1.86939747094883e-06 -6.93986134219095e-07 1.01907105187562e-05 1.38605043754797e-05 2.46882436006667e-05 -2.9173162019933e-06 7.15532317860734e-06 -8.64221557319951e-07 6.95876823962871e-06 -1.10814860831812e-06 -2.9173162019933e-06 1.0555939054899e-05 2.02655384492744e-06 3.11503692187141e-06 -1.26498142868115e-06 1.86939747094883e-06 7.15532317860734e-06 2.02655384492744e-06 6.66479771088421e-05 -3.10481363602914e-05 -7.6736341312557e-06 -6.93986134219095e-07 -8.64221557319951e-07 3.11503692187141e-06 -3.10481363602914e-05 4.40769368539489e-05 2.79571632331221e-06 1.01907105187562e-05 6.95876823962871e-06 -1.26498142868115e-06 -7.6736341312557e-06 2.79571632331221e-06 4.11843171762645e-05 1705 1706 0 22 10 1702 1731 0 45 8 0 0 0 0 0 22 52 0 515 0 39 42 0 0 2220 +376 422 0.999999107387359 0.000969021097732153 0.000919903579936197 -0.00798493900384398 -0.000969651404764403 0.999999295282445 0.000684989610946741 0.00840976024366302 -0.00091923916227926 -0.000685880985314889 0.999999342283102 -0.0118562770243815 3.67869485142295e-05 1.82614609034755e-05 -9.81251248137117e-06 5.09538653135716e-06 7.20380590265714e-06 1.23460275506367e-05 1.82614609034755e-05 2.94981439216147e-05 -8.97716011655747e-06 7.80407711646817e-06 4.39841670782798e-06 1.22075579753038e-05 -9.81251248137117e-06 -8.97716011655747e-06 1.46358820083776e-05 -2.54653823813893e-06 -4.79908597985865e-06 -3.5336363297806e-06 5.09538653135716e-06 7.80407711646817e-06 -2.54653823813893e-06 5.18151469809958e-05 -5.95326607138008e-06 7.13473498349257e-06 7.20380590265714e-06 4.39841670782798e-06 -4.79908597985865e-06 -5.95326607138008e-06 5.0179756525583e-05 -2.11035548773513e-06 1.23460275506367e-05 1.22075579753038e-05 -3.5336363297806e-06 7.13473498349257e-06 -2.11035548773513e-06 5.59487433745546e-05 2997 2999 0 17 14 2998 3042 0 54 11 0 0 0 0 0 14 48 0 614 0 16 18 0 0 2277 +377 428 0.999999720081265 0.000744206763257527 -7.74188962228754e-05 -0.01068483074792 -0.000744149868895782 0.999999454958593 0.000732341101471508 0.0125096225615159 7.79638672270978e-05 -0.000732283285214039 0.999999728841376 -0.00697077657980847 4.05503686940076e-05 2.30166327099119e-05 -1.26412248016249e-05 4.24630919089476e-06 1.08593394532053e-05 1.71547960924671e-05 2.30166327099119e-05 3.57221412190658e-05 -1.15569434580037e-05 6.23758912551443e-06 1.00312694983828e-05 1.87149385927228e-05 -1.26412248016249e-05 -1.15569434580037e-05 1.66416129246793e-05 -2.57238698595168e-06 -4.72312555632035e-06 -6.16550052878514e-06 4.24630919089476e-06 6.23758912551443e-06 -2.57238698595168e-06 7.04207369889545e-05 -2.58783031770116e-05 1.07601912480699e-05 1.08593394532053e-05 1.00312694983828e-05 -4.72312555632035e-06 -2.58783031770116e-05 6.93799183144395e-05 4.84109417306535e-06 1.71547960924671e-05 1.87149385927228e-05 -6.16550052878514e-06 1.07601912480699e-05 4.84109417306535e-06 5.69821030135025e-05 2589 2592 0 16 16 2588 2620 0 53 14 0 0 0 0 0 12 45 0 650 0 96 118 0 0 2304 +376 429 0.999955149634063 -0.00748528959145617 0.00580251325288967 -0.000453669266758779 0.00745354509134127 0.999957243053351 0.00547327422237968 0.00538752762027915 -0.00584323419770805 -0.00542977944985441 0.99996818654857 -0.0104342781085838 5.15356810882686e-05 3.44138609190357e-05 -5.57321229147025e-06 8.78445798232666e-06 -2.58285330986151e-06 2.4303006299622e-05 3.44138609190357e-05 6.57456281868928e-05 -4.31725277021447e-06 2.3303998822336e-05 -1.30222351426065e-05 2.33173825482908e-05 -5.57321229147025e-06 -4.31725277021447e-06 1.29133630860593e-05 2.01291762181648e-06 -5.29894862509103e-07 -2.69091234090584e-06 8.78445798232666e-06 2.3303998822336e-05 2.01291762181648e-06 6.52922239944254e-05 -3.06407202876637e-05 9.07645961360174e-06 -2.58285330986151e-06 -1.30222351426065e-05 -5.29894862509103e-07 -3.06407202876637e-05 6.06546451586279e-05 -6.70269416363138e-06 2.4303006299622e-05 2.33173825482908e-05 -2.69091234090584e-06 9.07645961360174e-06 -6.70269416363138e-06 7.17106941063725e-05 1593 1591 0 7 24 1589 1610 0 36 17 0 0 0 0 0 27 58 0 612 0 50 57 0 0 2397 +377 413 0.999999825441393 -4.91008441937788e-05 -0.000588817705308853 -0.0116789713983187 4.9848780301443e-05 0.999999191943542 0.00127028633079667 0.0105657586370299 0.000588754857379694 -0.00127031546090169 0.999999019832694 -0.0137775124227207 6.26463789326685e-05 3.05965588481607e-05 -6.94976864845848e-06 6.33781321305582e-06 3.21124136944409e-06 3.84764571164198e-05 3.05965588481607e-05 3.91762707583831e-05 -8.15613872975135e-06 4.06518582068416e-06 1.63402737137643e-05 3.10117753232433e-05 -6.94976864845848e-06 -8.15613872975135e-06 1.21972823354114e-05 7.31700258135624e-07 1.62933519824268e-06 -4.17019538592733e-06 6.33781321305582e-06 4.06518582068416e-06 7.31700258135624e-07 4.72213863591815e-05 -1.69406247168908e-05 3.52440487803421e-06 3.21124136944409e-06 1.63402737137643e-05 1.62933519824268e-06 -1.69406247168908e-05 5.9310829965508e-05 1.4971411106943e-05 3.84764571164198e-05 3.10117753232433e-05 -4.17019538592733e-06 3.52440487803421e-06 1.4971411106943e-05 7.73937305550145e-05 1825 1827 0 13 11 1826 1856 0 48 7 0 0 0 0 0 17 49 0 596 0 35 39 0 0 2326 +376 407 0.999994630385059 0.00036303631994491 0.0032569012389349 -0.00675097953004346 -0.000371345649394121 0.999996677098916 0.00255105733650101 0.0055377205600348 -0.00325596429010683 -0.00255225307441101 0.999991442313776 -0.00575008826917982 3.90780218069228e-05 1.73004003361255e-05 -2.57717825656089e-06 -6.78171774765143e-07 -7.62174008740451e-07 1.8586819565989e-05 1.73004003361255e-05 3.7137996104638e-05 -2.91084390867803e-06 1.07994868239384e-05 -5.19471235030889e-06 1.34729524725825e-05 -2.57717825656089e-06 -2.91084390867803e-06 1.17994136404797e-05 7.81908526624617e-07 4.82297964510613e-06 1.46231482991356e-07 -6.78171774765143e-07 1.07994868239384e-05 7.81908526624617e-07 6.48832137299031e-05 -2.56171795250503e-05 8.52040741330181e-07 -7.62174008740451e-07 -5.19471235030889e-06 4.82297964510613e-06 -2.56171795250503e-05 3.91644849946444e-05 -5.66487321205876e-07 1.8586819565989e-05 1.34729524725825e-05 1.46231482991356e-07 8.52040741330181e-07 -5.66487321205876e-07 5.44531961736528e-05 2286 2286 0 13 17 2285 2309 0 37 13 0 0 0 0 0 16 46 0 494 0 47 49 0 0 2300 +377 411 0.999999447863807 -0.000454451029357727 0.000947494771975148 -0.00648540632738245 0.000452065107648136 0.999996730590603 0.00251683238279179 0.00695363232546876 -0.000948635451293917 -0.00251640266383145 0.999996383897669 -0.00681511019182693 3.51070229139516e-05 2.28790843376233e-05 -2.21415955105646e-06 8.45452470630086e-06 -5.94104604330584e-07 3.16993916416715e-05 2.28790843376233e-05 3.5666118738907e-05 -2.93493411676324e-06 1.49529269045223e-05 -3.54674020590483e-06 3.21565165285115e-05 -2.21415955105646e-06 -2.93493411676324e-06 1.12485174266407e-05 5.54687596026507e-06 8.81462996826749e-07 6.63294061265272e-07 8.45452470630086e-06 1.49529269045223e-05 5.54687596026507e-06 7.69932046642465e-05 -4.08816092072433e-05 1.88604307070093e-05 -5.94104604330584e-07 -3.54674020590483e-06 8.81462996826749e-07 -4.08816092072433e-05 6.47722803693668e-05 -4.83336653369672e-06 3.16993916416715e-05 3.21565165285115e-05 6.63294061265272e-07 1.88604307070093e-05 -4.83336653369672e-06 7.58237209232776e-05 2098 2098 0 13 11 2096 2134 0 56 7 0 0 0 0 0 21 53 0 533 0 11 15 0 0 2270 +377 426 0.999997914557766 0.000681037682834599 0.00192537471525502 -0.00618358542484672 -0.000683672700886282 0.999998830244667 0.00136824739534974 0.00934123919463103 -0.001924440635002 -0.00136956086808063 0.999997210411745 -0.00939033023474568 2.73463775385704e-05 1.76432743330561e-05 -8.79232572127449e-06 8.22281793816964e-06 6.95460754802084e-06 1.85789165372553e-05 1.76432743330561e-05 2.33220786074266e-05 -1.0375492301057e-05 5.73122169814781e-06 1.0578589995391e-05 1.40341221007336e-05 -8.79232572127449e-06 -1.0375492301057e-05 1.34913386554257e-05 -2.08067351617014e-06 -6.02731003370706e-06 -4.54050675309842e-06 8.22281793816964e-06 5.73122169814781e-06 -2.08067351617014e-06 3.99469477804933e-05 -7.28574551355195e-06 8.93453362761239e-06 6.95460754802084e-06 1.0578589995391e-05 -6.02731003370706e-06 -7.28574551355195e-06 5.71243278124089e-05 7.74688075868471e-06 1.85789165372553e-05 1.40341221007336e-05 -4.54050675309842e-06 8.93453362761239e-06 7.74688075868471e-06 5.6702789031478e-05 2751 2753 0 18 17 2747 2777 0 43 12 0 0 0 0 0 18 48 0 641 0 15 19 0 0 2151 +377 412 0.999999888562856 0.000232609904614661 0.000410812497423138 -0.00851774558781401 -0.000232597679454312 0.99999997250496 -2.98060181429644e-05 0.00695421876302616 -0.000410819419302869 2.97104607878754e-05 0.999999915172343 -0.00635951639428991 3.15156671885701e-05 2.05339593342277e-05 -6.26113284132009e-06 8.04656870095162e-06 7.13201781522154e-06 2.08756858899033e-05 2.05339593342277e-05 3.31632384414259e-05 -7.20279615954179e-06 5.96610683872377e-06 1.23270935004787e-05 2.68251354909638e-05 -6.26113284132009e-06 -7.20279615954179e-06 1.34682162785252e-05 -1.29365130450461e-06 -1.08345336301652e-06 -3.91622737271162e-06 8.04656870095162e-06 5.96610683872377e-06 -1.29365130450461e-06 4.15481198418107e-05 -8.18254778669775e-06 8.19471545439766e-06 7.13201781522154e-06 1.23270935004787e-05 -1.08345336301652e-06 -8.18254778669775e-06 4.29984941012874e-05 1.2635818384596e-05 2.08756858899033e-05 2.68251354909638e-05 -3.91622737271162e-06 8.19471545439766e-06 1.2635818384596e-05 5.89099759458972e-05 2928 2925 0 11 9 2931 2964 0 50 9 0 0 0 0 0 17 48 0 564 0 12 17 0 0 2252 +377 409 0.999999727863375 0.00072606941137495 -0.000130753149276084 -0.0183655299359155 -0.000726467442025152 0.999995022849117 -0.00307026416601551 0.0138940604468626 0.000128523273602147 0.00307035831839007 0.999995278179635 -0.00785729686064022 5.01825407292365e-05 2.66388564731673e-05 -2.84737680922529e-06 1.64188423166226e-06 4.33326419193534e-06 2.64019087761619e-05 2.66388564731673e-05 5.8455353293994e-05 -1.45426872933579e-06 1.14564602523978e-05 3.86554458721973e-06 4.16641585368713e-05 -2.84737680922529e-06 -1.45426872933579e-06 1.05827327069291e-05 -3.0423488425169e-07 4.60937468821202e-06 -2.8729041164595e-07 1.64188423166226e-06 1.14564602523978e-05 -3.0423488425169e-07 5.05898453936094e-05 -1.0425283222487e-05 8.2692242601716e-06 4.33326419193534e-06 3.86554458721973e-06 4.60937468821202e-06 -1.0425283222487e-05 3.50222281106604e-05 4.62728292851362e-07 2.64019087761619e-05 4.16641585368713e-05 -2.8729041164595e-07 8.2692242601716e-06 4.62728292851362e-07 7.50969271254986e-05 2420 2418 0 8 10 2425 2455 0 53 8 0 0 0 0 0 22 53 0 500 0 39 44 0 0 2279 +377 414 0.999999862831774 0.000443622285645334 0.000278452332997172 -0.0165018642655038 -0.000443797029734787 0.999999704451234 0.00062780701005071 0.0148952688340981 -0.000278173741520186 -0.000627930500253843 0.9999997641613 -0.0066015890344896 4.55580810971145e-05 2.91910799570271e-05 -1.05016115718505e-05 2.12427610165264e-06 5.81945072399769e-06 2.36168788660341e-05 2.91910799570271e-05 5.0269108226939e-05 -9.97246220419228e-06 2.97644054298101e-06 1.43746644700582e-05 2.96750699834513e-05 -1.05016115718505e-05 -9.97246220419228e-06 1.56692692172996e-05 3.59132692278322e-07 -2.53593470887837e-06 -5.6526896258469e-06 2.12427610165264e-06 2.97644054298101e-06 3.59132692278322e-07 5.77116728601436e-05 -3.31196513422878e-05 -6.83103902743384e-06 5.81945072399769e-06 1.43746644700582e-05 -2.53593470887837e-06 -3.31196513422878e-05 7.3343256577919e-05 1.16106442197383e-05 2.36168788660341e-05 2.96750699834513e-05 -5.6526896258469e-06 -6.83103902743384e-06 1.16106442197383e-05 6.01258596958216e-05 2012 2012 0 11 12 2004 2033 0 48 4 0 0 0 0 0 21 51 0 609 0 50 54 0 0 2376 +377 421 0.999999443619945 0.000350922868666638 0.000994792913812521 -0.00463209953416426 -0.000350676248405597 0.999999907742541 -0.000248074741620808 0.00753286202829379 -0.000994879877135429 0.000247725753350013 0.999999474422852 -0.0108811766508406 3.55026714908079e-05 1.06738172859679e-05 -8.38708755060818e-06 1.72100245125746e-06 -4.84154453891198e-07 1.64239959532968e-05 1.06738172859679e-05 2.52389176026397e-05 -7.22763541074144e-06 5.57602356305538e-06 7.15472786401951e-06 1.2565960592868e-05 -8.38708755060818e-06 -7.22763541074144e-06 1.29678281742936e-05 7.98396603295692e-07 -2.43412827595822e-06 -1.7728088723591e-06 1.72100245125746e-06 5.57602356305538e-06 7.98396603295692e-07 4.16170666130563e-05 -2.8052517856489e-06 3.16243484380699e-08 -4.84154453891198e-07 7.15472786401951e-06 -2.43412827595822e-06 -2.8052517856489e-06 4.89389192902709e-05 -1.13057023250664e-06 1.64239959532968e-05 1.2565960592868e-05 -1.7728088723591e-06 3.16243484380699e-08 -1.13057023250664e-06 6.13596656233445e-05 2746 2749 0 17 14 2743 2780 0 53 11 0 0 0 0 0 19 52 0 620 0 15 22 0 0 2359 +377 379 0.999992063422516 8.80587588766179e-05 -0.00398313163651586 -0.00812002684440537 -9.57606991041622e-05 0.999998126221384 -0.00193349000754887 0.00256407184101612 0.00398295391227861 0.00193385608972575 0.99999019809134 0.000835233248754444 4.60480386082009e-05 2.39649318143153e-05 -6.68889380019197e-06 1.06795198092609e-05 -3.11463357990756e-06 1.1403059892983e-05 2.39649318143153e-05 4.20474474195756e-05 -9.615244308347e-06 1.64855435313577e-05 5.75782044844268e-06 1.5332268140493e-05 -6.68889380019197e-06 -9.615244308347e-06 1.22457064815725e-05 -1.39646631106647e-06 -2.12814508187484e-06 -2.97740492253168e-06 1.06795198092609e-05 1.64855435313577e-05 -1.39646631106647e-06 4.1312817619636e-05 -1.2597648069374e-05 -3.92373748005795e-06 -3.11463357990756e-06 5.75782044844268e-06 -2.12814508187484e-06 -1.2597648069374e-05 4.72728835134728e-05 5.33991145023716e-06 1.1403059892983e-05 1.5332268140493e-05 -2.97740492253168e-06 -3.92373748005795e-06 5.33991145023716e-06 3.92968148715972e-05 2447 2422 0 21 63 2383 2412 0 53 7 0 0 0 0 0 19 51 0 642 0 104 82 0 0 2746 +377 415 0.9999942789806 0.000420402781498901 -0.00335637714983279 -0.0135823523642514 -0.000426687329521866 0.999998156918183 -0.0018719236524152 0.00690042926873289 0.00335558400184486 0.0018733450667066 0.999992615289867 -0.00524556640243912 4.15408102605526e-05 2.69847050331893e-05 -8.80532228908915e-06 8.63152924754329e-06 7.21507870804747e-06 2.21449590879516e-05 2.69847050331893e-05 4.19971738035804e-05 -9.8549698757055e-06 9.56919969823968e-06 1.29565239539873e-05 2.77686842869759e-05 -8.80532228908915e-06 -9.8549698757055e-06 1.40640777777403e-05 1.38525187625629e-06 -3.21474302005738e-06 -4.290059019288e-06 8.63152924754329e-06 9.56919969823968e-06 1.38525187625629e-06 8.33218567724245e-05 -4.94582197771968e-05 1.18545756140633e-05 7.21507870804747e-06 1.29565239539873e-05 -3.21474302005738e-06 -4.94582197771968e-05 7.7841045764211e-05 2.51005572108229e-06 2.21449590879516e-05 2.77686842869759e-05 -4.290059019288e-06 1.18545756140633e-05 2.51005572108229e-06 6.17263829056064e-05 2019 2024 0 21 14 2014 2042 0 48 8 0 0 0 0 0 12 43 0 575 0 98 116 0 0 2260 +377 418 0.999998403618152 0.000456023321157055 0.00172765849572439 -0.00861632957414511 -0.000461495307743957 0.999994874716588 0.00316821126772443 0.0101879611441654 -0.00172620486276053 -0.00316900351633863 0.999993488795545 -0.0102181627776984 3.21339902356068e-05 2.03409948517409e-05 -9.77722650594287e-06 4.66417665826336e-06 1.28138316155277e-05 2.32932546178091e-05 2.03409948517409e-05 2.61403041514177e-05 -9.45752561180785e-06 6.83650095126822e-06 1.05317504041101e-05 1.726892034163e-05 -9.77722650594287e-06 -9.45752561180785e-06 1.42372220471813e-05 -2.87831339263274e-06 -3.75849624698955e-06 -5.51727598092504e-06 4.66417665826336e-06 6.83650095126822e-06 -2.87831339263274e-06 4.86813395775233e-05 -1.56474620931545e-05 7.45716818407286e-06 1.28138316155277e-05 1.05317504041101e-05 -3.75849624698955e-06 -1.56474620931545e-05 5.38170031670159e-05 8.04259010559316e-06 2.32932546178091e-05 1.726892034163e-05 -5.51727598092504e-06 7.45716818407286e-06 8.04259010559316e-06 6.17564905258944e-05 2769 2771 0 12 13 2768 2804 0 45 10 0 0 0 0 0 17 49 0 617 0 15 17 0 0 2215 +377 416 0.999997054842589 0.00100156997393806 -0.00221069304399184 -0.02234877708084 -0.00100756404573987 0.999995815053745 -0.00271195311348142 0.0180392174431473 0.00220796758155108 0.00271417254117991 0.999993879054555 -0.0070547986344616 4.18263450238108e-05 2.21095454333761e-05 -1.09939968754429e-05 6.04518919785489e-06 -8.98598878602804e-08 1.75975541848071e-05 2.21095454333761e-05 5.01689338065785e-05 -1.36004966005723e-05 1.65744094780831e-05 8.36086829647908e-06 2.12465827410948e-05 -1.09939968754429e-05 -1.36004966005723e-05 1.71818156879978e-05 -2.05919671417841e-06 -4.40062291170845e-06 -5.15110384650972e-06 6.04518919785489e-06 1.65744094780831e-05 -2.05919671417841e-06 6.98750324840893e-05 -4.13261265595869e-05 4.32566220117124e-06 -8.98598878602804e-08 8.36086829647908e-06 -4.40062291170845e-06 -4.13261265595869e-05 7.94051407017816e-05 2.87103869817267e-06 1.75975541848071e-05 2.12465827410948e-05 -5.15110384650972e-06 4.32566220117124e-06 2.87103869817267e-06 4.93695164049528e-05 1981 1985 0 13 12 1986 2012 0 48 10 0 0 0 0 0 17 48 0 604 0 48 52 0 0 2264 +377 425 0.999998162793132 -0.000388115527006586 0.00187717252747022 -0.00961246295451908 0.000386257390516616 0.99999943523319 0.000990120461882628 0.00800115033250205 -0.00187755574843035 -0.000989393571064506 0.999997747939851 -0.0103858118785585 4.63175505933985e-05 1.51412039724226e-05 -6.17677908093811e-06 1.79869202035206e-06 1.36467001462425e-06 9.32742728972754e-06 1.51412039724226e-05 2.80412058749892e-05 -7.75342430225382e-06 7.00872585063079e-06 7.37023435942329e-06 1.03402094887643e-05 -6.17677908093811e-06 -7.75342430225382e-06 1.19887233272468e-05 -1.33934221152008e-06 2.31055737089012e-07 -2.17819836599425e-06 1.79869202035206e-06 7.00872585063079e-06 -1.33934221152008e-06 5.2366288913509e-05 -1.99435131213805e-05 -2.49026237591216e-06 1.36467001462425e-06 7.37023435942329e-06 2.31055737089012e-07 -1.99435131213805e-05 6.01342552167535e-05 1.0967666029931e-05 9.32742728972754e-06 1.03402094887643e-05 -2.17819836599425e-06 -2.49026237591216e-06 1.0967666029931e-05 5.62390834822979e-05 2669 2665 0 18 16 2664 2689 0 49 14 0 0 0 0 0 16 47 0 628 0 42 47 0 0 2141 +377 380 0.999998887371406 0.000564543646311953 -0.00138077746996537 -0.0145263830841879 -0.000566331623111909 0.999999001305375 -0.00129485780931034 0.0110388283700936 0.00138004508724121 0.00129563834656023 0.999998208396811 -0.00158129606305554 3.32787749437753e-05 1.1569107252783e-05 -7.26041794201132e-06 1.17325814581371e-06 3.83603357677692e-06 3.38033498114975e-06 1.1569107252783e-05 3.02031923989091e-05 -8.35560204323182e-06 1.05862154940143e-05 6.69240029553466e-06 1.41773479197912e-05 -7.26041794201132e-06 -8.35560204323182e-06 1.15343524931595e-05 3.87005948206364e-07 -2.01799177304188e-06 -4.187206754717e-06 1.17325814581371e-06 1.05862154940143e-05 3.87005948206364e-07 3.89459274140391e-05 -7.67148128992281e-06 5.14682469139987e-06 3.83603357677692e-06 6.69240029553466e-06 -2.01799177304188e-06 -7.67148128992281e-06 4.5843559130978e-05 1.19473646112725e-05 3.38033498114975e-06 1.41773479197912e-05 -4.187206754717e-06 5.14682469139987e-06 1.19473646112725e-05 3.52465479396616e-05 1578 1556 0 11 63 1520 1546 0 46 7 0 0 0 0 0 20 50 0 675 0 106 84 0 0 2828 +377 424 0.999998263519404 -2.38024146355801e-05 0.00186343543545299 -0.00818562475558623 2.06669561787116e-05 0.999998584174163 0.00168262370936457 0.00932150247536193 -0.00186347284766016 -0.00168258227598267 0.999996848187948 -0.0116822000870491 2.92646895894561e-05 1.48874043688934e-05 -7.94228534036365e-06 3.90585773792458e-06 4.35882776293472e-06 1.06704001210065e-05 1.48874043688934e-05 2.87959610766427e-05 -8.79654530229129e-06 7.17623570680224e-06 9.80736112251789e-06 1.08211291872968e-05 -7.94228534036365e-06 -8.79654530229129e-06 1.44787413614948e-05 -1.27583963632052e-06 -2.47059771552907e-08 -1.80049993289829e-06 3.90585773792458e-06 7.17623570680224e-06 -1.27583963632052e-06 4.24252200309512e-05 -8.33921223082744e-06 5.03343209550199e-06 4.35882776293472e-06 9.80736112251789e-06 -2.47059771552907e-08 -8.33921223082744e-06 5.00568216941863e-05 8.21098202202555e-06 1.06704001210065e-05 1.08211291872968e-05 -1.80049993289829e-06 5.03343209550199e-06 8.21098202202555e-06 5.19001829477934e-05 2422 2425 0 12 15 2426 2457 0 50 14 0 0 0 0 0 15 45 0 628 0 41 46 0 0 2247 +377 417 0.999997946452341 6.38152032720844e-05 0.00202559095585134 -0.00924126385556064 -6.92724102317319e-05 0.999996368304674 0.00269417497499308 0.0105180864061473 -0.00202541167019846 -0.00269430975994402 0.999994319185106 -0.0120521447929334 4.82943413604856e-05 3.36731303285828e-05 -9.31755123579087e-06 8.47092111600848e-06 2.45509608704611e-06 3.48936189302254e-05 3.36731303285828e-05 4.63265562571487e-05 -1.03516151640616e-05 2.09355955786529e-05 -9.5731826049785e-07 3.46482805444366e-05 -9.31755123579087e-06 -1.03516151640616e-05 1.53866131940781e-05 -9.8368383862959e-07 -1.09319481553826e-06 -6.17264870616057e-06 8.47092111600848e-06 2.09355955786529e-05 -9.8368383862959e-07 8.43461626062705e-05 -4.06814481806589e-05 1.9415040250599e-05 2.45509608704611e-06 -9.5731826049785e-07 -1.09319481553826e-06 -4.06814481806589e-05 7.71216288891833e-05 3.99450659717739e-07 3.48936189302254e-05 3.46482805444366e-05 -6.17264870616057e-06 1.9415040250599e-05 3.99450659717739e-07 7.44267883867177e-05 2027 2025 0 15 13 2018 2047 0 49 7 0 0 0 0 0 19 51 0 607 0 50 54 0 0 2339 +377 422 0.999996927213628 0.000260138607875649 -0.00246533794997397 -0.0180080477439635 -0.000259898926342657 0.999999961469206 9.75404299140282e-05 0.0134995485024153 0.00246536322901419 -9.68993915068543e-05 0.999996956292696 -0.0129612794778177 4.17384577439183e-05 3.06721252292569e-05 -1.02123573378572e-05 5.70789287933239e-06 1.87208615431903e-05 2.27801943063257e-05 3.06721252292569e-05 4.22412291639537e-05 -9.75840043408083e-06 1.01445242590296e-05 1.41856681048199e-05 2.6449170660571e-05 -1.02123573378572e-05 -9.75840043408083e-06 1.50387133463078e-05 -1.27914114520872e-06 -7.61528024502694e-06 -5.05901045060312e-06 5.70789287933239e-06 1.01445242590296e-05 -1.27914114520872e-06 5.91688457675738e-05 -2.26420604495675e-05 4.88522012469847e-07 1.87208615431903e-05 1.41856681048199e-05 -7.61528024502694e-06 -2.26420604495675e-05 7.40541143600743e-05 1.29478809036029e-05 2.27801943063257e-05 2.6449170660571e-05 -5.05901045060312e-06 4.88522012469847e-07 1.29478809036029e-05 6.45843500361264e-05 2288 2287 0 14 14 2276 2306 0 52 6 0 0 0 0 0 16 49 0 598 0 57 60 0 0 2322 +377 408 0.999995099583696 0.000547519138456283 0.00308237431003522 -0.0120138052469916 -0.000543735122778037 0.999999097773023 -0.00122833434208282 0.0128435048444281 -0.00308304406559468 0.00122665232755927 0.999994495066526 -0.0079683301984732 6.12012589021787e-05 4.62878783616085e-05 -3.12076554201856e-06 1.6289734559081e-05 -1.39435588913591e-05 4.2560765409574e-05 4.62878783616085e-05 6.57671419458107e-05 -2.89397375930049e-06 1.95046221481233e-05 -9.2117895923882e-06 4.75540406091683e-05 -3.12076554201856e-06 -2.89397375930049e-06 1.2043103055504e-05 1.02612996425361e-06 1.36137974731332e-06 -1.65373033631844e-06 1.6289734559081e-05 1.95046221481233e-05 1.02612996425361e-06 9.16417913343434e-05 -5.92106281207592e-05 9.50217233544025e-06 -1.39435588913591e-05 -9.2117895923882e-06 1.36137974731332e-06 -5.92106281207592e-05 7.53509255979286e-05 -6.89926117924343e-07 4.2560765409574e-05 4.75540406091683e-05 -1.65373033631844e-06 9.50217233544025e-06 -6.89926117924343e-07 8.74111739636386e-05 1380 1379 0 10 15 1375 1406 0 50 8 0 0 0 0 0 20 51 0 491 0 48 54 0 0 2306 +377 381 0.99999973536086 0.000466563878608547 -0.000558208167289821 -0.01050646472392 -0.000467819316973369 0.999997356983411 -0.00225103782284754 0.0101409492855393 0.000557156438998852 0.00225129836769837 0.999997310612565 0.00144431974660674 2.92216119712727e-05 2.13356980212823e-05 -6.31979817478991e-06 9.4192520129761e-06 2.92601593442483e-06 1.44076743357026e-05 2.13356980212823e-05 2.76857337226535e-05 -7.01971090716234e-06 7.54604078327354e-06 5.60771914802633e-06 1.63852781973239e-05 -6.31979817478991e-06 -7.01971090716234e-06 1.10759860666023e-05 -3.69501039848359e-07 -2.47236409260354e-07 -3.30702367181181e-06 9.4192520129761e-06 7.54604078327354e-06 -3.69501039848359e-07 3.58616432261492e-05 -6.40384161440289e-06 4.61550063970472e-06 2.92601593442483e-06 5.60771914802633e-06 -2.47236409260354e-07 -6.40384161440289e-06 3.96055363375101e-05 3.0764055093367e-06 1.44076743357026e-05 1.63852781973239e-05 -3.30702367181181e-06 4.61550063970472e-06 3.0764055093367e-06 3.54476270143374e-05 2691 2668 0 14 55 2663 2691 0 51 24 0 0 0 0 0 17 51 0 659 0 135 138 0 0 2900 +377 429 0.999969396293641 -0.00760301803198241 -0.00184406966675413 -0.00722953207911156 0.00760957818933843 0.99996464943947 0.00357689686440516 0.00747389872851594 0.00181680926649914 -0.00359081999041959 0.999991902575159 -0.00905343313654005 3.94479497148529e-05 2.35526610699939e-05 -4.50369393462569e-06 3.7272787441466e-06 -1.14621030801764e-06 2.64512188984232e-05 2.35526610699939e-05 3.30123752473532e-05 -5.75645957280096e-06 6.54988809455195e-06 -2.29837540583293e-06 2.49323533565074e-05 -4.50369393462569e-06 -5.75645957280096e-06 1.06382191429258e-05 -1.23703142778021e-06 2.61385844459238e-06 -1.09694127503773e-06 3.7272787441466e-06 6.54988809455195e-06 -1.23703142778021e-06 4.64028225244203e-05 -1.09800532805098e-05 6.09900767642841e-06 -1.14621030801764e-06 -2.29837540583293e-06 2.61385844459238e-06 -1.09800532805098e-05 4.03658679192895e-05 -2.7882347840662e-06 2.64512188984232e-05 2.49323533565074e-05 -1.09694127503773e-06 6.09900767642841e-06 -2.7882347840662e-06 7.09878002614684e-05 2944 2945 0 2 25 2952 2983 0 41 20 0 0 0 0 0 27 59 0 617 0 15 15 0 0 2420 +377 410 0.999999092586332 -5.52133081509866e-05 0.00134602303214859 -0.00885738541644953 5.59334767968894e-05 0.999999855321799 -0.000535002642647243 0.00971804336203306 -0.00134599329814263 0.000535077444926569 0.999998950996534 -0.0061888514677726 4.03098238928282e-05 2.19553098203202e-05 -1.01286037694165e-06 3.38764333526929e-06 -3.61511392539456e-06 2.54577949779709e-05 2.19553098203202e-05 3.77885523082451e-05 -1.57946853846481e-06 -1.08460510469022e-07 8.66013702378849e-06 2.41797343208868e-05 -1.01286037694165e-06 -1.57946853846481e-06 9.62995397609384e-06 1.58900786368244e-06 5.43029413208984e-06 9.48818094591259e-07 3.38764333526929e-06 -1.08460510469022e-07 1.58900786368244e-06 4.91126239960837e-05 -2.55128348020671e-05 1.22838454695896e-06 -3.61511392539456e-06 8.66013702378849e-06 5.43029413208984e-06 -2.55128348020671e-05 5.49305973925371e-05 2.83806616244341e-07 2.54577949779709e-05 2.41797343208868e-05 9.48818094591259e-07 1.22838454695896e-06 2.83806616244341e-07 6.67462944360743e-05 2413 2409 0 17 9 2409 2444 0 51 9 0 0 0 0 0 24 54 0 509 0 32 36 0 0 2355 +377 419 0.999998267984996 0.000899688730137549 -0.00162929039691505 -0.0120627555762281 -0.000900314135539618 0.999999521311837 -0.000383158653610901 0.0100654777477311 0.00162894489347052 0.000384624863149606 0.999998599300143 -0.00690717786861647 3.5684021066756e-05 2.51253390713232e-05 -1.02081576757318e-05 1.02198195654759e-05 9.19267540154735e-06 1.96053812804263e-05 2.51253390713232e-05 3.75521410330123e-05 -1.05114361983949e-05 1.21214822187143e-05 3.81943375400479e-06 2.21915598634655e-05 -1.02081576757318e-05 -1.05114361983949e-05 1.52204542998896e-05 -1.25594427930723e-06 -4.90065230826706e-06 -1.1498879439632e-06 1.02198195654759e-05 1.21214822187143e-05 -1.25594427930723e-06 7.94785693434578e-05 -4.38580553822204e-05 8.47181766986223e-06 9.19267540154735e-06 3.81943375400479e-06 -4.90065230826706e-06 -4.38580553822204e-05 7.89814040847427e-05 -3.65309814213514e-06 1.96053812804263e-05 2.21915598634655e-05 -1.1498879439632e-06 8.47181766986223e-06 -3.65309814213514e-06 5.2654793646292e-05 2830 2832 0 16 14 2829 2858 0 52 11 0 0 0 0 0 16 48 0 586 0 95 118 0 0 2228 +378 413 0.999999991596232 0.000129434207708814 7.37038613233179e-06 -0.0122413131612162 -0.000129429436449765 0.999999784437955 -0.000643717378711924 0.007028373877351 -7.45370359245826e-06 0.000643716419357349 0.999999792786785 -0.00832293171113489 2.6888239766192e-05 1.53918916133297e-05 -7.0182106814377e-06 8.02076397867812e-06 5.15742459695222e-06 1.52701490007531e-05 1.53918916133297e-05 2.49930963664315e-05 -8.22351691820094e-06 8.00189992684317e-06 8.23115512674274e-06 1.30421288470378e-05 -7.0182106814377e-06 -8.22351691820094e-06 1.19016148094835e-05 -5.53640346231525e-08 -1.71151012886099e-06 -6.34388035270532e-06 8.02076397867812e-06 8.00189992684317e-06 -5.53640346231525e-08 6.93516795342001e-05 -3.03197144294762e-05 6.28511939499006e-06 5.15742459695222e-06 8.23115512674274e-06 -1.71151012886099e-06 -3.03197144294762e-05 5.83941539852922e-05 1.21164775116431e-05 1.52701490007531e-05 1.30421288470378e-05 -6.34388035270532e-06 6.28511939499006e-06 1.21164775116431e-05 5.86711222460029e-05 2632 2628 0 8 12 2627 2659 0 42 6 0 0 0 0 0 19 52 0 603 0 11 17 0 0 2206 +377 423 0.999999271619048 0.00103116793793164 -0.000627259162556128 -0.0105994709244363 -0.00103114560195145 0.999999467723706 3.59312101034612e-05 0.00980213435542037 0.000627295879792775 -3.52843884050987e-05 0.999999802627426 -0.0114115994722963 2.97212547579232e-05 1.75522440862621e-05 -6.72721778340181e-06 3.10075316994291e-06 1.02897744717249e-05 1.60828459790197e-05 1.75522440862621e-05 2.46156374571667e-05 -8.02349769603232e-06 5.26453626512696e-06 9.17708245792838e-06 1.32382184774707e-05 -6.72721778340181e-06 -8.02349769603232e-06 1.2401719441907e-05 4.08266510065489e-07 -3.00310341462803e-06 -9.20598119836494e-07 3.10075316994291e-06 5.26453626512696e-06 4.08266510065489e-07 4.11915276783476e-05 -1.25309821010654e-05 1.48086210192552e-06 1.02897744717249e-05 9.17708245792838e-06 -3.00310341462803e-06 -1.25309821010654e-05 5.90547474620285e-05 5.74050375023479e-06 1.60828459790197e-05 1.32382184774707e-05 -9.20598119836494e-07 1.48086210192552e-06 5.74050375023479e-06 4.80880259640191e-05 2922 2920 0 11 12 2922 2960 0 50 9 0 0 0 0 0 21 52 0 614 0 12 15 0 0 2260 +378 414 0.999999300469963 2.03733387412413e-05 0.00118264301963108 -0.0113190569872627 -2.2923934503731e-05 0.999997674018957 0.00215671768417854 0.0135850739080363 -0.00118259632928588 -0.00215674328632086 0.999996974957584 -0.00869849916366887 3.39309243341123e-05 2.32913960633913e-05 -7.31116764074059e-06 9.89226520741423e-06 5.7870072757733e-06 1.92132734049257e-05 2.32913960633913e-05 2.88453606408369e-05 -7.89795809569167e-06 1.09770691438245e-05 3.18447360587019e-06 1.94818026563688e-05 -7.31116764074059e-06 -7.89795809569167e-06 1.23458607522191e-05 -3.00076107015723e-06 -1.524030203621e-06 -1.69514430439935e-06 9.89226520741423e-06 1.09770691438245e-05 -3.00076107015723e-06 4.91985472589541e-05 -9.95682167005252e-06 7.03898054486788e-06 5.7870072757733e-06 3.18447360587019e-06 -1.524030203621e-06 -9.95682167005252e-06 4.46826425019055e-05 7.41651225184006e-08 1.92132734049257e-05 1.94818026563688e-05 -1.69514430439935e-06 7.03898054486788e-06 7.41651225184006e-08 4.68775700239145e-05 2564 2564 0 12 16 2557 2585 0 42 11 0 0 0 0 0 22 52 0 605 0 42 58 0 0 2455 +378 427 0.99999683077735 0.000627184581501547 0.00243825239814658 -0.0111739566208232 -0.000633579618228559 0.99999635945825 0.00262290814053994 0.0126004345935894 -0.00243659847404249 -0.00262444465498361 0.999993587618505 -0.0125889762895109 4.00158461510741e-05 2.52535526098947e-05 -1.28955366410209e-05 1.14949888960113e-06 2.45514572274813e-05 2.41962414699223e-05 2.52535526098947e-05 3.7573542758282e-05 -1.18608738147999e-05 1.81072969544572e-05 1.07129944180639e-05 1.62187079616015e-05 -1.28955366410209e-05 -1.18608738147999e-05 1.92022493641089e-05 -5.65247958611372e-06 -9.77248892092563e-06 -3.15820874923319e-06 1.14949888960113e-06 1.81072969544572e-05 -5.65247958611372e-06 7.9946178215736e-05 -2.78913531447055e-05 2.43526249638e-06 2.45514572274813e-05 1.07129944180639e-05 -9.77248892092563e-06 -2.78913531447055e-05 7.13339399409327e-05 1.01629127768374e-05 2.41962414699223e-05 1.62187079616015e-05 -3.15820874923319e-06 2.43526249638e-06 1.01629127768374e-05 6.78860889991985e-05 2051 2048 0 17 17 2029 2055 0 42 7 0 0 0 0 0 19 49 0 652 0 94 115 0 0 2353 +378 412 0.999997148544787 -0.000294526884827963 0.0023698430769005 -0.0102043596157514 0.000289872425821217 0.999998029060842 0.0019641406284602 0.0104370122671049 -0.00237041689830464 -0.00196344807563965 0.999995262986472 -0.0092216797179319 3.55133207650953e-05 2.35988133480202e-05 -7.10380198986959e-06 9.0235492927731e-07 7.5889882721601e-06 1.97729266017574e-05 2.35988133480202e-05 3.99810875910841e-05 -7.86482682966428e-06 7.29263965001243e-06 9.9673940432475e-06 2.18600239208233e-05 -7.10380198986959e-06 -7.86482682966428e-06 1.23621607082414e-05 1.24591062363058e-06 -2.65843003262916e-06 -5.84960185883929e-06 9.0235492927731e-07 7.29263965001243e-06 1.24591062363058e-06 7.62592607510785e-05 -4.79582691098382e-05 -1.38327028067268e-05 7.5889882721601e-06 9.9673940432475e-06 -2.65843003262916e-06 -4.79582691098382e-05 7.69565413803187e-05 2.59152148269099e-05 1.97729266017574e-05 2.18600239208233e-05 -5.84960185883929e-06 -1.38327028067268e-05 2.59152148269099e-05 6.51907336017189e-05 2433 2429 0 11 11 2427 2451 0 39 9 0 0 0 0 0 18 49 0 573 0 10 14 0 0 2217 +378 382 0.999989381929536 0.000406991937933015 0.00459024898534506 -0.00777210882466401 -0.000413360501674532 0.999998953308293 0.00138654802081306 0.00913691462375317 -0.00458967986690349 -0.00138843072597187 0.999988503483334 -0.00619504798321194 3.08564573129272e-05 2.33338044263313e-05 -8.30003616147977e-06 8.59366945880531e-06 8.5794953280613e-06 1.43190173467357e-05 2.33338044263313e-05 3.78637296003341e-05 -1.07316513612873e-05 1.28021253761396e-05 9.17345262377836e-06 2.02711721630543e-05 -8.30003616147977e-06 -1.07316513612873e-05 1.30486665200469e-05 -3.88591195938335e-06 -1.28571544009282e-06 -4.08763487189901e-06 8.59366945880531e-06 1.28021253761396e-05 -3.88591195938335e-06 3.88294005105469e-05 -9.79795008391824e-06 6.36320887872369e-06 8.5794953280613e-06 9.17345262377836e-06 -1.28571544009282e-06 -9.79795008391824e-06 3.6555855428017e-05 1.04730130607802e-05 1.43190173467357e-05 2.02711721630543e-05 -4.08763487189901e-06 6.36320887872369e-06 1.04730130607802e-05 4.46491949791169e-05 2115 2092 0 15 57 2059 2082 0 43 3 0 0 0 0 0 24 53 0 674 0 140 142 0 0 2807 +377 407 0.999997178325069 3.05956390504002e-06 0.00237556993987482 -0.0154000646337926 -1.72195474915272e-06 0.999999841474269 -0.00056307057401759 0.0106208414293376 -0.00237557128603626 0.000563064894591527 0.999997019805054 -0.00777189555603652 3.44325420751748e-05 2.36573141774773e-05 -1.72786527883765e-06 5.50241462137804e-07 9.1147446381302e-07 1.87397109774633e-05 2.36573141774773e-05 3.47642847933854e-05 -2.92889438653137e-06 3.60909716407697e-06 -1.89394694509795e-08 2.51628043807073e-05 -1.72786527883765e-06 -2.92889438653137e-06 1.03960056397146e-05 4.38041567366815e-07 5.5370549291748e-06 -4.56363407500001e-07 5.50241462137804e-07 3.60909716407697e-06 4.38041567366815e-07 4.60574409404033e-05 -1.44838638634727e-05 3.05880999191575e-06 9.1147446381302e-07 -1.89394694509795e-08 5.5370549291748e-06 -1.44838638634727e-05 3.81492664495818e-05 3.80750842518334e-06 1.87397109774633e-05 2.51628043807073e-05 -4.56363407500001e-07 3.05880999191575e-06 3.80750842518334e-06 4.66823742901918e-05 2684 2682 0 11 17 2684 2709 0 46 13 0 0 0 0 0 18 47 0 485 0 44 48 0 0 2316 +378 415 0.999995406887315 -0.000228608798392444 0.00302224126946109 -0.0128168706016526 0.000225853555127079 0.999999558654461 0.00091196549017131 0.0100093652557177 -0.00302244841894327 -0.000911278717475889 0.999995017175913 -0.0106747389022923 3.11269316555163e-05 2.39749958091725e-05 -8.40291847718268e-06 1.87953265158305e-06 1.23105043299932e-05 2.19097972571418e-05 2.39749958091725e-05 3.55457825051504e-05 -8.87867256286927e-06 7.00740004019456e-06 1.08279792101498e-05 1.78859725852672e-05 -8.40291847718268e-06 -8.87867256286927e-06 1.32589628445778e-05 8.93738057663555e-07 -2.24616627048301e-06 -4.12699120439675e-06 1.87953265158305e-06 7.00740004019456e-06 8.93738057663555e-07 6.13838753124716e-05 -2.73272429348575e-05 1.99434428166337e-06 1.23105043299932e-05 1.08279792101498e-05 -2.24616627048301e-06 -2.73272429348575e-05 6.14515356407899e-05 1.16371927187615e-05 2.19097972571418e-05 1.78859725852672e-05 -4.12699120439675e-06 1.99434428166337e-06 1.16371927187615e-05 5.43523511325229e-05 2043 2041 0 12 15 2033 2057 0 40 8 0 0 0 0 0 20 52 0 583 0 93 113 0 0 2344 +378 426 0.999995213076665 0.000953294692547774 0.00294364620559938 -0.0120709894691047 -0.000959152562981938 0.999997561482528 0.00198923486762895 0.0161192104041391 -0.00294174270042513 -0.00199204875111675 0.999993688925914 -0.00656542596101987 3.05516603154354e-05 1.99045424708738e-05 -9.57380532636175e-06 7.16693584224833e-06 1.72210853627755e-06 1.59297421269028e-05 1.99045424708738e-05 2.85634769852478e-05 -1.05059959429064e-05 1.13327240183206e-05 1.53135742011279e-06 7.60139076768135e-06 -9.57380532636175e-06 -1.05059959429064e-05 1.55150473257528e-05 1.21912171677496e-06 -5.61496002229533e-06 -3.44646359217845e-06 7.16693584224833e-06 1.13327240183206e-05 1.21912171677496e-06 0.000105536490854532 -6.65870762574973e-05 -8.56658230237339e-06 1.72210853627755e-06 1.53135742011279e-06 -5.61496002229533e-06 -6.65870762574973e-05 0.000104017796173317 8.23556008376481e-06 1.59297421269028e-05 7.60139076768135e-06 -3.44646359217845e-06 -8.56658230237339e-06 8.23556008376481e-06 5.39559268209076e-05 1958 1954 0 8 19 1949 1975 0 43 11 0 0 0 0 0 24 53 0 660 0 15 20 0 0 2103 +378 380 0.999999613010478 0.000157441675550683 0.00086555820941531 -0.00606435315475088 -0.000156259869039014 0.999999055813567 -0.00136526731010333 0.00244418569182343 -0.000865772342139869 0.00136513152974674 0.999998693426225 -0.000848595369307602 3.38919656585371e-05 2.2760466605141e-05 -8.17340339480083e-06 6.32058483966817e-06 6.96006914449576e-06 1.54950390011375e-05 2.2760466605141e-05 3.11040816124872e-05 -9.98676293776556e-06 8.60676532425762e-06 6.90938461821744e-06 1.78027581768967e-05 -8.17340339480083e-06 -9.98676293776556e-06 1.44224621072944e-05 -2.13731612974551e-06 -2.75388509513427e-06 -3.8361478671161e-06 6.32058483966817e-06 8.60676532425762e-06 -2.13731612974551e-06 2.9941581101408e-05 -1.82956228812541e-06 4.4262302440903e-06 6.96006914449576e-06 6.90938461821744e-06 -2.75388509513427e-06 -1.82956228812541e-06 3.1117893335361e-05 6.34973448556891e-06 1.54950390011375e-05 1.78027581768967e-05 -3.8361478671161e-06 4.4262302440903e-06 6.34973448556891e-06 3.03784106176272e-05 2572 2546 0 11 54 2536 2561 0 42 24 0 0 0 0 0 20 51 0 658 0 87 80 0 0 2717 +378 381 0.999999568706189 8.54620483243442e-05 0.000924815481657265 -0.00800717027669722 -8.58101249790912e-05 0.999999925502022 0.000376341031291166 0.00610083661063177 -0.000924783249884979 -0.000376420227509672 0.999999501541752 -0.00532384008182895 3.57438660781095e-05 2.5332326314699e-05 -9.27202693035407e-06 1.21581182325116e-05 -1.68466525608515e-06 2.03318187729618e-05 2.5332326314699e-05 2.91838997630238e-05 -1.05121072550592e-05 1.15422899270895e-05 -3.80252251659897e-07 2.18266152590686e-05 -9.27202693035407e-06 -1.05121072550592e-05 1.41837019603611e-05 -2.84471107336957e-06 -3.01807996502422e-06 -4.76683039050814e-06 1.21581182325116e-05 1.15422899270895e-05 -2.84471107336957e-06 4.27520816378075e-05 -1.40033219305194e-05 1.02279197618062e-05 -1.68466525608515e-06 -3.80252251659897e-07 -3.01807996502422e-06 -1.40033219305194e-05 4.38666322562065e-05 -2.69451011073897e-06 2.03318187729618e-05 2.18266152590686e-05 -4.76683039050814e-06 1.02279197618062e-05 -2.69451011073897e-06 3.74177268472506e-05 2300 2274 0 11 54 2239 2267 0 47 3 0 0 0 0 0 21 54 0 649 0 141 144 0 0 2784 +378 420 0.999999314953359 0.000555331752187451 -0.00103038801340433 -0.0135978375429491 -0.000553899595361292 0.999998880984683 0.00138968507965067 0.0131105167787816 0.00103115859663463 -0.00138911339614789 0.999998503536841 -0.0113509782334564 3.4995906755354e-05 2.13503023615527e-05 -8.74116356181823e-06 9.42726862008015e-06 5.40788053731942e-06 1.49908016712046e-05 2.13503023615527e-05 3.29728672554099e-05 -9.55179080805182e-06 1.77719387700531e-05 1.72980314142393e-06 1.02201868881622e-05 -8.74116356181823e-06 -9.55179080805182e-06 1.48823494329052e-05 4.47657961721518e-07 -4.18415558556233e-06 -4.27551505428931e-06 9.42726862008015e-06 1.77719387700531e-05 4.47657961721518e-07 0.000109576891055655 -6.0473929286442e-05 -1.49028344388272e-05 5.40788053731942e-06 1.72980314142393e-06 -4.18415558556233e-06 -6.0473929286442e-05 8.86036564608284e-05 1.4477484520606e-05 1.49908016712046e-05 1.02201868881622e-05 -4.27551505428931e-06 -1.49028344388272e-05 1.4477484520606e-05 6.68026578961836e-05 2403 2405 0 7 17 2406 2430 0 37 15 0 0 0 0 0 21 51 0 628 0 12 15 0 0 2254 +378 418 0.99999847251454 0.000619117569889456 0.00163452195492586 -0.0126845985897056 -0.000619379481886265 0.999999795426658 0.000159736342371869 0.0144654480088159 -0.00163442272497013 -0.000160748487738502 0.999998651410231 -0.00775063610207242 3.2899586166128e-05 2.03501772664689e-05 -8.17019369030385e-06 2.66393693402377e-06 1.19957110576172e-05 1.47742851015458e-05 2.03501772664689e-05 4.08273157384445e-05 -9.19115291663357e-06 8.64231151811135e-06 1.29871756154988e-05 1.1872569640311e-05 -8.17019369030385e-06 -9.19115291663357e-06 1.46023023279342e-05 2.06877712861012e-06 -2.97023497378679e-06 -9.05796778661314e-07 2.66393693402377e-06 8.64231151811135e-06 2.06877712861012e-06 6.85939503209256e-05 -3.53274288243804e-05 -9.76121018416552e-07 1.19957110576172e-05 1.29871756154988e-05 -2.97023497378679e-06 -3.53274288243804e-05 7.43048600344292e-05 1.47240409783818e-05 1.47742851015458e-05 1.1872569640311e-05 -9.05796778661314e-07 -9.76121018416552e-07 1.47240409783818e-05 5.92197752739954e-05 2006 2008 0 6 17 2005 2029 0 38 12 0 0 0 0 0 21 54 0 626 0 14 18 0 0 2285 +378 421 0.999997784013907 0.000756469850821372 0.0019646171740928 -0.00891283984974592 -0.000759137635951657 0.999998790416556 0.00135752549678286 0.0112197360327989 -0.00196358787061436 -0.00135901390336232 0.999997148697877 -0.00815152948427403 2.96967804206485e-05 2.00625931399563e-05 -8.75336601452232e-06 7.75230970956056e-06 8.26211671687788e-06 1.09389141088338e-05 2.00625931399563e-05 2.91931105607409e-05 -9.55310455669312e-06 1.04369031605809e-05 3.78524453468132e-06 9.36267445081322e-06 -8.75336601452232e-06 -9.55310455669312e-06 1.37175017793526e-05 -2.77716339886043e-06 -4.2311871497059e-07 -9.97361590417153e-08 7.75230970956056e-06 1.04369031605809e-05 -2.77716339886043e-06 7.65236118016188e-05 -3.62251955888123e-05 -2.96970848340209e-06 8.26211671687788e-06 3.78524453468132e-06 -4.2311871497059e-07 -3.62251955888123e-05 6.51068422975777e-05 2.70751283450724e-06 1.09389141088338e-05 9.36267445081322e-06 -9.97361590417153e-08 -2.96970848340209e-06 2.70751283450724e-06 5.12865631675089e-05 1978 1975 0 12 15 1969 2002 0 47 8 0 0 0 0 0 20 52 0 629 0 14 22 0 0 2417 +378 411 0.999991693864037 0.000152050136617752 0.00407296988578841 -0.00636012603092078 -0.00016142167448895 0.999997340403123 0.00230068027401489 0.00970239605602683 -0.00407260923458044 -0.00230131862987083 0.999989058833439 -0.00643318960350002 5.02238920731482e-05 4.11653500771886e-05 -3.62983230103171e-06 1.22485001163097e-05 2.57858490494139e-06 3.7315467772019e-05 4.11653500771886e-05 5.27688153301942e-05 -5.99098659415108e-06 1.75939535959236e-05 -7.3754441870795e-07 3.58160406874189e-05 -3.62983230103171e-06 -5.99098659415108e-06 1.25956372497615e-05 2.47330517157986e-06 1.30143641307799e-06 -3.48132603448853e-06 1.22485001163097e-05 1.75939535959236e-05 2.47330517157986e-06 7.85070213952728e-05 -4.48036134439433e-05 1.47778953738031e-05 2.57858490494139e-06 -7.3754441870795e-07 1.30143641307799e-06 -4.48036134439433e-05 7.43591606656208e-05 -5.27186966183838e-07 3.7315467772019e-05 3.58160406874189e-05 -3.48132603448853e-06 1.47778953738031e-05 -5.27186966183838e-07 8.52474286967253e-05 2245 2244 0 13 13 2240 2271 0 48 8 0 0 0 0 0 24 55 0 539 0 10 16 0 0 2275 +378 409 0.999998878103323 5.19429630164704e-05 0.00149702839797744 -0.00949996699129265 -5.14821577428665e-05 0.999999951288918 -0.000307850206242105 0.00645733516073115 -0.00149704431570744 0.000307772790613851 0.999998832066431 -0.00596179548388326 3.47591265666332e-05 2.76608293968301e-05 -1.10951243849269e-06 6.58212136795716e-06 -1.48686861556855e-06 3.17500893163208e-05 2.76608293968301e-05 3.3508884758518e-05 -2.25153290839914e-06 3.51777707445708e-06 -1.5663609630194e-06 2.93494228133938e-05 -1.10951243849269e-06 -2.25153290839914e-06 9.20668534346048e-06 1.9513318415947e-06 4.38613912724595e-06 4.54483436509373e-07 6.58212136795716e-06 3.51777707445708e-06 1.9513318415947e-06 4.19631303337705e-05 -9.70654963586301e-06 8.11124344327269e-06 -1.48686861556855e-06 -1.5663609630194e-06 4.38613912724595e-06 -9.70654963586301e-06 2.94666684342136e-05 -4.86063845827707e-06 3.17500893163208e-05 2.93494228133938e-05 4.54483436509373e-07 8.11124344327269e-06 -4.86063845827707e-06 6.93112275104941e-05 2803 2799 0 8 13 2805 2844 0 46 10 0 0 0 0 0 19 50 0 501 0 10 15 0 0 2336 +378 417 0.999997994018786 6.5505569401324e-05 0.00200191593842214 -0.0141629803552686 -6.90133899080904e-05 0.999998462492501 0.00175221282531551 0.0124037937357212 -0.00200179808076254 -0.00175234746941472 0.999996461035133 -0.00772702065785184 3.46056374839195e-05 2.36035097952977e-05 -1.01356370416808e-05 1.35787062325912e-07 1.10205681201431e-05 2.07781288583745e-05 2.36035097952977e-05 4.25573585238437e-05 -1.03378528405478e-05 1.49612403614576e-05 1.14972873758124e-05 2.34484680944498e-05 -1.01356370416808e-05 -1.03378528405478e-05 1.47422034650278e-05 -5.4897108183843e-07 -2.68889205792149e-06 -6.1895685647272e-06 1.35787062325912e-07 1.49612403614576e-05 -5.4897108183843e-07 6.91813638977418e-05 -2.64463470756168e-05 3.55500860645094e-06 1.10205681201431e-05 1.14972873758124e-05 -2.68889205792149e-06 -2.64463470756168e-05 5.6759322874828e-05 8.96764378075249e-06 2.07781288583745e-05 2.34484680944498e-05 -6.1895685647272e-06 3.55500860645094e-06 8.96764378075249e-06 5.56173003917614e-05 2087 2087 0 14 17 2080 2103 0 38 13 0 0 0 0 0 24 57 0 611 0 43 60 0 0 2350 +378 416 0.999999588109552 0.000690570626889128 0.000588976176124614 -0.016108227184248 -0.000690740653666417 0.99999971981461 0.000288527384471051 0.0135154689131347 -0.000588776762565325 -0.000288934095418268 0.999999784929483 -0.00759941358669648 3.23125478102845e-05 2.38958851650503e-05 -1.0685614888104e-05 7.95739819976272e-06 1.10529644185837e-05 2.22976593214238e-05 2.38958851650503e-05 2.94452698505397e-05 -1.17617459997498e-05 1.09362654065327e-05 6.78283930417398e-06 2.50022392229836e-05 -1.0685614888104e-05 -1.17617459997498e-05 1.5294891750992e-05 -4.31455639395513e-06 -3.57229007069185e-06 -5.51609892682257e-06 7.95739819976272e-06 1.09362654065327e-05 -4.31455639395513e-06 6.58642577684146e-05 -2.90216263127454e-05 7.45309191362307e-06 1.10529644185837e-05 6.78283930417398e-06 -3.57229007069185e-06 -2.90216263127454e-05 5.58189172384324e-05 4.18873766716929e-06 2.22976593214238e-05 2.50022392229836e-05 -5.51609892682257e-06 7.45309191362307e-06 4.18873766716929e-06 5.43525285172602e-05 2551 2547 0 8 16 2550 2578 0 40 14 0 0 0 0 0 23 55 0 617 0 40 52 0 0 2295 +378 423 0.999999597637086 0.000253665104281222 0.000860453183677798 -0.0150348885078268 -0.000255105295511006 0.999998566217227 0.00167406235790041 0.0141219383291751 -0.000860027298772256 -0.0016742811904835 0.999998228566201 -0.00988404562052871 3.35185034910223e-05 1.92084378507287e-05 -8.05291286762529e-06 2.06644272020632e-07 8.95617614477211e-06 1.60914363510224e-05 1.92084378507287e-05 2.8475804666788e-05 -8.67312790253341e-06 1.21941587609139e-05 2.9919468056487e-06 1.50033714369822e-05 -8.05291286762529e-06 -8.67312790253341e-06 1.24932185882201e-05 8.39993654671195e-07 -1.72035768767695e-06 -2.7013410566995e-06 2.06644272020632e-07 1.21941587609139e-05 8.39993654671195e-07 8.54506482121246e-05 -4.40398044938916e-05 1.36422210698104e-06 8.95617614477211e-06 2.9919468056487e-06 -1.72035768767695e-06 -4.40398044938916e-05 6.76355402133369e-05 8.5084725204989e-06 1.60914363510224e-05 1.50033714369822e-05 -2.7013410566995e-06 1.36422210698104e-06 8.5084725204989e-06 5.51197980185854e-05 2489 2487 0 7 13 2481 2503 0 38 7 0 0 0 0 0 23 53 0 625 0 11 15 0 0 2318 +378 428 0.999990879259867 -5.55279304366659e-05 0.00427063387876705 -0.0126026734353908 4.71736688893608e-05 0.999998085356099 0.00195628698854392 0.0133874616673548 -0.00427073433059175 -0.00195606768429013 0.999988967252885 -0.00979445533587383 3.82777695350723e-05 2.96504413636414e-05 -1.28363115355188e-05 4.10282351713882e-06 1.4610132998194e-05 2.35875303818399e-05 2.96504413636414e-05 3.47219066910528e-05 -1.31392097407581e-05 5.25213121866505e-06 1.24044395592611e-05 1.67373213750632e-05 -1.28363115355188e-05 -1.31392097407581e-05 1.86036192032702e-05 -1.30233910376604e-06 -6.73006945622266e-06 -4.27547662233368e-06 4.10282351713882e-06 5.25213121866505e-06 -1.30233910376604e-06 6.64242149853971e-05 -2.15658769371878e-05 -7.68130354436177e-07 1.4610132998194e-05 1.24044395592611e-05 -6.73006945622266e-06 -2.15658769371878e-05 6.34285119233334e-05 7.86231447889825e-06 2.35875303818399e-05 1.67373213750632e-05 -4.27547662233368e-06 -7.68130354436177e-07 7.86231447889825e-06 5.71979702829551e-05 1708 1707 0 6 18 1700 1729 0 41 8 0 0 0 0 0 19 49 0 645 0 91 114 0 0 2320 +378 424 0.999998876318276 -2.28108690905352e-05 0.00149894691382986 -0.00654025707362286 2.15810844597885e-05 0.999999663203333 0.000820443464038412 0.00373999677713315 -0.00149896512401799 -0.000820410193221137 0.99999854001427 -0.00875273881351255 3.76185733695038e-05 2.04427344226301e-05 -8.44003516626629e-06 4.44298277914881e-06 1.43228728734126e-05 2.17787342999245e-05 2.04427344226301e-05 3.1204064971514e-05 -8.34270306585426e-06 9.62546298706971e-06 1.11722119364093e-05 1.55905385157509e-05 -8.44003516626629e-06 -8.34270306585426e-06 1.14803420684033e-05 5.80793292324826e-07 -2.63296499570042e-06 -3.60613438558731e-06 4.44298277914881e-06 9.62546298706971e-06 5.80793292324826e-07 5.6342734373093e-05 -1.51893030295495e-05 8.30709215980275e-06 1.43228728734126e-05 1.11722119364093e-05 -2.63296499570042e-06 -1.51893030295495e-05 4.89432636192424e-05 6.1900408205518e-06 2.17787342999245e-05 1.55905385157509e-05 -3.60613438558731e-06 8.30709215980275e-06 6.1900408205518e-06 5.02129167610773e-05 2304 2303 0 11 17 2298 2340 0 46 12 0 0 0 0 0 16 47 0 637 0 13 17 0 0 2314 +378 425 0.999995602634389 0.000349020500042045 0.00294497819610637 -0.0111680090065928 -0.000353011233426431 0.9999990201029 0.0013546867933956 0.00865784319271407 -0.00294450249686875 -0.0013557204467279 0.999994745949756 -0.00966569064172865 3.84637198345133e-05 1.41671147961706e-05 -9.48207265440172e-06 1.20914813957973e-06 1.17706086952802e-05 1.9236092447743e-05 1.41671147961706e-05 2.82440946033597e-05 -8.69819491919086e-06 5.32493596670199e-06 6.11208483996154e-06 1.2376976100978e-05 -9.48207265440172e-06 -8.69819491919086e-06 1.51155633353218e-05 1.14776306789449e-06 -4.00217023176887e-06 -2.27571977858361e-06 1.20914813957973e-06 5.32493596670199e-06 1.14776306789449e-06 5.56244037926783e-05 -2.64198334833361e-05 -6.75210747442455e-07 1.17706086952802e-05 6.11208483996154e-06 -4.00217023176887e-06 -2.64198334833361e-05 6.01299779469402e-05 8.21127461248161e-06 1.9236092447743e-05 1.2376976100978e-05 -2.27571977858361e-06 -6.75210747442455e-07 8.21127461248161e-06 5.97083608271888e-05 2810 2808 0 16 20 2801 2837 0 42 15 0 0 0 0 0 21 51 0 629 0 15 20 0 0 2018 +378 419 0.999995769547653 0.000125879342997363 0.00290603530393092 -0.0143868380872669 -0.00013450309966753 0.99999558783154 0.00296752866367989 0.0144570394307732 -0.0029056489314551 -0.00296790698044742 0.99999137432902 -0.0120224614991672 3.80726006838995e-05 1.70776597081668e-05 -8.26311444570682e-06 3.11179617595742e-06 4.64591649003701e-06 2.01676657009713e-05 1.70776597081668e-05 3.81758865687132e-05 -8.49944105123743e-06 8.7427999886118e-06 6.14725200030749e-06 1.92666639699117e-05 -8.26311444570682e-06 -8.49944105123743e-06 1.43466073661154e-05 -2.33053683683884e-06 1.02002471663243e-06 -4.63073696290992e-06 3.11179617595742e-06 8.7427999886118e-06 -2.33053683683884e-06 6.47495030543445e-05 -2.6733235241592e-05 8.38620077652184e-06 4.64591649003701e-06 6.14725200030749e-06 1.02002471663243e-06 -2.6733235241592e-05 6.56643454150143e-05 8.63070229735059e-08 2.01676657009713e-05 1.92666639699117e-05 -4.63073696290992e-06 8.38620077652184e-06 8.63070229735059e-08 6.5410537165889e-05 2180 2180 0 10 14 2170 2192 0 37 6 0 0 0 0 0 22 53 0 593 0 93 117 0 0 2318 +378 410 0.999999419516411 5.71174767727891e-05 0.00107596674447435 -0.00515971057788334 -5.72193294340512e-05 0.999999993885462 9.46309875749073e-05 0.00359554101195919 -0.00107596133281208 -9.46924987387842e-05 0.9999994166701 -0.00578819136110575 3.59499213088002e-05 2.27081165408181e-05 -1.39318397591006e-06 4.27505465353202e-06 -8.27134956531381e-07 2.36078673359801e-05 2.27081165408181e-05 3.26832344087777e-05 -2.65748051332342e-06 5.00071511961262e-06 3.42541766593342e-06 1.98578000630889e-05 -1.39318397591006e-06 -2.65748051332342e-06 1.03598907051798e-05 2.4783080294412e-06 3.32702502481136e-06 -7.88804738782832e-07 4.27505465353202e-06 5.00071511961262e-06 2.4783080294412e-06 4.70821412241933e-05 -1.81730735311502e-05 7.54528819162864e-06 -8.27134956531381e-07 3.42541766593342e-06 3.32702502481136e-06 -1.81730735311502e-05 3.64827142325637e-05 5.91995834797643e-07 2.36078673359801e-05 1.98578000630889e-05 -7.88804738782832e-07 7.54528819162864e-06 5.91995834797643e-07 5.26407072166808e-05 2769 2767 0 17 10 2765 2797 0 47 7 0 0 0 0 0 22 51 0 508 0 10 14 0 0 2249 +378 429 0.999975482859918 -0.00691868118430952 0.00107959702857163 -0.012799012360971 0.00691313836662092 0.999963321554554 0.00505609172265934 0.0162760027192595 -0.00111453891729862 -0.0050485043581116 0.999986635114064 -0.00898277352627679 3.86709877693184e-05 1.6643113089016e-05 -3.84055409257552e-06 4.61010485364601e-06 -2.84666742456534e-06 1.74832370441146e-05 1.6643113089016e-05 3.09240725982512e-05 -5.45627162216353e-06 8.46316673273527e-06 -5.0519281931036e-06 5.81150991626632e-06 -3.84055409257552e-06 -5.45627162216353e-06 1.45222994689071e-05 1.48034235645953e-06 -1.3041476703081e-06 -1.74776215496629e-06 4.61010485364601e-06 8.46316673273527e-06 1.48034235645953e-06 6.96378357792562e-05 -4.17298728394798e-05 -5.10475112714019e-06 -2.84666742456534e-06 -5.0519281931036e-06 -1.3041476703081e-06 -4.17298728394798e-05 7.26165710185505e-05 1.21206662002353e-07 1.74832370441146e-05 5.81150991626632e-06 -1.74776215496629e-06 -5.10475112714019e-06 1.21206662002353e-07 5.69020257730518e-05 2453 2451 0 2 30 2448 2463 0 28 23 0 0 0 0 0 29 60 0 618 0 14 14 0 0 2427 +378 408 0.999994969933722 0.000135673586437343 0.00316886413899441 -0.0141303424329285 -0.000140721920398391 0.999998721374383 0.00159293657751656 0.013631345148967 -0.00316864396778511 -0.00159337449358712 0.999993710406785 -0.00576489301157605 3.12389261972286e-05 2.19405309381137e-05 -3.02232784095995e-06 -2.67643529403247e-06 3.57094069355114e-06 2.03409744366604e-05 2.19405309381137e-05 3.39809662038237e-05 -2.04645751288572e-06 4.38478893984379e-06 -2.4979532528405e-06 1.81944062399307e-05 -3.02232784095995e-06 -2.04645751288572e-06 1.20863293531731e-05 1.93478317012349e-06 1.80308973782866e-06 -3.27196907336452e-07 -2.67643529403247e-06 4.38478893984379e-06 1.93478317012349e-06 4.9954759299733e-05 -2.30443746703051e-05 -6.34765133595264e-06 3.57094069355114e-06 -2.4979532528405e-06 1.80308973782866e-06 -2.30443746703051e-05 3.93235715705333e-05 6.54164320158528e-06 2.03409744366604e-05 1.81944062399307e-05 -3.27196907336452e-07 -6.34765133595264e-06 6.54164320158528e-06 5.02452766909987e-05 2403 2405 0 12 17 2396 2423 0 41 11 0 0 0 0 0 21 53 0 497 0 44 62 0 0 2330 +378 422 0.999999028786027 0.000325970923349719 -0.00135505348954308 -0.0161882358585977 -0.000325429208184772 0.999999867057796 0.000399975274209327 0.0136743531840042 0.00135518368970873 -0.000399533911763602 0.999999001924412 -0.0129915625982689 3.08798183083189e-05 1.63547374137965e-05 -9.79492695622084e-06 3.46251115533513e-06 1.14534216088345e-05 1.52471799231716e-05 1.63547374137965e-05 2.66087135355889e-05 -9.14676911192761e-06 1.11655831861256e-05 2.08669676886282e-06 1.65042987053908e-05 -9.79492695622084e-06 -9.14676911192761e-06 1.44040808159688e-05 -3.69223014153789e-06 -3.41307687595195e-06 -2.15142276892641e-06 3.46251115533513e-06 1.11655831861256e-05 -3.69223014153789e-06 5.81602624841118e-05 -1.06602427121918e-05 3.15583163732879e-06 1.14534216088345e-05 2.08669676886282e-06 -3.41307687595195e-06 -1.06602427121918e-05 5.02656599115751e-05 3.5316663890987e-06 1.52471799231716e-05 1.65042987053908e-05 -2.15142276892641e-06 3.15583163732879e-06 3.5316663890987e-06 5.13145491833909e-05 2552 2554 0 12 16 2547 2571 0 41 11 0 0 0 0 0 24 58 0 611 0 51 66 0 0 2397 +379 383 0.999999759260961 0.000692484704318037 -4.407894757279e-05 -0.00821457740623669 -0.000692458787858601 0.999999588973916 0.000585280126748679 0.00467614135126727 4.44842269907076e-05 -0.000585249462994298 0.999999827752095 -0.00275622053870815 3.52998628462997e-05 1.58459873968209e-05 -6.96932711536919e-06 3.68478448709525e-06 5.3453100900078e-06 1.06776050821156e-05 1.58459873968209e-05 2.33770997085294e-05 -8.00011649425033e-06 6.92609380128728e-06 4.84657114386183e-06 1.36505083187184e-05 -6.96932711536919e-06 -8.00011649425033e-06 1.35271578635172e-05 5.79129915774049e-07 -3.0995971734973e-06 -3.89678282992998e-06 3.68478448709525e-06 6.92609380128728e-06 5.79129915774049e-07 3.77044015815579e-05 -3.17225615049197e-06 1.90835856944947e-06 5.3453100900078e-06 4.84657114386183e-06 -3.0995971734973e-06 -3.17225615049197e-06 3.45741869142355e-05 4.62592330514349e-06 1.06776050821156e-05 1.36505083187184e-05 -3.89678282992998e-06 1.90835856944947e-06 4.62592330514349e-06 3.78648663856491e-05 3304 3275 0 12 61 3280 3324 0 47 32 0 0 0 0 0 21 51 0 649 0 57 34 0 0 2704 +379 414 0.999997767839444 0.000500948536910855 0.00205264870161802 -0.0121144630900783 -0.000502403269173416 0.999999622982496 0.000708255476458549 0.00726958945097353 -0.00205229312818884 -0.000709285152936769 0.999997642500965 -0.00484475046807579 3.07651353534788e-05 1.90587066452502e-05 -7.93524478879472e-06 -6.90553200358934e-08 1.2656015526566e-05 2.16617413622545e-05 1.90587066452502e-05 2.74487623110173e-05 -7.79303519537385e-06 5.35713510073296e-06 8.25978084653644e-06 1.65779961578523e-05 -7.93524478879472e-06 -7.79303519537385e-06 1.34420288116598e-05 1.70560213140443e-06 -1.82439232717165e-06 -3.3070130832065e-06 -6.90553200358934e-08 5.35713510073296e-06 1.70560213140443e-06 5.4650957078118e-05 -9.44591969320595e-06 7.41984681654488e-06 1.2656015526566e-05 8.25978084653644e-06 -1.82439232717165e-06 -9.44591969320595e-06 4.06854092191793e-05 6.32691695097562e-06 2.16617413622545e-05 1.65779961578523e-05 -3.3070130832065e-06 7.41984681654488e-06 6.32691695097562e-06 5.9963769322935e-05 2315 2314 0 16 11 2315 2352 0 43 9 0 0 0 0 0 17 47 0 613 0 12 17 0 0 2474 +379 415 0.999998931741143 -0.000109327898386914 0.00145758841350423 -0.012214128442594 0.000104440656572099 0.999994374503744 0.003352618829509 0.00722716248198034 -0.00145794674861679 -0.00335246301655332 0.999993317669174 -0.0114426588060337 4.321900382812e-05 2.43269095352615e-05 -6.70613350801531e-06 1.00415814063769e-05 1.90894710545241e-06 2.4181698492366e-05 2.43269095352615e-05 3.10223844434439e-05 -7.78875144800924e-06 9.37274422311262e-06 4.25259556160325e-06 1.95633376830152e-05 -6.70613350801531e-06 -7.78875144800924e-06 1.11580180254162e-05 -1.14867340204278e-06 2.42963414106401e-06 -2.18058019847328e-06 1.00415814063769e-05 9.37274422311262e-06 -1.14867340204278e-06 5.82941585460161e-05 -2.51782574225826e-05 9.34943163088349e-06 1.90894710545241e-06 4.25259556160325e-06 2.42963414106401e-06 -2.51782574225826e-05 5.10754544258481e-05 5.50647220744846e-06 2.4181698492366e-05 1.95633376830152e-05 -2.18058019847328e-06 9.34943163088349e-06 5.50647220744846e-06 5.7388831710667e-05 2684 2683 0 12 14 2682 2712 0 46 12 0 0 0 0 0 26 57 0 589 0 57 62 0 0 2364 +378 407 0.999997853136545 0.000745105757811714 0.00193353037508704 -0.0122494856304843 -0.000747963689221111 0.999998628345781 0.0014777878319159 0.00886258501141438 -0.00193242661472956 -0.00147923086981978 0.999997038797322 -0.00730261827969311 2.16648568999518e-05 1.69356823808609e-05 -9.17796391008064e-07 1.61632934998656e-06 1.30234887925478e-06 1.50840958965342e-05 1.69356823808609e-05 2.36880686317447e-05 -3.01072304287633e-06 4.01830581653608e-06 3.87921336705657e-07 1.41267666581488e-05 -9.17796391008064e-07 -3.01072304287633e-06 1.08476445876318e-05 6.96205333924181e-07 3.42734789671016e-06 -1.46609635485097e-06 1.61632934998656e-06 4.01830581653608e-06 6.96205333924181e-07 3.96387266556155e-05 -6.62208761474584e-06 4.9815211109109e-06 1.30234887925478e-06 3.87921336705657e-07 3.42734789671016e-06 -6.62208761474584e-06 3.12779739939663e-05 1.48530775654859e-06 1.50840958965342e-05 1.41267666581488e-05 -1.46609635485097e-06 4.9815211109109e-06 1.48530775654859e-06 4.22659865487732e-05 2826 2822 0 16 19 2814 2848 0 42 14 0 0 0 0 0 18 47 0 488 0 18 24 0 0 2343 +379 416 0.999998202309108 0.00121746980126644 0.0014536663422117 -0.0172187462044758 -0.0012214945807614 0.999995414636336 0.00277103902738377 0.014245708349399 -0.00145028602028891 -0.0027728096914714 0.999995104086452 -0.00519347739193308 3.70492451261519e-05 7.07444670624809e-06 -8.61529962650755e-06 -9.99466235867556e-07 1.9582940942407e-06 1.63050121771641e-05 7.07444670624809e-06 3.59091517806692e-05 -9.31110897246482e-06 1.05984630705168e-05 1.04799632455484e-05 1.46750403229753e-05 -8.61529962650755e-06 -9.31110897246482e-06 1.49304627445854e-05 -3.42945009918714e-07 -2.66446374518473e-06 -2.94075528636925e-06 -9.99466235867556e-07 1.05984630705168e-05 -3.42945009918714e-07 5.67490666662269e-05 -2.95329001289937e-05 2.52663325786234e-07 1.9582940942407e-06 1.04799632455484e-05 -2.66446374518473e-06 -2.95329001289937e-05 6.76036092056255e-05 2.6966388788407e-06 1.63050121771641e-05 1.46750403229753e-05 -2.94075528636925e-06 2.52663325786234e-07 2.6966388788407e-06 5.93103817775634e-05 2295 2294 0 9 12 2299 2338 0 47 12 0 0 0 0 0 27 56 0 622 0 19 25 0 0 2286 +379 382 0.999996097085862 0.000338824128603258 0.00277326725225625 -0.00576504726805375 -0.000343122870573094 0.99999874029311 0.00154973510263979 0.00559055308982163 -0.00277273867110667 -0.0015506806255772 0.999994953642197 -0.00525267810331066 2.85959828291124e-05 1.66500784162029e-05 -6.78488915267396e-06 4.59321913081942e-06 3.0178432469869e-06 1.53504374870789e-05 1.66500784162029e-05 2.63820278490047e-05 -8.90375305493722e-06 1.07814216691937e-05 -1.01311995830859e-06 1.66928434203497e-05 -6.78488915267396e-06 -8.90375305493722e-06 1.23541451327703e-05 -1.84445722452735e-07 -1.57713404578477e-06 -3.77393742450198e-06 4.59321913081942e-06 1.07814216691937e-05 -1.84445722452735e-07 5.52758148932742e-05 -1.94101528846352e-05 9.16736731430199e-06 3.0178432469869e-06 -1.01311995830859e-06 -1.57713404578477e-06 -1.94101528846352e-05 4.22240278905837e-05 8.54807733550503e-07 1.53504374870789e-05 1.66928434203497e-05 -3.77393742450198e-06 9.16736731430199e-06 8.54807733550503e-07 4.31870845895649e-05 2721 2697 0 17 57 2692 2715 0 42 27 0 0 0 0 0 22 51 0 680 0 97 81 0 0 2775 +379 381 0.999999346987792 0.000890407913700176 0.00071637820791243 -0.00592661540511199 -0.000891081557290534 0.999999160643658 0.000940577289077003 0.00345060901357032 -0.000715540109154198 -0.000941215026277666 0.999999301058069 -0.00103199371465443 2.79559019589879e-05 1.83291754641754e-05 -7.56566933215795e-06 7.04452986387134e-06 4.35427129847741e-06 1.24965453679101e-05 1.83291754641754e-05 2.45457194187332e-05 -8.35356697638607e-06 7.69249491961857e-06 2.55292396023983e-06 1.27954874113293e-05 -7.56566933215795e-06 -8.35356697638607e-06 1.25786129911312e-05 6.6188747905134e-07 -1.01314016462108e-06 -1.80983200646044e-06 7.04452986387134e-06 7.69249491961857e-06 6.6188747905134e-07 3.42552881278755e-05 -5.12290226187679e-06 -6.00707180121661e-07 4.35427129847741e-06 2.55292396023983e-06 -1.01314016462108e-06 -5.12290226187679e-06 3.58898535477971e-05 1.05841695946256e-05 1.24965453679101e-05 1.27954874113293e-05 -1.80983200646044e-06 -6.00707180121661e-07 1.05841695946256e-05 3.41165659732185e-05 2225 2204 0 15 48 2197 2228 0 48 25 0 0 0 0 0 16 49 0 661 0 97 82 0 0 2792 +379 417 0.999999600305162 0.000505300648840528 -0.00073760475195305 -0.0141439387180331 -0.000505846208100401 0.999999598528106 -0.000739637235685766 0.00551496355600895 0.000737230716650374 0.000740010054623434 0.999999454437846 -0.00470264500572169 2.53591910151013e-05 1.69371912721573e-05 -7.19792533954563e-06 5.05042776388859e-06 3.75730788052134e-06 1.35832973147374e-05 1.69371912721573e-05 2.14988094743642e-05 -8.57793624441635e-06 5.87495708431626e-06 4.9929496897753e-06 1.67756119459009e-05 -7.19792533954563e-06 -8.57793624441635e-06 1.33849696617607e-05 -3.89693927363878e-07 -4.34908490593444e-07 -3.08229153508315e-06 5.05042776388859e-06 5.87495708431626e-06 -3.89693927363878e-07 4.70863557797466e-05 -1.65415088808921e-06 5.61585812288858e-06 3.75730788052134e-06 4.9929496897753e-06 -4.34908490593444e-07 -1.65415088808921e-06 4.04620943161292e-05 8.32812481162091e-06 1.35832973147374e-05 1.67756119459009e-05 -3.08229153508315e-06 5.61585812288858e-06 8.32812481162091e-06 4.21812879900769e-05 3149 3150 0 20 13 3146 3186 0 48 12 0 0 0 0 0 15 49 0 610 0 15 19 0 0 2354 +379 418 0.999999854095328 0.000396088267913431 -0.000367319216264094 -0.0164733566747319 -0.000395891036303268 0.99999977752249 0.000536866145443379 0.012191689351845 0.000367531780925479 -0.000536720648726919 0.999999788425645 -0.00855539989672174 3.48782603327982e-05 2.53178983363891e-05 -1.01356276303116e-05 1.18909685606325e-05 6.44774819334532e-06 1.86063742771438e-05 2.53178983363891e-05 2.749713572424e-05 -9.37937095143342e-06 1.30080504290701e-05 -1.69547497799688e-06 1.6244750875821e-05 -1.01356276303116e-05 -9.37937095143342e-06 1.29769454879215e-05 -9.10324186984711e-08 -3.11066437504127e-06 -4.943487271527e-06 1.18909685606325e-05 1.30080504290701e-05 -9.10324186984711e-08 6.97073615852068e-05 -3.62070002678097e-05 8.07332445251838e-06 6.44774819334532e-06 -1.69547497799688e-06 -3.11066437504127e-06 -3.62070002678097e-05 6.71787953764444e-05 7.96247411673325e-06 1.86063742771438e-05 1.6244750875821e-05 -4.943487271527e-06 8.07332445251838e-06 7.96247411673325e-06 4.82034218018628e-05 2467 2469 0 10 13 2458 2489 0 46 7 0 0 0 0 0 19 52 0 625 0 62 71 0 0 2288 +379 426 0.999999777964346 0.000629603382128268 0.000218336530741275 -0.0132967587856096 -0.000629528126748648 0.999999742481624 -0.000344573684547345 0.0124807156597356 -0.00021855341927279 0.000344436159052503 0.999999916799064 -0.0086936153579397 3.83818910769008e-05 2.46685057793175e-05 -9.27554980108737e-06 1.18445726868739e-05 3.4421564240981e-06 1.45529123982105e-05 2.46685057793175e-05 3.04851504410469e-05 -1.08671709284324e-05 9.67369236581979e-06 8.77048203842521e-06 1.80641792606164e-05 -9.27554980108737e-06 -1.08671709284324e-05 1.48869166359711e-05 -5.58161774404279e-06 -4.01948934481924e-06 -4.31378475179949e-06 1.18445726868739e-05 9.67369236581979e-06 -5.58161774404279e-06 7.49561704670898e-05 -3.29434168959234e-05 -2.21751684753148e-06 3.4421564240981e-06 8.77048203842521e-06 -4.01948934481924e-06 -3.29434168959234e-05 7.98154100519755e-05 1.46413580213784e-05 1.45529123982105e-05 1.80641792606164e-05 -4.31378475179949e-06 -2.21751684753148e-06 1.46413580213784e-05 5.76224197084637e-05 2384 2380 0 8 17 2373 2403 0 49 8 0 0 0 0 0 23 52 0 655 0 62 72 0 0 2116 +379 420 0.999996431867088 0.000605643935787215 0.00260181638791463 -0.00947105032465028 -0.000606814969948954 0.999999714944652 0.000449317489406562 0.0113466273865602 -0.00260154351984025 -0.000450894707315285 0.999996514326564 -0.0119992645446378 3.59864258356316e-05 1.64937865246546e-05 -9.72407193901528e-06 2.73551619776619e-06 1.03625910662111e-05 1.55351381416688e-05 1.64937865246546e-05 3.74769660500231e-05 -9.70177623101209e-06 2.13547048041451e-05 1.15905954960208e-06 1.55720287214049e-05 -9.72407193901528e-06 -9.70177623101209e-06 1.48750451545952e-05 -8.13980465079838e-07 -3.67644224403519e-06 -4.75678998517305e-06 2.73551619776619e-06 2.13547048041451e-05 -8.13980465079838e-07 9.29738888856362e-05 -4.50983988139811e-05 3.11141805167559e-06 1.03625910662111e-05 1.15905954960208e-06 -3.67644224403519e-06 -4.50983988139811e-05 7.79342290546119e-05 6.29666526078185e-06 1.55351381416688e-05 1.55720287214049e-05 -4.75678998517305e-06 3.11141805167559e-06 6.29666526078185e-06 5.21754669999948e-05 2145 2147 0 14 11 2133 2165 0 46 5 0 0 0 0 0 16 47 0 633 0 57 67 0 0 2278 +379 423 0.999999988612844 0.000150888258406347 2.65429876674559e-06 -0.0211909191288854 -0.000150890695412028 0.999999543582086 0.000943433949645355 0.0180798099423423 -2.51194444969267e-06 -0.000943434339411312 0.99999955496257 -0.00921073352261001 3.04315512653624e-05 1.6925151428732e-05 -8.37066788538323e-06 7.04936125326067e-06 7.36833750098445e-06 1.59778843504741e-05 1.6925151428732e-05 2.67656037553002e-05 -1.00022985809833e-05 1.23209089012902e-05 2.86126413664758e-06 6.88605745542639e-06 -8.37066788538323e-06 -1.00022985809833e-05 1.40632047021911e-05 -2.21261220280242e-06 -1.72453363718968e-06 -4.20440152343377e-06 7.04936125326067e-06 1.23209089012902e-05 -2.21261220280242e-06 8.38573274630857e-05 -4.35513448085229e-05 -6.49082978557896e-06 7.36833750098445e-06 2.86126413664758e-06 -1.72453363718968e-06 -4.35513448085229e-05 7.72415222760462e-05 1.28115017392237e-05 1.59778843504741e-05 6.88605745542639e-06 -4.20440152343377e-06 -6.49082978557896e-06 1.28115017392237e-05 4.66362996537778e-05 2195 2193 0 11 12 2184 2212 0 42 4 0 0 0 0 0 23 52 0 633 0 56 65 0 0 2298 +379 427 0.999984285259221 0.000308158003956488 0.00559770249749644 -0.00602135846758252 -0.000330300527569564 0.999992123808983 0.00395515126913416 0.00852960907032639 -0.00559643959740187 -0.00395693803904533 0.999976510976727 -0.00983202454162888 3.48306332901258e-05 8.22616059625513e-06 -1.0086415079806e-05 -1.24324744110419e-06 1.21830609569854e-05 5.26066621595212e-06 8.22616059625513e-06 3.32200167321185e-05 -8.73417697474393e-06 1.82915479888996e-05 4.40235207530098e-06 1.34198118203487e-05 -1.0086415079806e-05 -8.73417697474393e-06 1.50255672787306e-05 -2.09966900277719e-06 -4.72886016267359e-06 -3.39675610828343e-06 -1.24324744110419e-06 1.82915479888996e-05 -2.09966900277719e-06 5.97056316734586e-05 -1.158254232836e-05 7.80324448598798e-06 1.21830609569854e-05 4.40235207530098e-06 -4.72886016267359e-06 -1.158254232836e-05 5.39511480094324e-05 7.3222247756967e-06 5.26066621595212e-06 1.34198118203487e-05 -3.39675610828343e-06 7.80324448598798e-06 7.3222247756967e-06 5.29380661118979e-05 2751 2749 0 17 17 2742 2768 0 43 13 0 0 0 0 0 25 55 0 674 0 58 64 0 0 2362 +379 413 0.999999881832681 -0.00011335598947801 0.000472742047713152 -0.0135379327710146 0.000112630591570546 0.999998816783849 0.00153419205164754 0.00375038399276733 -0.00047291539821519 -0.00153413862513968 0.999998711384022 -0.010145835469605 3.57813571706356e-05 1.83753604681806e-05 -8.14212145469482e-06 4.639211669861e-06 3.24185391847052e-08 2.12098519829751e-05 1.83753604681806e-05 3.52021587928054e-05 -9.51052535566541e-06 9.41429012673707e-06 9.49422812667949e-06 1.96722356926619e-05 -8.14212145469482e-06 -9.51052535566541e-06 1.4371602475158e-05 -7.59730012788882e-07 -4.00904407000796e-07 -4.10664048181262e-06 4.639211669861e-06 9.41429012673707e-06 -7.59730012788882e-07 6.44263887662946e-05 -1.2817142879193e-05 1.38301005491557e-05 3.24185391847052e-08 9.49422812667949e-06 -4.00904407000796e-07 -1.2817142879193e-05 4.95444432703706e-05 5.17750224039451e-06 2.12098519829751e-05 1.96722356926619e-05 -4.10664048181262e-06 1.38301005491557e-05 5.17750224039451e-06 6.22612407762618e-05 2250 2246 0 12 11 2235 2268 0 48 4 0 0 0 0 0 23 56 0 613 0 39 50 0 0 2248 +379 412 0.999992701925947 -0.000323973640857586 0.00380672246494759 -0.0132722211447358 0.000315876090036143 0.99999768681008 0.00212758002994874 0.0133808292704534 -0.00380740293912407 -0.00212636205010405 0.999990491088436 -0.0077437962926685 3.49778653935387e-05 2.11569849133175e-05 -7.280299346618e-06 6.87716797591965e-06 6.05757947984936e-06 1.55590307684087e-05 2.11569849133175e-05 4.77225584056788e-05 -7.78121395275973e-06 2.29930283948676e-05 -5.74182310846847e-07 2.12570385707454e-05 -7.280299346618e-06 -7.78121395275973e-06 1.36834100787332e-05 -1.271576964874e-07 -1.11334446508201e-06 -3.84895216163173e-06 6.87716797591965e-06 2.29930283948676e-05 -1.271576964874e-07 7.36028814369296e-05 -4.2006802043555e-05 1.25744073384487e-05 6.05757947984936e-06 -5.74182310846847e-07 -1.11334446508201e-06 -4.2006802043555e-05 6.68584636366217e-05 -1.66598082858454e-06 1.55590307684087e-05 2.12570385707454e-05 -3.84895216163173e-06 1.25744073384487e-05 -1.66598082858454e-06 4.83023302558572e-05 2191 2189 0 11 9 2187 2214 0 43 5 0 0 0 0 0 19 49 0 580 0 57 67 0 0 2228 +379 428 0.999999478846921 0.00101662016764268 9.37513819536611e-05 -0.00708260602173717 -0.00101660305372645 0.999999466621706 -0.000182413086078272 0.00676044577797795 -9.39367767708581e-05 0.000182317683071946 0.999999978968072 -0.00970768557539718 3.23887664928497e-05 2.25031348573843e-05 -9.51846493843469e-06 6.14389860251627e-06 6.1325827976184e-06 1.80054935324997e-05 2.25031348573843e-05 2.98390137910247e-05 -1.17110448904192e-05 4.74192037377458e-06 5.56743909510285e-06 2.32287339736301e-05 -9.51846493843469e-06 -1.17110448904192e-05 1.44657607061922e-05 -2.41166904689857e-06 -1.37615724619345e-06 -4.55498380423985e-06 6.14389860251627e-06 4.74192037377458e-06 -2.41166904689857e-06 5.76022968333077e-05 -1.40003758423329e-05 1.93703456670273e-06 6.1325827976184e-06 5.56743909510285e-06 -1.37615724619345e-06 -1.40003758423329e-05 4.81340569741083e-05 7.73232104151426e-06 1.80054935324997e-05 2.32287339736301e-05 -4.55498380423985e-06 1.93703456670273e-06 7.73232104151426e-06 5.92397171253517e-05 2928 2924 0 11 16 2929 2962 0 47 18 0 0 0 0 0 18 50 0 633 0 56 63 0 0 2319 +379 411 0.999981810179317 0.000229145713902097 0.00602717203481278 -0.00774803941445217 -0.000252513320679803 0.999992454200021 0.00387656807511902 0.0101459170277705 -0.00602623825601911 -0.00387801950226569 0.999974322378941 -0.0074604137545353 6.76594396341029e-05 3.27766072090512e-05 -5.14834692494605e-06 1.12427267311748e-05 -1.01654682636324e-05 2.98870001951978e-05 3.27766072090512e-05 5.98579993510711e-05 -2.96064044668474e-06 1.65084748519707e-05 -2.40678012811102e-06 3.82530737078564e-05 -5.14834692494605e-06 -2.96064044668474e-06 1.21550071778938e-05 8.39135234814123e-07 3.04303859289369e-06 -1.35649187224733e-06 1.12427267311748e-05 1.65084748519707e-05 8.39135234814123e-07 7.37497386185516e-05 -4.5302315719673e-05 1.83490965890948e-07 -1.01654682636324e-05 -2.40678012811102e-06 3.04303859289369e-06 -4.5302315719673e-05 6.65152868127029e-05 5.59121520053765e-06 2.98870001951978e-05 3.82530737078564e-05 -1.35649187224733e-06 1.83490965890948e-07 5.59121520053765e-06 7.73901085373137e-05 2178 2179 0 17 11 2161 2191 0 44 6 0 0 0 0 0 22 53 0 554 0 56 64 0 0 2268 +379 419 0.999997138014287 0.00059840691604092 0.00231643527825978 -0.0126900847219534 -0.000603047633186735 0.999997811744085 0.00200320757636895 0.0119670393429172 -0.00231523147603861 -0.00200459876402947 0.999995310632509 -0.0116205766257994 3.43187423604406e-05 1.42484076907094e-05 -8.6209850792584e-06 7.42752839111486e-06 3.36740134345599e-06 8.39018983364227e-06 1.42484076907094e-05 2.82002368101463e-05 -7.67725592585667e-06 2.67080317342366e-06 4.04392584238609e-06 1.15815585397319e-05 -8.6209850792584e-06 -7.67725592585667e-06 1.32700115254014e-05 -1.95512671777554e-07 -2.96249389886115e-06 4.91549229985107e-07 7.42752839111486e-06 2.67080317342366e-06 -1.95512671777554e-07 4.46591227867949e-05 -1.48116934933911e-05 1.25904410208477e-06 3.36740134345599e-06 4.04392584238609e-06 -2.96249389886115e-06 -1.48116934933911e-05 5.30429368465046e-05 -5.99402533143857e-06 8.39018983364227e-06 1.15815585397319e-05 4.91549229985107e-07 1.25904410208477e-06 -5.99402533143857e-06 5.66621189401652e-05 2729 2729 0 10 14 2733 2758 0 41 14 0 0 0 0 0 20 51 0 608 0 56 63 0 0 2327 +379 425 0.999999173402221 0.000474544112100691 -0.00119499069467373 -0.0184297895239303 -0.000472259506761906 0.99999806180543 0.00191137551012241 0.00916890927651131 0.0011958954105436 -0.00191080958446761 0.999997459317222 -0.00718224713272172 4.32369898682252e-05 2.22320938912245e-05 -1.10411938998811e-05 4.79645730455297e-06 7.57450429919007e-06 1.50064000595557e-05 2.22320938912245e-05 4.61452614918693e-05 -9.47898236866337e-06 1.25565137372659e-05 3.91605918980472e-06 1.63869944172525e-05 -1.10411938998811e-05 -9.47898236866337e-06 1.73131458462919e-05 -1.49032703569488e-06 -4.90047587469146e-06 -4.6674820355067e-06 4.79645730455297e-06 1.25565137372659e-05 -1.49032703569488e-06 8.2382918664735e-05 -4.0906909023366e-05 -1.79126872547202e-06 7.57450429919007e-06 3.91605918980472e-06 -4.90047587469146e-06 -4.0906909023366e-05 8.00215340724055e-05 -2.02572037578627e-06 1.50064000595557e-05 1.63869944172525e-05 -4.6674820355067e-06 -1.79126872547202e-06 -2.02572037578627e-06 5.26119217337621e-05 2276 2274 0 12 16 2281 2305 0 42 17 0 0 0 0 0 26 55 0 632 0 45 58 0 0 2058 +379 424 0.99999999791367 6.45643980970242e-05 2.02470720690142e-06 -0.00782570880354116 -6.45612153638091e-05 0.999998820710618 -0.00153440842777082 -0.000886408838849307 -2.12377297575973e-06 0.00153440829385198 0.999998822792646 -0.00577146393130612 2.81975891372301e-05 1.66701908123148e-05 -9.36177071456293e-06 4.80106536922604e-06 5.65283325473348e-06 1.52775930023085e-05 1.66701908123148e-05 2.11555072053998e-05 -9.31304844909702e-06 5.94294669139205e-06 6.83300330917921e-06 1.70597680843571e-05 -9.36177071456293e-06 -9.31304844909702e-06 1.37585755499196e-05 -7.38045940748062e-07 -1.37039035014424e-06 -5.67122821919419e-06 4.80106536922604e-06 5.94294669139205e-06 -7.38045940748062e-07 5.79845354497002e-05 -1.53762246792199e-05 6.6208531985157e-06 5.65283325473348e-06 6.83300330917921e-06 -1.37039035014424e-06 -1.53762246792199e-05 6.01964951380569e-05 1.33226009551824e-05 1.52775930023085e-05 1.70597680843571e-05 -5.67122821919419e-06 6.6208531985157e-06 1.33226009551824e-05 5.38343278044066e-05 2429 2427 0 15 15 2425 2452 0 46 15 0 0 0 0 0 13 44 0 628 0 53 67 0 0 2320 +379 421 0.99999994699408 0.000318060185842723 -6.96387536682773e-05 -0.0146482624111623 -0.000318061123346182 0.999999949328085 -1.3451720565883e-05 0.0132169692980484 6.96344716828052e-05 1.34738692330824e-05 0.999999997484748 -0.00802393773374132 2.63984034429383e-05 1.86134821625623e-05 -8.85884308423984e-06 -9.27205697906608e-07 1.29466204691065e-05 9.98344776789814e-06 1.86134821625623e-05 2.8278646702704e-05 -9.56027585472433e-06 3.25488635684084e-06 8.2372505587999e-06 1.6595236111559e-05 -8.85884308423984e-06 -9.56027585472433e-06 1.42830885124707e-05 -2.06248597315259e-07 -4.20992846325442e-06 -2.60213367310134e-06 -9.27205697906608e-07 3.25488635684084e-06 -2.06248597315259e-07 5.51429258797436e-05 -2.09356710788391e-05 -2.57746136063623e-06 1.29466204691065e-05 8.2372505587999e-06 -4.20992846325442e-06 -2.09356710788391e-05 5.90318198396404e-05 6.25905609050217e-06 9.98344776789814e-06 1.6595236111559e-05 -2.60213367310134e-06 -2.57746136063623e-06 6.25905609050217e-06 4.77476803087059e-05 2423 2420 0 12 14 2417 2446 0 44 11 0 0 0 0 0 22 55 0 630 0 59 69 0 0 2415 +379 408 0.999997073228361 0.000906803178060817 0.00224304318006226 -0.0130105237961516 -0.000907803680666117 0.999999488902871 0.000445069067153161 0.00636514719624696 -0.00224263844360478 -0.000447104007392391 0.999997385331991 -0.00498024492383033 2.67968284158604e-05 2.35376051030148e-05 -1.43328811949602e-06 2.02142604977069e-06 3.13828264444572e-06 2.35775307258678e-05 2.35376051030148e-05 3.40891059236983e-05 -2.51161926009613e-06 3.45130088321625e-06 4.01956886514065e-06 2.74014068425905e-05 -1.43328811949602e-06 -2.51161926009613e-06 1.17842293480412e-05 1.65483210246967e-06 2.54933624305525e-06 6.36067310423816e-08 2.02142604977069e-06 3.45130088321625e-06 1.65483210246967e-06 4.14522996978164e-05 -1.01772543045809e-05 5.68082994087293e-07 3.13828264444572e-06 4.01956886514065e-06 2.54933624305525e-06 -1.01772543045809e-05 3.43947462291317e-05 5.89544665733044e-06 2.35775307258678e-05 2.74014068425905e-05 6.36067310423816e-08 5.68082994087293e-07 5.89544665733044e-06 5.83257855228743e-05 2806 2809 0 19 15 2803 2841 0 42 15 0 0 0 0 0 17 49 0 498 0 18 23 0 0 2323 +379 409 0.999999854201715 0.000519949263364694 0.000145771439788327 -0.0155278969508505 -0.000519897504029641 0.999999801881527 -0.000354885180105872 0.00533483647501643 -0.000145955933196287 0.000354809342156516 0.999999926403595 -0.00196205219822228 4.06084266838977e-05 2.19878215095369e-05 -8.60923459145233e-07 -9.17811408799679e-07 -8.08927009585603e-07 2.49133306633078e-05 2.19878215095369e-05 4.7040803079572e-05 -1.73381762798502e-06 1.81962049920941e-05 -2.76484576189354e-06 2.14728890858641e-05 -8.60923459145233e-07 -1.73381762798502e-06 1.26017975423342e-05 2.74666685874817e-06 4.06838784134859e-06 4.11032747484843e-07 -9.17811408799679e-07 1.81962049920941e-05 2.74666685874817e-06 7.5393001559794e-05 -1.49056227454662e-05 -7.09804879679088e-06 -8.08927009585603e-07 -2.76484576189354e-06 4.06838784134859e-06 -1.49056227454662e-05 3.81963523676326e-05 6.49425605302792e-06 2.49133306633078e-05 2.14728890858641e-05 4.11032747484843e-07 -7.09804879679088e-06 6.49425605302792e-06 6.67995943069225e-05 1692 1688 0 11 10 1695 1723 0 45 10 0 0 0 0 0 18 48 0 509 0 39 52 0 0 2336 +379 410 0.999999666221526 0.000517759821547448 0.000632045570639022 -0.0117503573438874 -0.000517508470081796 0.999999786978749 -0.000397778129731398 0.00781263781936637 -0.000632251389533349 0.000397450908025337 0.999999721145439 -0.00463331908716675 2.61137684190521e-05 1.70498893707551e-05 -1.33162177342916e-06 -3.04260197367847e-06 3.10782512814758e-06 1.14868067514914e-05 1.70498893707551e-05 3.36941454475491e-05 -2.5347903518216e-06 6.99468240810337e-06 5.57511495320014e-06 1.89942496481149e-05 -1.33162177342916e-06 -2.5347903518216e-06 1.29877481132848e-05 3.84708722369966e-06 3.40814889708558e-06 1.15781247232557e-06 -3.04260197367847e-06 6.99468240810337e-06 3.84708722369966e-06 6.89392480860191e-05 -2.25220188912202e-05 -6.11271793297596e-06 3.10782512814758e-06 5.57511495320014e-06 3.40814889708558e-06 -2.25220188912202e-05 5.98597392738193e-05 1.11240785970976e-05 1.14868067514914e-05 1.89942496481149e-05 1.15781247232557e-06 -6.11271793297596e-06 1.11240785970976e-05 5.81678405168969e-05 1712 1709 0 17 9 1699 1725 0 43 5 0 0 0 0 0 22 51 0 513 0 38 50 0 0 2255 +379 422 0.99999909528925 0.000872549782473642 -0.00102375659144257 -0.0153623393424115 -0.000872236954104935 0.999999572790665 0.000305975787664832 0.012160890254352 0.00102402313319116 -0.000305082552514183 0.999999429150466 -0.00778429017365429 4.76308809651039e-05 2.47118229773168e-05 -1.04533972335832e-05 1.80285283666896e-06 1.37710178837135e-05 2.54039134413617e-05 2.47118229773168e-05 3.50921089713223e-05 -1.06193378168727e-05 7.15054277431672e-06 1.02929605454465e-05 1.74324050355325e-05 -1.04533972335832e-05 -1.06193378168727e-05 1.41046019811793e-05 -2.3134875538111e-06 -3.67107168909454e-06 -3.40413502368303e-06 1.80285283666896e-06 7.15054277431672e-06 -2.3134875538111e-06 4.38603310462911e-05 -1.96313496082992e-06 -4.92462384661654e-06 1.37710178837135e-05 1.02929605454465e-05 -3.67107168909454e-06 -1.96313496082992e-06 4.25195814123816e-05 7.50738307873619e-06 2.54039134413617e-05 1.74324050355325e-05 -3.40413502368303e-06 -4.92462384661654e-06 7.50738307873619e-06 5.75923008158559e-05 3013 3015 0 17 14 3017 3058 0 48 11 0 0 0 0 0 24 58 0 605 0 16 19 0 0 2390 +379 407 0.999998725400834 0.00140555913001313 0.000757364007457438 -0.0147245071479708 -0.00140665733410249 0.99999795728981 0.00145145835322506 0.00927449147217106 -0.000755322349842053 -0.00145252185483313 0.999998659833306 -0.000345100961979218 3.20430436103622e-05 1.2841205883543e-05 -1.77039309734881e-06 2.55314772922451e-06 -4.03937470971655e-06 1.23073902208353e-05 1.2841205883543e-05 3.20215258835592e-05 -5.5628250159909e-06 1.08336370176326e-05 -2.99932671395588e-07 5.88632028207338e-06 -1.77039309734881e-06 -5.5628250159909e-06 1.37642316936239e-05 1.9096071914236e-06 4.52661824597309e-06 -3.84435871702875e-07 2.55314772922451e-06 1.08336370176326e-05 1.9096071914236e-06 7.91215357093094e-05 -3.23827452336768e-05 -6.72395549267414e-06 -4.03937470971655e-06 -2.99932671395588e-07 4.52661824597309e-06 -3.23827452336768e-05 5.38154628660957e-05 -1.65558276493069e-06 1.23073902208353e-05 5.88632028207338e-06 -3.84435871702875e-07 -6.72395549267414e-06 -1.65558276493069e-06 4.55161361824184e-05 2271 2267 0 16 17 2264 2293 0 50 14 0 0 0 0 0 15 45 0 488 0 51 64 0 0 2335 +380 384 0.999999770485809 0.000257626872459715 -0.000626623270636963 -0.00681785418331403 -0.000257040800507763 0.999999529677776 0.000935186748209418 0.00475693634480268 0.00062686390515922 -0.000935025465823687 0.999999366384311 -0.00285642213329191 2.81397702113879e-05 1.99131588618189e-05 -5.39876977424358e-06 2.08670903702495e-06 9.88921353326082e-06 2.0132461821586e-05 1.99131588618189e-05 2.25917569424283e-05 -7.51194813603305e-06 2.03186189859226e-06 9.32734391570729e-06 1.45235830083429e-05 -5.39876977424358e-06 -7.51194813603305e-06 1.06724483315074e-05 1.01745402683268e-06 -2.35368157392351e-06 -2.76017181724724e-06 2.08670903702495e-06 2.03186189859226e-06 1.01745402683268e-06 3.46023970615563e-05 -1.04046762606012e-05 -3.66135896135408e-06 9.88921353326082e-06 9.32734391570729e-06 -2.35368157392351e-06 -1.04046762606012e-05 3.70960710749853e-05 6.52712252058135e-06 2.0132461821586e-05 1.45235830083429e-05 -2.76017181724724e-06 -3.66135896135408e-06 6.52712252058135e-06 3.81140184337918e-05 3232 3211 0 16 59 3212 3253 0 40 33 0 0 0 0 0 21 53 0 677 0 56 33 0 0 2813 +380 383 0.999999788902481 0.000252388219750554 -0.000598744670599418 -0.00981474923595889 -0.000252812746321236 0.999999716661176 -0.000709058025511347 0.00262433164363359 0.000598565543059048 0.000709209246115476 0.999999569370675 -0.000277702808021415 2.48662143873379e-05 1.51033111295142e-05 -7.19790777338587e-06 2.93563709701785e-06 5.73423126291454e-06 1.70506740317841e-05 1.51033111295142e-05 2.34083067293575e-05 -7.81288645822101e-06 3.89971364376195e-06 6.57815974581911e-06 1.46028500663414e-05 -7.19790777338587e-06 -7.81288645822101e-06 1.25875373575437e-05 -6.10274595836978e-08 -2.40365390673472e-06 -4.92801085053001e-06 2.93563709701785e-06 3.89971364376195e-06 -6.10274595836978e-08 3.05934571061582e-05 3.27357634741866e-06 2.14747252363406e-06 5.73423126291454e-06 6.57815974581911e-06 -2.40365390673472e-06 3.27357634741866e-06 2.96197393025244e-05 2.01883121482663e-06 1.70506740317841e-05 1.46028500663414e-05 -4.92801085053001e-06 2.14747252363406e-06 2.01883121482663e-06 3.69743270008478e-05 3263 3240 0 14 60 3249 3297 0 48 32 0 0 0 0 0 19 49 0 654 0 59 36 0 0 2724 +379 429 0.99997487351343 -0.00688861521997753 0.00167311749473185 -0.0133921066282141 0.0068813288955762 0.999966981810668 0.00432233745723933 0.015659419837232 -0.00170283717101545 -0.00431071558032306 0.999989258980692 -0.00958482293962891 3.03388747636105e-05 1.30167347132668e-05 -3.88982801076679e-06 5.8976548054556e-08 1.06503959136543e-06 1.61287024012304e-05 1.30167347132668e-05 3.95407739371477e-05 -5.56190736327008e-06 1.49747310421043e-05 -4.67315881362985e-06 7.98144791607167e-06 -3.88982801076679e-06 -5.56190736327008e-06 1.28525594284521e-05 1.63044471494358e-07 -7.99090087679933e-07 -1.36817608667358e-06 5.8976548054556e-08 1.49747310421043e-05 1.63044471494358e-07 6.61128865294345e-05 -3.09969675093977e-05 4.89138255642981e-06 1.06503959136543e-06 -4.67315881362985e-06 -7.99090087679933e-07 -3.09969675093977e-05 6.04090040303214e-05 -4.92078157919314e-06 1.61287024012304e-05 7.98144791607167e-06 -1.36817608667358e-06 4.89138255642981e-06 -4.92078157919314e-06 5.86302539654455e-05 2265 2262 0 2 24 2263 2280 0 33 12 0 0 0 0 0 30 61 0 620 0 55 63 0 0 2428 +380 416 0.999999781603358 0.000403040581329589 -0.000523785762666365 -0.0124928005652208 -0.000402609855775649 0.999999580965074 0.000822176976151484 0.0096840489188346 0.000524116913868261 -0.000821965915280429 0.999999524836635 -0.00570060924549693 2.75296489801284e-05 1.6910773157552e-05 -7.54309549230556e-06 4.18162094159189e-06 6.93941448373084e-06 1.77908695087115e-05 1.6910773157552e-05 2.74534313026421e-05 -7.72830310575624e-06 7.16952162642371e-06 6.25921249592218e-06 2.10537790164798e-05 -7.54309549230556e-06 -7.72830310575624e-06 1.29785474606408e-05 4.12172435876614e-07 -1.80583234121316e-06 -3.27355289818584e-06 4.18162094159189e-06 7.16952162642371e-06 4.12172435876614e-07 3.79797528116751e-05 -6.24420615569343e-06 6.80004657407864e-06 6.93941448373084e-06 6.25921249592218e-06 -1.80583234121316e-06 -6.24420615569343e-06 3.63587075634285e-05 4.49594820569446e-06 1.77908695087115e-05 2.10537790164798e-05 -3.27355289818584e-06 6.80004657407864e-06 4.49594820569446e-06 4.76616458656202e-05 2987 2989 0 14 12 2993 3030 0 45 12 0 0 0 0 0 17 49 0 615 0 18 25 0 0 2264 +380 382 0.999999765750339 7.99537020333273e-05 0.000679784284262393 -0.0064028995334622 -8.12733141613901e-05 0.999998112147658 0.00194141591848087 0.00394592966267746 -0.000679627777540171 -0.00194147071202655 0.999997884396541 -0.00564869998751966 2.69371599921811e-05 1.6280265208613e-05 -6.68396582368849e-06 3.45263757258654e-06 4.17658943812765e-06 1.12667697546796e-05 1.6280265208613e-05 2.1783660581416e-05 -8.56620337367189e-06 4.80914672806651e-06 4.13303595348323e-06 1.42592282678471e-05 -6.68396582368849e-06 -8.56620337367189e-06 1.15359224646114e-05 -2.09669302147137e-06 -2.15647642998043e-06 -4.02335489991455e-06 3.45263757258654e-06 4.80914672806651e-06 -2.09669302147137e-06 3.04303163471541e-05 -3.64491472968353e-06 5.31838812851892e-06 4.17658943812765e-06 4.13303595348323e-06 -2.15647642998043e-06 -3.64491472968353e-06 3.14915232678048e-05 3.60817328352704e-06 1.12667697546796e-05 1.42592282678471e-05 -4.02335489991455e-06 5.31838812851892e-06 3.60817328352704e-06 2.90242308004797e-05 2831 2817 0 17 58 2809 2826 0 35 28 0 0 0 0 0 21 49 0 665 0 99 83 0 0 2798 +380 419 0.999997335044175 0.000858423420219574 0.00214313176913602 -0.012031018041697 -0.000859864196283601 0.999999404897316 0.000671445141513511 0.009072943612033 -0.00214255410951769 -0.000673286154418068 0.999997478070641 -0.0120169903590569 4.60253520990314e-05 2.93969330136002e-05 -9.45541780365012e-06 9.6733370628321e-06 6.92138808715785e-06 1.69180394292137e-05 2.93969330136002e-05 4.63628840934027e-05 -1.05963140649067e-05 1.87538139964191e-05 2.27074953546639e-08 2.23065965984044e-05 -9.45541780365012e-06 -1.05963140649067e-05 1.46423432778862e-05 -1.42678427991581e-06 -2.58910396926228e-06 -2.53893344254794e-06 9.6733370628321e-06 1.87538139964191e-05 -1.42678427991581e-06 6.82656711954143e-05 -2.37397036696188e-05 4.19119258650362e-06 6.92138808715785e-06 2.27074953546639e-08 -2.58910396926228e-06 -2.37397036696188e-05 5.54266345195813e-05 4.85317815105306e-06 1.69180394292137e-05 2.23065965984044e-05 -2.53893344254794e-06 4.19119258650362e-06 4.85317815105306e-06 5.49380158922948e-05 2207 2212 0 24 14 2202 2226 0 38 14 0 0 0 0 0 18 50 0 595 0 57 64 0 0 2251 +380 414 0.999999374817198 0.000315810113048167 0.00107267384821906 -0.00976921952054241 -0.000316343627764778 0.999999826341643 0.000497235751543483 0.00797848520769091 -0.00107251662986138 -0.000497574774216797 0.999999301063467 -0.00618395449957427 3.42013342791365e-05 2.43980248067742e-05 -8.45942496127675e-06 2.16508821890346e-06 8.31058034186036e-06 2.24010970733883e-05 2.43980248067742e-05 2.86800734386477e-05 -9.86365331378051e-06 2.2168366495469e-06 1.15620531171519e-05 2.08043529457645e-05 -8.45942496127675e-06 -9.86365331378051e-06 1.258544072356e-05 -5.95336543534416e-07 -3.99438915784147e-06 -4.73945889829781e-06 2.16508821890346e-06 2.2168366495469e-06 -5.95336543534416e-07 3.59265187605831e-05 -7.60887345071813e-06 1.23461845915814e-06 8.31058034186036e-06 1.15620531171519e-05 -3.99438915784147e-06 -7.60887345071813e-06 4.46897508334908e-05 7.89010659275276e-06 2.24010970733883e-05 2.08043529457645e-05 -4.73945889829781e-06 1.23461845915814e-06 7.89010659275276e-06 3.81218021677269e-05 3027 3026 0 11 11 3026 3058 0 34 9 0 0 0 0 0 21 51 0 615 0 12 16 0 0 2361 +380 417 0.999999081007641 0.000251035924742097 -0.0013322780631418 -0.0136358833404162 -0.000250395738918626 0.999999853131688 0.000480664722880526 0.00626656578928519 0.00133239853158557 -0.000480330684403253 0.99999899699779 -0.00353222086773989 4.45478230957632e-05 3.05118310222767e-05 -7.3042838774722e-06 4.77419340932076e-06 5.14828636386454e-06 3.39258024637043e-05 3.05118310222767e-05 3.96998354791608e-05 -9.40723129695656e-06 9.5121124968049e-06 5.04749956425779e-06 3.69625427375581e-05 -7.3042838774722e-06 -9.40723129695656e-06 1.218598093418e-05 1.39194752527124e-06 8.13456216938028e-07 -4.71861248108658e-06 4.77419340932076e-06 9.5121124968049e-06 1.39194752527124e-06 4.87035680820434e-05 -1.68704193492245e-05 9.43900304005783e-06 5.14828636386454e-06 5.04749956425779e-06 8.13456216938028e-07 -1.68704193492245e-05 4.42377930276954e-05 5.97635539756222e-06 3.39258024637043e-05 3.69625427375581e-05 -4.71861248108658e-06 9.43900304005783e-06 5.97635539756222e-06 6.28705507840353e-05 3127 3132 0 20 13 3131 3173 0 44 12 0 0 0 0 0 23 57 0 614 0 16 19 0 0 2340 +380 418 0.99999979944358 0.000329978729352483 -0.000540580093532484 -0.0173960432346469 -0.000328778383173797 0.999997483826667 0.00221906401655307 0.0137887717748572 0.000541310977263803 -0.00221888584045641 0.999997391760625 -0.00882686907957912 5.29792349832547e-05 4.40822637767837e-05 -1.05007242136072e-05 4.73445593561552e-06 1.25925391224702e-05 3.48288535160196e-05 4.40822637767837e-05 5.71586337211262e-05 -1.16560294484918e-05 1.52779592030727e-05 4.42068555956978e-06 2.91726437069257e-05 -1.05007242136072e-05 -1.16560294484918e-05 1.57235823022394e-05 -4.73670387514776e-06 -3.95584294684926e-06 -1.77812208416509e-06 4.73445593561552e-06 1.52779592030727e-05 -4.73670387514776e-06 6.96380665631361e-05 -2.74113453152672e-05 -2.46913929102976e-06 1.25925391224702e-05 4.42068555956978e-06 -3.95584294684926e-06 -2.74113453152672e-05 6.07542035486066e-05 9.09656168560999e-06 3.48288535160196e-05 2.91726437069257e-05 -1.77812208416509e-06 -2.46913929102976e-06 9.09656168560999e-06 7.08364923790822e-05 2199 2207 0 20 13 2188 2219 0 46 6 0 0 0 0 0 21 53 0 620 0 60 68 0 0 2165 +380 427 0.999997294246837 0.00087091474216829 0.00215708287195076 -0.0082780276983795 -0.00087196062983173 0.999999502729167 0.00048396908959011 0.00799027459626449 -0.00215666030348148 -0.000485848671428841 0.999997556380716 -0.00915676646575994 3.80629996444062e-05 3.10857756320614e-05 -1.10270415648722e-05 9.87618112172912e-06 1.07730767240217e-05 2.83906319927523e-05 3.10857756320614e-05 3.87510487935367e-05 -1.1507524466297e-05 8.30005224627964e-06 8.69603917148722e-06 2.76025914625249e-05 -1.10270415648722e-05 -1.1507524466297e-05 1.49725632588394e-05 -3.16602577691968e-06 -6.46130272545399e-06 -4.88939101474478e-06 9.87618112172912e-06 8.30005224627964e-06 -3.16602577691968e-06 4.74902734056632e-05 -9.09540116417908e-06 8.20434272657459e-06 1.07730767240217e-05 8.69603917148722e-06 -6.46130272545399e-06 -9.09540116417908e-06 5.45263827329579e-05 3.4846215525331e-07 2.83906319927523e-05 2.76025914625249e-05 -4.88939101474478e-06 8.20434272657459e-06 3.4846215525331e-07 6.90826395478764e-05 2765 2767 0 14 17 2766 2798 0 48 12 0 0 0 0 0 18 48 0 642 0 60 66 0 0 2369 +380 415 0.999997281116288 0.000444017133684505 0.00228923760613663 -0.0121964961639489 -0.000442696191429749 0.999999735258489 -0.000577497216064295 0.00618808523248432 -0.002289493418739 0.000576482209147006 0.99999721294019 -0.00709244567677057 3.73440716829517e-05 2.11881263712292e-05 -7.04248357178422e-06 -7.68699318805694e-07 9.98254274008763e-06 1.88748128220535e-05 2.11881263712292e-05 2.97800918558145e-05 -8.08653528466389e-06 8.49978762521043e-06 2.17727545252543e-06 1.80289459035194e-05 -7.04248357178422e-06 -8.08653528466389e-06 1.37205882892939e-05 2.68001978073408e-06 -2.13560184563141e-06 -2.21082945618087e-06 -7.68699318805694e-07 8.49978762521043e-06 2.68001978073408e-06 5.94918884890882e-05 -2.64957375106576e-05 6.63300804285661e-06 9.98254274008763e-06 2.17727545252543e-06 -2.13560184563141e-06 -2.64957375106576e-05 5.34083920812182e-05 6.35601417958148e-06 1.88748128220535e-05 1.80289459035194e-05 -2.21082945618087e-06 6.63300804285661e-06 6.35601417958148e-06 4.85180930024796e-05 2734 2739 0 19 14 2735 2770 0 53 10 0 0 0 0 0 19 50 0 583 0 58 63 0 0 2271 +380 424 0.999999412117725 0.000682673870017029 0.000842449163051316 -0.0135874207722595 -0.00068248954768372 0.999999743110003 -0.00021906150878037 0.00638600002929702 -0.000842598494202525 0.000218486417249754 0.99999962114566 -0.0050166188888975 3.87671895885973e-05 2.57198653229874e-05 -1.01348080087482e-05 8.42916431872936e-06 5.6083991230821e-06 2.16634755761008e-05 2.57198653229874e-05 3.48983029038723e-05 -1.28429009277022e-05 7.80180598260393e-06 9.13410902341497e-06 1.93696000005987e-05 -1.01348080087482e-05 -1.28429009277022e-05 1.5510268100834e-05 -1.77968545072909e-06 -4.48405451701694e-07 -5.12448327395174e-06 8.42916431872936e-06 7.80180598260393e-06 -1.77968545072909e-06 5.73724537150034e-05 -1.69328003598214e-05 6.57016470578193e-06 5.6083991230821e-06 9.13410902341497e-06 -4.48405451701694e-07 -1.69328003598214e-05 5.20638894997824e-05 2.76803229831323e-06 2.16634755761008e-05 1.93696000005987e-05 -5.12448327395174e-06 6.57016470578193e-06 2.76803229831323e-06 5.19033106453078e-05 2456 2454 0 15 15 2457 2480 0 42 14 0 0 0 0 0 22 53 0 633 0 47 61 0 0 2216 +380 413 0.999993742982565 0.000604853695320135 -0.00348541930426086 -0.0168686393032891 -0.00061125223734441 0.999998129516161 -0.00183502994018877 0.005329982066091 0.00348430286020003 0.00183714892872225 0.999992242228605 -0.00896581745496148 4.81620112565577e-05 2.87906086287687e-05 -6.94124048742833e-06 8.63120623033938e-06 5.60162086435036e-06 3.02438389703495e-05 2.87906086287687e-05 3.71632505105595e-05 -7.8003146420879e-06 1.58590862779158e-05 7.99798849773191e-07 2.82073496953872e-05 -6.94124048742833e-06 -7.8003146420879e-06 1.20267742859397e-05 4.82953756653727e-07 -5.9890403239836e-07 -3.07874913380233e-06 8.63120623033938e-06 1.58590862779158e-05 4.82953756653727e-07 5.99605611109819e-05 -2.74210143489663e-05 1.66417029129775e-05 5.60162086435036e-06 7.99798849773191e-07 -5.9890403239836e-07 -2.74210143489663e-05 5.87439421387818e-05 1.0021507574388e-06 3.02438389703495e-05 2.82073496953872e-05 -3.07874913380233e-06 1.66417029129775e-05 1.0021507574388e-06 5.68632094780997e-05 2517 2519 0 18 11 2510 2540 0 44 4 0 0 0 0 0 20 52 0 611 0 40 52 0 0 2309 +380 426 0.99999894412207 0.00127128595311369 -0.000703979239968402 -0.018868370829642 -0.00127007004043997 0.999997705712494 0.00172496140257793 0.018447715868531 0.000706170544038388 -0.00172406547828748 0.999998264459189 -0.00763688657016313 5.37168554178269e-05 4.0620730274024e-05 -1.26242090652662e-05 9.07055007720338e-06 7.38792455885895e-06 3.0495380336246e-05 4.0620730274024e-05 4.67541244797665e-05 -1.24197819896107e-05 1.51970375536613e-05 9.33306115911757e-07 2.58942149126179e-05 -1.26242090652662e-05 -1.24197819896107e-05 1.56108728388291e-05 -4.63395712921598e-06 -2.2836061020989e-06 -5.89152195927076e-06 9.07055007720338e-06 1.51970375536613e-05 -4.63395712921598e-06 7.61973097215272e-05 -3.63599843229976e-05 -6.75165388861944e-06 7.38792455885895e-06 9.33306115911757e-07 -2.2836061020989e-06 -3.63599843229976e-05 6.16023340141789e-05 1.25920765207066e-05 3.0495380336246e-05 2.58942149126179e-05 -5.89152195927076e-06 -6.75165388861944e-06 1.25920765207066e-05 6.40640101989106e-05 2162 2163 0 12 17 2150 2173 0 43 8 0 0 0 0 0 24 53 0 645 0 67 77 0 0 2109 +380 420 0.999999528523741 0.000870877110049931 -0.00042956414552501 -0.0177128088378497 -0.000870609197394279 0.999999426657208 0.000623478050710146 0.0161316042913077 0.000430106872000486 -0.000623103774259082 0.999999713374842 -0.00816508894868115 4.66122970025131e-05 3.16901509090648e-05 -1.17413501604802e-05 9.87403148255931e-06 8.62990380490564e-06 2.0083742401923e-05 3.16901509090648e-05 4.13711124073478e-05 -1.09825859773095e-05 1.3138183565645e-05 2.07659269514627e-06 2.83644684191593e-05 -1.17413501604802e-05 -1.09825859773095e-05 1.69087117115258e-05 -2.995206223174e-06 -5.83766695774581e-06 -3.22033735491306e-06 9.87403148255931e-06 1.3138183565645e-05 -2.995206223174e-06 6.48414249406697e-05 -3.57004914354492e-05 9.70430575979839e-06 8.62990380490564e-06 2.07659269514627e-06 -5.83766695774581e-06 -3.57004914354492e-05 7.20865826740271e-05 -1.15215625336774e-06 2.0083742401923e-05 2.83644684191593e-05 -3.22033735491306e-06 9.70430575979839e-06 -1.15215625336774e-06 5.83150470531857e-05 2143 2147 0 16 11 2133 2165 0 50 4 0 0 0 0 0 20 51 0 626 0 60 70 0 0 2269 +380 422 0.99999871104728 0.00128874138340459 -0.00095762697605024 -0.0133607656993539 -0.00128849050707631 0.99999913543004 0.000262547871798939 0.0113219137084724 0.000957964504422236 -0.000261313640119184 0.999999507009473 -0.00941726680999579 2.77127881616828e-05 1.85214078825781e-05 -8.78026027306767e-06 2.88524207720567e-06 1.19875777260029e-05 1.87089921986084e-05 1.85214078825781e-05 3.05878057558885e-05 -9.80107734303824e-06 8.94871267931736e-06 7.92333441886171e-06 2.20928007843124e-05 -8.78026027306767e-06 -9.80107734303824e-06 1.29562092709853e-05 1.0708785024298e-06 -5.22382675219922e-06 -3.84288454135002e-06 2.88524207720567e-06 8.94871267931736e-06 1.0708785024298e-06 5.48844814134847e-05 -1.75061226045564e-05 7.04266232978831e-06 1.19875777260029e-05 7.92333441886171e-06 -5.22382675219922e-06 -1.75061226045564e-05 5.32651647750589e-05 5.14680896021923e-06 1.87089921986084e-05 2.20928007843124e-05 -3.84288454135002e-06 7.04266232978831e-06 5.14680896021923e-06 5.05091977494209e-05 2621 2624 0 15 14 2625 2662 0 42 11 0 0 0 0 0 18 51 0 605 0 17 21 0 0 2309 +380 411 0.99999682341258 6.12613055858747e-05 0.00251980392140984 -0.0128979021375063 -5.83294976220638e-05 0.999999321358684 -0.00116356342380233 0.0096775420169414 -0.00251987349278126 0.00116341274874456 0.999996148346761 -0.00381614410547542 5.00032041516081e-05 4.22604502717002e-05 -7.36903677656269e-06 6.34231785398509e-06 -1.5628387349563e-06 3.79104372510427e-05 4.22604502717002e-05 5.92859101157527e-05 -8.44530668999793e-06 2.14989977642695e-05 -9.56666960818355e-06 4.78052174791732e-05 -7.36903677656269e-06 -8.44530668999793e-06 1.32175574057797e-05 1.94577838430119e-06 2.0587426822683e-06 -6.52200832744571e-06 6.34231785398509e-06 2.14989977642695e-05 1.94577838430119e-06 7.43699308082641e-05 -4.01730866187341e-05 1.55925452533374e-05 -1.5628387349563e-06 -9.56666960818355e-06 2.0587426822683e-06 -4.01730866187341e-05 4.98406056201732e-05 -6.07715470934338e-06 3.79104372510427e-05 4.78052174791732e-05 -6.52200832744571e-06 1.55925452533374e-05 -6.07715470934338e-06 7.77478062617148e-05 2123 2123 0 8 11 2120 2147 0 40 4 0 0 0 0 0 25 57 0 543 0 56 65 0 0 2234 +380 412 0.999997591724438 3.11261836242804e-05 0.00219444218077708 -0.0133116302789867 -3.21426232005148e-05 0.999999892227427 0.000463154386746916 0.0104797099922993 -0.00219442752804791 -0.000463223806471677 0.999997484952602 -0.00723649679332884 4.11630359455228e-05 2.75362052447289e-05 -9.69308728839322e-06 4.61452610977137e-06 5.5369098407749e-06 2.21889640824404e-05 2.75362052447289e-05 4.49673814227471e-05 -1.06638984516176e-05 1.71641492275042e-05 2.4519363757545e-06 1.65974038492537e-05 -9.69308728839322e-06 -1.06638984516176e-05 1.56600208095609e-05 -1.17094290276777e-06 -3.19779321398168e-06 -6.64734543127436e-06 4.61452610977137e-06 1.71641492275042e-05 -1.17094290276777e-06 6.12875932082317e-05 -2.90146789008013e-05 -9.03320538046262e-08 5.5369098407749e-06 2.4519363757545e-06 -3.19779321398168e-06 -2.90146789008013e-05 5.21806065668247e-05 9.39624700333984e-06 2.21889640824404e-05 1.65974038492537e-05 -6.64734543127436e-06 -9.03320538046262e-08 9.39624700333984e-06 5.80853341582995e-05 1610 1608 0 6 9 1614 1640 0 43 5 0 0 0 0 0 23 54 0 577 0 59 69 0 0 2234 +380 425 0.999998113386121 0.000313701495395027 -0.00191698084776374 -0.0175734852559409 -0.000317382702436861 0.999998105832085 -0.00192031259510199 0.00664192190911475 0.00191637481174742 0.00192091738877558 0.999996318785208 -0.00584997189336234 3.04718940425519e-05 6.9148240092213e-06 -6.57309411729292e-06 -6.38744160474898e-06 9.62147726014229e-06 8.96265963060106e-06 6.9148240092213e-06 2.99702387428661e-05 -7.48525856704817e-06 1.22814275645875e-05 6.44877595808658e-06 1.61660408303142e-05 -6.57309411729292e-06 -7.48525856704817e-06 1.25874153673081e-05 -1.84531968543925e-06 1.43686104484802e-07 -1.84432189566973e-06 -6.38744160474898e-06 1.22814275645875e-05 -1.84531968543925e-06 6.04036508210686e-05 -2.09454047045933e-05 2.77180712663901e-07 9.62147726014229e-06 6.44877595808658e-06 1.43686104484802e-07 -2.09454047045933e-05 5.67119126793405e-05 6.73675322465482e-06 8.96265963060106e-06 1.61660408303142e-05 -1.84432189566973e-06 2.77180712663901e-07 6.73675322465482e-06 4.54004808150789e-05 1988 1990 0 15 16 1994 2013 0 35 16 0 0 0 0 0 20 49 0 645 0 45 58 0 0 2125 +380 423 0.999998987781373 0.000976260321086827 0.00103506135795662 -0.0214092634645272 -0.000976862085260871 0.999999354069696 0.000581034126670472 0.0175084747807225 -0.00103449344881606 -0.000582044650733413 0.999999295523416 -0.00979165006277876 3.70480324245976e-05 2.30595106530187e-05 -1.0231734431043e-05 1.03517262590332e-05 4.79230977016451e-06 2.2196707199593e-05 2.30595106530187e-05 4.07161948407912e-05 -1.26457971672383e-05 1.45088294903977e-05 4.92577468044188e-06 2.02528559903739e-05 -1.0231734431043e-05 -1.26457971672383e-05 1.78048774966253e-05 -4.35122918566032e-06 -1.15474593074595e-06 -4.73714036466658e-06 1.03517262590332e-05 1.45088294903977e-05 -4.35122918566032e-06 7.18975082904959e-05 -3.26021974248584e-05 6.01410335394291e-06 4.79230977016451e-06 4.92577468044188e-06 -1.15474593074595e-06 -3.26021974248584e-05 5.59535628650287e-05 3.86307641595716e-06 2.2196707199593e-05 2.02528559903739e-05 -4.73714036466658e-06 6.01410335394291e-06 3.86307641595716e-06 6.02410226963551e-05 1636 1643 0 15 12 1629 1655 0 39 4 0 0 0 0 0 24 55 0 612 0 56 65 0 0 2235 +380 421 0.99999968240614 0.00078743421333191 -0.000123024304518866 -0.0179632373206294 -0.000787377282293432 0.999999583237443 0.000462127640503104 0.01651521492166 0.000123388148362001 -0.000462030627191655 0.999999885651526 -0.00548686661487107 3.32844966388654e-05 2.35303276317614e-05 -8.9932625051651e-06 2.70086665138865e-06 9.13287799120416e-06 1.48784896976613e-05 2.35303276317614e-05 4.76106339118352e-05 -9.49546960136147e-06 1.70075282878702e-05 8.30938726437014e-06 2.17623546945734e-05 -8.9932625051651e-06 -9.49546960136147e-06 1.54479999149272e-05 -4.79097615736213e-07 -6.66071746045876e-06 -4.59968342096543e-06 2.70086665138865e-06 1.70075282878702e-05 -4.79097615736213e-07 6.46090934977244e-05 -2.26379912792147e-05 -4.06794948207175e-06 9.13287799120416e-06 8.30938726437014e-06 -6.66071746045876e-06 -2.26379912792147e-05 6.03724612112571e-05 1.50313625762129e-05 1.48784896976613e-05 2.17623546945734e-05 -4.59968342096543e-06 -4.06794948207175e-06 1.50313625762129e-05 5.3814889482643e-05 2150 2148 0 7 14 2148 2173 0 38 10 0 0 0 0 0 28 60 0 628 0 61 71 0 0 2308 +380 428 0.999997467454402 0.000627114699839315 0.00216143746975606 -0.00804666462013731 -0.000630969039935388 0.999998211375776 0.00178300962423293 0.00763808214167639 -0.00216031545221133 -0.00178436890880492 0.999996074524668 -0.0100114906243447 3.7677902806232e-05 2.03649877552017e-05 -9.85835940908038e-06 6.08908234141449e-06 4.74811865264926e-06 1.77724848306301e-05 2.03649877552017e-05 3.10383864903411e-05 -1.07826714764414e-05 4.51449029008656e-06 7.03881441716051e-06 1.16342763427308e-05 -9.85835940908038e-06 -1.07826714764414e-05 1.45982196335614e-05 1.61929792540564e-06 -6.88577763676796e-06 -3.34801978820419e-06 6.08908234141449e-06 4.51449029008656e-06 1.61929792540564e-06 5.38774977756669e-05 -2.00883680232756e-05 -2.03286948350845e-06 4.74811865264926e-06 7.03881441716051e-06 -6.88577763676796e-06 -2.00883680232756e-05 6.45094630223427e-05 4.56539406508051e-06 1.77724848306301e-05 1.16342763427308e-05 -3.34801978820419e-06 -2.03286948350845e-06 4.56539406508051e-06 4.9506710659324e-05 2741 2747 0 24 16 2738 2764 0 40 16 0 0 0 0 0 14 46 0 660 0 57 64 0 0 2277 +380 407 0.999997106899929 0.000381635310066588 0.00237498342334027 -0.0119092292924566 -0.000384550633467753 0.999999173077641 0.00122717759283194 0.0066679744799077 -0.00237451312511222 -0.00122808734386428 0.999996426738063 0.000860761475587119 2.73538411820942e-05 2.33294162583079e-05 -1.85684191912684e-06 1.02142334423012e-07 1.29014399883541e-06 2.07753540452356e-05 2.33294162583079e-05 3.65617034212472e-05 -3.87852733374622e-06 7.15547837027048e-06 -1.08399812943046e-06 2.47699953595962e-05 -1.85684191912684e-06 -3.87852733374622e-06 1.25655773002678e-05 6.14879829857311e-07 3.8311889829126e-06 6.14112759501528e-07 1.02142334423012e-07 7.15547837027048e-06 6.14879829857311e-07 4.6008363626419e-05 -1.22769502315141e-05 2.80266003667734e-06 1.29014399883541e-06 -1.08399812943046e-06 3.8311889829126e-06 -1.22769502315141e-05 3.72164190415504e-05 2.71433882585945e-06 2.07753540452356e-05 2.47699953595962e-05 6.14112759501528e-07 2.80266003667734e-06 2.71433882585945e-06 5.55208281272275e-05 1906 1903 0 11 17 1909 1939 0 46 15 0 0 0 0 0 22 52 0 485 0 48 58 0 0 2303 +381 416 0.999983181587769 0.000937534464819456 -0.00572342299060428 -0.0174851343753007 -0.000936614103677886 0.999999548013352 0.000163484291156269 0.0134997536380768 0.00572357367585092 -0.000158120902915753 0.999983607716725 -0.000102823604891524 4.74903604460245e-05 3.48681056471289e-05 -1.13552924545351e-05 9.88709768706441e-06 1.06530586035237e-05 3.63270515110307e-05 3.48681056471289e-05 3.53610333235412e-05 -1.08316121120458e-05 1.15238711377784e-05 6.30458961554077e-06 3.10469098226117e-05 -1.13552924545351e-05 -1.08316121120458e-05 1.47368319610481e-05 -1.36992712847125e-06 -3.4214346115069e-06 -6.48982764590714e-06 9.88709768706441e-06 1.15238711377784e-05 -1.36992712847125e-06 4.35228687542013e-05 -1.01242345012796e-05 2.40654828743009e-06 1.06530586035237e-05 6.30458961554077e-06 -3.4214346115069e-06 -1.01242345012796e-05 4.56088766993e-05 7.38757994472964e-06 3.63270515110307e-05 3.10469098226117e-05 -6.48982764590714e-06 2.40654828743009e-06 7.38757994472964e-06 5.78698453096482e-05 2690 2696 0 16 12 2682 2707 0 37 5 0 0 0 0 0 16 47 0 614 0 56 62 0 0 2277 +380 429 0.999973099510113 -0.00733404445159791 -0.000109763923741212 -0.0145412590353876 0.00733437483865313 0.999967341099737 0.00339465456975399 0.0134590731696062 8.48637914597785e-05 -0.00339536830164354 0.999994232119482 -0.00774774535321853 3.81138831983736e-05 2.99311756383115e-05 -5.16964727599239e-06 6.20022517044665e-06 -4.55843205954892e-07 2.83095928584191e-05 2.99311756383115e-05 4.56192034188119e-05 -7.02439874295555e-06 1.38211609950751e-05 -3.01721986135831e-06 2.59677588702255e-05 -5.16964727599239e-06 -7.02439874295555e-06 1.27283653427542e-05 9.41392653884838e-07 -7.09357068366096e-07 -1.24078015195801e-06 6.20022517044665e-06 1.38211609950751e-05 9.41392653884838e-07 6.66838764916703e-05 -2.80202880896164e-05 5.46352375369916e-06 -4.55843205954892e-07 -3.01721986135831e-06 -7.09357068366096e-07 -2.80202880896164e-05 5.80706747652544e-05 -2.6886882141527e-06 2.83095928584191e-05 2.59677588702255e-05 -1.24078015195801e-06 5.46352375369916e-06 -2.6886882141527e-06 6.65573312881462e-05 1641 1642 0 9 24 1641 1655 0 29 12 0 0 0 0 0 33 65 0 619 0 57 65 0 0 2405 +380 410 0.999998119062502 0.000138343625033401 0.00193461430250336 -0.0117221807384018 -0.000137265019653168 0.999999835091492 -0.000557651595834056 0.00857573765270395 -0.00193469113101228 0.000557384992056005 0.999997973144045 -0.00184025165132665 4.12607552290907e-05 2.06534439661751e-05 -2.1238917230953e-06 -9.01723635295239e-06 8.38223334998174e-06 2.11651071150718e-05 2.06534439661751e-05 5.04064019854471e-05 -1.77866111853336e-06 6.09249218361781e-06 6.68699896700539e-06 2.82053309346257e-05 -2.1238917230953e-06 -1.77866111853336e-06 9.83258233424781e-06 2.14903519219265e-06 4.00285620797183e-06 3.57545824784219e-07 -9.01723635295239e-06 6.09249218361781e-06 2.14903519219265e-06 6.74560056448616e-05 -3.24064851935246e-05 -2.27281760097263e-06 8.38223334998174e-06 6.68699896700539e-06 4.00285620797183e-06 -3.24064851935246e-05 4.93713699563964e-05 6.29509216161653e-06 2.11651071150718e-05 2.82053309346257e-05 3.57545824784219e-07 -2.27281760097263e-06 6.29509216161653e-06 5.14641805455445e-05 2266 2264 0 7 9 2269 2294 0 43 5 0 0 0 0 0 28 55 0 512 0 34 46 0 0 2341 +380 409 0.999999494221681 0.000605963444527183 0.000802723293666146 -0.0132481677690074 -0.000603575225341331 0.999995401282335 -0.00297205503458502 0.00392976021972504 -0.000804520558874437 0.00297156902749116 0.999995261250865 -0.00116650231049894 5.16435062848135e-05 3.82912582663318e-05 -3.33119778875885e-06 5.25718024445922e-06 -1.80832760847959e-06 4.27307406925964e-05 3.82912582663318e-05 5.21588916942081e-05 -3.36012599066244e-06 8.60935086592517e-06 -1.69690994752676e-06 4.71724243590265e-05 -3.33119778875885e-06 -3.36012599066244e-06 1.10113317767148e-05 2.84471732198669e-07 3.7723179140464e-06 -3.7344554049169e-07 5.25718024445922e-06 8.60935086592517e-06 2.84471732198669e-07 4.27825290190786e-05 -7.65886994326994e-06 7.97909106584655e-06 -1.80832760847959e-06 -1.69690994752676e-06 3.7723179140464e-06 -7.65886994326994e-06 3.67117326143069e-05 1.02415566613887e-05 4.27307406925964e-05 4.71724243590265e-05 -3.7344554049169e-07 7.97909106584655e-06 1.02415566613887e-05 8.89008440958033e-05 2336 2333 0 12 10 2342 2365 0 40 10 0 0 0 0 0 14 45 0 506 0 39 51 0 0 2277 +381 385 0.999999062320467 0.000107499150247651 0.00136521138285646 -0.00622511327574731 -0.00010734671706704 0.999999987996751 -0.000111728153608017 0.00352503352561243 -0.00136522337715106 0.000111581497882762 0.99999906185691 0.000729263894430388 2.46384856371257e-05 1.54832206354254e-05 -8.91561864173316e-06 4.29114014091094e-06 7.66775474963584e-06 1.90454940186485e-05 1.54832206354254e-05 1.93989399319815e-05 -9.13192012666723e-06 6.06047155266282e-06 5.02787813306899e-06 1.75547053483961e-05 -8.91561864173316e-06 -9.13192012666723e-06 1.34318761781668e-05 -1.86831933017971e-06 -3.88660866587119e-06 -5.8592865010623e-06 4.29114014091094e-06 6.06047155266282e-06 -1.86831933017971e-06 3.29164181789186e-05 -3.55023058887063e-06 7.32518744905972e-06 7.66775474963584e-06 5.02787813306899e-06 -3.88660866587119e-06 -3.55023058887063e-06 3.11216658032195e-05 8.24883404214181e-06 1.90454940186485e-05 1.75547053483961e-05 -5.8592865010623e-06 7.32518744905972e-06 8.24883404214181e-06 4.44835794885583e-05 3117 3092 0 8 59 3104 3161 0 52 31 0 0 0 0 0 17 49 0 651 0 56 32 0 0 2748 +381 413 0.999989330710717 0.00052675380464946 -0.00458922598718579 -0.0166435697175347 -0.000537465818704134 0.999997133544513 -0.00233324521882497 0.00793106600973089 0.00458798378657758 0.00233568687685918 0.999986747397978 -0.00205477720256253 5.99291674494124e-05 4.25029661520103e-05 -8.35853444868422e-06 6.53488211052815e-06 4.9149717037304e-06 4.24553918379856e-05 4.25029661520103e-05 5.35741863310447e-05 -9.29151747442815e-06 1.18287177139311e-05 8.92884744008063e-06 4.42458348628912e-05 -8.35853444868422e-06 -9.29151747442815e-06 1.37581036235381e-05 -2.63810177559014e-07 -1.08237092030535e-06 -4.78661436777337e-06 6.53488211052815e-06 1.18287177139311e-05 -2.63810177559014e-07 4.98404072729214e-05 -1.70044848279323e-05 3.54657534734255e-06 4.9149717037304e-06 8.92884744008063e-06 -1.08237092030535e-06 -1.70044848279323e-05 5.85401208654955e-05 1.31380357273366e-05 4.24553918379856e-05 4.42458348628912e-05 -4.78661436777337e-06 3.54657534734255e-06 1.31380357273366e-05 6.5687565026227e-05 2049 2051 0 21 11 2039 2056 0 36 11 0 0 0 0 0 15 48 0 602 0 46 54 0 0 2307 +380 408 0.999999754249474 0.000339936091716111 -0.000613143087162447 -0.0128451130924642 -0.000340839208127806 0.999998856420546 -0.00147342669782234 0.00547871952818838 0.000612641515071523 0.00147363531893125 0.99999872653385 -0.00209108655502668 3.18390421083057e-05 2.59708695843022e-05 -7.29631166919968e-07 2.28018407075017e-06 8.83766546432945e-07 2.38582182338916e-05 2.59708695843022e-05 3.07543616122348e-05 -1.09588114587958e-06 4.52703824251273e-06 -1.74099037419593e-06 2.73396491547232e-05 -7.29631166919968e-07 -1.09588114587958e-06 9.44770988560199e-06 2.03331099819312e-06 2.58621743584511e-06 2.01625363622147e-06 2.28018407075017e-06 4.52703824251273e-06 2.03331099819312e-06 4.19813098614665e-05 -1.53873984724619e-05 3.66084890423815e-06 8.83766546432945e-07 -1.74099037419593e-06 2.58621743584511e-06 -1.53873984724619e-05 3.30876289068029e-05 1.52014117781503e-06 2.38582182338916e-05 2.73396491547232e-05 2.01625363622147e-06 3.66084890423815e-06 1.52014117781503e-06 4.54695196301512e-05 3111 3114 0 19 15 3112 3148 0 42 14 0 0 0 0 0 23 54 0 497 0 17 21 0 0 2297 +381 417 0.999993930592875 0.000644960739201871 -0.00342385792010873 -0.0161551016751484 -0.000642962593697651 0.999999622383844 0.000584663384136212 0.00910007321575064 0.00342423371213308 -0.000582458423007337 0.999993967664641 -0.00184366147571647 4.5671028598157e-05 3.73597964062316e-05 -9.40810019082107e-06 1.15386287427012e-05 -3.18714018062641e-08 3.17681951787425e-05 3.73597964062316e-05 4.61738015880249e-05 -1.27900142426785e-05 1.24944922522661e-05 9.48467960500429e-07 3.6443687580178e-05 -9.40810019082107e-06 -1.27900142426785e-05 1.63503400380589e-05 -1.43984157944584e-07 -1.37252556019329e-06 -5.03277788338732e-06 1.15386287427012e-05 1.24944922522661e-05 -1.43984157944584e-07 4.6770697944865e-05 -1.02550686446592e-05 7.98742474969439e-06 -3.18714018062641e-08 9.48467960500429e-07 -1.37252556019329e-06 -1.02550686446592e-05 4.96833266842124e-05 3.172276486354e-06 3.17681951787425e-05 3.6443687580178e-05 -5.03277788338732e-06 7.98742474969439e-06 3.172276486354e-06 5.43961301756386e-05 2149 2150 0 13 13 2147 2172 0 35 10 0 0 0 0 0 20 54 0 614 0 57 69 0 0 2352 +381 426 0.99999498487378 0.00100185059431259 0.00300441719393074 -0.00762554356682786 -0.00100646526326985 0.999998315640807 0.00153484306124563 0.00910363428351229 -0.00300287444997994 -0.00153785920535601 0.999994308850856 -0.00849824464589492 3.87606950189897e-05 2.37838184943466e-05 -9.53070430789777e-06 2.63144466755494e-06 9.00674670046459e-06 2.35323194724009e-05 2.37838184943466e-05 4.02399328264667e-05 -9.05614883331878e-06 1.33814666413694e-05 2.55146396817922e-06 2.51122351172964e-05 -9.53070430789777e-06 -9.05614883331878e-06 1.37184100293334e-05 -1.47713781420572e-07 -1.88494270183769e-06 -1.89836452002741e-06 2.63144466755494e-06 1.33814666413694e-05 -1.47713781420572e-07 5.52752853429757e-05 -1.51623030392751e-05 7.84347730425838e-06 9.00674670046459e-06 2.55146396817922e-06 -1.88494270183769e-06 -1.51623030392751e-05 5.00949344443112e-05 7.63836204200518e-07 2.35323194724009e-05 2.51122351172964e-05 -1.89836452002741e-06 7.84347730425838e-06 7.63836204200518e-07 5.56851393520134e-05 2131 2128 0 9 17 2130 2157 0 46 16 0 0 0 0 0 16 46 0 635 0 48 58 0 0 2135 +381 383 0.99999051247616 0.000476125904437966 -0.00432992630300868 -0.00811629606549216 -0.000487560896503875 0.999996395679007 -0.00264024873193086 0.00274697184983125 0.00432865360574898 0.00264233478525816 0.999987140329737 0.00374797988655152 2.37014306110934e-05 1.44409995933746e-05 -7.92367169817711e-06 4.08469296056294e-06 6.00603495935097e-06 1.14554560707288e-05 1.44409995933746e-05 2.63939547996889e-05 -9.76546864086433e-06 6.93248837226769e-06 6.06318965397194e-06 9.98798462420813e-06 -7.92367169817711e-06 -9.76546864086433e-06 1.35060927779488e-05 6.12173038751033e-07 -1.60839775282359e-06 -3.84252648238923e-06 4.08469296056294e-06 6.93248837226769e-06 6.12173038751033e-07 3.25440248042328e-05 3.66129105897902e-06 -4.85859435405681e-06 6.00603495935097e-06 6.06318965397194e-06 -1.60839775282359e-06 3.66129105897902e-06 3.05416995934187e-05 9.39181465965519e-07 1.14554560707288e-05 9.98798462420813e-06 -3.84252648238923e-06 -4.85859435405681e-06 9.39181465965519e-07 3.24545776167379e-05 2210 2190 0 16 56 2190 2209 0 36 34 0 0 0 0 0 14 45 0 665 0 99 94 0 0 2698 +381 384 0.99999641979846 3.66558211531548e-05 -0.00267563947723981 -0.00738541728712597 -3.86207708929161e-05 0.999999729628681 -0.000734337117169281 0.00440870653911862 0.00267561183609361 0.000734437823353646 0.999996150843785 0.00384421124891496 2.90512376436784e-05 2.0566445020592e-05 -6.68050716875438e-06 4.7175770215909e-06 5.23212507941751e-06 1.86466084620654e-05 2.0566445020592e-05 2.79383740293627e-05 -7.94137679777938e-06 6.15624378941187e-06 3.04077397699596e-06 1.72438987926038e-05 -6.68050716875438e-06 -7.94137679777938e-06 1.28948487740859e-05 3.21624842116314e-07 -1.46015810458472e-06 -2.36584864896741e-06 4.7175770215909e-06 6.15624378941187e-06 3.21624842116314e-07 3.41895953539501e-05 -8.32077970128171e-06 1.91776743685457e-07 5.23212507941751e-06 3.04077397699596e-06 -1.46015810458472e-06 -8.32077970128171e-06 3.51295445836229e-05 3.87196378680132e-06 1.86466084620654e-05 1.72438987926038e-05 -2.36584864896741e-06 1.91776743685457e-07 3.87196378680132e-06 3.66807616633366e-05 2633 2619 0 16 56 2613 2638 0 41 34 0 0 0 0 0 22 54 0 666 0 98 91 0 0 2823 +381 418 0.999996230139217 0.000314246328522556 0.00272781168673913 -0.00708586774348369 -0.0003178631032616 0.999999070931131 0.00132555645738184 0.00568065970020775 -0.00272739260116423 -0.00132641853090639 0.999995400961164 -0.00836321985666153 4.24530147015011e-05 3.08593992523453e-05 -9.8951523010533e-06 1.47810347997903e-05 -1.20468633876269e-06 3.32665384470602e-05 3.08593992523453e-05 4.44379148245782e-05 -1.01168965734233e-05 1.62644656204066e-05 2.90103159726286e-07 4.03656566935587e-05 -9.8951523010533e-06 -1.01168965734233e-05 1.46041910869879e-05 -2.25554050841952e-06 -3.43804025616796e-06 -2.66867051796089e-06 1.47810347997903e-05 1.62644656204066e-05 -2.25554050841952e-06 5.10277359177765e-05 -1.00441966684256e-05 2.13517669389421e-05 -1.20468633876269e-06 2.90103159726286e-07 -3.43804025616796e-06 -1.00441966684256e-05 5.10056308717791e-05 -8.34075108501302e-06 3.32665384470602e-05 4.03656566935587e-05 -2.66867051796089e-06 2.13517669389421e-05 -8.34075108501302e-06 7.05344422031766e-05 2121 2128 0 19 13 2120 2139 0 35 11 0 0 0 0 0 21 53 0 623 0 48 59 0 0 2196 +381 414 0.99999191712245 0.000887200884875388 -0.00392155126912016 -0.0123056038686469 -0.000887383662365088 0.999999605268438 -4.48687446201785e-05 0.0128777613684572 0.00392150991357017 4.83483024789542e-05 0.999992309681649 -0.00145940006863563 5.181681922552e-05 4.29021602132294e-05 -8.98441299112913e-06 1.539873197529e-05 6.13042169609494e-06 4.17059565483147e-05 4.29021602132294e-05 5.56724747891759e-05 -9.47698700887243e-06 1.90987079786976e-05 4.86950936926018e-06 4.91415863251194e-05 -8.98441299112913e-06 -9.47698700887243e-06 1.34434302222557e-05 -1.32199568768106e-06 -3.31502767139735e-06 -4.2417127801878e-06 1.539873197529e-05 1.90987079786976e-05 -1.32199568768106e-06 4.01756560998424e-05 -3.86948603898354e-06 1.05313567936682e-05 6.13042169609494e-06 4.86950936926018e-06 -3.31502767139735e-06 -3.86948603898354e-06 4.20739399791206e-05 1.94723839967992e-06 4.17059565483147e-05 4.91415863251194e-05 -4.2417127801878e-06 1.05313567936682e-05 1.94723839967992e-06 7.04584926088891e-05 2683 2691 0 16 12 2685 2724 0 47 11 0 0 0 0 0 22 53 0 604 0 52 62 0 0 2353 +381 415 0.999997878564538 0.000657551128112649 -0.00195204839509961 -0.0109267218336435 -0.00066120171431102 0.999998032813839 -0.00187007506384054 0.0061221926594068 0.00195081488508914 0.00187136179434224 0.999996346156484 -0.00547128826332877 3.63901032753397e-05 2.54911267480798e-05 -8.76314917815555e-06 6.49806233559411e-06 1.02494089952605e-05 3.56116533143e-05 2.54911267480798e-05 2.50344680013057e-05 -1.04264057463952e-05 2.81718427988138e-06 1.01352693276476e-05 2.8113197514572e-05 -8.76314917815555e-06 -1.04264057463952e-05 1.27282787261193e-05 1.14842491047852e-06 -4.54648151104454e-06 -7.52516519153053e-06 6.49806233559411e-06 2.81718427988138e-06 1.14842491047852e-06 3.55595142999709e-05 -7.93625187331948e-06 6.21318307094254e-06 1.02494089952605e-05 1.01352693276476e-05 -4.54648151104454e-06 -7.93625187331948e-06 4.60707032474819e-05 1.58333698104839e-05 3.56116533143e-05 2.8113197514572e-05 -7.52516519153053e-06 6.21318307094254e-06 1.58333698104839e-05 6.26140360385103e-05 3009 3013 0 15 14 3019 3054 0 37 13 0 0 0 0 0 20 52 0 592 0 18 22 0 0 2265 +381 424 0.999997578114283 0.000397697836885054 -0.00216462514064244 -0.0176169533926805 -0.000397358091640315 0.99999990866885 0.000157381189023705 0.0102341188910141 0.00216468753310318 -0.000156520676549448 0.999997644811807 -0.00255846280061043 2.97964691037956e-05 2.52970743993814e-05 -9.67930771770907e-06 4.75340453348978e-06 1.09908362885456e-05 2.22938970504413e-05 2.52970743993814e-05 3.67262016825209e-05 -1.26785790768675e-05 9.34532314106289e-06 1.08418499663543e-05 3.00298102622624e-05 -9.67930771770907e-06 -1.26785790768675e-05 1.84262527030807e-05 8.51988222752462e-07 -9.09243296770728e-06 -3.70409315271724e-06 4.75340453348978e-06 9.34532314106289e-06 8.51988222752462e-07 5.72446930824662e-05 -1.754521481192e-05 5.5140594794472e-06 1.09908362885456e-05 1.08418499663543e-05 -9.09243296770728e-06 -1.754521481192e-05 6.63117500851691e-05 7.65370925414165e-06 2.22938970504413e-05 3.00298102622624e-05 -3.70409315271724e-06 5.5140594794472e-06 7.65370925414165e-06 5.27472924500914e-05 1600 1603 0 20 15 1585 1606 0 35 7 0 0 0 0 0 21 51 0 631 0 51 53 0 0 2197 +381 423 0.999998976433331 0.000713343792604905 0.00124027131048959 -0.0115792542996872 -0.000713861711381216 0.999999658175865 0.000417192532799495 0.00882979797389251 -0.00123997328483133 -0.000418077487975407 0.999999143838367 -0.0103031436706729 2.37111579829644e-05 1.61071163450741e-05 -7.65141331470362e-06 3.07702845046662e-06 1.03013455880902e-05 1.35866344829582e-05 1.61071163450741e-05 2.57950125715766e-05 -8.76306943707386e-06 8.45007050726255e-06 3.88596555504008e-06 1.93008757601661e-05 -7.65141331470362e-06 -8.76306943707386e-06 1.26133828874918e-05 -1.99118802415187e-06 -2.24925930413177e-06 -2.22076338073833e-06 3.07702845046662e-06 8.45007050726255e-06 -1.99118802415187e-06 5.49415605962744e-05 -1.31333308880936e-05 -4.05080738131047e-07 1.03013455880902e-05 3.88596555504008e-06 -2.24925930413177e-06 -1.31333308880936e-05 4.80681129559565e-05 7.55619164559768e-06 1.35866344829582e-05 1.93008757601661e-05 -2.22076338073833e-06 -4.05080738131047e-07 7.55619164559768e-06 4.3061817221768e-05 2570 2571 0 10 12 2577 2594 0 35 12 0 0 0 0 0 22 53 0 613 0 48 61 0 0 2244 +381 419 0.999998814075247 0.000514805642172627 -0.00145149001063475 -0.0116195871676083 -0.000514962786710101 0.999999861586244 -0.000107892638180877 0.0079961299704959 0.00145143426598968 0.000108639973569085 0.999998940767403 -0.00759628770922474 3.12218427851303e-05 1.85485431064741e-05 -8.26811942251501e-06 6.05584992502856e-06 8.98164931245262e-06 2.29233064510922e-05 1.85485431064741e-05 2.49936122093632e-05 -8.3598820383287e-06 6.96490539083914e-06 2.9166311959182e-06 2.37090097337872e-05 -8.26811942251501e-06 -8.3598820383287e-06 1.34901293474444e-05 1.3243057710284e-06 -3.25422364723272e-06 -2.72952970209039e-06 6.05584992502856e-06 6.96490539083914e-06 1.3243057710284e-06 4.1448263289617e-05 -1.14672271352489e-05 9.35604216981946e-06 8.98164931245262e-06 2.9166311959182e-06 -3.25422364723272e-06 -1.14672271352489e-05 4.41989832332653e-05 4.6209193986989e-06 2.29233064510922e-05 2.37090097337872e-05 -2.72952970209039e-06 9.35604216981946e-06 4.6209193986989e-06 6.12027889311475e-05 3055 3059 0 19 14 3053 3091 0 35 11 0 0 0 0 0 19 51 0 599 0 16 18 0 0 2225 +381 422 0.999975298568124 0.00105629377588113 -0.00694884861333796 -0.0157944608823027 -0.00105547303029823 0.999999435573168 0.000121778603130473 0.0129003040825857 0.00694897332520187 -0.000114441272721601 0.999975849044826 -0.00452723731813206 5.06455888287823e-05 3.85920619167783e-05 -1.05694722667292e-05 1.69671391097819e-05 7.64359118469636e-06 3.63926353362461e-05 3.85920619167783e-05 4.4379504719908e-05 -1.13040889644219e-05 1.73464107326098e-05 7.31962774163314e-06 3.6085199279323e-05 -1.05694722667292e-05 -1.13040889644219e-05 1.40109203193424e-05 -3.06386178661103e-06 -6.28460880840907e-06 -6.71484903670189e-06 1.69671391097819e-05 1.73464107326098e-05 -3.06386178661103e-06 4.23381202939328e-05 -9.34300119402504e-08 1.16874347048475e-05 7.64359118469636e-06 7.31962774163314e-06 -6.28460880840907e-06 -9.34300119402504e-08 4.81105116222619e-05 4.08162007381117e-06 3.63926353362461e-05 3.6085199279323e-05 -6.71484903670189e-06 1.16874347048475e-05 4.08162007381117e-06 6.81266247138712e-05 2667 2671 0 16 14 2668 2700 0 42 15 0 0 0 0 0 15 49 0 609 0 58 66 0 0 2269 +381 420 0.999998559970412 0.00103336541008332 0.00134618462042752 -0.00668620966903721 -0.00103293346447319 0.999999414835763 -0.000321522300754659 0.00651139912002995 -0.00134651608271259 0.000320131318609234 0.99999904220473 -0.0083958817972544 3.47022337746336e-05 2.30086405733501e-05 -9.28054908328842e-06 9.51003086432013e-06 9.63784234301218e-06 2.10779551500283e-05 2.30086405733501e-05 3.32525130269709e-05 -9.80485360387489e-06 1.2329631687771e-05 5.2683222061716e-06 2.69537997052102e-05 -9.28054908328842e-06 -9.80485360387489e-06 1.41956200636917e-05 1.28862383920408e-06 -6.5470827236889e-06 -4.18489332952073e-06 9.51003086432013e-06 1.2329631687771e-05 1.28862383920408e-06 6.51996103232442e-05 -2.81141535563943e-05 1.00920340742171e-05 9.63784234301218e-06 5.2683222061716e-06 -6.5470827236889e-06 -2.81141535563943e-05 5.83419031392499e-05 2.59285055670216e-06 2.10779551500283e-05 2.69537997052102e-05 -4.18489332952073e-06 1.00920340742171e-05 2.59285055670216e-06 5.2121954641947e-05 2555 2560 0 18 11 2553 2575 0 38 9 0 0 0 0 0 20 51 0 632 0 46 56 0 0 2277 +381 412 0.99999944005521 6.46315313200568e-05 0.0010562727072447 -0.00669752549937373 -6.36315090297899e-05 0.999999549805269 -0.000946752497499008 0.00448691760040626 -0.00105633342177998 0.000946684755143571 0.999998993973332 -0.0094926284846252 4.39780125052626e-05 3.66218283147359e-05 -8.59806842197266e-06 1.53496707612608e-05 2.90238717438306e-06 3.27618963261034e-05 3.66218283147359e-05 4.16452713113663e-05 -9.82029677268567e-06 1.27256975659774e-05 3.67912240007946e-06 3.38450521917914e-05 -8.59806842197266e-06 -9.82029677268567e-06 1.35480060906245e-05 -1.15995459319031e-06 -1.21136578338519e-06 -6.85497682005438e-06 1.53496707612608e-05 1.27256975659774e-05 -1.15995459319031e-06 5.32566402919465e-05 -2.08939047139003e-05 8.77839595180146e-06 2.90238717438306e-06 3.67912240007946e-06 -1.21136578338519e-06 -2.08939047139003e-05 4.61256210838127e-05 3.40300165344894e-06 3.27618963261034e-05 3.38450521917914e-05 -6.85497682005438e-06 8.77839595180146e-06 3.40300165344894e-06 5.26324242715776e-05 2609 2613 0 15 9 2615 2635 0 35 6 0 0 0 0 0 17 49 0 576 0 43 49 0 0 2202 +381 411 0.999997048507094 -0.000117325812685636 0.00242676981882218 -0.00390767398716708 0.000116358899099954 0.999999913799757 0.000398573814925578 0.00280980138490755 -0.00242681637263078 -0.000398290262273304 0.999996975959008 -0.00706040662140869 2.74647455494793e-05 2.1493341366481e-05 -3.90630715862294e-06 2.50031063803518e-06 4.59210476591252e-06 1.91902173263706e-05 2.1493341366481e-05 2.64621185518015e-05 -5.79523260584409e-06 2.84413886435667e-06 3.51439249296222e-06 1.97120666357238e-05 -3.90630715862294e-06 -5.79523260584409e-06 1.191467636276e-05 1.4446514090643e-06 1.08188198452465e-06 -3.0872293415071e-06 2.50031063803518e-06 2.84413886435667e-06 1.4446514090643e-06 4.05236875177652e-05 -1.10508147667717e-05 -5.73750230804056e-06 4.59210476591252e-06 3.51439249296222e-06 1.08188198452465e-06 -1.10508147667717e-05 4.3196566158233e-05 7.33202218430082e-06 1.91902173263706e-05 1.97120666357238e-05 -3.0872293415071e-06 -5.73750230804056e-06 7.33202218430082e-06 4.16905339111896e-05 2582 2585 0 17 11 2580 2605 0 41 9 0 0 0 0 0 16 48 0 534 0 42 53 0 0 2217 +381 410 0.999999696099545 0.000392758356369444 -0.000673455040527133 -0.0133842855383612 -0.000392141155694072 0.999999503258129 0.000916356268184766 0.00878577818747897 0.000673814612575557 -0.000916091900265779 0.99999935337454 -0.00110405937768839 5.28501943245298e-05 4.20399519014315e-05 -1.21110111913665e-06 1.20175770505662e-05 -9.52642105879702e-06 4.31755918452054e-05 4.20399519014315e-05 4.73842611645194e-05 -1.95254531281156e-06 1.39655565499734e-05 -9.08069797436154e-06 4.41738585155557e-05 -1.21110111913665e-06 -1.95254531281156e-06 9.716839598401e-06 3.31106739173717e-06 2.33181360465537e-06 8.80725437368356e-08 1.20175770505662e-05 1.39655565499734e-05 3.31106739173717e-06 4.96542268933202e-05 -2.12443339456888e-05 1.64523294796689e-05 -9.52642105879702e-06 -9.08069797436154e-06 2.33181360465537e-06 -2.12443339456888e-05 5.09871916959419e-05 -1.39546054650242e-05 4.31755918452054e-05 4.41738585155557e-05 8.80725437368356e-08 1.64523294796689e-05 -1.39546054650242e-05 6.59871199163866e-05 2130 2135 0 15 9 2133 2154 0 35 7 0 0 0 0 0 18 48 0 504 0 37 43 0 0 2347 +381 425 0.999994475891282 0.000289466367673208 -0.00331125295668802 -0.0180531940485766 -0.000287949021451865 0.999999853336681 0.000458706854719718 0.0102700410183725 0.00331138525125573 -0.000457750848724525 0.99999441258033 -0.00413299061962556 4.6392653493265e-05 2.8151992687527e-05 -8.0481004890037e-06 1.53712424551741e-05 -2.47286186298174e-06 2.66498184335542e-05 2.8151992687527e-05 4.05290295714387e-05 -7.47597045520123e-06 1.8508190471742e-05 -5.37449453278214e-07 2.96545133436618e-05 -8.0481004890037e-06 -7.47597045520123e-06 1.49247481517212e-05 -1.2181027701875e-06 -4.55470140907886e-06 -1.25427170779728e-06 1.53712424551741e-05 1.8508190471742e-05 -1.2181027701875e-06 6.62384410737211e-05 -2.37823513719038e-05 9.98473442219295e-06 -2.47286186298174e-06 -5.37449453278214e-07 -4.55470140907886e-06 -2.37823513719038e-05 6.33131213026379e-05 -3.04581936365556e-06 2.66498184335542e-05 2.96545133436618e-05 -1.25427170779728e-06 9.98473442219295e-06 -3.04581936365556e-06 5.70431160549835e-05 2099 2103 0 17 16 2090 2118 0 43 7 0 0 0 0 0 18 49 0 635 0 52 53 0 0 2130 +381 427 0.999999900840645 -8.4577105062906e-05 0.000437224671291842 -0.00879048459353722 8.41640186955525e-05 0.999999550206324 0.000944724069517469 0.00748104725643261 -0.000437304376657833 -0.000944687177253831 0.999999458165363 -0.00364789883878862 3.07627594419423e-05 1.83123405980862e-05 -8.16772814010104e-06 8.04414670972854e-06 5.66490661670136e-06 2.3055428620705e-05 1.83123405980862e-05 2.34074883516274e-05 -8.14103000830195e-06 5.06726359167441e-06 3.99333867268362e-06 2.18472037445296e-05 -8.16772814010104e-06 -8.14103000830195e-06 1.30363323139167e-05 -4.16271692582325e-06 -3.88968368479181e-06 -3.06086003235688e-06 8.04414670972854e-06 5.06726359167441e-06 -4.16271692582325e-06 3.7861560869015e-05 -1.65397100731805e-07 4.63021006702388e-06 5.66490661670136e-06 3.99333867268362e-06 -3.88968368479181e-06 -1.65397100731805e-07 4.05963376936267e-05 1.63200560098732e-06 2.3055428620705e-05 2.18472037445296e-05 -3.06086003235688e-06 4.63021006702388e-06 1.63200560098732e-06 5.12524889313323e-05 2993 2995 0 13 17 2997 3034 0 36 15 0 0 0 0 0 17 48 0 647 0 19 21 0 0 2360 +381 428 0.99999933475963 0.00108263145697778 -0.000397981689857896 -0.00823932972919246 -0.00108273671240243 0.999999378899216 -0.000264352784086338 0.00994506866176871 0.000397695246031364 0.000264783517614667 0.999999885864084 -0.00553563372312783 3.07721638436429e-05 2.15569601654131e-05 -1.03136825507216e-05 4.59092946506968e-06 1.40568873250158e-05 2.43654938275587e-05 2.15569601654131e-05 2.68617023568249e-05 -1.01221794228104e-05 3.15982439112591e-06 9.04795466128187e-06 2.61183514733779e-05 -1.03136825507216e-05 -1.01221794228104e-05 1.35352280414931e-05 7.2574913533996e-07 -6.34732209199102e-06 -6.07555277603725e-06 4.59092946506968e-06 3.15982439112591e-06 7.2574913533996e-07 4.10079648880875e-05 -2.89866998878573e-06 4.76537520290864e-06 1.40568873250158e-05 9.04795466128187e-06 -6.34732209199102e-06 -2.89866998878573e-06 5.2185778668244e-05 1.13216460972852e-05 2.43654938275587e-05 2.61183514733779e-05 -6.07555277603725e-06 4.76537520290864e-06 1.13216460972852e-05 5.93533074186777e-05 2552 2551 0 10 16 2554 2601 0 45 13 0 0 0 0 0 17 49 0 654 0 17 20 0 0 2278 +381 421 0.999997594446426 0.000267250005365225 0.0021770803376751 -0.00717129355238476 -0.000272447922689179 0.999997112524877 0.00238761681122582 0.00724238483092526 -0.00217643596080417 -0.0023882042087012 0.999994779789958 -0.0090401868321378 7.09080562745741e-05 4.98556830913339e-05 -9.56057802228622e-06 2.55887233334342e-05 -6.39434786711788e-06 5.44792317112258e-05 4.98556830913339e-05 5.54736611722252e-05 -9.56523359164161e-06 1.73804940199403e-05 -3.97841778576648e-06 5.13338022272247e-05 -9.56057802228622e-06 -9.56523359164161e-06 1.43804206306155e-05 -1.30984958542906e-07 -3.35426326553265e-06 -3.08313788468199e-06 2.55887233334342e-05 1.73804940199403e-05 -1.30984958542906e-07 6.13500443812343e-05 -2.74142711614289e-05 2.29498035555682e-05 -6.39434786711788e-06 -3.97841778576648e-06 -3.35426326553265e-06 -2.74142711614289e-05 6.02820443738197e-05 -1.6655292754089e-05 5.44792317112258e-05 5.13338022272247e-05 -3.08313788468199e-06 2.29498035555682e-05 -1.6655292754089e-05 8.30801602946531e-05 2118 2117 0 12 14 2117 2155 0 48 10 0 0 0 0 0 21 53 0 627 0 51 58 0 0 2311 +381 429 0.999970971140688 -0.00758065398621373 0.000768479726773693 -0.00588879299786437 0.00757836436490718 0.999966962477828 0.00293978679808883 0.00492680222796833 -0.000790739844617232 -0.00293387764005493 0.99999538353559 -0.00941983536451048 3.89469599980461e-05 2.44884885494052e-05 -3.72202687140622e-06 3.37600777686072e-06 3.07649431723249e-06 2.61106853269741e-05 2.44884885494052e-05 4.27938659789072e-05 -4.64840263008592e-06 1.55199688602517e-05 -9.15722761767756e-06 2.91830648470521e-05 -3.72202687140622e-06 -4.64840263008592e-06 1.13207701242886e-05 1.83969201223329e-06 -9.99834698484617e-07 -8.73158138303239e-07 3.37600777686072e-06 1.55199688602517e-05 1.83969201223329e-06 5.14063289255607e-05 -1.71680067561256e-05 4.82695009277022e-06 3.07649431723249e-06 -9.15722761767756e-06 -9.99834698484617e-07 -1.71680067561256e-05 4.70446183744877e-05 -1.7416599705091e-06 2.61106853269741e-05 2.91830648470521e-05 -8.73158138303239e-07 4.82695009277022e-06 -1.7416599705091e-06 5.99969095292384e-05 2634 2630 0 5 24 2644 2661 0 35 23 0 0 0 0 0 27 59 0 611 0 45 54 0 0 2393 +381 409 0.999998551270538 0.000528871486666218 -0.00161794677775787 -0.0134915932194102 -0.00052979773945647 0.999999696001321 -0.000572111546322861 0.0104028724220485 0.00161764371242014 0.000572967902033425 0.999998527467217 0.00101719875057032 2.77458640030158e-05 2.39286337159674e-05 -2.07696552385039e-06 2.9092148282608e-06 -3.14840146048767e-07 2.04527928542676e-05 2.39286337159674e-05 3.25980052585885e-05 -3.3033848863383e-06 6.78473912873943e-06 -2.80874787971553e-06 2.55904396440209e-05 -2.07696552385039e-06 -3.3033848863383e-06 1.27168790126036e-05 2.3626086870258e-06 1.78000429776171e-06 1.75958661363067e-07 2.9092148282608e-06 6.78473912873943e-06 2.3626086870258e-06 4.70233164689973e-05 -1.33972224157246e-05 -2.76189745075753e-06 -3.14840146048767e-07 -2.80874787971553e-06 1.78000429776171e-06 -1.33972224157246e-05 3.74025118172178e-05 2.37568012487884e-06 2.04527928542676e-05 2.55904396440209e-05 1.75958661363067e-07 -2.76189745075753e-06 2.37568012487884e-06 4.36955318310179e-05 2121 2124 0 20 10 2108 2139 0 45 3 0 0 0 0 0 15 47 0 507 0 45 46 0 0 2241 +382 417 0.999996403577131 0.000464203840279263 -0.00264146694051531 -0.0103762236288381 -0.00046704099260217 0.999999314663458 -0.00107356663767385 0.00503546814587204 0.00264096677646549 0.00107479645001607 0.999995935045276 -0.000318670412505699 3.86340474482652e-05 2.502379677661e-05 -8.73485515889876e-06 6.99862541936023e-06 4.81988466867903e-06 2.68244265136217e-05 2.502379677661e-05 3.88289993053258e-05 -9.79494136411613e-06 1.31620936437185e-05 7.29084724827243e-06 3.31326204393688e-05 -8.73485515889876e-06 -9.79494136411613e-06 1.38186037869226e-05 -3.26011203305607e-07 -2.72524026778039e-06 -5.53195098126944e-06 6.99862541936023e-06 1.31620936437185e-05 -3.26011203305607e-07 3.68360761855696e-05 2.13004842081264e-06 1.05240191681142e-05 4.81988466867903e-06 7.29084724827243e-06 -2.72524026778039e-06 2.13004842081264e-06 4.32022701780876e-05 1.01632882649311e-05 2.68244265136217e-05 3.31326204393688e-05 -5.53195098126944e-06 1.05240191681142e-05 1.01632882649311e-05 5.29606368225791e-05 2719 2720 0 20 13 2714 2739 0 39 10 0 0 0 0 0 19 52 0 610 0 59 61 0 0 2306 +381 408 0.999995603674281 0.000452060504788462 -0.00293057561081588 -0.0145707771234641 -0.000453295664094412 0.999999808715601 -0.000420822768787675 0.00862137827929828 0.0029303848128892 0.000422149335931397 0.999995617307789 0.00245265906576929 5.14028652704467e-05 4.49840836255665e-05 -2.7045914358495e-06 9.46826989239872e-06 -3.76029413634049e-06 4.26023381430271e-05 4.49840836255665e-05 6.08268591131338e-05 -2.77868951991653e-06 1.50219495497565e-05 -5.04147718468849e-06 5.13922699900388e-05 -2.7045914358495e-06 -2.77868951991653e-06 1.0171606289115e-05 2.63621030765665e-06 2.38602555567202e-06 5.03797764847395e-07 9.46826989239872e-06 1.50219495497565e-05 2.63621030765665e-06 4.14190422305211e-05 -1.08900985372631e-05 1.09738909075032e-05 -3.76029413634049e-06 -5.04147718468849e-06 2.38602555567202e-06 -1.08900985372631e-05 3.74717623030493e-05 -2.41686645383178e-06 4.26023381430271e-05 5.13922699900388e-05 5.03797764847395e-07 1.09738909075032e-05 -2.41686645383178e-06 6.50726769839278e-05 2584 2588 0 18 15 2574 2609 0 42 12 0 0 0 0 0 22 53 0 495 0 57 68 0 0 2317 +381 407 0.999999333693707 0.000695524632517363 -0.000921334699331992 -0.0146886470928586 -0.000695806225631472 0.999999711307251 -0.000305350799404467 0.0105902866352585 0.0009211220543468 0.000305991666366993 0.99999952895152 0.00146564197784253 2.67075892616888e-05 1.77855860791917e-05 -3.25265859595848e-06 -1.94066384992885e-06 1.85458219099768e-06 1.65498790937557e-05 1.77855860791917e-05 3.07044490509854e-05 -3.38299735332689e-06 6.10205532407241e-06 9.76019916213877e-07 1.98648212331991e-05 -3.25265859595848e-06 -3.38299735332689e-06 1.11036637858342e-05 1.40182086091546e-06 3.17794695826932e-06 -1.13984524823662e-06 -1.94066384992885e-06 6.10205532407241e-06 1.40182086091546e-06 5.123756395519e-05 -1.67199818400705e-05 -3.23431921743579e-06 1.85458219099768e-06 9.76019916213877e-07 3.17794695826932e-06 -1.67199818400705e-05 3.63808777212999e-05 2.36399826197247e-06 1.65498790937557e-05 1.98648212331991e-05 -1.13984524823662e-06 -3.23431921743579e-06 2.36399826197247e-06 4.08422305936114e-05 2090 2096 0 18 17 2080 2103 0 38 9 0 0 0 0 0 21 51 0 495 0 51 56 0 0 2309 +382 385 0.999999959790764 0.000255944175537845 0.000122110806251835 -0.00351146317321756 -0.000255890514779331 0.999999870786838 -0.00043925658970298 0.00375769155910889 -0.000122223215639212 0.000439225325043736 0.999999896071294 -0.00118855800329782 2.39576259409475e-05 1.45999668151187e-05 -7.5383996509809e-06 6.05471236274275e-06 6.95608099928858e-06 1.59510223535555e-05 1.45999668151187e-05 1.82400422196471e-05 -7.45976930467252e-06 5.20774290728993e-06 5.2690369560069e-06 1.40079244449151e-05 -7.5383996509809e-06 -7.45976930467252e-06 1.09541034597219e-05 -5.63716031868089e-07 -2.8578225202189e-06 -4.03699870480322e-06 6.05471236274275e-06 5.20774290728993e-06 -5.63716031868089e-07 2.59283053747243e-05 -1.32389262777164e-07 3.58158832288609e-06 6.95608099928858e-06 5.2690369560069e-06 -2.8578225202189e-06 -1.32389262777164e-07 3.3003961681993e-05 5.14256331391578e-06 1.59510223535555e-05 1.40079244449151e-05 -4.03699870480322e-06 3.58158832288609e-06 5.14256331391578e-06 3.64988561347656e-05 2693 2669 0 23 56 2668 2719 0 51 32 0 0 0 0 0 19 51 0 655 0 56 32 0 0 2800 +382 414 0.999987294021231 0.00051230251065237 -0.00501491198669987 -0.0117736526597816 -0.000515041860614752 0.999999718872654 -0.000544964673543461 0.00784317541311665 0.0050146313901005 0.000547540638834338 0.999987276754695 0.000580431328747192 4.21804191764657e-05 3.38579545668621e-05 -9.70073922821107e-06 1.07642049507611e-05 4.2343907690298e-06 3.52748507754448e-05 3.38579545668621e-05 4.69471265085715e-05 -8.53657284477411e-06 1.8320597598959e-05 -1.80271852884778e-06 4.3718294055713e-05 -9.70073922821107e-06 -8.53657284477411e-06 1.32480562959522e-05 -9.20415032551888e-07 -2.04005474076194e-06 -5.139800184444e-06 1.07642049507611e-05 1.8320597598959e-05 -9.20415032551888e-07 3.53106162391044e-05 -7.34800579819302e-06 1.28326947492746e-05 4.2343907690298e-06 -1.80271852884778e-06 -2.04005474076194e-06 -7.34800579819302e-06 3.6732434870602e-05 -1.1340901572701e-06 3.52748507754448e-05 4.3718294055713e-05 -5.139800184444e-06 1.28326947492746e-05 -1.1340901572701e-06 7.05306547395388e-05 2617 2620 0 20 11 2616 2652 0 51 11 0 0 0 0 0 22 52 0 599 0 58 60 0 0 2395 +382 384 0.999999056801273 -8.76253956684636e-05 -0.00137066347208506 -0.0025879371248085 8.7205890918455e-05 0.999999949343941 -0.000306116397118497 0.00274907121624699 0.00137069022622306 0.000305996578460668 0.999999013786712 0.00377512773019582 2.60395653075492e-05 2.06219195392256e-05 -8.143119062983e-06 6.09807431377866e-06 6.00337597064663e-06 1.47083639938481e-05 2.06219195392256e-05 2.52695295754827e-05 -9.58313872278108e-06 5.417113591004e-06 4.43885467747112e-06 1.75746307838093e-05 -8.143119062983e-06 -9.58313872278108e-06 1.2688798484794e-05 -1.03145728496778e-06 -2.2812233045697e-06 -4.52693184977131e-06 6.09807431377866e-06 5.417113591004e-06 -1.03145728496778e-06 2.22851646567966e-05 -3.5681725413353e-07 2.20684330671748e-06 6.00337597064663e-06 4.43885467747112e-06 -2.2812233045697e-06 -3.5681725413353e-07 2.67655050471813e-05 5.3491522480916e-06 1.47083639938481e-05 1.75746307838093e-05 -4.52693184977131e-06 2.20684330671748e-06 5.3491522480916e-06 2.81066342888738e-05 2780 2762 0 21 53 2753 2778 0 40 26 0 0 0 0 0 21 52 0 680 0 101 82 0 0 2835 +382 386 0.999999693919902 -5.64252441169562e-05 -0.000780369331921211 -0.00698500775862298 5.66511732197843e-05 0.999999956491199 0.000289496535531412 0.00322799665353561 0.000780352963055589 -0.000289540655760482 0.999999653607671 0.00328171478852461 2.73095194736016e-05 1.95485348141494e-05 -9.15848244722514e-06 2.93304768845676e-06 7.53342875277271e-06 1.57215007305365e-05 1.95485348141494e-05 3.16858878832561e-05 -1.00850734452174e-05 8.76399229578094e-06 5.75085115725913e-06 2.19882924500399e-05 -9.15848244722514e-06 -1.00850734452174e-05 1.46926019011666e-05 -1.43999270986714e-06 -3.00504921596824e-06 -5.89063285431583e-06 2.93304768845676e-06 8.76399229578094e-06 -1.43999270986714e-06 3.19824502203951e-05 -1.68018628612514e-06 1.77482940735033e-06 7.53342875277271e-06 5.75085115725913e-06 -3.00504921596824e-06 -1.68018628612514e-06 3.2710764398436e-05 2.13647879018188e-06 1.57215007305365e-05 2.19882924500399e-05 -5.89063285431583e-06 1.77482940735033e-06 2.13647879018188e-06 3.85785678020121e-05 2112 2086 0 11 49 2058 2086 0 49 0 0 0 0 0 0 21 51 0 636 0 86 64 0 0 2735 +382 419 0.999999706474045 0.000206807394959743 -0.000737755057164468 -0.00714715553366899 -0.000206301669131949 0.999999743762516 0.000685503116476342 0.005290257335363 0.000737896635237724 -0.000685350715163681 0.999999492901348 -0.00574336422827552 2.85751295395188e-05 1.79215541801066e-05 -8.58157465438575e-06 3.59962405141433e-06 1.21096909668791e-05 2.05465909571597e-05 1.79215541801066e-05 2.12549120732515e-05 -8.86277478759007e-06 5.80499611895797e-07 6.47031956829149e-06 2.0466775498153e-05 -8.58157465438575e-06 -8.86277478759007e-06 1.30780120321229e-05 -5.00187327912728e-08 -4.32566412968215e-06 -5.11428479928099e-06 3.59962405141433e-06 5.80499611895797e-07 -5.00187327912728e-08 3.38294838238714e-05 -4.65421825972073e-06 -2.57435981919111e-06 1.21096909668791e-05 6.47031956829149e-06 -4.32566412968215e-06 -4.65421825972073e-06 4.57312053348276e-05 9.16764603147121e-06 2.05465909571597e-05 2.0466775498153e-05 -5.11428479928099e-06 -2.57435981919111e-06 9.16764603147121e-06 4.94081027547888e-05 2594 2595 0 17 14 2591 2625 0 33 10 0 0 0 0 0 16 47 0 592 0 15 16 0 0 2245 +382 412 0.999994947209736 0.000109520240414163 0.00317703640433137 -0.00281205234546599 -0.000107840424470659 0.999999854315886 -0.000528903251124412 0.00167212840521526 -0.00317709386709885 0.000528557965732812 0.999994813337068 -0.00323748058078755 4.45148214752769e-05 3.24427975331832e-05 -6.90127930670881e-06 9.00564086353424e-06 2.80860128026397e-06 3.66834090851618e-05 3.24427975331832e-05 4.56949016495978e-05 -8.60639466497007e-06 1.84384868716908e-05 2.10549185825831e-06 4.21295421300176e-05 -6.90127930670881e-06 -8.60639466497007e-06 1.14374270947675e-05 1.06249435945781e-06 -8.46728050539251e-07 -4.44694727105515e-06 9.00564086353424e-06 1.84384868716908e-05 1.06249435945781e-06 3.95154852832792e-05 -9.92084420458533e-06 1.2440657150593e-05 2.80860128026397e-06 2.10549185825831e-06 -8.46728050539251e-07 -9.92084420458533e-06 3.95819700202747e-05 4.64418263723764e-06 3.66834090851618e-05 4.21295421300176e-05 -4.44694727105515e-06 1.2440657150593e-05 4.64418263723764e-06 6.44409272459234e-05 2157 2152 0 16 9 2149 2174 0 38 6 0 0 0 0 0 23 55 0 576 0 12 12 0 0 2324 +382 416 0.999988596127478 0.00115894762117207 -0.00463297479031772 -0.0140202369178513 -0.00116094760386944 0.999999234071677 -0.000429018321844995 0.0117721196081795 0.00463247403202756 0.00043439207035635 0.999989175685353 0.00119604008787767 4.08326794729755e-05 2.95398648137108e-05 -9.33912193573401e-06 9.40499689051758e-06 9.84037513085005e-06 3.17156725166036e-05 2.95398648137108e-05 3.8435313242454e-05 -1.05284262250621e-05 1.23438933004874e-05 9.79456793546188e-06 3.24033561910485e-05 -9.33912193573401e-06 -1.05284262250621e-05 1.39606767265012e-05 -9.87895685912834e-07 -3.62096288249567e-06 -5.91321205870252e-06 9.40499689051758e-06 1.23438933004874e-05 -9.87895685912834e-07 3.31330109548044e-05 -3.75478970692497e-06 7.28862739082966e-06 9.84037513085005e-06 9.79456793546188e-06 -3.62096288249567e-06 -3.75478970692497e-06 4.22764667182722e-05 4.86378865012008e-06 3.17156725166036e-05 3.24033561910485e-05 -5.91321205870252e-06 7.28862739082966e-06 4.86378865012008e-06 6.07214270663486e-05 2615 2623 0 22 12 2610 2640 0 47 5 0 0 0 0 0 19 49 0 606 0 60 62 0 0 2236 +382 413 0.999989111564883 0.00104317087448132 -0.00454846635720563 -0.0130874493275308 -0.00103809949861073 0.999998837125902 0.00111718229270547 0.00814742541752106 0.00454962647994115 -0.0011124483676937 0.999989031618608 -0.00493363476154532 8.60604463008115e-05 6.45218305288392e-05 -1.05412055661793e-05 2.67557651950379e-05 -1.04366628502811e-05 6.5509681511151e-05 6.45218305288392e-05 6.68258002431791e-05 -1.45049201225294e-05 2.32300279584343e-05 4.46736801051433e-06 6.51516014193359e-05 -1.05412055661793e-05 -1.45049201225294e-05 1.59472788403527e-05 -1.53097939855163e-07 -4.76825589337571e-06 -1.05569538282934e-05 2.67557651950379e-05 2.32300279584343e-05 -1.53097939855163e-07 4.62769163313626e-05 -1.67962890195081e-05 2.39597178505108e-05 -1.04366628502811e-05 4.46736801051433e-06 -4.76825589337571e-06 -1.67962890195081e-05 6.99055221915331e-05 1.28716705603842e-07 6.5509681511151e-05 6.51516014193359e-05 -1.05569538282934e-05 2.39597178505108e-05 1.28716705603842e-07 9.40539026134808e-05 2153 2155 0 14 11 2155 2177 0 41 11 0 0 0 0 0 20 52 0 597 0 42 44 0 0 2248 +382 425 0.999993129253136 0.000946248117814974 -0.00358414020664623 -0.0171293571097529 -0.00095072581365904 0.999998769543871 -0.00124781055053766 0.00970168273221565 0.00358295505813411 0.00125120951176146 0.999992798427973 -0.000755863521690149 3.7376145548431e-05 1.27586518134147e-05 -1.06428368602765e-05 4.92873967399372e-07 3.33424459701358e-06 8.88934187217302e-06 1.27586518134147e-05 3.76605238234655e-05 -8.63824779942501e-06 1.23294520934851e-05 4.87449511589507e-06 2.23716341904639e-05 -1.06428368602765e-05 -8.63824779942501e-06 1.88198480658723e-05 -5.1169141572409e-07 -6.5856843776135e-06 -4.83195634552458e-06 4.92873967399372e-07 1.23294520934851e-05 -5.1169141572409e-07 3.89254417591004e-05 -2.77803389529861e-06 4.10464604611766e-07 3.33424459701358e-06 4.87449511589507e-06 -6.5856843776135e-06 -2.77803389529861e-06 4.71910558408142e-05 3.04988617007318e-06 8.88934187217302e-06 2.23716341904639e-05 -4.83195634552458e-06 4.10464604611766e-07 3.04988617007318e-06 4.39360529352232e-05 1636 1638 0 22 16 1617 1645 0 45 6 0 0 0 0 0 20 49 0 633 0 54 56 0 0 2040 +382 426 0.999998016737747 0.000453424850143554 0.00193931082540045 -0.00565015069428892 -0.000456479084199788 0.99999865588686 0.00157475436778725 0.00501211880901617 -0.00193859418598406 -0.00157563649946591 0.999996879606233 -0.00552811261898999 2.87012723346417e-05 1.83264635147097e-05 -7.33926238646751e-06 3.51448611583972e-06 8.35666388034812e-06 2.05522726687505e-05 1.83264635147097e-05 2.59851410289445e-05 -9.3853095112556e-06 5.50377516698921e-06 6.31291524962686e-06 2.079035307695e-05 -7.33926238646751e-06 -9.3853095112556e-06 1.34107057888135e-05 1.79180396002419e-08 -2.83477964812856e-06 -2.07953151336313e-06 3.51448611583972e-06 5.50377516698921e-06 1.79180396002419e-08 3.68326490104855e-05 -1.4005969555088e-06 -1.4009705023971e-06 8.35666388034812e-06 6.31291524962686e-06 -2.83477964812856e-06 -1.4005969555088e-06 4.05810830414668e-05 7.96852782207784e-06 2.05522726687505e-05 2.079035307695e-05 -2.07953151336313e-06 -1.4009705023971e-06 7.96852782207784e-06 5.00249426004961e-05 2664 2667 0 22 17 2662 2692 0 47 16 0 0 0 0 0 13 42 0 649 0 17 19 0 0 2212 +382 427 0.999999240124604 0.000242620479200655 -0.00120867097179936 -0.0062724126817839 -0.000242218417966717 0.999999915292967 0.00033278265754505 0.0055394304598822 0.00120875160930427 -0.000332489642301065 0.999999214184784 -0.00499313452805617 2.64419431329794e-05 1.58757475967561e-05 -8.59335742950824e-06 5.54206391188756e-06 1.19055416246074e-05 2.07795145869642e-05 1.58757475967561e-05 1.81082882515845e-05 -8.26527855959156e-06 2.2412278722609e-06 2.63606023869529e-06 1.72161172630661e-05 -8.59335742950824e-06 -8.26527855959156e-06 1.29477176654031e-05 6.11658347193555e-07 -4.27356792088843e-06 -3.77486735751031e-06 5.54206391188756e-06 2.2412278722609e-06 6.11658347193555e-07 2.45952434311989e-05 1.81594813869896e-06 5.473487058024e-06 1.19055416246074e-05 2.63606023869529e-06 -4.27356792088843e-06 1.81594813869896e-06 4.34228153874686e-05 1.07173470786951e-05 2.07795145869642e-05 1.72161172630661e-05 -3.77486735751031e-06 5.473487058024e-06 1.07173470786951e-05 4.57100150756863e-05 3139 3141 0 22 17 3131 3179 0 48 14 0 0 0 0 0 20 51 0 655 0 19 19 0 0 2444 +382 415 0.999999216966991 0.00063990424437451 -0.00107544779633466 -0.0088766552492867 -0.000641385932760593 0.999998844922889 -0.00137796116512855 0.00593069373109208 0.00107456479091137 0.00137864986322746 0.999998472316365 -0.00257231332863027 2.99631415985223e-05 2.26059566470688e-05 -9.53033780592211e-06 9.43414085325432e-06 1.06832871639067e-05 2.64800316558034e-05 2.26059566470688e-05 2.54525059338171e-05 -1.04901665839181e-05 9.86823481106326e-06 9.73150714200889e-06 2.67516617430349e-05 -9.53033780592211e-06 -1.04901665839181e-05 1.31646767442419e-05 -1.24792478948623e-06 -3.83364174741911e-06 -7.60100274980204e-06 9.43414085325432e-06 9.86823481106326e-06 -1.24792478948623e-06 3.78998340720426e-05 -3.9038414711497e-06 1.28507519632211e-05 1.06832871639067e-05 9.73150714200889e-06 -3.83364174741911e-06 -3.9038414711497e-06 4.05574852380609e-05 1.34835020611755e-05 2.64800316558034e-05 2.67516617430349e-05 -7.60100274980204e-06 1.28507519632211e-05 1.34835020611755e-05 5.43288340866545e-05 3140 3144 0 21 14 3138 3179 0 47 12 0 0 0 0 0 24 55 0 579 0 16 17 0 0 2242 +382 418 0.999997742101471 0.000688998777608669 0.00201024193694114 -0.00417559056823378 -0.000689675782135373 0.99999970569071 0.00033610386645288 0.00352293003277528 -0.00201000977015512 -0.000337489522744596 0.999997922978616 -0.00500882479370997 3.0564677670357e-05 2.25282933585219e-05 -9.10587267195689e-06 2.62997823982054e-06 1.01954766647605e-05 2.31691141114099e-05 2.25282933585219e-05 3.05341096873531e-05 -1.02305307061582e-05 5.35726324075013e-06 9.52883831735099e-06 2.66100993575353e-05 -9.10587267195689e-06 -1.02305307061582e-05 1.30182893088572e-05 -2.74655605483726e-06 -2.62634444649694e-06 -5.39222922064708e-06 2.62997823982054e-06 5.35726324075013e-06 -2.74655605483726e-06 3.58730457914682e-05 -3.94618647958004e-06 1.43775333354167e-06 1.01954766647605e-05 9.52883831735099e-06 -2.62634444649694e-06 -3.94618647958004e-06 4.14553997215411e-05 1.04326220843072e-05 2.31691141114099e-05 2.66100993575353e-05 -5.39222922064708e-06 1.43775333354167e-06 1.04326220843072e-05 4.74618539729052e-05 2654 2654 0 13 13 2654 2678 0 42 11 0 0 0 0 0 14 47 0 605 0 15 17 0 0 2209 +382 420 0.999999843236653 0.000481991179876975 -0.000284975738027959 -0.00210254669917802 -0.000482099789928877 0.999999811142853 -0.000381174567902235 0.00322519463737612 0.000284791961428532 0.000381311894891472 0.999999886747382 -0.00895638984351093 2.6668441181866e-05 1.52214420139012e-05 -8.08220927448978e-06 6.71452093722369e-06 4.88095006544868e-06 1.2048192483149e-05 1.52214420139012e-05 2.32866395747981e-05 -9.24063329392153e-06 8.13128288496562e-06 3.20288262055191e-06 1.95392186656115e-05 -8.08220927448978e-06 -9.24063329392153e-06 1.26660027794965e-05 1.9919706211276e-06 -2.84792774623279e-06 -2.90847755746194e-06 6.71452093722369e-06 8.13128288496562e-06 1.9919706211276e-06 3.74083683010454e-05 -7.17686174374594e-06 5.02920940014673e-06 4.88095006544868e-06 3.20288262055191e-06 -2.84792774623279e-06 -7.17686174374594e-06 4.99849936807722e-05 1.52133475093281e-06 1.2048192483149e-05 1.95392186656115e-05 -2.90847755746194e-06 5.02920940014673e-06 1.52133475093281e-06 4.20686271622846e-05 2663 2664 0 17 11 2661 2690 0 51 9 0 0 0 0 0 15 46 0 617 0 13 15 0 0 2338 +382 428 0.999998959568404 0.0013404700259013 0.000532918584949057 -0.0042633104737945 -0.00134077336474309 0.999998939137903 0.000569253768268024 0.00737779175517747 -0.000532154951982435 -0.000569967699042694 0.999999695973918 -0.00312876600090561 2.90369403298089e-05 1.47076996603578e-05 -9.45829891400889e-06 3.70939952899883e-06 9.44267133045224e-06 2.00796622895984e-05 1.47076996603578e-05 1.93725278425307e-05 -8.79940369188547e-06 2.40449510590209e-06 6.01214645320148e-06 1.67693375125431e-05 -9.45829891400889e-06 -8.79940369188547e-06 1.4190182602724e-05 -1.5824341879313e-06 -4.05593613525736e-06 -3.30776675226907e-06 3.70939952899883e-06 2.40449510590209e-06 -1.5824341879313e-06 2.73839903698326e-05 5.24456481956123e-06 1.03849643008014e-07 9.44267133045224e-06 6.01214645320148e-06 -4.05593613525736e-06 5.24456481956123e-06 4.2531269557811e-05 8.75529029008453e-06 2.00796622895984e-05 1.67693375125431e-05 -3.30776675226907e-06 1.03849643008014e-07 8.75529029008453e-06 4.77112418268436e-05 3099 3102 0 16 16 3095 3142 0 52 12 0 0 0 0 0 16 48 0 639 0 16 18 0 0 2284 +382 424 0.999996825452874 0.00121501345769952 -0.00220744795438036 -0.0140276461891486 -0.00121649238803864 0.999999036456837 -0.000668753816680932 0.00899312317503481 0.00220663328252182 0.00067143703732392 0.999997339967393 0.000456193109324995 3.24643530799954e-05 2.39030161373994e-05 -1.08424915256594e-05 8.39989889210098e-06 3.32629843417829e-06 2.23845273731473e-05 2.39030161373994e-05 3.24145858425574e-05 -1.3499440271811e-05 1.03885138463444e-05 4.82831404062516e-06 2.47569478823625e-05 -1.08424915256594e-05 -1.3499440271811e-05 1.753449493111e-05 -2.08345817849577e-06 -2.34782958368148e-06 -6.37302457319914e-06 8.39989889210098e-06 1.03885138463444e-05 -2.08345817849577e-06 3.28785661728296e-05 4.35606924612784e-06 6.88648831509219e-06 3.32629843417829e-06 4.82831404062516e-06 -2.34782958368148e-06 4.35606924612784e-06 3.98113808908558e-05 1.99037084034835e-06 2.23845273731473e-05 2.47569478823625e-05 -6.37302457319914e-06 6.88648831509219e-06 1.99037084034835e-06 4.52453547010332e-05 2139 2146 0 20 15 2123 2152 0 43 6 0 0 0 0 0 21 52 0 629 0 51 52 0 0 2238 +382 411 0.999998140915634 0.000197321622098366 0.00191813176096957 -0.00226635282784387 -0.000198295752722646 0.999999851471443 0.000507676950800414 0.00142257509014107 -0.0019180313004328 -0.000508056364367495 0.999998031515393 -0.00385424287523718 3.55823550569257e-05 2.65883944731647e-05 -4.20364209515991e-06 5.65344069219486e-06 5.63033663931974e-06 2.47540055249491e-05 2.65883944731647e-05 3.85245228006371e-05 -5.84278981804242e-06 9.73719702679258e-06 4.78137677599791e-06 3.63946023807162e-05 -4.20364209515991e-06 -5.84278981804242e-06 1.05754616127935e-05 2.86222641694598e-06 1.1998377196501e-06 -3.2794695965475e-06 5.65344069219486e-06 9.73719702679258e-06 2.86222641694598e-06 3.53134501197993e-05 -8.86028049906659e-06 1.02392320656396e-05 5.63033663931974e-06 4.78137677599791e-06 1.1998377196501e-06 -8.86028049906659e-06 3.30005058182709e-05 6.1391975171039e-06 2.47540055249491e-05 3.63946023807162e-05 -3.2794695965475e-06 1.02392320656396e-05 6.1391975171039e-06 5.86450143607064e-05 2709 2715 0 21 11 2710 2735 0 42 9 0 0 0 0 0 20 51 0 536 0 11 13 0 0 2262 +382 421 0.999999011233305 0.000628816016160648 0.00125782464224241 -0.00242722098524517 -0.000628897817751485 0.999999800154601 6.46397127843651e-05 0.00420733138347672 -0.00125778374438527 -6.54306920433902e-05 0.999999206849124 -0.00800368612561181 2.81650530888103e-05 1.96935542670793e-05 -9.1140876274483e-06 2.54592906243184e-06 1.04325542651562e-05 1.84547276893285e-05 1.96935542670793e-05 2.72578750920762e-05 -9.68127543661582e-06 7.17349724280482e-06 9.4462984193482e-06 2.14062839316912e-05 -9.1140876274483e-06 -9.68127543661582e-06 1.42892656096522e-05 -1.94437989843367e-06 -3.90460810501595e-06 -5.27963943904856e-06 2.54592906243184e-06 7.17349724280482e-06 -1.94437989843367e-06 3.69138229674087e-05 2.89803651225465e-07 -9.05662888210151e-07 1.04325542651562e-05 9.4462984193482e-06 -3.90460810501595e-06 2.89803651225465e-07 4.19286053005428e-05 1.1872518917473e-05 1.84547276893285e-05 2.14062839316912e-05 -5.27963943904856e-06 -9.05662888210151e-07 1.1872518917473e-05 4.22285756213474e-05 2654 2657 0 18 14 2648 2686 0 53 8 0 0 0 0 0 24 56 0 627 0 15 16 0 0 2329 +382 410 0.999999729171802 0.000572464755168868 -0.000462536946219832 -0.00936076162168829 -0.000573211923843745 0.99999852860088 -0.0016168562601842 0.00586603169373603 0.000461610672420247 0.00161712095398672 0.999998585916704 0.000583155929959709 2.82028817110665e-05 2.19559179431914e-05 -3.14271726599179e-06 2.31672469645025e-06 4.35932149859698e-07 2.07374659505511e-05 2.19559179431914e-05 2.82039401960194e-05 -3.9944721472155e-06 5.2635968864721e-06 -7.93891312039738e-07 2.02103303464304e-05 -3.14271726599179e-06 -3.9944721472155e-06 1.06561907219174e-05 3.16293939219108e-06 2.38394564300961e-06 -1.9957094666462e-06 2.31672469645025e-06 5.2635968864721e-06 3.16293939219108e-06 3.5321711066461e-05 -5.30391768591413e-06 6.98409463932449e-07 4.35932149859698e-07 -7.93891312039738e-07 2.38394564300961e-06 -5.30391768591413e-06 4.23672574636789e-05 2.66925013271391e-06 2.07374659505511e-05 2.02103303464304e-05 -1.9957094666462e-06 6.98409463932449e-07 2.66925013271391e-06 3.5918939485217e-05 2055 2055 0 22 9 2048 2077 0 47 7 0 0 0 0 0 20 50 0 516 0 32 32 0 0 2289 +382 423 0.999999477588607 0.000950462705130657 0.00037608929611366 -0.00906751655070084 -0.000950647522359227 0.999999427326117 0.000491545243516131 0.00822229760312316 -0.000375621885315296 -0.000491902515084832 0.999999808470039 -0.0102056881138512 3.66489160150501e-05 1.8935100378668e-05 -1.0676049486096e-05 4.56667476372168e-06 1.01236072413829e-05 1.7403067777258e-05 1.8935100378668e-05 3.01194259911822e-05 -1.17896990899253e-05 1.5427876445842e-05 5.04029189419609e-06 1.53319827148267e-05 -1.0676049486096e-05 -1.17896990899253e-05 1.62071542844951e-05 -5.73521639273045e-07 -4.50157981145735e-06 -4.63225078431739e-06 4.56667476372168e-06 1.5427876445842e-05 -5.73521639273045e-07 5.21591122966251e-05 -8.79808656552986e-06 2.40996484162253e-06 1.01236072413829e-05 5.04029189419609e-06 -4.50157981145735e-06 -8.79808656552986e-06 5.46722623342147e-05 6.50498632894869e-07 1.7403067777258e-05 1.53319827148267e-05 -4.63225078431739e-06 2.40996484162253e-06 6.50498632894869e-07 3.84192608009946e-05 2135 2137 0 21 12 2131 2148 0 35 12 0 0 0 0 0 27 57 0 618 0 13 16 0 0 2220 +383 385 0.999995893279471 0.000457149537279474 0.00282921163814274 0.00103789214216917 -0.000457535365328226 0.999999886119744 0.000135727258436387 -0.00100323919832606 -0.002829149268298 -0.000137021165422917 0.999995988561763 -0.000368125880034078 2.95197701483025e-05 1.73557445321153e-05 -7.07448258624931e-06 3.32283196761565e-06 7.29871144358983e-06 1.6748636605567e-05 1.73557445321153e-05 2.53558622139262e-05 -7.91311461979685e-06 6.38975443525323e-06 3.51909859734397e-06 1.58440534416452e-05 -7.07448258624931e-06 -7.91311461979685e-06 1.32106063687639e-05 -9.57932111945189e-07 -3.8303550860911e-06 -3.10146243366452e-06 3.32283196761565e-06 6.38975443525323e-06 -9.57932111945189e-07 3.07546941856044e-05 -8.22193830423091e-06 -3.31385014512962e-07 7.29871144358983e-06 3.51909859734397e-06 -3.8303550860911e-06 -8.22193830423091e-06 3.72763165300865e-05 8.10912353954682e-06 1.6748636605567e-05 1.58440534416452e-05 -3.10146243366452e-06 -3.31385014512962e-07 8.10912353954682e-06 3.51036254192034e-05 2669 2640 0 19 56 2642 2667 0 50 28 0 0 0 0 0 11 43 0 643 0 98 81 0 0 2717 +382 422 0.999975946388287 0.000667810938828864 -0.00690367100898578 -0.0118315575348538 -0.000685298685551702 0.999996562061756 -0.00253105321565463 0.00886630771820346 0.00690195700956702 0.00253572341135129 0.999972966182696 -0.000731893325450175 5.41525525059018e-05 3.74455199319326e-05 -1.03285013360244e-05 1.61419314490063e-05 6.05205923598358e-06 3.90941964193312e-05 3.74455199319326e-05 5.15928400935387e-05 -9.80745972164176e-06 2.4305377597161e-05 -4.11883909161497e-07 3.99846780707817e-05 -1.03285013360244e-05 -9.80745972164176e-06 1.4773484808633e-05 2.9844528974362e-07 -6.25761840359722e-06 -4.26638083231618e-06 1.61419314490063e-05 2.4305377597161e-05 2.9844528974362e-07 4.76850038341513e-05 -8.91758657899603e-06 1.15656526219372e-05 6.05205923598358e-06 -4.11883909161497e-07 -6.25761840359722e-06 -8.91758657899603e-06 5.12896879506793e-05 -4.4938431413179e-06 3.90941964193312e-05 3.99846780707817e-05 -4.26638083231618e-06 1.15656526219372e-05 -4.4938431413179e-06 7.42638986880497e-05 2300 2298 0 14 14 2303 2336 0 51 15 0 0 0 0 0 21 54 0 608 0 61 62 0 0 2330 +383 417 0.999999578707447 0.000687467945403709 0.000608253855434252 -0.00460902765965706 -0.000686861736202784 0.999999267816629 -0.000996286686303502 0.00495776912126872 -0.000608938325242159 0.000995868480276145 0.999999318719811 -0.000429065856073132 4.14081679374713e-05 2.54485509222383e-05 -8.70658966484682e-06 1.82007157597914e-06 1.28299641570992e-05 2.53865157513764e-05 2.54485509222383e-05 2.75206633628615e-05 -8.93699365937752e-06 4.77882335400936e-06 1.03598944095386e-05 2.60627472140598e-05 -8.70658966484682e-06 -8.93699365937752e-06 1.24097451963479e-05 2.27773891205809e-06 -2.50431900612281e-06 -3.68490620132192e-06 1.82007157597914e-06 4.77882335400936e-06 2.27773891205809e-06 2.44310333843409e-05 1.64392374206494e-06 7.32150921288101e-06 1.28299641570992e-05 1.03598944095386e-05 -2.50431900612281e-06 1.64392374206494e-06 3.7959431063703e-05 9.63514746011054e-06 2.53865157513764e-05 2.60627472140598e-05 -3.68490620132192e-06 7.32150921288101e-06 9.63514746011054e-06 4.74579700077282e-05 3257 3253 0 11 13 3259 3302 0 49 12 0 0 0 0 0 18 51 0 605 0 13 16 0 0 2404 +383 416 0.999999144016467 0.000572462010614338 0.00117654306311027 -0.00634012856680808 -0.00057355622874866 0.999999403158294 0.00092990123620801 0.00695981096741208 -0.00117601002776895 -0.000930575253830102 0.999998875514423 -0.00208013538017836 2.91898978381642e-05 1.92437507583066e-05 -8.06022090093687e-06 6.05394207926176e-06 1.01773497692186e-05 2.19668043160252e-05 1.92437507583066e-05 2.50231867951201e-05 -8.82273836853208e-06 7.10306136251777e-06 8.44171623406929e-06 2.19811934562637e-05 -8.06022090093687e-06 -8.82273836853208e-06 1.26096772349833e-05 -3.80713262284793e-07 -2.2588417089922e-06 -3.9821563806468e-06 6.05394207926176e-06 7.10306136251777e-06 -3.80713262284793e-07 3.16699944818207e-05 -3.69398894314213e-06 9.40944574861771e-06 1.01773497692186e-05 8.44171623406929e-06 -2.2588417089922e-06 -3.69398894314213e-06 3.9564214265977e-05 8.11847261364065e-06 2.19668043160252e-05 2.19811934562637e-05 -3.9821563806468e-06 9.40944574861771e-06 8.11847261364065e-06 4.32269853979781e-05 2494 2492 0 17 12 2488 2526 0 46 12 0 0 0 0 0 18 49 0 617 0 12 19 0 0 2351 +382 409 0.999998030333397 0.00033348452489024 -0.00195655753754641 -0.012518735912306 -0.000335437178108772 0.999999445977049 -0.000997761241232776 0.0107556590042002 0.00195622371563515 0.000998415578114983 0.999997588174646 0.00280288380011928 2.93372949947657e-05 2.32729391674554e-05 -2.74328505444711e-06 2.2247089552492e-06 1.04395319865889e-06 1.93683135873783e-05 2.32729391674554e-05 3.6249629250918e-05 -2.83203354171346e-06 7.26244592235586e-06 -3.52568468958859e-06 2.70338347389123e-05 -2.74328505444711e-06 -2.83203354171346e-06 1.10056272425354e-05 2.18950136440216e-06 9.33873408256928e-07 -1.35354671582883e-07 2.2247089552492e-06 7.26244592235586e-06 2.18950136440216e-06 4.00306774716946e-05 -1.88526598816929e-05 -4.03989272089415e-07 1.04395319865889e-06 -3.52568468958859e-06 9.33873408256928e-07 -1.88526598816929e-05 4.35039692957004e-05 -2.27766254544955e-06 1.93683135873783e-05 2.70338347389123e-05 -1.35354671582883e-07 -4.03989272089415e-07 -2.27766254544955e-06 4.96247944396192e-05 2037 2039 0 13 10 2029 2058 0 44 2 0 0 0 0 0 18 47 0 497 0 44 45 0 0 2254 +383 415 0.999997931483908 -2.82476610848061e-05 0.0020337723508486 -0.00201324245695532 2.54028637820513e-05 0.999999021368913 0.00139879087438721 0.00109417350104714 -0.0020338098731063 -0.00139873631732379 0.999996953572417 -0.00446698552043342 3.10884214839051e-05 2.17829640486863e-05 -9.27700705325767e-06 4.91882806486658e-06 1.15186823497826e-05 2.30880265421353e-05 2.17829640486863e-05 2.8127499487972e-05 -8.73919401641562e-06 3.95525152267093e-06 8.24131160633298e-06 1.91186600380273e-05 -9.27700705325767e-06 -8.73919401641562e-06 1.44348591917506e-05 -6.25743777187647e-07 -3.76258505753357e-06 -4.92715286555861e-06 4.91882806486658e-06 3.95525152267093e-06 -6.25743777187647e-07 3.77194938399519e-05 -1.01000365275144e-05 2.15970197180744e-06 1.15186823497826e-05 8.24131160633298e-06 -3.76258505753357e-06 -1.01000365275144e-05 4.26528963790328e-05 9.72343906006254e-06 2.30880265421353e-05 1.91186600380273e-05 -4.92715286555861e-06 2.15970197180744e-06 9.72343906006254e-06 4.19792660238457e-05 2602 2601 0 13 14 2611 2646 0 54 12 0 0 0 0 0 15 46 0 586 0 55 60 0 0 2267 +382 408 0.999994015129326 0.000673397784789603 -0.00339355874454644 -0.0134819245893396 -0.000675048835618011 0.999999654346451 -0.000485402975095081 0.00998566667062126 0.00339323070226266 0.000487690887900157 0.999994124054236 -0.001078178929186 3.17877433617989e-05 2.4570368537091e-05 -2.06533409821106e-07 5.01565884993939e-06 -3.70287520991961e-06 2.00949042032734e-05 2.4570368537091e-05 3.9283122554961e-05 -1.11112570233074e-06 1.21055356867948e-05 -3.3790075616745e-06 3.4768641846123e-05 -2.06533409821106e-07 -1.11112570233074e-06 1.01971111475649e-05 4.73882572251194e-06 2.7810889871558e-06 1.41470712756578e-07 5.01565884993939e-06 1.21055356867948e-05 4.73882572251194e-06 3.43011868092312e-05 -7.06255562759833e-06 8.25960767375683e-06 -3.70287520991961e-06 -3.3790075616745e-06 2.7810889871558e-06 -7.06255562759833e-06 3.70308470819062e-05 -6.77357231072015e-07 2.00949042032734e-05 3.4768641846123e-05 1.41470712756578e-07 8.25960767375683e-06 -6.77357231072015e-07 5.39922347637661e-05 2725 2728 0 15 15 2723 2754 0 41 10 0 0 0 0 0 20 52 0 492 0 59 61 0 0 2308 +382 429 0.999975780662907 -0.00680644611252652 0.00145271433057324 -0.00167525234879633 0.00680126658064011 0.999970601388234 0.0035410637035498 0.00491754043930574 -0.00147677368206786 -0.00353109764390656 0.999992675217634 -0.00627778536410042 2.8183651179151e-05 1.69849970756017e-05 -3.54473922887709e-06 2.55337530500887e-06 4.0475172718105e-06 1.77084200067638e-05 1.69849970756017e-05 2.81290067991591e-05 -6.38603652238705e-06 5.96794610111878e-06 3.38137083369446e-06 1.91494142498124e-05 -3.54473922887709e-06 -6.38603652238705e-06 1.22005007597329e-05 8.41229484652448e-07 -1.00248956594401e-06 4.39062441187194e-07 2.55337530500887e-06 5.96794610111878e-06 8.41229484652448e-07 3.86352866374047e-05 1.40812777226805e-07 1.94355929911498e-06 4.0475172718105e-06 3.38137083369446e-06 -1.00248956594401e-06 1.40812777226805e-07 3.9813550949415e-05 2.22159733705987e-06 1.77084200067638e-05 1.91494142498124e-05 4.39062441187194e-07 1.94355929911498e-06 2.22159733705987e-06 4.93503145211158e-05 2179 2176 0 6 24 2182 2196 0 32 22 0 0 0 0 0 33 64 0 611 0 15 15 0 0 2393 +383 387 0.999998396252387 0.000338386914748725 0.00175868898631915 0.000478837364234452 -0.000340590281929001 0.999999157372694 0.00125269795320077 0.00357622731230675 -0.00175826360780429 -0.00125329493656709 0.999997668877727 0.000108017735469681 2.64400604375918e-05 1.70834871861127e-05 -5.80841834326909e-06 5.95906409601427e-06 5.18895215752728e-06 1.2077517321337e-05 1.70834871861127e-05 2.52367196780277e-05 -7.79427631612282e-06 8.3946599424634e-06 6.28342722327071e-06 1.67288455302092e-05 -5.80841834326909e-06 -7.79427631612282e-06 1.16992773160999e-05 -7.73344706518635e-07 -2.33295584813184e-06 -2.5874168212951e-06 5.95906409601427e-06 8.3946599424634e-06 -7.73344706518635e-07 2.59676829397257e-05 2.07396810076632e-06 5.23228212865134e-06 5.18895215752728e-06 6.28342722327071e-06 -2.33295584813184e-06 2.07396810076632e-06 3.30302339092429e-05 9.43412484892883e-06 1.2077517321337e-05 1.67288455302092e-05 -2.5874168212951e-06 5.23228212865134e-06 9.43412484892883e-06 3.25405210301478e-05 3130 3103 0 15 58 3103 3153 0 51 35 0 0 0 0 0 18 49 0 640 0 57 33 0 0 2724 +383 413 0.999999822932484 8.12058462840889e-05 -0.00058952575030947 -0.00607549917853805 -8.06968074485832e-05 0.999999623976 0.000863444198450332 0.00191437227638574 0.000589595645350494 -0.000863396472716454 0.999999453461604 -0.00351883257386876 7.25944420383179e-05 4.85373131284877e-05 -7.96813572999813e-06 3.99214243793705e-06 1.07009012720309e-05 5.91904828466351e-05 4.85373131284877e-05 4.56617375590672e-05 -9.82976932921081e-06 5.51825663951574e-06 1.26421364614012e-05 4.65855054564178e-05 -7.96813572999813e-06 -9.82976932921081e-06 1.30493296339392e-05 -1.20365092432957e-06 -1.49459572832216e-06 -5.35417575782249e-06 3.99214243793705e-06 5.51825663951574e-06 -1.20365092432957e-06 3.9218106165597e-05 -7.13715159763338e-06 -8.5461951970477e-07 1.07009012720309e-05 1.26421364614012e-05 -1.49459572832216e-06 -7.13715159763338e-06 4.51671299970817e-05 1.71776015164044e-05 5.91904828466351e-05 4.65855054564178e-05 -5.35417575782249e-06 -8.5461951970477e-07 1.71776015164044e-05 7.71023510361021e-05 2444 2440 0 13 11 2430 2461 0 45 4 0 0 0 0 0 17 49 0 605 0 17 28 0 0 2213 +383 419 0.999999619290741 0.000620973435970031 0.000613033739458922 -0.00442921965278032 -0.000621768827488626 0.99999896412928 0.00129813092236515 0.00782129783706953 -0.000612226999616021 -0.00129851159342408 0.99999896952234 -0.00864741405759347 3.41947110883537e-05 2.42395151977721e-05 -9.10008632305918e-06 1.23177434728896e-05 2.29566498158685e-06 1.74299587855734e-05 2.42395151977721e-05 3.77069038298818e-05 -9.79167147520651e-06 9.83249802831701e-06 6.77103847132633e-06 2.53924109727555e-05 -9.10008632305918e-06 -9.79167147520651e-06 1.49239105629707e-05 -1.8975691236783e-06 -3.64952769520189e-06 -2.52293559919101e-06 1.23177434728896e-05 9.83249802831701e-06 -1.8975691236783e-06 4.16540217361187e-05 -1.36819759775014e-05 1.33858068759223e-05 2.29566498158685e-06 6.77103847132633e-06 -3.64952769520189e-06 -1.36819759775014e-05 4.87301802429795e-05 -7.72818231983138e-06 1.74299587855734e-05 2.53924109727555e-05 -2.52293559919101e-06 1.33858068759223e-05 -7.72818231983138e-06 5.22325651738339e-05 2633 2628 0 11 14 2633 2658 0 40 15 0 0 0 0 0 21 53 0 603 0 55 61 0 0 2262 +383 386 0.999998459896855 0.000595773292401391 -0.00165083557706147 -0.00186407289510885 -0.000596185513903392 0.999999791225116 -0.000249223910020296 0.00262469956062132 0.00165068675145904 0.000250207730446648 0.999998606313699 0.00306450844394965 2.51054950634429e-05 1.93237203294134e-05 -7.65398327947317e-06 3.5083820948767e-06 3.58056383921463e-06 1.51188484097437e-05 1.93237203294134e-05 2.68179250897719e-05 -8.93998930021288e-06 6.43783320581806e-06 3.54021054069794e-06 1.6009943336004e-05 -7.65398327947317e-06 -8.93998930021288e-06 1.22948603101424e-05 -2.54605436608943e-06 -1.10555025953197e-06 -3.92435252724947e-06 3.5083820948767e-06 6.43783320581806e-06 -2.54605436608943e-06 3.28517534598629e-05 -9.94760546091921e-06 -3.18161899158817e-06 3.58056383921463e-06 3.54021054069794e-06 -1.10555025953197e-06 -9.94760546091921e-06 3.96799319438242e-05 1.01892454233797e-05 1.51188484097437e-05 1.6009943336004e-05 -3.92435252724947e-06 -3.18161899158817e-06 1.01892454233797e-05 3.34027628190055e-05 2004 1983 0 21 44 1971 1997 0 45 15 0 0 0 0 0 12 43 0 642 0 54 44 0 0 2803 +383 414 0.999999835650009 0.000424658361172942 0.000385182076372051 -0.00545240918573177 -0.00042564398002055 0.999996626521459 0.00256237641737713 0.00584227921936691 -0.00038409264239847 -0.00256253994668261 0.999996642925297 -0.00468704760752396 3.72753864215496e-05 2.92131760283817e-05 -9.72013486399223e-06 9.71943692806128e-06 8.02103900284317e-06 3.30917405767212e-05 2.92131760283817e-05 3.44054836235669e-05 -9.59437164175758e-06 1.26801234342545e-05 5.32210327215239e-06 3.42691060200646e-05 -9.72013486399223e-06 -9.59437164175758e-06 1.32052420599921e-05 -7.99405157280234e-07 -3.28254184364257e-06 -4.85400136744278e-06 9.71943692806128e-06 1.26801234342545e-05 -7.99405157280234e-07 3.66283690900477e-05 -5.28057158059265e-06 1.09542464695969e-05 8.02103900284317e-06 5.32210327215239e-06 -3.28254184364257e-06 -5.28057158059265e-06 3.88723413215089e-05 1.58256473402119e-06 3.30917405767212e-05 3.42691060200646e-05 -4.85400136744278e-06 1.09542464695969e-05 1.58256473402119e-06 5.94079507716666e-05 2539 2542 0 16 11 2540 2575 0 40 9 0 0 0 0 0 20 51 0 602 0 11 14 0 0 2388 +383 418 0.999999899161667 0.000448740129441813 1.75770359376227e-05 -0.0102146130912466 -0.000448742210376997 0.999999892286386 0.000118564938683243 0.00954671047860886 -1.75238291984047e-05 -0.000118572814285311 0.999999992816701 -0.0016089423161452 3.39896780926808e-05 2.66535185803656e-05 -1.41222893738804e-05 8.64991704125407e-06 1.4966019191633e-05 2.63106663915123e-05 2.66535185803656e-05 2.68116813850177e-05 -1.31792253221799e-05 8.7477921498192e-06 1.03278511901703e-05 2.71527393848323e-05 -1.41222893738804e-05 -1.31792253221799e-05 1.78114957245864e-05 -4.24424256704365e-06 -8.3463277099235e-06 -7.9866801529092e-06 8.64991704125407e-06 8.7477921498192e-06 -4.24424256704365e-06 4.19657126030655e-05 -1.01504312907779e-05 9.42675142120443e-06 1.4966019191633e-05 1.03278511901703e-05 -8.3463277099235e-06 -1.01504312907779e-05 4.93435421478577e-05 9.59338511635828e-06 2.63106663915123e-05 2.71527393848323e-05 -7.9866801529092e-06 9.42675142120443e-06 9.59338511635828e-06 4.7014413962345e-05 2290 2290 0 11 13 2274 2306 0 48 6 0 0 0 0 0 22 55 0 620 0 53 61 0 0 2202 +383 426 0.999999769430467 0.000670238123796207 -0.000109178162457265 -0.00656403165386995 -0.000670261802898534 0.999999751831555 -0.000216992957161622 0.00760641541542507 0.000109032698410206 0.000217066085081662 0.999999970497092 -0.00132546676504824 4.09734420924122e-05 3.17855338809072e-05 -1.14882798535298e-05 1.2290218415195e-05 3.83492244926851e-06 2.27477610329048e-05 3.17855338809072e-05 3.38092726326952e-05 -1.29830528959032e-05 1.14331995309097e-05 2.24923287472145e-06 2.59453170697792e-05 -1.14882798535298e-05 -1.29830528959032e-05 1.68192075985652e-05 -1.51618110008905e-06 -5.39695527010517e-06 -6.99787767391033e-06 1.2290218415195e-05 1.14331995309097e-05 -1.51618110008905e-06 4.9086976705845e-05 -1.48488091388697e-05 5.10892293936711e-06 3.83492244926851e-06 2.24923287472145e-06 -5.39695527010517e-06 -1.48488091388697e-05 5.53085560147137e-05 5.89585145830596e-06 2.27477610329048e-05 2.59453170697792e-05 -6.99787767391033e-06 5.10892293936711e-06 5.89585145830596e-06 4.22440389930828e-05 2184 2186 0 18 17 2166 2197 0 55 8 0 0 0 0 0 13 42 0 638 0 60 69 0 0 2103 +383 425 0.999990505405303 0.00142857960002323 -0.00411682639589594 -0.010206725147923 -0.00143549062781109 0.999997564754162 -0.00167626143661427 0.00457923749762097 0.00411442169751894 0.00168215518689896 0.999990120895213 -0.00426243389177493 4.30015486298998e-05 2.00407850826965e-05 -9.23534415923747e-06 1.98904093034168e-06 7.40630672097541e-06 2.25312157565299e-05 2.00407850826965e-05 4.02152421527959e-05 -1.0812742900968e-05 7.2086361152645e-06 9.75606187485267e-06 2.46679594684621e-05 -9.23534415923747e-06 -1.0812742900968e-05 1.61807345570593e-05 -3.85401370012533e-07 -1.91896484394023e-06 -4.94010472226464e-06 1.98904093034168e-06 7.2086361152645e-06 -3.85401370012533e-07 4.43012169767753e-05 -1.4672407508578e-05 7.28463016386458e-06 7.40630672097541e-06 9.75606187485267e-06 -1.91896484394023e-06 -1.4672407508578e-05 5.69309161028418e-05 3.27387687334582e-06 2.25312157565299e-05 2.46679594684621e-05 -4.94010472226464e-06 7.28463016386458e-06 3.27387687334582e-06 4.91631511222734e-05 2458 2453 0 14 16 2457 2482 0 45 16 0 0 0 0 0 16 47 0 638 0 20 33 0 0 2035 +383 423 0.999996919921361 0.00072170839689072 -0.00237471783183316 -0.014352006079336 -0.000723016981179663 0.999999587243312 -0.000550235995297994 0.0118614260398422 0.00237431974171441 0.000551951261845784 0.999997028973371 -0.00356890357877554 2.53686579405681e-05 1.9201304477561e-05 -8.57694312535334e-06 1.64148561720631e-06 1.01225909943951e-05 1.77693184254212e-05 1.9201304477561e-05 3.07837131227984e-05 -8.35929921155812e-06 7.78213688367522e-06 6.74303568611825e-06 2.50702008402168e-05 -8.57694312535334e-06 -8.35929921155812e-06 1.59038448030031e-05 -5.43958144015311e-07 -3.97687425713947e-06 -2.8434805631802e-06 1.64148561720631e-06 7.78213688367522e-06 -5.43958144015311e-07 4.82252628056239e-05 -1.71352262638428e-05 -1.24147966761704e-06 1.01225909943951e-05 6.74303568611825e-06 -3.97687425713947e-06 -1.71352262638428e-05 4.91816507578939e-05 8.47990613584333e-06 1.77693184254212e-05 2.50702008402168e-05 -2.8434805631802e-06 -1.24147966761704e-06 8.47990613584333e-06 4.6393448190201e-05 2049 2047 0 16 12 2029 2056 0 40 4 0 0 0 0 0 24 54 0 615 0 52 60 0 0 2252 +383 427 0.999993562359318 -7.80060997038896e-05 0.00358736044586337 0.00171546277202841 7.56660984826154e-05 0.999999784310314 0.000652421618244589 0.000688869415456808 -0.00358741056497252 -0.000652145976619848 0.999993352573438 -0.00516916601113785 4.3963640597957e-05 2.2953815420872e-05 -8.95229293894811e-06 4.57942355977275e-06 7.67028369394012e-06 2.16959275871754e-05 2.2953815420872e-05 3.01138235266778e-05 -7.28312919269995e-06 9.15105163822517e-06 5.15529861936006e-07 2.09115965538467e-05 -8.95229293894811e-06 -7.28312919269995e-06 1.48415552387314e-05 -2.91602492093237e-06 -3.02608331903436e-06 -9.49776629762017e-07 4.57942355977275e-06 9.15105163822517e-06 -2.91602492093237e-06 4.26318213146305e-05 -7.70510276075612e-06 7.66260321895436e-06 7.67028369394012e-06 5.15529861936006e-07 -3.02608331903436e-06 -7.70510276075612e-06 4.56096956832518e-05 2.99930208428472e-06 2.16959275871754e-05 2.09115965538467e-05 -9.49776629762017e-07 7.66260321895436e-06 2.99930208428472e-06 4.4727132149129e-05 2657 2653 0 13 17 2658 2690 0 50 13 0 0 0 0 0 16 47 0 650 0 56 62 0 0 2335 +383 420 0.999999833562642 0.00057110037494056 8.19698096924427e-05 -0.00633802361849194 -0.000571106628153412 0.999999834008998 7.62836576082309e-05 0.00777730130479272 -8.19262304607299e-05 -7.63304584134043e-05 0.999999993730877 -0.00551849179741212 3.45387162177077e-05 2.09659069089514e-05 -1.02748160995317e-05 6.31911541403995e-06 1.28712789625871e-05 1.19360976756088e-05 2.09659069089514e-05 3.50152532813358e-05 -1.01320470127301e-05 1.28837126095085e-05 5.7914302769299e-06 2.10033810041882e-05 -1.02748160995317e-05 -1.01320470127301e-05 1.65072180545655e-05 -3.36275859248672e-06 -5.26984868100728e-06 -1.74592968712424e-06 6.31911541403995e-06 1.28837126095085e-05 -3.36275859248672e-06 4.35966383031453e-05 -9.50772371386833e-06 2.28466836930618e-06 1.28712789625871e-05 5.7914302769299e-06 -5.26984868100728e-06 -9.50772371386833e-06 5.39069482013371e-05 5.45249592947108e-06 1.19360976756088e-05 2.10033810041882e-05 -1.74592968712424e-06 2.28466836930618e-06 5.45249592947108e-06 4.06635969953053e-05 1948 1945 0 11 11 1935 1968 0 50 4 0 0 0 0 0 21 52 0 628 0 52 61 0 0 2259 +383 428 0.999999806309697 0.000612265811096431 0.000111853231592615 0.00155681929251157 -0.000612353499226065 0.999999503918256 0.000785612139581242 0.00145484829721434 -0.000111372172650421 -0.000785680481133554 0.999999685151161 -0.00451281440726102 4.26437050803951e-05 3.29574102074597e-05 -9.43659643317455e-06 1.3930310563419e-05 5.8945334924403e-06 3.15081704408914e-05 3.29574102074597e-05 3.45044440377039e-05 -1.01763697431644e-05 1.18700934532738e-05 1.77051695187501e-06 2.97082075442122e-05 -9.43659643317455e-06 -1.01763697431644e-05 1.32649251301431e-05 -2.57696891635403e-06 -3.2802240331387e-06 -4.19885032732613e-06 1.3930310563419e-05 1.18700934532738e-05 -2.57696891635403e-06 3.50706530441498e-05 3.66736675440505e-06 1.36593770344585e-05 5.8945334924403e-06 1.77051695187501e-06 -3.2802240331387e-06 3.66736675440505e-06 4.37548874392244e-05 3.92980731469847e-07 3.15081704408914e-05 2.97082075442122e-05 -4.19885032732613e-06 1.36593770344585e-05 3.92980731469847e-07 5.6283659192595e-05 2831 2832 0 20 16 2833 2865 0 46 16 0 0 0 0 0 21 54 0 651 0 55 61 0 0 2346 +383 421 0.999998728671601 0.000544033609059463 -0.00149889379697597 -0.00812848492857231 -0.00054526157331097 0.999999515996889 -0.000818960196792601 0.00788734500017185 0.00149844752963518 0.00081977644481521 0.999998541309727 -0.0035302807678811 5.65305747330869e-05 4.06384349404979e-05 -1.18942841796461e-05 1.49637804494022e-05 1.09339232944792e-05 3.39792313255492e-05 4.06384349404979e-05 4.51981796020845e-05 -1.24863656993411e-05 1.50788394934905e-05 9.84104904967333e-06 4.17116992794705e-05 -1.18942841796461e-05 -1.24863656993411e-05 1.66445228326806e-05 -4.83754190370597e-06 -4.31239517414987e-06 -7.23263579136507e-06 1.49637804494022e-05 1.50788394934905e-05 -4.83754190370597e-06 4.41350629154529e-05 -3.81409620328933e-06 1.07826848886583e-05 1.09339232944792e-05 9.84104904967333e-06 -4.31239517414987e-06 -3.81409620328933e-06 4.15025661743906e-05 7.24797675606237e-06 3.39792313255492e-05 4.17116992794705e-05 -7.23263579136507e-06 1.07826848886583e-05 7.24797675606237e-06 6.90701629475803e-05 2228 2230 0 17 14 2220 2245 0 41 12 0 0 0 0 0 19 52 0 625 0 55 64 0 0 2326 +383 410 0.999984706600048 0.000582532143901394 -0.00549974747764443 -0.00845022543500861 -0.000568314973119115 0.999996494112263 0.00258626782701928 0.00717807672728351 0.00550123478028917 -0.0025831026853511 0.999981531827668 -0.000225700291151398 7.32746469450896e-05 5.18236038351201e-05 -1.35027808636069e-06 3.45689797442763e-06 -7.23887327661338e-07 4.95602992562158e-05 5.18236038351201e-05 7.62071602357069e-05 -2.28303807810914e-06 1.49761978803923e-05 -3.63625450534478e-06 6.23498791019937e-05 -1.35027808636069e-06 -2.28303807810914e-06 1.17709888776115e-05 2.74363284056391e-06 3.20753059307106e-06 9.65970791136992e-07 3.45689797442763e-06 1.49761978803923e-05 2.74363284056391e-06 4.06197692712998e-05 -1.72408532997946e-05 9.44155735716867e-06 -7.23887327661338e-07 -3.63625450534478e-06 3.20753059307106e-06 -1.72408532997946e-05 4.08808611662223e-05 -2.53055397351912e-06 4.95602992562158e-05 6.23498791019937e-05 9.65970791136992e-07 9.44155735716867e-06 -2.53055397351912e-06 7.7766593622958e-05 1933 1928 0 13 9 1929 1957 0 49 5 0 0 0 0 0 11 41 0 505 0 10 22 0 0 2229 +383 422 0.999998868126264 0.000864913599095948 -0.00123112576780575 -0.00542591103680647 -0.000863205250629786 0.99999866487766 0.00138748679031396 0.00665656616497848 0.00123232418029574 -0.00138642250562715 0.999998279603395 -0.00728990866476554 3.15843159223998e-05 2.40449766436962e-05 -1.02586446856959e-05 6.85252269496172e-06 1.318267722439e-05 2.31244193340094e-05 2.40449766436962e-05 3.10029173099005e-05 -1.21094791327173e-05 8.70446279441688e-06 9.5240186210676e-06 2.421605181921e-05 -1.02586446856959e-05 -1.21094791327173e-05 1.48935513960287e-05 -2.67796001577706e-06 -5.78391752993188e-06 -5.25978401301797e-06 6.85252269496172e-06 8.70446279441688e-06 -2.67796001577706e-06 3.07244563837469e-05 9.41768226064047e-07 5.03157734900656e-06 1.318267722439e-05 9.5240186210676e-06 -5.78391752993188e-06 9.41768226064047e-07 4.30014871134158e-05 6.05475958700764e-06 2.31244193340094e-05 2.421605181921e-05 -5.25978401301797e-06 5.03157734900656e-06 6.05475958700764e-06 5.07100900724241e-05 3121 3119 0 18 14 3112 3151 0 46 11 0 0 0 0 0 17 50 0 612 0 14 18 0 0 2329 +383 424 0.999999515182946 0.000913564989351429 -0.000367468205745515 -0.00499114863632904 -0.000913834715829058 0.999999312695832 -0.000734516150730122 0.00115284720657764 0.000366796924943665 0.00073485159982754 0.999999662726514 -0.00153588972189484 2.7682590991827e-05 2.02501526770428e-05 -7.83330895114472e-06 4.7669733490503e-06 7.42120065501588e-06 1.93377169713216e-05 2.02501526770428e-05 2.24895553020878e-05 -9.14297770913163e-06 5.72700401743516e-06 5.78111538627078e-06 2.13702421153823e-05 -7.83330895114472e-06 -9.14297770913163e-06 1.34603629621785e-05 -2.89744046218584e-06 -1.01458343000597e-06 -4.58093161358427e-06 4.7669733490503e-06 5.72700401743516e-06 -2.89744046218584e-06 3.59161826536844e-05 -5.88096304595736e-06 5.08990200450159e-06 7.42120065501588e-06 5.78111538627078e-06 -1.01458343000597e-06 -5.88096304595736e-06 4.23269971192246e-05 7.58655450745177e-06 1.93377169713216e-05 2.13702421153823e-05 -4.58093161358427e-06 5.08990200450159e-06 7.58655450745177e-06 4.7586236216235e-05 2624 2622 0 11 15 2625 2656 0 53 14 0 0 0 0 0 18 48 0 623 0 21 34 0 0 2217 +383 412 0.999999647318409 -0.000271368118897017 -0.000794809664332155 -0.00622165497716487 0.000272432491741514 0.999999065957406 0.00133935240061332 0.00602977705150324 0.00079444546440458 -0.0013395684602257 0.999998787205637 -0.0041071277481365 4.8248433183673e-05 3.56173599131214e-05 -8.7439889860948e-06 8.24324633326142e-06 2.81300442190088e-06 3.40926401433791e-05 3.56173599131214e-05 5.49917336531207e-05 -8.02373777940611e-06 1.56707993319794e-05 4.31218467702547e-06 3.97220267324197e-05 -8.7439889860948e-06 -8.02373777940611e-06 1.40617365813032e-05 -4.64280234575234e-07 -3.17767630233775e-08 -3.97939950832613e-06 8.24324633326142e-06 1.56707993319794e-05 -4.64280234575234e-07 4.24079318712762e-05 -1.72335280230116e-05 1.23626827755195e-05 2.81300442190088e-06 4.31218467702547e-06 -3.17767630233775e-08 -1.72335280230116e-05 4.14102653178318e-05 -2.08984580598146e-06 3.40926401433791e-05 3.97220267324197e-05 -3.97939950832613e-06 1.23626827755195e-05 -2.08984580598146e-06 5.99386564491225e-05 1984 1981 0 16 9 1973 2000 0 44 6 0 0 0 0 0 18 49 0 566 0 48 58 0 0 2222 +384 387 0.999999872114507 2.86761357449919e-05 0.000504924399791388 0.00127599190410152 -2.90952392506045e-05 0.999999655089813 0.000830044409852447 -0.00171051245495431 -0.000504900423171647 -0.000830058994598023 0.999999528038703 0.000304942071260755 3.02355859545571e-05 2.15197168657879e-05 -9.51491411589435e-06 7.12130579378064e-06 1.02635493605013e-05 1.97391789498919e-05 2.15197168657879e-05 2.34690695184346e-05 -1.04935858276585e-05 5.86687591093519e-06 9.50388680155004e-06 2.16135395805236e-05 -9.51491411589435e-06 -1.04935858276585e-05 1.20041593699494e-05 -1.23557476434261e-06 -3.88090668413273e-06 -6.51853015658983e-06 7.12130579378064e-06 5.86687591093519e-06 -1.23557476434261e-06 1.97348628249117e-05 4.03343896146686e-06 6.89172872991281e-06 1.02635493605013e-05 9.50388680155004e-06 -3.88090668413273e-06 4.03343896146686e-06 2.78803112860099e-05 1.00054139416302e-05 1.97391789498919e-05 2.16135395805236e-05 -6.51853015658983e-06 6.89172872991281e-06 1.00054139416302e-05 3.46889492435799e-05 3250 3227 0 10 55 3232 3281 0 46 33 0 0 0 0 0 16 46 0 661 0 57 33 0 0 2735 +383 411 0.999996233791636 0.000152430362840388 0.00274028603017056 -0.00217606158628436 -0.00014949646308127 0.999999415489443 -0.00107082752109938 0.00306459831494084 -0.00274044765507203 0.00107041382507047 0.999995672071081 -0.00100257754882882 4.01281683111233e-05 3.61418055528306e-05 -5.9583867131201e-06 1.10842685374253e-05 -1.14854432918581e-06 3.09846666591199e-05 3.61418055528306e-05 5.13586649242631e-05 -7.15112690629795e-06 2.10970524825087e-05 -7.29132698086302e-06 4.31842910780194e-05 -5.9583867131201e-06 -7.15112690629795e-06 1.14862034352484e-05 7.64312770665713e-07 2.46958173171078e-06 -2.81204885046609e-06 1.10842685374253e-05 2.10970524825087e-05 7.64312770665713e-07 4.35145333958005e-05 -1.37420871473225e-05 1.48029314393803e-05 -1.14854432918581e-06 -7.29132698086302e-06 2.46958173171078e-06 -1.37420871473225e-05 3.63963829452594e-05 -2.22474032802942e-06 3.09846666591199e-05 4.31842910780194e-05 -2.81204885046609e-06 1.48029314393803e-05 -2.22474032802942e-06 6.68386903548097e-05 2001 2005 0 15 11 1997 2031 0 53 4 0 0 0 0 0 12 44 0 535 0 50 59 0 0 2354 +384 416 0.999999755052144 0.000282245367529977 0.000640494499785197 -0.0041842317064531 -0.000282666424260411 0.999999743963796 0.000657397927809804 0.00259460964843584 -0.000640308788275669 -0.000657578813071604 0.999999578797291 -0.00325344929455725 3.40551316970411e-05 2.27638587591613e-05 -1.05879934221029e-05 7.70280894572719e-06 1.38077420265648e-05 2.72887485415044e-05 2.27638587591613e-05 2.94024253013396e-05 -1.07859758402334e-05 8.64967084016509e-06 1.12981436695815e-05 2.87359352028539e-05 -1.05879934221029e-05 -1.07859758402334e-05 1.42912543480276e-05 -1.32623961202702e-06 -4.13329968653303e-06 -6.66219109534346e-06 7.70280894572719e-06 8.64967084016509e-06 -1.32623961202702e-06 2.83155193812564e-05 4.74736118269127e-07 9.65728423389142e-06 1.38077420265648e-05 1.12981436695815e-05 -4.13329968653303e-06 4.74736118269127e-07 3.89314698492267e-05 1.17049693095681e-05 2.72887485415044e-05 2.87359352028539e-05 -6.66219109534346e-06 9.65728423389142e-06 1.17049693095681e-05 5.01816363907605e-05 3041 3039 0 12 12 3044 3085 0 52 12 0 0 0 0 0 20 52 0 610 0 19 25 0 0 2274 +384 417 0.999999448909946 0.00037484281903793 0.000980649104229726 -0.00312479317322821 -0.000375168327709566 0.999999874589035 0.000331768955988977 0.00210854052055923 -0.000980524620034844 -0.000332136681638909 0.999999464128204 -0.00114713647072929 3.79658873546504e-05 2.52215333074749e-05 -9.61679605037855e-06 4.87078547495789e-06 1.28119358747563e-05 3.1057475105986e-05 2.52215333074749e-05 3.01927786237363e-05 -1.00391298430795e-05 7.04135654695516e-06 1.07871646747749e-05 3.07292425238585e-05 -9.61679605037855e-06 -1.00391298430795e-05 1.32896388192597e-05 -7.7452986608077e-08 -4.80292875303134e-06 -5.28794274071659e-06 4.87078547495789e-06 7.04135654695516e-06 -7.7452986608077e-08 2.75080939622503e-05 -1.47969295216719e-06 7.81746204992157e-06 1.28119358747563e-05 1.07871646747749e-05 -4.80292875303134e-06 -1.47969295216719e-06 4.10486521310893e-05 9.32703455576659e-06 3.1057475105986e-05 3.07292425238585e-05 -5.28794274071659e-06 7.81746204992157e-06 9.32703455576659e-06 6.14667924740367e-05 3118 3118 0 20 13 3117 3157 0 48 12 0 0 0 0 0 14 48 0 607 0 15 19 0 0 2370 +383 409 0.999996375389412 0.00100015855157263 -0.00249977817214074 -0.00869016129968083 -0.00100130399084542 0.999999394267342 -0.000457006856517954 0.00525433420990541 0.00249931957862779 0.000459508237906056 0.999996771121699 0.000986064878379548 4.11329551019423e-05 2.10403075846363e-05 -1.13995736765366e-06 1.08312600147849e-06 -5.01425260354741e-06 2.47904076636928e-05 2.10403075846363e-05 4.47718236082797e-05 -2.84247659187676e-06 1.03091942824856e-05 -3.4900445428681e-06 3.01604477407268e-05 -1.13995736765366e-06 -2.84247659187676e-06 1.18756105250676e-05 -6.18504553393672e-07 6.56697752835793e-06 3.24260203697043e-07 1.08312600147849e-06 1.03091942824856e-05 -6.18504553393672e-07 4.42563904036782e-05 -1.99267129296993e-05 2.17261824292172e-06 -5.01425260354741e-06 -3.4900445428681e-06 6.56697752835793e-06 -1.99267129296993e-05 3.62475726853599e-05 -1.87131167454323e-06 2.47904076636928e-05 3.01604477407268e-05 3.24260203697043e-07 2.17261824292172e-06 -1.87131167454323e-06 4.92053467621973e-05 1911 1906 0 17 10 1904 1934 0 52 10 0 0 0 0 0 14 46 0 508 0 11 22 0 0 2261 +383 429 0.999973220267256 -0.00730949941702044 -0.000360508817375454 -0.00572556722692916 0.00731022109083776 0.999971193270303 0.0020428649415478 0.0088476291449494 0.000345566112196103 -0.00204544563333084 0.999997848365797 -0.0050343293473985 3.66599524582994e-05 1.51081155137144e-05 -4.1514674436979e-06 -9.66625560499015e-07 -2.10395450283023e-06 2.15347994151059e-05 1.51081155137144e-05 4.60704643110181e-05 -5.67273619127503e-06 1.42459889112351e-05 -1.35143354761107e-06 2.26840000689671e-05 -4.1514674436979e-06 -5.67273619127503e-06 1.20372910190173e-05 1.22761342837373e-06 -1.50816137125799e-06 -2.10114134558374e-06 -9.66625560499015e-07 1.42459889112351e-05 1.22761342837373e-06 5.08838809115404e-05 -1.46944743653049e-05 3.0894973342973e-06 -2.10395450283023e-06 -1.35143354761107e-06 -1.50816137125799e-06 -1.46944743653049e-05 4.67188935338255e-05 -4.27867712699636e-06 2.15347994151059e-05 2.26840000689671e-05 -2.10114134558374e-06 3.0894973342973e-06 -4.27867712699636e-06 5.80117251917707e-05 2046 2043 0 2 23 2048 2063 0 33 11 0 0 0 0 0 32 64 0 617 0 50 57 0 0 2468 +384 415 0.999999169312309 0.000133068047352737 0.00128205600022266 -0.00135806793474521 -0.000132264356676776 0.999999794725657 -0.00062694081283409 -0.00139326488676722 -0.00128213916283923 0.000626770721729981 0.999998981638296 -0.0015289162503995 3.02035231066889e-05 2.46977125680095e-05 -6.26600812858016e-06 9.67165199302457e-06 4.34907231445272e-06 2.68820564984257e-05 2.46977125680095e-05 3.01436373061822e-05 -8.14994630091408e-06 7.56496659581697e-06 4.64048138323494e-06 2.82672826253409e-05 -6.26600812858016e-06 -8.14994630091408e-06 1.16647676759415e-05 7.80509848309353e-07 -5.33843542367326e-07 -3.53512385438198e-06 9.67165199302457e-06 7.56496659581697e-06 7.80509848309353e-07 3.43538256452108e-05 -8.80434575174659e-06 1.29989146803436e-05 4.34907231445272e-06 4.64048138323494e-06 -5.33843542367326e-07 -8.80434575174659e-06 4.00237025450919e-05 5.66991162198195e-06 2.68820564984257e-05 2.82672826253409e-05 -3.53512385438198e-06 1.29989146803436e-05 5.66991162198195e-06 5.18681014590244e-05 2754 2753 0 12 14 2759 2792 0 47 11 0 0 0 0 0 16 48 0 579 0 57 62 0 0 2373 +384 426 0.999999007927376 0.000710308959473914 0.00121639033430675 -0.00443463448380801 -0.000711970629497652 0.999998813326046 0.00136617873016615 0.00489425185004334 -0.00121541848185574 -0.00136704340900966 0.999998326973716 -0.00116691271064663 3.1087229467622e-05 2.33469229073047e-05 -1.1321491716891e-05 9.16829488634709e-06 1.14130685071354e-05 1.70343341775919e-05 2.33469229073047e-05 3.03580168193067e-05 -1.21922321685498e-05 1.20331362303146e-05 9.14072128922105e-06 1.68583745494648e-05 -1.1321491716891e-05 -1.21922321685498e-05 1.46119778838877e-05 -3.97483496165044e-06 -3.31908211279503e-06 -5.01209349146187e-06 9.16829488634709e-06 1.20331362303146e-05 -3.97483496165044e-06 4.13181259095738e-05 -1.72291114569692e-06 8.50454260814619e-07 1.14130685071354e-05 9.14072128922105e-06 -3.31908211279503e-06 -1.72291114569692e-06 4.31746306990985e-05 7.67301291915448e-06 1.70343341775919e-05 1.68583745494648e-05 -5.01209349146187e-06 8.50454260814619e-07 7.67301291915448e-06 3.70628320434132e-05 2021 2017 0 12 17 2006 2033 0 44 8 0 0 0 0 0 21 50 0 666 0 66 76 0 0 2125 +384 413 0.999996353592647 0.000174434711480203 -0.00269487920718824 -0.00647290465641934 -0.000175237569590092 0.999999940337228 -0.000297686637473576 -0.000258093375064248 0.00269482711952156 0.000298157796069439 0.999996324497608 -0.00221759217840595 2.94893117840047e-05 2.10621506492105e-05 -7.80315644326102e-06 5.04526600853822e-06 6.81326657120188e-06 1.66299651620011e-05 2.10621506492105e-05 2.94819314208323e-05 -1.01439596602833e-05 5.35944315845188e-06 1.09444550849622e-05 2.42934420552208e-05 -7.80315644326102e-06 -1.01439596602833e-05 1.30692898058333e-05 -3.10107502525027e-07 -2.22964659073936e-06 -6.63894954631192e-06 5.04526600853822e-06 5.35944315845188e-06 -3.10107502525027e-07 4.07268860627801e-05 -9.28327298581087e-06 -1.19533405117122e-06 6.81326657120188e-06 1.09444550849622e-05 -2.22964659073936e-06 -9.28327298581087e-06 4.57692387354311e-05 1.51295318815796e-05 1.66299651620011e-05 2.42934420552208e-05 -6.63894954631192e-06 -1.19533405117122e-06 1.51295318815796e-05 3.82584537631751e-05 2594 2592 0 16 11 2582 2613 0 46 4 0 0 0 0 0 17 50 0 603 0 34 44 0 0 2244 +384 418 0.999999853970385 0.000286224558120083 -0.000458404527419224 -0.00645356958914554 -0.000285768700683895 0.999999464950638 0.000994200526725111 0.00511118977313075 0.000458688846756619 -0.000994069383876203 0.999999400715121 -0.00418156126255702 3.88259770556834e-05 3.11784715193035e-05 -1.29373537858244e-05 1.20775054459142e-05 1.45287055207841e-05 2.82910917161891e-05 3.11784715193035e-05 3.56075245124495e-05 -1.29859117265772e-05 1.22847882393156e-05 1.11716323217191e-05 2.6442042340603e-05 -1.29373537858244e-05 -1.29859117265772e-05 1.61904221726094e-05 -3.45097144301681e-06 -6.7967398619729e-06 -5.99483948846733e-06 1.20775054459142e-05 1.22847882393156e-05 -3.45097144301681e-06 4.11540103250429e-05 -5.72611820201628e-06 7.49640736276547e-06 1.45287055207841e-05 1.11716323217191e-05 -6.7967398619729e-06 -5.72611820201628e-06 4.79415821714675e-05 1.21419433599031e-05 2.82910917161891e-05 2.6442042340603e-05 -5.99483948846733e-06 7.49640736276547e-06 1.21419433599031e-05 4.69064771262199e-05 2130 2133 0 15 13 2120 2151 0 43 6 0 0 0 0 0 17 49 0 622 0 62 70 0 0 2285 +384 427 0.999997601372014 0.000495177634188546 0.00213355321679516 0.00128222927999083 -0.000497103838350819 0.999999469299407 0.000902379453675301 0.00101542395552345 -0.00213310524639419 -0.000903437886696084 0.999997316827397 -0.00338118181527579 4.16384699899145e-05 2.72231528501466e-05 -1.07878089782743e-05 1.0826179202186e-05 4.46200657211186e-06 2.53967189053075e-05 2.72231528501466e-05 3.2993128523581e-05 -1.13362778711733e-05 9.61260578164234e-06 4.10346121639787e-06 2.90281909185432e-05 -1.07878089782743e-05 -1.13362778711733e-05 1.61735346139861e-05 -3.53690186207279e-06 -6.21935483979503e-06 -6.42820337298656e-06 1.0826179202186e-05 9.61260578164234e-06 -3.53690186207279e-06 3.94190947709992e-05 -3.18319583041667e-06 1.21551222637961e-05 4.46200657211186e-06 4.10346121639787e-06 -6.21935483979503e-06 -3.18319583041667e-06 4.69075641050832e-05 3.8228918266919e-06 2.53967189053075e-05 2.90281909185432e-05 -6.42820337298656e-06 1.21551222637961e-05 3.8228918266919e-06 5.11538372183326e-05 2804 2806 0 22 17 2795 2826 0 52 12 0 0 0 0 0 11 41 0 645 0 59 65 0 0 2362 +384 419 0.999995319630074 -5.69210629779042e-05 0.00305899949964031 0.00124457839326348 5.42001676302466e-05 0.999999602883406 0.000889547847429678 -0.00107152820121676 -0.00305904891886989 -0.000889377885731024 0.999994925600469 -0.00355139102701099 3.4251624808989e-05 2.21702368491175e-05 -8.74199402562129e-06 3.14174268927056e-06 9.13980174838065e-06 1.73462411683583e-05 2.21702368491175e-05 3.47361399734875e-05 -7.74882982433e-06 2.13613425283634e-06 5.22328417531287e-06 2.20416810873127e-05 -8.74199402562129e-06 -7.74882982433e-06 1.42388822416347e-05 1.57283908873563e-06 -5.12669452693012e-07 -1.88656438892613e-06 3.14174268927056e-06 2.13613425283634e-06 1.57283908873563e-06 4.69046348518907e-05 -7.56283445044936e-06 4.57854083403973e-06 9.13980174838065e-06 5.22328417531287e-06 -5.12669452693012e-07 -7.56283445044936e-06 3.61882315495333e-05 6.13383889564756e-06 1.73462411683583e-05 2.20416810873127e-05 -1.88656438892613e-06 4.57854083403973e-06 6.13383889564756e-06 4.54291228749055e-05 2143 2143 0 15 14 2150 2182 0 47 14 0 0 0 0 0 15 47 0 597 0 56 62 0 0 2335 +384 424 0.999999793058162 -0.000115189441057936 -0.000632941566379232 -0.00197624052621606 0.000115317536857166 0.999999972878384 0.000202348946779636 -0.0032484164544431 0.000632918240750755 -0.000202421894167582 0.999999779219914 -0.00112880745836724 2.79004948730004e-05 1.93962974499712e-05 -7.25396148714956e-06 5.40289205011662e-06 7.54924810561097e-06 1.84828590772882e-05 1.93962974499712e-05 2.74949016155643e-05 -8.06624258526971e-06 5.64933391100799e-06 6.00000882351686e-06 2.15151498529743e-05 -7.25396148714956e-06 -8.06624258526971e-06 1.19574579370013e-05 -3.75007779768281e-07 -8.36573646542129e-07 -3.079852942227e-06 5.40289205011662e-06 5.64933391100799e-06 -3.75007779768281e-07 3.40695505417382e-05 -4.22960071528511e-06 4.64019402642431e-06 7.54924810561097e-06 6.00000882351686e-06 -8.36573646542129e-07 -4.22960071528511e-06 4.19130309065716e-05 9.96345995800421e-06 1.84828590772882e-05 2.15151498529743e-05 -3.079852942227e-06 4.64019402642431e-06 9.96345995800421e-06 4.14422582718863e-05 2516 2513 0 15 15 2513 2543 0 46 14 0 0 0 0 0 11 42 0 632 0 40 54 0 0 2317 +384 386 0.999999968782282 -0.000223243058268168 -0.000112240690437735 0.00227953062622315 0.000223224843502322 0.999999961919649 -0.000162269433407339 -0.00287943927531082 0.000112276911688148 0.0001622443734311 0.999999980535329 0.00238672920403761 2.65429799615667e-05 1.77151716705945e-05 -8.13535920231343e-06 5.03673717166822e-06 8.93196443575827e-06 1.64987076722487e-05 1.77151716705945e-05 2.32858100110872e-05 -9.07410499465754e-06 6.59335539784083e-06 5.4424887326322e-06 1.38876466093256e-05 -8.13535920231343e-06 -9.07410499465754e-06 1.4501017465807e-05 -3.00431504166914e-06 -1.7349480188707e-06 -4.0706063656475e-06 5.03673717166822e-06 6.59335539784083e-06 -3.00431504166914e-06 2.7878476618107e-05 -1.67402691033296e-06 3.06116621597083e-07 8.93196443575827e-06 5.4424887326322e-06 -1.7349480188707e-06 -1.67402691033296e-06 3.19103590018347e-05 8.31967087865655e-06 1.64987076722487e-05 1.38876466093256e-05 -4.0706063656475e-06 3.06116621597083e-07 8.31967087865655e-06 2.9452726459339e-05 2539 2515 0 15 44 2509 2538 0 50 15 0 0 0 0 0 15 46 0 646 0 76 65 0 0 2765 +384 414 0.999998711059828 0.000611616830007111 0.0014845213150701 -0.00341708293282699 -0.000610864003675667 0.999999684635436 -0.000507517681743673 0.00527968031920396 -0.00148483125326037 0.000506610186949679 0.999998769310377 -0.00147115213042142 4.72330045180528e-05 2.67783740153057e-05 -8.2825809322168e-06 5.41660726680287e-06 6.93926897961019e-06 3.17266334808034e-05 2.67783740153057e-05 2.89671265844115e-05 -7.70376450489103e-06 5.65841318614689e-06 4.80486285233629e-06 2.91221362000653e-05 -8.2825809322168e-06 -7.70376450489103e-06 1.11853000172564e-05 1.67163575513256e-06 -1.41073847725955e-06 -3.6406992064319e-06 5.41660726680287e-06 5.65841318614689e-06 1.67163575513256e-06 2.57466276451115e-05 -1.40382637559508e-06 7.87172661349626e-06 6.93926897961019e-06 4.80486285233629e-06 -1.41073847725955e-06 -1.40382637559508e-06 3.38570922959656e-05 3.1137335917115e-06 3.17266334808034e-05 2.91221362000653e-05 -3.6406992064319e-06 7.87172661349626e-06 3.1137335917115e-06 5.44898613133356e-05 3091 3089 0 16 11 3088 3133 0 48 9 0 0 0 0 0 16 47 0 609 0 11 15 0 0 2461 +384 425 0.999998789448271 0.000789212462259062 0.00134098683174556 -0.00521054159546478 -0.000790121358267386 0.999999458427453 0.000677386921218404 -0.00138467113712895 -0.00134045150330391 -0.000678445643543412 0.999998871450001 0.00135093667132026 5.63442181114461e-05 2.09215238573669e-05 -1.06926540120319e-05 3.86348628433806e-06 5.25325686466708e-06 2.24968632510849e-05 2.09215238573669e-05 5.1098837467349e-05 -1.3284996157436e-05 4.24423357725478e-06 1.719741199877e-05 3.24085756969851e-05 -1.06926540120319e-05 -1.3284996157436e-05 1.76431060111112e-05 -3.69114092529679e-07 -5.05317392360264e-06 -6.7725495244023e-06 3.86348628433806e-06 4.24423357725478e-06 -3.69114092529679e-07 4.24118307168124e-05 -1.20616745139944e-05 -6.52629576011398e-06 5.25325686466708e-06 1.719741199877e-05 -5.05317392360264e-06 -1.20616745139944e-05 6.22326395654697e-05 1.736189794875e-05 2.24968632510849e-05 3.24085756969851e-05 -6.7725495244023e-06 -6.52629576011398e-06 1.736189794875e-05 5.87905698157195e-05 1864 1867 0 23 16 1863 1893 0 49 16 0 0 0 0 0 11 41 0 629 0 39 52 0 0 2027 +384 421 0.999999786351213 0.000295196951571688 0.000583229190705331 -0.00511089648648452 -0.000294901648516488 0.999999828323693 -0.000506345338956479 0.00378126776735431 -0.0005833785621792 0.00050617323552661 0.99999970172901 0.000204490016292675 3.15827239837792e-05 1.99170759277197e-05 -7.06868361549666e-06 1.19419737915066e-05 1.35026567752321e-06 1.38883756748395e-05 1.99170759277197e-05 3.62676373698802e-05 -8.19865619132371e-06 1.17514219383718e-05 6.13856324363789e-06 2.77807105932428e-05 -7.06868361549666e-06 -8.19865619132371e-06 1.40001932345607e-05 -2.92747853200933e-06 -4.35777806189207e-06 -8.44239089582451e-07 1.19419737915066e-05 1.17514219383718e-05 -2.92747853200933e-06 4.09753412202222e-05 -4.69695992308566e-06 2.7189781811585e-07 1.35026567752321e-06 6.13856324363789e-06 -4.35777806189207e-06 -4.69695992308566e-06 4.77958058013832e-05 4.35525521687127e-06 1.38883756748395e-05 2.77807105932428e-05 -8.44239089582451e-07 2.7189781811585e-07 4.35525521687127e-06 5.28459455634977e-05 2084 2082 0 16 14 2075 2109 0 54 11 0 0 0 0 0 17 49 0 628 0 60 69 0 0 2394 +384 412 0.999984565817575 7.79759508711939e-06 0.00555590369182981 0.00157259918612768 2.99809013382156e-06 0.999998112193188 -0.00194309059809535 -0.00110616540155578 -0.00555590835479067 0.00194307726518064 0.999982678016522 0.0013534549336372 9.55459463692313e-05 7.43787748161318e-05 -9.62510626331433e-06 3.20282319801764e-05 -1.20258150998674e-05 6.54518779607398e-05 7.43787748161318e-05 9.7076956571538e-05 -1.24664427411636e-05 3.81436631062975e-05 -5.40714792349398e-06 6.68805417475595e-05 -9.62510626331433e-06 -1.24664427411636e-05 1.45567442097333e-05 -8.36263134940909e-07 -1.68262314855475e-06 -8.89321781409815e-06 3.20282319801764e-05 3.81436631062975e-05 -8.36263134940909e-07 5.11987396790693e-05 -1.67989995759569e-05 2.47360497330495e-05 -1.20258150998674e-05 -5.40714792349398e-06 -1.68262314855475e-06 -1.67989995759569e-05 4.94710962591306e-05 -5.89735449465212e-06 6.54518779607398e-05 6.68805417475595e-05 -8.89321781409815e-06 2.47360497330495e-05 -5.89735449465212e-06 7.58232693085521e-05 1435 1431 0 11 9 1434 1461 0 49 5 0 0 0 0 0 13 44 0 570 0 53 63 0 0 2266 +384 422 0.999999837240818 0.000265369105204154 0.00050507185157626 -0.00289348516609826 -0.000265700607996568 0.999999749275087 0.000656393898832131 0.00345073749960794 -0.000504897538280569 -0.000656527989896043 0.999999657024678 -0.00550165184399654 3.74641837667025e-05 1.54994050964795e-05 -6.88247748707761e-06 8.25817695574278e-06 6.45771158842768e-06 2.13406667174485e-05 1.54994050964795e-05 2.46886747462679e-05 -7.42167003134896e-06 7.20525166551254e-06 7.89407065010292e-06 2.04554514507979e-05 -6.88247748707761e-06 -7.42167003134896e-06 1.14038559588798e-05 -2.65424894644778e-06 -6.62165594639055e-07 -2.58754187056941e-06 8.25817695574278e-06 7.20525166551254e-06 -2.65424894644778e-06 3.09927925419224e-05 3.58326105252361e-06 5.95056262134776e-06 6.45771158842768e-06 7.89407065010292e-06 -6.62165594639055e-07 3.58326105252361e-06 3.34003003970368e-05 4.73477574288523e-06 2.13406667174485e-05 2.04554514507979e-05 -2.58754187056941e-06 5.95056262134776e-06 4.73477574288523e-06 5.1607633367482e-05 2613 2616 0 24 14 2608 2654 0 55 11 0 0 0 0 0 20 54 0 605 0 16 19 0 0 2390 +384 388 0.999990700856107 -5.55894484452496e-05 0.00431220490295756 0.00832901368376882 5.12360577481205e-05 0.99999948898581 0.00100965488412194 -0.00747530538097345 -0.00431225882551779 -0.00100942455481646 0.999990192694853 -0.00317882845875983 2.9669265539895e-05 2.48188538055826e-05 6.3581719565993e-07 2.97780950777349e-06 -2.34488569050042e-06 2.25128348037575e-05 2.48188538055826e-05 3.94579944726918e-05 4.22279202673228e-07 6.12554805211212e-06 -7.508416647269e-06 2.8962100949907e-05 6.3581719565993e-07 4.22279202673228e-07 9.84097019265194e-06 2.12975699637707e-06 4.45709925711857e-06 1.4155704809459e-06 2.97780950777349e-06 6.12554805211212e-06 2.12975699637707e-06 2.80632880334906e-05 -7.28580552140948e-06 3.9151097103803e-06 -2.34488569050042e-06 -7.508416647269e-06 4.45709925711857e-06 -7.28580552140948e-06 2.35391875602824e-05 -5.07515363289103e-06 2.25128348037575e-05 2.8962100949907e-05 1.4155704809459e-06 3.9151097103803e-06 -5.07515363289103e-06 4.35855134706145e-05 2126 2103 0 18 54 2104 2136 0 50 28 0 0 0 0 0 17 49 0 660 0 98 81 0 0 2667 +384 420 0.999999632385767 0.000423850585189166 -0.000745371727889732 -0.00522234123218826 -0.000424047522305102 0.999999875224011 -0.000264075103793304 0.00399619819236857 0.000745259706497961 0.000264391079749945 0.999999687342615 -0.00552472333413983 4.58116847705525e-05 3.40878551833496e-05 -1.23029322150657e-05 1.29205942384292e-05 1.06422814889293e-05 2.42725345149579e-05 3.40878551833496e-05 4.39378509662332e-05 -1.28206665791956e-05 1.49475820130933e-05 1.20892076515708e-05 3.68275581450285e-05 -1.23029322150657e-05 -1.28206665791956e-05 1.66675484800428e-05 -4.36832413758263e-06 -7.95554875651721e-06 -6.84596103100899e-06 1.29205942384292e-05 1.49475820130933e-05 -4.36832413758263e-06 4.27335578618952e-05 -6.25272517334457e-06 8.71070928653923e-06 1.06422814889293e-05 1.20892076515708e-05 -7.95554875651721e-06 -6.25272517334457e-06 5.11760010691881e-05 7.99972680552276e-06 2.42725345149579e-05 3.68275581450285e-05 -6.84596103100899e-06 8.71070928653923e-06 7.99972680552276e-06 5.57695158755514e-05 2032 2034 0 15 11 2023 2049 0 42 4 0 0 0 0 0 17 47 0 624 0 60 70 0 0 2262 +384 411 0.999999854102137 0.000139959661858422 0.000521734605348662 -0.00116347437878046 -0.000141719789677582 0.999994294296356 0.00337509855172692 0.00154137040328818 -0.000521259250833584 -0.00337517199942579 0.999994168234379 -0.00271224644280151 4.45989038046825e-05 2.58419121430285e-05 -5.04071076413542e-06 8.29802445767798e-06 -2.79001081218063e-06 2.42242978996078e-05 2.58419121430285e-05 3.06809697759287e-05 -5.66312249278831e-06 9.69364475863713e-06 1.19287902924918e-06 2.80275229746132e-05 -5.04071076413542e-06 -5.66312249278831e-06 1.36370095061076e-05 1.69138478837383e-06 -1.12959349569703e-06 -2.04799924857921e-06 8.29802445767798e-06 9.69364475863713e-06 1.69138478837383e-06 3.68164409818952e-05 -1.2713511173574e-05 8.93595236717262e-06 -2.79001081218063e-06 1.19287902924918e-06 -1.12959349569703e-06 -1.2713511173574e-05 4.54434324373078e-05 -2.00956230758151e-06 2.42242978996078e-05 2.80275229746132e-05 -2.04799924857921e-06 8.93595236717262e-06 -2.00956230758151e-06 4.51651535936715e-05 2105 2103 0 17 11 2092 2128 0 53 4 0 0 0 0 0 20 52 0 544 0 55 63 0 0 2267 +384 423 0.99999937509534 0.000484901216168241 -0.00100731312911247 -0.00934176766554303 -0.00048428131897331 0.999999693285158 0.000615549505177419 0.00768720852929484 0.00100761130085826 -0.000615061297586879 0.999999303209291 -0.00516683358399611 3.26605041712101e-05 2.34448897225588e-05 -1.08347883938852e-05 7.18981656651959e-06 1.31359539187861e-05 2.2658694486387e-05 2.34448897225588e-05 3.37369241972441e-05 -1.14898903213075e-05 1.21877686363526e-05 1.05774389686522e-05 2.42349409468763e-05 -1.08347883938852e-05 -1.14898903213075e-05 1.55308340393234e-05 -3.33007089523703e-06 -2.92273799566898e-06 -4.91048938014457e-06 7.18981656651959e-06 1.21877686363526e-05 -3.33007089523703e-06 4.04323189696175e-05 -3.514556174854e-06 4.37755183350464e-06 1.31359539187861e-05 1.05774389686522e-05 -2.92273799566898e-06 -3.514556174854e-06 4.27480241437393e-05 9.96010373633575e-06 2.2658694486387e-05 2.42349409468763e-05 -4.91048938014457e-06 4.37755183350464e-06 9.96010373633575e-06 4.45245623856726e-05 1470 1468 0 11 12 1459 1492 0 47 4 0 0 0 0 0 18 48 0 625 0 58 67 0 0 2322 +384 429 0.999974452644056 -0.00711676790424144 -0.000667588060511831 -0.00234215333767766 0.00711981627992563 0.99996369860577 0.00468077844047254 0.00432502948904485 0.000634251812362443 -0.00468541196330114 0.999988822257215 -0.00389329144645983 5.17366267255533e-05 3.72512879878298e-05 -7.45977482082794e-06 6.55099187037562e-06 3.14684655595109e-06 3.74666911494844e-05 3.72512879878298e-05 5.0055678542005e-05 -1.02539521185106e-05 9.77961729338627e-06 4.88681340819724e-06 3.52178705162586e-05 -7.45977482082794e-06 -1.02539521185106e-05 1.63575616777221e-05 -1.3998255471106e-06 -3.91271981435425e-06 -1.92735950522294e-06 6.55099187037562e-06 9.77961729338627e-06 -1.3998255471106e-06 4.0528365256656e-05 -3.71375831586633e-06 -8.06722387181351e-07 3.14684655595109e-06 4.88681340819724e-06 -3.91271981435425e-06 -3.71375831586633e-06 4.24857375919337e-05 2.54458616455731e-06 3.74666911494844e-05 3.52178705162586e-05 -1.92735950522294e-06 -8.06722387181351e-07 2.54458616455731e-06 6.81780967511155e-05 1495 1492 0 6 24 1485 1509 0 40 11 0 0 0 0 0 24 56 0 615 0 60 68 0 0 2422 +385 387 0.999999271596785 6.90591710456851e-05 -0.00120500486748433 -0.00143586583564085 -6.82140802257973e-05 0.999999751731436 0.000701344355385328 0.00520433117763788 0.0012050530025793 -0.000701261646225141 0.99999902803921 0.00654040846215753 2.32866886614102e-05 1.56340280161809e-05 -7.40385958917227e-06 2.96122846797896e-06 4.48834757053898e-06 7.40632702409701e-06 1.56340280161809e-05 2.4722367909281e-05 -9.01638704282341e-06 5.64730381728774e-06 4.40412583358197e-06 1.45324567249374e-05 -7.40385958917227e-06 -9.01638704282341e-06 1.31124189332103e-05 -3.14741937937947e-06 -2.32138649668986e-06 -2.5618362470477e-06 2.96122846797896e-06 5.64730381728774e-06 -3.14741937937947e-06 2.56430094774302e-05 4.31027794220577e-06 -9.83957035748181e-07 4.48834757053898e-06 4.40412583358197e-06 -2.32138649668986e-06 4.31027794220577e-06 3.26686946589841e-05 2.09905510224897e-06 7.40632702409701e-06 1.45324567249374e-05 -2.5618362470477e-06 -9.83957035748181e-07 2.09905510224897e-06 3.54567283687916e-05 2181 2159 0 19 56 2158 2181 0 34 28 0 0 0 0 0 21 51 0 641 0 94 85 0 0 2745 +385 414 0.999994108510117 0.000728845495872001 -0.00335435974498082 -0.00796098423593316 -0.000732542783439977 0.99999912543894 -0.00110113687865304 0.00994251152119573 0.00335355425273407 0.00110358760334051 0.999993767864718 0.0044170738460881 6.03398111894011e-05 4.63817607714262e-05 -7.77526072178744e-06 1.94370880151742e-05 -3.28597305111767e-06 4.77865096108935e-05 4.63817607714262e-05 5.51267114002006e-05 -9.55155314419155e-06 2.28492505898764e-05 -3.39815611786643e-06 4.39090844413259e-05 -7.77526072178744e-06 -9.55155314419155e-06 1.26323757113535e-05 -1.74303171662947e-06 -6.81766780149873e-07 -4.86788059687117e-06 1.94370880151742e-05 2.28492505898764e-05 -1.74303171662947e-06 4.27761619068563e-05 -1.11977927493613e-05 1.19738990974851e-05 -3.28597305111767e-06 -3.39815611786643e-06 -6.81766780149873e-07 -1.11977927493613e-05 4.41211154328371e-05 -1.28518274867439e-06 4.77865096108935e-05 4.39090844413259e-05 -4.86788059687117e-06 1.19738990974851e-05 -1.28518274867439e-06 7.35416878186543e-05 2622 2621 0 11 11 2629 2668 0 52 11 0 0 0 0 0 23 54 0 600 0 50 60 0 0 2388 +384 410 0.999999710061771 0.000223119484758289 -0.00072807559293389 -0.00226857748207081 -0.000223171580377083 0.999999972543097 -7.14720277625954e-05 0.000930129491963024 0.00072805962614118 7.16344928208313e-05 0.999999732398804 0.00081546003769928 3.51614695038768e-05 2.41608813209703e-05 -2.31204706588836e-06 1.60286974216444e-06 1.25537420427289e-06 2.23589385419272e-05 2.41608813209703e-05 3.34170332004937e-05 -2.85163472958735e-06 3.60792248781147e-06 2.09152490238186e-06 2.94074254755469e-05 -2.31204706588836e-06 -2.85163472958735e-06 1.16639030749619e-05 1.78536299671647e-06 2.94805915812854e-06 -5.88486269366161e-07 1.60286974216444e-06 3.60792248781147e-06 1.78536299671647e-06 3.27017852574507e-05 -1.08236327273343e-05 -4.34940271078601e-06 1.25537420427289e-06 2.09152490238186e-06 2.94805915812854e-06 -1.08236327273343e-05 3.47087583708177e-05 6.92769459949103e-06 2.23589385419272e-05 2.94074254755469e-05 -5.88486269366161e-07 -4.34940271078601e-06 6.92769459949103e-06 4.95225598681864e-05 2470 2467 0 17 9 2461 2489 0 51 6 0 0 0 0 0 22 51 0 517 0 31 43 0 0 2266 +385 415 0.999998559375999 0.000111012326263534 -0.0016937892991957 -0.00463790531004393 -0.000110735146173446 0.999999980463819 0.000163737868206385 0.00219196977760184 0.00169380744302717 -0.000163550070316048 0.999998552132812 -0.00376168349621941 3.53007622062725e-05 2.49902321343301e-05 -8.95259879177676e-06 9.12186750738135e-06 8.93875304243822e-06 3.52654001593227e-05 2.49902321343301e-05 2.78747241357957e-05 -9.10737623867536e-06 8.22692652591722e-06 5.84481145833932e-06 3.32822895766822e-05 -8.95259879177676e-06 -9.10737623867536e-06 1.18696025220441e-05 -6.602149820214e-07 -3.43540926668308e-06 -5.02975392439019e-06 9.12186750738135e-06 8.22692652591722e-06 -6.602149820214e-07 2.8118179612343e-05 -1.97196789633412e-06 1.36108592960372e-05 8.93875304243822e-06 5.84481145833932e-06 -3.43540926668308e-06 -1.97196789633412e-06 3.58661298667253e-05 5.45215248353434e-06 3.52654001593227e-05 3.32822895766822e-05 -5.02975392439019e-06 1.36108592960372e-05 5.45215248353434e-06 6.89771998248193e-05 2507 2515 0 22 14 2509 2548 0 40 12 0 0 0 0 0 18 49 0 579 0 16 20 0 0 2290 +384 428 0.999997503387639 -0.000404716740730719 0.00219759478729508 0.00305688105621311 0.000398018549847015 0.999995277008512 0.00304754686657099 -0.00104192974717151 -0.00219881780130867 -0.00304666457453742 0.999992941492712 -0.00558354081501548 2.78145222551102e-05 1.85377135215645e-05 -8.46719045587621e-06 7.69820733195297e-06 2.48795443284516e-06 1.5139497446657e-05 1.85377135215645e-05 3.03025035906476e-05 -9.39483227077948e-06 7.96147983301085e-06 2.81732994879757e-06 1.88329755605051e-05 -8.46719045587621e-06 -9.39483227077948e-06 1.54862017065629e-05 -2.05020908685356e-06 -6.35911720459376e-06 -2.24780146547948e-06 7.69820733195297e-06 7.96147983301085e-06 -2.05020908685356e-06 3.73060817584459e-05 -1.85010553621854e-06 8.64876917527562e-06 2.48795443284516e-06 2.81732994879757e-06 -6.35911720459376e-06 -1.85010553621854e-06 4.53311962772629e-05 -1.18956838806489e-06 1.5139497446657e-05 1.88329755605051e-05 -2.24780146547948e-06 8.64876917527562e-06 -1.18956838806489e-06 4.5646051611598e-05 2721 2716 0 11 16 2726 2760 0 47 16 0 0 0 0 0 13 46 0 643 0 56 63 0 0 2322 +385 388 0.999999272185735 -0.000169511945734515 0.00119452655943986 0.00179438462866698 0.000169494304546238 0.999999985525288 1.48695689291914e-05 -0.00125844666364285 -0.001194529062719 -1.46670926584527e-05 0.999999286442343 0.00154085216234715 2.11193166095507e-05 1.74492007510877e-05 4.99038488844764e-07 1.841046067125e-06 -1.2944687948957e-07 1.98692068302487e-05 1.74492007510877e-05 2.28868507826927e-05 -2.73785022985945e-08 2.34431945394411e-07 -2.27365439728428e-06 2.49557724072201e-05 4.99038488844764e-07 -2.73785022985945e-08 9.00133470392206e-06 3.25780456989916e-06 3.57539145748305e-06 1.60966072493512e-06 1.841046067125e-06 2.34431945394411e-07 3.25780456989916e-06 1.92735926639015e-05 -1.72036350870327e-07 4.41323173664674e-06 -1.2944687948957e-07 -2.27365439728428e-06 3.57539145748305e-06 -1.72036350870327e-07 1.99163220235531e-05 -3.75938465805526e-06 1.98692068302487e-05 2.49557724072201e-05 1.60966072493512e-06 4.41323173664674e-06 -3.75938465805526e-06 4.33869880438978e-05 3359 3334 0 13 58 3336 3390 0 48 32 0 0 0 0 0 20 52 0 672 0 55 31 0 0 2737 +385 416 0.999988437601838 0.00121990104352482 -0.00465150557116873 -0.0119814816203671 -0.00123061040023726 0.999996597389765 -0.00230017541397874 0.0107427844657918 0.00464868375752046 0.0023058730095674 0.999986536253857 0.00483704921488819 2.82197858060318e-05 2.01436739770825e-05 -9.61011766356112e-06 4.74872227070495e-06 9.92263235752019e-06 1.79804353656222e-05 2.01436739770825e-05 3.09647284255047e-05 -1.06476360486061e-05 1.20728360152058e-05 2.91620192912397e-06 2.10739255950201e-05 -9.61011766356112e-06 -1.06476360486061e-05 1.4498592835084e-05 -6.99503136870993e-07 -2.29164886826531e-06 -5.09431075472445e-06 4.74872227070495e-06 1.20728360152058e-05 -6.99503136870993e-07 3.67781963792446e-05 -8.40665915390233e-06 -1.31031873112019e-07 9.92263235752019e-06 2.91620192912397e-06 -2.29164886826531e-06 -8.40665915390233e-06 3.90105310676396e-05 7.9466908384941e-06 1.79804353656222e-05 2.10739255950201e-05 -5.09431075472445e-06 -1.31031873112019e-07 7.9466908384941e-06 4.32776549795726e-05 2665 2668 0 22 12 2654 2683 0 44 5 0 0 0 0 0 23 55 0 620 0 55 67 0 0 2236 +385 413 0.999994021399258 -6.47480142503002e-07 -0.00345791343462385 -0.00451144898817448 -1.01276724557286e-05 0.99999514500109 -0.00311606670008449 -0.00184187481149783 0.00345789866404921 0.00311608309098045 0.999989166422816 -0.00198059776132145 4.75006492858564e-05 2.15982268176709e-05 -8.48852758709152e-06 6.89612543114686e-06 5.27895607377648e-06 2.06563973753393e-05 2.15982268176709e-05 4.20876578834423e-05 -1.19331528404942e-05 1.44168458760443e-05 1.56597122134357e-05 3.23805951016329e-05 -8.48852758709152e-06 -1.19331528404942e-05 1.65319939487262e-05 -8.1252821598458e-07 -6.58000325322403e-06 -8.28531262955581e-06 6.89612543114686e-06 1.44168458760443e-05 -8.1252821598458e-07 3.31100552320805e-05 2.28613068398994e-06 1.1116455286844e-05 5.27895607377648e-06 1.56597122134357e-05 -6.58000325322403e-06 2.28613068398994e-06 4.62554088324951e-05 1.08371788745621e-05 2.06563973753393e-05 3.23805951016329e-05 -8.28531262955581e-06 1.1116455286844e-05 1.08371788745621e-05 4.64021038463873e-05 1507 1508 0 21 11 1498 1525 0 45 10 0 0 0 0 0 24 57 0 610 0 68 78 0 0 2251 +385 417 0.999999170866341 0.000243861915038266 -0.00126443584146092 -0.00763922514048224 -0.000242976038039495 0.999999724979293 0.000700716764151982 0.00688448027343367 0.00126460637184689 -0.000700408955553014 0.999998955098464 -0.000712384454136326 2.63188573947203e-05 2.12801840598675e-05 -8.77048708725331e-06 6.28429646795106e-06 1.01546299318752e-05 1.63334119488792e-05 2.12801840598675e-05 2.95258166180578e-05 -1.06414310785786e-05 9.27845406328455e-06 1.04198726303239e-05 2.47639998896669e-05 -8.77048708725331e-06 -1.06414310785786e-05 1.43374347748209e-05 -7.6359065806115e-07 -4.24245822733051e-06 -4.58004925448404e-06 6.28429646795106e-06 9.27845406328455e-06 -7.6359065806115e-07 3.37292852775695e-05 2.96343742380316e-06 9.47048782065846e-06 1.01546299318752e-05 1.04198726303239e-05 -4.24245822733051e-06 2.96343742380316e-06 4.96197656292454e-05 9.08476128294087e-06 1.63334119488792e-05 2.47639998896669e-05 -4.58004925448404e-06 9.47048782065846e-06 9.08476128294087e-06 4.33786517149778e-05 2776 2772 0 11 13 2777 2812 0 44 10 0 0 0 0 0 28 62 0 611 0 53 64 0 0 2340 +385 412 0.999999869620879 -0.000102874621078476 0.000500175006180302 0.000900923937872758 0.000102487877189433 0.99999969584341 0.000773181299644849 -0.000706448419868603 -0.000500254394782004 -0.000773129936963545 0.999999576007731 -0.0065893826347341 3.53886336741178e-05 2.48798370248106e-05 -4.19201958326404e-06 1.01024222416193e-05 2.12522423248787e-06 2.58295606637196e-05 2.48798370248106e-05 3.59005629049094e-05 -6.40058771860944e-06 1.11347434469826e-05 3.36027452467384e-06 3.48589405418787e-05 -4.19201958326404e-06 -6.40058771860944e-06 1.08474515700256e-05 2.47391575383547e-06 5.31917954933374e-07 -3.35381689886396e-06 1.01024222416193e-05 1.11347434469826e-05 2.47391575383547e-06 3.03013938669121e-05 -3.64304191780856e-06 1.25250238585858e-05 2.12522423248787e-06 3.36027452467384e-06 5.31917954933374e-07 -3.64304191780856e-06 3.52110334184165e-05 2.39521243810379e-06 2.58295606637196e-05 3.48589405418787e-05 -3.35381689886396e-06 1.25250238585858e-05 2.39521243810379e-06 5.20010280611438e-05 2868 2869 0 20 9 2861 2892 0 44 6 0 0 0 0 0 18 49 0 568 0 12 14 0 0 2320 +385 420 0.99999547295189 0.00032681178550936 0.00299119872012994 0.00315325141507513 -0.000334075915464678 0.999996995813615 0.00242832391315583 0.000774198494356833 -0.00299039612913762 -0.00242931220746741 0.999992577959051 -0.00770929802420341 3.05450410433315e-05 1.58931624507011e-05 -9.25936169598041e-06 9.80136401384536e-06 1.01772214058563e-05 1.23860089573475e-05 1.58931624507011e-05 3.12920823861321e-05 -1.08709227689514e-05 1.15175204712317e-05 1.43401731363625e-05 2.45329029953346e-05 -9.25936169598041e-06 -1.08709227689514e-05 1.34136983168982e-05 -3.49883514013888e-06 -4.4388758827198e-06 -4.68067198464991e-06 9.80136401384536e-06 1.15175204712317e-05 -3.49883514013888e-06 3.43654980392258e-05 2.77947562365328e-06 6.50370738220551e-06 1.01772214058563e-05 1.43401731363625e-05 -4.4388758827198e-06 2.77947562365328e-06 4.63183530665244e-05 1.0673714616251e-05 1.23860089573475e-05 2.45329029953346e-05 -4.68067198464991e-06 6.50370738220551e-06 1.0673714616251e-05 4.95967055807888e-05 2052 2049 0 15 11 2048 2068 0 38 9 0 0 0 0 0 16 47 0 630 0 13 18 0 0 2363 +385 418 0.999999069498225 0.000197795873328576 0.0013497701571655 -0.00252560618997335 -0.000200579424157509 0.999997853099825 0.00206241694012832 0.00528823967654964 -0.00134935932178388 -0.00206268575716657 0.99999696227383 -0.00939386482573605 4.00424569286638e-05 2.98726806703977e-05 -8.76982179787059e-06 8.87377351828399e-06 4.06845827094225e-06 3.07866540546051e-05 2.98726806703977e-05 3.89916620446818e-05 -9.35104585302252e-06 1.3713206933546e-05 3.22632163775239e-06 3.39131575976437e-05 -8.76982179787059e-06 -9.35104585302252e-06 1.38820091072245e-05 -5.93376560632412e-07 -1.87960168247174e-06 -3.31224488678786e-06 8.87377351828399e-06 1.3713206933546e-05 -5.93376560632412e-07 3.97216923693995e-05 -9.71174345524403e-06 1.48546430047591e-05 4.06845827094225e-06 3.22632163775239e-06 -1.87960168247174e-06 -9.71174345524403e-06 4.88900909207685e-05 -2.02278274292263e-06 3.07866540546051e-05 3.39131575976437e-05 -3.31224488678786e-06 1.48546430047591e-05 -2.02278274292263e-06 5.61631056712684e-05 2683 2682 0 15 13 2675 2704 0 44 11 0 0 0 0 0 17 49 0 621 0 15 20 0 0 2189 +385 427 0.999999810045383 0.000464633183673077 0.000405000250979198 -0.00295507031097589 -0.00046467360170576 0.999999887068257 9.97091669073713e-05 0.00618157080665346 -0.000404953877054152 -9.98973408924689e-05 0.999999913016436 -0.00310871971998141 2.56530896726121e-05 1.54656448607033e-05 -1.0672582300962e-05 7.66423745639683e-06 1.21516514145983e-05 1.68494658975391e-05 1.54656448607033e-05 2.17504416210323e-05 -1.00347441192112e-05 8.77062171039413e-06 8.44903769349655e-06 1.83892751722975e-05 -1.0672582300962e-05 -1.00347441192112e-05 1.29333598195209e-05 -3.33607768962134e-06 -4.79661192411122e-06 -5.39285786135168e-06 7.66423745639683e-06 8.77062171039413e-06 -3.33607768962134e-06 3.12304774569519e-05 9.39046667280514e-06 1.40064408687639e-05 1.21516514145983e-05 8.44903769349655e-06 -4.79661192411122e-06 9.39046667280514e-06 4.05266072767109e-05 1.05869359469813e-05 1.68494658975391e-05 1.83892751722975e-05 -5.39285786135168e-06 1.40064408687639e-05 1.05869359469813e-05 4.49163495224398e-05 2467 2468 0 17 17 2460 2497 0 36 14 0 0 0 0 0 28 58 0 673 0 19 21 0 0 2442 +385 411 0.999996297098962 0.000518795218854494 0.00267144902366959 0.00061056759156608 -0.000523070700114609 0.999998583220899 0.00159998538674279 0.00363064078435653 -0.00267061517404756 -0.00160137681886637 0.999995151691685 -0.00414299909042305 5.40094033043521e-05 3.77916717866451e-05 -4.53424599507033e-06 9.44777048183914e-06 -1.07802153148259e-06 3.38317763759244e-05 3.77916717866451e-05 5.3541396020779e-05 -5.19250856992227e-06 1.60344782699026e-05 -4.29825747781189e-06 4.20487657669882e-05 -4.53424599507033e-06 -5.19250856992227e-06 1.17421766059917e-05 1.80477899233747e-06 2.90438532142315e-06 -9.81997753291826e-07 9.44777048183914e-06 1.60344782699026e-05 1.80477899233747e-06 3.27827193711114e-05 -5.06212026010903e-06 1.31320525815418e-05 -1.07802153148259e-06 -4.29825747781189e-06 2.90438532142315e-06 -5.06212026010903e-06 3.87705948130681e-05 -2.76070607565537e-08 3.38317763759244e-05 4.20487657669882e-05 -9.81997753291826e-07 1.31320525815418e-05 -2.76070607565537e-08 5.89754278805374e-05 2078 2076 0 14 11 2075 2105 0 46 9 0 0 0 0 0 16 48 0 546 0 12 16 0 0 2253 +385 389 0.999998622163564 0.000259669115593267 0.00163958620503019 0.00454015205929751 -0.000261522072582345 0.999999327326056 0.00113002373489228 -0.00256131260391497 -0.00163929166985943 -0.00113045096588692 0.999998017399752 -0.00466968439611501 3.9397540738783e-05 1.27447470210933e-05 -7.42815900633445e-07 2.06805959976037e-06 -4.18138348124852e-06 1.23725388241042e-05 1.27447470210933e-05 2.87403143914517e-05 -1.21486361314834e-06 6.78847750929877e-06 -1.48817171723571e-06 1.97494566962901e-05 -7.42815900633445e-07 -1.21486361314834e-06 9.24703821452473e-06 4.57508974724731e-06 3.86415039163213e-06 1.96531500609218e-06 2.06805959976037e-06 6.78847750929877e-06 4.57508974724731e-06 2.671105708311e-05 -5.09175578417992e-06 7.17148895360393e-06 -4.18138348124852e-06 -1.48817171723571e-06 3.86415039163213e-06 -5.09175578417992e-06 2.78391772475607e-05 -3.19518011512028e-06 1.23725388241042e-05 1.97494566962901e-05 1.96531500609218e-06 7.17148895360393e-06 -3.19518011512028e-06 3.61393809795108e-05 2889 2867 0 20 54 2860 2886 0 45 26 0 0 0 0 0 18 50 0 498 0 53 30 0 0 2651 +385 419 0.999999407927433 0.000763135040601471 -0.000775738159679595 -0.00339715111300766 -0.000763390678889748 0.999999654398256 -0.00032929931731751 0.00432017147927119 0.000775486591735243 0.000329891313628777 0.999999644896071 -0.00333779805722345 2.54405457967063e-05 1.85305646562358e-05 -8.52084137627564e-06 7.26770155676631e-06 1.00579331403213e-05 1.95657527175101e-05 1.85305646562358e-05 2.54765019775947e-05 -8.87448031935288e-06 5.17971436156518e-06 7.48580057621039e-06 2.58756176026326e-05 -8.52084137627564e-06 -8.87448031935288e-06 1.40177281856966e-05 -1.55845468529344e-06 -2.22949028300511e-06 -3.7585200201845e-06 7.26770155676631e-06 5.17971436156518e-06 -1.55845468529344e-06 2.59305847834904e-05 5.01634787125018e-06 9.02296313332486e-06 1.00579331403213e-05 7.48580057621039e-06 -2.22949028300511e-06 5.01634787125018e-06 3.20649556724941e-05 1.06916901293872e-05 1.95657527175101e-05 2.58756176026326e-05 -3.7585200201845e-06 9.02296313332486e-06 1.06916901293872e-05 5.4452681457383e-05 3316 3311 0 15 14 3305 3355 0 43 10 0 0 0 0 0 16 48 0 603 0 15 18 0 0 2248 +385 421 0.999997517204961 0.000485137375692487 0.00217490819142827 0.00110783806267574 -0.000488446524488284 0.999998723625038 0.00152123906352869 0.00386371817416786 -0.00217416740550283 -0.00152229761295108 0.999996477796832 -0.00571616118377784 3.79093603789057e-05 2.51733707631121e-05 -1.01149512969683e-05 8.98364534407728e-06 7.84866968146142e-06 2.26499926874517e-05 2.51733707631121e-05 3.23483642640436e-05 -1.07488484170818e-05 9.54792453041835e-06 6.25200086495114e-06 2.87326931416865e-05 -1.01149512969683e-05 -1.07488484170818e-05 1.39816127367721e-05 -2.38156720449477e-06 -3.33887781456601e-06 -4.79541949017698e-06 8.98364534407728e-06 9.54792453041835e-06 -2.38156720449477e-06 3.23272617957031e-05 1.09881259901678e-06 9.75853290035413e-06 7.84866968146142e-06 6.25200086495114e-06 -3.33887781456601e-06 1.09881259901678e-06 3.79769020788849e-05 1.52527368344411e-06 2.26499926874517e-05 2.87326931416865e-05 -4.79541949017698e-06 9.75853290035413e-06 1.52527368344411e-06 5.17146555872257e-05 2703 2700 0 16 14 2696 2733 0 52 10 0 0 0 0 0 16 49 0 620 0 15 18 0 0 2310 +385 424 0.999999208808157 0.00080082269243726 -0.000970085602516339 -0.00653270379965761 -0.000802088289687559 0.999998826894197 -0.00130493854465054 0.00486364273611096 0.000969039440104497 0.00130571560649558 0.999998678033786 -1.01698683309826e-05 3.64288124045256e-05 2.04471726388832e-05 -1.21774474322659e-05 2.27661379411061e-06 9.87824726830963e-06 1.64402013639457e-05 2.04471726388832e-05 2.87263365414873e-05 -1.30942788867451e-05 5.51405254919569e-06 1.25255617362845e-05 2.17984209719382e-05 -1.21774474322659e-05 -1.30942788867451e-05 1.77358098640477e-05 7.58533327686224e-08 -5.21126249284411e-06 -5.44271365195737e-06 2.27661379411061e-06 5.51405254919569e-06 7.58533327686224e-08 3.07719930625749e-05 5.74718394281524e-06 5.74801809708497e-06 9.87824726830963e-06 1.25255617362845e-05 -5.21126249284411e-06 5.74718394281524e-06 4.79929903230126e-05 7.49160929516321e-06 1.64402013639457e-05 2.17984209719382e-05 -5.44271365195737e-06 5.74801809708497e-06 7.49160929516321e-06 4.00556220064081e-05 2118 2126 0 20 15 2105 2130 0 38 6 0 0 0 0 0 19 49 0 621 0 76 87 0 0 2209 +385 426 0.999995580304679 0.000286995515750663 0.00295922366209902 0.000291469491256846 -0.000291624580289096 0.999998734474711 0.00156397061364416 0.00428303775128228 -0.00295877106457376 -0.00156482668372899 0.99999439847993 -0.00712804522322978 2.61895429162831e-05 1.88751911373162e-05 -7.54426422586836e-06 5.53300423693299e-06 5.28513065782071e-06 1.93034448673361e-05 1.88751911373162e-05 3.0009346670631e-05 -9.31896218523538e-06 8.0826197863379e-06 5.21226985663515e-06 2.69243601650085e-05 -7.54426422586836e-06 -9.31896218523538e-06 1.15183736661072e-05 -1.01924812079422e-06 -1.85634342216289e-06 -4.83985321062946e-06 5.53300423693299e-06 8.0826197863379e-06 -1.01924812079422e-06 3.15477681640257e-05 1.69002417165233e-06 6.95011328174963e-06 5.28513065782071e-06 5.21226985663515e-06 -1.85634342216289e-06 1.69002417165233e-06 3.92662075053372e-05 6.64135086253471e-06 1.93034448673361e-05 2.69243601650085e-05 -4.83985321062946e-06 6.95011328174963e-06 6.64135086253471e-06 5.26851045644714e-05 2716 2712 0 18 17 2709 2736 0 44 16 0 0 0 0 0 16 46 0 650 0 17 21 0 0 2220 +386 412 0.999999899578901 0.000300816724833987 -0.000332191940871888 -0.00619669382203082 -0.000300887139473512 0.999999932274157 -0.000211940112062257 0.00672512962254168 0.000332128163243537 0.000212040043061843 0.999999922364949 -0.00046777114501727 5.00841426194467e-05 3.65858966928634e-05 -7.2766569071144e-06 1.43124562996974e-05 4.9753520254738e-07 3.80363094096279e-05 3.65858966928634e-05 3.84367955806788e-05 -8.24510121940486e-06 1.16071506061004e-05 6.2737929198764e-06 3.42180312907783e-05 -7.2766569071144e-06 -8.24510121940486e-06 1.24544230339751e-05 -3.07626342049121e-07 -1.46704359695707e-06 -5.54359833523309e-06 1.43124562996974e-05 1.16071506061004e-05 -3.07626342049121e-07 3.94981384253414e-05 -1.68492750828222e-05 9.60860033154726e-06 4.9753520254738e-07 6.2737929198764e-06 -1.46704359695707e-06 -1.68492750828222e-05 5.61856017426192e-05 5.81404205613653e-06 3.80363094096279e-05 3.42180312907783e-05 -5.54359833523309e-06 9.60860033154726e-06 5.81404205613653e-06 5.57739431166391e-05 2632 2629 0 11 9 2630 2657 0 41 7 0 0 0 0 0 13 44 0 571 0 22 30 0 0 2220 +385 425 0.999997085370575 0.00069322491942592 -0.0023127234086819 -0.00785544425582017 -0.000694559979908804 0.999999592608667 -0.000576514470666398 0.00291148364876852 0.00231232281230095 0.000578119115464627 0.999997159466716 -3.262236360168e-05 3.87857201535012e-05 1.87975439168311e-05 -7.25160064721148e-06 1.24272416777282e-06 1.1391326481416e-06 1.84984527554788e-05 1.87975439168311e-05 4.74939385440184e-05 -8.12378038822782e-06 1.38744570510051e-05 1.11377199091419e-05 3.73783556184263e-05 -7.25160064721148e-06 -8.12378038822782e-06 1.38032738320848e-05 -1.1086111849288e-06 -3.48457148551849e-06 -3.89833507017499e-06 1.24272416777282e-06 1.38744570510051e-05 -1.1086111849288e-06 3.71350749971015e-05 3.60857732381106e-06 2.94513051154253e-06 1.1391326481416e-06 1.11377199091419e-05 -3.48457148551849e-06 3.60857732381106e-06 4.1747186737294e-05 8.28908815955956e-06 1.84984527554788e-05 3.73783556184263e-05 -3.89833507017499e-06 2.94513051154253e-06 8.28908815955956e-06 5.61739641162261e-05 2349 2348 0 18 16 2330 2356 0 41 6 0 0 0 0 0 28 58 0 621 0 81 93 0 0 2062 +386 390 0.999996761003438 -0.000284056491719378 0.00252928735864034 -0.00354022383192213 0.000281147872476983 0.999999298931996 0.00115025709772813 0.00763606901225247 -0.00252961232343366 -0.00114954226828958 0.999996139799583 0.0051257255772614 2.32913171680728e-05 1.25620255043654e-05 -2.03597245558854e-06 7.76722405608596e-07 6.8165352253274e-06 1.19477286831e-05 1.25620255043654e-05 2.25756632466608e-05 -3.70755517733483e-06 3.89143791526175e-06 3.37815105842724e-06 9.70986621794282e-06 -2.03597245558854e-06 -3.70755517733483e-06 8.92947226288447e-06 1.90122097973069e-06 2.84140244005273e-06 1.09072927358181e-07 7.76722405608596e-07 3.89143791526175e-06 1.90122097973069e-06 3.55144520532693e-05 -8.41494948028196e-06 8.60987951447727e-06 6.8165352253274e-06 3.37815105842724e-06 2.84140244005273e-06 -8.41494948028196e-06 3.53209643045784e-05 1.04594853832309e-05 1.19477286831e-05 9.70986621794282e-06 1.09072927358181e-07 8.60987951447727e-06 1.04594853832309e-05 4.32884363098642e-05 2038 2017 0 10 47 2022 2048 0 42 30 0 0 0 0 0 16 48 0 407 0 58 46 0 0 2564 +385 428 0.999999450430875 0.00093595098328613 -0.000472370305066689 -0.00120072772663808 -0.000935381654055026 0.999998837666966 0.00120404562931862 0.00773020397986475 0.000473496683705761 -0.00120360312109504 0.999999163569859 -0.00490508282447908 3.35620107083985e-05 1.97425077619324e-05 -8.29808098754397e-06 5.6938079238503e-06 6.85979627599307e-06 2.89651643064148e-05 1.97425077619324e-05 2.49681857684836e-05 -8.88658139285867e-06 6.82593420054275e-06 5.88355411135193e-06 2.58840119732041e-05 -8.29808098754397e-06 -8.88658139285867e-06 1.28694909077277e-05 -2.13690692396202e-06 -2.25180561659599e-06 -3.82067570153028e-06 5.6938079238503e-06 6.82593420054275e-06 -2.13690692396202e-06 3.09029646291982e-05 1.06336874301853e-05 8.46725819552869e-06 6.85979627599307e-06 5.88355411135193e-06 -2.25180561659599e-06 1.06336874301853e-05 3.93738329241807e-05 6.5888639930054e-06 2.89651643064148e-05 2.58840119732041e-05 -3.82067570153028e-06 8.46725819552869e-06 6.5888639930054e-06 6.88466550063196e-05 3138 3137 0 15 16 3129 3176 0 51 13 0 0 0 0 0 17 50 0 634 0 16 21 0 0 2294 +385 423 0.999999646124971 0.000439077134925943 0.000717607972846834 -0.00309668481755876 -0.000439453841672282 0.999999765693522 0.000524874482262275 0.00281729578494435 -0.00071737734432277 -0.000525189652102785 0.999999604772709 -0.00640908963109541 3.36218785460126e-05 2.42394312273319e-05 -1.10361509607985e-05 7.54135499505199e-06 1.54032409001997e-05 2.03166023990462e-05 2.42394312273319e-05 3.43332555618513e-05 -1.26284751762853e-05 1.07704969479237e-05 1.11188696555896e-05 2.60795199661261e-05 -1.10361509607985e-05 -1.26284751762853e-05 1.61812058629544e-05 -2.91948817118489e-06 -5.36984574145625e-06 -4.67782299882798e-06 7.54135499505199e-06 1.07704969479237e-05 -2.91948817118489e-06 3.77803831118035e-05 -1.2027330678841e-06 1.03513290521616e-05 1.54032409001997e-05 1.11188696555896e-05 -5.36984574145625e-06 -1.2027330678841e-06 4.38918067976203e-05 6.21878584310705e-06 2.03166023990462e-05 2.60795199661261e-05 -4.67782299882798e-06 1.03513290521616e-05 6.21878584310705e-06 4.45475295383138e-05 2863 2863 0 20 12 2859 2886 0 46 12 0 0 0 0 0 18 49 0 623 0 13 18 0 0 2241 +385 422 0.999986469936631 0.000866023422630052 -0.00512932228543271 -0.00779696186518703 -0.000873447792414765 0.999998573991061 -0.00144537358452396 0.00771326899901052 0.00512806324359463 0.00144983422375456 0.999985800373232 -0.00246045278868196 5.0820983868321e-05 3.25897625933484e-05 -9.42758600334793e-06 1.14202629370225e-05 4.36715147119967e-06 3.31057082950699e-05 3.25897625933484e-05 4.34877126032581e-05 -1.07748435045951e-05 1.30241798748749e-05 5.55996256963133e-06 3.23540386183081e-05 -9.42758600334793e-06 -1.07748435045951e-05 1.45042094151834e-05 -7.55897994717091e-07 -4.65805277081399e-06 -6.41787586561649e-06 1.14202629370225e-05 1.30241798748749e-05 -7.55897994717091e-07 3.7211551889395e-05 -1.21890726979632e-06 -5.94396892070413e-07 4.36715147119967e-06 5.55996256963133e-06 -4.65805277081399e-06 -1.21890726979632e-06 4.17806862568489e-05 6.70554195155207e-06 3.31057082950699e-05 3.23540386183081e-05 -6.41787586561649e-06 -5.94396892070413e-07 6.70554195155207e-06 6.35407276728926e-05 2908 2906 0 18 14 2910 2946 0 50 15 0 0 0 0 0 23 57 0 598 0 54 63 0 0 2309 +386 413 0.99999890067668 0.0008767512418852 -0.00119580629304143 -0.0107772844359482 -0.000877195440874462 0.999999546447142 -0.000370990120616518 0.0109627717654652 0.00119548048463109 0.000372038668606852 0.999999216206513 -0.00308922720614433 5.02238333915104e-05 3.04424105905919e-05 -7.83709210287295e-06 1.33723152267383e-05 2.55186494793792e-07 3.52854143987967e-05 3.04424105905919e-05 3.21350470503555e-05 -9.22462223699191e-06 8.21295079067028e-06 1.09417320663272e-05 3.12251228620669e-05 -7.83709210287295e-06 -9.22462223699191e-06 1.21458418889256e-05 1.22198594892976e-06 -3.27939783511431e-06 -6.39464665137426e-06 1.33723152267383e-05 8.21295079067028e-06 1.22198594892976e-06 3.53625450650824e-05 -7.76343924477644e-06 1.06260997762186e-05 2.55186494793792e-07 1.09417320663272e-05 -3.27939783511431e-06 -7.76343924477644e-06 5.17222586059706e-05 6.07050423063323e-06 3.52854143987967e-05 3.12251228620669e-05 -6.39464665137426e-06 1.06260997762186e-05 6.07050423063323e-06 5.50853351546393e-05 2742 2742 0 20 11 2738 2766 0 40 10 0 0 0 0 0 19 52 0 609 0 12 21 0 0 2237 +386 388 0.999998765915575 0.000142046526137521 0.00156460541683137 -0.000946881798641088 -0.000142735578305199 0.999999892882501 0.000440297105060414 0.00180187453020241 -0.00156454270656051 -0.000440519886555606 0.999998679073302 -0.00374731171089754 3.65364003770506e-05 3.00196732822423e-05 -1.25135268527581e-07 5.0626582099796e-07 -4.03988266218235e-06 3.13315185872273e-05 3.00196732822423e-05 4.00026590595472e-05 -8.06358680748345e-07 6.58061581765168e-07 -3.42543804635475e-06 3.42561320180799e-05 -1.25135268527581e-07 -8.06358680748345e-07 1.19798380313623e-05 3.02752390640711e-06 1.81926620226071e-06 1.37991918315883e-06 5.0626582099796e-07 6.58061581765168e-07 3.02752390640711e-06 2.84945464346163e-05 -7.88806149912285e-06 3.28407658542387e-06 -4.03988266218235e-06 -3.42543804635475e-06 1.81926620226071e-06 -7.88806149912285e-06 3.32794802549658e-05 -1.00556626591741e-05 3.13315185872273e-05 3.42561320180799e-05 1.37991918315883e-06 3.28407658542387e-06 -1.00556626591741e-05 5.59224064450183e-05 2229 2213 0 22 53 2172 2197 0 44 7 0 0 0 0 0 16 48 0 648 0 106 89 0 0 2625 +385 429 0.999978165746852 -0.00660560132789206 -0.000184555298752836 0.00208354420979904 0.00660597967297002 0.999975910240825 0.00213072067472982 0.00117551116415268 0.000170476161541773 -0.00213189332058732 0.999997712981759 -0.00618089132728907 3.23418913239801e-05 1.78481182096112e-05 -3.01821930065174e-06 1.73404829936974e-06 4.238290324597e-06 2.06044505038035e-05 1.78481182096112e-05 2.43758597031657e-05 -4.10942596067742e-06 2.23765079731528e-06 -2.7889370614968e-06 1.86767387587448e-05 -3.01821930065174e-06 -4.10942596067742e-06 1.15962582538905e-05 1.84431688468659e-06 -1.77519441223403e-06 9.47512576902849e-07 1.73404829936974e-06 2.23765079731528e-06 1.84431688468659e-06 3.17044117555293e-05 -2.26991219110751e-06 8.23301540435126e-07 4.238290324597e-06 -2.7889370614968e-06 -1.77519441223403e-06 -2.26991219110751e-06 3.67956708866162e-05 -4.40912487186772e-06 2.06044505038035e-05 1.86767387587448e-05 9.47512576902849e-07 8.23301540435126e-07 -4.40912487186772e-06 4.41392622791415e-05 2889 2885 0 7 24 2888 2910 0 38 22 0 0 0 0 0 25 57 0 611 0 16 18 0 0 2408 +386 427 0.99999973615343 -0.000218957171511811 0.000692640474902458 -0.00659096566119009 0.000217388184186313 0.999997412408132 0.0022644909843725 0.00810767399767242 -0.000693134509172449 -0.00226433981503919 0.999997196160946 -0.00656752306102567 3.91804845354613e-05 2.30715427106049e-05 -7.27482685965932e-06 3.98778474813741e-06 3.10631246576601e-06 1.92592332855616e-05 2.30715427106049e-05 3.52707963759531e-05 -7.94857809243049e-06 5.84829135166499e-06 4.40421626147816e-07 2.11129412015701e-05 -7.27482685965932e-06 -7.94857809243049e-06 1.492244957139e-05 2.72505341872314e-06 -6.16229384294441e-06 -2.25844641741985e-06 3.98778474813741e-06 5.84829135166499e-06 2.72505341872314e-06 5.49864479991274e-05 -3.02800543504682e-05 7.98613209743364e-06 3.10631246576601e-06 4.40421626147816e-07 -6.16229384294441e-06 -3.02800543504682e-05 7.17799653308405e-05 -1.89330537600282e-06 1.92592332855616e-05 2.11129412015701e-05 -2.25844641741985e-06 7.98613209743364e-06 -1.89330537600282e-06 4.23529181549297e-05 2155 2154 0 17 17 2141 2171 0 47 12 0 0 0 0 0 21 51 0 637 0 63 69 0 0 2350 +386 389 0.999999968562336 0.000250002801999725 1.93371442567208e-05 -0.00482702871178886 -0.000249978209615784 0.99999917308331 -0.00126148467729131 0.00479278601070509 -1.9652502970516e-05 0.00126147980376848 0.999999204140925 -0.000415750043897486 3.25355105575659e-05 1.2751713863532e-05 -6.52048228193259e-07 -1.29862442908444e-06 7.87623209249638e-07 1.15428322412433e-05 1.2751713863532e-05 3.15957586356436e-05 -2.11034660976811e-06 6.23768144013322e-06 1.62392073552161e-06 1.96617504894443e-05 -6.52048228193259e-07 -2.11034660976811e-06 9.65980472714552e-06 3.61680602165461e-06 3.16011500187815e-06 1.9104193635706e-07 -1.29862442908444e-06 6.23768144013322e-06 3.61680602165461e-06 2.97466221606619e-05 -1.23218429710378e-05 4.17282846677551e-06 7.87623209249638e-07 1.62392073552161e-06 3.16011500187815e-06 -1.23218429710378e-05 3.77947955042508e-05 7.8404515790336e-07 1.15428322412433e-05 1.96617504894443e-05 1.9104193635706e-07 4.17282846677551e-06 7.8404515790336e-07 4.13424136746799e-05 2574 2552 0 11 46 2557 2577 0 38 28 0 0 0 0 0 19 51 0 505 0 56 45 0 0 2544 +386 416 0.999999799928282 0.000269167191585742 -0.000572444249933615 -0.00851009258942976 -0.000269371607581127 0.999999899978481 -0.000357046165244831 0.00805761950855045 0.000572348087563307 0.000357200294037846 0.999999772412782 -0.00446742521913952 4.00753710762532e-05 2.81594739892882e-05 -7.42356354026791e-06 8.20538339398415e-06 8.26386405128022e-06 3.29673794617099e-05 2.81594739892882e-05 3.5975187944617e-05 -8.10125323222957e-06 6.08077959020499e-06 9.78670084267805e-06 3.68432134227623e-05 -7.42356354026791e-06 -8.10125323222957e-06 1.21711080496814e-05 -9.57448877133722e-07 -5.79739766242069e-07 -4.1134986097066e-06 8.20538339398415e-06 6.08077959020499e-06 -9.57448877133722e-07 4.02657210325743e-05 -8.74091206974902e-06 8.16174736728323e-06 8.26386405128022e-06 9.78670084267805e-06 -5.79739766242069e-07 -8.74091206974902e-06 4.73198578561878e-05 9.08071388242758e-06 3.29673794617099e-05 3.68432134227623e-05 -4.1134986097066e-06 8.16174736728323e-06 9.08071388242758e-06 6.27110899322279e-05 2588 2596 0 21 12 2593 2623 0 41 10 0 0 0 0 0 22 54 0 614 0 40 51 0 0 2338 +386 426 0.999999124440292 0.00112474885467202 0.000697179075927509 -0.00471957238415726 -0.00112525557101596 0.999999102748583 0.000726843813162099 0.0098285845153052 -0.000696360933636216 -0.000727627681406125 0.999999492819575 -0.000795688188573036 3.6418935216606e-05 2.87277068643492e-05 -1.146194190013e-05 6.82409154232031e-06 1.02154517654631e-05 2.47016800951447e-05 2.87277068643492e-05 3.54248765946876e-05 -1.31056310760194e-05 9.42118909538361e-06 8.28031641263401e-06 2.4013533165887e-05 -1.146194190013e-05 -1.31056310760194e-05 1.71373607473438e-05 -1.65180346000363e-06 -3.25668943992266e-06 -3.87109942536147e-06 6.82409154232031e-06 9.42118909538361e-06 -1.65180346000363e-06 4.20356347537829e-05 -9.03028504531977e-06 4.70915944972817e-06 1.02154517654631e-05 8.28031641263401e-06 -3.25668943992266e-06 -9.03028504531977e-06 5.6070938940677e-05 5.8440617933091e-06 2.47016800951447e-05 2.4013533165887e-05 -3.87109942536147e-06 4.70915944972817e-06 5.8440617933091e-06 5.22856720536612e-05 2080 2080 0 17 17 2078 2109 0 49 17 0 0 0 0 0 21 51 0 655 0 25 36 0 0 2100 +386 414 0.999999746351091 -5.60606800216362e-05 0.000710038699420667 -0.00720036534218394 5.52898553858247e-05 0.999999409226729 0.0010855824358597 0.00747179333942202 -0.000710099138438356 -0.00108554290256589 0.999999158677556 -0.0036842263799027 2.32494838323437e-05 1.85926424558517e-05 -5.89721997655959e-06 1.23647101014937e-06 7.55025847476712e-06 1.68315475233614e-05 1.85926424558517e-05 2.64596139312292e-05 -8.12614720843921e-06 3.24297578942013e-06 8.13449172647642e-06 1.9799485832126e-05 -5.89721997655959e-06 -8.12614720843921e-06 1.32802590872738e-05 -2.53484707024079e-06 -1.13915135415799e-06 -2.83340817845204e-06 1.23647101014937e-06 3.24297578942013e-06 -2.53484707024079e-06 3.41047387435105e-05 -5.10249652292553e-06 3.2347030374747e-06 7.55025847476712e-06 8.13449172647642e-06 -1.13915135415799e-06 -5.10249652292553e-06 3.64679441692118e-05 5.99236308640306e-06 1.68315475233614e-05 1.9799485832126e-05 -2.83340817845204e-06 3.2347030374747e-06 5.99236308640306e-06 3.76606599819986e-05 2714 2717 0 16 11 2720 2751 0 46 10 0 0 0 0 0 16 47 0 615 0 43 60 0 0 2420 +386 428 0.999999535852466 0.000699863141099893 0.000662183083376251 -0.00375948246457754 -0.000700249493955992 0.999999584646649 0.000583401384333411 0.00952366526695436 -0.000661774507210927 -0.000583864806918137 0.999999610578119 -0.00702943986260777 3.75842313923056e-05 2.72109922197254e-05 -1.21758246503781e-05 8.70392113578478e-06 6.60605244191415e-06 1.86549069270871e-05 2.72109922197254e-05 3.3195437682353e-05 -1.26899132630982e-05 5.68266037625221e-06 6.89611187450115e-06 2.12828372204238e-05 -1.21758246503781e-05 -1.26899132630982e-05 1.53218378066838e-05 -1.70359467196258e-06 -3.43765318955922e-06 -5.41762731459837e-06 8.70392113578478e-06 5.68266037625221e-06 -1.70359467196258e-06 3.8282353681954e-05 1.01110690477655e-06 1.00019737900032e-05 6.60605244191415e-06 6.89611187450115e-06 -3.43765318955922e-06 1.01110690477655e-06 4.47812809201184e-05 3.34340059381008e-06 1.86549069270871e-05 2.12828372204238e-05 -5.41762731459837e-06 1.00019737900032e-05 3.34340059381008e-06 4.76233122676675e-05 1542 1543 0 15 16 1533 1560 0 43 8 0 0 0 0 0 13 46 0 662 0 59 66 0 0 2368 +386 415 0.999999255463378 -6.14011769001492e-05 -0.00121872990641724 -0.0101183871798427 6.58054953913178e-05 0.999993466779437 0.00361414832015371 0.0102774383487504 0.00121850003122561 -0.00361422582841317 0.999992726288214 -0.00471646023241146 5.91971680819545e-05 4.42302590164276e-05 -1.16411777735346e-05 1.76133211963403e-05 -4.70253615828948e-06 3.77868706167338e-05 4.42302590164276e-05 5.07134709684662e-05 -1.25045294526301e-05 1.62720213708802e-05 1.74938704016659e-06 4.03054748121822e-05 -1.16411777735346e-05 -1.25045294526301e-05 1.66308841017442e-05 -9.24146218729317e-07 -6.957216421681e-06 -6.65241681955389e-06 1.76133211963403e-05 1.62720213708802e-05 -9.24146218729317e-07 5.22190363331303e-05 -2.61211455623077e-05 2.05410688307832e-05 -4.70253615828948e-06 1.74938704016659e-06 -6.957216421681e-06 -2.61211455623077e-05 7.0176992475408e-05 -2.96721562499175e-06 3.77868706167338e-05 4.03054748121822e-05 -6.65241681955389e-06 2.05410688307832e-05 -2.96721562499175e-06 5.93125834512832e-05 2050 2054 0 12 15 2053 2082 0 45 12 0 0 0 0 0 22 54 0 586 0 58 65 0 0 2263 +386 417 0.999999666331245 -0.000221282711055307 -0.000786365919456628 -0.00408958877749243 0.000221375462858652 0.999999968550391 0.000117864844127449 0.00377502232198885 0.000786339813273481 -0.000118038886919029 0.99999968386821 -0.00517414099477929 3.53124564633294e-05 2.46923954932466e-05 -9.39612473682813e-06 4.50846476466444e-06 1.18165091201885e-05 2.03951055251877e-05 2.46923954932466e-05 3.41849057472096e-05 -1.02224731285426e-05 6.74493293187449e-06 1.45357498749896e-05 2.6648246130778e-05 -9.39612473682813e-06 -1.02224731285426e-05 1.43662029636895e-05 -1.7884039353076e-06 -3.33628094827951e-06 -5.37295462719872e-06 4.50846476466444e-06 6.74493293187449e-06 -1.7884039353076e-06 4.62868602315335e-05 -1.07212431186473e-05 8.92409184674436e-06 1.18165091201885e-05 1.45357498749896e-05 -3.33628094827951e-06 -1.07212431186473e-05 5.24776130767439e-05 1.18871883952476e-05 2.03951055251877e-05 2.6648246130778e-05 -5.37295462719872e-06 8.92409184674436e-06 1.18871883952476e-05 4.83698404746411e-05 2085 2085 0 20 13 2085 2112 0 42 10 0 0 0 0 0 12 46 0 606 0 45 60 0 0 2411 +386 420 0.999997803421473 0.000449512325603724 -0.00204721540088722 -0.00538779342138323 -0.000452537136729336 0.999998806395038 -0.00147730113357201 0.00768608596702717 0.00204654889225259 0.00147822432955985 0.999996813240154 -0.000994969763478492 3.91426480862292e-05 2.45998102817131e-05 -1.11308480038604e-05 9.85990757103691e-06 8.75536837970121e-06 2.19087158832423e-05 2.45998102817131e-05 3.32065615416887e-05 -1.16709460210959e-05 1.29042638012762e-05 5.25702760198817e-06 2.60383729865451e-05 -1.11308480038604e-05 -1.16709460210959e-05 1.47312757412357e-05 -3.1950652896298e-06 -2.45804425728158e-06 -5.34408283665513e-06 9.85990757103691e-06 1.29042638012762e-05 -3.1950652896298e-06 4.30670445614684e-05 -6.37536874542916e-06 7.25459228850549e-06 8.75536837970121e-06 5.25702760198817e-06 -2.45804425728158e-06 -6.37536874542916e-06 4.61440384872868e-05 5.84682931395382e-06 2.19087158832423e-05 2.60383729865451e-05 -5.34408283665513e-06 7.25459228850549e-06 5.84682931395382e-06 5.74605347045007e-05 2611 2612 0 16 11 2613 2645 0 46 11 0 0 0 0 0 16 47 0 630 0 18 28 0 0 2279 +386 418 0.999999938466715 0.000174535988406862 0.00030430865049535 -0.00951788373130091 -0.000174917593229002 0.999999197903652 0.0012544305031849 0.0110779160266438 -0.000304089463142732 -0.00125448365493241 0.999999166899832 -0.0016224668826666 2.4803779410503e-05 1.73829817792742e-05 -7.66687574143838e-06 5.46496107624517e-06 4.07238379907238e-06 1.52746313447296e-05 1.73829817792742e-05 2.43613215814371e-05 -9.27801190725378e-06 7.77361977439451e-06 5.12682115033384e-06 1.70154458318413e-05 -7.66687574143838e-06 -9.27801190725378e-06 1.37020299649358e-05 -3.77916304569468e-06 -6.96285708178932e-07 -6.97596336471868e-07 5.46496107624517e-06 7.77361977439451e-06 -3.77916304569468e-06 3.99201443600814e-05 -8.38930520057928e-06 9.75611761298525e-06 4.07238379907238e-06 5.12682115033384e-06 -6.96285708178932e-07 -8.38930520057928e-06 4.13703005833809e-05 1.44431813676169e-06 1.52746313447296e-05 1.70154458318413e-05 -6.97596336471868e-07 9.75611761298525e-06 1.44431813676169e-06 4.60543242920294e-05 2117 2115 0 10 13 2116 2139 0 38 12 0 0 0 0 0 16 49 0 624 0 22 33 0 0 2219 +386 419 0.999999579475043 0.00058904045680417 0.000702909010894326 -0.00658570956301502 -0.00058918966704189 0.999999803937273 0.000212087134079019 0.00966152353219296 -0.000702783945177728 -0.000212501191617176 0.999999730468949 -0.00786798056585675 3.19526866219797e-05 1.76434119723224e-05 -9.32098199854538e-06 6.77721154396788e-06 1.01419566422842e-05 1.07272699707076e-05 1.76434119723224e-05 3.15849543941282e-05 -9.8018941348796e-06 6.71538321997952e-06 9.31382214570447e-06 2.07314350079491e-05 -9.32098199854538e-06 -9.8018941348796e-06 1.58673002824931e-05 -3.92219698381676e-06 -2.90938012024317e-06 -2.36226307051505e-06 6.77721154396788e-06 6.71538321997952e-06 -3.92219698381676e-06 4.91452028967132e-05 -1.1804294594999e-05 2.37914199769672e-06 1.01419566422842e-05 9.31382214570447e-06 -2.90938012024317e-06 -1.1804294594999e-05 5.26690725299604e-05 5.0590514522426e-06 1.07272699707076e-05 2.07314350079491e-05 -2.36226307051505e-06 2.37914199769672e-06 5.0590514522426e-06 4.42029722450397e-05 2031 2032 0 15 14 2020 2041 0 38 7 0 0 0 0 0 15 47 0 601 0 59 66 0 0 2254 +386 421 0.999999913228353 0.000384221563976696 -0.000160987814014549 -0.00640421886335518 -0.000383859353369817 0.999997408671503 0.00224394792183982 0.0114881858210318 0.00016184957002225 -0.00224388593045057 0.999997469387122 -0.00408357242769326 5.37319587991888e-05 3.42808253187557e-05 -1.29592547907649e-05 5.23213902948106e-06 1.09799740451096e-05 3.04570544034187e-05 3.42808253187557e-05 4.44221406881636e-05 -1.18062735541764e-05 1.15916488024105e-05 7.993045358913e-06 3.3544039476681e-05 -1.29592547907649e-05 -1.18062735541764e-05 1.84162311734601e-05 4.91629755555048e-07 -5.46289163324371e-06 -3.87114894855598e-06 5.23213902948106e-06 1.15916488024105e-05 4.91629755555048e-07 4.79536618904214e-05 -1.63381370399293e-05 5.2799115341121e-06 1.09799740451096e-05 7.993045358913e-06 -5.46289163324371e-06 -1.63381370399293e-05 5.78637629585368e-05 8.79628411236069e-06 3.04570544034187e-05 3.3544039476681e-05 -3.87114894855598e-06 5.2799115341121e-06 8.79628411236069e-06 6.21342847942996e-05 2029 2031 0 21 14 2021 2052 0 46 10 0 0 0 0 0 16 49 0 630 0 23 33 0 0 2323 +387 391 0.999999767812541 -0.000101237664893479 0.000673888565724958 -0.000452965061947118 0.000101924166136154 0.999999475869742 -0.0010187598867275 0.00178510439653229 -0.00067378507564755 0.00101882833571436 0.999999254000969 0.00335059749445589 2.45712778990606e-05 9.71235038335108e-06 -2.17102694979779e-07 -2.81115509150438e-07 -8.22274264869593e-07 5.41350058794188e-06 9.71235038335108e-06 2.05215340682934e-05 -1.93874582002626e-06 2.1541166904453e-06 -1.10910983357163e-06 1.62951399906933e-05 -2.17102694979779e-07 -1.93874582002626e-06 9.49083567714995e-06 2.93536843796361e-06 2.93075377652667e-06 -6.90079119049872e-07 -2.81115509150438e-07 2.1541166904453e-06 2.93536843796361e-06 2.30892517443005e-05 1.25071588961539e-06 9.79668814457419e-06 -8.22274264869593e-07 -1.10910983357163e-06 2.93075377652667e-06 1.25071588961539e-06 2.3088652140704e-05 7.35955514528181e-06 5.41350058794188e-06 1.62951399906933e-05 -6.90079119049872e-07 9.79668814457419e-06 7.35955514528181e-06 4.32261205618509e-05 3194 3177 0 17 53 3178 3219 0 41 34 0 0 0 0 0 21 50 0 418 0 54 34 0 0 2398 +387 390 0.999997533409955 -4.96693597235146e-05 0.00222051952480644 0.000344474142437452 5.24248230788752e-05 0.999999228748417 -0.00124086832905755 2.9543046001777e-05 -0.00222045617909184 0.00124098167868731 0.999996764764182 0.00864719114429989 4.79231595707343e-05 2.13465266154314e-05 -2.86814426739379e-06 7.45994523165584e-06 -2.1146071281233e-06 1.13198353835522e-05 2.13465266154314e-05 3.76641779095998e-05 -6.62553359451446e-06 9.80880414803008e-06 2.14643462950734e-06 1.61470152740477e-05 -2.86814426739379e-06 -6.62553359451446e-06 1.32337210732697e-05 7.72386081303087e-07 -1.00281589527288e-06 -4.31816138437407e-06 7.45994523165584e-06 9.80880414803008e-06 7.72386081303087e-07 2.98702139408354e-05 1.55137671210646e-06 5.1187442546952e-06 -2.1146071281233e-06 2.14643462950734e-06 -1.00281589527288e-06 1.55137671210646e-06 4.16441576521188e-05 1.21320900628418e-05 1.13198353835522e-05 1.61470152740477e-05 -4.31816138437407e-06 5.1187442546952e-06 1.21320900628418e-05 4.86338047081717e-05 2181 2161 0 18 54 2124 2148 0 40 5 0 0 0 0 0 17 46 0 403 0 63 39 0 0 2464 +387 414 0.999999617529116 0.000230521974726356 0.00084368313993573 -0.00355831851513196 -0.000231196046990288 0.999999654110809 0.000798953471187622 0.00489194081555217 -0.000843498671782959 -0.000799148221818048 0.999999324935827 -0.00190139168566389 3.67542580062796e-05 2.70298140599864e-05 -1.03203894098723e-05 7.34528691497416e-06 1.76726668041853e-05 2.92615371186871e-05 2.70298140599864e-05 3.59505870567513e-05 -1.0307991467439e-05 9.82308440193583e-06 1.47463776562108e-05 3.33131972709834e-05 -1.03203894098723e-05 -1.0307991467439e-05 1.33085476902773e-05 -1.68322859566058e-06 -6.25362409818248e-06 -6.01687619735785e-06 7.34528691497416e-06 9.82308440193583e-06 -1.68322859566058e-06 2.85773940454951e-05 6.60014907905984e-06 8.12606302719612e-06 1.76726668041853e-05 1.47463776562108e-05 -6.25362409818248e-06 6.60014907905984e-06 4.16419827381963e-05 1.41347840703651e-05 2.92615371186871e-05 3.33131972709834e-05 -6.01687619735785e-06 8.12606302719612e-06 1.41347840703651e-05 5.30515779684515e-05 3087 3086 0 11 11 3090 3122 0 34 9 0 0 0 0 0 16 46 0 605 0 11 14 0 0 2328 +386 424 0.999998694635339 0.000622003676364695 -0.00149125418490335 -0.00703632499230771 -0.000621781041481501 0.999999795481214 0.000149752688050288 0.00579196202316667 0.00149134702663636 -0.000148825258988218 0.999998876866913 -0.00361606267119738 2.46578673707793e-05 1.73347223011237e-05 -9.10217760042663e-06 6.15084914722858e-06 1.06263143767008e-05 2.02912779317387e-05 1.73347223011237e-05 2.40554885794195e-05 -9.89868225102799e-06 6.36522587936212e-06 8.91489093407222e-06 2.23559658754072e-05 -9.10217760042663e-06 -9.89868225102799e-06 1.46390666380119e-05 -2.58970003613124e-07 -6.17170462151634e-06 -5.45392787180539e-06 6.15084914722858e-06 6.36522587936212e-06 -2.58970003613124e-07 2.96433205294717e-05 6.56269676919337e-07 7.51746458345882e-06 1.06263143767008e-05 8.91489093407222e-06 -6.17170462151634e-06 6.56269676919337e-07 4.64083328189474e-05 1.17496472611815e-05 2.02912779317387e-05 2.23559658754072e-05 -5.45392787180539e-06 7.51746458345882e-06 1.17496472611815e-05 4.84958802558695e-05 2383 2390 0 20 15 2382 2422 0 46 12 0 0 0 0 0 11 42 0 630 0 14 18 0 0 2223 +386 425 0.999999116519258 0.00123394935549 0.000494297170030323 -0.00848417682992979 -0.00123420974736466 0.999999099585729 0.000526833968533208 0.00828996557208421 -0.000493646638522176 -0.000527443569470889 0.999999739058105 -0.00241993401450174 4.44646356437004e-05 1.31423509923221e-05 -8.83584667542593e-06 4.3053537876556e-06 6.90829025689994e-06 1.45085133698574e-05 1.31423509923221e-05 3.02277662574585e-05 -9.07259633394703e-06 2.54958475588705e-06 1.09276631683071e-05 2.29541772201891e-05 -8.83584667542593e-06 -9.07259633394703e-06 1.47272264731593e-05 3.48676871022431e-07 -4.73804880283726e-06 -3.39350524939085e-06 4.3053537876556e-06 2.54958475588705e-06 3.48676871022431e-07 3.25215964008368e-05 -2.64209938652819e-06 1.33320673961866e-06 6.90829025689994e-06 1.09276631683071e-05 -4.73804880283726e-06 -2.64209938652819e-06 4.8824783475593e-05 1.15310624175951e-05 1.45085133698574e-05 2.29541772201891e-05 -3.39350524939085e-06 1.33320673961866e-06 1.15310624175951e-05 5.34518631588351e-05 2882 2884 0 24 16 2877 2912 0 43 12 0 0 0 0 0 20 50 0 640 0 16 19 0 0 2049 +387 416 0.999998114609673 0.00027130743809108 -0.00192280247922623 -0.00633155912731817 -0.000271139293940016 0.999999959395432 8.77075726537209e-05 0.00379423367046398 0.0019228261968685 -8.71860599841083e-05 0.999998147567288 -0.00496801518774872 4.52584128297053e-05 2.39323117768937e-05 -1.0026729649117e-05 9.98458865956218e-06 9.41369355953938e-06 2.90172806172286e-05 2.39323117768937e-05 4.24404068490386e-05 -1.13966290583231e-05 1.50159110898359e-05 1.66319977057844e-05 4.15093793477939e-05 -1.0026729649117e-05 -1.13966290583231e-05 1.2550817487408e-05 -4.85753554768656e-07 -2.61668848306637e-06 -8.40604785210515e-06 9.98458865956218e-06 1.50159110898359e-05 -4.85753554768656e-07 3.17795795579773e-05 7.48026548284848e-06 1.80997689407624e-05 9.41369355953938e-06 1.66319977057844e-05 -2.61668848306637e-06 7.48026548284848e-06 3.76058392711222e-05 1.58041488724381e-05 2.90172806172286e-05 4.15093793477939e-05 -8.40604785210515e-06 1.80997689407624e-05 1.58041488724381e-05 6.75867873038198e-05 3062 3060 0 19 12 3060 3095 0 45 12 0 0 0 0 0 21 51 0 614 0 18 26 0 0 2272 +387 427 0.999999764555009 0.000661548400166796 0.000182328386439379 -0.000154736573810108 -0.000661610155427044 0.999999723725777 0.000338851549273333 0.00225641389740884 -0.00018210416936643 -0.000338972099804524 0.999999925967991 -0.00550881565370585 2.83410144341919e-05 2.20945710663538e-05 -1.07633920074838e-05 9.55785483904668e-06 9.318591551299e-06 2.17428276764362e-05 2.20945710663538e-05 2.700429232569e-05 -1.09433868164115e-05 9.61059534489446e-06 4.90239448292228e-06 2.4377386849899e-05 -1.07633920074838e-05 -1.09433868164115e-05 1.66427770029948e-05 -8.00178207520775e-06 -8.33519595989091e-06 -5.28251998955523e-06 9.55785483904668e-06 9.61059534489446e-06 -8.00178207520775e-06 3.92380880007947e-05 1.97438894586852e-06 8.92209417392325e-06 9.318591551299e-06 4.90239448292228e-06 -8.33519595989091e-06 1.97438894586852e-06 5.02508402314432e-05 5.74098893698918e-06 2.17428276764362e-05 2.4377386849899e-05 -5.28251998955523e-06 8.92209417392325e-06 5.74098893698918e-06 4.72009653025094e-05 2802 2804 0 17 17 2802 2833 0 48 14 0 0 0 0 0 14 41 0 648 0 57 62 0 0 2373 +387 389 0.999999245552748 -0.000218932154067952 0.00120870287791091 -2.17217047808621e-05 0.000216842756366741 0.999998482652101 0.00172848856370695 -0.00100534043751098 -0.00120907946561268 -0.00172822516118983 0.999997775679845 -0.00138944371986791 4.77348835401343e-05 1.08806909760931e-05 -1.01078897524926e-07 -2.37342294375792e-06 -4.71418553731946e-06 9.47682967976811e-06 1.08806909760931e-05 3.51016867546406e-05 -2.03154648417891e-06 1.09005955509731e-05 1.60466011282817e-07 1.43570924150716e-05 -1.01078897524926e-07 -2.03154648417891e-06 1.27990009704744e-05 2.13998365396269e-06 3.43375931375364e-06 -1.14714837979858e-07 -2.37342294375792e-06 1.09005955509731e-05 2.13998365396269e-06 3.90362489569928e-05 -9.82865572964181e-06 -9.41531428488485e-07 -4.71418553731946e-06 1.60466011282817e-07 3.43375931375364e-06 -9.82865572964181e-06 3.32110842357328e-05 -3.32796840084066e-06 9.47682967976811e-06 1.43570924150716e-05 -1.14714837979858e-07 -9.41531428488485e-07 -3.32796840084066e-06 3.50761964170537e-05 1542 1520 0 14 54 1488 1515 0 45 4 0 0 0 0 0 22 50 0 501 0 63 40 0 0 2562 +387 426 0.99999963153871 0.000791271091128014 0.000332885123072545 -0.0051647636205678 -0.000791351944467781 0.999999657398988 0.000242825052494921 0.00612683683665404 -0.000332692868581524 -0.000243088392312717 0.999999915111741 -0.00233680055412001 3.12750376186107e-05 2.11543924049757e-05 -1.28217564243646e-05 8.82457198001127e-06 1.07157142808674e-05 1.58443304184074e-05 2.11543924049757e-05 3.38113290012518e-05 -1.33781473747141e-05 1.43589877355076e-05 1.04092026520967e-05 2.13204985204227e-05 -1.28217564243646e-05 -1.33781473747141e-05 1.88554825672914e-05 -5.99404464470455e-06 -9.1589274897787e-06 -5.37802042744735e-06 8.82457198001127e-06 1.43589877355076e-05 -5.99404464470455e-06 4.10719264914527e-05 3.09890484274324e-06 4.52177199688422e-06 1.07157142808674e-05 1.04092026520967e-05 -9.1589274897787e-06 3.09890484274324e-06 5.20573291036836e-05 1.1044629772692e-05 1.58443304184074e-05 2.13204985204227e-05 -5.37802042744735e-06 4.52177199688422e-06 1.1044629772692e-05 3.77187321986175e-05 2139 2134 0 13 17 2121 2145 0 41 8 0 0 0 0 0 16 45 0 658 0 24 29 0 0 2126 +386 422 0.999999251231833 1.44006828387633e-05 0.00122365370686127 -0.00727103103646629 -1.68952999420347e-05 0.999997921753639 0.00203867676515619 0.0114588993077022 -0.00122362180546991 -0.00203869591265633 0.999997173230331 -0.00773923392046922 4.17511271065812e-05 2.07438334333285e-05 -1.1622519162918e-05 -3.44658761175989e-06 1.81644129087706e-05 2.347176504831e-05 2.07438334333285e-05 3.07752380675282e-05 -1.13854487438636e-05 3.37926696472222e-06 1.18853903245137e-05 2.14166149326517e-05 -1.1622519162918e-05 -1.13854487438636e-05 1.53924148809794e-05 -3.65627626631416e-06 -3.53613790992174e-06 -5.15332362563423e-06 -3.44658761175989e-06 3.37926696472222e-06 -3.65627626631416e-06 4.40340457119893e-05 -1.16610288501436e-05 -4.6627346041562e-06 1.81644129087706e-05 1.18853903245137e-05 -3.53613790992174e-06 -1.16610288501436e-05 5.17153535444303e-05 1.35791536572426e-05 2.347176504831e-05 2.14166149326517e-05 -5.15332362563423e-06 -4.6627346041562e-06 1.35791536572426e-05 5.87729953410154e-05 2672 2670 0 13 15 2676 2701 0 42 14 0 0 0 0 0 26 60 0 614 0 47 60 0 0 2319 +387 420 0.999997450941492 0.000653639348606884 -0.00216121866539253 -0.00799270791874211 -0.000653681661827205 0.999999786172042 -1.8872090334655e-05 0.00841225368377046 0.00216120586772272 2.02847912373584e-05 0.999997664386135 -0.0063057665429838 5.17049175583714e-05 3.76897901051849e-05 -1.49789449375901e-05 2.01425677467593e-05 1.33496361779226e-05 3.14061435622125e-05 3.76897901051849e-05 4.39409618637551e-05 -1.4435615019697e-05 2.08249124296314e-05 6.18444041193522e-06 3.97046499725714e-05 -1.49789449375901e-05 -1.4435615019697e-05 1.88675111584448e-05 -7.67178841887851e-06 -1.09201222193532e-05 -8.48431282297084e-06 2.01425677467593e-05 2.08249124296314e-05 -7.67178841887851e-06 4.48340153538229e-05 1.85399430780609e-06 1.90464422355189e-05 1.33496361779226e-05 6.18444041193522e-06 -1.09201222193532e-05 1.85399430780609e-06 5.63662155016472e-05 4.65596038791899e-06 3.14061435622125e-05 3.97046499725714e-05 -8.48431282297084e-06 1.90464422355189e-05 4.65596038791899e-06 6.21848927386712e-05 2139 2140 0 16 11 2124 2155 0 46 4 0 0 0 0 0 17 45 0 629 0 20 23 0 0 2272 +386 429 0.999971801586595 -0.00733265688658545 -0.0016211645948655 -0.00755773707914847 0.00733904590136299 0.999965184891394 0.00397081986213703 0.0121768509256902 0.00159199149423657 -0.00398260569269238 0.999990802165189 -0.00218720893282111 2.87210519207814e-05 1.68553080291121e-05 -4.99134112040373e-06 -7.75084528343945e-07 5.05157920139704e-06 2.0249438909398e-05 1.68553080291121e-05 2.83977928689357e-05 -5.74093743402565e-06 4.81403081753696e-08 3.42952199797242e-06 2.07758305117094e-05 -4.99134112040373e-06 -5.74093743402565e-06 1.16315401361745e-05 1.87411740272241e-06 -1.4997803212255e-06 -1.69948598582405e-06 -7.75084528343945e-07 4.81403081753696e-08 1.87411740272241e-06 3.43403534582727e-05 -7.26295909024849e-06 2.09031791857923e-06 5.05157920139704e-06 3.42952199797242e-06 -1.4997803212255e-06 -7.26295909024849e-06 4.56662330632722e-05 4.32601203766753e-06 2.0249438909398e-05 2.07758305117094e-05 -1.69948598582405e-06 2.09031791857923e-06 4.32601203766753e-06 5.98818794904003e-05 2548 2546 0 6 25 2553 2565 0 29 24 0 0 0 0 0 24 55 0 618 0 17 25 0 0 2489 +387 418 0.999998186704089 0.00141105621499516 -0.00127887016255634 -0.00791685677494334 -0.00141005926938289 0.999998701573124 0.000780118531870457 0.00815862221501218 0.00127996929313978 -0.000778313834557663 0.999998877952462 -0.00271209132114282 3.45631660220173e-05 2.37518628687305e-05 -1.14702039590174e-05 1.00049618193648e-05 9.99832126196129e-06 2.03254725414733e-05 2.37518628687305e-05 3.10391772830949e-05 -1.15596650577336e-05 8.63955048274342e-06 8.64615224214869e-06 2.53990425144674e-05 -1.14702039590174e-05 -1.15596650577336e-05 1.70084119895138e-05 -5.65018240726894e-06 -6.31583373576572e-06 -5.16205405210468e-06 1.00049618193648e-05 8.63955048274342e-06 -5.65018240726894e-06 4.04026068336823e-05 1.98814871716111e-07 3.14826291114657e-06 9.99832126196129e-06 8.64615224214869e-06 -6.31583373576572e-06 1.98814871716111e-07 4.5383636308114e-05 6.66815529814933e-06 2.03254725414733e-05 2.53990425144674e-05 -5.16205405210468e-06 3.14826291114657e-06 6.66815529814933e-06 4.66801735218646e-05 2189 2193 0 20 13 2173 2209 0 48 6 0 0 0 0 0 18 46 0 621 0 23 27 0 0 2197 +387 413 0.999996415727775 0.000386458335859481 -0.00264937380471016 -0.00620898024619729 -0.000390828526452421 0.999998563696705 -0.00164919907516269 -0.000441566488566124 0.00264873265267574 0.00165022861484437 0.999995130468571 -0.00229495500955979 4.22636502842298e-05 2.13392422128034e-05 -6.9718012715851e-06 6.89687292952597e-06 7.55288099674477e-06 1.92238207305004e-05 2.13392422128034e-05 3.15029619579983e-05 -9.76097207522071e-06 1.09598663542674e-05 1.55154785451181e-05 3.0687915375628e-05 -6.9718012715851e-06 -9.76097207522071e-06 1.25275982817715e-05 -1.95177031034112e-06 -2.02185440073101e-06 -6.42819909235224e-06 6.89687292952597e-06 1.09598663542674e-05 -1.95177031034112e-06 3.68922871779831e-05 4.15052936264448e-06 8.77092403266962e-06 7.55288099674477e-06 1.55154785451181e-05 -2.02185440073101e-06 4.15052936264448e-06 5.0285151155092e-05 2.22337136575845e-05 1.92238207305004e-05 3.0687915375628e-05 -6.42819909235224e-06 8.77092403266962e-06 2.22337136575845e-05 5.04373753290441e-05 2606 2603 0 15 11 2594 2627 0 49 4 0 0 0 0 0 16 47 0 600 0 37 45 0 0 2291 +386 423 0.99999824179484 0.00147097970523873 -0.00116302447754286 -0.0104102177960046 -0.00147079507927781 0.999998905646511 0.000159585763008971 0.0141931881873648 0.0011632579522016 -0.000157874911745809 0.999999310952987 -0.00452678332101718 3.9020171327308e-05 2.97021969360894e-05 -9.46870018906529e-06 8.28720020666629e-06 1.09496276351452e-05 2.97398747347595e-05 2.97021969360894e-05 3.35587604460547e-05 -9.79414065236749e-06 9.47054382352606e-06 5.20734687737012e-06 3.056319586429e-05 -9.46870018906529e-06 -9.79414065236749e-06 1.25266052364045e-05 -9.27203571637515e-07 -2.03363453261101e-06 -5.01618739156145e-06 8.28720020666629e-06 9.47054382352606e-06 -9.27203571637515e-07 3.7369061428106e-05 -9.27977411394887e-06 4.26173232855162e-06 1.09496276351452e-05 5.20734687737012e-06 -2.03363453261101e-06 -9.27977411394887e-06 4.47936526493286e-05 3.15979110089331e-06 2.97398747347595e-05 3.056319586429e-05 -5.01618739156145e-06 4.26173232855162e-06 3.15979110089331e-06 6.66474784319387e-05 2582 2584 0 16 12 2583 2604 0 38 12 0 0 0 0 0 18 49 0 619 0 21 34 0 0 2239 +387 428 0.999993863257752 0.000420158755133832 0.00347806173855933 0.00250791555669514 -0.000420961560937114 0.999999884924734 0.000230091033662428 0.000631335218767727 -0.00347796466355818 -0.00023155375195156 0.999993925053877 -0.00352138771387494 3.9506522994248e-05 2.90587031210165e-05 -1.32359780018197e-05 1.45067367366461e-05 1.27399326710635e-05 2.8760535447677e-05 2.90587031210165e-05 3.60720088480075e-05 -1.37340710181238e-05 1.38266499228355e-05 1.0605890691383e-05 3.12181615429266e-05 -1.32359780018197e-05 -1.37340710181238e-05 1.62025620010923e-05 -6.63546925120661e-06 -9.4112005779848e-06 -6.53539125302378e-06 1.45067367366461e-05 1.38266499228355e-05 -6.63546925120661e-06 3.56735219524647e-05 8.60423028661904e-06 1.35342728213461e-05 1.27399326710635e-05 1.0605890691383e-05 -9.4112005779848e-06 8.60423028661904e-06 5.27307000926992e-05 7.13722417740601e-06 2.8760535447677e-05 3.12181615429266e-05 -6.53539125302378e-06 1.35342728213461e-05 7.13722417740601e-06 6.18460840191123e-05 2775 2776 0 23 16 2777 2807 0 44 16 0 0 0 0 0 17 49 0 645 0 55 63 0 0 2274 +387 425 0.999999739810757 2.56869273393979e-05 -0.000720915112783715 -0.00742033412255229 -2.55865016126396e-05 0.999999989968749 0.000139312000314395 -0.00121344094977904 0.000720918684049264 -0.000139293518371215 0.999999730436747 0.000720553532209772 5.7042314833083e-05 2.91065023632436e-05 -1.02175459303336e-05 7.23050946124589e-06 1.05579182480516e-05 3.22299107963327e-05 2.91065023632436e-05 4.05360568751887e-05 -9.40231020336072e-06 1.07532864940458e-05 7.17602537925648e-06 3.3115016344482e-05 -1.02175459303336e-05 -9.40231020336072e-06 1.56186813784079e-05 -1.65125986057176e-06 -1.74130199773879e-06 -4.15180091398711e-06 7.23050946124589e-06 1.07532864940458e-05 -1.65125986057176e-06 3.95930088339048e-05 1.72223895648532e-06 2.5379627494497e-06 1.05579182480516e-05 7.17602537925648e-06 -1.74130199773879e-06 1.72223895648532e-06 4.14935276103443e-05 1.36933998420683e-05 3.22299107963327e-05 3.3115016344482e-05 -4.15180091398711e-06 2.5379627494497e-06 1.36933998420683e-05 6.31328849737681e-05 1991 1992 0 18 16 1993 2013 0 40 16 0 0 0 0 0 19 46 0 630 0 43 57 0 0 2120 +387 417 0.99999992165278 0.000362854426435515 0.00015821219899138 -0.00469677309919369 -0.00036309026618417 0.999998819284642 0.00149318276872586 0.00397038051547275 -0.000157670204210698 -0.00149324009704859 0.999998872686424 -0.00330968038199081 3.94294791124244e-05 2.17968222112359e-05 -7.81522716731684e-06 4.79497416366587e-06 8.91214710012076e-06 2.65573410723251e-05 2.17968222112359e-05 2.63694810194784e-05 -8.4691459295343e-06 4.19299972649334e-06 7.49356351789168e-06 2.10037305794e-05 -7.81522716731684e-06 -8.4691459295343e-06 1.20976285898141e-05 5.61771509138945e-07 -2.31610861780852e-06 -4.04598602416379e-06 4.79497416366587e-06 4.19299972649334e-06 5.61771509138945e-07 2.55698244073439e-05 2.18932004586865e-06 4.55607886289636e-06 8.91214710012076e-06 7.49356351789168e-06 -2.31610861780852e-06 2.18932004586865e-06 3.42455976896393e-05 6.00656115352045e-06 2.65573410723251e-05 2.10037305794e-05 -4.04598602416379e-06 4.55607886289636e-06 6.00656115352045e-06 4.0267867511288e-05 3206 3209 0 16 13 3208 3254 0 49 12 0 0 0 0 0 12 41 0 605 0 15 17 0 0 2324 +387 419 0.999997080590781 0.000599242296624282 0.0023408798740955 -0.00146100869171665 -0.000603517091450109 0.999998150982325 0.0018258693961032 0.00313544520849697 -0.00233978140759698 -0.0018272768266563 0.999995593231472 -0.00645105793067126 3.37426504259956e-05 2.64009848370962e-05 -9.81294473676053e-06 1.28416448255079e-05 8.33126452888569e-06 1.92173208623263e-05 2.64009848370962e-05 4.28098264018288e-05 -1.16390263049057e-05 1.19493502694955e-05 3.57736220354057e-06 3.09013212593501e-05 -9.81294473676053e-06 -1.16390263049057e-05 1.66027686276216e-05 -1.76137167934471e-06 -5.25509500282715e-06 -3.33458474126476e-06 1.28416448255079e-05 1.19493502694955e-05 -1.76137167934471e-06 3.83102477907808e-05 1.21663496719401e-06 7.00724266351448e-06 8.33126452888569e-06 3.57736220354057e-06 -5.25509500282715e-06 1.21663496719401e-06 4.52933667847022e-05 -1.14785800951333e-06 1.92173208623263e-05 3.09013212593501e-05 -3.33458474126476e-06 7.00724266351448e-06 -1.14785800951333e-06 5.37116160424788e-05 2171 2171 0 21 14 2169 2196 0 43 14 0 0 0 0 0 17 46 0 594 0 54 60 0 0 2221 +387 421 0.999999497009712 0.00075584825065551 -0.000659297917701761 -0.00552707806113603 -0.000757201098445574 0.999997603612175 -0.0020541218081366 0.00522840057260577 0.000657743733392945 0.00205461999604077 0.999997672952219 -0.00264573354706834 4.61350703724826e-05 2.98894672470025e-05 -1.31193818306053e-05 1.21745499511095e-05 1.14813880926106e-05 2.85285241349625e-05 2.98894672470025e-05 4.41594706799914e-05 -1.12382721734111e-05 1.91256273647915e-05 -1.04283494794085e-06 3.54485778000982e-05 -1.31193818306053e-05 -1.12382721734111e-05 1.74794118568782e-05 -5.89857767996246e-06 -8.88371275854599e-06 -5.20566944549836e-06 1.21745499511095e-05 1.91256273647915e-05 -5.89857767996246e-06 4.33120186254277e-05 3.14735843898494e-06 1.04681925829618e-05 1.14813880926106e-05 -1.04283494794085e-06 -8.88371275854599e-06 3.14735843898494e-06 5.35769146672986e-05 -4.93076730683432e-06 2.85285241349625e-05 3.54485778000982e-05 -5.20566944549836e-06 1.04681925829618e-05 -4.93076730683432e-06 5.81158054546794e-05 2129 2126 0 7 14 2126 2151 0 40 11 0 0 0 0 0 18 50 0 633 0 20 24 0 0 2316 +387 423 0.999996973417875 0.000712778866681692 -0.00235480389360614 -0.010871243577611 -0.000711693221194604 0.999999640098158 0.000461840137769378 0.00812534661234629 0.00235513223599787 -0.00046016284200395 0.99999712079701 -0.00621118424735932 3.53546445959451e-05 2.84196564325426e-05 -1.11065003765371e-05 1.05359414453404e-05 1.37049285736012e-05 2.30470961095789e-05 2.84196564325426e-05 4.49814559809799e-05 -1.61104129435248e-05 2.01463936058929e-05 1.2654214988588e-05 3.04616198749514e-05 -1.11065003765371e-05 -1.61104129435248e-05 2.02025158560483e-05 -3.00950975461332e-06 -8.62549900664722e-06 -8.51349805021047e-06 1.05359414453404e-05 2.01463936058929e-05 -3.00950975461332e-06 4.86863792221222e-05 -1.83668745419374e-07 8.07526397875052e-06 1.37049285736012e-05 1.2654214988588e-05 -8.62549900664722e-06 -1.83668745419374e-07 5.59813391851808e-05 1.62665448521829e-05 2.30470961095789e-05 3.04616198749514e-05 -8.51349805021047e-06 8.07526397875052e-06 1.62665448521829e-05 4.87848004793558e-05 1586 1588 0 16 12 1574 1605 0 44 4 0 0 0 0 0 20 47 0 620 0 19 22 0 0 2232 +388 391 0.999999779207688 0.000256209970960444 -0.000613140299118615 -0.00291815498379472 -0.000256240757269902 0.999999965913686 -5.01328436021341e-05 0.00387742778604157 0.000613127433684519 5.02899440677465e-05 0.999999810772818 0.00949512527259557 2.7066874821918e-05 6.71876287638576e-06 -5.692703147879e-07 -1.38532938555434e-06 4.02248633339401e-06 6.33679486714448e-06 6.71876287638576e-06 2.98068109453971e-05 -2.91001864851934e-06 4.50035567498175e-06 2.69956942764616e-06 1.94024627339677e-05 -5.692703147879e-07 -2.91001864851934e-06 1.11081003551223e-05 3.04361953296074e-06 2.51067005119405e-06 -2.11770349904769e-06 -1.38532938555434e-06 4.50035567498175e-06 3.04361953296074e-06 3.01751873036114e-05 1.70795788893015e-06 9.02425301754676e-06 4.02248633339401e-06 2.69956942764616e-06 2.51067005119405e-06 1.70795788893015e-06 3.29064019008742e-05 1.1125710655314e-05 6.33679486714448e-06 1.94024627339677e-05 -2.11770349904769e-06 9.02425301754676e-06 1.1125710655314e-05 5.16726524372526e-05 2079 2060 0 16 55 2069 2100 0 45 33 0 0 0 0 0 16 49 0 418 0 90 83 0 0 2394 +388 392 0.999999722019562 0.00063269731630315 0.000394531247207742 -0.00351162784763223 -0.000632452643438358 0.999999607815631 -0.000619977611375655 0.00843258728394385 -0.000394923350649639 0.000619727916703791 0.999999729986392 0.00504654750562806 2.2342423972365e-05 1.37400750973932e-05 -1.46644449657916e-06 2.29666109325202e-06 -1.30068802568796e-06 1.61043640990779e-05 1.37400750973932e-05 2.12419179951e-05 -2.33762653368784e-06 4.37750841950717e-06 -2.46024000411117e-06 1.60895875919593e-05 -1.46644449657916e-06 -2.33762653368784e-06 9.98450425060011e-06 2.42399648022319e-06 3.14223862113015e-06 -2.40693767534556e-06 2.29666109325202e-06 4.37750841950717e-06 2.42399648022319e-06 3.06527111245558e-05 -1.08868608087322e-06 1.03623104626259e-05 -1.30068802568796e-06 -2.46024000411117e-06 3.14223862113015e-06 -1.08868608087322e-06 2.78100169194501e-05 5.1129824406525e-06 1.61043640990779e-05 1.60895875919593e-05 -2.40693767534556e-06 1.03623104626259e-05 5.1129824406525e-06 4.64704404348235e-05 2347 2328 0 16 55 2329 2377 0 47 33 0 0 0 0 0 17 49 0 443 0 55 33 0 0 2295 +387 422 0.999997777027347 0.00127968559250972 -0.0016758117881734 -0.00543829017584545 -0.00128166435623579 0.999998482186083 -0.00118023811493532 0.00629146068470871 0.00167429891089153 0.00118238331953493 0.999997899344215 -0.00597184657188132 3.90575947705961e-05 1.63848248998781e-05 -8.70342188592081e-06 6.53510261170149e-06 8.77034926554174e-06 2.05821602834401e-05 1.63848248998781e-05 3.2370592068745e-05 -9.47311108298191e-06 8.21614104320056e-06 1.15145410779466e-05 2.39198137968934e-05 -8.70342188592081e-06 -9.47311108298191e-06 1.41285735690075e-05 -2.6353602761269e-06 -7.50965215358401e-06 -4.26535302405063e-06 6.53510261170149e-06 8.21614104320056e-06 -2.6353602761269e-06 2.84207556633093e-05 2.95652959350678e-06 5.6206038381581e-06 8.77034926554174e-06 1.15145410779466e-05 -7.50965215358401e-06 2.95652959350678e-06 5.71012905830128e-05 8.87284694139085e-06 2.05821602834401e-05 2.39198137968934e-05 -4.26535302405063e-06 5.6206038381581e-06 8.87284694139085e-06 4.50569352734737e-05 2613 2616 0 18 14 2613 2654 0 48 11 0 0 0 0 0 16 46 0 597 0 16 19 0 0 2315 +387 429 0.999970011051966 -0.00733267245512853 -0.00249176872853955 -0.00430161231923603 0.00734278161652856 0.999964748995372 0.0040723856344042 0.00507706729606244 0.00246181942122052 -0.0040905600214556 0.999988603316982 -0.00387013423768249 4.47210314689797e-05 2.299062588736e-05 -5.38529665342471e-06 9.29072727070393e-07 4.39908460684167e-06 1.91079004857764e-05 2.299062588736e-05 4.1603036620363e-05 -5.96874652496041e-06 9.20093620825655e-06 1.18968142945555e-06 2.59862860316616e-05 -5.38529665342471e-06 -5.96874652496041e-06 1.34768795421747e-05 -2.08517277722356e-06 -2.21951207716718e-06 -1.26520687286269e-06 9.29072727070393e-07 9.20093620825655e-06 -2.08517277722356e-06 4.22614574676929e-05 -1.54050623122112e-06 -4.98232681917284e-06 4.39908460684167e-06 1.18968142945555e-06 -2.21951207716718e-06 -1.54050623122112e-06 4.3656673498569e-05 5.02454425143634e-06 1.91079004857764e-05 2.59862860316616e-05 -1.26520687286269e-06 -4.98232681917284e-06 5.02454425143634e-06 5.27714830327704e-05 1534 1531 0 3 24 1531 1548 0 35 12 0 0 0 0 0 27 59 0 609 0 20 20 0 0 2402 +388 390 0.999978725488419 6.97959930977732e-05 0.00652255311027052 0.00851625758477044 -7.2405859139129e-05 0.999999917420992 0.000399894237985399 0.00033412542682571 -0.00652252466062908 -0.000400358001492531 0.999978647964806 0.00402017384422001 5.36112889221781e-05 2.63655183641955e-05 -3.02030310923152e-06 1.08481759530255e-05 -8.88325653650399e-06 3.32055801910873e-05 2.63655183641955e-05 3.36231835445284e-05 -5.30391543769882e-06 7.95235707475857e-06 -3.94114921001659e-06 2.61092565195651e-05 -3.02030310923152e-06 -5.30391543769882e-06 1.0728840548214e-05 3.89650907143736e-06 7.61792780419791e-07 -2.4493758651517e-06 1.08481759530255e-05 7.95235707475857e-06 3.89650907143736e-06 2.84987084769313e-05 -6.27758059700397e-06 1.63130843322004e-05 -8.88325653650399e-06 -3.94114921001659e-06 7.61792780419791e-07 -6.27758059700397e-06 4.17232744772533e-05 -3.63746804371225e-07 3.32055801910873e-05 2.61092565195651e-05 -2.4493758651517e-06 1.63130843322004e-05 -3.63746804371225e-07 5.9552110409037e-05 2672 2652 0 15 54 2652 2684 0 51 28 0 0 0 0 0 16 47 0 406 0 80 66 0 0 2500 +388 428 0.999999335127348 0.00113694408846306 -0.000192621392267145 -0.00373093594929163 -0.00113667041768931 0.999998352915975 0.00141497197780025 0.00895148566213681 0.000194229819029028 -0.00141475208998567 0.999998980375131 -0.00402730002433823 3.30120269574528e-05 1.63756230881684e-05 -8.23261444716763e-06 5.55861598863624e-06 1.37420294030976e-06 2.37216972610792e-05 1.63756230881684e-05 2.45665616033799e-05 -9.79394189264356e-06 3.97253838487299e-06 5.1599822774525e-06 2.48897869451177e-05 -8.23261444716763e-06 -9.79394189264356e-06 1.38833216336638e-05 -1.64786297094492e-07 -1.16931816613667e-06 -4.72013066819107e-06 5.55861598863624e-06 3.97253838487299e-06 -1.64786297094492e-07 2.39490734767966e-05 8.23130955178925e-06 9.59818175429577e-06 1.37420294030976e-06 5.1599822774525e-06 -1.16931816613667e-06 8.23130955178925e-06 3.82677295945125e-05 7.71447005890184e-06 2.37216972610792e-05 2.48897869451177e-05 -4.72013066819107e-06 9.59818175429577e-06 7.71447005890184e-06 6.06910531321689e-05 3104 3101 0 10 16 3104 3154 0 47 13 0 0 0 0 0 12 45 0 631 0 16 19 0 0 2271 +388 414 0.99997671686416 0.000771374605636182 -0.00678017041041588 -0.011513044046399 -0.000778277333953138 0.999999181525349 -0.00101549644239794 0.0119203688393547 0.00677938153285049 0.00102074965140709 0.999976498751936 0.00316782156843179 3.64075214698293e-05 2.08279158782479e-05 -8.74924157837697e-06 1.09370058758023e-05 4.46495588992052e-06 2.01381646778671e-05 2.08279158782479e-05 4.14855001014738e-05 -8.57791668373979e-06 1.26245851186894e-05 1.27358493343065e-05 3.15139515426927e-05 -8.74924157837697e-06 -8.57791668373979e-06 1.30197784541993e-05 -9.50059166637409e-07 3.69014712228859e-08 -4.84223138147739e-06 1.09370058758023e-05 1.26245851186894e-05 -9.50059166637409e-07 3.51730804043984e-05 -5.48265229443155e-06 6.49411648198541e-06 4.46495588992052e-06 1.27358493343065e-05 3.69014712228859e-08 -5.48265229443155e-06 4.26967330383237e-05 1.41315515625216e-05 2.01381646778671e-05 3.15139515426927e-05 -4.84223138147739e-06 6.49411648198541e-06 1.41315515625216e-05 4.99423569649089e-05 2616 2615 0 15 11 2621 2658 0 42 11 0 0 0 0 0 18 48 0 609 0 50 57 0 0 2373 +387 424 0.99999982742542 0.000545998043801023 -0.000216876153545235 -0.00319950454216932 -0.000546144608395152 0.999999622161827 -0.000676315214735907 -0.00221378927579405 0.000216506804816906 0.000676433543763042 0.9999997477812 -0.000448112583202097 3.50545589582204e-05 1.75809726821264e-05 -8.68613558330215e-06 6.41830716536122e-06 4.99556409087171e-06 1.57134295997699e-05 1.75809726821264e-05 2.49140300775932e-05 -9.52806426248543e-06 7.78144304138201e-06 5.6939098078652e-06 1.74541408999061e-05 -8.68613558330215e-06 -9.52806426248543e-06 1.4748052187482e-05 4.18814438049163e-07 -1.99603245971717e-06 -2.28687201611547e-06 6.41830716536122e-06 7.78144304138201e-06 4.18814438049163e-07 3.51146601050759e-05 1.99350814208223e-06 5.21687661977915e-06 4.99556409087171e-06 5.6939098078652e-06 -1.99603245971717e-06 1.99350814208223e-06 4.65729683329133e-05 5.09524738553807e-06 1.57134295997699e-05 1.74541408999061e-05 -2.28687201611547e-06 5.21687661977915e-06 5.09524738553807e-06 3.89557660975415e-05 2588 2586 0 16 15 2584 2606 0 38 14 0 0 0 0 0 11 41 0 629 0 42 55 0 0 2224 +388 420 0.999998628402456 9.13991817860169e-05 0.00165373498388517 0.000522909244867641 -9.29792659575114e-05 0.999999539270986 0.000955412304276583 -0.000103793824216427 -0.00165364689805861 -0.000955564756900303 0.999998176172303 -0.00694371684306124 3.59563662965627e-05 1.91263189462436e-05 -6.69776086936452e-06 8.86944837474346e-06 6.61169540493733e-06 1.988535537595e-05 1.91263189462436e-05 2.92672256623999e-05 -7.74472313780959e-06 1.15741477263088e-05 2.62549551121473e-06 2.62810233458564e-05 -6.69776086936452e-06 -7.74472313780959e-06 1.19882634696211e-05 5.96152060164374e-07 -3.11050515549217e-07 -2.2332570739579e-06 8.86944837474346e-06 1.15741477263088e-05 5.96152060164374e-07 3.27112306249271e-05 4.77862569627204e-06 1.24620297265469e-05 6.61169540493733e-06 2.62549551121473e-06 -3.11050515549217e-07 4.77862569627204e-06 3.23238191415099e-05 1.99425660659092e-06 1.988535537595e-05 2.62810233458564e-05 -2.2332570739579e-06 1.24620297265469e-05 1.99425660659092e-06 5.19659507117565e-05 2028 2029 0 15 11 2030 2054 0 46 9 0 0 0 0 0 16 46 0 627 0 46 56 0 0 2361 +388 427 0.999999480958844 0.000611114058674813 0.000815243307348717 -0.00533648896204516 -0.000611364120815299 0.999999766139916 0.000306519207552958 0.00862649853635147 -0.00081505579849886 -0.000307017458964722 0.999999620712091 -0.00138291736303577 2.52245501526845e-05 1.16062781567294e-05 -8.28963526009909e-06 3.85278224803204e-06 8.09647039376068e-06 1.42078323593193e-05 1.16062781567294e-05 1.96104263335118e-05 -7.98317063363916e-06 1.6863153107107e-06 5.00818865152346e-06 1.51758879293116e-05 -8.28963526009909e-06 -7.98317063363916e-06 1.29618909389037e-05 2.13451400654241e-06 -1.35864531795409e-06 -3.75954347479505e-06 3.85278224803204e-06 1.6863153107107e-06 2.13451400654241e-06 2.59253569962441e-05 1.90642928012414e-06 7.51276457812172e-06 8.09647039376068e-06 5.00818865152346e-06 -1.35864531795409e-06 1.90642928012414e-06 3.90263387627252e-05 9.60081842662046e-06 1.42078323593193e-05 1.51758879293116e-05 -3.75954347479505e-06 7.51276457812172e-06 9.60081842662046e-06 3.91906033424351e-05 2420 2422 0 16 17 2421 2463 0 43 15 0 0 0 0 0 17 48 0 662 0 19 21 0 0 2444 +388 415 0.999999921645192 0.000348690998910689 -0.000187414503999505 -0.00417265132201726 -0.000348755407259415 0.999999880104458 -0.000343745159445946 0.00302567821356723 0.000187294620686324 0.000343810494333529 0.999999923357532 -0.000648128456190195 2.75513244211916e-05 1.61309797958453e-05 -6.68213942579327e-06 4.99675323114603e-06 3.06025589566143e-06 2.34367278925478e-05 1.61309797958453e-05 2.3812083463677e-05 -7.18241457064466e-06 4.89799767582909e-06 6.86934780755966e-06 2.54631925443294e-05 -6.68213942579327e-06 -7.18241457064466e-06 1.14189950856516e-05 1.87416690645578e-06 -9.74709684233996e-07 -4.28924007795085e-06 4.99675323114603e-06 4.89799767582909e-06 1.87416690645578e-06 2.66416146320649e-05 -2.91165284719418e-06 7.74212128112151e-06 3.06025589566143e-06 6.86934780755966e-06 -9.74709684233996e-07 -2.91165284719418e-06 3.22861414817388e-05 7.47462050357018e-06 2.34367278925478e-05 2.54631925443294e-05 -4.28924007795085e-06 7.74212128112151e-06 7.47462050357018e-06 5.9028287054532e-05 2497 2497 0 12 14 2500 2542 0 44 13 0 0 0 0 0 21 53 0 587 0 16 20 0 0 2253 +388 426 0.99999124664762 -1.62709352153699e-05 0.00418406063478392 -0.00205295469903575 2.73676355224515e-06 0.999994768394982 0.00323468316480867 0.00668781319265044 -0.00418409137675152 -0.00323464339970245 0.999986015132926 -0.00632261681601215 2.75140478146015e-05 1.67262365415675e-05 -6.16765782473568e-06 6.09019557140554e-06 3.65236973160834e-06 1.80120266000944e-05 1.67262365415675e-05 2.76273735450278e-05 -7.14719559032723e-06 6.83769129463336e-06 5.54305261440811e-06 2.23666562302446e-05 -6.16765782473568e-06 -7.14719559032723e-06 1.23769920994141e-05 2.62222879864382e-06 -1.35717031728461e-06 -1.83264002367508e-06 6.09019557140554e-06 6.83769129463336e-06 2.62222879864382e-06 3.30119773952716e-05 -4.16837775421838e-08 5.86931098774124e-06 3.65236973160834e-06 5.54305261440811e-06 -1.35717031728461e-06 -4.16837775421838e-08 4.57480105491969e-05 5.33287973898117e-06 1.80120266000944e-05 2.23666562302446e-05 -1.83264002367508e-06 5.86931098774124e-06 5.33287973898117e-06 4.20813266906172e-05 2686 2681 0 12 17 2686 2712 0 43 17 0 0 0 0 0 21 51 0 657 0 48 58 0 0 2199 +388 416 0.999987790552152 0.00102671783398562 -0.00483369394094197 -0.0132359627458794 -0.00104008018916856 0.999995642803601 -0.00276271732396009 0.0117643585897358 0.00483083634844137 0.00276771102201548 0.999984501277831 0.00651883608033981 4.49697691508699e-05 3.60267749836885e-05 -9.96527888518174e-06 1.63920300375348e-05 1.56632716595352e-06 3.40475251868609e-05 3.60267749836885e-05 4.28565260915252e-05 -9.64669491275276e-06 1.99496052590466e-05 -4.92894159568538e-06 3.61616440913789e-05 -9.96527888518174e-06 -9.64669491275276e-06 1.31524369908644e-05 -1.1788651991297e-07 -2.68923769786261e-06 -5.73521456581885e-06 1.63920300375348e-05 1.99496052590466e-05 -1.1788651991297e-07 4.0778461436875e-05 -1.50318649712462e-05 1.0700135344774e-05 1.56632716595352e-06 -4.92894159568538e-06 -2.68923769786261e-06 -1.50318649712462e-05 4.69129773194564e-05 9.22725986840338e-07 3.40475251868609e-05 3.61616440913789e-05 -5.73521456581885e-06 1.0700135344774e-05 9.22725986840338e-07 5.56899092742114e-05 2669 2667 0 12 12 2668 2702 0 48 5 0 0 0 0 0 19 50 0 617 0 54 60 0 0 2243 +388 424 0.999999048717105 0.000979382215978183 -0.000971275120678727 -0.00930794159756273 -0.000980781662086935 0.99999848020721 -0.00144140577284143 0.0083513442754289 0.000969861957361872 0.00144235701048398 0.999998489485878 0.00176898681039856 3.13252170547436e-05 2.3098588662873e-05 -9.70163492969334e-06 5.66072961833869e-06 1.07256097512668e-05 1.83076996757986e-05 2.3098588662873e-05 3.23381737284495e-05 -1.05148508534949e-05 1.02655224089037e-05 9.86372948895132e-06 2.44963722784668e-05 -9.70163492969334e-06 -1.05148508534949e-05 1.47812218531168e-05 1.81659181296317e-06 -5.53982878542477e-06 -4.74651968344159e-06 5.66072961833869e-06 1.02655224089037e-05 1.81659181296317e-06 3.56955044807713e-05 -2.32814318925473e-07 7.2161611329685e-06 1.07256097512668e-05 9.86372948895132e-06 -5.53982878542477e-06 -2.32814318925473e-07 4.87690324858489e-05 5.90157385818732e-06 1.83076996757986e-05 2.44963722784668e-05 -4.74651968344159e-06 7.2161611329685e-06 5.90157385818732e-06 3.94165185977798e-05 2095 2093 0 16 15 2079 2108 0 44 7 0 0 0 0 0 12 43 0 627 0 49 51 0 0 2202 +388 425 0.999983307469876 0.000519535702629015 -0.00575455161249484 -0.0101708244547105 -0.000520597047525624 0.999999847755943 -0.000182939346420631 0.00339159608221822 0.00575445569287668 0.000185932095279379 0.999983425697114 -0.00206757829246263 5.63681110489156e-05 2.57427308742358e-05 -1.09849714907904e-05 1.64900256691544e-06 4.43931609982856e-06 2.83148546735044e-05 2.57427308742358e-05 3.90313032669832e-05 -7.86524223264774e-06 7.77307087528892e-06 5.90165031517475e-06 3.3682085519672e-05 -1.09849714907904e-05 -7.86524223264774e-06 1.62480133190825e-05 6.96292086134652e-07 -4.90796976449797e-06 -5.02916942743032e-06 1.64900256691544e-06 7.77307087528892e-06 6.96292086134652e-07 3.40731273636855e-05 -2.62952221622933e-07 3.11734068007361e-06 4.43931609982856e-06 5.90165031517475e-06 -4.90796976449797e-06 -2.62952221622933e-07 3.93105688874889e-05 2.67468025146697e-06 2.83148546735044e-05 3.3682085519672e-05 -5.02916942743032e-06 3.11734068007361e-06 2.67468025146697e-06 5.32813337039528e-05 2340 2339 0 18 16 2327 2356 0 51 7 0 0 0 0 0 17 48 0 627 0 53 54 0 0 2052 +388 418 0.999992607108153 0.000269655145846975 0.00383575483323528 -0.00205372072543146 -0.000274638963267253 0.999999118796077 0.00129883813796706 0.00538943291027984 -0.00383540121476554 -0.00129988198352792 0.999991799968555 -0.00665364584539725 2.47845099732681e-05 1.50623015443102e-05 -7.4782490929605e-06 5.00293438175959e-06 5.47786132184368e-06 1.41458254059214e-05 1.50623015443102e-05 2.62759275570952e-05 -8.83703763954092e-06 7.17924075627997e-06 7.46580431773307e-06 1.83733950592588e-05 -7.4782490929605e-06 -8.83703763954092e-06 1.24396625778319e-05 -3.08646964090874e-07 -1.56290829837027e-06 -3.70119154251514e-06 5.00293438175959e-06 7.17924075627997e-06 -3.08646964090874e-07 3.4981708609535e-05 -3.70370578685621e-06 7.56119382593036e-06 5.47786132184368e-06 7.46580431773307e-06 -1.56290829837027e-06 -3.70370578685621e-06 4.09797590631498e-05 2.39611110257055e-06 1.41458254059214e-05 1.83733950592588e-05 -3.70119154251514e-06 7.56119382593036e-06 2.39611110257055e-06 3.75711810713196e-05 2624 2626 0 14 13 2625 2651 0 41 11 0 0 0 0 0 17 49 0 625 0 50 60 0 0 2188 +388 421 0.999998425278479 0.000491152379294424 0.00170534744348454 -0.00214902976499664 -0.000496031177943136 0.999995782478371 0.00286163913527929 0.00693068713351753 -0.00170393475027484 -0.00286248053449575 0.999994451390385 -0.00660219713144462 3.54276683383542e-05 2.46239539186153e-05 -9.31609631180212e-06 6.02191466478847e-06 8.14276550504097e-06 2.12770604264545e-05 2.46239539186153e-05 3.78449413555816e-05 -1.11460247552878e-05 6.33683469025421e-06 8.24106479893212e-06 2.86633469813684e-05 -9.31609631180212e-06 -1.11460247552878e-05 1.49006008570426e-05 -1.82290355116913e-06 -1.63498804893186e-06 -4.51027876600209e-06 6.02191466478847e-06 6.33683469025421e-06 -1.82290355116913e-06 2.70291933143503e-05 4.69193218259298e-06 3.74904211482277e-06 8.14276550504097e-06 8.24106479893212e-06 -1.63498804893186e-06 4.69193218259298e-06 3.8262273126619e-05 9.01229308258826e-06 2.12770604264545e-05 2.86633469813684e-05 -4.51027876600209e-06 3.74904211482277e-06 9.01229308258826e-06 4.77171937556437e-05 2666 2664 0 15 14 2662 2696 0 44 11 0 0 0 0 0 17 49 0 625 0 53 59 0 0 2332 +388 417 0.999995070524944 0.000193313871469595 -0.00313393611285809 -0.00798247750150313 -0.000191785284747588 0.999999862514656 0.000488046178951811 0.00652792885812461 0.00313403002808412 -0.000487442730310561 0.999994970115034 -0.000907529655779954 4.80542038929898e-05 3.20753759878913e-05 -8.63772375496623e-06 1.13613349804183e-05 5.60768679649484e-06 3.05355237554307e-05 3.20753759878913e-05 3.85025136226285e-05 -9.66400226955393e-06 1.20917009647788e-05 4.02697650278631e-06 3.19645999134198e-05 -8.63772375496623e-06 -9.66400226955393e-06 1.31633887735692e-05 1.60541076638618e-06 -1.58691080862153e-07 -4.84075775160135e-06 1.13613349804183e-05 1.20917009647788e-05 1.60541076638618e-06 2.91536317166571e-05 3.31271102352581e-06 1.30493408456063e-05 5.60768679649484e-06 4.02697650278631e-06 -1.58691080862153e-07 3.31271102352581e-06 3.84930898070551e-05 7.01358638813126e-06 3.05355237554307e-05 3.19645999134198e-05 -4.84075775160135e-06 1.30493408456063e-05 7.01358638813126e-06 5.32064865347229e-05 2744 2745 0 14 13 2750 2781 0 41 10 0 0 0 0 0 14 47 0 608 0 52 62 0 0 2310 +389 391 0.999993394113707 0.000323782314268162 0.00362034445339407 0.000482695365894656 -0.000330823158473143 0.99999805498908 0.00194436984534754 0.00782074440485607 -0.00361970785921625 -0.00194555469484826 0.999991556230323 0.00182237873900426 3.83918941655138e-05 5.72971289407012e-06 -1.03567306623957e-06 2.36519724259777e-06 -5.69585924944523e-06 2.84903171098606e-06 5.72971289407012e-06 2.89982178079616e-05 -1.39145742854763e-06 4.03306548165567e-06 3.46895782061785e-06 1.12903226547461e-05 -1.03567306623957e-06 -1.39145742854763e-06 1.12081545571925e-05 1.7791993424644e-06 3.38033475351414e-06 -8.77315844759617e-07 2.36519724259777e-06 4.03306548165567e-06 1.7791993424644e-06 2.86823411487811e-05 -6.53259169649974e-06 6.48523404697003e-07 -5.69585924944523e-06 3.46895782061785e-06 3.38033475351414e-06 -6.53259169649974e-06 3.41779663046026e-05 9.50046159331185e-06 2.84903171098606e-06 1.12903226547461e-05 -8.77315844759617e-07 6.48523404697003e-07 9.50046159331185e-06 4.01708762364254e-05 1597 1573 0 17 49 1548 1578 0 54 8 0 0 0 0 0 18 51 0 420 0 133 132 0 0 2397 +388 419 0.99999774482861 0.000137382524533895 -0.00211930737197311 -0.00490919721828259 -0.000135351602421927 0.999999531566074 0.000958408877001557 0.0038128359179105 0.0021194380478487 -0.000958119863976456 0.999997294990685 -0.00591647322801211 3.03637532660698e-05 1.55655298755861e-05 -7.54297142443042e-06 6.57083329926187e-06 5.80975328374087e-06 1.51334225856723e-05 1.55655298755861e-05 2.60194935558798e-05 -6.86008102934791e-06 7.42719998316217e-06 4.1024295275755e-06 2.74957160811489e-05 -7.54297142443042e-06 -6.86008102934791e-06 1.27823402343936e-05 8.13606516888958e-07 -2.43599644410082e-06 -3.08834520843432e-06 6.57083329926187e-06 7.42719998316217e-06 8.13606516888958e-07 2.57540222226734e-05 4.06275812799926e-06 9.99346200744014e-06 5.80975328374087e-06 4.1024295275755e-06 -2.43599644410082e-06 4.06275812799926e-06 3.19418297466485e-05 4.86877091435939e-06 1.51334225856723e-05 2.74957160811489e-05 -3.08834520843432e-06 9.99346200744014e-06 4.86877091435939e-06 5.89972490347401e-05 3313 3314 0 15 14 3317 3364 0 50 11 0 0 0 0 0 16 48 0 599 0 15 17 0 0 2245 +388 422 0.999982794297184 0.00087247898082998 -0.00580085252558553 -0.00940684509541437 -0.000876312638285843 0.999999399312747 -0.000658369429526576 0.00880478761851374 0.00580027462759848 0.000663441462198831 0.999982958184624 -0.000628983513521245 5.50168188472991e-05 3.92444436426169e-05 -9.64483306603245e-06 1.25678849849831e-05 1.00385648831076e-05 4.04536234371337e-05 3.92444436426169e-05 4.93018214808208e-05 -9.82513124819165e-06 1.70047593968668e-05 3.6808048206909e-06 4.3787568199671e-05 -9.64483306603245e-06 -9.82513124819165e-06 1.36165192194688e-05 -3.57309457888514e-07 -4.25333471931532e-06 -5.28834972648009e-06 1.25678849849831e-05 1.70047593968668e-05 -3.57309457888514e-07 3.20060222738052e-05 -3.6706218230833e-06 1.12149115769178e-05 1.00385648831076e-05 3.6808048206909e-06 -4.25333471931532e-06 -3.6706218230833e-06 4.06512648744999e-05 5.03725167806935e-06 4.04536234371337e-05 4.3787568199671e-05 -5.28834972648009e-06 1.12149115769178e-05 5.03725167806935e-06 7.24195310127006e-05 2892 2894 0 17 14 2901 2941 0 49 14 0 0 0 0 0 18 52 0 597 0 54 61 0 0 2342 +389 393 0.99999938746619 -0.000291644758699341 0.00106771277943563 -0.0021630856652047 0.000291195733651894 0.999999869116749 0.000420679841916888 0.00351132247852797 -0.00106783532876089 -0.000420368670830124 0.999999341508729 0.00360752054416186 1.97613743192122e-05 8.20217204184496e-06 -8.87181538399781e-07 -7.09457167223508e-07 1.0174560320029e-06 6.78161570101053e-06 8.20217204184496e-06 1.72427122958918e-05 -2.11146192797724e-06 -4.2986288686168e-07 -4.82621120640345e-07 1.26723943144631e-05 -8.87181538399781e-07 -2.11146192797724e-06 8.49916299573484e-06 3.75816286710916e-06 3.11851206370165e-06 9.45130144917824e-07 -7.09457167223508e-07 -4.2986288686168e-07 3.75816286710916e-06 1.94947862920394e-05 1.30569195039129e-06 6.11579115620096e-06 1.0174560320029e-06 -4.82621120640345e-07 3.11851206370165e-06 1.30569195039129e-06 2.01744694490115e-05 3.77388622799221e-06 6.78161570101053e-06 1.26723943144631e-05 9.45130144917824e-07 6.11579115620096e-06 3.77388622799221e-06 3.33764831547213e-05 3125 3102 0 17 50 3103 3144 0 52 30 0 0 0 0 0 17 49 0 433 0 50 30 0 0 2422 +389 428 0.99999540831876 0.00125522267597962 -0.00275821634955384 -0.0067354573452043 -0.00125267196661109 0.999998786389191 0.000926300755017051 0.014495940753493 0.00275937571586514 -0.000922841361440317 0.999995767095781 -0.0014645133731667 3.86715142439328e-05 2.22986735314084e-05 -3.02020744141528e-06 7.6970027173558e-06 -1.16396916025549e-06 2.61751661159768e-05 2.22986735314084e-05 3.1252279232965e-05 -5.11388775691771e-06 6.87439564665102e-06 -2.87071284478787e-06 2.70841900195056e-05 -3.02020744141528e-06 -5.11388775691771e-06 1.13493252799935e-05 2.29625808074543e-06 1.76427600730662e-06 3.88842896706418e-07 7.6970027173558e-06 6.87439564665102e-06 2.29625808074543e-06 3.2657896140368e-05 3.83481196290627e-09 9.43881253759269e-06 -1.16396916025549e-06 -2.87071284478787e-06 1.76427600730662e-06 3.83481196290627e-09 3.57804316113474e-05 -2.03516145389427e-06 2.61751661159768e-05 2.70841900195056e-05 3.88842896706418e-07 9.43881253759269e-06 -2.03516145389427e-06 6.25198935876846e-05 2748 2751 0 17 16 2746 2777 0 55 14 0 0 0 0 0 18 51 0 551 0 40 47 0 0 2257 +388 429 0.999973541566668 -0.0070962795591929 -0.001599682166134 -0.000633232448849534 0.00709989878316163 0.99997222284366 0.00226825447809017 0.000960862919924027 0.00158354156362446 -0.00227955204509506 0.999996148011876 -0.00622092449069862 3.02676449944376e-05 1.51620730357426e-05 -4.2470770434999e-06 3.1453260072556e-06 5.00679712871116e-07 1.45579170274862e-05 1.51620730357426e-05 2.63054865642246e-05 -6.17423303181065e-06 6.422877376334e-06 -4.46757167493702e-07 1.6099584863831e-05 -4.2470770434999e-06 -6.17423303181065e-06 1.13507580022227e-05 7.93321704623936e-07 1.57130347857406e-06 -1.0092788323291e-07 3.1453260072556e-06 6.422877376334e-06 7.93321704623936e-07 3.6698349416078e-05 -1.81121565210823e-06 2.34011100701823e-06 5.00679712871116e-07 -4.46757167493702e-07 1.57130347857406e-06 -1.81121565210823e-06 3.25245583791487e-05 9.3192928691666e-07 1.45579170274862e-05 1.6099584863831e-05 -1.0092788323291e-07 2.34011100701823e-06 9.3192928691666e-07 3.8274942019964e-05 2894 2890 0 6 24 2898 2914 0 33 22 0 0 0 0 0 24 56 0 620 0 46 55 0 0 2394 +388 423 0.999999306901551 0.00061008913395422 0.00100696954590665 -0.00403104192832455 -0.000609585486994614 0.999999689006531 -0.000500392222062258 0.00296061745893816 -0.00100727451660309 0.000499778041220155 0.999999367809779 -0.00555253829499664 2.63058971792434e-05 1.8767713686954e-05 -8.61456438021947e-06 8.60141708911503e-06 6.94123778152995e-06 1.88485900467696e-05 1.8767713686954e-05 2.37789523592398e-05 -1.03425483233938e-05 8.80426953175014e-06 3.26126356425016e-06 2.16277964093126e-05 -8.61456438021947e-06 -1.03425483233938e-05 1.40575027947612e-05 -1.5479003561137e-06 -1.67684824904744e-06 -4.41791487925622e-06 8.60141708911503e-06 8.80426953175014e-06 -1.5479003561137e-06 3.07564239565415e-05 4.04248726240769e-07 8.61065195581045e-06 6.94123778152995e-06 3.26126356425016e-06 -1.67684824904744e-06 4.04248726240769e-07 3.5639589551589e-05 1.82777723510915e-06 1.88485900467696e-05 2.16277964093126e-05 -4.41791487925622e-06 8.61065195581045e-06 1.82777723510915e-06 4.21785439876863e-05 2864 2865 0 15 12 2867 2895 0 49 12 0 0 0 0 0 18 49 0 628 0 51 64 0 0 2235 +389 392 0.999999392837047 1.39139000008954e-05 -0.00110187655423198 -0.00664853268423939 -1.38039274485867e-05 0.999999994923475 9.98123269665164e-05 0.00855872356020808 0.00110187793741701 -9.97970561401573e-05 0.999999387952592 0.00553925157288965 1.97058743298057e-05 1.36676069788089e-05 -5.93950763250127e-07 5.4427134059409e-07 1.76997306923261e-06 1.03898847393407e-05 1.36676069788089e-05 2.05769148976613e-05 -2.38283121754572e-06 -9.06091856207744e-08 7.76937493611655e-07 1.15250836629278e-05 -5.93950763250127e-07 -2.38283121754572e-06 8.6556583206545e-06 1.61648265208071e-06 3.11989408849797e-06 -8.29583621889594e-07 5.4427134059409e-07 -9.06091856207744e-08 1.61648265208071e-06 3.28498085400278e-05 -1.06879728987269e-05 2.04911879584786e-06 1.76997306923261e-06 7.76937493611655e-07 3.11989408849797e-06 -1.06879728987269e-05 2.97082827253298e-05 5.56135411827181e-06 1.03898847393407e-05 1.15250836629278e-05 -8.29583621889594e-07 2.04911879584786e-06 5.56135411827181e-06 3.36332931231128e-05 2139 2120 0 22 52 2112 2138 0 48 27 0 0 0 0 0 18 50 0 424 0 75 61 0 0 2289 +389 426 0.999998959055916 0.000586954785436366 0.00131809376123941 -0.00555507858852284 -0.000589859359788796 0.999997396536287 0.00220431090924278 0.0125975178235633 -0.00131679649879336 -0.00220508610462053 0.999996701815687 -0.00249941306032109 3.69519608177909e-05 7.43354116027142e-06 -2.3441124390995e-06 -9.90645230628333e-07 -3.91145333385052e-06 1.20186914853424e-05 7.43354116027142e-06 2.14904467874506e-05 -4.44216931938008e-06 2.35423398300419e-06 1.86668930376576e-06 1.45094923578137e-05 -2.3441124390995e-06 -4.44216931938008e-06 9.04544822971748e-06 2.86892142970655e-06 3.77934274795155e-06 -3.13902016521212e-07 -9.90645230628333e-07 2.35423398300419e-06 2.86892142970655e-06 2.76305599070865e-05 6.63750858958093e-06 1.85497374991092e-06 -3.91145333385052e-06 1.86668930376576e-06 3.77934274795155e-06 6.63750858958093e-06 2.78000561706483e-05 2.57060817657068e-06 1.20186914853424e-05 1.45094923578137e-05 -3.13902016521212e-07 1.85497374991092e-06 2.57060817657068e-06 4.02388015655644e-05 2880 2885 0 20 17 2872 2900 0 41 13 0 0 0 0 0 18 48 0 563 0 16 20 0 0 2191 +389 427 0.999999280499801 0.000350593625242079 -0.00114720703925495 -0.00591030144379739 -0.000347852537194488 0.999997086585681 0.00238868557226843 0.0131938898983486 0.00114804115489988 -0.00238828479472939 0.99999648904246 0.000458794514511921 4.9573011449903e-05 -7.01376014754702e-07 -1.50138846241223e-06 -2.37045945439433e-06 -1.19498089652051e-05 -6.75923266663007e-08 -7.01376014754702e-07 3.4419992012666e-05 -4.5880807205884e-06 5.85375827563465e-06 7.73212753414486e-06 1.78520393659793e-05 -1.50138846241223e-06 -4.5880807205884e-06 1.03606296064045e-05 4.74659891747258e-06 1.93551717360593e-06 1.16437033255208e-06 -2.37045945439433e-06 5.85375827563465e-06 4.74659891747258e-06 3.08757533691821e-05 -7.97376419555718e-07 8.82963510957864e-06 -1.19498089652051e-05 7.73212753414486e-06 1.93551717360593e-06 -7.97376419555718e-07 3.97839975126792e-05 2.13511329968728e-06 -6.75923266663007e-08 1.78520393659793e-05 1.16437033255208e-06 8.82963510957864e-06 2.13511329968728e-06 3.99215364640768e-05 2134 2130 0 17 17 2124 2147 0 40 13 0 0 0 0 0 22 53 0 559 0 42 47 0 0 2420 +389 418 0.999999432274967 0.000176026839658829 0.00105093496280318 -0.00395216056936511 -0.000177792888889552 0.999998571988262 0.00168059844248654 0.00863938948103789 -0.00105063763162315 -0.0016807843371318 0.99999803556036 -0.00340150523102249 2.26200282571999e-05 1.2105969059954e-05 -2.97104359316494e-06 1.03508024155375e-06 3.94495062891737e-07 1.51003096229827e-05 1.2105969059954e-05 2.12058709373672e-05 -4.85943051283772e-06 -2.65493611172483e-07 2.05292896075045e-06 1.42666962034895e-05 -2.97104359316494e-06 -4.85943051283772e-06 1.05289087731136e-05 4.26652843864909e-06 2.48028676382691e-06 -6.43333964100384e-07 1.03508024155375e-06 -2.65493611172483e-07 4.26652843864909e-06 2.0783159543821e-05 -1.14394486836682e-07 2.88022234664007e-06 3.94495062891737e-07 2.05292896075045e-06 2.48028676382691e-06 -1.14394486836682e-07 2.86949901793242e-05 -1.22748383128119e-06 1.51003096229827e-05 1.42666962034895e-05 -6.43333964100384e-07 2.88022234664007e-06 -1.22748383128119e-06 3.70447533075697e-05 2910 2908 0 12 13 2907 2943 0 44 10 0 0 0 0 0 16 48 0 554 0 15 19 0 0 2199 +389 415 0.999997110356809 0.000103084052467981 -0.00240180176334287 -0.00807400729767746 -0.000102691130687771 0.999999981325582 0.00016371734000023 0.00864911593999684 0.00240181859513749 -0.000163470223176768 0.999997102268263 0.00225066944325907 4.31508800096096e-05 1.26080212589901e-05 -2.75821209731856e-06 3.9714216348702e-06 -7.03551725006842e-06 1.50685124739074e-05 1.26080212589901e-05 3.12741419887164e-05 -7.48172631311283e-06 5.70330270148081e-06 4.20139693930288e-06 1.9515500320245e-05 -2.75821209731856e-06 -7.48172631311283e-06 1.10901618164458e-05 2.98441582580496e-06 2.94541850416277e-06 -5.65470162058736e-07 3.9714216348702e-06 5.70330270148081e-06 2.98441582580496e-06 2.93789206872504e-05 -2.76620828079343e-06 5.61395171701859e-06 -7.03551725006842e-06 4.20139693930288e-06 2.94541850416277e-06 -2.76620828079343e-06 3.03957566336151e-05 -4.65776100760442e-08 1.50685124739074e-05 1.9515500320245e-05 -5.65470162058736e-07 5.61395171701859e-06 -4.65776100760442e-08 3.87349491780005e-05 2141 2145 0 18 14 2132 2157 0 41 8 0 0 0 0 0 22 53 0 533 0 40 46 0 0 2238 +389 419 0.999992182182881 0.000771024106641887 -0.00387828505231888 -0.00911784768733807 -0.000758216872799577 0.999994258689278 0.00330268007157672 0.0113435002162664 0.00388080923183103 -0.00329971367066372 0.99998702552053 -0.00074947485713478 5.76508516496033e-05 2.39464926740684e-05 -5.86020042068359e-06 2.91720333095822e-06 -5.18686958247139e-06 2.42577623442465e-05 2.39464926740684e-05 3.70467396812424e-05 -7.2544753215854e-06 5.693109579007e-06 1.30665036222792e-06 3.09407548818046e-05 -5.86020042068359e-06 -7.2544753215854e-06 1.18553820962741e-05 3.54230785398417e-06 2.78466351248193e-06 5.77482380975924e-07 2.91720333095822e-06 5.693109579007e-06 3.54230785398417e-06 2.45557548538018e-05 -9.68966505351681e-07 7.60436760730922e-06 -5.18686958247139e-06 1.30665036222792e-06 2.78466351248193e-06 -9.68966505351681e-07 2.94915670997225e-05 -1.2188873511481e-06 2.42577623442465e-05 3.09407548818046e-05 5.77482380975924e-07 7.60436760730922e-06 -1.2188873511481e-06 5.84567461604481e-05 2966 2967 0 17 14 2960 2989 0 48 11 0 0 0 0 0 15 47 0 541 0 35 42 0 0 2265 +389 421 0.999998878629605 0.000473871538207757 0.00142062848672817 -0.00407944847746178 -0.000478576739950721 0.999994395665959 0.00331354809476634 0.0108425862720017 -0.001419050328919 -0.00331422425880147 0.999993501085745 -0.00278076120281729 3.03569828896475e-05 8.87547750822071e-06 -3.57722225678357e-06 -8.76635111901128e-07 -1.43834155838006e-06 1.0530423468705e-05 8.87547750822071e-06 2.16743474235358e-05 -5.27876672529545e-06 1.90005487083029e-06 3.1794512111324e-06 1.39133720248809e-05 -3.57722225678357e-06 -5.27876672529545e-06 1.02056025725103e-05 3.87038232548212e-06 2.16311198647981e-06 5.76569212658372e-09 -8.76635111901128e-07 1.90005487083029e-06 3.87038232548212e-06 1.84633414692202e-05 4.99697623563947e-06 2.70080741935447e-06 -1.43834155838006e-06 3.1794512111324e-06 2.16311198647981e-06 4.99697623563947e-06 2.73221385311365e-05 8.79558853108551e-07 1.0530423468705e-05 1.39133720248809e-05 5.76569212658372e-09 2.70080741935447e-06 8.79558853108551e-07 3.5645992163585e-05 2889 2895 0 19 14 2884 2921 0 52 11 0 0 0 0 0 15 48 0 557 0 15 20 0 0 2306 +389 423 0.999999771555511 0.000327969560679431 -0.000591037132913587 -0.00632458346460273 -0.000327743890937267 0.999999873377201 0.000381876319536702 0.00723274306794953 0.000591162301883564 -0.000381682523489531 0.999999752422761 -0.00313313374142013 2.9886029605953e-05 1.02078451952943e-05 -4.24964367583328e-06 2.44194785023963e-06 3.31776055400377e-06 1.00375335782976e-05 1.02078451952943e-05 2.25607616005077e-05 -5.84962571067283e-06 2.27646816109682e-06 2.32577452868967e-06 1.59220075151811e-05 -4.24964367583328e-06 -5.84962571067283e-06 1.02740819577017e-05 2.88660113464221e-06 3.00726501810147e-06 -4.91229297348532e-08 2.44194785023963e-06 2.27646816109682e-06 2.88660113464221e-06 2.31236741302312e-05 1.68771982187134e-06 6.4480032422466e-06 3.31776055400377e-06 2.32577452868967e-06 3.00726501810147e-06 1.68771982187134e-06 2.22793430778856e-05 2.85940201906897e-06 1.00375335782976e-05 1.59220075151811e-05 -4.91229297348532e-08 6.4480032422466e-06 2.85940201906897e-06 4.07671822191162e-05 3068 3064 0 16 12 3060 3099 0 52 10 0 0 0 0 0 16 48 0 546 0 12 17 0 0 2205 +389 429 0.999976656822662 -0.00648471890886265 -0.00215272628182796 -0.00236404811725885 0.00648793367047712 0.999977843457779 0.00148973494847385 0.00751660171374565 0.00214301807246765 -0.00150366691865395 0.999996573223798 -0.00300378993170587 2.38942683642715e-05 9.42808724935662e-06 -3.24587907028267e-06 1.5291008161151e-07 -9.71625035375297e-07 1.09111098439022e-05 9.42808724935662e-06 1.58704897391274e-05 -6.41108571233954e-06 1.22795015172937e-07 1.03012114721461e-08 9.61060484238924e-06 -3.24587907028267e-06 -6.41108571233954e-06 1.02080318741725e-05 2.42544226257615e-06 9.14173288784291e-07 -7.8364357471383e-07 1.5291008161151e-07 1.22795015172937e-07 2.42544226257615e-06 2.09612587533274e-05 6.0273911404926e-06 7.70969766970445e-07 -9.71625035375297e-07 1.03012114721461e-08 9.14173288784291e-07 6.0273911404926e-06 2.90536124640548e-05 -2.33792191818464e-06 1.09111098439022e-05 9.61060484238924e-06 -7.8364357471383e-07 7.70969766970445e-07 -2.33792191818464e-06 3.63121684145858e-05 3101 3102 0 2 25 3102 3133 0 41 20 0 0 0 0 0 27 59 0 556 0 14 15 0 0 2381 +389 425 0.999999839343779 0.000418062840123268 -0.000382800050702452 -0.00933973503056541 -0.000417817792186691 0.999999707912568 0.000640002398781613 0.00903695463008423 0.000383067500111888 -0.000639842355289212 0.999999721930487 -0.00521778494329698 3.71353142030647e-05 9.39007099537967e-06 -3.37761535581995e-06 -2.1296904307509e-06 1.36550772834841e-06 8.94600600856305e-06 9.39007099537967e-06 2.91743363593679e-05 -5.09895403178832e-06 5.59062474101564e-06 4.00234786267593e-06 1.9720101184995e-05 -3.37761535581995e-06 -5.09895403178832e-06 1.24188599837889e-05 2.96423818599835e-06 2.16354464058159e-06 1.14781675501137e-06 -2.1296904307509e-06 5.59062474101564e-06 2.96423818599835e-06 3.22201633383529e-05 -7.94885760478018e-06 5.74103720424234e-06 1.36550772834841e-06 4.00234786267593e-06 2.16354464058159e-06 -7.94885760478018e-06 3.69306533032609e-05 2.48900221382292e-06 8.94600600856305e-06 1.9720101184995e-05 1.14781675501137e-06 5.74103720424234e-06 2.48900221382292e-06 4.14500372119374e-05 2819 2815 0 19 16 2815 2844 0 52 15 0 0 0 0 0 23 53 0 550 0 43 46 0 0 2054 +389 420 0.999999806343585 0.000381292458700843 0.00049186263578979 -0.00221152331198982 -0.000381612978786829 0.999999714818626 0.000651716349987021 0.00608227431628339 -0.000491614000990266 -0.000651903924943567 0.999999666668418 -0.00242916184218451 3.26484118270524e-05 1.08770187368983e-05 -2.81454646928386e-06 3.85083379239527e-06 -1.58437109573588e-06 1.30888007598938e-05 1.08770187368983e-05 2.14171333946111e-05 -4.96593867075481e-06 7.15107600138624e-07 6.93323871579327e-07 1.56028537786751e-05 -2.81454646928386e-06 -4.96593867075481e-06 9.29552353963378e-06 3.96570320249909e-06 2.31924936468733e-06 3.42438878355463e-07 3.85083379239527e-06 7.15107600138624e-07 3.96570320249909e-06 2.22605031278155e-05 1.82836409094528e-06 1.75697105443839e-06 -1.58437109573588e-06 6.93323871579327e-07 2.31924936468733e-06 1.82836409094528e-06 2.45911078739977e-05 -1.43467095783539e-06 1.30888007598938e-05 1.56028537786751e-05 3.42438878355463e-07 1.75697105443839e-06 -1.43467095783539e-06 4.36469755670751e-05 2221 2217 0 12 11 2215 2243 0 38 9 0 0 0 0 0 15 46 0 572 0 13 16 0 0 2329 +389 416 0.999999064147384 0.000857121338321465 -0.00106632423216385 -0.0109667110189261 -0.000851136977853787 0.999983957700935 0.00559999166246406 0.0145012067600101 0.00107110699821993 -0.00559907883371284 0.999983751390997 -0.00317501585455746 6.26317811786109e-05 2.62514783908278e-05 -6.33207111969972e-06 9.05832297264921e-06 -1.237351684782e-05 1.86924132420614e-05 2.62514783908278e-05 7.09294186633827e-05 -9.20477681612605e-06 2.68304286423702e-05 -2.35163368759637e-06 3.80347201283246e-05 -6.33207111969972e-06 -9.20477681612605e-06 1.26939462101862e-05 1.50145420387117e-06 1.76564771240672e-06 -2.9810757642452e-06 9.05832297264921e-06 2.68304286423702e-05 1.50145420387117e-06 4.51768389365413e-05 -1.82765061710617e-05 1.32641539059944e-05 -1.237351684782e-05 -2.35163368759637e-06 1.76564771240672e-06 -1.82765061710617e-05 4.62199762084772e-05 -2.57368166622649e-06 1.86924132420614e-05 3.80347201283246e-05 -2.9810757642452e-06 1.32641539059944e-05 -2.57368166622649e-06 5.81112499322614e-05 2124 2127 0 23 12 2113 2139 0 46 9 0 0 0 0 0 24 55 0 556 0 88 99 0 0 2217 +390 392 0.999999978993356 7.65276859899368e-05 0.00019014941472109 -0.00636083090950436 -7.66623207335934e-05 0.999999746329763 0.000708140733603048 0.00793151854953224 -0.000190095174114145 -0.000708155296022806 0.999999731189915 -0.00226639541056761 1.97472013820773e-05 7.28003265274509e-06 3.81464923720318e-08 -1.92723144248179e-07 9.07262664068548e-07 3.56070917486758e-06 7.28003265274509e-06 2.10481955723488e-05 -3.81377695534794e-06 4.91155909583149e-06 -2.73215201826204e-06 6.0098037104654e-06 3.81464923720318e-08 -3.81377695534794e-06 9.03935185189931e-06 2.76165809352323e-06 4.63994508008295e-06 5.58877478727251e-07 -1.92723144248179e-07 4.91155909583149e-06 2.76165809352323e-06 3.26498534573442e-05 -9.48996139878828e-06 3.89783374840941e-06 9.07262664068548e-07 -2.73215201826204e-06 4.63994508008295e-06 -9.48996139878828e-06 2.80895668286108e-05 -7.12592715619915e-06 3.56070917486758e-06 6.0098037104654e-06 5.58877478727251e-07 3.89783374840941e-06 -7.12592715619915e-06 3.23496711774648e-05 2743 2720 0 13 56 2722 2746 0 43 28 0 0 0 0 0 20 52 0 416 0 84 69 0 0 2312 +390 393 0.999999146556297 -0.000171862625328918 0.0012951254443352 -0.00615081865237749 0.000169029107121358 0.999997592860169 0.0021876249744061 0.00762105905429747 -0.00129549829775849 -0.00218740419349387 0.999996768468306 -0.0017432998745809 3.08918473656067e-05 5.24302844490164e-06 -9.25586731789869e-08 2.26649428243236e-06 -6.36832649810504e-06 5.38279222343398e-06 5.24302844490164e-06 2.26025588052086e-05 -2.65723685246691e-06 2.86092590940146e-06 -7.55427311376776e-07 1.0997120069574e-05 -9.25586731789869e-08 -2.65723685246691e-06 1.21531473675821e-05 3.13306252989565e-06 3.76672106673791e-06 1.00220585459584e-06 2.26649428243236e-06 2.86092590940146e-06 3.13306252989565e-06 3.04241889254501e-05 -1.16623470601513e-05 3.15321583780161e-06 -6.36832649810504e-06 -7.55427311376776e-07 3.76672106673791e-06 -1.16623470601513e-05 3.58947735592773e-05 -2.9018687258996e-06 5.38279222343398e-06 1.0997120069574e-05 1.00220585459584e-06 3.15321583780161e-06 -2.9018687258996e-06 3.17309018927075e-05 2824 2810 0 16 46 2813 2851 0 48 30 0 0 0 0 0 17 47 0 428 0 49 29 0 0 2358 +390 428 0.999996857300033 0.00086167135774306 -0.00235433908536126 -0.00454874194563084 -0.000859916589819984 0.99999935183132 0.00074624419458225 0.0113591259999231 0.00235498057660076 -0.000744217314123081 0.999996950098886 -0.00158274928260714 2.83865604332664e-05 1.51941421640269e-05 -1.69700664531393e-06 3.89094792481601e-06 -8.97605638055576e-07 1.55025758111347e-05 1.51941421640269e-05 2.15921515716101e-05 -4.90966336182856e-06 3.36361222032607e-06 -5.46674033418331e-06 1.75322087232271e-05 -1.69700664531393e-06 -4.90966336182856e-06 1.07755596388472e-05 3.66361283379561e-06 1.53849554376854e-06 2.1655981502524e-06 3.89094792481601e-06 3.36361222032607e-06 3.66361283379561e-06 2.5437075174873e-05 1.12399211115283e-06 6.303339136133e-06 -8.97605638055576e-07 -5.46674033418331e-06 1.53849554376854e-06 1.12399211115283e-06 3.27721566082425e-05 -9.68927074157755e-06 1.55025758111347e-05 1.75322087232271e-05 2.1655981502524e-06 6.303339136133e-06 -9.68927074157755e-06 4.86440291831273e-05 2926 2923 0 15 16 2922 2951 0 46 14 0 0 0 0 0 13 46 0 486 0 44 50 0 0 2352 +389 424 0.999997410936053 0.000207296620672171 0.00226608678176989 -0.00508023331181034 -0.000209486295945061 0.999999511396772 0.000966085766389816 0.00974620223371754 -0.00226588540823793 -0.000966557979258191 0.999996965759891 -0.00512319099886415 3.47758272175113e-05 1.71038435924519e-05 -3.66709006450697e-06 9.22514039270655e-07 1.30824436919223e-06 1.99143893884611e-05 1.71038435924519e-05 2.75112093332823e-05 -5.50515573030748e-06 3.50130224409265e-06 6.21251243235145e-06 1.88790600962031e-05 -3.66709006450697e-06 -5.50515573030748e-06 1.14560461698589e-05 2.36502643952994e-06 2.91730042371456e-06 6.38213477669889e-08 9.22514039270655e-07 3.50130224409265e-06 2.36502643952994e-06 2.69273737140674e-05 -3.66624716429437e-06 3.40669626916038e-06 1.30824436919223e-06 6.21251243235145e-06 2.91730042371456e-06 -3.66624716429437e-06 4.05180146192923e-05 7.18866589791643e-06 1.99143893884611e-05 1.88790600962031e-05 6.38213477669889e-08 3.40669626916038e-06 7.18866589791643e-06 4.22334845957377e-05 2603 2606 0 16 15 2604 2627 0 38 14 0 0 0 0 0 17 47 0 551 0 40 43 0 0 2205 +390 420 0.999999745071353 0.000600311390737504 0.000386630912280026 -0.00281398201892158 -0.000600647480690174 0.999999441378747 0.000869749847828879 0.00815562244584135 -0.000386108575559038 -0.000869981854988145 0.999999547025767 -0.00254396374130403 2.55630974270513e-05 7.55979875808496e-06 -1.94593606446299e-06 -5.12080030229105e-07 -4.75010960667962e-07 9.51287404363262e-06 7.55979875808496e-06 2.20620808601809e-05 -5.37137384488117e-06 -3.38047116343444e-07 1.04614316070613e-06 1.23325045502402e-05 -1.94593606446299e-06 -5.37137384488117e-06 1.1112729021269e-05 4.48956277690911e-06 2.07614484307765e-06 2.39046381686573e-07 -5.12080030229105e-07 -3.38047116343444e-07 4.48956277690911e-06 2.52033112188232e-05 3.1219829429323e-06 1.57859693369799e-06 -4.75010960667962e-07 1.04614316070613e-06 2.07614484307765e-06 3.1219829429323e-06 3.23222518895897e-05 3.99236389171213e-06 9.51287404363262e-06 1.23325045502402e-05 2.39046381686573e-07 1.57859693369799e-06 3.99236389171213e-06 3.96118351963275e-05 2714 2712 0 15 11 2706 2733 0 37 9 0 0 0 0 0 16 47 0 507 0 13 16 0 0 2277 +390 429 0.999973420859744 -0.00703400507256529 -0.00191842297214682 -0.00266831561362556 0.00703970151942784 0.999970783868204 0.00297892808349866 0.0104992254316701 0.00189741312799829 -0.00299235403126324 0.999993722800685 -0.00400157634253306 2.38921577719389e-05 5.90808022599116e-06 -1.14070787294226e-06 -1.29475956876636e-06 -2.16121315210747e-06 7.14213897967045e-06 5.90808022599116e-06 1.83579172561416e-05 -4.39498389802434e-06 1.1338869361169e-07 -2.2816257798818e-07 6.72132632003156e-06 -1.14070787294226e-06 -4.39498389802434e-06 8.78452061177302e-06 2.70178190389796e-06 2.21143624648769e-06 2.35181031944086e-06 -1.29475956876636e-06 1.1338869361169e-07 2.70178190389796e-06 2.98684954735789e-05 9.07623456648991e-07 2.70685386063994e-06 -2.16121315210747e-06 -2.2816257798818e-07 2.21143624648769e-06 9.07623456648991e-07 3.73408795557667e-05 -5.1586124375365e-06 7.14213897967045e-06 6.72132632003156e-06 2.35181031944086e-06 2.70685386063994e-06 -5.1586124375365e-06 3.89993498526354e-05 2823 2822 0 6 25 2823 2855 0 42 21 0 0 0 0 0 19 51 0 479 0 14 14 0 0 2448 +390 421 0.999999820165315 0.000458992885788468 -0.000385998534853214 -0.00243956611480145 -0.000459001448597072 0.99999989441473 -2.20952318218599e-05 0.00523297407475258 0.000385988352543238 2.22724017350248e-05 0.999999925258463 -0.0017555071212519 1.77219970212299e-05 6.9460607731562e-06 -7.56224415266997e-07 1.56569289001628e-06 1.81948862235644e-06 5.55370252548573e-06 6.9460607731562e-06 1.47971358438152e-05 -4.48956900674674e-06 -5.890475441152e-07 -1.68995381211826e-07 9.11185125779165e-06 -7.56224415266997e-07 -4.48956900674674e-06 9.70426643962875e-06 3.67976258249433e-06 1.94544831338254e-06 -6.24688622893848e-09 1.56569289001628e-06 -5.890475441152e-07 3.67976258249433e-06 1.90790508255035e-05 4.13326702496534e-06 2.30453793799053e-06 1.81948862235644e-06 -1.68995381211826e-07 1.94544831338254e-06 4.13326702496534e-06 2.46989245405939e-05 3.48949266946191e-06 5.55370252548573e-06 9.11185125779165e-06 -6.24688622893848e-09 2.30453793799053e-06 3.48949266946191e-06 3.04617767034921e-05 3040 3037 0 16 14 3033 3068 0 54 11 0 0 0 0 0 10 43 0 494 0 15 19 0 0 2333 +390 394 0.999990246206871 -0.000496101334730567 0.00438877825687737 -0.00482897786468512 0.000485062319847924 0.99999671725174 0.00251598892859747 0.00841966934964452 -0.00439001203508883 -0.00251383555719937 0.999987204130694 -0.004672521110519 3.4825328282115e-05 7.62409810147188e-07 1.72849876116384e-07 -4.84388383234331e-06 -4.12116335554913e-06 5.13935160016633e-06 7.62409810147188e-07 2.55648732467048e-05 -2.34313939993791e-06 5.55677867387207e-06 8.66188320685757e-07 1.10611497055156e-05 1.72849876116384e-07 -2.34313939993791e-06 1.01317166482509e-05 1.6304922613766e-06 5.98909654455052e-06 1.06717427500815e-06 -4.84388383234331e-06 5.55677867387207e-06 1.6304922613766e-06 3.87222084805458e-05 -1.62396061419766e-05 2.74984632326694e-06 -4.12116335554913e-06 8.66188320685757e-07 5.98909654455052e-06 -1.62396061419766e-05 4.13651308739209e-05 -1.5530598749955e-06 5.13935160016633e-06 1.10611497055156e-05 1.06717427500815e-06 2.74984632326694e-06 -1.5530598749955e-06 3.37800259050503e-05 2617 2600 0 13 44 2592 2622 0 48 20 0 0 0 0 0 22 54 0 442 0 72 56 0 0 2527 +390 425 0.999992620625114 0.00128928765712714 0.00361889937053643 -0.00993683890423507 -0.00130451433285135 0.99999029400657 0.00420834112311225 0.0174856504341092 -0.00361343848325591 -0.00421303097428347 0.999984596597536 -0.00518109575393445 5.37272400303036e-05 1.27032531302751e-05 -2.55972289784353e-06 7.88817155938265e-06 -1.34035527243802e-05 1.04717186559431e-05 1.27032531302751e-05 3.98916979398095e-05 -6.26664646256566e-06 9.2231804771136e-07 4.5085539651168e-06 1.46235753560071e-05 -2.55972289784353e-06 -6.26664646256566e-06 1.32556151227646e-05 3.15826398407245e-06 4.03948187236913e-06 6.83825980470302e-07 7.88817155938265e-06 9.2231804771136e-07 3.15826398407245e-06 3.95022575088367e-05 -2.3122418581556e-05 3.34282697506393e-06 -1.34035527243802e-05 4.5085539651168e-06 4.03948187236913e-06 -2.3122418581556e-05 5.62554360935982e-05 -2.54568507793275e-06 1.04717186559431e-05 1.46235753560071e-05 6.83825980470302e-07 3.34282697506393e-06 -2.54568507793275e-06 4.56756924096378e-05 2499 2501 0 18 16 2500 2528 0 48 15 0 0 0 0 0 22 51 0 495 0 41 44 0 0 1995 +390 423 0.999999817001781 0.000489412200564604 -0.000355629162789817 -0.00700827153948482 -0.000489065333767102 0.999999405295521 0.000974794185156798 0.0094611740911488 0.000356106027462816 -0.000974620080876002 0.999999461651953 -0.00204687627390243 2.42829555674398e-05 6.76545210123234e-06 -2.23599391939136e-06 5.6743582813225e-07 -3.54592902061846e-07 1.03600733388415e-05 6.76545210123234e-06 2.15994843968679e-05 -5.68948205911511e-06 -3.43205723303076e-06 2.45859413883837e-06 8.33381119027002e-06 -2.23599391939136e-06 -5.68948205911511e-06 1.14121484096788e-05 3.93812394092808e-06 1.55969021639912e-06 -2.24926576434523e-07 5.6743582813225e-07 -3.43205723303076e-06 3.93812394092808e-06 2.62408725294733e-05 -4.33444304960525e-06 1.66313881218191e-06 -3.54592902061846e-07 2.45859413883837e-06 1.55969021639912e-06 -4.33444304960525e-06 3.16549669037154e-05 -1.96516886182996e-06 1.03600733388415e-05 8.33381119027002e-06 -2.24926576434523e-07 1.66313881218191e-06 -1.96516886182996e-06 3.3402239019134e-05 2762 2764 0 20 12 2757 2793 0 46 10 0 0 0 0 0 13 43 0 485 0 12 15 0 0 2256 +390 424 0.999999895498257 0.000454904244287483 -4.54489176991397e-05 -0.0065582115409929 -0.000454917613719993 0.999999853133946 -0.000294587935117338 0.0069466571523064 4.53149017222357e-05 0.000294608579845572 0.999999955576171 -0.00338058853627213 2.42902542519223e-05 1.42231865429853e-05 -1.10093840695926e-06 8.12091844944523e-07 3.45207859096081e-06 1.02781891601732e-05 1.42231865429853e-05 2.3322784096774e-05 -4.47746032593816e-06 2.90932771016846e-07 -6.51087367524915e-08 1.72538910473848e-05 -1.10093840695926e-06 -4.47746032593816e-06 1.26533830630692e-05 3.10079395394797e-06 2.83846580332777e-06 1.77930571319835e-06 8.12091844944523e-07 2.90932771016846e-07 3.10079395394797e-06 2.8560168634686e-05 -9.90104674837442e-06 5.13381011097469e-06 3.45207859096081e-06 -6.51087367524915e-08 2.83846580332777e-06 -9.90104674837442e-06 3.55701416297088e-05 2.54650873073371e-06 1.02781891601732e-05 1.72538910473848e-05 1.77930571319835e-06 5.13381011097469e-06 2.54650873073371e-06 4.07543054385667e-05 2709 2710 0 14 15 2711 2740 0 45 14 0 0 0 0 0 12 42 0 497 0 39 42 0 0 2233 +390 427 0.9999987061634 0.000379600345721157 -0.00156319387877152 -0.00508070946808713 -0.00037690325651627 0.99999844063351 0.00172530417159472 0.00931140650398598 0.00156384636723938 -0.00172471276646956 0.999997289871534 -0.00207702900308519 3.65331709357633e-05 1.15032438110714e-05 -2.77043462433392e-06 1.33374828886618e-06 -4.00926374833244e-06 1.01849878641272e-05 1.15032438110714e-05 2.50063317815269e-05 -6.41298735335902e-06 1.68208435966422e-07 1.15206097547642e-06 1.22781373348452e-05 -2.77043462433392e-06 -6.41298735335902e-06 1.31413559786733e-05 3.62380259927685e-06 2.65312347534158e-06 1.76686264058565e-06 1.33374828886618e-06 1.68208435966422e-07 3.62380259927685e-06 2.50895676335991e-05 -4.27320275723852e-07 1.68746713285261e-06 -4.00926374833244e-06 1.15206097547642e-06 2.65312347534158e-06 -4.27320275723852e-07 3.73278434636176e-05 -2.04024726492063e-06 1.01849878641272e-05 1.22781373348452e-05 1.76686264058565e-06 1.68746713285261e-06 -2.04024726492063e-06 4.09452279363938e-05 2752 2754 0 17 17 2748 2769 0 43 11 0 0 0 0 0 17 47 0 486 0 49 53 0 0 2332 +390 426 0.999999663473642 0.000819991430619562 -2.58196976489709e-05 -0.00228001782578209 -0.00081999183416707 0.999999663684604 -1.56227385065602e-05 0.00653233991169011 2.58068784537109e-05 1.56439051903297e-05 0.999999999544637 -0.00209398761616428 1.88354842990709e-05 6.34085750719537e-06 -2.65793991884841e-06 1.08758841905351e-07 1.91567091212392e-06 4.18729261155206e-06 6.34085750719537e-06 1.5026955882704e-05 -5.10448432891635e-06 -2.02018913297875e-06 -2.07967904251968e-06 9.28758417563626e-06 -2.65793991884841e-06 -5.10448432891635e-06 1.17386438892688e-05 5.13894927694444e-06 2.40262282595802e-06 -6.10073136195634e-07 1.08758841905351e-07 -2.02018913297875e-06 5.13894927694444e-06 2.01133088351288e-05 5.05358996044468e-06 3.87151216952192e-06 1.91567091212392e-06 -2.07967904251968e-06 2.40262282595802e-06 5.05358996044468e-06 2.64223677096403e-05 3.96548344622728e-06 4.18729261155206e-06 9.28758417563626e-06 -6.10073136195634e-07 3.87151216952192e-06 3.96548344622728e-06 3.69476942155654e-05 2978 2974 0 18 17 2968 2996 0 43 13 0 0 0 0 0 15 45 0 491 0 16 19 0 0 2092 +390 419 0.999999053107444 0.000371486665896702 -0.00132505919584945 -0.00857429033557019 -0.000368474337191885 0.999997349131273 0.00227287419118588 0.0131594976218949 0.00132590002574676 -0.0022723837887093 0.99999653912453 -0.0005349493830603 3.51314423762832e-05 1.09307983413663e-05 -2.46462146954698e-06 3.6664101724993e-07 -3.48810589977879e-08 1.4559729162092e-05 1.09307983413663e-05 2.48183566117934e-05 -5.08863361283288e-06 2.26078756447932e-06 3.91143867964448e-07 9.50073119541301e-06 -2.46462146954698e-06 -5.08863361283288e-06 1.24635550440144e-05 3.94835730653464e-06 -8.08520412091816e-08 3.37176960644119e-07 3.6664101724993e-07 2.26078756447932e-06 3.94835730653464e-06 3.45057323298125e-05 -1.72049318744184e-05 4.99316624600186e-06 -3.48810589977879e-08 3.91143867964448e-07 -8.08520412091816e-08 -1.72049318744184e-05 4.8158549662218e-05 -7.52448239653113e-06 1.4559729162092e-05 9.50073119541301e-06 3.37176960644119e-07 4.99316624600186e-06 -7.52448239653113e-06 3.83026794167796e-05 2715 2712 0 15 14 2708 2734 0 44 11 0 0 0 0 0 15 47 0 480 0 42 48 0 0 2248 +391 395 0.999999428366087 -8.85191138962762e-06 0.00106920023556058 -0.00113349026805257 7.56349614421256e-06 0.999999273928364 0.00120502511970422 0.000803318217160581 -0.0010692101260202 -0.00120501634397914 0.999998702361817 -0.00134970923876727 2.3268052248557e-05 3.67013566443934e-06 6.15247444737637e-07 -2.15041665755054e-06 -2.1917267465178e-06 6.17388045789361e-06 3.67013566443934e-06 1.95322878578689e-05 -2.43469050193141e-06 8.34727634054325e-07 1.5352128293922e-07 8.93622619136198e-06 6.15247444737637e-07 -2.43469050193141e-06 9.04858165242636e-06 5.31751206743777e-06 4.06958694423753e-06 1.46921314190794e-06 -2.15041665755054e-06 8.34727634054325e-07 5.31751206743777e-06 2.36288600338091e-05 8.09791775085888e-07 -2.44230441077213e-07 -2.1917267465178e-06 1.5352128293922e-07 4.06958694423753e-06 8.09791775085888e-07 2.35664138843522e-05 4.63788000914907e-07 6.17388045789361e-06 8.93622619136198e-06 1.46921314190794e-06 -2.44230441077213e-07 4.63788000914907e-07 3.02510410269924e-05 2555 2544 0 28 53 2535 2578 0 45 30 0 0 0 0 0 14 45 0 421 0 51 33 0 0 2541 +390 416 0.999998379475185 0.000674413539324349 0.00166919542963745 -0.00802282774206519 -0.000680137377041061 0.999993883112951 0.00343091093288167 0.0138284677644223 -0.0016668713665722 -0.00343204065520665 0.999992721291904 -0.00492524801384547 3.35076584140882e-05 3.2174277080178e-06 -1.77088812125605e-06 -9.79304199825899e-07 -2.48980770921719e-06 3.95775412745144e-06 3.2174277080178e-06 2.82863204610782e-05 -5.05291730284152e-06 2.98085025583108e-06 6.42720354566097e-06 6.89405107279234e-06 -1.77088812125605e-06 -5.05291730284152e-06 1.17577339063053e-05 3.17444142775876e-06 3.39248900793508e-06 1.14682374121499e-06 -9.79304199825899e-07 2.98085025583108e-06 3.17444142775876e-06 3.51298267549357e-05 -1.57865225059776e-05 1.10377910028129e-06 -2.48980770921719e-06 6.42720354566097e-06 3.39248900793508e-06 -1.57865225059776e-05 5.11758223100735e-05 1.49712469695061e-06 3.95775412745144e-06 6.89405107279234e-06 1.14682374121499e-06 1.10377910028129e-06 1.49712469695061e-06 3.06812348914671e-05 1545 1548 0 20 12 1539 1562 0 41 9 0 0 0 0 0 21 52 0 504 0 42 45 0 0 2317 +390 418 0.999999931223421 0.000179765260068366 -0.000324403458202482 -0.00300533055236322 -0.000179630006972447 0.999999896959703 0.000416909634500677 0.00418499716631624 0.000324478370644725 -0.0004168513332316 0.999999860474367 -0.00183751413389892 1.60098938746566e-05 4.83353345904112e-06 -2.45507158852104e-07 1.97757875412458e-06 2.68551584215176e-06 3.95080139234773e-06 4.83353345904112e-06 1.32797765744312e-05 -4.59402983220728e-06 -2.67920360283086e-06 -9.20403156030052e-07 5.75672780079844e-06 -2.45507158852104e-07 -4.59402983220728e-06 9.41272789752715e-06 2.97695757295915e-06 2.91086432920645e-06 6.56835541617796e-08 1.97757875412458e-06 -2.67920360283086e-06 2.97695757295915e-06 1.76739006847719e-05 2.06649201338974e-06 1.92582839619267e-06 2.68551584215176e-06 -9.20403156030052e-07 2.91086432920645e-06 2.06649201338974e-06 1.93033564220432e-05 1.92826881276455e-06 3.95080139234773e-06 5.75672780079844e-06 6.56835541617796e-08 1.92582839619267e-06 1.92826881276455e-06 2.62556078103799e-05 3117 3116 0 15 13 3114 3147 0 42 11 0 0 0 0 0 15 48 0 503 0 15 18 0 0 2229 +391 428 0.99999874351161 0.000551365108517502 0.00148626098565704 0.00392753915702505 -0.000553191144652173 0.999999092408163 0.00122847971420368 0.000997674861961597 -0.00148558229588777 -0.00122930035704909 0.999998140931209 -0.00320667648149321 1.98495241705301e-05 1.09839557643081e-05 -2.45876311513686e-06 2.55575201387336e-06 1.92541615563557e-06 8.38455391964212e-06 1.09839557643081e-05 2.3603365905763e-05 -5.88782849851021e-06 2.84456030233362e-06 1.07163470749318e-06 1.20751871740698e-05 -2.45876311513686e-06 -5.88782849851021e-06 1.14197668776306e-05 2.96455275736878e-06 1.27621613652459e-06 2.52501495102314e-06 2.55575201387336e-06 2.84456030233362e-06 2.96455275736878e-06 3.28120640224773e-05 -3.95155469344444e-07 8.35030842980389e-06 1.92541615563557e-06 1.07163470749318e-06 1.27621613652459e-06 -3.95155469344444e-07 3.60846028503432e-05 5.78124381073703e-07 8.38455391964212e-06 1.20751871740698e-05 2.52501495102314e-06 8.35030842980389e-06 5.78124381073703e-07 3.88638483590965e-05 2690 2694 0 21 16 2686 2718 0 45 16 0 0 0 0 0 20 53 0 486 0 46 64 0 0 2329 +391 427 0.999997796510126 0.000295613734100892 0.00207836171388448 0.00426342909531234 -0.000296563186880613 0.999999851813409 0.000456534156395726 -0.000806547376378129 -0.00207822644813243 -0.000457149516000696 0.999997735992012 -0.0016462129947407 2.56762851666219e-05 1.02644844283026e-05 -2.69475201417464e-06 -3.52128124188576e-07 3.08183491028279e-06 8.88746403128279e-06 1.02644844283026e-05 2.18692994513922e-05 -6.4055364622884e-06 3.61732093332275e-06 -3.22556538060273e-06 1.44301647800623e-05 -2.69475201417464e-06 -6.4055364622884e-06 1.23812321362392e-05 2.56758886600298e-06 2.1546419009047e-06 6.45169199140068e-07 -3.52128124188576e-07 3.61732093332275e-06 2.56758886600298e-06 2.50590375888694e-05 -2.14458187359153e-06 6.29129335239517e-06 3.08183491028279e-06 -3.22556538060273e-06 2.1546419009047e-06 -2.14458187359153e-06 3.05010581849149e-05 -1.18660058303632e-06 8.88746403128279e-06 1.44301647800623e-05 6.45169199140068e-07 6.29129335239517e-06 -1.18660058303632e-06 3.81266622888511e-05 2798 2802 0 26 17 2789 2827 0 48 14 0 0 0 0 0 18 49 0 506 0 49 63 0 0 2293 +390 417 0.999999883041262 0.000278090704058337 -0.000395705728491957 -0.00409391712763891 -0.000278134320187378 0.999999955251616 -0.00011017288801264 0.00639178788024382 0.000395675072728769 0.000110282934470746 0.999999915639452 -0.00374472137669858 2.09080966547715e-05 1.04264141647205e-05 -1.91251383005385e-06 2.33803171384645e-06 4.23066434255212e-09 4.534876170725e-06 1.04264141647205e-05 1.85556865806408e-05 -5.54924868980171e-06 2.98809559878886e-07 -1.25323596444331e-06 1.16592878907909e-05 -1.91251383005385e-06 -5.54924868980171e-06 1.16197544022042e-05 4.11469023110197e-06 1.15256255549644e-06 7.23158619600389e-07 2.33803171384645e-06 2.98809559878886e-07 4.11469023110197e-06 2.61816804505318e-05 -1.56754410374745e-06 3.6292526235215e-06 4.23066434255212e-09 -1.25323596444331e-06 1.15256255549644e-06 -1.56754410374745e-06 3.57528107500373e-05 3.5267262628195e-06 4.534876170725e-06 1.16592878907909e-05 7.23158619600389e-07 3.6292526235215e-06 3.5267262628195e-06 3.66940161836511e-05 2289 2286 0 11 13 2285 2310 0 46 8 0 0 0 0 0 10 43 0 492 0 45 49 0 0 2422 +391 393 0.99999742823772 -0.000385665473587588 0.00223490046486037 -0.0015963999779899 0.000381925621023011 0.999998526643912 0.00167357187611631 0.00180479689041781 -0.00223554261094635 -0.00167271400633932 0.999996102180947 -0.000278816641145446 2.83217688953605e-05 4.99462780321408e-06 -1.35686447836002e-06 -4.01227273569033e-06 -2.48760354837195e-06 3.21179699421048e-07 4.99462780321408e-06 2.91080944103665e-05 -4.38600519375023e-06 4.53034240143377e-06 1.27094908185293e-06 8.48687117334298e-06 -1.35686447836002e-06 -4.38600519375023e-06 1.28947851673082e-05 3.96108086875908e-06 3.80671469369501e-06 -9.32731749389341e-08 -4.01227273569033e-06 4.53034240143377e-06 3.96108086875908e-06 3.05286974370821e-05 -5.18863769660085e-06 -3.41811723963683e-06 -2.48760354837195e-06 1.27094908185293e-06 3.80671469369501e-06 -5.18863769660085e-06 3.10604108235149e-05 5.39543942104633e-07 3.21179699421048e-07 8.48687117334298e-06 -9.32731749389341e-08 -3.41811723963683e-06 5.39543942104633e-07 2.90673609237109e-05 1396 1377 0 20 51 1355 1380 0 44 15 0 0 0 0 0 18 50 0 431 0 93 83 0 0 2361 +391 425 0.999998348886482 0.00170836255261712 -0.000619452740579137 -0.00484788796739271 -0.00170829480949043 0.999998534827392 0.00010987225476238 -0.00025602997697463 0.000619639534619558 -0.000108813865449359 0.999999802103175 0.00100367760587676 3.8345613220647e-05 4.54268302337363e-07 -2.64504696379286e-06 -1.43251508845983e-06 -7.7519582122318e-06 -1.07085571431845e-07 4.54268302337363e-07 3.5999157907197e-05 -8.44710603242317e-06 3.88507725550012e-06 1.34268986834282e-05 9.75119291177679e-06 -2.64504696379286e-06 -8.44710603242317e-06 1.5321263354904e-05 4.62722289090414e-06 1.3052731957501e-06 -8.22270787222249e-07 -1.43251508845983e-06 3.88507725550012e-06 4.62722289090414e-06 3.00469490692695e-05 -1.58092383100484e-06 -1.17383511053094e-06 -7.7519582122318e-06 1.34268986834282e-05 1.3052731957501e-06 -1.58092383100484e-06 4.79961429488704e-05 2.30181914484253e-06 -1.07085571431845e-07 9.75119291177679e-06 -8.22270787222249e-07 -1.17383511053094e-06 2.30181914484253e-06 3.38273837732605e-05 1781 1781 0 25 16 1775 1800 0 45 15 0 0 0 0 0 18 49 0 502 0 48 53 0 0 2014 +390 422 0.999998819780185 0.000960055315273975 0.00119947156190824 -0.0037641322782849 -0.000960186734174467 0.999999533080878 0.0001089929444096 0.00961999225470915 -0.00119936636259642 -0.000110144532455731 0.999999274693992 -0.00535583755345349 2.72693302639708e-05 1.46216869303882e-05 -3.14740866455473e-06 2.13135405840701e-06 2.1279685744857e-06 9.72942322226121e-06 1.46216869303882e-05 2.99550095856522e-05 -7.79763352842698e-06 6.9036748813535e-06 2.67051049973283e-06 9.73598730302627e-06 -3.14740866455473e-06 -7.79763352842698e-06 1.27902054912712e-05 2.64360006307384e-06 1.7089466396171e-06 -1.12543248631339e-06 2.13135405840701e-06 6.9036748813535e-06 2.64360006307384e-06 3.73050211873974e-05 -9.34048706798219e-06 -1.93917590570824e-06 2.1279685744857e-06 2.67051049973283e-06 1.7089466396171e-06 -9.34048706798219e-06 3.84220437461484e-05 1.05562952834116e-06 9.72942322226121e-06 9.73598730302627e-06 -1.12543248631339e-06 -1.93917590570824e-06 1.05562952834116e-06 4.0928263151943e-05 2195 2194 0 18 14 2185 2218 0 54 6 0 0 0 0 0 19 52 0 469 0 46 48 0 0 2329 +391 429 0.999971026510518 -0.0071711383344572 -0.00255360813140714 -0.000309184885861578 0.00717694783478628 0.999971661664703 0.00227316680177416 0.00318678405367708 0.00253723457281087 -0.00229142805254933 0.999994155882024 -0.00146435592601528 2.53747634604609e-05 9.02401473433102e-06 -1.60755813825838e-06 -2.79358187760451e-07 -2.73552328905256e-06 3.16875839044021e-06 9.02401473433102e-06 2.6232196590895e-05 -4.81449827642632e-06 1.90807673372216e-06 2.05713603523444e-06 1.13246809883729e-05 -1.60755813825838e-06 -4.81449827642632e-06 1.06783404418335e-05 3.92482043664993e-06 3.35030172239089e-06 1.21146537413145e-06 -2.79358187760451e-07 1.90807673372216e-06 3.92482043664993e-06 3.11489249726587e-05 -1.03061551036874e-06 -3.0032117586848e-06 -2.73552328905256e-06 2.05713603523444e-06 3.35030172239089e-06 -1.03061551036874e-06 3.66213951302862e-05 -5.04055630563205e-07 3.16875839044021e-06 1.13246809883729e-05 1.21146537413145e-06 -3.0032117586848e-06 -5.04055630563205e-07 3.58866515436901e-05 1440 1438 0 2 24 1442 1460 0 34 17 0 0 0 0 0 28 60 0 490 0 47 54 0 0 2438 +391 394 0.999999981626943 -4.26483800022178e-05 -0.000186888279826022 -0.00299400092073117 4.26977348859388e-05 0.999999964216264 0.000264091602734264 -0.00144368754609201 0.000186877010059432 -0.000264099577588319 0.999999947664197 0.0010554121881427 2.16560298532201e-05 3.17411730154964e-06 -4.38587790350759e-07 -2.66249649714144e-06 -1.24136865339355e-06 2.20792502784903e-07 3.17411730154964e-06 1.76645325153617e-05 -2.25108991296018e-06 -3.56476169450386e-07 1.88594065040022e-07 1.20252776569913e-05 -4.38587790350759e-07 -2.25108991296018e-06 8.93316967553277e-06 4.75673492325068e-06 4.35213482379083e-06 1.0574857668011e-06 -2.66249649714144e-06 -3.56476169450386e-07 4.75673492325068e-06 2.24372526737582e-05 1.29244842199278e-06 -2.58913230824275e-06 -1.24136865339355e-06 1.88594065040022e-07 4.35213482379083e-06 1.29244842199278e-06 2.27829883097267e-05 3.88140627443435e-06 2.20792502784903e-07 1.20252776569913e-05 1.0574857668011e-06 -2.58913230824275e-06 3.88140627443435e-06 3.03719073142451e-05 2594 2578 0 21 45 2563 2594 0 47 24 0 0 0 0 0 17 50 0 440 0 84 64 0 0 2515 +391 426 0.99999875404802 0.00124073142138484 -0.000975954889958092 -0.00317868356564006 -0.00123922109362265 0.99999803614088 0.0015466238921283 0.00776447755627309 0.00097787191818021 -0.00154541254122314 0.999998327731896 -0.00226625882567943 3.03700315688233e-05 1.58575849019859e-05 -2.75751880918336e-06 4.60496901826337e-06 -5.26513663632145e-06 1.7461114101474e-05 1.58575849019859e-05 2.95257670509834e-05 -7.44215841992816e-06 3.91977417448742e-06 -3.7327906497313e-06 1.62408738572358e-05 -2.75751880918336e-06 -7.44215841992816e-06 1.36877603602523e-05 4.16119451547846e-06 2.50344270911333e-06 -1.36339327249421e-06 4.60496901826337e-06 3.91977417448742e-06 4.16119451547846e-06 2.85171078761324e-05 -1.87041437988858e-06 2.56421267340895e-06 -5.26513663632145e-06 -3.7327906497313e-06 2.50344270911333e-06 -1.87041437988858e-06 3.50596975086769e-05 -5.29406985916461e-06 1.7461114101474e-05 1.62408738572358e-05 -1.36339327249421e-06 2.56421267340895e-06 -5.29406985916461e-06 4.5720987195258e-05 2010 2012 0 24 17 1998 2029 0 50 10 0 0 0 0 0 17 47 0 512 0 56 66 0 0 2077 +391 423 0.999999948948341 0.000241338546073637 0.000209425454280582 -0.00588742200007845 -0.000241468526846657 0.999999778118494 0.000620850959395514 0.0042151916100631 -0.000209275572545078 -0.000620901497355972 0.99999978534251 -0.00117691603016929 2.27759758919648e-05 8.57016151913175e-06 -2.9926233298427e-06 -1.38596574405386e-06 2.85343603179338e-06 8.03335016637119e-06 8.57016151913175e-06 2.78848927229796e-05 -5.92155223924338e-06 5.99985605057924e-06 5.38757051053453e-06 9.25538554956057e-06 -2.9926233298427e-06 -5.92155223924338e-06 1.58831319939566e-05 3.18087500217946e-06 8.69779113262501e-07 3.37036389955497e-07 -1.38596574405386e-06 5.99985605057924e-06 3.18087500217946e-06 3.38021402005086e-05 -7.9768446025779e-07 -9.51791568561934e-07 2.85343603179338e-06 5.38757051053453e-06 8.69779113262501e-07 -7.9768446025779e-07 3.37792835140185e-05 3.52629487861475e-06 8.03335016637119e-06 9.25538554956057e-06 3.37036389955497e-07 -9.51791568561934e-07 3.52629487861475e-06 3.53863357295441e-05 1391 1398 0 26 12 1380 1406 0 40 6 0 0 0 0 0 15 47 0 497 0 44 53 0 0 2261 +391 419 0.999997207749646 -1.24502446523612e-05 0.00236312037421806 0.00218478013759571 7.17613968384326e-06 0.999997509428137 0.00223183467732263 -0.000438981109610424 -0.0023631422755847 -0.00223181148739957 0.999994717274082 -0.00305047423725988 2.65292414401758e-05 1.06779088643921e-05 -2.42019016268328e-06 -8.44813057360448e-07 3.16820728257334e-06 7.64640144350681e-06 1.06779088643921e-05 2.81029158359785e-05 -4.37288227822139e-06 4.12197458444836e-06 7.73061009107237e-07 1.60127583647008e-05 -2.42019016268328e-06 -4.37288227822139e-06 1.14147757744372e-05 2.68003146403769e-06 2.24963351675519e-06 6.37710253147426e-07 -8.44813057360448e-07 4.12197458444836e-06 2.68003146403769e-06 2.77286901076681e-05 -4.93687565484899e-06 2.43130688298419e-06 3.16820728257334e-06 7.73061009107237e-07 2.24963351675519e-06 -4.93687565484899e-06 2.85109751449578e-05 2.19333704845381e-06 7.64640144350681e-06 1.60127583647008e-05 6.37710253147426e-07 2.43130688298419e-06 2.19333704845381e-06 4.01097644799457e-05 2080 2087 0 27 14 2074 2105 0 39 14 0 0 0 0 0 12 44 0 490 0 45 60 0 0 2268 +391 424 0.999999141474523 0.000636381702831041 -0.00114545560619622 -0.00259386918443026 -0.000637458940537967 0.999999354716849 -0.000940325467655273 -0.00330665577044458 0.0011448564611307 0.000941054841279061 0.999998901859132 0.000947285319264475 2.17288958162608e-05 8.03699300778042e-06 -1.83791176427839e-06 -6.76986637439619e-07 1.17469382392878e-06 4.38054948514724e-06 8.03699300778042e-06 2.2272873347244e-05 -4.77996091181163e-06 2.69865124138083e-06 3.68325146633073e-06 1.17562612649895e-05 -1.83791176427839e-06 -4.77996091181163e-06 1.19664599656586e-05 3.48275907885458e-06 2.9154060863664e-06 1.90225004827818e-06 -6.76986637439619e-07 2.69865124138083e-06 3.48275907885458e-06 2.70971691863011e-05 -2.82409862725839e-06 1.20795399771217e-06 1.17469382392878e-06 3.68325146633073e-06 2.9154060863664e-06 -2.82409862725839e-06 3.36587738521986e-05 5.50960216451618e-06 4.38054948514724e-06 1.17562612649895e-05 1.90225004827818e-06 1.20795399771217e-06 5.50960216451618e-06 3.4478650843451e-05 2415 2422 0 23 15 2416 2442 0 43 14 0 0 0 0 0 17 48 0 501 0 46 52 0 0 2242 +392 394 0.999999907294577 -0.000146634618645059 0.000404856919706349 -0.000470013794697861 0.000146079741217324 0.999999050549037 0.0013702414871451 0.000151830337051028 -0.000405057460152476 -0.00137018221872222 0.99999897926405 0.00253122637527678 2.48277468693059e-05 9.02210759928889e-06 1.87036968523363e-07 2.34824694091215e-06 -2.43248517157546e-06 4.3274477979334e-06 9.02210759928889e-06 2.10510358614679e-05 -2.09916231339738e-06 2.97741171000154e-06 1.15676586164286e-06 1.64310221276943e-05 1.87036968523363e-07 -2.09916231339738e-06 1.02798160648782e-05 4.36409488795937e-06 4.61372471203187e-06 -1.52701200693364e-07 2.34824694091215e-06 2.97741171000154e-06 4.36409488795937e-06 2.37776599807002e-05 -5.27161839992707e-06 3.93265089147655e-06 -2.43248517157546e-06 1.15676586164286e-06 4.61372471203187e-06 -5.27161839992707e-06 2.69118012092173e-05 3.59272819730512e-06 4.3274477979334e-06 1.64310221276943e-05 -1.52701200693364e-07 3.93265089147655e-06 3.59272819730512e-06 3.14894122064063e-05 2384 2362 0 16 44 2335 2364 0 45 3 0 0 0 0 0 20 53 0 457 0 94 87 0 0 2447 +391 418 0.999999717415074 0.00057257690031168 0.0004871606163815 -0.00324277981401409 -0.00057323977625186 0.999998908661701 0.00136164296549265 0.0043826543809185 -0.000486380439415949 -0.0013619218405556 0.999998954300938 0.0003231778764735 1.75165924113909e-05 8.67754933276793e-06 -1.28013448806961e-06 -9.23417255662276e-07 3.45294965140019e-06 7.19103907374973e-06 8.67754933276793e-06 2.12530634273569e-05 -3.98489639803363e-06 4.931232550245e-06 2.78103864835649e-06 1.02091040560114e-05 -1.28013448806961e-06 -3.98489639803363e-06 1.07645296147743e-05 2.78601360809687e-06 2.35082800088746e-06 -5.02815755520121e-07 -9.23417255662276e-07 4.931232550245e-06 2.78601360809687e-06 2.67939342215638e-05 -1.98901783982837e-06 -1.26064948715746e-06 3.45294965140019e-06 2.78103864835649e-06 2.35082800088746e-06 -1.98901783982837e-06 2.71371948634406e-05 3.91916201643192e-06 7.19103907374973e-06 1.02091040560114e-05 -5.02815755520121e-07 -1.26064948715746e-06 3.91916201643192e-06 2.86131683499386e-05 2149 2154 0 18 13 2143 2172 0 40 7 0 0 0 0 0 14 46 0 501 0 44 51 0 0 2207 +391 421 0.999999915981924 0.000388043415785813 -0.000132130434894985 -0.0038102985491355 -0.000388093332109962 0.999999853263065 -0.000377964831758907 0.00258069561576522 0.000131983748742207 0.000378016078943781 0.999999919842064 0.000641123310516793 2.14507995424338e-05 8.46171001671142e-06 -1.19634942631357e-06 -2.34333135353553e-06 2.54144086430808e-06 1.15327291793377e-05 8.46171001671142e-06 2.11542357196634e-05 -4.14916007700209e-06 5.17642261199332e-06 -1.93510466843116e-06 1.0787165296804e-05 -1.19634942631357e-06 -4.14916007700209e-06 1.02795387460337e-05 2.93138242637803e-06 2.35272746461261e-06 -7.22298264875467e-07 -2.34333135353553e-06 5.17642261199332e-06 2.93138242637803e-06 3.23702917129086e-05 -9.42763133443666e-06 -3.14758077108837e-06 2.54144086430808e-06 -1.93510466843116e-06 2.35272746461261e-06 -9.42763133443666e-06 3.0561246860452e-05 1.93125095461721e-06 1.15327291793377e-05 1.0787165296804e-05 -7.22298264875467e-07 -3.14758077108837e-06 1.93125095461721e-06 3.46655182227522e-05 2073 2075 0 18 14 2070 2103 0 47 12 0 0 0 0 0 13 46 0 506 0 46 57 0 0 2348 +392 395 0.999999890774594 -0.000452856636068693 0.000115635922503678 -0.00422687309805079 0.000452754135485818 0.999999505982046 0.000884900760974693 0.00506174099204756 -0.000116036598559326 -0.000884848309678924 0.999999601789409 0.000718143526169393 2.80329883426661e-05 9.77415165668557e-06 -8.73170577077513e-07 3.60940808779168e-06 -4.54193792922255e-06 9.47023802663258e-06 9.77415165668557e-06 2.41083691320739e-05 -2.62896874202163e-06 3.21901576865008e-06 -5.7665275525301e-07 1.13091953551327e-05 -8.73170577077513e-07 -2.62896874202163e-06 1.15339819453175e-05 1.01080922534884e-06 6.08275681830496e-06 -8.82396613324495e-08 3.60940808779168e-06 3.21901576865008e-06 1.01080922534884e-06 3.41142996785876e-05 -1.53007625433176e-05 -2.14750973605849e-06 -4.54193792922255e-06 -5.7665275525301e-07 6.08275681830496e-06 -1.53007625433176e-05 3.27722517266122e-05 2.45324082374485e-07 9.47023802663258e-06 1.13091953551327e-05 -8.82396613324495e-08 -2.14750973605849e-06 2.45324082374485e-07 3.03187698147094e-05 1950 1933 0 14 45 1932 1961 0 48 27 0 0 0 0 0 18 48 0 459 0 98 84 0 0 2458 +392 396 0.999999649144707 6.36530118201308e-05 0.000835259694929387 0.00431928817901416 -6.48309883301644e-05 0.999999003339735 0.00141036040804699 -0.00493011859643623 -0.000835169088771514 -0.00141041406392611 0.999998656611478 0.00137155124004601 2.00620441313063e-05 8.7134382804117e-06 -2.84423490786881e-07 1.51291247041703e-06 1.45469682628413e-06 4.63747309020083e-06 8.7134382804117e-06 1.96618914793073e-05 -2.76656496831909e-06 2.34548930819977e-06 7.21233105762082e-07 1.18715349997682e-05 -2.84423490786881e-07 -2.76656496831909e-06 1.16069162832304e-05 3.31919380252376e-06 5.27586825096278e-06 8.82120790612655e-07 1.51291247041703e-06 2.34548930819977e-06 3.31919380252376e-06 2.84320203659973e-05 -5.08603193046595e-06 -4.21904499214035e-07 1.45469682628413e-06 7.21233105762082e-07 5.27586825096278e-06 -5.08603193046595e-06 2.78292265697734e-05 4.97998364474471e-06 4.63747309020083e-06 1.18715349997682e-05 8.82120790612655e-07 -4.21904499214035e-07 4.97998364474471e-06 3.3154585869786e-05 2374 2361 0 23 44 2334 2360 0 47 9 0 0 0 0 0 17 46 0 460 0 102 96 0 0 2474 +391 422 0.999999657323299 0.000696888087546901 -0.000446878370253795 -0.00157826387016253 -0.000697007111452495 0.99999972164736 -0.000266244790652001 0.00254564779883451 0.000446692703041045 0.000266556176818136 0.999999864706708 -0.00193533012586723 3.49809978204012e-05 1.01466937186076e-05 -3.71192286481796e-06 9.37462512020036e-07 -6.77227023150617e-07 1.43239565725958e-05 1.01466937186076e-05 1.89086831584155e-05 -5.5530800685181e-06 8.42862948762578e-07 1.62853859548762e-06 9.37019691881085e-06 -3.71192286481796e-06 -5.5530800685181e-06 1.0409719105102e-05 3.62832327702627e-06 2.27260703461341e-06 -1.94031066880744e-07 9.37462512020036e-07 8.42862948762578e-07 3.62832327702627e-06 2.2030976874462e-05 -2.33366432757224e-06 -5.23278312630695e-07 -6.77227023150617e-07 1.62853859548762e-06 2.27260703461341e-06 -2.33366432757224e-06 2.99792764569329e-05 -8.7845405420502e-07 1.43239565725958e-05 9.37019691881085e-06 -1.94031066880744e-07 -5.23278312630695e-07 -8.7845405420502e-07 3.4914600341008e-05 2546 2543 0 18 14 2539 2576 0 42 12 0 0 0 0 0 22 56 0 479 0 16 19 0 0 2334 +392 421 0.999998296768101 -0.000122467649596342 0.00184159240127939 0.00467184597373336 0.000118984528519058 0.999998204309067 0.00189135436215987 -0.00225471089139607 -0.0018418207240719 -0.00189113201974119 0.999996515651982 -0.00404321098926112 2.25400401004323e-05 9.56075098226606e-06 -3.61713173212994e-06 3.94132806493706e-06 5.30475597345034e-06 1.02059197326083e-05 9.56075098226606e-06 1.81345128938377e-05 -5.67574530000172e-06 3.36721162301249e-06 1.17435998459361e-06 1.02209739643822e-05 -3.61713173212994e-06 -5.67574530000172e-06 9.70099650298659e-06 2.10639979758982e-06 2.58139199998979e-06 -3.61116756997589e-07 3.94132806493706e-06 3.36721162301249e-06 2.10639979758982e-06 2.14373329818254e-05 1.43380807049882e-06 4.19733616334249e-06 5.30475597345034e-06 1.17435998459361e-06 2.58139199998979e-06 1.43380807049882e-06 2.36489785083753e-05 5.40125384278774e-06 1.02059197326083e-05 1.02209739643822e-05 -3.61116756997589e-07 4.19733616334249e-06 5.40125384278774e-06 3.38714344204702e-05 2730 2731 0 23 14 2721 2758 0 50 11 0 0 0 0 0 11 44 0 564 0 43 50 0 0 2418 +392 418 0.999997333877971 -4.92061465700616e-05 0.00230863936226091 0.00590152691737192 4.52151088785902e-05 0.999998504670154 0.00172876055320355 -0.00226038972604442 -0.00230872097572874 -0.00172865155873683 0.999995840776973 -0.00381228148527031 1.94769885520586e-05 8.96326680274411e-06 -3.54854868470641e-06 6.2415674491528e-07 2.21746201994302e-06 9.41012099632382e-06 8.96326680274411e-06 1.67947227392783e-05 -5.56759585206726e-06 3.28046348771878e-06 -4.88501857598432e-07 9.24770738562377e-06 -3.54854868470641e-06 -5.56759585206726e-06 9.95345760961312e-06 2.65543637573662e-06 1.8572215593238e-06 3.62183534400211e-07 6.2415674491528e-07 3.28046348771878e-06 2.65543637573662e-06 2.26593962156944e-05 1.12661617583349e-06 4.07912031055861e-06 2.21746201994302e-06 -4.88501857598432e-07 1.8572215593238e-06 1.12661617583349e-06 2.65852222258469e-05 1.43639676224539e-06 9.41012099632382e-06 9.24770738562377e-06 3.62183534400211e-07 4.07912031055861e-06 1.43639676224539e-06 3.57166539467308e-05 2731 2728 0 16 13 2724 2757 0 53 11 0 0 0 0 0 11 44 0 564 0 44 54 0 0 2294 +391 417 0.999999748013664 0.000157811393870319 -0.000692147508453169 -0.00208120000270187 -0.000157718124990526 0.999999978476248 0.000134805406034582 0.00161644204935882 0.000692168767384585 -0.000134696207858211 0.999999751379634 -0.00197568695546606 2.00063707173345e-05 7.69825488515955e-06 -2.58376822157734e-06 5.46861599416588e-07 3.12079997747014e-07 1.03954837252035e-05 7.69825488515955e-06 1.68845831592809e-05 -4.057740031317e-06 -3.85931906957692e-07 -5.28868547459228e-07 1.03511251101758e-05 -2.58376822157734e-06 -4.057740031317e-06 9.10652498562084e-06 4.38542817095118e-06 3.69240984072486e-06 1.1931715011291e-06 5.46861599416588e-07 -3.85931906957692e-07 4.38542817095118e-06 1.69954729001601e-05 2.30172524751464e-06 3.19460788808932e-06 3.12079997747014e-07 -5.28868547459228e-07 3.69240984072486e-06 2.30172524751464e-06 2.01928991131683e-05 7.34584544786601e-07 1.03954837252035e-05 1.03511251101758e-05 1.1931715011291e-06 3.19460788808932e-06 7.34584544786601e-07 3.36305643693573e-05 3033 3038 0 22 13 3032 3074 0 44 11 0 0 0 0 0 15 49 0 507 0 15 18 0 0 2428 +392 429 0.999973141452394 -0.00732866037260453 8.43265874051952e-05 0.00743232206301249 0.00732833626464794 0.99996751981987 0.00335481637193388 -0.0009590569037145 -0.000108910158264803 -0.00335410829285009 0.999994369032215 -0.00629986900418898 2.43916558198234e-05 7.58684430577942e-06 -2.53420572840061e-06 4.58235450404921e-07 -1.54100688466651e-06 8.18285130196949e-06 7.58684430577942e-06 2.00686661806425e-05 -4.54317558900195e-06 3.48969994089421e-06 -8.47855000049338e-07 8.13778098749723e-06 -2.53420572840061e-06 -4.54317558900195e-06 1.07375223748541e-05 1.57959261420234e-06 3.96530021119716e-06 6.71443801122729e-07 4.58235450404921e-07 3.48969994089421e-06 1.57959261420234e-06 2.9461144319594e-05 -1.58363035732439e-06 1.25401135775269e-07 -1.54100688466651e-06 -8.47855000049338e-07 3.96530021119716e-06 -1.58363035732439e-06 2.96174439470715e-05 -1.76124068521708e-06 8.18285130196949e-06 8.13778098749723e-06 6.71443801122729e-07 1.25401135775269e-07 -1.76124068521708e-06 3.65508340579039e-05 2080 2076 0 11 24 2076 2100 0 44 24 0 0 0 0 0 27 59 0 551 0 40 49 0 0 2361 +392 428 0.999999711619255 0.000468386871262718 0.000597808619913962 0.00220282846273771 -0.000468490810826085 0.999999875165477 0.000173739432703462 0.00259999500750601 -0.000597727168017509 -0.000174019450445417 0.999999806219713 -0.000419297835363155 1.8932570597721e-05 1.1833430897172e-05 -4.85424983306129e-06 3.74557718011397e-06 6.06833280011709e-06 1.28992057898021e-05 1.1833430897172e-05 1.79886847057207e-05 -6.73968396175797e-06 3.14707546336565e-06 3.80297879494496e-06 1.30151688634712e-05 -4.85424983306129e-06 -6.73968396175797e-06 1.21737103514263e-05 6.89283409342179e-07 -1.20601838008534e-06 -2.09379405346234e-06 3.74557718011397e-06 3.14707546336565e-06 6.89283409342179e-07 2.27983153412854e-05 6.44090274059128e-06 3.76891622319008e-06 6.06833280011709e-06 3.80297879494496e-06 -1.20601838008534e-06 6.44090274059128e-06 3.25076361720713e-05 5.46345275337991e-06 1.28992057898021e-05 1.30151688634712e-05 -2.09379405346234e-06 3.76891622319008e-06 5.46345275337991e-06 3.65707013134166e-05 2990 2993 0 20 16 2983 3034 0 49 13 0 0 0 0 0 16 49 0 547 0 16 20 0 0 2260 +392 424 0.999999490823029 -0.00022958131404774 -0.000982672937834835 -0.0030002548838644 0.000228533007635107 0.999999404886887 -0.00106677014209519 0.000677977771043828 0.000982917263524293 0.00106654502571839 0.999998948177128 -0.000403871880834028 2.30230802840864e-05 1.03191917185682e-05 -3.28157469669362e-06 1.01271571229907e-06 2.23739222735664e-06 7.40599913113156e-06 1.03191917185682e-05 2.09284668224183e-05 -5.77863257812074e-06 -6.532281636734e-08 3.57477716384205e-06 1.28928264923969e-05 -3.28157469669362e-06 -5.77863257812074e-06 1.13149833048194e-05 3.23129593108028e-06 2.33823508966785e-06 1.71977344552889e-08 1.01271571229907e-06 -6.532281636734e-08 3.23129593108028e-06 2.23958520876051e-05 -3.98224047386844e-07 4.06819739819775e-06 2.23739222735664e-06 3.57477716384205e-06 2.33823508966785e-06 -3.98224047386844e-07 3.01792122223597e-05 2.27443099515447e-06 7.40599913113156e-06 1.28928264923969e-05 1.71977344552889e-08 4.06819739819775e-06 2.27443099515447e-06 3.65295511559807e-05 2186 2184 0 11 15 2175 2205 0 46 6 0 0 0 0 0 19 50 0 567 0 63 75 0 0 2313 +392 420 0.999998067241014 0.000707776710199854 0.00183427543319934 0.0022817091966047 -0.000712032634650225 0.999997053890683 0.00232060756711613 0.0023191067946853 -0.00183262755723388 -0.00232190914591038 0.999995625097507 -0.0033631444128814 2.70637762934961e-05 1.34128748124237e-05 -3.58722048957316e-06 6.27111537059795e-06 6.73099518706485e-07 1.06299746949005e-05 1.34128748124237e-05 2.21796607128788e-05 -7.31059179903855e-06 7.05362033499745e-06 8.15043075519629e-07 1.61172385497509e-05 -3.58722048957316e-06 -7.31059179903855e-06 1.13224173906723e-05 2.27359560999752e-06 9.00750457418313e-07 -2.33691639087746e-06 6.27111537059795e-06 7.05362033499745e-06 2.27359560999752e-06 2.67772045562732e-05 6.30841289634906e-07 9.3116420656484e-06 6.73099518706485e-07 8.15043075519629e-07 9.00750457418313e-07 6.30841289634906e-07 2.85521790852139e-05 3.02809655424337e-06 1.06299746949005e-05 1.61172385497509e-05 -2.33691639087746e-06 9.3116420656484e-06 3.02809655424337e-06 3.60961205606707e-05 2694 2691 0 16 11 2684 2714 0 50 8 0 0 0 0 0 11 42 0 568 0 42 53 0 0 2235 +392 426 0.999995840735007 0.000610530334186417 0.00281882340668209 0.00313284283299889 -0.000614227148088917 0.999998952270557 0.00131079472054683 0.00121897772688487 -0.00281802017337902 -0.00131252066646629 0.999995168014227 -0.00569223747680891 1.79391909964446e-05 9.97364200738434e-06 -3.39886814485808e-06 2.08748699391817e-06 3.43889831240545e-06 8.09518615180474e-06 9.97364200738434e-06 2.07927796602174e-05 -6.94177141907479e-06 2.4109979358914e-06 3.84298385672385e-06 1.1811363308836e-05 -3.39886814485808e-06 -6.94177141907479e-06 1.07909516568853e-05 2.92087093473322e-06 2.30996482721393e-06 -1.53996670813827e-06 2.08748699391817e-06 2.4109979358914e-06 2.92087093473322e-06 2.63648821336265e-05 7.72036310190209e-07 3.00723516956019e-06 3.43889831240545e-06 3.84298385672385e-06 2.30996482721393e-06 7.72036310190209e-07 2.83711591586538e-05 5.9804909886198e-06 8.09518615180474e-06 1.1811363308836e-05 -1.53996670813827e-06 3.00723516956019e-06 5.9804909886198e-06 3.30506431930783e-05 2699 2698 0 22 17 2690 2721 0 55 17 0 0 0 0 0 16 46 0 575 0 44 54 0 0 2082 +392 425 0.999997777247687 0.000392947538507762 0.00207149509208661 -0.00131824124191295 -0.000395808255152171 0.999998968415188 0.00138076224767979 0.00214466003093214 -0.00207095038803725 -0.00138157909344527 0.999996901197048 -0.00197493194520053 3.81608249743692e-05 1.54720157585689e-05 -5.95683259614932e-06 2.60101033303627e-06 3.77331478151079e-06 9.91865307797316e-06 1.54720157585689e-05 3.05023073907473e-05 -9.22509736663596e-06 4.01765879015877e-06 5.11119088405077e-06 1.65394442014948e-05 -5.95683259614932e-06 -9.22509736663596e-06 1.27841701678468e-05 2.27550935184096e-06 1.92113479114246e-06 -1.9777448722594e-06 2.60101033303627e-06 4.01765879015877e-06 2.27550935184096e-06 2.70529640608118e-05 -1.89153203519931e-06 1.95513228613076e-06 3.77331478151079e-06 5.11119088405077e-06 1.92113479114246e-06 -1.89153203519931e-06 3.07964084313286e-05 6.74537831539975e-06 9.91865307797316e-06 1.65394442014948e-05 -1.9777448722594e-06 1.95513228613076e-06 6.74537831539975e-06 4.07861165505759e-05 1600 1599 0 22 16 1586 1617 0 47 7 0 0 0 0 0 19 49 0 560 0 60 72 0 0 2028 +393 428 0.999998762633308 0.00126380337963077 -0.000936767245148134 -0.000498274844544097 -0.00126492655832919 0.999998480731148 -0.00119937325237472 0.00961927154364322 0.000935250049977047 0.00120055671007756 0.999998841984795 0.00274984317568643 2.74807048034226e-05 1.13170768817336e-05 -4.86235805388988e-06 1.44759403370359e-06 -3.65032394532109e-06 9.26314462196828e-06 1.13170768817336e-05 2.28700624926343e-05 -7.93352215016544e-06 4.47687603832444e-06 1.03439095140315e-06 1.45600300999427e-05 -4.86235805388988e-06 -7.93352215016544e-06 1.28628647239029e-05 2.33810226163153e-06 -3.24343869729509e-07 8.49568758014853e-08 1.44759403370359e-06 4.47687603832444e-06 2.33810226163153e-06 2.81182045965398e-05 1.29551933366445e-08 5.48975518261963e-06 -3.65032394532109e-06 1.03439095140315e-06 -3.24343869729509e-07 1.29551933366445e-08 4.24507363741729e-05 1.49875772817797e-07 9.26314462196828e-06 1.45600300999427e-05 8.49568758014853e-08 5.48975518261963e-06 1.49875772817797e-07 3.61791908823477e-05 2663 2665 0 16 16 2660 2691 0 49 12 0 0 0 0 0 7 40 0 546 0 16 18 0 0 2251 +392 423 0.99999794762929 0.000143456810619979 0.00202092982349688 0.00305462614425789 -0.000146005741158871 0.999999194059442 0.00126117516254786 -0.000754202423511159 -0.00202074727058112 -0.00126146764150561 0.999997162635904 -0.00593954727925814 2.55375493268611e-05 1.26620820297959e-05 -3.62531507192728e-06 3.9257312839679e-06 1.63804690858939e-06 1.3749654714191e-05 1.26620820297959e-05 2.02489226891455e-05 -5.28713248666982e-06 4.78658001476991e-06 -1.43475843583254e-06 1.39404596701167e-05 -3.62531507192728e-06 -5.28713248666982e-06 1.05881939700217e-05 2.67155624167155e-06 2.55308146574651e-06 1.43254992193897e-06 3.9257312839679e-06 4.78658001476991e-06 2.67155624167155e-06 2.58754861729565e-05 -3.26776345136699e-06 2.69510270166332e-06 1.63804690858939e-06 -1.43475843583254e-06 2.55308146574651e-06 -3.26776345136699e-06 2.75397334934364e-05 1.37516845267477e-06 1.3749654714191e-05 1.39404596701167e-05 1.43254992193897e-06 2.69510270166332e-06 1.37516845267477e-06 3.284582630867e-05 2091 2090 0 20 12 2086 2117 0 50 12 0 0 0 0 0 13 44 0 553 0 43 54 0 0 2309 +393 396 0.999992104467521 -0.000268075622144161 0.00396473682359747 0.0022351821578797 0.000254667359183411 0.999994248600597 0.00338199796903942 0.00228406908687138 -0.00396562065202212 -0.00338096157730789 0.999986421383639 -0.00302164664189329 2.61839303504112e-05 9.56049499893984e-06 3.5158540877344e-07 -1.95942252942727e-06 -2.75473820421458e-06 6.51458874000923e-06 9.56049499893984e-06 2.22343805257757e-05 -6.09894644953501e-07 1.06254326771016e-06 2.38260291379881e-06 1.57006260081267e-05 3.5158540877344e-07 -6.09894644953501e-07 1.06849364714425e-05 1.0175637097306e-06 5.83034767035372e-06 1.55252422354691e-06 -1.95942252942727e-06 1.06254326771016e-06 1.0175637097306e-06 3.00058805924515e-05 -8.80660968707623e-06 1.86635150940393e-06 -2.75473820421458e-06 2.38260291379881e-06 5.83034767035372e-06 -8.80660968707623e-06 3.60960605480687e-05 4.1603012801472e-06 6.51458874000923e-06 1.57006260081267e-05 1.55252422354691e-06 1.86635150940393e-06 4.1603012801472e-06 3.62928496333223e-05 2627 2608 0 17 47 2601 2623 0 42 23 0 0 0 0 0 18 47 0 471 0 79 61 0 0 2473 +393 427 0.999994376010261 0.000315150224604576 -0.00333895615208018 -0.00113069921700073 -0.000321170479322139 0.999998323645821 -0.00180265223241361 0.0054802319252539 0.00333838244855115 0.00180371446846375 0.999992800882458 0.0015024387166026 3.30988864128672e-05 1.58543848426208e-05 -7.40518242382095e-06 6.01644626351682e-06 2.25456748117541e-06 1.64619224992403e-05 1.58543848426208e-05 2.19283932320459e-05 -7.20460911571763e-06 3.31056735756542e-06 5.8289730042806e-06 1.62572268792824e-05 -7.40518242382095e-06 -7.20460911571763e-06 1.33433896240585e-05 5.48729266457994e-07 1.21695313679975e-06 -1.93452884016931e-06 6.01644626351682e-06 3.31056735756542e-06 5.48729266457994e-07 2.71103522726667e-05 4.02637201485702e-07 3.94516534135098e-06 2.25456748117541e-06 5.8289730042806e-06 1.21695313679975e-06 4.02637201485702e-07 3.83255941476447e-05 7.04897826124015e-06 1.64619224992403e-05 1.62572268792824e-05 -1.93452884016931e-06 3.94516534135098e-06 7.04897826124015e-06 3.93611650940968e-05 1976 1973 0 17 17 1966 1997 0 48 12 0 0 0 0 0 17 48 0 569 0 19 20 0 0 2369 +393 426 0.999999293968083 0.000491102508185255 0.00108207285470975 -0.000215506653317415 -0.000491687629251862 0.999999733029173 0.000540541264799683 0.00849925022710562 -0.00108180710465694 -0.000541072924996907 0.999999268466471 -0.00264366302659765 2.14004713675575e-05 1.06237712647056e-05 -3.12351162733489e-06 2.86621109284469e-06 1.7732353785359e-06 1.03586638903726e-05 1.06237712647056e-05 1.68324764934125e-05 -5.45300312275079e-06 1.43954316901325e-06 4.9736320836956e-08 1.20877905361315e-05 -3.12351162733489e-06 -5.45300312275079e-06 1.07501427046524e-05 3.97091203106627e-06 1.2147513710168e-06 1.79134272512509e-06 2.86621109284469e-06 1.43954316901325e-06 3.97091203106627e-06 2.04607517187802e-05 2.26738752891557e-06 6.79267449012045e-06 1.7732353785359e-06 4.9736320836956e-08 1.2147513710168e-06 2.26738752891557e-06 3.21792170295082e-05 2.02346855179617e-07 1.03586638903726e-05 1.20877905361315e-05 1.79134272512509e-06 6.79267449012045e-06 2.02346855179617e-07 3.98260212857673e-05 2845 2843 0 10 17 2840 2872 0 45 12 0 0 0 0 0 16 46 0 577 0 17 19 0 0 2178 +393 397 0.999999836573156 -0.000490366930192512 0.000293928453304774 0.00657578363508998 0.000490477192486383 0.999999809336596 -0.00037517848483078 -0.00800065799671069 -0.000293744422141494 0.000375322588719113 0.999999886423578 -0.000548649375345404 2.47483002982381e-05 1.33053719630411e-05 -2.20124546246518e-06 7.71763370181253e-07 9.8174592658998e-07 1.45077339994806e-05 1.33053719630411e-05 2.16057333531285e-05 -3.38229117956575e-06 -3.16372209582113e-07 4.95421352395983e-06 1.62559521362011e-05 -2.20124546246518e-06 -3.38229117956575e-06 1.0191328987041e-05 4.01809347661143e-06 2.91784857359308e-06 4.70912714765141e-07 7.71763370181253e-07 -3.16372209582113e-07 4.01809347661143e-06 2.24089029678068e-05 -2.60009071468889e-06 1.82920030721693e-06 9.8174592658998e-07 4.95421352395983e-06 2.91784857359308e-06 -2.60009071468889e-06 2.74312421971339e-05 4.69738120818219e-06 1.45077339994806e-05 1.62559521362011e-05 4.70912714765141e-07 1.82920030721693e-06 4.69738120818219e-06 3.22786784957484e-05 2215 2203 0 17 44 2200 2238 0 48 27 0 0 0 0 0 8 39 0 463 0 49 31 0 0 2391 +392 422 0.999998031923577 0.000321784835829468 -0.00195770362712059 -0.00187273847972809 -0.000324023455483922 0.999999293956218 -0.00114328293348762 0.00429809238386521 0.00195733435378506 0.0011439150253135 0.999997430147019 0.000265658104451094 2.32899816788724e-05 1.24504192472151e-05 -4.81997183238796e-06 2.75004963903433e-06 3.62728610540471e-06 1.31708329931493e-05 1.24504192472151e-05 2.25244226440261e-05 -6.60315516850993e-06 7.78720181235345e-06 -9.7115747166661e-09 1.31743401102726e-05 -4.81997183238796e-06 -6.60315516850993e-06 1.14112960998099e-05 3.02015394379456e-06 -9.60839876629556e-07 -8.79305637578447e-07 2.75004963903433e-06 7.78720181235345e-06 3.02015394379456e-06 3.01470412843541e-05 -7.17444910165352e-06 1.8295829012697e-06 3.62728610540471e-06 -9.7115747166661e-09 -9.60839876629556e-07 -7.17444910165352e-06 3.23707937766216e-05 2.81351001673261e-06 1.31708329931493e-05 1.31743401102726e-05 -8.79305637578447e-07 1.8295829012697e-06 2.81351001673261e-06 3.8052959617133e-05 1968 1966 0 18 14 1962 1995 0 48 14 0 0 0 0 0 21 55 0 542 0 63 66 0 0 2389 +393 429 0.999977199603999 -0.00651656580967303 -0.00177049207657095 0.00344777607739699 0.00651919175365998 0.999977652441149 0.00148147128474001 0.00341508718195891 0.00176079840527293 -0.00149297968395356 0.999997335296769 -0.00215179456354509 2.13945707527646e-05 1.08480698153353e-05 -2.09747230092353e-06 3.14979900461389e-06 2.99896337550029e-06 8.87471312693203e-06 1.08480698153353e-05 2.00371352729176e-05 -4.96499493401571e-06 2.13644830841791e-06 1.9743326627896e-06 1.45200381034203e-05 -2.09747230092353e-06 -4.96499493401571e-06 1.02561333932995e-05 2.59652104800958e-06 7.61157084503891e-07 9.16312306533577e-07 3.14979900461389e-06 2.13644830841791e-06 2.59652104800958e-06 1.91496076601022e-05 7.85365039301437e-06 3.27056122653404e-06 2.99896337550029e-06 1.9743326627896e-06 7.61157084503891e-07 7.85365039301437e-06 2.81954115275037e-05 1.53913526879943e-06 8.87471312693203e-06 1.45200381034203e-05 9.16312306533577e-07 3.27056122653404e-06 1.53913526879943e-06 3.87737712943291e-05 3031 3032 0 2 25 3035 3065 0 40 20 0 0 0 0 0 24 56 0 550 0 17 17 0 0 2354 +393 420 0.999999721133481 0.000409016091419165 0.000624851019804122 0.00218308174721624 -0.000410364440753553 0.999997584571416 0.00215927125647655 0.00301603725877479 -0.00062396633383147 -0.00215952707096738 0.99999747355123 -0.00114735536864209 3.07981822143574e-05 1.06376444559066e-05 -5.81681377499745e-06 3.78471327511304e-06 7.7553705456973e-06 9.92712577923426e-06 1.06376444559066e-05 2.25373443001427e-05 -7.36615314477335e-06 4.80936823591506e-06 8.42247688871867e-06 1.69244182492473e-05 -5.81681377499745e-06 -7.36615314477335e-06 1.08811197074234e-05 4.38268261846493e-07 1.38863409072365e-07 -2.3745603031487e-06 3.78471327511304e-06 4.80936823591506e-06 4.38268261846493e-07 2.17211242854968e-05 7.77410165329003e-06 5.31956294711938e-06 7.7553705456973e-06 8.42247688871867e-06 1.38863409072365e-07 7.77410165329003e-06 3.15834351434954e-05 9.11270256631538e-06 9.92712577923426e-06 1.69244182492473e-05 -2.3745603031487e-06 5.31956294711938e-06 9.11270256631538e-06 4.06743408204969e-05 2173 2170 0 11 11 2169 2206 0 50 9 0 0 0 0 0 7 38 0 572 0 13 15 0 0 2381 +393 419 0.999998742298852 -6.46230315586942e-05 -0.00158468437795017 -0.00162878305147686 6.36272416953611e-05 0.999999800516096 -0.000628426082815043 0.00178614279962857 0.00158472467262973 0.000628324463346911 0.999998546926985 0.0036708812801966 2.41546678745865e-05 1.36718129781502e-05 -5.98546496536969e-06 3.74742010246828e-06 6.72679685741344e-06 1.15527588898686e-05 1.36718129781502e-05 2.06552898839372e-05 -7.55486675000412e-06 3.98744130085423e-06 3.12401510825702e-06 1.43626707576e-05 -5.98546496536969e-06 -7.55486675000412e-06 1.31612556819362e-05 1.18928720518746e-06 -1.26975490909006e-06 -1.88080962542489e-06 3.74742010246828e-06 3.98744130085423e-06 1.18928720518746e-06 2.56828147886302e-05 -4.86244907373565e-06 3.34114204374182e-06 6.72679685741344e-06 3.12401510825702e-06 -1.26975490909006e-06 -4.86244907373565e-06 4.00001313602814e-05 6.83165845510359e-06 1.15527588898686e-05 1.43626707576e-05 -1.88080962542489e-06 3.34114204374182e-06 6.83165845510359e-06 3.20481674850469e-05 2863 2859 0 8 14 2861 2891 0 52 10 0 0 0 0 0 11 43 0 546 0 16 17 0 0 2233 +393 395 0.999999090425093 -0.000285605142096842 0.0013181724805469 0.00198480112954865 0.000284359676651172 0.999999513120223 0.000944933273232681 -0.000720488606924863 -0.00131844171655715 -0.000944557578644749 0.999998684760345 -0.00432555489005888 1.87961021346102e-05 1.27462115200455e-05 -7.40077160552922e-07 1.01990543599255e-06 -4.35310662158393e-07 8.85656163100777e-06 1.27462115200455e-05 1.9228635693859e-05 -1.80379908449837e-06 1.11152110930173e-06 -1.08085164063029e-06 1.0628928931893e-05 -7.40077160552922e-07 -1.80379908449837e-06 9.39498317122683e-06 3.31198700102863e-06 4.02483255226736e-06 -8.0606136940438e-07 1.01990543599255e-06 1.11152110930173e-06 3.31198700102863e-06 2.21750983018047e-05 -5.13071963857416e-06 -2.96363177895485e-06 -4.35310662158393e-07 -1.08085164063029e-06 4.02483255226736e-06 -5.13071963857416e-06 2.49874795738789e-05 3.26809839234794e-06 8.85656163100777e-06 1.0628928931893e-05 -8.0606136940438e-07 -2.96363177895485e-06 3.26809839234794e-06 2.49322499395602e-05 2495 2482 0 20 47 2459 2488 0 47 11 0 0 0 0 0 18 48 0 450 0 91 76 0 0 2473 +393 424 0.999999826246392 0.000220871581223458 0.000546555514224322 -0.00267489730550762 -0.000221357842727946 0.999999579643236 0.000889783150971082 0.00680211691909399 -0.000546358756664514 -0.000889903980717609 0.999999454781359 -0.00548913857070117 2.47795324108537e-05 1.19239749026995e-05 -5.37599449315908e-06 3.03840310596153e-06 1.06513727160939e-06 9.33413258526109e-06 1.19239749026995e-05 2.17260119063881e-05 -7.25147776532593e-06 2.48238310291419e-06 6.26789154498225e-06 1.59684158808264e-05 -5.37599449315908e-06 -7.25147776532593e-06 1.1802700540691e-05 1.94107450665954e-06 2.37554951824801e-06 6.22527530395793e-08 3.03840310596153e-06 2.48238310291419e-06 1.94107450665954e-06 2.45034066074396e-05 -4.32643100032696e-06 5.00840352879698e-06 1.06513727160939e-06 6.26789154498225e-06 2.37554951824801e-06 -4.32643100032696e-06 3.79026961140467e-05 7.68379255983825e-06 9.33413258526109e-06 1.59684158808264e-05 6.22527530395793e-08 5.00840352879698e-06 7.68379255983825e-06 3.69473733469246e-05 2558 2560 0 16 15 2557 2580 0 39 14 0 0 0 0 0 21 52 0 580 0 44 45 0 0 2217 +394 427 0.999999841526549 -0.000307642658850886 0.000471490053855306 0.00774709285088874 0.000307473973618586 0.999999888719009 0.000357801235894328 -0.00308914491968162 -0.000471600076310976 -0.000357656208271951 0.999999824837687 -0.00397871655950343 2.19806863591639e-05 1.55332157573123e-05 -5.86343874891218e-06 5.56347886918223e-06 6.29729947252788e-06 1.25769513124286e-05 1.55332157573123e-05 2.75616966433916e-05 -8.92091114071075e-06 5.91614752091269e-06 7.97458960362314e-06 2.31134449563824e-05 -5.86343874891218e-06 -8.92091114071075e-06 1.4655202277564e-05 8.20302445687292e-07 -1.69115331519269e-06 -1.63655015987774e-06 5.56347886918223e-06 5.91614752091269e-06 8.20302445687292e-07 3.16217360038829e-05 1.42424207120877e-06 1.3999725047908e-05 6.29729947252788e-06 7.97458960362314e-06 -1.69115331519269e-06 1.42424207120877e-06 3.71740785648573e-05 6.41934052118491e-06 1.25769513124286e-05 2.31134449563824e-05 -1.63655015987774e-06 1.3999725047908e-05 6.41934052118491e-06 4.42945950425551e-05 2246 2248 0 18 20 2235 2261 0 44 11 0 0 0 0 0 12 41 0 568 0 23 23 0 0 2300 +394 396 0.99999899327245 0.000228662054950764 0.00140041699194379 0.0036403444070574 -0.000230833861965722 0.99999877076819 0.00155086357800258 -0.00277511359644763 -0.00140006064685398 -0.0015511852803681 0.999997816824822 0.00050780686106181 3.08928421464863e-05 9.83341941378017e-06 -1.27239053567631e-06 -8.38989868926311e-07 -4.05763970072662e-06 1.12750393327796e-05 9.83341941378017e-06 2.63542068596737e-05 -2.6543318300509e-06 5.44683335608127e-06 8.68509179565719e-07 1.98537006203398e-05 -1.27239053567631e-06 -2.6543318300509e-06 9.57331199113351e-06 4.62527845685522e-06 3.67278354608763e-06 6.62479429889079e-07 -8.38989868926311e-07 5.44683335608127e-06 4.62527845685522e-06 2.30471650216996e-05 -2.34982936300742e-06 4.55659699047833e-06 -4.05763970072662e-06 8.68509179565719e-07 3.67278354608763e-06 -2.34982936300742e-06 2.40701011953492e-05 1.46129320993043e-06 1.12750393327796e-05 1.98537006203398e-05 6.62479429889079e-07 4.55659699047833e-06 1.46129320993043e-06 3.79084397418231e-05 2978 2960 0 9 50 2962 2992 0 39 24 0 0 0 0 0 14 44 0 460 0 50 32 0 0 2463 +393 425 0.999998897212446 -0.000184437588755056 0.00147362025922676 8.80945846240589e-05 0.00018363291393372 0.999999833988801 0.000546169683596112 0.000276423975529501 -0.00147372074880879 -0.000545898476104749 0.999998765070242 -0.00300160906447863 2.82777900265418e-05 9.80145979154223e-06 -6.57802882227834e-06 1.91704211693312e-06 4.50603342586541e-06 7.42625143970734e-06 9.80145979154223e-06 2.02991618686607e-05 -7.85704272142839e-06 5.8850590840218e-06 4.20216402560031e-06 1.45540684356098e-05 -6.57802882227834e-06 -7.85704272142839e-06 1.36056976044893e-05 -1.01366057176084e-06 -1.12515241954105e-06 -1.93064889584552e-06 1.91704211693312e-06 5.8850590840218e-06 -1.01366057176084e-06 3.02254495470074e-05 -5.56038766252474e-06 4.01123570844236e-06 4.50603342586541e-06 4.20216402560031e-06 -1.12515241954105e-06 -5.56038766252474e-06 3.9673360317445e-05 5.42353558322042e-06 7.42625143970734e-06 1.45540684356098e-05 -1.93064889584552e-06 4.01123570844236e-06 5.42353558322042e-06 3.09348896340509e-05 2809 2806 0 18 16 2804 2832 0 52 14 0 0 0 0 0 18 48 0 565 0 45 47 0 0 2064 +394 420 0.99999988828207 0.000238437866746279 0.000408146091281707 -0.00015701588453121 -0.000239057947704788 0.99999881639473 0.00151988829739345 0.00800046203322454 -0.000407783209274519 -0.00151998569816162 0.999998761677399 0.000136526514455915 3.5862585039064e-05 1.3262464785201e-05 -5.37523434816966e-06 2.11801127269034e-06 1.10306939237336e-06 7.0487922807632e-06 1.3262464785201e-05 2.60117488455027e-05 -7.27280146471054e-06 9.67824835453386e-06 4.06232618652823e-06 1.98139586363686e-05 -5.37523434816966e-06 -7.27280146471054e-06 1.17678482897888e-05 6.73593313729736e-07 8.42889763259457e-07 -2.18583351815087e-06 2.11801127269034e-06 9.67824835453386e-06 6.73593313729736e-07 2.95226613251743e-05 1.09419075805627e-06 9.14158191335085e-06 1.10306939237336e-06 4.06232618652823e-06 8.42889763259457e-07 1.09419075805627e-06 3.44765393154709e-05 6.40126807730167e-06 7.0487922807632e-06 1.98139586363686e-05 -2.18583351815087e-06 9.14158191335085e-06 6.40126807730167e-06 4.47952263990618e-05 2618 2621 0 22 16 2614 2643 0 42 15 0 0 0 0 0 19 49 0 586 0 11 12 0 0 2269 +393 421 0.999998973880709 0.000665335598529539 0.0012686867499879 0.00154983537293395 -0.00066725388902213 0.999998634002959 0.0015122051656804 0.00572662114063026 -0.00126767889303655 -0.00151305015014539 0.999998051832836 -0.000135226578733666 2.37769091025923e-05 1.01490509967224e-05 -5.78501438708545e-06 1.5301895760939e-06 1.61558745158026e-06 1.01927780846169e-05 1.01490509967224e-05 1.73600620922444e-05 -7.08396194457289e-06 9.31496520184111e-07 3.58174412589799e-06 1.26730975472017e-05 -5.78501438708545e-06 -7.08396194457289e-06 1.19012415864722e-05 1.56173411059726e-06 -5.67051986868485e-07 -2.62558622075564e-06 1.5301895760939e-06 9.31496520184111e-07 1.56173411059726e-06 2.01752817474831e-05 4.73252115108036e-06 2.71093517171392e-06 1.61558745158026e-06 3.58174412589799e-06 -5.67051986868485e-07 4.73252115108036e-06 3.63972898146063e-05 2.62797649021569e-06 1.01927780846169e-05 1.26730975472017e-05 -2.62558622075564e-06 2.71093517171392e-06 2.62797649021569e-06 3.14635073549137e-05 2810 2813 0 17 14 2806 2843 0 48 10 0 0 0 0 0 13 45 0 577 0 15 16 0 0 2287 +393 422 0.999999980470364 -0.000191849179179829 4.74675029383575e-05 0.00204653636214991 0.00019176123160895 0.999998277912825 0.0018459141406485 0.000776842287266369 -4.78215583078993e-05 -0.00184590500217165 0.999998295172458 -0.00400335530409475 3.63012243223953e-05 2.53744149322412e-05 -7.15722135464143e-06 1.29390327817438e-05 -3.58692807049948e-07 1.62620030140317e-05 2.53744149322412e-05 3.87657245539748e-05 -8.27958821458847e-06 1.54647769539973e-05 1.57470984228021e-06 2.69393639654133e-05 -7.15722135464143e-06 -8.27958821458847e-06 1.38954742450187e-05 -9.25468234196931e-08 -3.94156054767825e-06 -2.36107166191364e-06 1.29390327817438e-05 1.54647769539973e-05 -9.25468234196931e-08 3.39336155777913e-05 -9.02062542403939e-06 1.08860982739645e-05 -3.58692807049948e-07 1.57470984228021e-06 -3.94156054767825e-06 -9.02062542403939e-06 5.04933146519332e-05 2.89578344768683e-06 1.62620030140317e-05 2.69393639654133e-05 -2.36107166191364e-06 1.08860982739645e-05 2.89578344768683e-06 4.79587636715847e-05 2303 2301 0 16 14 2290 2323 0 50 5 0 0 0 0 0 16 50 0 547 0 53 55 0 0 2309 +394 421 0.999999819408199 -0.000123323062860419 0.000588196388537462 0.00110529743180016 0.000122864806689984 0.999999688985194 0.000779059532569761 0.00493927086633238 -0.000588292281607384 -0.000778987123242424 0.999999523545513 0.00160732622289941 2.14486783376917e-05 9.33638262808786e-06 -5.13047273253036e-06 2.88322228042183e-06 3.15628049084868e-06 8.77631494880247e-06 9.33638262808786e-06 1.79922419141674e-05 -7.06931598859575e-06 1.92822125224289e-06 4.96155219642507e-06 8.89406737166464e-06 -5.13047273253036e-06 -7.06931598859575e-06 1.19182833265081e-05 4.10895138764707e-07 1.25291453013331e-06 -7.14911096976603e-08 2.88322228042183e-06 1.92822125224289e-06 4.10895138764707e-07 2.80649297739902e-05 -1.8427050751499e-06 2.67975477324559e-06 3.15628049084868e-06 4.96155219642507e-06 1.25291453013331e-06 -1.8427050751499e-06 4.03838242620122e-05 6.32693180660848e-06 8.77631494880247e-06 8.89406737166464e-06 -7.14911096976603e-08 2.67975477324559e-06 6.32693180660848e-06 3.17137402629409e-05 2643 2644 0 16 18 2641 2673 0 48 13 0 0 0 0 0 19 52 0 586 0 14 15 0 0 2343 +394 423 0.999999337302774 6.67819451281861e-05 0.00114931900893083 -0.000700884980099417 -6.8403176906216e-05 0.999999002734795 0.00141062057979252 0.00626892235520069 -0.00114922365876882 -0.00141069826204966 0.999998344606328 0.000829926675811858 3.02675480005322e-05 1.14022178049554e-05 -5.79328506329878e-06 5.29105571779993e-06 1.84402619500561e-06 1.43165301413922e-05 1.14022178049554e-05 2.67648143571598e-05 -9.55825149593757e-06 3.59487802882818e-06 9.84100686067352e-06 1.62036028104032e-05 -5.79328506329878e-06 -9.55825149593757e-06 1.48604111588317e-05 2.38874587124576e-07 9.44255197491102e-07 -1.15235752614924e-06 5.29105571779993e-06 3.59487802882818e-06 2.38874587124576e-07 2.77557990606507e-05 -6.34008404333105e-06 3.49920627186768e-06 1.84402619500561e-06 9.84100686067352e-06 9.44255197491102e-07 -6.34008404333105e-06 4.36833399035724e-05 4.88302104524791e-06 1.43165301413922e-05 1.62036028104032e-05 -1.15235752614924e-06 3.49920627186768e-06 4.88302104524791e-06 4.90861543178798e-05 1989 1991 0 17 16 1988 2020 0 50 13 0 0 0 0 0 21 51 0 566 0 12 14 0 0 2258 +393 423 0.999999658792214 0.00030276561399605 0.000768601612409474 0.000123203058576389 -0.000302398852602439 0.99999984039297 -0.00047725147203902 0.00105634477822407 -0.000768745985070216 0.000477018884951401 0.999999590741213 0.000616333558967787 2.40485334709362e-05 1.38359982328642e-05 -6.1927477694286e-06 3.80596238106684e-06 7.39944358022737e-06 1.58196858770932e-05 1.38359982328642e-05 2.16572865464955e-05 -8.32171080267093e-06 3.05014351754518e-06 5.9596862153882e-06 1.92849802892413e-05 -6.1927477694286e-06 -8.32171080267093e-06 1.22041938991198e-05 2.2376790327084e-06 1.76778749891706e-07 -2.82943317694308e-06 3.80596238106684e-06 3.05014351754518e-06 2.2376790327084e-06 1.89284520655091e-05 5.56739537331065e-06 7.01330504262478e-06 7.39944358022737e-06 5.9596862153882e-06 1.76778749891706e-07 5.56739537331065e-06 2.64754803413592e-05 9.625032882518e-06 1.58196858770932e-05 1.92849802892413e-05 -2.82943317694308e-06 7.01330504262478e-06 9.625032882518e-06 4.18931709925847e-05 3040 3037 0 11 12 3036 3074 0 52 9 0 0 0 0 0 13 45 0 559 0 13 16 0 0 2246 +394 426 0.9999993773143 0.000459993528269715 0.00101674823126868 0.000918771956317643 -0.000461032324650509 0.999999371802419 0.00102168682219816 0.00637072340936447 -0.00101627762322377 -0.00102215493980903 0.999998961188996 0.000332970100575232 2.34294894679302e-05 1.1881277059475e-05 -4.4900470873638e-06 2.12023466499472e-06 6.30040150958308e-06 1.22051447905395e-05 1.1881277059475e-05 2.30163164665494e-05 -7.64625299964684e-06 6.81507883404637e-06 6.00014542162182e-06 1.30963949288953e-05 -4.4900470873638e-06 -7.64625299964684e-06 1.34960393114325e-05 1.7094039460387e-06 -3.39203843351924e-06 2.66614642105744e-07 2.12023466499472e-06 6.81507883404637e-06 1.7094039460387e-06 3.22230245531478e-05 -3.34321536746977e-06 6.66396549297564e-06 6.30040150958308e-06 6.00014542162182e-06 -3.39203843351924e-06 -3.34321536746977e-06 4.92279058200039e-05 6.79097562168358e-06 1.22051447905395e-05 1.30963949288953e-05 2.66614642105744e-07 6.66396549297564e-06 6.79097562168358e-06 4.18077107921473e-05 2584 2586 0 18 21 2582 2600 0 36 18 0 0 0 0 0 14 44 0 574 0 17 18 0 0 2088 +394 397 0.999999858719748 0.000294467779233156 -0.000442548540936497 -6.74749085012752e-05 -0.000294216838887217 0.999999795977789 0.000566992796926032 -0.000233476827417226 0.000442715411756517 -0.000566862511588378 0.999999741334945 0.00026497454316128 2.02451775083059e-05 1.10423832182203e-05 -2.52542283139133e-06 -1.41407944388725e-07 1.12790590861632e-07 9.21730127611371e-06 1.10423832182203e-05 1.81344408592306e-05 -3.69013044466841e-06 2.79052962175842e-06 1.21649075705976e-06 1.3570784568643e-05 -2.52542283139133e-06 -3.69013044466841e-06 1.04279410900636e-05 2.05332497118732e-06 4.02927004456389e-06 1.20908965793788e-06 -1.41407944388725e-07 2.79052962175842e-06 2.05332497118732e-06 2.63803418528427e-05 -9.90336800696238e-06 2.26666428912218e-06 1.12790590861632e-07 1.21649075705976e-06 4.02927004456389e-06 -9.90336800696238e-06 3.20488100000072e-05 8.91583166044935e-07 9.21730127611371e-06 1.3570784568643e-05 1.20908965793788e-06 2.26666428912218e-06 8.91583166044935e-07 3.36715342095259e-05 2761 2751 0 22 44 2731 2757 0 44 19 0 0 0 0 0 16 47 0 468 0 50 32 0 0 2435 +394 429 0.999972615137865 -0.00703944620363986 -0.00228367499562197 0.00277164651577784 0.00704496446508406 0.999972261898357 0.00241741795503509 0.00748621190496056 0.00226659436716664 -0.00243344016357162 0.999994470444185 0.00119511209474923 2.53906151322053e-05 1.0162531453165e-05 -3.81030016119355e-06 -1.18296641914021e-06 2.4219065702459e-06 1.04478906492712e-05 1.0162531453165e-05 2.29782540791394e-05 -4.71149282265838e-06 1.76199076923259e-06 -1.3548255180072e-06 1.2924681119941e-05 -3.81030016119355e-06 -4.71149282265838e-06 1.04038435717466e-05 4.88231285587364e-06 1.05429903249509e-06 1.33018535720011e-06 -1.18296641914021e-06 1.76199076923259e-06 4.88231285587364e-06 3.56124301419871e-05 -6.95836115532417e-06 4.51903123758556e-06 2.4219065702459e-06 -1.3548255180072e-06 1.05429903249509e-06 -6.95836115532417e-06 4.52064862274057e-05 -9.04180717617624e-07 1.04478906492712e-05 1.2924681119941e-05 1.33018535720011e-06 4.51903123758556e-06 -9.04180717617624e-07 4.59124140785056e-05 2083 2085 0 18 29 2084 2107 0 40 26 0 0 0 0 0 25 57 0 549 0 16 15 0 0 2458 +394 428 0.999999644713285 0.000796865415456985 0.000274916013100732 0.00772022448313018 -0.000796772979972121 0.999999626068663 -0.000336177561015803 0.00168902044167431 -0.000275183798572846 0.000335958395925381 0.999999905702912 -0.00539079811968787 3.42183967269921e-05 1.2004734793294e-05 -4.79645820231894e-06 1.81610688753044e-06 4.47150998516388e-06 1.26468894808822e-05 1.2004734793294e-05 2.53932805555911e-05 -6.70865119247584e-06 6.22003798538069e-06 8.07826675906489e-06 1.74414776378882e-05 -4.79645820231894e-06 -6.70865119247584e-06 1.25401540881252e-05 1.86359974922822e-06 -1.08571104834687e-06 -1.07158118355161e-06 1.81610688753044e-06 6.22003798538069e-06 1.86359974922822e-06 3.11700469968244e-05 7.54568371053706e-06 6.0596518914264e-06 4.47150998516388e-06 8.07826675906489e-06 -1.08571104834687e-06 7.54568371053706e-06 4.09581510269175e-05 3.93687257322807e-06 1.26468894808822e-05 1.74414776378882e-05 -1.07158118355161e-06 6.0596518914264e-06 3.93687257322807e-06 4.94340705337624e-05 2221 2230 0 27 18 2204 2238 0 50 8 0 0 0 0 0 16 47 0 559 0 21 22 0 0 2331 +394 424 0.999999940661158 0.000130103125649619 0.000318984100185586 -0.00121913089308947 -0.000129551780065437 0.999998498867231 -0.00172785405055712 0.0025368429250956 -0.000319208420560744 0.00172781262307027 0.99999845638357 -0.00066160110036495 3.6675127071583e-05 1.72233490419535e-05 -6.12446008372718e-06 6.1107627673681e-06 2.05010414569674e-06 1.83067029408416e-05 1.72233490419535e-05 2.5272568323433e-05 -7.77639039158789e-06 4.85801581002619e-06 4.80697857056355e-06 2.26574268803039e-05 -6.12446008372718e-06 -7.77639039158789e-06 1.16175658816079e-05 1.83659762600485e-06 3.384343369427e-08 -2.49735767788723e-06 6.1107627673681e-06 4.85801581002619e-06 1.83659762600485e-06 2.07978932057029e-05 2.94631778211584e-06 9.87190156590393e-06 2.05010414569674e-06 4.80697857056355e-06 3.384343369427e-08 2.94631778211584e-06 3.13234869231162e-05 3.42465612566287e-06 1.83067029408416e-05 2.26574268803039e-05 -2.49735767788723e-06 9.87190156590393e-06 3.42465612566287e-06 4.9973885113776e-05 2860 2858 0 16 18 2854 2887 0 38 14 0 0 0 0 0 14 45 0 574 0 15 15 0 0 2249 +394 425 0.999998713675027 0.000676181577588677 0.00145445067486745 -0.00202557304606959 -0.000676814719506902 0.999999676406953 0.000434865295286494 0.00312531437653919 -0.00145415615631592 -0.000435849129533952 0.999998847732041 -0.000884053129237139 2.90957845712717e-05 7.04785757512763e-06 -4.639327448751e-06 5.06285587975762e-06 1.96589150954935e-06 2.90054375353403e-06 7.04785757512763e-06 2.22861666965321e-05 -6.26170431361593e-06 4.56451463161949e-06 2.48661398324589e-06 1.33824949836761e-05 -4.639327448751e-06 -6.26170431361593e-06 1.12835728717324e-05 2.59660833668289e-06 2.61001216586394e-06 -2.10678599503538e-06 5.06285587975762e-06 4.56451463161949e-06 2.59660833668289e-06 2.54482398493701e-05 3.43970164539197e-06 1.63458120036063e-06 1.96589150954935e-06 2.48661398324589e-06 2.61001216586394e-06 3.43970164539197e-06 3.0244242503026e-05 5.26347991713247e-06 2.90054375353403e-06 1.33824949836761e-05 -2.10678599503538e-06 1.63458120036063e-06 5.26347991713247e-06 4.51201160410678e-05 2263 2266 0 19 19 2262 2298 0 45 15 0 0 0 0 0 12 41 0 571 0 16 16 0 0 2039 +394 398 0.99999990757774 0.000299491444496151 -0.000308462942006024 0.00536992064721908 -0.000299694053517091 0.999999739268787 -0.000656997589363588 -0.00761579368582667 0.000308266096423038 0.000657089973151835 0.999999736602356 -0.00583040293745764 3.58441918669611e-05 1.77683721774354e-05 -3.27963107043378e-06 6.07891970401061e-06 -7.02465709962966e-06 1.30491411335239e-05 1.77683721774354e-05 3.23875959562836e-05 -3.01395370188047e-06 1.00305325405981e-05 -2.21694964333029e-06 2.28232335390933e-05 -3.27963107043378e-06 -3.01395370188047e-06 1.02663208085063e-05 2.14300594884417e-06 3.71326474704486e-06 -5.54819441180479e-07 6.07891970401061e-06 1.00305325405981e-05 2.14300594884417e-06 3.13569504833147e-05 -1.0226162443952e-05 1.0224676550165e-05 -7.02465709962966e-06 -2.21694964333029e-06 3.71326474704486e-06 -1.0226162443952e-05 3.68243108065427e-05 -3.6820826186125e-06 1.30491411335239e-05 2.28232335390933e-05 -5.54819441180479e-07 1.0224676550165e-05 -3.6820826186125e-06 4.08171257909222e-05 2222 2212 0 21 42 2193 2213 0 48 9 0 0 0 0 0 14 45 0 466 0 57 41 0 0 2386 +395 428 0.999988596269474 9.27662853114424e-07 0.00477570205799769 0.00933466312216453 -8.55555117988674e-06 0.999998724425083 0.0015972085051038 0.00166750297449877 -0.00477569448456094 -0.00159723114973179 0.99998732071704 -0.00268586511978431 3.12750929468608e-05 1.05176807519442e-05 -6.1824523810976e-06 4.39509743782368e-06 1.08682765359207e-07 1.39725333848526e-05 1.05176807519442e-05 2.49105328593952e-05 -7.41540112465371e-06 5.50201837857795e-06 4.02367747627274e-06 1.65016102106415e-05 -6.1824523810976e-06 -7.41540112465371e-06 1.15119519132187e-05 -3.57091107555468e-07 2.47253818642331e-07 -1.64352104280271e-06 4.39509743782368e-06 5.50201837857795e-06 -3.57091107555468e-07 2.96006033397659e-05 7.13878199015249e-06 9.04537837929976e-06 1.08682765359207e-07 4.02367747627274e-06 2.47253818642331e-07 7.13878199015249e-06 3.2696890257015e-05 6.69158914684006e-06 1.39725333848526e-05 1.65016102106415e-05 -1.64352104280271e-06 9.04537837929976e-06 6.69158914684006e-06 4.14198735625945e-05 2589 2594 0 24 16 2584 2617 0 45 25 0 0 0 0 0 12 44 0 552 0 16 17 0 0 2347 +394 422 0.999999876379481 1.21015805865084e-05 0.000497086083090298 0.00489410034406114 -1.26226986627051e-05 0.999999450395054 0.00104835597814549 0.00130116054070568 -0.000497073123124976 -0.00104836212311502 0.999999326927358 -0.00442086525080677 3.14570575305877e-05 9.78363854539113e-06 -6.7278935351317e-06 1.23409579306553e-06 3.92718856889531e-06 1.19822858430237e-05 9.78363854539113e-06 2.38000562103e-05 -7.53186426064818e-06 4.89037941268419e-06 5.18523952863284e-06 1.2274263349325e-05 -6.7278935351317e-06 -7.53186426064818e-06 1.45372314726959e-05 -2.22255846821736e-07 2.74066586920573e-08 -2.31150620122654e-06 1.23409579306553e-06 4.89037941268419e-06 -2.22255846821736e-07 3.41508768306961e-05 -2.3489304488035e-06 1.46267756086363e-06 3.92718856889531e-06 5.18523952863284e-06 2.74066586920573e-08 -2.3489304488035e-06 3.25347316878988e-05 4.82475068190629e-06 1.19822858430237e-05 1.2274263349325e-05 -2.31150620122654e-06 1.46267756086363e-06 4.82475068190629e-06 3.68610426526917e-05 2076 2078 0 19 20 2076 2109 0 52 16 0 0 0 0 0 11 44 0 551 0 48 49 0 0 2336 +395 427 0.99999188744696 0.000222391733878174 0.00402188788786519 0.00713802683522286 -0.000227267973514148 0.999999239691232 0.00121200916951901 0.000802407020684115 -0.00402161528916788 -0.00121291338334031 0.999991177686879 -0.00300717806384162 2.1447455162639e-05 1.39611533627309e-05 -6.30615198666269e-06 4.48988505493177e-06 6.46679103419356e-06 1.18667345586283e-05 1.39611533627309e-05 2.48765237903237e-05 -8.57475544382865e-06 1.62052041719153e-06 7.62035136991903e-06 1.500407995214e-05 -6.30615198666269e-06 -8.57475544382865e-06 1.3906882460556e-05 7.94402232027339e-07 -2.74379760689689e-06 -2.18135664406123e-06 4.48988505493177e-06 1.62052041719153e-06 7.94402232027339e-07 3.33256623464917e-05 -6.87800594413344e-06 4.4058811016966e-06 6.46679103419356e-06 7.62035136991903e-06 -2.74379760689689e-06 -6.87800594413344e-06 4.89406422258998e-05 4.45921321070217e-06 1.18667345586283e-05 1.500407995214e-05 -2.18135664406123e-06 4.4058811016966e-06 4.45921321070217e-06 3.39100733472569e-05 2031 2032 0 18 17 2027 2058 0 48 14 0 0 0 0 0 13 44 0 580 0 18 18 0 0 2307 +395 397 0.99999940792523 0.000320645575918484 0.00103987287841004 0.003625891963691 -0.000321771745001661 0.999999361785848 0.00108300084959529 -0.0030959699762363 -0.00103952495531732 -0.00108333481008848 0.999998872886143 -0.00119100765036483 3.77885287086854e-05 1.48159518045142e-05 -3.65667919032775e-06 3.40039329157841e-06 -8.40514894508362e-07 1.8033055759948e-05 1.48159518045142e-05 2.8559560338031e-05 -4.93083476109048e-06 4.24824436603496e-06 2.38360577320958e-06 1.72145355928668e-05 -3.65667919032775e-06 -4.93083476109048e-06 1.37497439317835e-05 4.45954685419111e-06 2.89921155091171e-06 -1.37885912774117e-06 3.40039329157841e-06 4.24824436603496e-06 4.45954685419111e-06 2.9554799735584e-05 -6.54101642237088e-06 2.78771700483916e-06 -8.40514894508362e-07 2.38360577320958e-06 2.89921155091171e-06 -6.54101642237088e-06 3.1871656184826e-05 6.01708649683031e-07 1.8033055759948e-05 1.72145355928668e-05 -1.37885912774117e-06 2.78771700483916e-06 6.01708649683031e-07 3.47703305795318e-05 1325 1319 0 25 43 1295 1321 0 44 26 0 0 0 0 0 11 42 0 461 0 67 49 0 0 2426 +395 426 0.999998530355514 0.000939910975295749 0.00143382501383358 -0.00174246096936954 -0.000941473014221416 0.999998963705983 0.00108913521810272 0.00990112389379898 -0.00143279983782422 -0.0010904835250188 0.999998378963839 -0.00102128745670092 2.3932297234978e-05 1.29993032736816e-05 -5.59233722958638e-06 2.32470703749294e-06 3.58089120305221e-06 1.18132270100627e-05 1.29993032736816e-05 2.21284715973217e-05 -7.97220770769918e-06 4.23163809020744e-06 4.77574336623724e-06 1.32658427844499e-05 -5.59233722958638e-06 -7.97220770769918e-06 1.51146118402471e-05 4.64031682716786e-06 -4.58060194227803e-06 -3.30970841100215e-06 2.32470703749294e-06 4.23163809020744e-06 4.64031682716786e-06 3.06443948048508e-05 -4.97764457600755e-06 -6.97333084242395e-07 3.58089120305221e-06 4.77574336623724e-06 -4.58060194227803e-06 -4.97764457600755e-06 5.26764518477443e-05 4.88264573212223e-06 1.18132270100627e-05 1.32658427844499e-05 -3.30970841100215e-06 -6.97333084242395e-07 4.88264573212223e-06 3.5855834765289e-05 2026 2030 0 24 17 2022 2050 0 50 18 0 0 0 0 0 16 46 0 586 0 28 29 0 0 2095 +395 421 0.999999730944765 0.000448863150864136 -0.000580200198596407 -0.00235798683481888 -0.000448465581894887 0.999999664706322 0.000685175791471947 0.00596874420913875 0.000580507554223604 -0.000684915407302134 0.999999596950851 0.000367202226618475 2.44517587486955e-05 1.2746824020226e-05 -6.54469961600538e-06 5.76250778059595e-06 7.65849534875471e-07 8.46301093304714e-06 1.2746824020226e-05 2.23556140599584e-05 -7.80969036022095e-06 5.19139632562594e-06 5.29877450632095e-06 1.62673391628177e-05 -6.54469961600538e-06 -7.80969036022095e-06 1.50963678393445e-05 -1.45941583957108e-07 -2.9837817009557e-06 -1.40737106378118e-06 5.76250778059595e-06 5.19139632562594e-06 -1.45941583957108e-07 3.24771745985498e-05 -8.43922205484198e-08 4.81668673084581e-06 7.65849534875471e-07 5.29877450632095e-06 -2.9837817009557e-06 -8.43922205484198e-08 4.19192753910999e-05 -9.78794969281238e-07 8.46301093304714e-06 1.62673391628177e-05 -1.40737106378118e-06 4.81668673084581e-06 -9.78794969281238e-07 3.68833979603052e-05 1965 1962 0 10 14 1965 1992 0 39 14 0 0 0 0 0 16 49 0 585 0 25 25 0 0 2336 +395 425 0.999999068034566 0.000826429146108661 -0.00108671287196534 -0.000558038658501401 -0.000827867009682631 0.999998781692925 -0.00132334760368416 -0.00389131166365654 0.00108561789498524 0.00132424602410563 0.999998533902052 0.00230128627750261 3.72648039893694e-05 7.15071789106611e-06 -5.63072699068654e-06 -4.10277519641025e-06 5.97472675037695e-06 5.13148974969312e-06 7.15071789106611e-06 2.8295019609662e-05 -8.97188011838068e-06 8.57019830487098e-06 5.35155618892489e-06 1.60726849408731e-05 -5.63072699068654e-06 -8.97188011838068e-06 1.40277681290958e-05 1.21981974538195e-06 8.67321548588591e-07 -2.84848769532049e-06 -4.10277519641025e-06 8.57019830487098e-06 1.21981974538195e-06 3.40683730718143e-05 -4.63182574192571e-07 1.25482213954027e-06 5.97472675037695e-06 5.35155618892489e-06 8.67321548588591e-07 -4.63182574192571e-07 3.63664696524078e-05 6.59678679748034e-06 5.13148974969312e-06 1.60726849408731e-05 -2.84848769532049e-06 1.25482213954027e-06 6.59678679748034e-06 3.90678939225537e-05 2658 2662 0 23 16 2705 2739 0 45 19 0 0 0 0 0 13 44 0 576 0 49 50 0 0 2057 +395 398 0.999998720336417 7.33517556144726e-05 0.00159810670742614 0.00800620013041807 -7.27799349302528e-05 0.999999933317306 -0.000357866545520301 -0.00870271514116588 -0.00159813285099947 0.000357749777469337 0.999998658992345 -0.00390239043868002 3.54309889812e-05 2.07308607554924e-05 -4.26148329108248e-06 3.20265165353433e-06 -1.94659437693743e-07 2.2181977604433e-05 2.07308607554924e-05 2.8615032331923e-05 -5.13983971164927e-06 7.23194211209943e-06 2.46267737839081e-06 2.31215428732689e-05 -4.26148329108248e-06 -5.13983971164927e-06 1.04910822319845e-05 2.25435161550707e-06 3.3406242773621e-06 -2.30425751819587e-06 3.20265165353433e-06 7.23194211209943e-06 2.25435161550707e-06 3.31536653097487e-05 -1.25908571892814e-05 6.2739726893472e-06 -1.94659437693743e-07 2.46267737839081e-06 3.3406242773621e-06 -1.25908571892814e-05 3.91171063924573e-05 3.75687569078774e-06 2.2181977604433e-05 2.31215428732689e-05 -2.30425751819587e-06 6.2739726893472e-06 3.75687569078774e-06 4.15529389641076e-05 2693 2681 0 24 45 2673 2705 0 52 24 0 0 0 0 0 12 44 0 473 0 51 35 0 0 2394 +395 429 0.999968013526236 -0.00726142752320415 -0.00335314698734731 0.00392834689064593 0.00726906159226257 0.999971003181805 0.0022701407761035 -6.47277237587714e-05 0.00333656529404059 -0.00229444239428406 0.99999180139946 -0.00202760878357256 4.88791538339265e-05 1.59270171715273e-05 -2.09138961050151e-06 3.08832137764397e-06 -8.30101278828553e-06 1.38202178166571e-05 1.59270171715273e-05 3.78908667599716e-05 -4.87776024682025e-06 5.9998958720431e-06 9.73965911517167e-07 2.30154518094918e-05 -2.09138961050151e-06 -4.87776024682025e-06 1.12975055010887e-05 2.79473027702931e-06 1.19398535408674e-06 1.80645747547585e-06 3.08832137764397e-06 5.9998958720431e-06 2.79473027702931e-06 3.08473668847405e-05 6.45775419454984e-07 2.7759061461701e-06 -8.30101278828553e-06 9.73965911517167e-07 1.19398535408674e-06 6.45775419454984e-07 3.50927530284489e-05 -1.31142497887323e-06 1.38202178166571e-05 2.30154518094918e-05 1.80645747547585e-06 2.7759061461701e-06 -1.31142497887323e-06 4.76060312176709e-05 2167 2172 0 19 24 2169 2190 0 36 32 0 0 0 0 0 25 57 0 559 0 25 24 0 0 2450 +396 425 0.999999786411058 0.000247851552089212 0.000604770574211239 -0.00485556111048493 -0.000248365967784759 0.999999607337674 0.000850669644369125 0.00808006110142031 -0.000604559496948946 -0.000850819667104447 0.999999455306706 -0.00229150283411424 2.68282586957691e-05 8.90002160231912e-06 -5.55346022780059e-06 3.31847097170692e-06 6.21924240773529e-06 2.97520394403843e-06 8.90002160231912e-06 2.11076928781715e-05 -7.06141602671277e-06 3.17300043760977e-06 3.958707643393e-06 1.20955495542877e-05 -5.55346022780059e-06 -7.06141602671277e-06 1.20714076795378e-05 1.55798349307401e-06 5.70593543662964e-07 -1.4950028568216e-06 3.31847097170692e-06 3.17300043760977e-06 1.55798349307401e-06 3.38024114918899e-05 -5.15831847387782e-06 7.86207145326154e-06 6.21924240773529e-06 3.958707643393e-06 5.70593543662964e-07 -5.15831847387782e-06 3.76840613776473e-05 2.14308205220901e-06 2.97520394403843e-06 1.20955495542877e-05 -1.4950028568216e-06 7.86207145326154e-06 2.14308205220901e-06 3.62149649560072e-05 2821 2820 0 17 19 2818 2849 0 38 19 0 0 0 0 0 19 49 0 581 0 19 21 0 0 2128 +395 424 0.999998808131053 0.000458065189421756 -0.00147441946421205 0.00147152268146418 -0.000458919062195437 0.999999727169595 -0.000578838517211721 -0.0013780586768922 0.00147415391617056 0.000579514466509865 0.99999874551582 -0.000741504461382902 3.69502997662024e-05 1.37128736020153e-05 -5.86657508525631e-06 1.80853817532109e-06 8.31879526080287e-07 1.45092488915996e-05 1.37128736020153e-05 2.52555451402597e-05 -8.0893143573342e-06 7.44381276223694e-06 5.80828670508906e-06 1.48516591021074e-05 -5.86657508525631e-06 -8.0893143573342e-06 1.47292208672685e-05 1.43336702669096e-06 2.64979003751288e-07 -1.11300997746785e-06 1.80853817532109e-06 7.44381276223694e-06 1.43336702669096e-06 3.04206831085141e-05 -5.39150536920601e-06 2.04411620490931e-06 8.31879526080287e-07 5.80828670508906e-06 2.64979003751288e-07 -5.39150536920601e-06 4.86577935232283e-05 5.36642672573297e-06 1.45092488915996e-05 1.48516591021074e-05 -1.11300997746785e-06 2.04411620490931e-06 5.36642672573297e-06 3.69051963330833e-05 2418 2415 0 17 15 2462 2502 0 51 14 0 0 0 0 0 15 46 0 579 0 48 49 0 0 2232 +396 398 0.99999997197436 0.000170855394728489 -0.00016388933008529 0.00142519388738564 -0.000170816452624643 0.999999957184756 0.000237596772469803 -0.00321553438904289 0.000163929917758675 -0.000237568770817013 0.99999995834403 -0.00330517616030997 1.96479849477856e-05 1.48904019676128e-05 -2.61936978602122e-06 4.41565823901402e-06 -9.24205059897178e-07 1.07629378167827e-05 1.48904019676128e-05 1.79909609509662e-05 -3.70652599016732e-06 4.62164401177793e-06 -1.96547225889847e-06 1.49773077275518e-05 -2.61936978602122e-06 -3.70652599016732e-06 1.0388902032606e-05 4.54297506518564e-06 1.83982190016513e-06 -4.45658904928538e-07 4.41565823901402e-06 4.62164401177793e-06 4.54297506518564e-06 2.94988936085524e-05 -1.33376654696496e-05 8.41855765809774e-06 -9.24205059897178e-07 -1.96547225889847e-06 1.83982190016513e-06 -1.33376654696496e-05 4.05466996582221e-05 -3.24108412180179e-06 1.07629378167827e-05 1.49773077275518e-05 -4.45658904928538e-07 8.41855765809774e-06 -3.24108412180179e-06 3.10773445971474e-05 2394 2379 0 18 45 2413 2446 0 50 23 0 0 0 0 0 18 49 0 467 0 97 87 0 0 2502 +396 426 0.999999079133046 0.000507385875710342 0.00125868686893273 0.000167283039186693 -0.00050760924823565 0.999999855475067 0.000177151617402879 0.00860782741600819 -0.00125859680279257 -0.000177790375365112 0.999999192162009 0.00278817654551036 3.13888199746105e-05 2.03024727777626e-05 -6.5051734177639e-06 7.02062589774746e-06 8.83801373972274e-06 2.07209203863062e-05 2.03024727777626e-05 2.29973472778438e-05 -8.53235548363274e-06 5.63181826199988e-06 4.75579939085115e-06 1.75567792819393e-05 -6.5051734177639e-06 -8.53235548363274e-06 1.39807848411765e-05 -3.32580959379618e-07 -6.71936479225049e-07 -1.83909820542888e-06 7.02062589774746e-06 5.63181826199988e-06 -3.32580959379618e-07 3.12489424808343e-05 5.61640458503547e-07 6.76696683593211e-06 8.83801373972274e-06 4.75579939085115e-06 -6.71936479225049e-07 5.61640458503547e-07 3.88747204730759e-05 7.12109203124431e-06 2.07209203863062e-05 1.75567792819393e-05 -1.83909820542888e-06 6.76696683593211e-06 7.12109203124431e-06 4.09321061823559e-05 2740 2737 0 8 19 2769 2806 0 51 18 0 0 0 0 0 18 48 0 579 0 20 21 0 0 2108 +396 424 0.999999776014353 0.000662208158172214 9.7219332742698e-05 -0.00251480496043847 -0.000662220014307904 0.999999773293844 0.000121970952107385 0.00372013655640617 -9.71385405429313e-05 -0.000122035305375562 0.999999987835744 -0.00149980849450347 2.65571687292813e-05 1.47376868569733e-05 -7.71878240649851e-06 4.92626028458063e-06 7.66484293120572e-06 1.43610685969824e-05 1.47376868569733e-05 1.74969915734897e-05 -8.43418117436879e-06 2.94679405064381e-06 2.9038278341955e-06 1.27990176885309e-05 -7.71878240649851e-06 -8.43418117436879e-06 1.2226089308912e-05 2.06537232811644e-06 1.02225725338583e-06 -2.6597291725982e-06 4.92626028458063e-06 2.94679405064381e-06 2.06537232811644e-06 2.25821749690806e-05 3.26233994487893e-06 1.081146909968e-05 7.66484293120572e-06 2.9038278341955e-06 1.02225725338583e-06 3.26233994487893e-06 2.400607643386e-05 4.80678497468403e-06 1.43610685969824e-05 1.27990176885309e-05 -2.6597291725982e-06 1.081146909968e-05 4.80678497468403e-06 3.46544948334098e-05 3015 3020 0 20 17 3014 3057 0 51 18 0 0 0 0 0 13 43 0 578 0 18 20 0 0 2227 +395 423 0.999998614913074 9.42508381145739e-05 -0.0016617125845567 -0.000593880577661482 -9.61605490372977e-05 0.999999335045824 -0.00114920018193302 -0.00119709577072206 0.00166160316651367 0.00114935838138534 0.999997959023031 -0.000854446236638063 3.41932073509516e-05 1.46905224748434e-05 -8.38429142650396e-06 3.90812613501221e-06 3.40680849649822e-06 1.53631508184307e-05 1.46905224748434e-05 2.73686511280726e-05 -9.87950495014e-06 6.43427485165952e-06 9.34934093283362e-06 2.03222040852028e-05 -8.38429142650396e-06 -9.87950495014e-06 1.48221639771912e-05 8.06757117704747e-09 -2.68705213949402e-06 -4.04874285619994e-06 3.90812613501221e-06 6.43427485165952e-06 8.06757117704747e-09 2.66685914258295e-05 4.38921097072384e-06 2.39340224710511e-06 3.40680849649822e-06 9.34934093283362e-06 -2.68705213949402e-06 4.38921097072384e-06 3.5090754143001e-05 7.23287969294451e-06 1.53631508184307e-05 2.03222040852028e-05 -4.04874285619994e-06 2.39340224710511e-06 7.23287969294451e-06 3.7518408142493e-05 2192 2198 0 24 12 2193 2228 0 50 12 0 0 0 0 0 13 44 0 561 0 23 24 0 0 2278 +395 422 0.999999973169277 0.000126304900429283 0.000194186808050744 0.00137743995369029 -0.000126317241669136 0.999999990003153 6.35424900606328e-05 -0.000408893442493273 -0.000194178780381608 -6.35670174977034e-05 0.999999979126918 -0.000683682959273983 3.13001510293817e-05 1.63539611752837e-05 -7.6271824881847e-06 4.74287691502667e-06 9.11350472683524e-06 2.06432827901629e-05 1.63539611752837e-05 2.71812802759091e-05 -8.78273167339052e-06 4.92474824403267e-06 8.11744579273726e-06 2.25178072229193e-05 -7.6271824881847e-06 -8.78273167339052e-06 1.34434231229302e-05 1.5903808638661e-06 -5.07110645808735e-06 -3.98225456830102e-06 4.74287691502667e-06 4.92474824403267e-06 1.5903808638661e-06 2.14227131539399e-05 9.69906934249718e-07 7.27453901410662e-06 9.11350472683524e-06 8.11744579273726e-06 -5.07110645808735e-06 9.69906934249718e-07 4.30284113689776e-05 7.16135618321284e-06 2.06432827901629e-05 2.25178072229193e-05 -3.98225456830102e-06 7.27453901410662e-06 7.16135618321284e-06 4.15827524275264e-05 3296 3299 0 17 14 3296 3343 0 52 15 0 0 0 0 0 12 46 0 550 0 16 16 0 0 2313 +396 427 0.999991191115336 -0.000367048088550362 0.0041812638559188 0.00987099777645893 0.000358471796436462 0.999997831032425 0.00205168916165491 -0.00265959196859273 -0.00418200785547816 -0.00205017222339591 0.999989153743255 -0.00356197865025392 4.01171186069053e-05 2.08152946752284e-05 -8.76741195748384e-06 5.4076893070244e-06 2.72173406460695e-06 2.11535137631e-05 2.08152946752284e-05 2.57042976700498e-05 -1.0975348593139e-05 6.96561847568965e-06 3.89457067611128e-06 1.98238447781052e-05 -8.76741195748384e-06 -1.0975348593139e-05 1.58614353579725e-05 -2.33155821559165e-06 -1.00910845568236e-06 -3.65555951266812e-06 5.4076893070244e-06 6.96561847568965e-06 -2.33155821559165e-06 3.25585000446903e-05 5.61721926037583e-06 7.76565327698474e-06 2.72173406460695e-06 3.89457067611128e-06 -1.00910845568236e-06 5.61721926037583e-06 3.6188097604474e-05 5.44157419443475e-06 2.11535137631e-05 1.98238447781052e-05 -3.65555951266812e-06 7.76565327698474e-06 5.44157419443475e-06 3.9978166131949e-05 2109 2110 0 22 17 2146 2183 0 48 19 0 0 0 0 0 17 47 0 579 0 59 63 0 0 2326 +396 428 0.999999853694025 0.000456552224335989 -0.000290124102085522 0.00423658246075081 -0.000456238841236296 0.99999931345825 0.00107931883544656 0.00374036205868858 0.000290616668318304 -0.00107918631165161 0.999999375449233 -0.00381719105773183 3.9976508033601e-05 2.63528944620865e-05 -8.83430317628455e-06 9.5409321457067e-06 -1.08654799456003e-06 2.17120595669963e-05 2.63528944620865e-05 3.02865730767571e-05 -1.0198341100026e-05 1.06891680230389e-05 -1.12507585247184e-06 2.71960728590932e-05 -8.83430317628455e-06 -1.0198341100026e-05 1.41626827853995e-05 1.07771854543807e-06 -8.022969082003e-07 -2.84965817909462e-06 9.5409321457067e-06 1.06891680230389e-05 1.07771854543807e-06 3.14126927205241e-05 2.71550524002638e-06 1.54505399088215e-05 -1.08654799456003e-06 -1.12507585247184e-06 -8.022969082003e-07 2.71550524002638e-06 3.96503288110685e-05 -5.84355788498783e-07 2.17120595669963e-05 2.71960728590932e-05 -2.84965817909462e-06 1.54505399088215e-05 -5.84355788498783e-07 5.8402282044058e-05 2382 2380 0 6 19 2428 2460 0 43 20 0 0 0 0 0 12 45 0 560 0 66 70 0 0 2239 +397 399 0.999997516151881 -0.000155874270819213 0.00222337430070771 0.00552947355152764 0.000156620741378335 0.999999931432185 -0.000335567531165617 -0.00478433536700584 -0.00222332184191156 0.000335914924198174 0.99999747199738 0.00122721402129253 3.25767809600451e-05 2.4949593987958e-05 -5.20385366226532e-06 4.62946556480923e-06 7.74398567325704e-06 3.20548247219686e-05 2.4949593987958e-05 3.05949603653316e-05 -4.90480278933123e-06 6.79446444225788e-06 4.1253495634138e-06 3.46375646493759e-05 -5.20385366226532e-06 -4.90480278933123e-06 1.17193739928055e-05 4.3612057339976e-06 2.23403426571747e-06 -3.1422416287886e-06 4.62946556480923e-06 6.79446444225788e-06 4.3612057339976e-06 2.37829394910673e-05 8.39448095645777e-07 5.22088181191646e-06 7.74398567325704e-06 4.1253495634138e-06 2.23403426571747e-06 8.39448095645777e-07 2.85095626274099e-05 5.38997967941564e-06 3.20548247219686e-05 3.46375646493759e-05 -3.1422416287886e-06 5.22088181191646e-06 5.38997967941564e-06 6.57381966926635e-05 2313 2297 0 17 48 2300 2329 0 47 31 0 0 0 0 0 12 45 0 477 0 49 33 0 0 2447 +396 422 0.999999332251037 -0.000203388430745808 0.00113759862270502 0.00292489109589727 0.000202534129459618 0.999999697464047 0.000751033781845285 0.00231200546470882 -0.00113775103012286 -0.000750802877796532 0.999999070908385 -0.00406015683694895 3.68302819947696e-05 1.60590852009514e-05 -6.64803774485561e-06 -1.30566284389695e-06 1.09538911829629e-05 1.7663183802433e-05 1.60590852009514e-05 3.07761156828901e-05 -7.10515892108293e-06 1.07732613189731e-06 7.85519759016288e-06 2.01539549652143e-05 -6.64803774485561e-06 -7.10515892108293e-06 1.29229815792689e-05 3.46994452831743e-07 1.60563926128092e-06 -2.24642879013933e-06 -1.30566284389695e-06 1.07732613189731e-06 3.46994452831743e-07 3.23150417595828e-05 -4.13065426694859e-06 2.72126240472882e-06 1.09538911829629e-05 7.85519759016288e-06 1.60563926128092e-06 -4.13065426694859e-06 3.66244800572373e-05 8.90038571402646e-06 1.7663183802433e-05 2.01539549652143e-05 -2.24642879013933e-06 2.72126240472882e-06 8.90038571402646e-06 5.03932328663156e-05 2628 2630 0 19 17 2665 2695 0 42 17 0 0 0 0 0 17 50 0 545 0 20 21 0 0 2330 +397 426 0.999998466162842 9.03332446205079e-06 0.00175145378553723 0.0013134765515722 -1.00116225726328e-05 0.999999843957742 0.000558555510880079 0.00447426838733944 -0.00175144846662327 -0.000558572189041136 0.999998310211262 -0.000590733886630479 2.62899054840572e-05 1.35112588219799e-05 -6.09769811773728e-06 2.86098630678455e-06 6.68215414728572e-06 1.54294987603786e-05 1.35112588219799e-05 2.02965908618756e-05 -7.98472116142714e-06 2.83578609306068e-06 5.53248505133602e-06 1.4441854526856e-05 -6.09769811773728e-06 -7.98472116142714e-06 1.30912433395642e-05 2.6978768404119e-06 -1.61544938392999e-06 -1.05505687923088e-06 2.86098630678455e-06 2.83578609306068e-06 2.6978768404119e-06 2.36563972223885e-05 5.7133408437421e-06 8.23182235246882e-06 6.68215414728572e-06 5.53248505133602e-06 -1.61544938392999e-06 5.7133408437421e-06 3.69431350990955e-05 7.27214174529154e-06 1.54294987603786e-05 1.4441854526856e-05 -1.05505687923088e-06 8.23182235246882e-06 7.27214174529154e-06 4.1271551620834e-05 2937 2932 0 18 17 2935 2968 0 48 20 0 0 0 0 0 15 45 0 576 0 22 24 0 0 2071 +396 423 0.999999568479089 0.000499292567008922 -0.000783421066600958 -0.0042991616616914 -0.000499837976257654 0.999999632769997 -0.0006961478783951 0.0072359067565303 0.000783073197444015 0.000696539161593221 0.999999450814631 -0.000111144520072101 2.39832511972827e-05 1.00419576302375e-05 -4.40722473079884e-06 -2.96842289702737e-07 5.89313816155753e-06 5.09918750788789e-06 1.00419576302375e-05 2.38340546607899e-05 -7.01262593191423e-06 6.71055458483117e-06 2.81154963556845e-06 1.56812010847871e-05 -4.40722473079884e-06 -7.01262593191423e-06 1.24982563360547e-05 2.28366524549141e-06 2.01084923035718e-06 -2.10070374041344e-07 -2.96842289702737e-07 6.71055458483117e-06 2.28366524549141e-06 3.50704958081893e-05 -8.19575192850482e-06 7.52194875896298e-06 5.89313816155753e-06 2.81154963556845e-06 2.01084923035718e-06 -8.19575192850482e-06 4.3223882351137e-05 5.89789876689963e-06 5.09918750788789e-06 1.56812010847871e-05 -2.10070374041344e-07 7.52194875896298e-06 5.89789876689963e-06 3.94514095143349e-05 2591 2589 0 11 13 2611 2643 0 38 13 0 0 0 0 0 13 45 0 561 0 15 16 0 0 2248 +397 429 0.999970491655291 -0.00752829589355367 -0.00152989529519543 0.00264394055599283 0.00753381113775473 0.999965025343217 0.00363177368250597 0.00164770240316278 0.00150250072073224 -0.00364319245709079 0.999992234790003 -0.00270974929627952 2.50698990237974e-05 1.15940195263864e-05 -2.43302009721353e-06 3.49954439309165e-06 1.79517781396015e-06 1.55890516823605e-05 1.15940195263864e-05 2.042755056834e-05 -5.9125826000927e-06 2.16025874796186e-06 2.63928750811246e-06 1.35328835064317e-05 -2.43302009721353e-06 -5.9125826000927e-06 1.05981173550042e-05 2.50897703347332e-06 1.46541736022434e-06 6.14092870873904e-07 3.49954439309165e-06 2.16025874796186e-06 2.50897703347332e-06 2.37445117926576e-05 5.75466886117927e-06 4.80014113027436e-06 1.79517781396015e-06 2.63928750811246e-06 1.46541736022434e-06 5.75466886117927e-06 2.67291511047632e-05 4.31780348315172e-06 1.55890516823605e-05 1.35328835064317e-05 6.14092870873904e-07 4.80014113027436e-06 4.31780348315172e-06 4.14606223473302e-05 2366 2364 0 4 25 2378 2403 0 37 29 0 0 0 0 0 26 58 0 557 0 22 22 0 0 2382 +396 429 0.999974928690437 -0.00705935976683965 -0.000554463919822708 0.00136088836472581 0.00706168386573613 0.999965786708079 0.00430790369821675 0.0104321226440535 0.000524033907740149 -0.00431171114234631 0.999990567223256 -0.000981764955605056 4.51519144022178e-05 1.79890386024274e-05 -5.40628009044233e-06 -2.01456490345284e-06 1.13476309620366e-06 2.48665479205076e-05 1.79890386024274e-05 3.36885683159761e-05 -8.73974123629956e-06 4.89290771603421e-06 2.40012178906268e-06 1.38486135586782e-05 -5.40628009044233e-06 -8.73974123629956e-06 1.32394706409315e-05 1.81902017565534e-06 2.3910247167694e-06 1.09881393052527e-06 -2.01456490345284e-06 4.89290771603421e-06 1.81902017565534e-06 3.29896678000973e-05 -3.75455840906322e-06 6.29841433875331e-06 1.13476309620366e-06 2.40012178906268e-06 2.3910247167694e-06 -3.75455840906322e-06 3.97734470105464e-05 -1.75817357950481e-07 2.48665479205076e-05 1.38486135586782e-05 1.09881393052527e-06 6.29841433875331e-06 -1.75817357950481e-07 5.65619830177363e-05 2545 2543 0 2 29 2570 2592 0 28 29 0 0 0 0 0 32 64 0 554 0 19 17 0 0 2380 +398 429 0.999973191084411 -0.00732108388159466 0.000137270746121781 0.00472577115383292 0.00732057283199625 0.999967380087418 0.00341291290779874 0.00138035112241001 -0.000162252490040615 -0.00341181651081 0.999994166574099 -0.00731139618351359 3.03029289635268e-05 1.7573105993737e-05 -3.55494049739613e-06 5.26500421799297e-06 -5.25550465884422e-06 1.80633040284911e-05 1.7573105993737e-05 3.3530208116745e-05 -7.05045031015319e-06 6.88573444747139e-06 -4.01323187393364e-07 1.87108284792349e-05 -3.55494049739613e-06 -7.05045031015319e-06 1.13399639301887e-05 1.91782219613991e-06 2.20622498242058e-06 -2.60480345484419e-07 5.26500421799297e-06 6.88573444747139e-06 1.91782219613991e-06 2.68435214015463e-05 -6.17827621140579e-07 8.74887251158941e-06 -5.25550465884422e-06 -4.01323187393364e-07 2.20622498242058e-06 -6.17827621140579e-07 3.89670169719747e-05 -8.60109161312514e-06 1.80633040284911e-05 1.87108284792349e-05 -2.60480345484419e-07 8.74887251158941e-06 -8.60109161312514e-06 4.91649245317625e-05 2669 2666 0 2 23 2676 2699 0 39 22 0 0 0 0 0 33 65 0 568 0 15 15 0 0 2328 +397 427 0.999999757694062 0.000356753945635032 -0.000597777918372419 -0.000322022650336384 -0.000356576054726681 0.999999892123899 0.000297667107052729 0.00667606303479164 0.000597884047801395 -0.000297453881634486 0.999999777027902 0.00228578624436922 3.50164669459878e-05 2.0043128216878e-05 -7.58491917190297e-06 7.03239446309401e-06 5.05475537600097e-06 1.8446443528847e-05 2.0043128216878e-05 2.76183269837924e-05 -8.91457893266911e-06 9.36283670116482e-06 3.4970464683445e-06 2.1379470281298e-05 -7.58491917190297e-06 -8.91457893266911e-06 1.3807324436456e-05 -2.14041108156244e-07 -8.51511002835481e-07 -2.43689854577463e-06 7.03239446309401e-06 9.36283670116482e-06 -2.14041108156244e-07 2.96633918945456e-05 4.93836558481406e-06 1.19589579983849e-05 5.05475537600097e-06 3.4970464683445e-06 -8.51511002835481e-07 4.93836558481406e-06 3.54364893061896e-05 5.23465156174026e-06 1.8446443528847e-05 2.1379470281298e-05 -2.43689854577463e-06 1.19589579983849e-05 5.23465156174026e-06 4.05261450843258e-05 2892 2893 0 16 17 2978 3020 0 43 19 0 0 0 0 0 14 45 0 576 0 24 24 0 0 2294 +397 428 0.999998971849686 0.000325020991771743 -0.0013966606335648 -0.00176094286706852 -0.000324066052308774 0.999999713629302 0.000683902411322089 0.00529644988140682 0.00139688251624212 -0.000683449097869676 0.999998790807552 0.00310787364305498 2.72027342252999e-05 2.08225551366835e-05 -6.29848159442706e-06 6.02231376191797e-06 4.07090453299516e-06 2.22454284270904e-05 2.08225551366835e-05 2.48482932228686e-05 -8.41191209660616e-06 7.38527877658907e-06 1.36780946640543e-06 2.06463286966238e-05 -6.29848159442706e-06 -8.41191209660616e-06 1.28363399901925e-05 -1.04503914300138e-06 -1.17650162944173e-06 -3.72285277312072e-06 6.02231376191797e-06 7.38527877658907e-06 -1.04503914300138e-06 2.65706629832967e-05 4.50580889913902e-06 3.38024343395153e-06 4.07090453299516e-06 1.36780946640543e-06 -1.17650162944173e-06 4.50580889913902e-06 3.29291766256695e-05 4.42656899612749e-06 2.22454284270904e-05 2.06463286966238e-05 -3.72285277312072e-06 3.38024343395153e-06 4.42656899612749e-06 4.36245120970585e-05 2881 2876 0 15 16 2962 3009 0 49 17 0 0 0 0 0 15 48 0 570 0 21 23 0 0 2259 +398 401 0.999997580259109 -0.000229805762012572 -0.00218784488455955 0.00592229819138528 0.000231676273394849 0.999999607871819 0.000854741079789547 -0.0149819456377407 0.00218764760221874 -0.000855245883287225 0.999997241372419 -0.00309094688971444 3.20329837745252e-05 2.39477284240368e-05 -7.2565421020927e-06 5.96104967444509e-06 2.81133623154501e-06 2.10996750398205e-05 2.39477284240368e-05 3.40880805267932e-05 -7.54076591569566e-06 9.87977028599866e-06 4.92932255172579e-06 2.83885148166325e-05 -7.2565421020927e-06 -7.54076591569566e-06 1.30664527883723e-05 5.73132238605792e-07 1.87813386907357e-06 -3.56450277229042e-06 5.96104967444509e-06 9.87977028599866e-06 5.73132238605792e-07 3.66480045388703e-05 -8.90258898487032e-06 6.77406328633106e-06 2.81133623154501e-06 4.92932255172579e-06 1.87813386907357e-06 -8.90258898487032e-06 4.01986348568085e-05 7.79756732445295e-06 2.10996750398205e-05 2.83885148166325e-05 -3.56450277229042e-06 6.77406328633106e-06 7.79756732445295e-06 4.10178184348389e-05 2139 2134 0 25 37 2175 2211 0 51 30 0 0 0 0 0 7 37 0 502 0 103 87 0 0 2501 +397 425 0.999998381200807 -0.000397592897616741 0.00175485488073413 -0.00348345237043688 0.000393579690071029 0.999997308113542 0.00228667022060591 0.0027201519518358 -0.00175575932070295 -0.00228597584370592 0.999995845803196 -0.00432239715869308 4.16053749163007e-05 1.32526996114452e-05 -6.67968246881847e-06 1.49038414997854e-06 4.47366500407229e-06 1.85260261508077e-05 1.32526996114452e-05 2.98584348368371e-05 -7.76200672581969e-06 1.46246597068726e-06 9.87586188374196e-06 1.80991093799011e-05 -6.67968246881847e-06 -7.76200672581969e-06 1.41498591572937e-05 1.48126779276869e-06 5.8624667386748e-07 -3.0637619148042e-06 1.49038414997854e-06 1.46246597068726e-06 1.48126779276869e-06 3.15263589699341e-05 -9.40726773097158e-06 -2.74082956357878e-06 4.47366500407229e-06 9.87586188374196e-06 5.8624667386748e-07 -9.40726773097158e-06 4.73829546520517e-05 1.08983805221088e-05 1.85260261508077e-05 1.80991093799011e-05 -3.0637619148042e-06 -2.74082956357878e-06 1.08983805221088e-05 4.2012603091423e-05 2096 2097 0 17 16 2146 2179 0 51 17 0 0 0 0 0 16 45 0 581 0 53 54 0 0 2026 +398 428 0.999999799003188 0.000221592594455252 0.00059404571021482 0.00278942370170115 -0.000221332830787064 0.999999879886298 -0.000437309006037145 0.00198766109362679 -0.000594142543299017 0.000437177436320771 0.999999727935227 0.00113422528962615 2.26203252712076e-05 1.42429169473789e-05 -8.17807260912845e-06 4.38698007964036e-06 1.04948005498317e-05 1.68844369111884e-05 1.42429169473789e-05 1.78027724038954e-05 -9.92972853940274e-06 3.25451512372439e-06 5.27586796620349e-06 1.61138637551465e-05 -8.17807260912845e-06 -9.92972853940274e-06 1.4595981738078e-05 1.60432675307489e-06 -2.48082375330867e-06 -5.27570200475491e-06 4.38698007964036e-06 3.25451512372439e-06 1.60432675307489e-06 2.16198350691613e-05 9.00110890699122e-06 8.86253343870518e-06 1.04948005498317e-05 5.27586796620349e-06 -2.48082375330867e-06 9.00110890699122e-06 3.28528434026516e-05 1.37631887489794e-05 1.68844369111884e-05 1.61138637551465e-05 -5.27570200475491e-06 8.86253343870518e-06 1.37631887489794e-05 4.29921525289171e-05 3306 3309 0 20 16 3301 3355 0 56 14 0 0 0 0 0 13 45 0 575 0 16 18 0 0 2220 +398 427 0.999999766430591 -0.000184363144431086 0.000658140558904761 0.00372516664472363 0.000183927118496915 0.999999763625012 0.000662510932025159 0.000643174929370851 -0.000658262545935442 -0.000662389727386307 0.99999956396504 -0.00197097668822706 2.12556282693322e-05 1.40981596249049e-05 -8.08854523593855e-06 6.47417415715106e-06 7.79398251247541e-06 1.62948298587061e-05 1.40981596249049e-05 1.97859756582778e-05 -9.28991402007706e-06 4.9442833088697e-06 3.11161974533138e-06 1.71225060163655e-05 -8.08854523593855e-06 -9.28991402007706e-06 1.52158541555227e-05 7.40897085946529e-07 -4.68714829060776e-06 -3.90642786164466e-06 6.47417415715106e-06 4.9442833088697e-06 7.40897085946529e-07 2.50825426995542e-05 2.57727701783744e-06 9.92010710238709e-06 7.79398251247541e-06 3.11161974533138e-06 -4.68714829060776e-06 2.57727701783744e-06 4.04408550219614e-05 8.61395711816646e-06 1.62948298587061e-05 1.71225060163655e-05 -3.90642786164466e-06 9.92010710238709e-06 8.61395711816646e-06 3.89297024479184e-05 2996 2995 0 14 17 2996 3046 0 47 16 0 0 0 0 0 24 54 0 594 0 19 19 0 0 2295 +397 400 0.999995816670732 -0.000433966830802303 -0.00285977513534286 0.00142619530912009 0.000433471096963347 0.999999890919544 -0.00017396467569582 -0.00584326651683553 0.00285985031829627 0.000172724318079315 0.999995895702811 -8.59492486806632e-05 2.99766278782685e-05 2.21614449353288e-05 -5.10286469923515e-06 3.68354883361707e-06 2.87033732704336e-06 2.41881951555919e-05 2.21614449353288e-05 3.29086860787552e-05 -5.0405984709924e-06 8.37827164793579e-06 1.09412708348731e-07 2.42493269357425e-05 -5.10286469923515e-06 -5.0405984709924e-06 1.28181652401181e-05 2.98640263456233e-06 1.59464152193928e-06 -4.1682248687058e-07 3.68354883361707e-06 8.37827164793579e-06 2.98640263456233e-06 3.22957238145963e-05 -1.15804031103565e-05 8.86246183982636e-07 2.87033732704336e-06 1.09412708348731e-07 1.59464152193928e-06 -1.15804031103565e-05 4.12120527495604e-05 7.39175528703401e-06 2.41881951555919e-05 2.42493269357425e-05 -4.1682248687058e-07 8.86246183982636e-07 7.39175528703401e-06 5.21837865633572e-05 2242 2228 0 21 43 2317 2362 0 53 31 0 0 0 0 0 17 49 0 499 0 50 34 0 0 2417 +398 400 0.999999758048232 -0.000178158647707122 -0.000672430645230705 0.00232939554772372 0.000178495001267016 0.999999858980383 0.000500178715772156 -0.00308382109928477 0.000672341439241179 -0.000500298620261904 0.999999648829078 -0.000742724519631008 4.98364034976816e-05 3.05548656189258e-05 -5.3892419028331e-06 1.03648073880178e-05 -4.28768725068465e-06 4.91073663966152e-05 3.05548656189258e-05 3.4045400703043e-05 -6.59393420471878e-06 8.85867701280016e-06 -2.13961833574506e-06 3.9385705556876e-05 -5.3892419028331e-06 -6.59393420471878e-06 1.22244357548921e-05 4.78965731314735e-06 1.17479719075633e-06 -3.92385542467079e-06 1.03648073880178e-05 8.85867701280016e-06 4.78965731314735e-06 3.05378555165991e-05 -1.28447412804613e-05 1.44373149005714e-05 -4.28768725068465e-06 -2.13961833574506e-06 1.17479719075633e-06 -1.28447412804613e-05 4.10147017518767e-05 -1.45722282072235e-06 4.91073663966152e-05 3.9385705556876e-05 -3.92385542467079e-06 1.44373149005714e-05 -1.45722282072235e-06 9.63855908549181e-05 3171 3154 0 12 45 3157 3207 0 58 29 0 0 0 0 0 15 48 0 493 0 51 35 0 0 2406 +399 402 0.999999529708557 -0.000830630547340087 0.000500635155539881 0.00562556736232918 0.000832111666338784 0.999995256486023 -0.00296556834829342 -0.00935311529052994 -0.000498169489109706 0.00296598353796551 0.999995477374179 0.00578522556668541 3.63384400490142e-05 1.7126449157213e-05 -2.73883472621374e-06 1.24450796409052e-06 -1.09839214781513e-06 1.88213140560074e-05 1.7126449157213e-05 3.70944385984336e-05 -3.24287765454115e-06 4.75784500212206e-06 4.94694846043895e-06 2.58432493977594e-05 -2.73883472621374e-06 -3.24287765454115e-06 1.25922665703102e-05 6.30638206696416e-06 2.08627631289709e-06 8.61293588913619e-07 1.24450796409052e-06 4.75784500212206e-06 6.30638206696416e-06 3.89126078184947e-05 -2.21654697896354e-05 4.18366838003224e-06 -1.09839214781513e-06 4.94694846043895e-06 2.08627631289709e-06 -2.21654697896354e-05 5.9525515639378e-05 5.94517042015821e-06 1.88213140560074e-05 2.58432493977594e-05 8.61293588913619e-07 4.18366838003224e-06 5.94517042015821e-06 3.99636163955553e-05 2160 2150 0 22 40 2229 2270 0 41 33 0 0 0 0 0 16 47 0 473 0 48 36 0 0 2570 +399 401 0.999993732523005 1.45477567683396e-05 0.00354043825979009 0.00407899150543509 -1.71907311310479e-05 0.999999721235094 0.000746481221157388 -0.00408491073915733 -0.00354042641321291 -0.000746537405325718 0.999993454009933 -0.00170409504578859 3.62284022454996e-05 2.69537909782257e-05 -2.45889532157639e-06 -3.7406886791763e-07 5.19348112730613e-06 3.16385134930456e-05 2.69537909782257e-05 3.90444129498816e-05 -4.07244384656631e-06 1.76381439131098e-06 6.9231517594859e-06 3.63012454967967e-05 -2.45889532157639e-06 -4.07244384656631e-06 1.27796792875129e-05 2.21354084505053e-06 2.75487176561313e-06 -9.98090214920027e-07 -3.7406886791763e-07 1.76381439131098e-06 2.21354084505053e-06 2.92245213519915e-05 -9.95275928055863e-06 1.39778581553357e-06 5.19348112730613e-06 6.9231517594859e-06 2.75487176561313e-06 -9.95275928055863e-06 4.06155044106796e-05 8.3913777268131e-06 3.16385134930456e-05 3.63012454967967e-05 -9.98090214920027e-07 1.39778581553357e-06 8.3913777268131e-06 5.74905389609357e-05 2045 2039 0 26 40 2032 2057 0 48 31 0 0 0 0 0 10 41 0 505 0 78 62 0 0 2522 +399 403 0.99999919736505 -0.000303427196233752 0.00123012242958018 0.00293924919382627 0.000303186246714615 0.999999934820037 0.000196056167940782 -0.00107883010136953 -0.00123018183817419 -0.000195683054376826 0.999999224180093 0.00276674943815473 2.59290508172394e-05 8.98971205694571e-06 -1.53140132383573e-06 9.91373016030562e-07 -4.54620305618898e-06 1.28601251635334e-05 8.98971205694571e-06 2.4674682112971e-05 -2.60794653557522e-06 1.69715161935736e-06 1.31647856586636e-06 1.83047726716483e-05 -1.53140132383573e-06 -2.60794653557522e-06 9.70566962612572e-06 6.28992756657012e-06 8.58559435581919e-07 1.63816826064568e-06 9.91373016030562e-07 1.69715161935736e-06 6.28992756657012e-06 2.99757381679667e-05 -1.65571636867427e-05 3.9203371800606e-06 -4.54620305618898e-06 1.31647856586636e-06 8.58559435581919e-07 -1.65571636867427e-05 5.22805740229031e-05 3.25776848015254e-06 1.28601251635334e-05 1.83047726716483e-05 1.63816826064568e-06 3.9203371800606e-06 3.25776848015254e-06 4.01028049709359e-05 2850 2850 0 22 28 2843 2882 0 50 22 0 0 0 0 0 24 55 0 449 0 32 26 0 0 2485 +399 429 0.999970991428443 -0.00745112791823653 -0.00158018807814227 0.00360027936787091 0.00745499618414349 0.999969194135175 0.00245638200277256 0.00112763556883007 0.00156183658256323 -0.00246809104273224 0.99999573458745 -0.00088766372772878 2.78020479176621e-05 1.59152756165245e-05 -2.92951402134487e-06 9.44308717604026e-07 2.18479936956285e-06 1.85284272206713e-05 1.59152756165245e-05 2.55657463083867e-05 -5.43745818395966e-06 1.56161458545538e-06 3.96860309681657e-06 2.19719165391972e-05 -2.92951402134487e-06 -5.43745818395966e-06 1.00675893524115e-05 2.91550487938052e-06 2.18657924381832e-06 -1.45298698393258e-07 9.44308717604026e-07 1.56161458545538e-06 2.91550487938052e-06 2.05741611684701e-05 6.06932428561317e-06 4.68264857541358e-06 2.18479936956285e-06 3.96860309681657e-06 2.18657924381832e-06 6.06932428561317e-06 2.77406724665286e-05 8.31723857901189e-06 1.85284272206713e-05 2.19719165391972e-05 -1.45298698393258e-07 4.68264857541358e-06 8.31723857901189e-06 4.8947607871358e-05 3000 2999 0 6 25 2998 3029 0 41 22 0 0 0 0 0 32 64 0 583 0 21 21 0 0 2364 +399 373 0.999999654357603 -0.000214276261789181 -0.000803349461884472 -0.00146056150076298 0.000213504189714822 0.999999515419606 -0.000961028883460438 0.00118882494782018 0.000803554998273693 0.000960857032812193 0.999999215526256 0.00226421721535623 2.7233144299849e-05 1.6864729167969e-05 -9.83866704278712e-06 6.34548134621292e-06 6.91230606103741e-06 1.34046951529915e-05 1.6864729167969e-05 2.64963716201457e-05 -1.0496863611003e-05 5.03708091675279e-06 6.74396650453247e-06 1.67022701825404e-05 -9.83866704278712e-06 -1.0496863611003e-05 1.71907969667968e-05 -1.3855882722696e-07 -2.52209223989951e-06 -3.94587755047009e-06 6.34548134621292e-06 5.03708091675279e-06 -1.3855882722696e-07 4.99695144229383e-05 -3.56527405276404e-05 -7.91760242063002e-09 6.91230606103741e-06 6.74396650453247e-06 -2.52209223989951e-06 -3.56527405276404e-05 8.07025449665553e-05 1.2540435820367e-05 1.34046951529915e-05 1.67022701825404e-05 -3.94587755047009e-06 -7.91760242063002e-09 1.2540435820367e-05 4.0395608613716e-05 2829 2805 0 17 64 2883 2934 0 48 44 0 0 0 0 0 23 53 0 596 0 66 40 0 0 2629 +398 402 0.999999633318162 -0.00053021958193342 0.000672481030647699 0.00672995672943576 0.000530020219100415 0.99999981555282 0.000296602246303498 -0.0101291902133193 -0.000672638170929505 -0.000296245709001636 0.999999729898149 0.000108977332085536 2.02817237684262e-05 1.05401089223685e-05 -2.15839767412557e-06 2.44583711652909e-07 -8.31329764248444e-08 1.50496277746108e-05 1.05401089223685e-05 2.02339463986029e-05 -3.30151133988398e-06 1.40289062362529e-06 1.07798394259133e-06 1.68900777538297e-05 -2.15839767412557e-06 -3.30151133988398e-06 1.15342871198132e-05 5.64125976650026e-06 1.52310815819386e-06 1.89485701027012e-06 2.44583711652909e-07 1.40289062362529e-06 5.64125976650026e-06 3.29297247396277e-05 -1.71593351116877e-05 4.26266192545482e-06 -8.31329764248444e-08 1.07798394259133e-06 1.52310815819386e-06 -1.71593351116877e-05 5.0082854067748e-05 7.75825787981131e-06 1.50496277746108e-05 1.68900777538297e-05 1.89485701027012e-06 4.26266192545482e-06 7.75825787981131e-06 4.13366976096053e-05 3077 3068 0 22 36 3064 3111 0 44 26 0 0 0 0 0 10 41 0 466 0 41 30 0 0 2575 +398 425 0.999997754179393 -8.12223892648645e-05 -0.00211779108823815 -0.00862328716106396 8.33065603634028e-05 0.99999951234744 0.000984055333327584 0.0063825896794114 0.00211771012816656 -0.000984229549206967 0.999997273294286 0.00107068566807271 5.21094621840452e-05 2.91743262829843e-05 -8.89755508047053e-06 7.12495416108986e-06 1.56798142169261e-06 3.68137857496873e-05 2.91743262829843e-05 4.28642812223134e-05 -8.14208639845264e-06 9.55425688342475e-06 -1.78527891584556e-06 3.60162104018749e-05 -8.89755508047053e-06 -8.14208639845264e-06 1.47378893725179e-05 3.76601295448579e-06 -2.05574025577909e-07 -2.08701814364691e-06 7.12495416108986e-06 9.55425688342475e-06 3.76601295448579e-06 3.84883384664141e-05 -1.1571221392551e-05 1.16260204458086e-05 1.56798142169261e-06 -1.78527891584556e-06 -2.05574025577909e-07 -1.1571221392551e-05 4.63686126241627e-05 -5.58879571994795e-06 3.68137857496873e-05 3.60162104018749e-05 -2.08701814364691e-06 1.16260204458086e-05 -5.58879571994795e-06 6.84953815637636e-05 2165 2162 0 14 16 2206 2251 0 56 15 0 0 0 0 0 25 54 0 594 0 65 66 0 0 2105 +398 426 0.999999623435655 -1.9762930851542e-05 0.000867604733784619 0.00377208899846567 1.99794494743035e-05 0.999999968662534 -0.000249551103287426 8.07020089804099e-05 -0.000867599774734887 0.00024956834358032 0.999999592493053 -0.00416279049313057 2.72661278167103e-05 1.819803293471e-05 -7.38175683965745e-06 6.98425057254898e-06 6.94697831547069e-06 1.7954539798628e-05 1.819803293471e-05 2.27485498131423e-05 -8.19764439176198e-06 7.43370551394002e-06 2.76985453407896e-06 2.21168644462566e-05 -7.38175683965745e-06 -8.19764439176198e-06 1.386825226276e-05 9.27743384620199e-07 -1.29642528084979e-06 -2.05226458531927e-06 6.98425057254898e-06 7.43370551394002e-06 9.27743384620199e-07 2.90417492232739e-05 4.17811017716429e-06 9.79973611376535e-06 6.94697831547069e-06 2.76985453407896e-06 -1.29642528084979e-06 4.17811017716429e-06 3.25054745507135e-05 6.69314393026729e-06 1.7954539798628e-05 2.21168644462566e-05 -2.05226458531927e-06 9.79973611376535e-06 6.69314393026729e-06 4.44374444867987e-05 2893 2894 0 23 15 2886 2917 0 51 14 0 0 0 0 0 16 46 0 597 0 16 18 0 0 2094 +399 427 0.999997658602556 0.000169290975942347 -0.0021573432670779 -0.00219939555081185 -0.000172759679630608 0.999998692607496 -0.00160777404869839 0.00503198963949934 0.00215706826494568 0.00160814298619202 0.999996380459768 0.00311628177704524 3.29110901931161e-05 1.7023706514077e-05 -9.8543763314422e-06 2.76100364843367e-06 5.20617596244864e-06 1.82584507548679e-05 1.7023706514077e-05 2.88794653237807e-05 -1.21821491045538e-05 6.71035866650993e-06 8.97349074972163e-06 2.10941463408637e-05 -9.8543763314422e-06 -1.21821491045538e-05 1.71026075531461e-05 -5.10198309861501e-07 -3.15172632376139e-06 -4.71928216262397e-06 2.76100364843367e-06 6.71035866650993e-06 -5.10198309861501e-07 2.89640897384923e-05 2.08303527703339e-06 5.89276873802403e-06 5.20617596244864e-06 8.97349074972163e-06 -3.15172632376139e-06 2.08303527703339e-06 4.78644178211647e-05 8.48801575547751e-06 1.82584507548679e-05 2.10941463408637e-05 -4.71928216262397e-06 5.89276873802403e-06 8.48801575547751e-06 4.19044355725408e-05 2219 2215 0 13 17 2287 2339 0 49 18 0 0 0 0 0 23 54 0 610 0 24 24 0 0 2320 +399 372 0.99999599424122 -0.000223729216879255 0.00282160357817092 -0.00573940764435657 0.000216550155285601 0.999996739641862 0.002544368620563 0.0169448420182123 -0.00282216362833167 -0.00254374740974305 0.999992782344738 -0.00615818165305271 3.80636881526356e-05 1.54676341856994e-05 -1.06683894621811e-05 -2.3726847893891e-06 1.64647949354037e-05 1.81671490078277e-05 1.54676341856994e-05 3.35245706095959e-05 -1.11134924002842e-05 1.48807373296056e-05 4.46732673785578e-06 1.37251009264537e-05 -1.06683894621811e-05 -1.11134924002842e-05 1.64918667149172e-05 4.23554522086605e-08 -4.20739814841253e-06 -6.14609518473017e-06 -2.3726847893891e-06 1.48807373296056e-05 4.23554522086605e-08 6.01229903824721e-05 -2.31834748377068e-05 2.61027284336339e-06 1.64647949354037e-05 4.46732673785578e-06 -4.20739814841253e-06 -2.31834748377068e-05 6.60714839432016e-05 5.0213502472508e-06 1.81671490078277e-05 1.37251009264537e-05 -6.14609518473017e-06 2.61027284336339e-06 5.0213502472508e-06 3.87907674212397e-05 1307 1287 0 13 66 1282 1301 0 42 34 0 0 0 0 0 20 51 0 620 0 113 93 0 0 2777 +400 402 0.999999980362019 4.4609090038349e-05 -0.000193095808240231 0.00490170218552877 -4.46979831375669e-05 0.999999893027252 -0.000460377644687675 -0.00820259900832175 0.000193075250556439 0.000460386266639968 0.999999875383209 -0.000283099260063549 2.00307495280631e-05 1.21660663641914e-05 -1.64064192875269e-06 9.81044343536317e-07 -9.26529969878971e-08 1.56395457026255e-05 1.21660663641914e-05 1.84742741411207e-05 -3.65923838851664e-06 1.61090118007159e-06 -3.15871188501623e-06 1.66473696484189e-05 -1.64064192875269e-06 -3.65923838851664e-06 1.25341606096544e-05 6.54327135171763e-06 2.4423445230792e-06 7.98024610713e-07 9.81044343536317e-07 1.61090118007159e-06 6.54327135171763e-06 3.03997105467481e-05 -1.21077839704951e-05 4.75161300214634e-06 -9.26529969878971e-08 -3.15871188501623e-06 2.4423445230792e-06 -1.21077839704951e-05 3.63034123481656e-05 -3.31097459745406e-07 1.56395457026255e-05 1.66473696484189e-05 7.98024610713e-07 4.75161300214634e-06 -3.31097459745406e-07 3.57455474296105e-05 2459 2449 0 21 37 2446 2493 0 46 31 0 0 0 0 0 7 35 0 462 0 47 35 0 0 2475 +399 428 0.999998977489572 0.000546763035275198 -0.00132138941760538 -0.00131760125136189 -0.000545790017432324 0.999999579760794 0.000736608099494265 0.00913082031466581 0.00132179161238603 -0.000735886145151532 0.999998855668603 0.00166867621658338 3.45503628122216e-05 2.47683704433191e-05 -8.34274422864758e-06 9.20106081456021e-06 3.27735896111817e-06 2.42615236637908e-05 2.47683704433191e-05 3.24189849659406e-05 -1.05972240357206e-05 7.10831803815305e-06 1.45687287210735e-06 2.43634625782553e-05 -8.34274422864758e-06 -1.05972240357206e-05 1.58433909432908e-05 1.65854136957794e-06 -3.43030544341698e-07 -3.00330536861584e-06 9.20106081456021e-06 7.10831803815305e-06 1.65854136957794e-06 3.15974890146636e-05 3.78415378025303e-06 1.00383583096121e-05 3.27735896111817e-06 1.45687287210735e-06 -3.43030544341698e-07 3.78415378025303e-06 3.94686094308396e-05 7.41551459774227e-07 2.42615236637908e-05 2.43634625782553e-05 -3.00330536861584e-06 1.00383583096121e-05 7.41551459774227e-07 4.41793066561601e-05 2738 2744 0 21 16 2803 2856 0 50 14 0 0 0 0 0 25 58 0 587 0 21 23 0 0 2248 +399 396 0.999998663794016 -0.000144121472841713 0.00162838545303418 -0.00724639701816693 0.000140759467423711 0.999997858905541 0.00206455106663681 0.0139150053362098 -0.00162867951264759 -0.00206431909730219 0.999996542988879 -0.00307282740861712 2.38034335276134e-05 1.30900447836547e-05 -2.44019965202835e-07 3.513813668931e-06 -3.59525091501344e-06 1.3547009723948e-05 1.30900447836547e-05 2.4606116896463e-05 -1.6790837832316e-06 4.86035149141261e-06 -1.1345284288863e-06 1.97204179385175e-05 -2.44019965202835e-07 -1.6790837832316e-06 1.04891502979574e-05 3.05702711095092e-06 4.29945491739994e-06 2.56742243832274e-06 3.513813668931e-06 4.86035149141261e-06 3.05702711095092e-06 3.26261232774254e-05 -1.07623509182787e-05 4.36709786369967e-06 -3.59525091501344e-06 -1.1345284288863e-06 4.29945491739994e-06 -1.07623509182787e-05 3.41599332795356e-05 3.424120127357e-06 1.3547009723948e-05 1.97204179385175e-05 2.56742243832274e-06 4.36709786369967e-06 3.424120127357e-06 3.61117748726236e-05 2588 2566 0 13 54 2566 2582 0 35 34 0 0 0 0 0 19 48 0 473 0 78 60 0 0 2553 +400 403 0.999995097147382 -0.000386038395548984 0.00310751597813773 0.00989475359380543 0.000386688614466704 0.99999990347008 -0.000208642629434803 -0.0109470911677785 -0.00310743513410355 0.00020984324753876 0.999995149894588 -0.000121147626463319 3.46568843231049e-05 1.83604855733819e-05 -1.00792527279453e-06 4.11638267695621e-06 -7.15787849399145e-06 1.83290721372855e-05 1.83604855733819e-05 2.86566394350236e-05 -3.08381983171177e-06 6.08511704986252e-06 -4.25831216878758e-06 2.31341939211182e-05 -1.00792527279453e-06 -3.08381983171177e-06 1.22015664662231e-05 5.94808897414688e-06 -2.74872944998982e-06 1.3611790889869e-06 4.11638267695621e-06 6.08511704986252e-06 5.94808897414688e-06 4.32350035012446e-05 -3.34586173125754e-05 9.53051089893547e-06 -7.15787849399145e-06 -4.25831216878758e-06 -2.74872944998982e-06 -3.34586173125754e-05 6.93604215730671e-05 -3.27215563622083e-06 1.83290721372855e-05 2.31341939211182e-05 1.3611790889869e-06 9.53051089893547e-06 -3.27215563622083e-06 5.03963940293123e-05 2636 2630 0 17 29 2626 2660 0 52 28 0 0 0 0 0 9 40 0 444 0 33 25 0 0 2429 +400 429 0.999969895989319 -0.00775512540574615 0.000255235286225296 0.0060186680206872 0.00775463058034016 0.999968154362739 0.00188572663419991 -0.00396519859422767 -0.00026985120462413 -0.00188369061090943 0.999998189443366 -0.00287898781169845 3.01372157062744e-05 1.4110199800373e-05 -3.02732444915008e-06 -3.68027576529782e-07 1.7381628610926e-06 1.56426683735329e-05 1.4110199800373e-05 2.99196526549602e-05 -5.94573816917729e-06 2.97163986641796e-06 3.77683907251972e-06 2.24123747566478e-05 -3.02732444915008e-06 -5.94573816917729e-06 1.12185225861654e-05 3.60607936076523e-06 1.19518714679304e-06 1.76613994585269e-07 -3.68027576529782e-07 2.97163986641796e-06 3.60607936076523e-06 2.70353245709462e-05 1.52919410223578e-06 3.67933123857088e-06 1.7381628610926e-06 3.77683907251972e-06 1.19518714679304e-06 1.52919410223578e-06 3.53531072783128e-05 4.56041763803264e-06 1.56426683735329e-05 2.24123747566478e-05 1.76613994585269e-07 3.67933123857088e-06 4.56041763803264e-06 5.08325346540756e-05 2773 2771 0 4 26 2781 2801 0 36 27 0 0 0 0 0 23 54 0 587 0 15 14 0 0 2467 +399 395 0.999999993667945 0.000103304805139756 -4.46343672626914e-05 -0.00741733190202248 -0.000103308722717274 0.99999999081125 -8.77770391704515e-05 0.0114919989703605 4.46252990626301e-05 8.77816497341137e-05 0.999999995151482 -0.001604546445846 2.14834354018159e-05 1.3646268106355e-05 -5.21394319622663e-07 1.60481869749526e-06 -2.22486711300949e-06 8.84790577537856e-06 1.3646268106355e-05 1.95087095283675e-05 -3.57234533134928e-06 1.9807919818178e-06 4.52216021812994e-07 1.22685736037771e-05 -5.21394319622663e-07 -3.57234533134928e-06 1.2575948652111e-05 2.60764992049832e-06 1.91201086387702e-06 -1.30359122417088e-07 1.60481869749526e-06 1.9807919818178e-06 2.60764992049832e-06 3.06901136584485e-05 -1.67970003139907e-05 -4.43208660906752e-06 -2.22486711300949e-06 4.52216021812994e-07 1.91201086387702e-06 -1.67970003139907e-05 4.59241816028901e-05 5.78250946253787e-06 8.84790577537856e-06 1.22685736037771e-05 -1.30359122417088e-07 -4.43208660906752e-06 5.78250946253787e-06 2.57512909074729e-05 2571 2553 0 14 54 2549 2578 0 47 23 0 0 0 0 0 15 46 0 456 0 111 96 0 0 2409 +400 373 0.999999882752874 -5.68490920756496e-05 0.000480897515150382 0.00115462187103598 5.68412294307776e-05 0.999999998250654 1.63635902581846e-05 -0.00156237792878613 -0.000480898444564375 -1.63362535336093e-05 0.9999998842349 0.000651930258727623 2.55453241937505e-05 1.27828498184213e-05 -5.52330996301174e-06 2.98763718066188e-06 3.71974807961597e-06 1.51298892365152e-05 1.27828498184213e-05 1.86693897993114e-05 -7.41144154079745e-06 2.49937866434553e-06 4.02824129449998e-06 1.45758941580221e-05 -5.52330996301174e-06 -7.41144154079745e-06 1.22167557023111e-05 4.18355249620607e-06 -1.16920308099588e-06 -2.61674086890206e-06 2.98763718066188e-06 2.49937866434553e-06 4.18355249620607e-06 4.91927859382803e-05 -3.43740318332808e-05 3.37145314595042e-06 3.71974807961597e-06 4.02824129449998e-06 -1.16920308099588e-06 -3.43740318332808e-05 7.12800815638914e-05 5.95337284592951e-06 1.51298892365152e-05 1.45758941580221e-05 -2.61674086890206e-06 3.37145314595042e-06 5.95337284592951e-06 4.0017064520664e-05 3136 3111 0 19 68 3113 3154 0 48 47 0 0 0 0 0 6 35 0 597 0 63 38 0 0 2628 +400 427 0.999966547251005 -1.84494907840418e-05 -0.00817948889105029 -0.00187967684720349 4.25043720980659e-05 0.999995675187303 0.00294071421049838 0.00339896268069353 0.00817939926161315 -0.00294096349956342 0.99996222336717 -0.00343671743905451 5.47377145360714e-05 0.000163775287970723 7.61243221232831e-07 7.03565636170361e-05 -1.32368059985857e-05 6.14505445510886e-05 0.000163775287970723 0.00169243747002644 8.93127863327841e-05 0.000547589477843669 -9.39510217197105e-05 0.000127167401114176 7.61243221232831e-07 8.93127863327841e-05 2.11552429972558e-05 2.94051342927226e-05 -7.40998088867151e-06 -5.5884337071119e-06 7.03565636170361e-05 0.000547589477843669 2.94051342927226e-05 0.000234119637049415 -3.10312990795393e-05 0.000111564397159396 -1.32368059985857e-05 -9.39510217197105e-05 -7.40998088867151e-06 -3.10312990795393e-05 5.40404472205583e-05 -9.02622782459421e-06 6.14505445510886e-05 0.000127167401114176 -5.5884337071119e-06 0.000111564397159396 -9.02622782459421e-06 0.000227501404411981 2404 2403 0 17 24 2400 2445 0 43 32 0 0 0 0 0 15 44 0 606 0 18 19 0 0 2385 +400 428 0.999999987577167 0.000157158126717162 -1.21239211667002e-05 0.00267598013753811 -0.000157158701610638 0.999999986525686 -4.74317434130916e-05 0.0030116162748759 1.21164667193969e-05 4.7433648203564e-05 0.99999999880162 -0.000997982531797924 2.24677875336334e-05 1.19348324408634e-05 -5.85985101544251e-06 4.67310045130315e-06 4.58372698695744e-06 1.45307767918886e-05 1.19348324408634e-05 2.07344983371906e-05 -7.72692153331e-06 3.64171898643442e-06 2.98352272023356e-06 2.05359313604597e-05 -5.85985101544251e-06 -7.72692153331e-06 1.2023015829739e-05 1.0393328486176e-06 -9.27232620731945e-07 -1.40753799784364e-06 4.67310045130315e-06 3.64171898643442e-06 1.0393328486176e-06 2.52064776916754e-05 4.07170632016111e-06 6.72311664382094e-06 4.58372698695744e-06 2.98352272023356e-06 -9.27232620731945e-07 4.07170632016111e-06 3.95104132182588e-05 7.11152267190526e-06 1.45307767918886e-05 2.05359313604597e-05 -1.40753799784364e-06 6.72311664382094e-06 7.11152267190526e-06 5.11271545966905e-05 2998 3005 0 16 19 2999 3055 0 48 21 0 0 0 0 0 10 42 0 582 0 16 17 0 0 2374 +400 404 0.999998087988002 -0.0003072569760276 -0.00193122072535154 0.00112413548184463 0.000305729035613586 0.999999640088858 -0.000791423976723922 -0.000942081894415695 0.00193146320082153 0.000790832033261865 0.999997822014928 0.00516012114127043 2.22426121385446e-05 1.21965840481243e-05 -1.3990643238965e-06 -9.75903256470398e-07 -1.74442908878283e-06 1.05960265418848e-05 1.21965840481243e-05 2.47838737500197e-05 -3.26782056268828e-06 5.56392284049923e-06 -2.18216081001618e-06 1.03202326530356e-05 -1.3990643238965e-06 -3.26782056268828e-06 1.3118600704739e-05 7.24462024011128e-06 -2.88382664144587e-07 -6.59246664804088e-07 -9.75903256470398e-07 5.56392284049923e-06 7.24462024011128e-06 5.02884319854363e-05 -2.64645071652118e-05 -1.20056153586428e-05 -1.74442908878283e-06 -2.18216081001618e-06 -2.88382664144587e-07 -2.64645071652118e-05 5.09798861143299e-05 8.23470655243418e-06 1.05960265418848e-05 1.03202326530356e-05 -6.59246664804088e-07 -1.20056153586428e-05 8.23470655243418e-06 3.46304551708251e-05 1512 1508 0 17 25 1546 1585 0 44 20 0 0 0 0 0 14 43 0 445 0 71 69 0 0 2447 +399 425 0.99999893269262 0.000136835788918342 0.00145460977179663 -0.00172017832415417 -0.000134335525559272 0.999998513815411 -0.00171881381632639 0.00361175882399503 -0.00145484280522256 0.00171861657605555 0.999997464891525 -0.000922554821252783 4.26968226770271e-05 1.86683436795744e-05 -5.47875328926991e-06 4.39322586895411e-06 6.4523661393659e-06 1.63097704320503e-05 1.86683436795744e-05 2.78293020366047e-05 -6.12979320051904e-06 4.11839272520482e-06 5.19023633812813e-06 2.23746336792001e-05 -5.47875328926991e-06 -6.12979320051904e-06 1.58166897833045e-05 1.08193172921201e-06 -3.14824612116809e-06 -1.82245141826554e-06 4.39322586895411e-06 4.11839272520482e-06 1.08193172921201e-06 3.13462120938351e-05 -6.56283532173668e-06 7.92912309209861e-07 6.4523661393659e-06 5.19023633812813e-06 -3.14824612116809e-06 -6.56283532173668e-06 5.15476054437839e-05 1.29238688555624e-05 1.63097704320503e-05 2.23746336792001e-05 -1.82245141826554e-06 7.92912309209861e-07 1.29238688555624e-05 4.56796324374741e-05 2858 2853 0 15 16 2855 2890 0 50 15 0 0 0 0 0 23 54 0 607 0 49 50 0 0 2121 +399 426 0.999999087398186 0.000263955518828924 0.0013249642554804 -0.000610034938723036 -0.000264250089423582 0.999999940409901 0.000222153290147203 0.00714334327014844 -0.00132490553793869 -0.000222503209332701 0.999999097558412 0.000431183640180367 3.4495242610854e-05 2.09551365997595e-05 -1.00911895342508e-05 9.21804810047612e-06 8.64828135508622e-06 2.74900109144466e-05 2.09551365997595e-05 2.95064878575407e-05 -1.09268483006291e-05 6.07233749308279e-06 9.92851779610877e-06 3.00241811300382e-05 -1.00911895342508e-05 -1.09268483006291e-05 1.63064665432507e-05 1.46137192523381e-06 -4.5335923307284e-06 -6.1198113410971e-06 9.21804810047612e-06 6.07233749308279e-06 1.46137192523381e-06 2.76498416032891e-05 1.49596787128768e-06 8.57337397870699e-06 8.64828135508622e-06 9.92851779610877e-06 -4.5335923307284e-06 1.49596787128768e-06 5.3969183484552e-05 1.35658383312817e-05 2.74900109144466e-05 3.00241811300382e-05 -6.1198113410971e-06 8.57337397870699e-06 1.35658383312817e-05 6.64748394725056e-05 2903 2910 0 24 17 2894 2927 0 46 13 0 0 0 0 0 17 47 0 610 0 23 25 0 0 2111 +400 374 0.999991974299328 -0.000422394313639251 0.00398408332935717 0.012362908515577 0.00041575316495509 0.999998523126919 0.00166760105715364 -0.00683932280693247 -0.00398478183057571 -0.00166593127823309 0.999990673049874 -0.000947607182706176 2.71794295705721e-05 1.41054864783303e-05 -5.79862365126135e-06 5.55140983498582e-06 7.94724064388182e-07 1.17908607933514e-05 1.41054864783303e-05 2.85657230415665e-05 -8.32512999412845e-06 7.16558607666054e-06 6.64289206082689e-06 1.44890290984213e-05 -5.79862365126135e-06 -8.32512999412845e-06 1.24748030274653e-05 1.76200539411257e-06 -5.85784589149682e-07 -2.23473719851219e-06 5.55140983498582e-06 7.16558607666054e-06 1.76200539411257e-06 4.59413995245875e-05 -1.78746933525321e-05 1.01587413046606e-05 7.94724064388182e-07 6.64289206082689e-06 -5.85784589149682e-07 -1.78746933525321e-05 5.74385529050474e-05 5.04782723628794e-06 1.17908607933514e-05 1.44890290984213e-05 -2.23473719851219e-06 1.01587413046606e-05 5.04782723628794e-06 4.32538883799708e-05 2441 2414 0 19 65 2411 2433 0 53 37 0 0 0 0 0 16 46 0 610 0 56 34 0 0 2715 +400 372 0.999999470820464 0.000429740998665043 0.000934709294988868 -0.00650937445378477 -0.000430555219763484 0.999999527930543 0.00087106882256824 0.016544360405433 -0.000934334519755443 -0.000871470805582364 0.999999183778487 0.000756529328750256 2.50395798810031e-05 1.6502387093023e-05 -7.84865460926575e-06 6.47567616847965e-06 2.04487437395709e-06 1.56586686950789e-05 1.6502387093023e-05 3.53301141562059e-05 -1.03128851347797e-05 9.91558437473419e-06 3.99508934589188e-06 2.45313350404126e-05 -7.84865460926575e-06 -1.03128851347797e-05 1.45963350199077e-05 8.62831580320806e-07 -1.96244272943125e-06 -5.47555630209924e-06 6.47567616847965e-06 9.91558437473419e-06 8.62831580320806e-07 4.6812175643486e-05 -1.6684758854874e-05 6.49020729550943e-06 2.04487437395709e-06 3.99508934589188e-06 -1.96244272943125e-06 -1.6684758854874e-05 5.29982621257789e-05 2.09248705935807e-06 1.56586686950789e-05 2.45313350404126e-05 -5.47555630209924e-06 6.49020729550943e-06 2.09248705935807e-06 5.15738554545353e-05 1621 1597 0 8 69 1659 1693 0 44 57 0 0 0 0 0 18 49 0 623 0 75 51 0 0 2701 +400 396 0.999999470500981 0.000471778516710382 0.000914561527706811 -0.0115724026179323 -0.000473630919859867 0.999997834893585 0.00202629758297126 0.0157716192937539 -0.000913603583915672 -0.00202672967466632 0.999997528844605 0.00337762396361988 2.86180260302145e-05 1.20709447577881e-05 -1.4500732145691e-06 -4.54902828146398e-06 1.84023346773368e-06 9.28521421372961e-06 1.20709447577881e-05 2.64078164993674e-05 -1.94305315117716e-06 1.99719846829212e-06 1.16348150446479e-06 1.67959607929766e-05 -1.4500732145691e-06 -1.94305315117716e-06 1.49113212925128e-05 5.75957621169482e-06 1.39662451321129e-06 2.34190319213197e-06 -4.54902828146398e-06 1.99719846829212e-06 5.75957621169482e-06 4.00587172462407e-05 -1.13399869353216e-05 1.80941847207439e-07 1.84023346773368e-06 1.16348150446479e-06 1.39662451321129e-06 -1.13399869353216e-05 4.61410592815412e-05 2.9978529403007e-06 9.28521421372961e-06 1.67959607929766e-05 2.34190319213197e-06 1.80941847207439e-07 2.9978529403007e-06 3.29289644586212e-05 2099 2079 0 15 58 2125 2153 0 42 45 0 0 0 0 0 13 40 0 462 0 104 85 0 0 2440 +401 405 0.999998988868058 -0.000423473589465552 0.00135754667701047 0.00967659228890747 0.000423650583654367 0.999999901797984 -0.000130093065033176 -0.00448607552892093 -0.00135749145271944 0.000130668058933976 0.999999070070975 -0.00366421419779463 2.7593198243549e-05 8.59657683892539e-06 -1.80531302470455e-06 -3.47409329301066e-06 -1.94957724240846e-07 1.08287798146304e-05 8.59657683892539e-06 2.20645399633134e-05 -3.45632110290739e-06 -2.72924706119812e-06 3.69441486192083e-06 1.30583144209558e-05 -1.80531302470455e-06 -3.45632110290739e-06 1.27701072482563e-05 7.62890157874359e-06 -6.24889135261456e-07 8.01883298758916e-08 -3.47409329301066e-06 -2.72924706119812e-06 7.62890157874359e-06 4.35976706992745e-05 -2.89841589444486e-05 -9.0799844859327e-06 -1.94957724240846e-07 3.69441486192083e-06 -6.24889135261456e-07 -2.89841589444486e-05 6.32973718948919e-05 7.9368497771773e-06 1.08287798146304e-05 1.30583144209558e-05 8.01883298758916e-08 -9.0799844859327e-06 7.9368497771773e-06 3.49982329567707e-05 2074 2080 0 18 19 2074 2103 0 41 20 0 0 0 0 0 16 48 0 453 0 42 53 0 0 2489 +400 426 0.999993141030522 0.000400323891556246 0.00368206907762576 0.00296050642181449 -0.000407028826967372 0.999998260233415 0.001820400416626 0.00350253043086491 -0.00368133392190604 -0.00182188663881258 0.999991564219234 -0.00550125296290485 2.88182006004779e-05 1.88292373729256e-05 -7.17433181294827e-06 5.21050613501163e-06 1.36249412477465e-06 1.5491531816378e-05 1.88292373729256e-05 2.70943540646253e-05 -9.93766891881426e-06 6.89209181785003e-06 4.36359220868559e-06 1.75220449699909e-05 -7.17433181294827e-06 -9.93766891881426e-06 1.46891186866873e-05 1.87345748081974e-07 -2.88041901679044e-06 -2.2435249474096e-06 5.21050613501163e-06 6.89209181785003e-06 1.87345748081974e-07 2.88525266650892e-05 5.16754536156056e-06 4.72506039771555e-06 1.36249412477465e-06 4.36359220868559e-06 -2.88041901679044e-06 5.16754536156056e-06 4.62646316108083e-05 2.94822572548003e-06 1.5491531816378e-05 1.75220449699909e-05 -2.2435249474096e-06 4.72506039771555e-06 2.94822572548003e-06 3.72147883778921e-05 2668 2669 0 18 20 2661 2690 0 45 31 0 0 0 0 0 12 42 0 601 0 17 18 0 0 2101 +401 397 0.999999482696159 0.000749301182850419 0.000687862741480312 -0.0102774322803465 -0.000749187775975091 0.999999705727919 -0.00016511133366424 0.0185308952853181 -0.000687986257179128 0.000164595909894047 0.999999749791517 0.0024330041102048 2.63069537468001e-05 1.92808214050741e-05 -2.40291895982521e-07 3.22596321594376e-06 -3.23744199455387e-06 1.92359098052735e-05 1.92808214050741e-05 2.30294463521149e-05 -2.20208784021545e-06 5.14863913604891e-06 -3.58145266067774e-06 2.05381829490996e-05 -2.40291895982521e-07 -2.20208784021545e-06 9.82005819175556e-06 5.07394878293325e-06 1.44678023020602e-06 3.05680875328201e-06 3.22596321594376e-06 5.14863913604891e-06 5.07394878293325e-06 4.23002090234976e-05 -3.43245158530215e-05 6.3663279447672e-06 -3.23744199455387e-06 -3.58145266067774e-06 1.44678023020602e-06 -3.43245158530215e-05 6.65744355783767e-05 -4.93491824139196e-07 1.92359098052735e-05 2.05381829490996e-05 3.05680875328201e-06 6.3663279447672e-06 -4.93491824139196e-07 4.34741990295094e-05 2720 2706 0 16 66 2699 2726 0 49 38 0 0 0 0 0 20 48 0 464 0 60 41 0 0 2494 +401 404 0.999999802786106 -0.000288249873381419 0.000557978278502637 0.00830142008040753 0.000288115177944156 0.999999929342291 0.000241464400486358 -0.00600863209467937 -0.000558047841160037 -0.000241303590855224 0.999999815177575 0.00185720229473069 2.19462887754652e-05 1.60281094981847e-05 -6.26906606599957e-07 2.51433168025234e-06 5.34609995001274e-07 1.69264609124761e-05 1.60281094981847e-05 2.04349795053407e-05 -2.46449962974483e-06 1.57825833590432e-06 1.97944897456361e-08 1.67537117590144e-05 -6.26906606599957e-07 -2.46449962974483e-06 1.03495417188294e-05 4.59027964166339e-06 1.01719208287486e-06 -2.01376415739307e-07 2.51433168025234e-06 1.57825833590432e-06 4.59027964166339e-06 3.04385607675034e-05 -1.24043129498499e-05 5.36934656929488e-06 5.34609995001274e-07 1.97944897456361e-08 1.01719208287486e-06 -1.24043129498499e-05 4.18276877733468e-05 3.32797914334171e-06 1.69264609124761e-05 1.67537117590144e-05 -2.01376415739307e-07 5.36934656929488e-06 3.32797914334171e-06 3.36472132069697e-05 2971 2974 0 19 22 2974 3009 0 48 21 0 0 0 0 0 13 41 0 445 0 25 24 0 0 2451 +401 373 0.99999461183143 0.00018922788649306 0.00327727034502507 -0.004341635573419 -0.00019668602483198 0.999997391604159 0.00227554377807594 0.0077219121029088 -0.00327683120026699 -0.00227617611033894 0.999992040668124 -0.010744966154163 3.6155961532097e-05 1.37680842866786e-05 -8.10983535057897e-06 5.76521205991541e-06 -4.50676700836062e-06 1.70252227380462e-05 1.37680842866786e-05 3.20947702879508e-05 -9.78728969594891e-06 6.73041219298233e-06 8.38359425555373e-06 1.21343364286198e-05 -8.10983535057897e-06 -9.78728969594891e-06 1.59347139745445e-05 1.34974983438836e-06 2.68781087239049e-07 -5.03768910520099e-06 5.76521205991541e-06 6.73041219298233e-06 1.34974983438836e-06 0.000104393986167229 -8.28405917939795e-05 3.5745185664044e-07 -4.50676700836062e-06 8.38359425555373e-06 2.68781087239049e-07 -8.28405917939795e-05 0.000123000636097991 1.12346210363873e-06 1.70252227380462e-05 1.21343364286198e-05 -5.03768910520099e-06 3.5745185664044e-07 1.12346210363873e-06 3.98268090084458e-05 1452 1425 0 11 60 1545 1578 0 37 47 0 0 0 0 0 16 46 0 611 0 67 43 0 0 2538 +401 403 0.999999823731549 -0.000590460647782137 -6.23946656842459e-05 0.00703217596899976 0.000590486205517771 0.999999741451912 0.000410392679198209 -0.00538896742560974 6.21523288250199e-05 -0.000410429450048311 0.999999913842374 0.00114911567532144 1.85010674098489e-05 1.11995452631073e-05 -6.26546303659541e-07 8.76523926044947e-08 -3.22268373263794e-07 9.21622776388129e-06 1.11995452631073e-05 1.88018621728036e-05 -2.44790901865096e-06 -1.24811738990181e-06 2.24388225946732e-06 7.14326845753862e-06 -6.26546303659541e-07 -2.44790901865096e-06 1.02740504374047e-05 3.64806649154827e-06 2.23028450327563e-06 1.22232409102263e-06 8.76523926044947e-08 -1.24811738990181e-06 3.64806649154827e-06 3.47808159045231e-05 -2.19498781149985e-05 -4.10820850715614e-06 -3.22268373263794e-07 2.24388225946732e-06 2.23028450327563e-06 -2.19498781149985e-05 4.70301022058208e-05 6.63873675997526e-06 9.21622776388129e-06 7.14326845753862e-06 1.22232409102263e-06 -4.10820850715614e-06 6.63873675997526e-06 3.21995978783386e-05 2564 2558 0 13 30 2551 2585 0 52 17 0 0 0 0 0 17 48 0 448 0 39 35 0 0 2466 +401 374 0.999999997735355 6.68608960340171e-05 7.67536190827723e-06 0.00173831268696507 -6.68625517230389e-05 0.999999974454498 0.000215917583661747 -0.002157608087602 -7.66092526909313e-06 -0.000215918096367053 0.999999976660343 -0.00202137463422496 2.87438997180848e-05 1.16697523319839e-05 -5.5546456553157e-06 -3.43862222176167e-07 3.48471040608505e-06 1.51568648779042e-05 1.16697523319839e-05 2.23541310906039e-05 -6.89387790591765e-06 8.80260498513169e-06 1.03366643698916e-06 9.76371908880086e-06 -5.5546456553157e-06 -6.89387790591765e-06 1.26422856528878e-05 -3.51898748748184e-07 6.4493882768316e-07 -1.7941159552772e-06 -3.43862222176167e-07 8.80260498513169e-06 -3.51898748748184e-07 6.74766445874453e-05 -4.09512904664054e-05 1.98807179095584e-07 3.48471040608505e-06 1.03366643698916e-06 6.4493882768316e-07 -4.09512904664054e-05 6.7888937328576e-05 3.78264863194393e-06 1.51568648779042e-05 9.76371908880086e-06 -1.7941159552772e-06 1.98807179095584e-07 3.78264863194393e-06 4.10010176643535e-05 2492 2471 0 19 52 2465 2485 0 49 23 0 0 0 0 0 16 48 0 624 0 51 34 0 0 2622 +401 427 0.999999308854429 -0.000627144142268484 0.000994475182373078 0.009354552567827 0.00062676011293143 0.999999728922754 0.000386427456244108 -0.00503446508544848 -0.000994717258509079 -0.000385803891788872 0.999999430846304 -0.00348898947903145 3.16322647481073e-05 1.65844550740506e-05 -9.01921121135768e-06 6.48154344618366e-06 3.41632136846423e-06 1.41695246435198e-05 1.65844550740506e-05 2.07047171841976e-05 -9.45776797705354e-06 3.28709273255179e-06 3.07328266805529e-06 1.64983310703035e-05 -9.01921121135768e-06 -9.45776797705354e-06 1.56964327652088e-05 1.51149270756479e-06 -3.98668356657862e-06 -2.1080511811966e-06 6.48154344618366e-06 3.28709273255179e-06 1.51149270756479e-06 4.16819130022298e-05 -8.40443207561814e-06 1.05942861635187e-05 3.41632136846423e-06 3.07328266805529e-06 -3.98668356657862e-06 -8.40443207561814e-06 4.67214751249558e-05 2.10301687961775e-06 1.41695246435198e-05 1.64983310703035e-05 -2.1080511811966e-06 1.05942861635187e-05 2.10301687961775e-06 3.51663020370144e-05 2213 2216 0 18 17 2312 2353 0 47 16 0 0 0 0 0 13 42 0 610 0 34 35 0 0 2356 +401 375 0.999998287258855 0.000283473908370857 0.00182896744103269 0.0121067100730503 -0.000282682463174345 0.999999866312981 -0.000432971874648872 -0.0114120909269008 -0.00182908993275301 0.000432454116058831 0.999998233705168 -0.00461155627845651 2.66032269565614e-05 1.74049715622706e-05 -7.25990840814141e-06 6.39186933554761e-06 1.69824972259158e-06 1.13690166055482e-05 1.74049715622706e-05 2.32718565948692e-05 -9.07547806844048e-06 5.77283580424944e-06 2.59481883552489e-06 1.54235951003149e-05 -7.25990840814141e-06 -9.07547806844048e-06 1.51280583579188e-05 -6.99277042150383e-07 -5.0317437595558e-06 -3.03570078502232e-06 6.39186933554761e-06 5.77283580424944e-06 -6.99277042150383e-07 5.86874632315019e-05 -3.77541949183563e-05 4.82814811683277e-06 1.69824972259158e-06 2.59481883552489e-06 -5.0317437595558e-06 -3.77541949183563e-05 8.69061978771462e-05 8.92615778650636e-06 1.13690166055482e-05 1.54235951003149e-05 -3.03570078502232e-06 4.82814811683277e-06 8.92615778650636e-06 3.51486652799528e-05 2130 2106 0 17 54 2216 2256 0 52 41 0 0 0 0 0 12 44 0 608 0 66 43 0 0 2450 +401 428 0.999998732612111 -0.000465242656068126 0.00152260416469525 0.00957356904482391 0.000462698254087504 0.999998496814335 0.00167101148919016 -0.00320979346157497 -0.00152337930176205 -0.00167030486508176 0.999997444695316 -0.0043005039805209 2.73229689415762e-05 1.84420998593051e-05 -9.61508046269487e-06 6.34262729177593e-06 7.87118592599161e-06 1.59267669274475e-05 1.84420998593051e-05 2.55354578388615e-05 -9.71180199552648e-06 7.12936222756001e-06 2.88426048800128e-06 1.63270230787776e-05 -9.61508046269487e-06 -9.71180199552648e-06 1.64085290898939e-05 -6.0826243970618e-07 -5.32557770907353e-06 -3.79977338974594e-06 6.34262729177593e-06 7.12936222756001e-06 -6.0826243970618e-07 4.62876289781618e-05 -7.00285717721268e-06 6.63546113439518e-06 7.87118592599161e-06 2.88426048800128e-06 -5.32557770907353e-06 -7.00285717721268e-06 4.7546392712784e-05 4.2996531914053e-06 1.59267669274475e-05 1.63270230787776e-05 -3.79977338974594e-06 6.63546113439518e-06 4.2996531914053e-06 3.9140729558706e-05 2230 2231 0 17 16 2326 2374 0 53 16 0 0 0 0 0 17 49 0 592 0 31 34 0 0 2327 +401 371 0.999989334816952 0.000414447029342537 0.00459983543288528 -0.00774592613597019 -0.000431072796073673 0.999993376482466 0.00361402371901753 0.0236596205437442 -0.00459830714440032 -0.00361596803871456 0.999982890026899 -0.00990285582406246 3.59176442520888e-05 1.51647214906983e-05 -6.31202673079988e-06 1.01125692310545e-05 6.59980710787078e-07 1.69256427575036e-05 1.51647214906983e-05 2.81079001747999e-05 -7.94425079978041e-06 7.75569992370751e-06 1.60242067784186e-06 1.04481335008186e-05 -6.31202673079988e-06 -7.94425079978041e-06 1.42367592750774e-05 4.79153726843855e-07 -1.27060543823193e-06 -2.658058456544e-06 1.01125692310545e-05 7.75569992370751e-06 4.79153726843855e-07 7.83799648376494e-05 -4.17897757826605e-05 9.07533318429195e-06 6.59980710787078e-07 1.60242067784186e-06 -1.27060543823193e-06 -4.17897757826605e-05 8.14178045485327e-05 -1.9910280516288e-06 1.69256427575036e-05 1.04481335008186e-05 -2.658058456544e-06 9.07533318429195e-06 -1.9910280516288e-06 4.04010291470843e-05 2041 2021 0 15 58 2031 2049 0 38 39 0 0 0 0 0 18 49 0 618 0 74 69 0 0 2343 +401 429 0.999968205276394 -0.00777914891678661 -0.00175307684868836 0.00450751452484857 0.00778733436203668 0.999958577503288 0.00471176199891685 0.00347418763698478 0.00171635073361833 -0.00472526398532948 0.999987362930366 -0.00129134310354512 2.99574307251635e-05 1.26742792530659e-05 -3.39320191632819e-06 4.67119374395931e-06 -1.77174942806753e-06 1.73757130020054e-05 1.26742792530659e-05 2.57497481740999e-05 -5.66056514474926e-06 8.23997297965477e-06 9.59056421181474e-07 1.36783523766781e-05 -3.39320191632819e-06 -5.66056514474926e-06 1.20346923261393e-05 3.89967943048498e-07 2.6445919031146e-06 9.29689273013731e-07 4.67119374395931e-06 8.23997297965477e-06 3.89967943048498e-07 4.03909707260168e-05 -7.19460866596259e-06 6.85615056183706e-06 -1.77174942806753e-06 9.59056421181474e-07 2.6445919031146e-06 -7.19460866596259e-06 4.49818269547319e-05 7.51545938058188e-07 1.73757130020054e-05 1.36783523766781e-05 9.29689273013731e-07 6.85615056183706e-06 7.51545938058188e-07 5.33262623395783e-05 2104 2101 0 5 25 2112 2135 0 39 24 0 0 0 0 0 28 60 0 584 0 14 15 0 0 2423 +402 405 0.999995146652594 -0.000962400355746749 -0.00296318356044361 0.00602580111210167 0.000958371555361428 0.999998614956033 -0.00136073876166253 -0.00959813739306014 0.0029644890317724 0.00135789232668695 0.999994683952475 0.00146435160690277 2.93234193335716e-05 8.72550474632919e-06 3.67369624399471e-08 -3.7350355350529e-06 -3.72215905852367e-06 9.5055170669456e-06 8.72550474632919e-06 2.58184074503596e-05 -2.98645011971797e-06 3.66506809490278e-06 5.07723380194888e-06 1.41539975933474e-05 3.67369624399471e-08 -2.98645011971797e-06 1.35549695973626e-05 5.828203231792e-06 8.80591216100995e-07 1.69026441455961e-06 -3.7350355350529e-06 3.66506809490278e-06 5.828203231792e-06 3.88753540092334e-05 -8.41154036910535e-06 -1.72124695267621e-06 -3.72215905852367e-06 5.07723380194888e-06 8.80591216100995e-07 -8.41154036910535e-06 4.93392480523754e-05 2.91570102867254e-06 9.5055170669456e-06 1.41539975933474e-05 1.69026441455961e-06 -1.72124695267621e-06 2.91570102867254e-06 3.22474121220233e-05 2129 2131 0 18 20 2127 2161 0 48 16 0 0 0 0 0 14 46 0 456 0 78 80 0 0 2545 +402 374 0.999994759093126 -0.000391689178122673 0.0032137775076305 0.0177948980996775 0.000390249630578374 0.999999823256324 0.000448544920817512 -0.0163182328331665 -0.00321395262980703 -0.000447288394550239 0.999994735206934 -0.00281088504374931 2.40596747370394e-05 1.49091219092488e-05 -7.32984555066449e-06 3.89993521416519e-06 8.06962357610923e-06 1.35695041329301e-05 1.49091219092488e-05 2.27591947901319e-05 -7.70686073128273e-06 2.74773834714577e-06 7.06877375753704e-06 8.87266421469957e-06 -7.32984555066449e-06 -7.70686073128273e-06 1.37511222455924e-05 4.22629682977975e-07 -2.28764853890181e-06 -3.51390305316395e-06 3.89993521416519e-06 2.74773834714577e-06 4.22629682977975e-07 4.03181502022082e-05 -1.44713021103738e-05 4.41020299577015e-06 8.06962357610923e-06 7.06877375753704e-06 -2.28764853890181e-06 -1.44713021103738e-05 5.13153026798303e-05 3.98875919220464e-06 1.35695041329301e-05 8.87266421469957e-06 -3.51390305316395e-06 4.41020299577015e-06 3.98875919220464e-06 3.38286004187983e-05 2551 2532 0 24 47 2568 2596 0 50 26 0 0 0 0 0 13 44 0 585 0 45 25 0 0 2575 +401 372 0.999999403720826 0.000471966044292286 0.000984787310007245 -0.00930949395218116 -0.000472144955312303 0.999999872077473 0.000181450210707381 0.0190053789131389 -0.00098470154569258 -0.000181915064872875 0.999999498634762 -0.00502391168401586 2.3020040444704e-05 1.04348923384152e-05 -4.99697897690412e-06 2.71469538145781e-06 2.82247053717441e-06 7.06615941945062e-06 1.04348923384152e-05 2.05372732586665e-05 -7.44585158626442e-06 2.57777112442686e-06 6.21189912668945e-06 8.99169621012809e-06 -4.99697897690412e-06 -7.44585158626442e-06 1.29786191973323e-05 -6.18710301294725e-07 -9.26912703482605e-08 -3.38054872281351e-06 2.71469538145781e-06 2.57777112442686e-06 -6.18710301294725e-07 6.20003043432749e-05 -3.2050723186738e-05 4.5015568852888e-06 2.82247053717441e-06 6.21189912668945e-06 -9.26912703482605e-08 -3.2050723186738e-05 6.76187333223844e-05 2.00311736242683e-06 7.06615941945062e-06 8.99169621012809e-06 -3.38054872281351e-06 4.5015568852888e-06 2.00311736242683e-06 3.1741773029024e-05 2506 2483 0 12 54 2494 2521 0 51 34 0 0 0 0 0 23 55 0 634 0 80 75 0 0 2604 +402 404 0.999999382020703 -0.000392263903139684 -0.00104023422478477 0.00386911430077487 0.000391861746163793 0.999999848423576 -0.00038677796864532 -0.00448785523655364 0.00104038578614542 0.000386370101624799 0.999999384157591 0.00415013569339206 2.18852019237599e-05 1.37193733022097e-05 -1.20643506922956e-06 1.07559698466487e-07 2.44923239935988e-07 7.78068292795537e-06 1.37193733022097e-05 2.11283392430781e-05 -3.26693027080541e-06 4.44819623304386e-06 -1.08722405875802e-06 1.28491908443258e-05 -1.20643506922956e-06 -3.26693027080541e-06 1.40271190663711e-05 3.08566320839776e-06 1.42834243924323e-06 2.2368301284026e-07 1.07559698466487e-07 4.44819623304386e-06 3.08566320839776e-06 4.18493098976204e-05 -2.27390599079843e-05 -5.44147188542321e-06 2.44923239935988e-07 -1.08722405875802e-06 1.42834243924323e-06 -2.27390599079843e-05 5.14434919521376e-05 7.60818212924935e-06 7.78068292795537e-06 1.28491908443258e-05 2.2368301284026e-07 -5.44147188542321e-06 7.60818212924935e-06 3.33647944690919e-05 2245 2246 0 22 26 2288 2328 0 47 24 0 0 0 0 0 14 43 0 446 0 82 79 0 0 2509 +402 372 0.999999579468462 -0.000127921043491908 -0.000908129454270507 -0.00058264423858922 0.00012789475281629 0.999999991400723 -2.90083745694196e-05 0.00624231953989714 0.000908133157242796 2.88922173784041e-05 0.999999587229619 -0.000597479173788801 2.57705110311052e-05 1.32432930958834e-05 -4.46103289845162e-06 7.09466492356217e-06 3.21182186605647e-06 1.1856028596234e-05 1.32432930958834e-05 2.14500743713003e-05 -6.37868702818543e-06 8.05752028324921e-06 2.61075546879825e-06 1.42973270407275e-05 -4.46103289845162e-06 -6.37868702818543e-06 1.10806977050267e-05 6.73815545885045e-07 2.18446036122415e-06 -2.84355006726149e-06 7.09466492356217e-06 8.05752028324921e-06 6.73815545885045e-07 4.02299443992232e-05 -2.15664594164192e-06 8.03896128522625e-06 3.21182186605647e-06 2.61075546879825e-06 2.18446036122415e-06 -2.15664594164192e-06 3.50390064898361e-05 8.02092799891781e-08 1.1856028596234e-05 1.42973270407275e-05 -2.84355006726149e-06 8.03896128522625e-06 8.02092799891781e-08 3.69153339376505e-05 2557 2544 0 23 51 2535 2555 0 45 30 0 0 0 0 0 17 49 0 586 0 95 78 0 0 2685 +402 371 0.999998522562454 0.00023241521243685 0.00170318997150466 -0.000447436379178493 -0.000234760628390159 0.999999024376106 0.00137700191887848 0.0105711244180117 -0.00170286827363833 -0.00137739972639213 0.999997601501942 -0.00343942178130193 2.78495026354979e-05 1.23461969629016e-05 -6.08920295686258e-06 4.52740791677011e-06 3.84633010629868e-06 9.86415021661342e-06 1.23461969629016e-05 2.53545726221785e-05 -8.39135038206971e-06 7.47403637575016e-06 5.39175929506065e-06 9.0923297068699e-06 -6.08920295686258e-06 -8.39135038206971e-06 1.3382010531813e-05 1.71981007567164e-06 -6.60838290273583e-07 -3.76630362184693e-06 4.52740791677011e-06 7.47403637575016e-06 1.71981007567164e-06 5.30533309451274e-05 -1.40692800318717e-05 4.8736462649049e-06 3.84633010629868e-06 5.39175929506065e-06 -6.60838290273583e-07 -1.40692800318717e-05 5.03106244445872e-05 2.3942868705285e-06 9.86415021661342e-06 9.0923297068699e-06 -3.76630362184693e-06 4.8736462649049e-06 2.3942868705285e-06 4.36930214865224e-05 1865 1845 0 21 51 1843 1858 0 44 34 0 0 0 0 0 16 48 0 576 0 95 78 0 0 2367 +402 429 0.999971603836606 -0.00742279689454406 0.0013013864558805 0.0106036245291969 0.00741972820626385 0.999969718695399 0.00234719526020303 -0.00416081784125692 -0.00131876980188914 -0.00233747267506896 0.999996398527366 -0.00577082404797831 3.95323971791264e-05 1.57699202231651e-05 -3.79014175015334e-06 2.6104258230154e-06 -2.94578127501399e-08 1.95026643572785e-05 1.57699202231651e-05 3.88501015017449e-05 -6.08985817029893e-06 5.27236493265277e-06 2.94680909745857e-06 2.55703116708524e-05 -3.79014175015334e-06 -6.08985817029893e-06 1.32451759223008e-05 2.89007806988575e-06 7.66070100324877e-07 7.18608237813302e-07 2.6104258230154e-06 5.27236493265277e-06 2.89007806988575e-06 4.15321703355415e-05 -4.71610320382429e-06 -2.01221008683794e-06 -2.94578127501399e-08 2.94680909745857e-06 7.66070100324877e-07 -4.71610320382429e-06 3.99345185110862e-05 2.89219767835626e-06 1.95026643572785e-05 2.55703116708524e-05 7.18608237813302e-07 -2.01221008683794e-06 2.89219767835626e-06 5.24755180946896e-05 2125 2123 0 9 29 2165 2193 0 37 29 0 0 0 0 0 27 59 0 557 0 17 17 0 0 2416 +402 406 0.999999452776952 -0.00078278321627171 0.000694043393514014 0.00907931627552497 0.000782343051336023 0.999999492833903 0.000634248600075446 -0.00687244519803291 -0.000694539520677818 -0.000633705272973752 0.999999558016143 -0.00156148622548488 2.16762623482821e-05 1.32516780096737e-05 -6.99764889580349e-07 -3.5417572644734e-07 7.36720659335015e-07 1.67907249922181e-05 1.32516780096737e-05 2.11208283747757e-05 -2.34158839381126e-06 1.02669914823511e-06 -5.0621828545685e-08 1.96563165846005e-05 -6.99764889580349e-07 -2.34158839381126e-06 9.53981623829437e-06 4.59419397445259e-06 3.34375434176869e-06 6.56244757266366e-07 -3.5417572644734e-07 1.02669914823511e-06 4.59419397445259e-06 2.92114296991721e-05 -8.38437888550608e-06 3.95833352416443e-06 7.36720659335015e-07 -5.0621828545685e-08 3.34375434176869e-06 -8.38437888550608e-06 2.90267654959688e-05 1.05287619823406e-06 1.67907249922181e-05 1.96563165846005e-05 6.56244757266366e-07 3.95833352416443e-06 1.05287619823406e-06 4.55538951451952e-05 3114 3129 0 33 21 3110 3163 0 50 21 0 0 0 0 0 16 49 0 473 0 31 32 0 0 2517 +402 373 0.999997594341458 -0.000334344578466942 0.0021678387854508 0.00726809927723493 0.000330021340248251 0.999997956898731 0.00199431298421744 -0.00488312916565684 -0.00216850114407066 -0.00199359275351995 0.99999566158595 -0.00147812775360116 3.12120676865093e-05 6.26364374055175e-06 -4.48871852745593e-06 3.6468299751056e-06 -3.39120341584915e-06 1.42563922563133e-05 6.26364374055175e-06 2.20251075214344e-05 -6.12199913577351e-06 5.19996165390481e-06 2.15148625025428e-06 9.36810228105921e-06 -4.48871852745593e-06 -6.12199913577351e-06 1.32018666823053e-05 6.34015821537618e-06 -3.30497191209816e-06 -7.6650643284335e-07 3.6468299751056e-06 5.19996165390481e-06 6.34015821537618e-06 7.62974632506676e-05 -6.27817891956657e-05 1.02727609963466e-05 -3.39120341584915e-06 2.15148625025428e-06 -3.30497191209816e-06 -6.27817891956657e-05 0.0001035043118807 -7.90151073223523e-06 1.42563922563133e-05 9.36810228105921e-06 -7.6650643284335e-07 1.02727609963466e-05 -7.90151073223523e-06 4.4228469379302e-05 2345 2321 0 16 53 2334 2375 0 48 41 0 0 0 0 0 15 45 0 580 0 50 27 0 0 2553 +402 375 0.999999966291583 -0.000223154186742565 -0.000132736736306367 0.0090894217225747 0.000223043179759993 0.999999625910103 -0.000835722079391978 -0.0085781152713325 0.000132923181531865 0.000835692445197373 0.999999641974718 8.11741620057441e-05 2.39881885555232e-05 6.87127346113172e-06 -3.23966640978679e-06 3.37370472833592e-06 6.12883535535899e-07 5.64592539058961e-06 6.87127346113172e-06 1.68382095803263e-05 -5.82296738372973e-06 7.39091387780088e-07 4.93228288559532e-06 1.13966648463056e-05 -3.23966640978679e-06 -5.82296738372973e-06 1.22941936150378e-05 2.18123324542594e-06 4.69486020580898e-07 -2.13152423815186e-06 3.37370472833592e-06 7.39091387780088e-07 2.18123324542594e-06 3.60889578871716e-05 -1.10976547177594e-05 5.4074545806904e-06 6.12883535535899e-07 4.93228288559532e-06 4.69486020580898e-07 -1.10976547177594e-05 4.68887065869e-05 5.22283897518639e-06 5.64592539058961e-06 1.13966648463056e-05 -2.13152423815186e-06 5.4074545806904e-06 5.22283897518639e-06 3.25602798581392e-05 3067 3051 0 29 53 3057 3094 0 47 41 0 0 0 0 0 15 47 0 580 0 50 27 0 0 2539 +402 428 0.999999984386149 1.84087638839087e-06 -0.00017670402400137 0.00607915915291755 -1.6922078215809e-06 0.999999646073064 0.000841338744470026 -0.00140386606966522 0.000176705510261685 -0.000841338432313557 0.999999630462334 -0.00236362064979474 2.7865281831943e-05 1.43193005538515e-05 -7.44400254408716e-06 5.00937545393831e-06 5.72616140054287e-06 1.70105940835302e-05 1.43193005538515e-05 1.94622500822281e-05 -8.5456624474323e-06 5.31017206159658e-06 3.24853198264688e-06 1.3908540456922e-05 -7.44400254408716e-06 -8.5456624474323e-06 1.26967897794249e-05 1.83466417630455e-06 -1.6193037369876e-06 -1.24245455093058e-06 5.00937545393831e-06 5.31017206159658e-06 1.83466417630455e-06 2.85622844447754e-05 -1.38626966889993e-06 5.38551688817067e-06 5.72616140054287e-06 3.24853198264688e-06 -1.6193037369876e-06 -1.38626966889993e-06 3.77783259304691e-05 7.63429009274284e-06 1.70105940835302e-05 1.3908540456922e-05 -1.24245455093058e-06 5.38551688817067e-06 7.63429009274284e-06 4.66066869348302e-05 3166 3174 0 23 19 3165 3214 0 46 17 0 0 0 0 0 11 44 0 560 0 16 18 0 0 2334 +403 371 0.99997994187902 -0.00140132366211077 0.00617674118164954 0.00819656779517957 0.00137758340394854 0.999991654959456 0.00384607272595548 0.000102171784160462 -0.00618207922921103 -0.00383748660482112 0.999973527446083 -0.00830099377226648 2.96182788169383e-05 1.00494579848459e-05 -3.02258904481452e-06 6.58936604317749e-06 -7.50596498329386e-06 1.30159544692547e-05 1.00494579848459e-05 2.69030168445727e-05 -6.47433117709689e-06 1.69360637999449e-06 7.13853405141975e-06 4.08059594622344e-06 -3.02258904481452e-06 -6.47433117709689e-06 1.39315140440383e-05 3.00806356204042e-06 -3.64947583377433e-07 -2.87024603000475e-06 6.58936604317749e-06 1.69360637999449e-06 3.00806356204042e-06 3.82692343196674e-05 -5.74156792502554e-06 5.21935976309027e-06 -7.50596498329386e-06 7.13853405141975e-06 -3.64947583377433e-07 -5.74156792502554e-06 5.35249925322529e-05 1.01397040972814e-06 1.30159544692547e-05 4.08059594622344e-06 -2.87024603000475e-06 5.21935976309027e-06 1.01397040972814e-06 3.88960695974459e-05 2004 1979 0 11 47 2085 2116 0 39 40 0 0 0 0 0 16 48 0 563 0 49 30 0 0 2335 +403 407 0.999996590520651 -0.00105209263562419 0.00238998915443988 0.00516486215209914 0.00104790587097705 0.999997915544803 0.0017523696343225 -0.00227427108397196 -0.00239182782780173 -0.00174985917598791 0.999995608566611 -0.00372746779091061 2.08609408464643e-05 1.00897907408259e-05 -1.79533178716906e-06 4.10639935823138e-07 -2.57166846237353e-06 8.37410828831221e-06 1.00897907408259e-05 1.91913694222198e-05 -2.89202296560331e-06 -9.92264041720442e-07 1.19233338490781e-08 1.25963568766343e-05 -1.79533178716906e-06 -2.89202296560331e-06 1.16451315558736e-05 3.4972385456053e-06 4.89100242983024e-06 1.04846284874209e-06 4.10639935823138e-07 -9.92264041720442e-07 3.4972385456053e-06 3.7560119321077e-05 -1.92603003931456e-05 -4.57371779774775e-06 -2.57166846237353e-06 1.19233338490781e-08 4.89100242983024e-06 -1.92603003931456e-05 3.69652494282111e-05 1.73654820262166e-06 8.37410828831221e-06 1.25963568766343e-05 1.04846284874209e-06 -4.57371779774775e-06 1.73654820262166e-06 2.81201173250516e-05 2559 2554 0 7 17 2562 2592 0 42 16 0 0 0 0 0 14 44 0 471 0 59 58 0 0 2436 +403 372 0.999990524055849 -0.00049030154248444 0.00432566791432471 0.00404668148293215 0.000481732188700119 0.999997920066316 0.00198186708428399 0.00392329459002429 -0.00432663062971074 -0.00197976449075023 0.99998868033591 -0.00547390235106467 2.6506088299953e-05 9.19030513806845e-06 -3.38241863035539e-06 3.75457857527382e-06 -1.01227595014876e-06 6.54233747370086e-06 9.19030513806845e-06 2.84554559902046e-05 -4.97403931718108e-06 5.7300667818284e-06 4.86243772562836e-06 7.73966873365783e-06 -3.38241863035539e-06 -4.97403931718108e-06 1.17652535419557e-05 3.43604071662946e-06 6.3139761848071e-07 -1.3892543656357e-06 3.75457857527382e-06 5.7300667818284e-06 3.43604071662946e-06 3.6073461454952e-05 -3.88813922906291e-06 5.94576969298124e-06 -1.01227595014876e-06 4.86243772562836e-06 6.3139761848071e-07 -3.88813922906291e-06 4.49571596494272e-05 -3.67364771854417e-06 6.54233747370086e-06 7.73966873365783e-06 -1.3892543656357e-06 5.94576969298124e-06 -3.67364771854417e-06 4.28477720699766e-05 1885 1864 0 13 48 1967 2008 0 48 39 0 0 0 0 0 15 47 0 562 0 52 33 0 0 2669 +403 405 0.999997781964141 -0.000525645927110352 0.00203954974392733 0.00648740167041833 0.000522109457566931 0.999998360163058 0.0017340913786688 -0.00478298227873811 -0.00204045791746875 -0.00173302266418146 0.999996416575546 -0.00539606579644254 2.30691207182585e-05 1.06954369085608e-05 -1.72061692660091e-06 7.8325759048608e-07 -3.86573686560762e-06 9.73649061247123e-06 1.06954369085608e-05 2.05300466170689e-05 -2.75560517438763e-06 1.4289616134347e-07 -3.19560533079048e-07 1.24410296930456e-05 -1.72061692660091e-06 -2.75560517438763e-06 1.44886195658776e-05 3.85880361892541e-06 9.94579615488002e-07 1.9283723809599e-06 7.8325759048608e-07 1.4289616134347e-07 3.85880361892541e-06 2.6927870013145e-05 -1.29070286496547e-05 -4.626428288489e-07 -3.86573686560762e-06 -3.19560533079048e-07 9.94579615488002e-07 -1.29070286496547e-05 4.24100772695265e-05 -7.96829204200856e-07 9.73649061247123e-06 1.24410296930456e-05 1.9283723809599e-06 -4.626428288489e-07 -7.96829204200856e-07 2.65842877052033e-05 2262 2259 0 12 20 2356 2401 0 41 20 0 0 0 0 0 11 43 0 443 0 46 45 0 0 2539 +403 429 0.99996200483166 -0.00864355867351706 -0.0011303921909364 0.0121474423528044 0.00864508416885295 0.999961717011661 0.00135167703363501 -0.0115742768504656 0.00111866561639747 -0.00136139801207303 0.999998447590141 -0.00408873846019281 3.47283189571832e-05 1.02228209765284e-05 -4.43795547078883e-06 7.2595549667141e-06 -6.09856913618308e-07 9.21672824034405e-06 1.02228209765284e-05 2.27960113079236e-05 -5.74618010546506e-06 4.9526786271777e-06 6.96440940998068e-07 1.29717844387262e-05 -4.43795547078883e-06 -5.74618010546506e-06 1.13015716393235e-05 4.09635789209466e-06 1.12664532524831e-06 -1.19532910179445e-06 7.2595549667141e-06 4.9526786271777e-06 4.09635789209466e-06 3.83779730372123e-05 -1.42261266610166e-05 -1.05919070487241e-06 -6.09856913618308e-07 6.96440940998068e-07 1.12664532524831e-06 -1.42261266610166e-05 4.27057176459041e-05 3.51854936389145e-06 9.21672824034405e-06 1.29717844387262e-05 -1.19532910179445e-06 -1.05919070487241e-06 3.51854936389145e-06 4.28906316531737e-05 2886 2884 0 7 25 2892 2917 0 33 26 0 0 0 0 0 20 52 0 533 0 14 12 0 0 2438 +403 377 0.999998372593621 -0.0004444860031434 0.00174849715546857 0.00993960521496921 0.00044216980876106 0.99999902464083 0.00132484083921007 -0.00749259609340672 -0.00174908432326526 -0.00132406555050279 0.999997593774329 -0.000833241877172072 1.83043675057964e-05 8.10977442033873e-06 -2.39748803800249e-06 3.28054301059053e-06 9.24918720902019e-07 8.4766956575377e-06 8.10977442033873e-06 1.47201021402714e-05 -4.86070708050056e-06 3.88533791474635e-06 1.24523681229572e-06 7.19759116100143e-06 -2.39748803800249e-06 -4.86070708050056e-06 1.02637271220494e-05 1.76494063464721e-06 8.22676190650778e-07 -1.29437797027383e-06 3.28054301059053e-06 3.88533791474635e-06 1.76494063464721e-06 4.19305560899355e-05 -2.00141516805761e-05 4.36108096978044e-06 9.24918720902019e-07 1.24523681229572e-06 8.22676190650778e-07 -2.00141516805761e-05 4.61911070033346e-05 3.56981699885046e-06 8.4766956575377e-06 7.19759116100143e-06 -1.29437797027383e-06 4.36108096978044e-06 3.56981699885046e-06 3.03777786553078e-05 2780 2762 0 14 47 2768 2798 0 46 34 0 0 0 0 0 13 45 0 528 0 45 26 0 0 2620 +402 376 0.999998367803025 -0.000806101687826325 -0.00161696980647611 0.00886448188881791 0.000804284081697667 0.999999044406144 -0.00112441714471123 -0.00900339929402875 0.00161787465586787 0.00112311480636503 0.999998060545484 0.00459319936462971 2.54922531258878e-05 1.29360882643698e-05 -6.79291184304982e-06 8.35774878887302e-06 3.01102779142075e-06 1.18100206724729e-05 1.29360882643698e-05 2.35868966370718e-05 -7.46318613778428e-06 1.15282074705836e-05 2.46969070797945e-06 1.3065007639694e-05 -6.79291184304982e-06 -7.46318613778428e-06 1.32842596933005e-05 -1.89726796182053e-06 -6.80514437107658e-07 -3.58877107142127e-06 8.35774878887302e-06 1.15282074705836e-05 -1.89726796182053e-06 4.885780332134e-05 -1.83146411955481e-05 9.65911380578801e-06 3.01102779142075e-06 2.46969070797945e-06 -6.80514437107658e-07 -1.83146411955481e-05 4.96634276454206e-05 9.36640584988187e-07 1.18100206724729e-05 1.3065007639694e-05 -3.58877107142127e-06 9.65911380578801e-06 9.36640584988187e-07 3.48948329513129e-05 2652 2632 0 21 50 2635 2655 0 49 31 0 0 0 0 0 13 44 0 571 0 96 80 0 0 2540 +403 406 0.999995138220985 -0.00069164569469072 -0.00304058557304093 0.0029134988135285 0.000689734366358516 0.999999563929406 -0.000629609006533906 -0.00349606813517729 0.00304101971348969 0.00062750874915047 0.999995179204316 0.00140544857945171 1.94209830320358e-05 1.52510791326456e-05 -1.14384475028999e-06 8.66285734454864e-07 3.17597759616092e-06 1.55761938317181e-05 1.52510791326456e-05 2.23925044352977e-05 -2.76260482894382e-06 2.3962936300723e-06 -4.07623594948441e-07 1.99009158300551e-05 -1.14384475028999e-06 -2.76260482894382e-06 1.12760206098817e-05 3.60205433099594e-06 3.38126974996513e-06 1.50359339757346e-06 8.66285734454864e-07 2.3962936300723e-06 3.60205433099594e-06 2.56772894905334e-05 -8.04155831890212e-06 2.06451368563153e-06 3.17597759616092e-06 -4.07623594948441e-07 3.38126974996513e-06 -8.04155831890212e-06 2.69248762930376e-05 2.51175596393501e-06 1.55761938317181e-05 1.99009158300551e-05 1.50359339757346e-06 2.06451368563153e-06 2.51175596393501e-06 3.66086496850547e-05 2858 2855 0 11 17 2971 3011 0 42 17 0 0 0 0 0 16 49 0 454 0 32 33 0 0 2551 +404 407 0.999997349556946 -0.00030470978084446 0.00228211109129008 0.00687469117096072 0.000302123538371582 0.999999311919199 0.00113352657503564 -0.00384985057593171 -0.00228245491764751 -0.00113283409121014 0.999996753537966 -0.00056346628895092 3.34093338069383e-05 1.25085450515512e-05 -1.8524669152967e-06 -1.48525350697464e-07 -2.24050246719006e-06 2.10766509148951e-05 1.25085450515512e-05 2.49035373194589e-05 -3.18483374665191e-06 3.63426001642823e-06 1.10508140984449e-07 2.0284073400655e-05 -1.8524669152967e-06 -3.18483374665191e-06 1.003343676548e-05 5.14173495325756e-06 4.27106239549263e-06 -4.90420525806951e-08 -1.48525350697464e-07 3.63426001642823e-06 5.14173495325756e-06 2.42798748352591e-05 -2.4455261772925e-06 2.5085692210083e-06 -2.24050246719006e-06 1.10508140984449e-07 4.27106239549263e-06 -2.4455261772925e-06 2.24020876407371e-05 -2.26968186973467e-06 2.10766509148951e-05 2.0284073400655e-05 -4.90420525806951e-08 2.5085692210083e-06 -2.26968186973467e-06 5.02950669037125e-05 2352 2352 0 21 19 2351 2394 0 50 20 0 0 0 0 0 20 50 0 484 0 31 30 0 0 2433 +403 375 0.999995147070834 -0.000561851815797906 -0.00306433635841352 0.010315307634134 0.00055394021876599 0.999996513030404 -0.00258206840859243 -0.0148151378772898 0.00306577641298969 0.00258035841884459 0.999991971350478 0.000274561617565479 2.71333215071489e-05 1.12280035037515e-05 -3.09550373408698e-06 3.1439103043016e-06 -1.15419314073475e-06 1.03256927281911e-05 1.12280035037515e-05 2.20767916573208e-05 -5.76807432417484e-06 4.99774370321676e-06 -2.65514101761498e-06 1.30655666021269e-05 -3.09550373408698e-06 -5.76807432417484e-06 1.12286953898174e-05 3.70633585786708e-06 1.32456159334312e-06 2.22920685283637e-07 3.1439103043016e-06 4.99774370321676e-06 3.70633585786708e-06 5.7637256655257e-05 -4.01370698316658e-05 4.74245376344187e-06 -1.15419314073475e-06 -2.65514101761498e-06 1.32456159334312e-06 -4.01370698316658e-05 7.23899539199897e-05 3.26891016076235e-06 1.03256927281911e-05 1.30655666021269e-05 2.22920685283637e-07 4.74245376344187e-06 3.26891016076235e-06 3.60397722527782e-05 2504 2475 0 13 53 2606 2642 0 48 45 0 0 0 0 0 15 47 0 553 0 52 30 0 0 2507 +403 373 0.999998865602149 -0.000631923525115277 0.00136728456210122 0.00814112957037578 0.000630775831762733 0.999999448542465 0.000839664584919477 -0.00704682382379395 -0.00136781441190626 -0.000838801182348861 0.999998712747327 -0.000924484490845359 3.0610226805365e-05 1.00811603548368e-05 -3.77281829050435e-06 4.58201109523036e-06 -3.34781473763337e-06 1.01541164665973e-05 1.00811603548368e-05 2.65385180245366e-05 -7.06285137711188e-06 6.90201449476608e-06 3.08863351761856e-06 1.07473700262947e-05 -3.77281829050435e-06 -7.06285137711188e-06 1.17878255604332e-05 2.6683776351431e-06 2.34163379895314e-06 -2.49896232521315e-06 4.58201109523036e-06 6.90201449476608e-06 2.6683776351431e-06 5.77184681401414e-05 -3.92756918307434e-05 2.64405806304038e-06 -3.34781473763337e-06 3.08863351761856e-06 2.34163379895314e-06 -3.92756918307434e-05 6.86193645886614e-05 6.98038393445828e-07 1.01541164665973e-05 1.07473700262947e-05 -2.49896232521315e-06 2.64405806304038e-06 6.98038393445828e-07 3.07269528700354e-05 2464 2438 0 12 53 2571 2606 0 45 47 0 0 0 0 0 7 37 0 538 0 52 29 0 0 2521 +404 371 0.99998693745078 -0.000700735014630207 0.00506299301288984 0.00195515522844289 0.000685063093055007 0.999994971304802 0.00309645824571663 0.00679217587392027 -0.0050651373493553 -0.00309294932842486 0.999982388868966 -0.00782096688617673 2.78078590057827e-05 1.36245207566649e-05 -3.74785368004292e-06 5.26466052556172e-06 1.50153572607881e-06 1.1914018547941e-05 1.36245207566649e-05 2.56883689788469e-05 -5.55328834641616e-06 7.53355443076179e-06 1.16897146271927e-06 6.21052855324314e-06 -3.74785368004292e-06 -5.55328834641616e-06 1.14611485470151e-05 4.19193208062683e-06 2.51471403852254e-06 -1.5951855148098e-06 5.26466052556172e-06 7.53355443076179e-06 4.19193208062683e-06 4.70575652954135e-05 -6.35813388861323e-06 3.9522372692778e-06 1.50153572607881e-06 1.16897146271927e-06 2.51471403852254e-06 -6.35813388861323e-06 4.34781130311445e-05 1.24954019370687e-06 1.1914018547941e-05 6.21052855324314e-06 -1.5951855148098e-06 3.9522372692778e-06 1.24954019370687e-06 3.44470966497804e-05 2014 1992 0 20 51 2060 2090 0 47 51 0 0 0 0 0 22 54 0 570 0 48 27 0 0 2435 +404 372 0.999997896070768 -0.000243481008602442 0.00203680412302667 0.000873587391217456 0.000241184647837059 0.999999335170561 0.00112760294497962 0.0077450738652433 -0.00203707731880168 -0.0011271093266977 0.999997289966609 -0.00341050584146866 2.51474891586219e-05 1.464786832896e-05 -4.67783017823981e-06 2.85193405240433e-06 5.6700668537664e-06 1.13617282939272e-05 1.464786832896e-05 2.23332537342152e-05 -6.32890369155606e-06 1.03438689528516e-06 7.41595078318753e-06 1.18073855051253e-05 -4.67783017823981e-06 -6.32890369155606e-06 1.22420421610406e-05 3.72938010055633e-06 2.11381899442327e-06 -2.3991529372564e-06 2.85193405240433e-06 1.03438689528516e-06 3.72938010055633e-06 3.23084181769305e-05 -2.90977458087682e-06 2.19135258830549e-06 5.6700668537664e-06 7.41595078318753e-06 2.11381899442327e-06 -2.90977458087682e-06 3.54090216597658e-05 3.30570406303975e-06 1.13617282939272e-05 1.18073855051253e-05 -2.3991529372564e-06 2.19135258830549e-06 3.30570406303975e-06 3.28468627643894e-05 2480 2461 0 19 51 2535 2561 0 44 51 0 0 0 0 0 20 52 0 574 0 48 27 0 0 2589 +403 374 0.999998896044915 -0.00074778858339887 0.00128402538388889 0.0116118914222263 0.000746612304289983 0.999999301461594 0.000916322209089589 -0.0120903711752495 -0.00128470970223452 -0.000915362528360395 0.999998755815437 -0.00152453768130938 2.19487052438661e-05 1.11944519195059e-05 -2.59580974562886e-06 4.06568561138515e-06 2.27427493469957e-06 8.98511831169298e-06 1.11944519195059e-05 2.11250034149931e-05 -5.25361111148973e-06 1.99998419809431e-06 4.31389571713423e-06 1.29105502155756e-05 -2.59580974562886e-06 -5.25361111148973e-06 1.27399920924359e-05 1.50965271814893e-06 2.25533739520383e-06 -2.17486381969706e-06 4.06568561138515e-06 1.99998419809431e-06 1.50965271814893e-06 4.17192027823555e-05 -1.25926081579193e-05 2.4993666404572e-06 2.27427493469957e-06 4.31389571713423e-06 2.25533739520383e-06 -1.25926081579193e-05 4.36000393009614e-05 4.60388415607312e-06 8.98511831169298e-06 1.29105502155756e-05 -2.17486381969706e-06 2.4993666404572e-06 4.60388415607312e-06 3.57125130237622e-05 2182 2156 0 20 47 2166 2191 0 46 32 0 0 0 0 0 16 48 0 560 0 44 24 0 0 2562 +404 375 0.999999892827847 -0.00043599093401223 0.000155744017839883 0.0173872107660333 0.000436308109047907 0.999997819280706 -0.00204231953079537 -0.0205185395013309 -0.000154853245406115 0.00204238726429351 0.999997902335167 -0.00520357994213929 3.00142620535667e-05 1.31969489748197e-05 -2.72657673747581e-06 2.86298676696595e-06 3.3432990758216e-06 7.13435374176161e-06 1.31969489748197e-05 2.22747483006971e-05 -6.27136341837663e-06 5.28558279335047e-07 4.66594118630694e-06 1.45827507773687e-05 -2.72657673747581e-06 -6.27136341837663e-06 1.29655564378075e-05 1.46948470814252e-06 2.78489619032014e-06 -1.67090171234562e-06 2.86298676696595e-06 5.28558279335047e-07 1.46948470814252e-06 4.73606053907869e-05 -2.84106186260237e-05 1.28435080256161e-06 3.3432990758216e-06 4.66594118630694e-06 2.78489619032014e-06 -2.84106186260237e-05 6.39695111280657e-05 8.78106121340971e-06 7.13435374176161e-06 1.45827507773687e-05 -1.67090171234562e-06 1.28435080256161e-06 8.78106121340971e-06 3.57093568334064e-05 2131 2112 0 29 53 2214 2245 0 54 44 0 0 0 0 0 14 46 0 566 0 70 50 0 0 2417 +403 376 0.999999519989183 -0.000532099822209635 -0.000822733968717674 0.0144796986490169 0.000531626968374321 0.999999693461968 -0.000574846707634315 -0.0155241297715907 0.000823039592349352 0.000574409044136109 0.999999496329913 -0.00488043269730427 2.64812306481763e-05 9.14373952063404e-06 -4.24014861443698e-06 3.33615138623007e-06 -4.93414467139332e-06 6.02318782619163e-06 9.14373952063404e-06 2.37185464233592e-05 -6.99579941365254e-06 3.0906133740877e-06 3.19115431071404e-06 1.22449057147637e-05 -4.24014861443698e-06 -6.99579941365254e-06 1.28818689584796e-05 7.04162549390064e-07 1.24718354585892e-06 -3.37750749524451e-06 3.33615138623007e-06 3.0906133740877e-06 7.04162549390064e-07 5.05931903042088e-05 -3.15502361612118e-05 8.48279405509003e-06 -4.93414467139332e-06 3.19115431071404e-06 1.24718354585892e-06 -3.15502361612118e-05 5.91499192306514e-05 -6.71909810514465e-06 6.02318782619163e-06 1.22449057147637e-05 -3.37750749524451e-06 8.48279405509003e-06 -6.71909810514465e-06 3.26891042332403e-05 1525 1503 0 25 50 1607 1640 0 49 38 0 0 0 0 0 12 43 0 546 0 62 44 0 0 2508 +404 374 0.999998477037537 -0.000231499186838777 0.00172983546391792 0.00595810277223469 0.000229177347226865 0.999999072841489 0.00134230916893625 -0.00665465896665863 -0.00173014460356734 -0.00134191068554701 0.999997602934808 -0.00229919610001458 2.75977366267041e-05 6.19588265953432e-06 -4.69026839654304e-06 -2.96310053216563e-06 2.22789535168103e-06 4.60593784750508e-06 6.19588265953432e-06 2.36357839617228e-05 -5.96717292715052e-06 7.10405964277568e-06 8.06915142983497e-07 5.9499980290037e-06 -4.69026839654304e-06 -5.96717292715052e-06 1.29598872485702e-05 2.20700810149147e-06 1.16612834739531e-06 4.82192910171562e-07 -2.96310053216563e-06 7.10405964277568e-06 2.20700810149147e-06 5.65712199278002e-05 -3.00202531926102e-05 5.58210367871059e-06 2.22789535168103e-06 8.06915142983497e-07 1.16612834739531e-06 -3.00202531926102e-05 6.24966720811098e-05 -1.01459350328598e-06 4.60593784750508e-06 5.9499980290037e-06 4.82192910171562e-07 5.58210367871059e-06 -1.01459350328598e-06 3.81363239842454e-05 2427 2408 0 22 41 2453 2468 0 40 39 0 0 0 0 0 18 50 0 573 0 72 52 0 0 2532 +404 406 0.999995417958891 -0.000540811210898257 0.00297852051493819 0.00856352304730637 0.000538131692519286 0.999999449899281 0.000900341832941357 -0.00433874751519438 -0.00297900579140881 -0.000898734871252159 0.999995158888345 -0.00467549063691514 2.12591810988292e-05 1.50948428233529e-05 -1.01335294380118e-06 -5.17668395116579e-07 -3.74483557941251e-07 1.50744530402086e-05 1.50948428233529e-05 2.1606918864412e-05 -2.91288085951878e-06 -1.03827709245238e-07 -1.75518959955705e-06 1.66336094201423e-05 -1.01335294380118e-06 -2.91288085951878e-06 1.15008156251264e-05 4.4125273684628e-06 4.49677321661229e-06 2.67173077104607e-06 -5.17668395116579e-07 -1.03827709245238e-07 4.4125273684628e-06 2.49832172762898e-05 -1.10349065746404e-06 3.40820120433422e-06 -3.74483557941251e-07 -1.75518959955705e-06 4.49677321661229e-06 -1.10349065746404e-06 2.59521542226817e-05 1.00843648325549e-06 1.50744530402086e-05 1.66336094201423e-05 2.67173077104607e-06 3.40820120433422e-06 1.00843648325549e-06 3.53792977860003e-05 2161 2158 0 19 22 2255 2302 0 45 24 0 0 0 0 0 14 47 0 471 0 48 48 0 0 2596 +404 376 0.999999238757153 -0.000945315842003431 0.00079300887347704 0.014746597255494 0.000945132808038417 0.99999952664614 0.000231152484961857 -0.0146703039849035 -0.000793227010209181 -0.000230402810295292 0.99999965885267 -0.00193656452945115 3.12272697679936e-05 1.0806473017601e-05 -4.02568780351939e-06 1.01806372425169e-06 4.81197900298806e-06 1.00195188732038e-05 1.0806473017601e-05 2.77485521286794e-05 -5.07682650111894e-06 4.36423634864885e-06 6.77073716408354e-06 1.43441743216064e-05 -4.02568780351939e-06 -5.07682650111894e-06 1.34471180524697e-05 1.53418705392524e-06 1.08053214346301e-06 -7.97446157432505e-07 1.01806372425169e-06 4.36423634864885e-06 1.53418705392524e-06 4.57412777725992e-05 -2.42254190008123e-05 5.6286857014654e-06 4.81197900298806e-06 6.77073716408354e-06 1.08053214346301e-06 -2.42254190008123e-05 5.36804513370603e-05 7.32142013009036e-07 1.00195188732038e-05 1.43441743216064e-05 -7.97446157432505e-07 5.6286857014654e-06 7.32142013009036e-07 3.84916513339197e-05 2552 2531 0 27 50 2593 2618 0 48 50 0 0 0 0 0 10 41 0 554 0 47 27 0 0 2549 +404 378 0.999998032920921 -0.000731525662685015 0.00184364435107407 0.0118106644821117 0.000730346091583478 0.999999528243601 0.000640396097790624 -0.00971022334553183 -0.00184411194750286 -0.000639048339634781 0.999998095432359 -0.00163238357853757 2.0473399547868e-05 1.11712460076188e-05 -4.154294847869e-06 4.12556085983861e-06 6.80229955860877e-06 1.16463084489641e-05 1.11712460076188e-05 1.93535592238093e-05 -6.19236459979711e-06 3.03112638078316e-06 2.4960650311097e-07 8.1552323203362e-06 -4.154294847869e-06 -6.19236459979711e-06 1.14263143812373e-05 2.05210376908182e-07 2.965845035642e-06 -1.85976923782551e-06 4.12556085983861e-06 3.03112638078316e-06 2.05210376908182e-07 3.90683953099673e-05 -1.162680896244e-05 8.37564846614887e-07 6.80229955860877e-06 2.4960650311097e-07 2.965845035642e-06 -1.162680896244e-05 3.23252001356017e-05 1.05852947445783e-05 1.16463084489641e-05 8.1552323203362e-06 -1.85976923782551e-06 8.37564846614887e-07 1.05852947445783e-05 3.4517384481787e-05 2689 2671 0 23 45 2683 2706 0 44 38 0 0 0 0 0 20 51 0 583 0 44 24 0 0 2613 +404 373 0.999990225928429 -0.000371242163501002 0.00440570390137092 0.0061914394705281 0.000353653258886541 0.99999196776088 0.00399241068729637 -0.00540035963622829 -0.00440715066488483 -0.00399081357364616 0.999982325058817 -0.0094872333213745 2.92642533421992e-05 1.01028237075795e-05 -5.39558616354337e-06 3.39067337803876e-06 -4.16428451573204e-07 1.30384265635706e-05 1.01028237075795e-05 2.47072149359188e-05 -5.74286011772389e-06 7.06649796143392e-06 1.82960409316683e-06 1.13567646113587e-05 -5.39558616354337e-06 -5.74286011772389e-06 1.19051870877901e-05 4.03111588644342e-06 6.77216616628309e-07 -2.39423070636406e-06 3.39067337803876e-06 7.06649796143392e-06 4.03111588644342e-06 8.18225012363759e-05 -5.97445524374152e-05 9.21494732381426e-06 -4.16428451573204e-07 1.82960409316683e-06 6.77216616628309e-07 -5.97445524374152e-05 9.14475033621266e-05 -4.42539585802292e-06 1.30384265635706e-05 1.13567646113587e-05 -2.39423070636406e-06 9.21494732381426e-06 -4.42539585802292e-06 3.94070052618175e-05 1560 1538 0 21 53 1653 1689 0 51 45 0 0 0 0 0 22 52 0 571 0 70 47 0 0 2596 +404 408 0.999999543664326 -0.000734458751648572 0.000610934924431596 0.00818990080571812 0.000734386166647097 0.999999723254899 0.000119025557897647 -0.00538946529294435 -0.000611022174721017 -0.000118576841424814 0.999999806295699 -0.00167219825377545 1.9424009983315e-05 1.39943267383313e-05 -1.75237525575849e-06 -7.02019987439376e-07 2.38041141932454e-06 9.2349526178602e-06 1.39943267383313e-05 1.99558256612542e-05 -3.72101066519261e-06 2.5371938424232e-07 -2.25357348956009e-06 1.40926177522114e-05 -1.75237525575849e-06 -3.72101066519261e-06 1.06291170494721e-05 3.86320108591082e-06 3.8103492116413e-06 2.87352578928811e-07 -7.02019987439376e-07 2.5371938424232e-07 3.86320108591082e-06 2.78910625427386e-05 -6.76643060770876e-06 2.60049629334164e-06 2.38041141932454e-06 -2.25357348956009e-06 3.8103492116413e-06 -6.76643060770876e-06 2.6230386174765e-05 8.82455767093106e-08 9.2349526178602e-06 1.40926177522114e-05 2.87352578928811e-07 2.60049629334164e-06 8.82455767093106e-08 2.84433476334938e-05 2716 2720 0 17 16 2770 2819 0 50 17 0 0 0 0 0 13 43 0 484 0 33 32 0 0 2416 +405 408 0.999999621032785 -0.000116290620558007 0.000862792430232184 0.00443606688549117 0.000116096499406862 0.999999967939662 0.00022503839022186 -0.000562139700356096 -0.000862818572424816 -0.000224938137758824 0.999999602473394 -0.000445361161208795 2.07923604678239e-05 1.62148384417217e-05 -8.09567122451635e-07 2.66274909461132e-06 4.98995735950471e-07 2.05218548522021e-05 1.62148384417217e-05 2.20074259958315e-05 -2.61962838893786e-06 3.53016032877006e-06 -6.51617898465687e-07 2.2514650858618e-05 -8.09567122451635e-07 -2.61962838893786e-06 9.39663045351147e-06 4.78386762005858e-06 2.49503326706261e-06 9.39854078220453e-07 2.66274909461132e-06 3.53016032877006e-06 4.78386762005858e-06 2.41730405109497e-05 -2.67326026317561e-06 8.77425721810497e-06 4.98995735950471e-07 -6.51617898465687e-07 2.49503326706261e-06 -2.67326026317561e-06 2.26011444464072e-05 -2.88890684921138e-06 2.05218548522021e-05 2.2514650858618e-05 9.39854078220453e-07 8.77425721810497e-06 -2.88890684921138e-06 4.26700606696635e-05 2454 2456 0 19 31 2448 2498 0 46 16 0 0 0 0 0 18 50 0 488 0 33 31 0 0 2444 +404 377 0.999998284546281 -0.000824740611378126 0.00165852567606374 0.00708081087447259 0.000821530692848629 0.999997790127613 0.00193515560367644 -0.00605834292559203 -0.00166011801234933 -0.0019337897542588 0.999996752227412 -0.00237303386156727 2.42738036721833e-05 7.86783807460028e-06 -5.50954839983075e-06 2.94428660182451e-06 -1.72942726346633e-06 9.25582108707046e-06 7.86783807460028e-06 2.33512194415254e-05 -6.05647644165763e-06 4.32464572063586e-06 3.73600620155695e-06 3.20835015261887e-06 -5.50954839983075e-06 -6.05647644165763e-06 1.29747348464395e-05 7.68844410049867e-07 1.61131187141931e-06 -2.09263654746368e-06 2.94428660182451e-06 4.32464572063586e-06 7.68844410049867e-07 5.93370256403362e-05 -3.73096440722921e-05 4.6826481747411e-06 -1.72942726346633e-06 3.73600620155695e-06 1.61131187141931e-06 -3.73096440722921e-05 6.51179611087306e-05 -4.01326850775588e-07 9.25582108707046e-06 3.20835015261887e-06 -2.09263654746368e-06 4.6826481747411e-06 -4.01326850775588e-07 3.57357701051338e-05 1915 1897 0 18 40 1939 1966 0 51 36 0 0 0 0 0 17 49 0 548 0 68 49 0 0 2524 +405 409 0.999994980684379 -0.000528504583971035 -0.00312398606788723 0.00327511684018404 0.000523685834841625 0.999998672270677 -0.00154311698519436 -0.0051859401149909 0.0031247974644796 0.00154147325255117 0.999993929732085 0.00279908561608243 3.14187699801528e-05 1.80751031580029e-05 -2.53610685087127e-06 2.19486336470524e-06 -1.04053710427753e-06 1.98502023821425e-05 1.80751031580029e-05 3.72856381530589e-05 -2.16527280727771e-06 9.76018284646131e-06 -2.25703569417267e-06 3.1468109671681e-05 -2.53610685087127e-06 -2.16527280727771e-06 1.06790533681177e-05 1.91647524693476e-06 3.62507407030103e-06 9.15738773188908e-07 2.19486336470524e-06 9.76018284646131e-06 1.91647524693476e-06 4.04622481104469e-05 -1.79585353208423e-05 3.24376671743508e-06 -1.04053710427753e-06 -2.25703569417267e-06 3.62507407030103e-06 -1.79585353208423e-05 3.54594379744584e-05 -7.18241280238577e-07 1.98502023821425e-05 3.1468109671681e-05 9.15738773188908e-07 3.24376671743508e-06 -7.18241280238577e-07 5.39938231006418e-05 2490 2487 0 18 33 2505 2548 0 53 12 0 0 0 0 0 13 45 0 483 0 50 49 0 0 2399 +405 374 0.99999783642625 -0.00035399236262006 0.00204983712208021 0.0153643754221689 0.000353641959459164 0.999999922796512 0.000171301884490531 -0.0173344724250275 -0.00204989760338445 -0.000170576605449846 0.999997884409481 -0.00122847642688766 2.28028462169921e-05 1.13251699389065e-05 -6.07780288676324e-06 5.22385680459984e-07 5.47469010360275e-06 1.03373081071086e-05 1.13251699389065e-05 2.50263384779931e-05 -9.3069349717427e-06 6.43908857921058e-06 8.08502441052022e-06 1.225059813348e-05 -6.07780288676324e-06 -9.3069349717427e-06 1.4423468744753e-05 3.28075692762433e-06 -1.3052589854973e-06 -4.19591244455414e-06 5.22385680459984e-07 6.43908857921058e-06 3.28075692762433e-06 4.0996823150096e-05 -1.15431733166039e-05 3.64767560648849e-06 5.47469010360275e-06 8.08502441052022e-06 -1.3052589854973e-06 -1.15431733166039e-05 5.54509568446668e-05 6.98292345329985e-06 1.03373081071086e-05 1.225059813348e-05 -4.19591244455414e-06 3.64767560648849e-06 6.98292345329985e-06 3.21854907122345e-05 1848 1827 0 20 46 1907 1924 0 57 48 0 0 0 0 0 10 42 0 567 0 81 61 0 0 2572 +405 376 0.999998127132047 -0.000328012489410289 0.00190739094162445 0.0104864044876648 0.000325229938068139 0.999998882839981 0.00145895314469149 -0.00606162923756574 -0.00190786736561647 -0.00145833007162709 0.999997116653602 0.0017823824078033 2.31449622152274e-05 1.15360480979917e-05 -2.98800226143579e-06 1.98458297543092e-06 3.76452523433526e-06 1.17549268093597e-05 1.15360480979917e-05 2.17614753223327e-05 -5.67244044342849e-06 5.50773944140729e-06 2.36080026309826e-06 1.7123269257062e-05 -2.98800226143579e-06 -5.67244044342849e-06 1.11161675519862e-05 1.52129655354795e-06 7.79751603570654e-07 -1.56346326088407e-06 1.98458297543092e-06 5.50773944140729e-06 1.52129655354795e-06 3.79070844207461e-05 -1.12284437358348e-05 9.83371420941012e-06 3.76452523433526e-06 2.36080026309826e-06 7.79751603570654e-07 -1.12284437358348e-05 3.96411207012016e-05 -4.53771760747737e-07 1.17549268093597e-05 1.7123269257062e-05 -1.56346326088407e-06 9.83371420941012e-06 -4.53771760747737e-07 3.71466189176614e-05 2946 2922 0 14 49 2950 2978 0 53 54 0 0 0 0 0 13 44 0 548 0 36 16 0 0 2543 +405 407 0.999999335908257 5.04559460716706e-06 -0.00115245719511303 0.00340089884923395 -5.12134943296855e-06 0.999999997826645 -6.57303681583207e-05 -0.00375924755549107 0.00115245686095954 6.57362266433286e-05 0.999999333760744 0.00152973332433044 2.53141208833231e-05 1.75305913540428e-05 -2.65479506561102e-06 -5.27653288135387e-07 2.00597528616847e-06 1.61581619498877e-05 1.75305913540428e-05 2.5057431320083e-05 -4.23688585978253e-06 1.62160712877183e-06 -1.031941720488e-06 1.89980322759799e-05 -2.65479506561102e-06 -4.23688585978253e-06 1.11357480060363e-05 2.79874501091895e-06 3.55975351203869e-06 -1.01675640051597e-07 -5.27653288135387e-07 1.62160712877183e-06 2.79874501091895e-06 2.99502026864317e-05 -1.11434683026936e-05 -1.52099585581789e-06 2.00597528616847e-06 -1.031941720488e-06 3.55975351203869e-06 -1.11434683026936e-05 3.04396833846142e-05 3.95877976566219e-06 1.61581619498877e-05 1.89980322759799e-05 -1.01675640051597e-07 -1.52099585581789e-06 3.95877976566219e-06 3.30033344418338e-05 2701 2696 0 16 35 2713 2757 0 46 20 0 0 0 0 0 11 41 0 465 0 54 52 0 0 2440 +405 372 0.999998421287217 -0.000165766895289978 0.00176916489059261 0.00500366556742494 0.000161951698548969 0.999997661806718 0.00215642128185502 0.00590511649239863 -0.00176951821720397 -0.00215613135822613 0.999996109943856 -0.00210773483666109 2.63016178794669e-05 1.07230198438486e-05 -4.71372349045126e-06 4.11430484665793e-07 5.07944936420785e-06 1.16733033987958e-05 1.07230198438486e-05 2.36049625710867e-05 -6.40853281389245e-06 2.00024057588162e-06 5.87780067449673e-06 1.42379957533418e-05 -4.71372349045126e-06 -6.40853281389245e-06 1.11696798818684e-05 3.75837721884357e-06 1.4314286771444e-06 -3.39477062826653e-06 4.11430484665793e-07 2.00024057588162e-06 3.75837721884357e-06 3.63021825125433e-05 -7.80192402275669e-06 8.26207268592814e-06 5.07944936420785e-06 5.87780067449673e-06 1.4314286771444e-06 -7.80192402275669e-06 4.43488449815863e-05 -4.56586820123209e-06 1.16733033987958e-05 1.42379957533418e-05 -3.39477062826653e-06 8.26207268592814e-06 -4.56586820123209e-06 4.18105199027597e-05 2090 2070 0 18 51 2088 2114 0 47 54 0 0 0 0 0 17 49 0 569 0 36 15 0 0 2585 +406 410 0.999998592460074 -0.000748781399667988 -0.0015014673777066 0.00462825888305841 0.000747593059116785 0.999999407032661 -0.000791857907151795 -0.00840120389871621 0.00150205941585754 0.000790734305990111 0.999998559277346 0.000733927896337543 2.05828334266372e-05 1.10729411973789e-05 -1.31366424534823e-06 1.98094320252255e-06 3.57371093381962e-07 8.45755733138683e-06 1.10729411973789e-05 2.16974674736261e-05 -3.26450187470044e-06 4.08642834815071e-06 2.72919214053844e-06 1.49658372965639e-05 -1.31366424534823e-06 -3.26450187470044e-06 1.24910727832644e-05 5.16483687017648e-06 4.0619128434363e-07 -1.73774237887543e-06 1.98094320252255e-06 4.08642834815071e-06 5.16483687017648e-06 2.80636609568804e-05 -5.2518549478279e-06 1.04736383586205e-06 3.57371093381962e-07 2.72919214053844e-06 4.0619128434363e-07 -5.2518549478279e-06 3.96334392050836e-05 3.61420963544911e-06 8.45755733138683e-06 1.49658372965639e-05 -1.73774237887543e-06 1.04736383586205e-06 3.61420963544911e-06 2.64688162415252e-05 2250 2245 0 18 17 2298 2335 0 44 16 0 0 0 0 0 18 48 0 514 0 58 57 0 0 2442 +406 409 0.999998411254223 -0.000516088800666041 -0.0017062067227438 0.0014944765283294 0.0005153359926804 0.999999769696942 -0.000441627533550994 0.000364837554907373 0.00170643424882331 0.000440747562181932 0.999998446910664 0.00228372859676408 2.16846340313296e-05 1.90703808028457e-05 -2.76047083015585e-06 2.7408679936574e-07 1.57824239588634e-06 1.66666880101408e-05 1.90703808028457e-05 3.03627434248185e-05 -4.59281710135139e-06 6.27372232019404e-06 -1.14742516095738e-06 2.41624159238978e-05 -2.76047083015585e-06 -4.59281710135139e-06 1.02682313285725e-05 3.35420843960129e-06 2.39124798546566e-06 -1.1929147936585e-06 2.7408679936574e-07 6.27372232019404e-06 3.35420843960129e-06 3.04637848783854e-05 -5.91916936528899e-06 -3.45840181604172e-06 1.57824239588634e-06 -1.14742516095738e-06 2.39124798546566e-06 -5.91916936528899e-06 2.84204858848791e-05 2.67793849905586e-07 1.66666880101408e-05 2.41624159238978e-05 -1.1929147936585e-06 -3.45840181604172e-06 2.67793849905586e-07 4.44198133206728e-05 2145 2140 0 13 23 2190 2226 0 43 29 0 0 0 0 0 20 52 0 507 0 64 63 0 0 2408 +405 373 0.999994668525386 -0.000724674700835298 0.00318398608360032 0.0116013502250907 0.00072014783495801 0.999998728687696 0.00142267708475712 -0.0107244061580517 -0.00318501301385042 -0.00142037655910572 0.999993919092777 -0.0043846799523817 2.10663758185787e-05 1.24712490258561e-05 -3.13525799735629e-06 3.28643515796582e-06 3.48228812036731e-06 1.26072165446227e-05 1.24712490258561e-05 1.85625230901819e-05 -5.8163979078494e-06 2.4559950130783e-06 3.27505993782873e-07 1.09321860699876e-05 -3.13525799735629e-06 -5.8163979078494e-06 1.1967059097809e-05 2.74152501737891e-06 1.2038695586441e-06 -1.18876998173117e-06 3.28643515796582e-06 2.4559950130783e-06 2.74152501737891e-06 4.34296942193345e-05 -2.54279826678477e-05 1.74835586673606e-06 3.48228812036731e-06 3.27505993782873e-07 1.2038695586441e-06 -2.54279826678477e-05 5.69561822306504e-05 1.72292766387408e-06 1.26072165446227e-05 1.09321860699876e-05 -1.18876998173117e-06 1.74835586673606e-06 1.72292766387408e-06 3.2068047113385e-05 2677 2652 0 18 53 2723 2752 0 47 55 0 0 0 0 0 10 40 0 544 0 56 33 0 0 2618 +405 377 0.999999034525647 -0.000797226799680538 0.00113814638941323 0.0135366497709703 0.000796213093232823 0.999999286224304 0.000890839824607351 -0.0124287113488731 -0.0011388557784144 -0.000889932757467081 0.999998955513056 0.00032753856713172 2.70254052694169e-05 1.57798061056603e-05 -5.29528673329097e-06 9.97130643702654e-07 6.78557220792949e-06 1.36923365936096e-05 1.57798061056603e-05 2.50091910548937e-05 -9.02821083676061e-06 3.20756825518308e-06 5.58057538710563e-06 1.60171047157133e-05 -5.29528673329097e-06 -9.02821083676061e-06 1.4860930473889e-05 9.5631489647468e-07 -2.81680798764867e-06 -3.72715294307698e-06 9.97130643702654e-07 3.20756825518308e-06 9.5631489647468e-07 4.74032917774518e-05 -2.18022678737236e-05 4.16575408166489e-07 6.78557220792949e-06 5.58057538710563e-06 -2.81680798764867e-06 -2.18022678737236e-05 5.26711875147434e-05 7.54782730685504e-06 1.36923365936096e-05 1.60171047157133e-05 -3.72715294307698e-06 4.16575408166489e-07 7.54782730685504e-06 3.51588484125942e-05 2173 2160 0 19 46 2233 2253 0 50 48 0 0 0 0 0 15 47 0 551 0 82 63 0 0 2537 +405 378 0.999997490459464 -0.00087924335382751 0.00206058387352934 0.0156597008469164 0.000876570759654102 0.9999987739897 0.00129755261904226 -0.0107238263583904 -0.00206172221174882 -0.00129574311521002 0.999997035171255 0.00164324068435355 2.49741711019575e-05 1.4999642634094e-05 -4.96184170195005e-06 1.75446546540574e-06 7.36994176542823e-06 1.44293145623026e-05 1.4999642634094e-05 2.5533036674149e-05 -6.66224321467864e-06 4.53166677876437e-06 2.63892771013661e-06 1.00937053594831e-05 -4.96184170195005e-06 -6.66224321467864e-06 1.34109869455793e-05 8.8893970456042e-07 1.87673683285132e-06 -2.15242716203646e-06 1.75446546540574e-06 4.53166677876437e-06 8.8893970456042e-07 4.65555578697924e-05 -1.62891740230745e-05 2.6981363570381e-06 7.36994176542823e-06 2.63892771013661e-06 1.87673683285132e-06 -1.62891740230745e-05 4.09204837648356e-05 4.94522934082326e-06 1.44293145623026e-05 1.00937053594831e-05 -2.15242716203646e-06 2.6981363570381e-06 4.94522934082326e-06 3.31205015787415e-05 2362 2337 0 20 47 2380 2395 0 47 48 0 0 0 0 0 10 41 0 566 0 62 41 0 0 2632 +406 373 0.999999388700226 -0.000349780240466576 0.00104892943423283 0.00929555084865902 0.000348514013691014 0.999999210722291 0.00120710098032349 -0.00913660573050433 -0.00104935082640737 -0.00120673467581573 0.999998721326315 -0.00276127208748198 2.93314062143534e-05 1.19841429481285e-05 -3.43366440521921e-06 6.2862669968302e-06 -3.55027444015122e-08 1.76991146180859e-05 1.19841429481285e-05 1.99423999404688e-05 -6.30283064042925e-06 3.28538719486413e-06 6.14672697674309e-06 1.18275005345431e-05 -3.43366440521921e-06 -6.30283064042925e-06 1.10046119879191e-05 3.07169596472733e-06 1.98483619549486e-06 -4.27085997266675e-07 6.2862669968302e-06 3.28538719486413e-06 3.07169596472733e-06 4.24579117392711e-05 -2.2686313734429e-05 8.97642860666075e-06 -3.55027444015122e-08 6.14672697674309e-06 1.98483619549486e-06 -2.2686313734429e-05 5.47294839790253e-05 -1.57332646871669e-06 1.76991146180859e-05 1.18275005345431e-05 -4.27085997266675e-07 8.97642860666075e-06 -1.57332646871669e-06 4.61038957370477e-05 2943 2922 0 24 53 2940 2967 0 48 56 0 0 0 0 0 15 44 0 572 0 50 27 0 0 2602 +406 374 0.999987009914518 -0.000517037039277 0.00507076669956647 0.0182546420195904 0.000501020907627667 0.999994883936586 0.00315928452414121 -0.0146563524546203 -0.00507237422431907 -0.00315670292463099 0.999982152963929 -0.00283005186711209 3.30487375693251e-05 1.4516195348006e-05 -6.95345621941658e-06 4.45336913476739e-06 5.51743535174638e-06 1.1482762181638e-05 1.4516195348006e-05 2.62017049355397e-05 -6.36483385737626e-06 4.42205302450989e-06 4.09788997902659e-06 1.04697319428139e-05 -6.95345621941658e-06 -6.36483385737626e-06 1.31337893564689e-05 6.52821909810414e-07 -1.15858360833469e-06 -2.09557289634278e-06 4.45336913476739e-06 4.42205302450989e-06 6.52821909810414e-07 3.91738053744786e-05 -1.30912183713621e-05 5.14007973792504e-06 5.51743535174638e-06 4.09788997902659e-06 -1.15858360833469e-06 -1.30912183713621e-05 5.55649272981888e-05 1.35172902919263e-06 1.1482762181638e-05 1.04697319428139e-05 -2.09557289634278e-06 5.14007973792504e-06 1.35172902919263e-06 3.43314233907317e-05 1984 1964 0 27 47 2015 2031 0 57 47 0 0 0 0 0 15 46 0 590 0 49 29 0 0 2570 +405 375 0.999988695856265 -0.00061317371190582 0.00471510102606167 0.0152872242346805 0.000607624972434381 0.999999121383562 0.00117814430194763 -0.0122907513128777 -0.00471581929041119 -0.00117526597090411 0.999988189829419 -0.00355955185244841 3.51383375625619e-05 1.36235395225514e-05 -4.80577746460908e-06 5.95916977457069e-06 9.07176124097398e-07 1.50989745728689e-05 1.36235395225514e-05 2.61904903777733e-05 -7.76423623189132e-06 2.06943850695121e-06 5.77239321101838e-06 1.50375519779734e-05 -4.80577746460908e-06 -7.76423623189132e-06 1.33862089487672e-05 2.8234062913011e-06 4.7559961746666e-07 -1.86800449316855e-06 5.95916977457069e-06 2.06943850695121e-06 2.8234062913011e-06 3.54780873369957e-05 -1.12811768435013e-05 4.83064681961678e-06 9.07176124097398e-07 5.77239321101838e-06 4.7559961746666e-07 -1.12811768435013e-05 4.99012169115077e-05 3.93868636480606e-06 1.50989745728689e-05 1.50375519779734e-05 -1.86800449316855e-06 4.83064681961678e-06 3.93868636480606e-06 3.23076262055225e-05 1818 1791 0 15 53 1865 1895 0 52 57 0 0 0 0 0 17 49 0 553 0 55 32 0 0 2424 +406 377 0.999993584400112 -0.000470678178325668 0.00355100276940341 0.0150834100501629 0.000462760124067893 0.999997405803726 0.00223030017837177 -0.0124061488236003 -0.00355204331103033 -0.00222864260717606 0.999991208031574 -0.000540855351432318 3.40470927303542e-05 1.47410439781027e-05 -9.20878291747619e-06 3.14254763398512e-06 6.54256513983239e-06 1.74569104739735e-05 1.47410439781027e-05 2.37328030405402e-05 -8.34218978663745e-06 6.57775927520995e-06 6.33171190256956e-06 1.38355845762198e-05 -9.20878291747619e-06 -8.34218978663745e-06 1.4536708377713e-05 -1.62180761843358e-06 -1.76668171422361e-06 -5.49034665240417e-06 3.14254763398512e-06 6.57775927520995e-06 -1.62180761843358e-06 4.46133504825207e-05 -1.20132521076275e-05 8.95844401499967e-06 6.54256513983239e-06 6.33171190256956e-06 -1.76668171422361e-06 -1.20132521076275e-05 4.25240955362113e-05 5.63890385477867e-06 1.74569104739735e-05 1.38355845762198e-05 -5.49034665240417e-06 8.95844401499967e-06 5.63890385477867e-06 4.05879459679377e-05 2549 2528 0 18 49 2579 2592 0 48 52 0 0 0 0 0 13 44 0 567 0 51 32 0 0 2546 +406 408 0.999999604562329 5.63179930976833e-05 -0.00088752660224474 -0.00289133544329196 -5.67999880533519e-05 0.999999850929363 -0.000543060781449975 -0.000452777638153688 0.000887495885847243 0.000543110978203689 0.999999458690612 0.0038532524226241 2.84353021772247e-05 2.06601790492335e-05 -2.00657298056633e-06 2.90223147918846e-06 -1.91059867506546e-06 2.17100618269658e-05 2.06601790492335e-05 3.3676140114348e-05 -3.03472750394568e-06 8.8836263692795e-06 -1.57318818625649e-06 2.92339983525443e-05 -2.00657298056633e-06 -3.03472750394568e-06 1.02194080873833e-05 3.36843972735508e-06 3.60525629034897e-06 -1.06598879620391e-07 2.90223147918846e-06 8.8836263692795e-06 3.36843972735508e-06 2.65179127050402e-05 -4.63225173247309e-07 6.99985425339307e-06 -1.91059867506546e-06 -1.57318818625649e-06 3.60525629034897e-06 -4.63225173247309e-07 2.79945955025444e-05 -2.92745486545453e-06 2.17100618269658e-05 2.92339983525443e-05 -1.06598879620391e-07 6.99985425339307e-06 -2.92745486545453e-06 4.38557189074925e-05 2631 2634 0 16 27 2645 2686 0 43 32 0 0 0 0 0 15 43 0 489 0 56 54 0 0 2462 +406 378 0.999998207604737 -0.000344517056547735 -0.0018617452324279 0.0124570018871216 0.000345481416415914 0.999999806319679 0.000517690250154127 -0.0108916394870528 0.0018615665187233 -0.00051833252062848 0.999998132949004 0.00548452546233529 2.68581677757853e-05 1.68877071296364e-05 -6.60532083858756e-06 4.57331617271487e-06 8.11751877114602e-06 1.25372797947897e-05 1.68877071296364e-05 2.72110114467685e-05 -9.96599809205194e-06 6.27694727816533e-06 6.27496537232503e-06 9.61024105119463e-06 -6.60532083858756e-06 -9.96599809205194e-06 1.53568428434742e-05 -2.79764851683715e-07 -3.80331878186002e-06 -3.74263721414531e-06 4.57331617271487e-06 6.27694727816533e-06 -2.79764851683715e-07 4.87650613320023e-05 -1.92594745827126e-05 4.14919625586635e-06 8.11751877114602e-06 6.27496537232503e-06 -3.80331878186002e-06 -1.92594745827126e-05 5.4997063906951e-05 1.24948003720426e-05 1.25372797947897e-05 9.61024105119463e-06 -3.74263721414531e-06 4.14919625586635e-06 1.24948003720426e-05 4.17651933825196e-05 2134 2113 0 23 47 2184 2196 0 43 51 0 0 0 0 0 9 40 0 600 0 77 56 0 0 2652 +407 410 0.999999913009693 -0.000403936314767562 0.000104000286060055 0.00302704588772011 0.000403967429738755 0.999999873604544 -0.000299334615673222 -0.000926219333454635 -0.000103879360793354 0.000299376602362264 0.999999949791363 0.00161720316160741 3.72531680608815e-05 2.06978396084514e-05 -2.38233096750535e-06 2.40879728956002e-06 -3.18684131393353e-06 3.00418219361475e-05 2.06978396084514e-05 2.62880217952481e-05 -2.08091953316581e-06 2.60258645080226e-06 -2.078993165105e-06 2.42622862159999e-05 -2.38233096750535e-06 -2.08091953316581e-06 1.08145780427335e-05 5.25042429719396e-06 1.34432067866803e-06 -1.2833706166974e-06 2.40879728956002e-06 2.60258645080226e-06 5.25042429719396e-06 2.23831443195743e-05 -7.25549381028591e-06 3.7607960693991e-06 -3.18684131393353e-06 -2.078993165105e-06 1.34432067866803e-06 -7.25549381028591e-06 3.44632773451889e-05 -1.56019104161739e-06 3.00418219361475e-05 2.42622862159999e-05 -1.2833706166974e-06 3.7607960693991e-06 -1.56019104161739e-06 5.64585582348287e-05 2858 2855 0 17 17 2856 2897 0 47 19 0 0 0 0 0 22 51 0 505 0 34 33 0 0 2395 +406 375 0.99999995140179 -0.000126211880722896 -0.000285073639136016 0.0104661618977536 0.000125935736350325 0.999999523085811 -0.000968487656110138 -0.0109047356181983 0.000285195737828887 0.000968451708084713 0.99999949038221 0.0012690981345683 2.68694559425523e-05 9.27056712401468e-06 -6.78291282098088e-06 5.6046776882973e-06 6.01603426088288e-06 1.33068350776566e-05 9.27056712401468e-06 1.88927236694672e-05 -8.70385339692306e-06 2.84117315254615e-06 1.03223338209227e-05 1.3074529159455e-05 -6.78291282098088e-06 -8.70385339692306e-06 1.29991502068093e-05 3.80060747547045e-07 -2.50805814143419e-06 -5.09962913236062e-06 5.6046776882973e-06 2.84117315254615e-06 3.80060747547045e-07 3.59375376194568e-05 -1.18018019516728e-05 8.60121099590069e-06 6.01603426088288e-06 1.03223338209227e-05 -2.50805814143419e-06 -1.18018019516728e-05 5.57544448180272e-05 1.36690788429176e-05 1.33068350776566e-05 1.3074529159455e-05 -5.09962913236062e-06 8.60121099590069e-06 1.36690788429176e-05 3.96284726450508e-05 2926 2902 0 24 53 2923 2950 0 50 56 0 0 0 0 0 18 50 0 588 0 50 27 0 0 2438 +406 372 0.999999981567394 -0.000185665445300882 4.89239583875398e-05 0.00170233858544045 0.000185626102891005 0.99999966041871 0.000802935498950431 0.0068536992770861 -4.90730191508394e-05 -0.000802926402586504 0.999999676450463 0.000619408496499049 2.9960029907734e-05 1.68844100936038e-05 -7.87176632816169e-06 9.83430548479776e-06 4.35997618115742e-06 1.73893959753045e-05 1.68844100936038e-05 2.62363522231749e-05 -9.31194948033993e-06 8.86839718212602e-06 6.97988504498343e-06 1.4349590521802e-05 -7.87176632816169e-06 -9.31194948033993e-06 1.46923982870325e-05 -1.48654991258695e-06 -5.89327427132251e-07 -5.34749375224987e-06 9.83430548479776e-06 8.86839718212602e-06 -1.48654991258695e-06 4.15952473510088e-05 -1.02749778813326e-06 8.81806486505702e-06 4.35997618115742e-06 6.97988504498343e-06 -5.89327427132251e-07 -1.02749778813326e-06 4.20229027972139e-05 -1.89661912012612e-06 1.73893959753045e-05 1.4349590521802e-05 -5.34749375224987e-06 8.81806486505702e-06 -1.89661912012612e-06 4.42024190402944e-05 2332 2317 0 23 55 2339 2359 0 43 57 0 0 0 0 0 13 45 0 599 0 71 50 0 0 2610 +407 411 0.99999929139403 -0.000622740865607962 -0.00101459610325826 0.00461090449136712 0.000624716379172923 0.999997907624414 0.00194794153914258 0.00334987486531181 0.0010133809175419 -0.00194857399362352 0.999997588056345 -0.00143099017316387 2.90001866435204e-05 1.50678333086944e-05 -3.00291498829083e-06 1.64878659487405e-06 1.55011426404851e-06 1.65851037725701e-05 1.50678333086944e-05 2.80009181531205e-05 -4.80674224336288e-06 8.18898412267797e-06 5.63430688619813e-06 2.1215323822941e-05 -3.00291498829083e-06 -4.80674224336288e-06 1.14517531037086e-05 4.53118754705364e-06 2.58690462760463e-06 -1.82136460910056e-07 1.64878659487405e-06 8.18898412267797e-06 4.53118754705364e-06 3.28915793377419e-05 -4.3417001628377e-06 5.07753141687548e-06 1.55011426404851e-06 5.63430688619813e-06 2.58690462760463e-06 -4.3417001628377e-06 4.79464342883279e-05 1.06610362038896e-05 1.65851037725701e-05 2.1215323822941e-05 -1.82136460910056e-07 5.07753141687548e-06 1.06610362038896e-05 4.56247209625897e-05 2035 2031 0 14 34 2058 2102 0 48 28 0 0 0 0 0 21 53 0 536 0 34 32 0 0 2473 +408 410 0.999999669747973 0.000218130431955839 -0.000782894027866255 0.00509991816498185 -0.000218102354364312 0.999999975569514 3.59490432136055e-05 -0.00397408747695016 0.000782901850320099 -3.57782803106658e-05 0.999999692892257 -6.59381735500467e-05 4.09555019779863e-05 3.13477075927303e-05 -1.31344327430774e-06 1.20316961425104e-06 5.01964673360289e-07 3.19309813511137e-05 3.13477075927303e-05 4.20566415632381e-05 -1.80421678837248e-06 6.08463084617427e-06 9.28825842055052e-08 3.92268170820804e-05 -1.31344327430774e-06 -1.80421678837248e-06 9.53711030047692e-06 2.9585144934714e-06 3.80826492987222e-06 1.43541849611387e-06 1.20316961425104e-06 6.08463084617427e-06 2.9585144934714e-06 2.77688016613544e-05 -8.34347421644906e-06 9.27887213966292e-07 5.01964673360289e-07 9.28825842055052e-08 3.80826492987222e-06 -8.34347421644906e-06 2.75908335270184e-05 3.04871226385678e-06 3.19309813511137e-05 3.92268170820804e-05 1.43541849611387e-06 9.27887213966292e-07 3.04871226385678e-06 6.5166248860731e-05 2443 2444 0 17 25 2463 2499 0 51 23 0 0 0 0 0 15 45 0 505 0 41 40 0 0 2418 +406 376 0.999997050381374 -0.00036509873944922 -0.00240123540345977 0.00930101120902805 0.000361976124506973 0.999999088541871 -0.00130072622494727 -0.00796291913347987 0.00240170810833934 0.0012998531984156 0.99999627108296 0.00445567432604013 3.06159565778235e-05 1.5992546159255e-05 -6.2496214061987e-06 6.0877838800201e-06 5.16198523684704e-06 1.31987851113934e-05 1.5992546159255e-05 2.78974264810836e-05 -6.80513986079327e-06 5.43247735532194e-06 2.59346574579335e-06 1.44301088878568e-05 -6.2496214061987e-06 -6.80513986079327e-06 1.32647706671851e-05 1.45604080350042e-06 6.57185476182976e-07 -1.48505530140024e-06 6.0877838800201e-06 5.43247735532194e-06 1.45604080350042e-06 4.86826246698442e-05 -1.98200118022002e-05 4.87604078777709e-06 5.16198523684704e-06 2.59346574579335e-06 6.57185476182976e-07 -1.98200118022002e-05 5.38553507143931e-05 -9.17042928767313e-08 1.31987851113934e-05 1.44301088878568e-05 -1.48505530140024e-06 4.87604078777709e-06 -9.17042928767313e-08 3.70173084020906e-05 2022 2003 0 25 51 2032 2058 0 54 51 0 0 0 0 0 16 47 0 577 0 69 51 0 0 2582 +409 412 0.999998064720166 -0.000732353935727188 0.00182598292331216 0.00309632603582577 0.000731024299523051 0.999999467272995 0.000728736714355473 -0.00136216555272101 -0.00182651564376261 -0.00072740046615855 0.999998067362715 0.000303742930982394 3.09232423767693e-05 1.74075815765275e-05 -5.50413424890333e-06 5.11784144802064e-06 4.89812163514981e-06 1.86746242927499e-05 1.74075815765275e-05 2.56757996733232e-05 -6.32636647805778e-06 5.76681704707334e-06 6.86119126169594e-06 1.95594471824251e-05 -5.50413424890333e-06 -6.32636647805778e-06 1.12739255177529e-05 6.33634273322747e-07 2.48194494360291e-06 -2.81405155447022e-06 5.11784144802064e-06 5.76681704707334e-06 6.33634273322747e-07 2.67284456054622e-05 -7.1554583406878e-06 2.7357955512181e-06 4.89812163514981e-06 6.86119126169594e-06 2.48194494360291e-06 -7.1554583406878e-06 3.48759475460036e-05 7.97358719754375e-06 1.86746242927499e-05 1.95594471824251e-05 -2.81405155447022e-06 2.7357955512181e-06 7.97358719754375e-06 4.0480600245364e-05 2585 2580 0 11 31 2582 2614 0 44 30 0 0 0 0 0 18 50 0 562 0 24 23 0 0 2374 +410 412 0.999998808298951 -0.000343214349928054 0.00150519254185181 0.00148933322457037 0.000337170459123193 0.999991887918972 0.004013777812905 0.00172877701797867 -0.00150655791775076 -0.00401326552322136 0.99999081194933 0.000543998944791984 4.96098671281162e-05 2.48419506522607e-05 -4.99168885542037e-06 5.52267807344956e-06 2.55795172826347e-06 2.91771703720573e-05 2.48419506522607e-05 3.90320266019989e-05 -7.08123039239552e-06 1.26052929068254e-05 7.4318279945188e-06 3.03683596551194e-05 -4.99168885542037e-06 -7.08123039239552e-06 1.19747514679204e-05 -1.0973598208359e-07 2.37823511196451e-06 -2.04623912128713e-06 5.52267807344956e-06 1.26052929068254e-05 -1.0973598208359e-07 3.56198203750372e-05 -8.3357830877267e-06 1.14888490101109e-05 2.55795172826347e-06 7.4318279945188e-06 2.37823511196451e-06 -8.3357830877267e-06 3.70622152368847e-05 2.60106651819341e-08 2.91771703720573e-05 3.03683596551194e-05 -2.04623912128713e-06 1.14888490101109e-05 2.60106651819341e-08 5.54706943129207e-05 2643 2639 0 11 23 2646 2690 0 49 22 0 0 0 0 0 21 53 0 571 0 22 21 0 0 2406 +407 409 0.999999970632564 -0.000198139917420573 0.000139554447242426 0.00209461543761496 0.000198073305130966 0.999999866536275 0.000477173342282796 0.00132459653424928 -0.000139648975703605 -0.000477145686258827 0.999999876415071 0.000597994737160423 1.60877756664982e-05 1.20976892460473e-05 -1.37990481785334e-06 -5.2546430613974e-07 1.69502233844507e-06 1.27295899379696e-05 1.20976892460473e-05 1.96033560244934e-05 -2.80661273398063e-06 3.96430798968724e-06 -9.35009187499652e-07 1.70118474158816e-05 -1.37990481785334e-06 -2.80661273398063e-06 9.97123517691974e-06 4.70279577830921e-06 2.43796539486589e-06 2.8124433651148e-07 -5.2546430613974e-07 3.96430798968724e-06 4.70279577830921e-06 2.57376442679734e-05 -3.26757900024401e-06 -1.37123329591643e-08 1.69502233844507e-06 -9.35009187499652e-07 2.43796539486589e-06 -3.26757900024401e-06 2.36979804252834e-05 -1.11515337856919e-06 1.27295899379696e-05 1.70118474158816e-05 2.8124433651148e-07 -1.37123329591643e-08 -1.11515337856919e-06 3.4728627518694e-05 2830 2825 0 11 20 2835 2874 0 44 18 0 0 0 0 0 19 50 0 502 0 30 28 0 0 2418 +410 414 0.999998318971092 -0.000308229642195061 0.00180749812689703 0.000300287270017648 0.000306290310430845 0.999999377304219 0.00107311575316221 0.00176799475653231 -0.0018078277674602 -0.00107256033006121 0.99999779068411 3.67644179917901e-05 3.12493699128418e-05 1.90429398584719e-05 -8.15320754237625e-06 3.55880799393579e-06 1.09408317180528e-05 1.81632091736879e-05 1.90429398584719e-05 2.51464921767782e-05 -8.38295784955808e-06 5.38075699442275e-06 1.00359633214866e-05 2.18941794594317e-05 -8.15320754237625e-06 -8.38295784955808e-06 1.22998509119856e-05 1.70111470122464e-07 -1.85044713918372e-06 -4.92345569431976e-06 3.55880799393579e-06 5.38075699442275e-06 1.70111470122464e-07 2.4143336824686e-05 -1.37766090215756e-06 5.98594072468825e-06 1.09408317180528e-05 1.00359633214866e-05 -1.85044713918372e-06 -1.37766090215756e-06 3.71396151784041e-05 1.38642050467285e-05 1.81632091736879e-05 2.18941794594317e-05 -4.92345569431976e-06 5.98594072468825e-06 1.38642050467285e-05 4.2518943231171e-05 2771 2767 0 16 47 2772 2796 0 38 42 0 0 0 0 0 12 43 0 598 0 51 64 0 0 2532 +409 411 0.999999401488772 -0.00099130630860912 -0.000462962093203268 0.00284606540954484 0.000992605649993986 0.999995545703166 0.00281483709125165 -0.000915022035735002 0.000460169665266417 -0.0028152949453295 0.999995931170847 0.000211576979220111 3.48904298611551e-05 2.17325837212173e-05 -3.05647576083276e-06 1.91161154398616e-06 5.2661855410506e-06 2.35102501928075e-05 2.17325837212173e-05 3.23729066990358e-05 -4.40723725719764e-06 5.48653769815212e-06 4.25185671140717e-06 2.79051846571161e-05 -3.05647576083276e-06 -4.40723725719764e-06 1.47352864654149e-05 3.93911708562774e-06 1.54248948716832e-06 3.41750867906044e-07 1.91161154398616e-06 5.48653769815212e-06 3.93911708562774e-06 2.64475871818224e-05 -9.8768864736243e-06 4.51884731784537e-06 5.2661855410506e-06 4.25185671140717e-06 1.54248948716832e-06 -9.8768864736243e-06 4.34486931165519e-05 9.0436816702065e-06 2.35102501928075e-05 2.79051846571161e-05 3.41750867906044e-07 4.51884731784537e-06 9.0436816702065e-06 5.09156275941663e-05 2551 2547 0 13 16 2542 2575 0 48 15 0 0 0 0 0 10 42 0 531 0 30 30 0 0 2426 +411 415 0.999997060935951 4.4849590826606e-05 -0.00242406847536658 -0.00370984773470307 -4.65719072739659e-05 0.999999746542528 -0.000710454739421102 0.00275789356899029 0.00242403599736395 0.00071056554484138 0.999996809567956 0.00147871369269634 5.70175776442152e-05 4.55327459020581e-05 -8.39299675987339e-06 1.65596875298284e-05 5.0036826921036e-06 4.74507930636619e-05 4.55327459020581e-05 5.42568919732862e-05 -1.00826129501526e-05 1.94422868902895e-05 3.65437559433903e-06 5.59432542399883e-05 -8.39299675987339e-06 -1.00826129501526e-05 1.31322738043289e-05 6.47395308595263e-07 -4.16994553854219e-07 -4.87707074720066e-06 1.65596875298284e-05 1.94422868902895e-05 6.47395308595263e-07 3.37344052669443e-05 -3.90522053390049e-06 2.44987450654313e-05 5.0036826921036e-06 3.65437559433903e-06 -4.16994553854219e-07 -3.90522053390049e-06 3.33756162822667e-05 2.2273451999253e-06 4.74507930636619e-05 5.59432542399883e-05 -4.87707074720066e-06 2.44987450654313e-05 2.2273451999253e-06 8.38157260644736e-05 2824 2821 0 12 51 2933 2981 0 46 53 0 0 0 0 0 28 59 0 583 0 27 25 0 0 2391 +408 412 0.99999961549101 -0.000749759675050905 -0.00045483872170014 0.00679616279796785 0.000749888936525253 0.999999678480259 0.000284087945203079 -0.00672911776214084 0.000454625577775031 -0.000284428914494017 0.999999856207878 -0.00375865533551046 3.74665205498446e-05 2.64781300719912e-05 -4.0879389057799e-06 6.46251448614274e-06 2.41469762610799e-06 2.96733575301994e-05 2.64781300719912e-05 3.14745189045511e-05 -6.27402333286156e-06 7.88931056308357e-06 2.3430760480932e-06 2.76782649093556e-05 -4.0879389057799e-06 -6.27402333286156e-06 1.33017886995046e-05 3.48110366012318e-06 -2.21258841488501e-06 -4.70427547691303e-06 6.46251448614274e-06 7.88931056308357e-06 3.48110366012318e-06 3.62787442128641e-05 -1.85813833162485e-05 5.52303695432017e-07 2.41469762610799e-06 2.3430760480932e-06 -2.21258841488501e-06 -1.85813833162485e-05 4.38605674683856e-05 6.5338481260053e-06 2.96733575301994e-05 2.76782649093556e-05 -4.70427547691303e-06 5.52303695432017e-07 6.5338481260053e-06 4.94707331201631e-05 1503 1502 0 16 26 1501 1532 0 48 23 0 0 0 0 0 7 39 0 564 0 56 55 0 0 2374 +408 411 0.999999426574959 -0.00104413058470153 -0.000237993855678718 0.0079419429988701 0.00104407400873847 0.999999426699008 -0.000237720675517817 -0.00985570083031292 0.000238241930664529 0.000237472056003876 0.999999943423901 -0.00219377108141799 2.23887845175585e-05 1.28589390680141e-05 -2.19145693400585e-06 2.94617770500911e-06 -1.98917357983622e-06 1.13387047082535e-05 1.28589390680141e-05 1.99245783690422e-05 -3.95110806712455e-06 3.86771858731554e-06 -2.5484963946621e-06 1.59174210245191e-05 -2.19145693400585e-06 -3.95110806712455e-06 1.16046139548378e-05 3.78254908866292e-06 3.65334663668688e-06 1.23176281144218e-06 2.94617770500911e-06 3.86771858731554e-06 3.78254908866292e-06 2.36769141932067e-05 -6.00394892672335e-06 3.07493334004104e-06 -1.98917357983622e-06 -2.5484963946621e-06 3.65334663668688e-06 -6.00394892672335e-06 2.92861050338265e-05 -4.93202895586391e-07 1.13387047082535e-05 1.59174210245191e-05 1.23176281144218e-06 3.07493334004104e-06 -4.93202895586391e-07 3.01680423435204e-05 2065 2066 0 23 19 2059 2094 0 54 17 0 0 0 0 0 14 46 0 541 0 54 53 0 0 2483 +410 413 0.999997918138134 8.71510410301056e-05 -0.00203865742415665 -0.0020138431562235 -8.46582161462081e-05 0.999999248757087 0.00122283206068262 -0.000434900404838586 0.0020387624637168 -0.00122265692581433 0.999997174274837 -0.00297637744094997 3.14638565540656e-05 1.94484186393591e-05 -4.91794554059095e-06 3.49765063727937e-06 7.28640087091567e-06 2.05772008670683e-05 1.94484186393591e-05 2.6266697409355e-05 -5.81619658914213e-06 6.11654782476851e-06 7.84017051824655e-06 2.47566116542843e-05 -4.91794554059095e-06 -5.81619658914213e-06 9.99373308012399e-06 4.50361328225256e-06 1.14257966996095e-06 -1.87150075726873e-06 3.49765063727937e-06 6.11654782476851e-06 4.50361328225256e-06 2.21724742513372e-05 3.60065001238335e-06 1.01256905330728e-05 7.28640087091567e-06 7.84017051824655e-06 1.14257966996095e-06 3.60065001238335e-06 2.88768099312331e-05 9.14339681840886e-06 2.05772008670683e-05 2.47566116542843e-05 -1.87150075726873e-06 1.01256905330728e-05 9.14339681840886e-06 4.65958975685642e-05 2748 2752 0 21 44 2747 2785 0 53 38 0 0 0 0 0 15 48 0 595 0 28 30 0 0 2488 +412 416 0.999999213545749 0.00110506293986188 0.000593079912837311 -0.00467466805310977 -0.00110525260092005 0.999999338149584 0.000319557634356013 0.00767339892173743 -0.000592726389008247 -0.00032021288615477 0.999999773069542 0.00110340505965126 3.55556679792442e-05 2.18504064226245e-05 -1.15831363210412e-05 9.50329420355233e-06 8.13078037408833e-06 1.88608011938845e-05 2.18504064226245e-05 3.62980922149277e-05 -1.31286627125947e-05 1.34982544617498e-05 1.43620070729104e-05 2.71137943653502e-05 -1.15831363210412e-05 -1.31286627125947e-05 1.67236271147631e-05 -3.9370197774092e-06 -4.80597401164852e-06 -8.73205425074922e-06 9.50329420355233e-06 1.34982544617498e-05 -3.9370197774092e-06 3.54555024099551e-05 -5.92780123764014e-06 8.29109421616976e-06 8.13078037408833e-06 1.43620070729104e-05 -4.80597401164852e-06 -5.92780123764014e-06 4.58606907881842e-05 1.58880631178068e-05 1.88608011938845e-05 2.71137943653502e-05 -8.73205425074922e-06 8.29109421616976e-06 1.58880631178068e-05 4.60503563919357e-05 2119 2119 0 18 42 2178 2215 0 45 40 0 0 0 0 0 12 43 0 613 0 58 62 0 0 2413 +412 415 0.999998054231386 2.59795363094287e-05 -0.00197252592036693 -0.00192301167816404 -2.58403709186532e-05 0.999999997175558 7.05773218709226e-05 0.00111455432106394 0.00197252774836174 -7.05262137423558e-05 0.99999805207827 0.0034531175341809 3.26323564005465e-05 2.72733548116562e-05 -8.43771253042343e-06 7.08696874924451e-06 8.95631427043985e-06 2.67147410500718e-05 2.72733548116562e-05 4.89543642572646e-05 -1.15157523384897e-05 1.49176402057692e-05 1.08496205962448e-05 4.27872233699746e-05 -8.43771253042343e-06 -1.15157523384897e-05 1.28468327000286e-05 -6.63921337731687e-08 -9.96182449155362e-07 -6.0880574629729e-06 7.08696874924451e-06 1.49176402057692e-05 -6.63921337731687e-08 2.99990693420718e-05 -1.91476321168569e-06 1.27273235691877e-05 8.95631427043985e-06 1.08496205962448e-05 -9.96182449155362e-07 -1.91476321168569e-06 3.23912913480206e-05 1.25179110065715e-05 2.67147410500718e-05 4.27872233699746e-05 -6.0880574629729e-06 1.27273235691877e-05 1.25179110065715e-05 6.77677706744408e-05 2101 2105 0 24 27 2206 2253 0 47 26 0 0 0 0 0 13 45 0 588 0 26 27 0 0 2437 +409 413 0.999999915008062 -0.000263948121524645 0.000316725841862297 0.00263669225911193 0.000264118148752829 0.999999820986716 -0.00053690608095298 -0.00348777997455466 -0.000316584069812661 0.000536989688363306 0.999999805708282 0.000651209596065273 2.59148443738448e-05 1.90269581967975e-05 -6.18179443977218e-06 7.78988822549639e-06 6.41484264148764e-06 2.25229483277029e-05 1.90269581967975e-05 2.28241401722066e-05 -7.59516397783397e-06 7.22422514422623e-06 8.12303414433163e-06 2.56098898639451e-05 -6.18179443977218e-06 -7.59516397783397e-06 1.06379437966208e-05 9.24303773667494e-07 -1.4871342575987e-06 -6.40198560507617e-06 7.78988822549639e-06 7.22422514422623e-06 9.24303773667494e-07 2.33133427633532e-05 -4.6982815829551e-08 8.70449930709692e-06 6.41484264148764e-06 8.12303414433163e-06 -1.4871342575987e-06 -4.6982815829551e-08 3.26360075455287e-05 1.22502938761682e-05 2.25229483277029e-05 2.56098898639451e-05 -6.40198560507617e-06 8.70449930709692e-06 1.22502938761682e-05 5.06875645417693e-05 2853 2847 0 17 18 2835 2868 0 46 17 0 0 0 0 0 17 50 0 586 0 29 29 0 0 2384 +413 415 0.999998465813888 5.14899009254613e-05 0.00175091937555067 0.00207527795600686 -5.34019183185336e-05 0.999999402365464 0.00109197845625105 0.00225280744157205 -0.00175086210327825 -0.00109207028340634 0.999997870929929 0.000225128255324213 2.8949006776741e-05 2.06290696561647e-05 -7.82934870115344e-06 4.51503145123943e-06 5.9701944179726e-06 1.53110955545366e-05 2.06290696561647e-05 3.53875932693067e-05 -9.9193783026047e-06 1.08897633362989e-05 7.30710154225869e-06 2.97795254947383e-05 -7.82934870115344e-06 -9.9193783026047e-06 1.24912125451176e-05 4.74700694219816e-07 -2.2071375907591e-06 -4.10344438435031e-06 4.51503145123943e-06 1.08897633362989e-05 4.74700694219816e-07 3.00857459773772e-05 -1.11846109020831e-06 1.75565174542398e-05 5.9701944179726e-06 7.30710154225869e-06 -2.2071375907591e-06 -1.11846109020831e-06 3.3539415493286e-05 3.62315681639223e-06 1.53110955545366e-05 2.97795254947383e-05 -4.10344438435031e-06 1.75565174542398e-05 3.62315681639223e-06 4.98914305452244e-05 2296 2292 0 10 52 2400 2451 0 53 52 0 0 0 0 0 18 50 0 589 0 24 22 0 0 2404 +411 414 0.999997031689646 -0.000934420127446498 0.00225021575004834 0.000282311758699853 0.00092856562817645 0.999996185258129 0.0026013909863114 0.00105801114005113 -0.00225263795815307 -0.00259929379157413 0.999994084629511 -0.00425558378616063 2.64790875316732e-05 2.10238423375679e-05 -9.53095722662057e-06 5.10894661193347e-06 1.07616377934533e-05 1.71032772907797e-05 2.10238423375679e-05 2.79908413039183e-05 -1.06047279004019e-05 7.78236696368801e-06 1.09059899360489e-05 1.96029582542605e-05 -9.53095722662057e-06 -1.06047279004019e-05 1.48352413734383e-05 -1.44583042306648e-06 -3.77247297695183e-06 -5.31926655731151e-06 5.10894661193347e-06 7.78236696368801e-06 -1.44583042306648e-06 2.67858468151945e-05 -2.97398031838331e-06 4.42219568469394e-06 1.07616377934533e-05 1.09059899360489e-05 -3.77247297695183e-06 -2.97398031838331e-06 3.88442204486537e-05 1.11486025052523e-05 1.71032772907797e-05 1.96029582542605e-05 -5.31926655731151e-06 4.42219568469394e-06 1.11486025052523e-05 3.56436155350054e-05 2221 2217 0 17 26 2319 2362 0 44 23 0 0 0 0 0 17 48 0 600 0 37 36 0 0 2543 +411 413 0.999999985722797 0.000109300995709603 -0.000128870855712936 -0.000817566401065944 -0.000109405530802132 0.999999664802754 -0.00081143379810685 0.000690275061353127 0.000128782121993695 0.000811447885706219 0.99999966248369 -0.00450352212083281 3.70093981069072e-05 2.65063058062591e-05 -6.31011546044893e-06 6.0488900109603e-06 1.11198475301725e-05 2.72749786045353e-05 2.65063058062591e-05 3.17749657861624e-05 -7.70840587520322e-06 6.47773291780163e-06 1.24413771782953e-05 3.30358991444694e-05 -6.31011546044893e-06 -7.70840587520322e-06 1.14990911333149e-05 -7.27720259595575e-07 -1.598844966239e-07 -3.16223152088871e-06 6.0488900109603e-06 6.47773291780163e-06 -7.27720259595575e-07 2.89253724393597e-05 -3.7235382957416e-06 7.30769836392739e-06 1.11198475301725e-05 1.24413771782953e-05 -1.598844966239e-07 -3.7235382957416e-06 3.41571369612673e-05 1.26576400891274e-05 2.72749786045353e-05 3.30358991444694e-05 -3.16223152088871e-06 7.30769836392739e-06 1.26576400891274e-05 6.05602951711876e-05 2658 2653 0 13 23 2659 2697 0 49 21 0 0 0 0 0 21 53 0 608 0 49 47 0 0 2376 +413 417 0.999993926240248 0.000284216614308011 0.00347371609803385 0.00126947403384047 -0.000290319176740154 0.999998415378308 0.00175640418123915 0.00654004603243574 -0.00347321139425822 -0.00175740199965994 0.999992424141714 0.000490517194468233 4.05190078385268e-05 2.21547144786696e-05 -8.42091556481525e-06 2.67104416035545e-06 1.12526666692894e-05 2.20820233310758e-05 2.21547144786696e-05 3.55715814003759e-05 -9.4592188176523e-06 1.0125040609615e-05 1.08117253715969e-05 2.95572948213782e-05 -8.42091556481525e-06 -9.4592188176523e-06 1.34653317715702e-05 4.3472116020611e-07 -3.66474789930055e-07 -3.55469026098334e-06 2.67104416035545e-06 1.0125040609615e-05 4.3472116020611e-07 2.90566225971262e-05 2.0151777921966e-06 8.77659384650361e-06 1.12526666692894e-05 1.08117253715969e-05 -3.66474789930055e-07 2.0151777921966e-06 3.45728484216905e-05 1.18879033643553e-05 2.20820233310758e-05 2.95572948213782e-05 -3.55469026098334e-06 8.77659384650361e-06 1.18879033643553e-05 5.43840506670856e-05 2748 2742 0 6 42 2808 2857 0 50 35 0 0 0 0 0 24 57 0 614 0 19 18 0 0 2467 +414 417 0.999999697706898 -0.000719600815666006 -0.000294551828208207 0.00209300704632841 0.000720135424850054 0.999998086451643 0.00181892771229375 0.0010691614098151 0.000293242362703636 -0.0018191392796504 0.999998302369158 -0.00217059838778072 3.38501020579054e-05 2.22562464127778e-05 -9.66838869065665e-06 6.55826625052817e-06 8.06359322441268e-06 2.40605039065327e-05 2.22562464127778e-05 2.68199907434604e-05 -1.02771231231729e-05 5.8338370810641e-06 1.05162469093833e-05 2.48984397805299e-05 -9.66838869065665e-06 -1.02771231231729e-05 1.3310354755861e-05 8.80260166107916e-07 -3.41897789824406e-06 -6.50746614374901e-06 6.55826625052817e-06 5.8338370810641e-06 8.80260166107916e-07 2.92906706520511e-05 1.83611886969075e-06 9.87690113491015e-06 8.06359322441268e-06 1.05162469093833e-05 -3.41897789824406e-06 1.83611886969075e-06 3.88514577205835e-05 1.04807322489324e-05 2.40605039065327e-05 2.48984397805299e-05 -6.50746614374901e-06 9.87690113491015e-06 1.04807322489324e-05 4.43580168712967e-05 2497 2497 0 20 46 2495 2542 0 48 47 0 0 0 0 0 14 48 0 604 0 25 23 0 0 2480 +414 416 0.999999829851115 -0.000385014372997228 -0.000438248416348154 -0.00114213369484652 0.000385988083083619 0.999997452614723 0.00222391035434855 0.00031507481912367 0.000437391062509909 -0.00222407913461883 0.999997431077231 -0.00249664910012206 3.81553642147504e-05 2.42004401695997e-05 -9.1087082632212e-06 9.23423166776884e-06 9.8281838858519e-06 2.98291248260891e-05 2.42004401695997e-05 3.10945635477435e-05 -9.63476601113677e-06 9.21268593313456e-06 1.2437640573747e-05 3.15629737063602e-05 -9.1087082632212e-06 -9.63476601113677e-06 1.22614562792128e-05 -8.72807208499448e-07 -2.39063194581185e-06 -5.37450258463699e-06 9.23423166776884e-06 9.21268593313456e-06 -8.72807208499448e-07 2.26377651174581e-05 5.80896858317343e-06 1.29859642754073e-05 9.8281838858519e-06 1.2437640573747e-05 -2.39063194581185e-06 5.80896858317343e-06 3.66732191238997e-05 1.09924816161454e-05 2.98291248260891e-05 3.15629737063602e-05 -5.37450258463699e-06 1.29859642754073e-05 1.09924816161454e-05 5.39925605348162e-05 3196 3191 0 13 24 3202 3246 0 47 23 0 0 0 0 0 19 51 0 603 0 31 30 0 0 2437 +412 414 0.999999991280183 -8.31930709252185e-05 0.000102559963874077 -0.00301682047589792 8.31103656687337e-05 0.99999967160779 0.000806149476973728 0.00517743887942872 -0.000102626996244798 -0.000806140946148152 0.999999669802183 -0.000226481296309149 4.00339232927678e-05 3.13238348177487e-05 -1.19127600315863e-05 1.16780717157465e-05 5.79018117128394e-06 2.91068715733641e-05 3.13238348177487e-05 4.65623333932713e-05 -1.12141540724661e-05 2.03476844536533e-05 -6.14936837891649e-08 3.32400126205993e-05 -1.19127600315863e-05 -1.12141540724661e-05 1.49076731906458e-05 -4.15009920801226e-06 -2.29355415502102e-06 -6.43507498120433e-06 1.16780717157465e-05 2.03476844536533e-05 -4.15009920801226e-06 4.13489079925731e-05 -1.51279686426074e-05 8.18216993165002e-06 5.79018117128394e-06 -6.14936837891649e-08 -2.29355415502102e-06 -1.51279686426074e-05 4.48529877885568e-05 8.48033552150083e-06 2.91068715733641e-05 3.32400126205993e-05 -6.43507498120433e-06 8.18216993165002e-06 8.48033552150083e-06 5.41337487573808e-05 2055 2052 0 12 42 2117 2151 0 44 39 0 0 0 0 0 19 50 0 612 0 64 72 0 0 2529 +415 419 0.999999719771741 -4.08329318969185e-05 0.000747521980875852 0.000778789882261859 4.02189246371092e-05 0.999999661852986 0.000821386846758932 0.0011365828752988 -0.000747555267736701 -0.000821356552052912 0.999999383267078 0.000459443243830844 2.85586536744504e-05 1.39410694759941e-05 -8.73964141003866e-06 6.76966077136074e-06 9.93124611778004e-06 2.02375368506016e-05 1.39410694759941e-05 1.98211116329148e-05 -8.79398014392288e-06 5.11040629392226e-06 5.81968451947598e-06 1.76156387754833e-05 -8.73964141003866e-06 -8.79398014392288e-06 1.2671815405983e-05 1.23364247073748e-06 -2.17397166929696e-06 -3.78492009407951e-06 6.76966077136074e-06 5.11040629392226e-06 1.23364247073748e-06 2.0515847840712e-05 8.95835969907872e-06 9.15111830449691e-06 9.93124611778004e-06 5.81968451947598e-06 -2.17397166929696e-06 8.95835969907872e-06 3.05109053051389e-05 1.4785459855045e-05 2.02375368506016e-05 1.76156387754833e-05 -3.78492009407951e-06 9.15111830449691e-06 1.4785459855045e-05 5.37873401414609e-05 2638 2641 0 16 26 2637 2688 0 46 23 0 0 0 0 0 21 53 0 599 0 29 27 0 0 2486 +415 418 0.999994580840657 -0.000212342986967794 0.00328530056091982 0.00584023188211963 0.000207449757716373 0.99999886887815 0.00148970031148416 -0.00426820626430839 -0.0032856131722584 -0.00148901070375541 0.999993493775438 -0.00210485955779258 2.69223353644227e-05 1.50857360179204e-05 -7.92872931923603e-06 2.52485768709842e-06 1.01487854687821e-05 1.66735624185682e-05 1.50857360179204e-05 2.3126334894687e-05 -8.93735239744713e-06 7.38340032035016e-06 5.81493431536261e-06 1.59413864837069e-05 -7.92872931923603e-06 -8.93735239744713e-06 1.22483500027763e-05 1.08862909647832e-06 -2.22221101194e-06 -3.34411291709473e-06 2.52485768709842e-06 7.38340032035016e-06 1.08862909647832e-06 2.5895191458026e-05 8.11170780077445e-07 4.74072653114541e-06 1.01487854687821e-05 5.81493431536261e-06 -2.22221101194e-06 8.11170780077445e-07 3.27755196423352e-05 8.84920165580882e-06 1.66735624185682e-05 1.59413864837069e-05 -3.34411291709473e-06 4.74072653114541e-06 8.84920165580882e-06 3.65898637851486e-05 2774 2776 0 16 42 2818 2859 0 48 35 0 0 0 0 0 22 53 0 618 0 31 30 0 0 2431 +416 418 0.999998013411333 -0.000272264302835275 -0.00197460009538757 -0.000158656804268484 0.000274084721723157 0.999999537667927 0.000921705754522608 -0.000579570785521463 0.00197434823489194 -0.00092224513119006 0.999997625703664 -0.0032421068359762 3.61568394990628e-05 2.69071362385609e-05 -1.33933820840476e-05 6.7262539007465e-06 1.21476530922598e-05 2.52400000806838e-05 2.69071362385609e-05 3.44803786299225e-05 -1.36801068542499e-05 1.25623999846599e-05 9.65118200284704e-06 3.02921339194015e-05 -1.33933820840476e-05 -1.36801068542499e-05 1.70788426141551e-05 -1.72199418120284e-06 -7.5183903569954e-06 -8.59647115706393e-06 6.7262539007465e-06 1.25623999846599e-05 -1.72199418120284e-06 3.36735655484602e-05 -1.719982310848e-06 1.47399219508048e-05 1.21476530922598e-05 9.65118200284704e-06 -7.5183903569954e-06 -1.719982310848e-06 3.69937837903695e-05 7.21494954378911e-06 2.52400000806838e-05 3.02921339194015e-05 -8.59647115706393e-06 1.47399219508048e-05 7.21494954378911e-06 4.67614712713676e-05 1568 1566 0 18 29 1565 1598 0 50 29 0 0 0 0 0 19 52 0 619 0 26 24 0 0 2378 +413 416 0.999990681368281 0.000398270020965014 0.00429866928154877 0.000544102133854704 -0.000402245932216637 0.999999492126126 0.000924091824860616 0.00452857869689777 -0.00429829906029649 -0.000925812335821673 0.999990333701635 0.000995858938206285 3.6244222214104e-05 1.42468867953755e-05 -1.05042610577777e-05 3.24469076986385e-06 1.07690378200904e-05 1.42902546021027e-05 1.42468867953755e-05 3.00283366883124e-05 -9.02729534679359e-06 8.46807699893093e-06 1.06114355582677e-05 2.46269588088773e-05 -1.05042610577777e-05 -9.02729534679359e-06 1.34486812245847e-05 -1.75743103540195e-06 -9.80916250131395e-07 -3.19008424519744e-06 3.24469076986385e-06 8.46807699893093e-06 -1.75743103540195e-06 2.65103150041671e-05 -1.3378833157207e-06 5.30252365395707e-06 1.07690378200904e-05 1.06114355582677e-05 -9.80916250131395e-07 -1.3378833157207e-06 3.56487203496745e-05 1.28532418983653e-05 1.42902546021027e-05 2.46269588088773e-05 -3.19008424519744e-06 5.30252365395707e-06 1.28532418983653e-05 4.38654321814432e-05 2639 2633 0 18 25 2681 2725 0 47 22 0 0 0 0 0 17 49 0 619 0 16 14 0 0 2399 +414 418 0.999999638105186 0.000289616502555632 0.000799944860041929 -0.000910978120742239 -0.000289438385256772 0.999999933299747 -0.000222768763847015 0.00165369977709372 -0.000800009324195668 0.00022253714847957 0.99999965523109 0.000803919743134132 3.85220886202387e-05 3.03211023946819e-05 -1.15243531445849e-05 1.01309467878824e-05 8.12695259810061e-06 2.95576305563794e-05 3.03211023946819e-05 3.57257581251634e-05 -1.31236016061219e-05 9.84563846390244e-06 1.02491230423269e-05 3.09204201563923e-05 -1.15243531445849e-05 -1.31236016061219e-05 1.61958891618356e-05 -1.06716452036506e-07 -3.887623383962e-06 -6.42204201911435e-06 1.01309467878824e-05 9.84563846390244e-06 -1.06716452036506e-07 2.93167992140475e-05 1.05557365111763e-06 1.38232493061835e-05 8.12695259810061e-06 1.02491230423269e-05 -3.887623383962e-06 1.05557365111763e-06 3.86128104215951e-05 8.32550644108932e-06 2.95576305563794e-05 3.09204201563923e-05 -6.42204201911435e-06 1.38232493061835e-05 8.32550644108932e-06 5.19774882393226e-05 1530 1532 0 15 27 1583 1624 0 47 38 0 0 0 0 0 15 48 0 621 0 43 41 0 0 2447 +416 419 0.999995225261741 4.80094447216555e-05 0.00308984608240981 0.00373076821063176 -5.12670563835465e-05 0.999999442990299 0.00105422520409217 -0.000653199501614672 -0.00308979374856891 -0.00105437857775608 0.999994670716002 -0.00238400449686423 2.97174454748324e-05 1.65054265193712e-05 -9.30336686836533e-06 8.68518336838426e-06 8.02435500297746e-06 1.74984775949246e-05 1.65054265193712e-05 2.57444213265057e-05 -1.05920694757448e-05 1.02511052577792e-05 9.26078132900838e-06 1.94253395928062e-05 -9.30336686836533e-06 -1.05920694757448e-05 1.42874078138521e-05 -4.06314466134611e-06 -3.9939769773147e-06 -6.04053655196857e-06 8.68518336838426e-06 1.02511052577792e-05 -4.06314466134611e-06 2.59201425761991e-05 7.00135560404898e-06 9.38336074341672e-06 8.02435500297746e-06 9.26078132900838e-06 -3.9939769773147e-06 7.00135560404898e-06 3.46361709077524e-05 1.10684585741024e-05 1.74984775949246e-05 1.94253395928062e-05 -6.04053655196857e-06 9.38336074341672e-06 1.10684585741024e-05 3.79233119372063e-05 2710 2703 0 15 55 2764 2817 0 56 54 0 0 0 0 0 13 45 0 602 0 25 23 0 0 2405 +417 420 0.999999817920918 -0.000342359541178042 -0.000496938703430983 -0.00180570793879545 0.000342958048508691 0.999999215413828 0.00120480351317005 0.000584728223374811 0.00049652583756177 -0.00120497372292849 0.999999150749849 -0.00239395722301043 2.8935391548717e-05 1.76487144648532e-05 -1.04770606530783e-05 7.98387717205745e-06 8.92741238347361e-06 1.6353106557591e-05 1.76487144648532e-05 2.54068421954224e-05 -1.13077863147495e-05 1.0387548051627e-05 9.13510018002117e-06 1.89534572971783e-05 -1.04770606530783e-05 -1.13077863147495e-05 1.48383752742391e-05 -2.67646409785006e-06 -4.37903578552273e-06 -7.00540865399059e-06 7.98387717205745e-06 1.0387548051627e-05 -2.67646409785006e-06 2.65022582354803e-05 9.58784936130669e-07 7.53553019620737e-06 8.92741238347361e-06 9.13510018002117e-06 -4.37903578552273e-06 9.58784936130669e-07 3.93625579068249e-05 1.23008270413836e-05 1.6353106557591e-05 1.89534572971783e-05 -7.00540865399059e-06 7.53553019620737e-06 1.23008270413836e-05 3.35013640085061e-05 2017 2016 0 12 28 2063 2100 0 46 31 0 0 0 0 0 17 48 0 644 0 48 46 0 0 2441 +417 419 0.999988319020111 4.58444661070629e-05 0.00483318959045497 0.00422166390326584 -5.49765220791335e-05 0.999998213701084 0.00188933115770497 0.00111907802707158 -0.00483309434155542 -0.00188957480041995 0.99998653526243 0.000258550671869562 4.14173801511442e-05 2.96469304581172e-05 -1.02241091053727e-05 8.42746556437664e-06 9.18824568914428e-06 3.27379894428308e-05 2.96469304581172e-05 3.95064991165941e-05 -1.0546589451538e-05 9.41990200411716e-06 8.85081385146828e-06 3.39808653865515e-05 -1.02241091053727e-05 -1.0546589451538e-05 1.42976780526402e-05 -3.85981039263607e-06 -2.45304185353679e-06 -6.48340210516374e-06 8.42746556437664e-06 9.41990200411716e-06 -3.85981039263607e-06 2.86823104183973e-05 -1.23053279662449e-06 1.3373343601917e-05 9.18824568914428e-06 8.85081385146828e-06 -2.45304185353679e-06 -1.23053279662449e-06 3.92258403681463e-05 5.08494135390086e-06 3.27379894428308e-05 3.39808653865515e-05 -6.48340210516374e-06 1.3373343601917e-05 5.08494135390086e-06 6.83053721702887e-05 2710 2703 0 15 40 2761 2814 0 52 35 0 0 0 0 0 17 49 0 590 0 29 27 0 0 2399 +417 421 0.999999187339602 0.000999215460227161 0.000791762969023346 -0.00167862003731906 -0.000998820631282068 0.999999376723265 -0.000498909237702042 0.00233915565935263 -0.00079226099335947 0.000498118003069717 0.999999562100391 0.00382330438398761 2.51068013032676e-05 1.9175056141196e-05 -1.10438105656445e-05 9.07609973579681e-06 1.24298351712374e-05 1.91908656441621e-05 1.9175056141196e-05 2.22690048579919e-05 -1.08746327923911e-05 8.05628638977088e-06 9.7126468919343e-06 2.14048948698646e-05 -1.10438105656445e-05 -1.08746327923911e-05 1.61037562496593e-05 -3.79165536499207e-06 -6.75683581795188e-06 -7.06648876181225e-06 9.07609973579681e-06 8.05628638977088e-06 -3.79165536499207e-06 2.85367486657435e-05 6.16553594102968e-06 1.12212145250455e-05 1.24298351712374e-05 9.7126468919343e-06 -6.75683581795188e-06 6.16553594102968e-06 3.50209635764322e-05 1.12164528895923e-05 1.91908656441621e-05 2.14048948698646e-05 -7.06648876181225e-06 1.12212145250455e-05 1.12164528895923e-05 3.8450664281261e-05 2273 2269 0 17 30 2315 2353 0 50 27 0 0 0 0 0 19 51 0 627 0 53 52 0 0 2467 +416 371 0.999988931629024 -0.000459936007551036 0.00468242226969539 0.00344969311056445 0.000446725028132356 0.999995918216811 0.00282205359039769 0.00580881108412196 -0.00468370112112435 -0.00281993059964148 0.999985055355939 -0.00471403185053754 4.20921650358987e-05 4.14713489862651e-06 -7.0297256635967e-06 5.021234679225e-07 1.62919320282057e-06 1.15509127388814e-05 4.14713489862651e-06 2.77191180915579e-05 -8.0307341046959e-06 6.51831703081943e-06 1.1429908494335e-05 1.16782991964801e-05 -7.0297256635967e-06 -8.0307341046959e-06 1.32797858439016e-05 -2.96798006766407e-07 -2.04954343571809e-06 -3.23028023842863e-06 5.021234679225e-07 6.51831703081943e-06 -2.96798006766407e-07 3.4853705942068e-05 6.72224538239624e-06 2.24466910364375e-06 1.62919320282057e-06 1.1429908494335e-05 -2.04954343571809e-06 6.72224538239624e-06 4.03046408878575e-05 7.24796149048479e-06 1.15509127388814e-05 1.16782991964801e-05 -3.23028023842863e-06 2.24466910364375e-06 7.24796149048479e-06 4.93206568881568e-05 2731 2713 0 12 50 2737 2760 0 44 56 0 0 0 0 0 19 51 0 644 0 39 19 0 0 2307 +415 417 0.999999632222302 0.000332065386974766 0.000790751439831104 -0.00229199842769623 -0.000331961009629553 0.9999999361724 -0.000132125258165144 0.00378353065724916 -0.00079079526358432 0.000131862710926089 0.999999678627487 0.00413087023521353 2.71745166362577e-05 2.23533337335685e-05 -8.69107237839868e-06 6.00862066302096e-06 6.29835227093547e-06 1.81226481421064e-05 2.23533337335685e-05 3.59019329172353e-05 -9.93792022568051e-06 1.35546725458355e-05 6.57096691624683e-06 2.84846954672454e-05 -8.69107237839868e-06 -9.93792022568051e-06 1.44492725000104e-05 8.19786910872476e-08 -2.31211505898754e-06 -3.94714488982928e-06 6.00862066302096e-06 1.35546725458355e-05 8.19786910872476e-08 3.01796371033635e-05 4.3558525870194e-06 1.07611720708354e-05 6.29835227093547e-06 6.57096691624683e-06 -2.31211505898754e-06 4.3558525870194e-06 3.49144244840698e-05 9.71489416485119e-06 1.81226481421064e-05 2.84846954672454e-05 -3.94714488982928e-06 1.07611720708354e-05 9.71489416485119e-06 4.54384969537011e-05 2822 2822 0 15 29 2834 2881 0 49 33 0 0 0 0 0 24 57 0 613 0 52 51 0 0 2533 +418 422 0.999999420464925 -0.00051978447573828 0.00094281170623622 0.00184121084790585 0.000516387006392027 0.999993385854058 0.00360022118711891 0.00199035852960239 -0.000944676809424288 -0.00359973224494988 0.999993074732766 -0.00542872259171592 4.27510890633302e-05 3.09803569903411e-05 -1.12787978644965e-05 1.95536590777671e-05 5.47756952849408e-06 3.08924011082287e-05 3.09803569903411e-05 3.33483921176399e-05 -1.19750872573763e-05 1.5559240485292e-05 5.42428041799522e-06 2.72361971005501e-05 -1.12787978644965e-05 -1.19750872573763e-05 1.48319632361537e-05 -2.53074354490511e-06 -6.55332050093835e-06 -6.34401774925081e-06 1.95536590777671e-05 1.5559240485292e-05 -2.53074354490511e-06 3.35705590857174e-05 -1.14061858288574e-07 1.43060450823825e-05 5.47756952849408e-06 5.42428041799522e-06 -6.55332050093835e-06 -1.14061858288574e-07 4.90347775593745e-05 3.53948099331308e-06 3.08924011082287e-05 2.72361971005501e-05 -6.34401774925081e-06 1.43060450823825e-05 3.53948099331308e-06 5.7543575677697e-05 2286 2282 0 17 50 2389 2435 0 53 39 0 0 0 0 0 21 54 0 612 0 41 40 0 0 2531 +417 371 0.999997019788793 -0.000382997363809907 0.00241116705190156 0.00408775833932776 0.000376254198571667 0.999996019079801 0.00279647230081367 0.00489840078242823 -0.00241222849475712 -0.00279555675500884 0.999993182984823 -0.00318775144429971 4.52887559381296e-05 1.59757496783822e-05 -7.12482050477336e-06 6.72836007402329e-06 2.31954667423701e-06 2.31402045444231e-05 1.59757496783822e-05 3.07919081391381e-05 -8.9550257153925e-06 4.17711922394902e-06 9.57726688809604e-06 2.33187572756657e-05 -7.12482050477336e-06 -8.9550257153925e-06 1.42089027374932e-05 2.36622650544125e-06 -2.25019732871016e-06 -4.54411665990102e-06 6.72836007402329e-06 4.17711922394902e-06 2.36622650544125e-06 3.33337431122712e-05 -3.25067740989401e-07 1.1058082151303e-05 2.31954667423701e-06 9.57726688809604e-06 -2.25019732871016e-06 -3.25067740989401e-07 5.20366326274304e-05 2.9363077070483e-06 2.31402045444231e-05 2.33187572756657e-05 -4.54411665990102e-06 1.1058082151303e-05 2.9363077070483e-06 6.54810397211979e-05 2800 2777 0 12 51 2799 2829 0 50 55 0 0 0 0 0 15 47 0 647 0 48 27 0 0 2312 +419 423 0.999996343317494 -0.000305532365195279 0.00268700606889777 0.00246388102666913 0.000307414339988524 0.999999707738863 -0.000700013294950984 -0.00474864775700027 -0.00268679140687264 0.00070083675942183 0.999996144982456 -0.00210862423375084 6.89447340162981e-05 5.42171191730243e-05 -1.23471320374776e-05 2.00734578512003e-05 8.31843113899107e-06 6.48565845941534e-05 5.42171191730243e-05 5.55159046828396e-05 -1.25402961588681e-05 1.91920701009409e-05 6.22280232656196e-06 6.0330299019846e-05 -1.23471320374776e-05 -1.25402961588681e-05 1.35415864078999e-05 -1.71566306316407e-06 -3.43205873504065e-06 -9.09485583871171e-06 2.00734578512003e-05 1.91920701009409e-05 -1.71566306316407e-06 3.36297790200572e-05 2.07330462412411e-06 2.78154157818809e-05 8.31843113899107e-06 6.22280232656196e-06 -3.43205873504065e-06 2.07330462412411e-06 3.7603170770901e-05 5.87896059770015e-06 6.48565845941534e-05 6.0330299019846e-05 -9.09485583871171e-06 2.78154157818809e-05 5.87896059770015e-06 9.68646337164767e-05 2898 2896 0 15 23 2897 2930 0 49 20 0 0 0 0 0 16 48 0 614 0 26 25 0 0 2472 +416 420 0.999999954701247 -8.18022434203748e-05 -0.000289665147148097 -0.000681779319836934 8.17358121767113e-05 0.999999970360643 -0.000229342474516065 0.00119255370255243 0.000289683899291536 0.000229318788111076 0.999999931748064 -0.000519235441790442 6.04765754330699e-05 3.591741712692e-05 -1.13422506598995e-05 9.07383531860058e-06 3.41798344489333e-06 3.37905137680671e-05 3.591741712692e-05 5.24112406987786e-05 -1.27423443682407e-05 1.59831891307735e-05 9.04137451907459e-06 4.48486319937758e-05 -1.13422506598995e-05 -1.27423443682407e-05 1.58359692426096e-05 -2.37003434217095e-06 -5.1976667989678e-06 -7.83087296389702e-06 9.07383531860058e-06 1.59831891307735e-05 -2.37003434217095e-06 2.9711495013072e-05 -1.64856377297078e-07 1.23644533603754e-05 3.41798344489333e-06 9.04137451907459e-06 -5.1976667989678e-06 -1.64856377297078e-07 4.53068788991592e-05 5.91187298959366e-06 3.37905137680671e-05 4.48486319937758e-05 -7.83087296389702e-06 1.23644533603754e-05 5.91187298959366e-06 6.68318910444172e-05 2026 2026 0 20 23 2021 2056 0 47 21 0 0 0 0 0 21 52 0 625 0 25 24 0 0 2385 +417 389 0.999996733593368 0.000154001925600063 0.00255129104585437 0.00663708020938284 -0.000148707803931995 0.999997835847384 -0.00207513530577318 -0.00314861995029139 -0.00255160509930415 0.00207474913064884 0.99999459234911 0.00358523857338813 5.13116560886318e-05 3.35614535074475e-05 -2.08806311471826e-06 1.04421142377506e-05 -6.01881402989632e-06 2.44143881391063e-05 3.35614535074475e-05 6.2267129635311e-05 -3.40221080316706e-06 2.47445957477843e-05 -1.13424653834547e-05 4.40283839594613e-05 -2.08806311471826e-06 -3.40221080316706e-06 1.01827758138293e-05 2.37626216247474e-06 3.71860933661137e-06 -1.20428239012526e-06 1.04421142377506e-05 2.47445957477843e-05 2.37626216247474e-06 4.67613392295248e-05 -1.5554705080654e-05 1.1382327042358e-05 -6.01881402989632e-06 -1.13424653834547e-05 3.71860933661137e-06 -1.5554705080654e-05 3.63566884323229e-05 -5.39668148233606e-06 2.44143881391063e-05 4.40283839594613e-05 -1.20428239012526e-06 1.1382327042358e-05 -5.39668148233606e-06 6.15630996198255e-05 2078 2057 0 20 51 2124 2143 0 55 52 0 0 0 0 0 16 48 0 502 0 66 46 0 0 2400 +419 421 0.999998287456461 3.66360487166911e-05 0.00185033563014811 0.00156180623255736 -4.15739728804024e-05 0.999996438160053 0.0026686960882979 0.00214040294769521 -0.00185023126906885 -0.00266876844384297 0.999994727145721 -0.005009991618257 2.66756009587058e-05 1.87999699678105e-05 -8.68523222457006e-06 8.04059931130029e-06 3.81871908276798e-06 1.93466629514272e-05 1.87999699678105e-05 2.23441726403112e-05 -9.57943793823135e-06 7.84512192016896e-06 2.62479619704598e-06 1.87475494056424e-05 -8.68523222457006e-06 -9.57943793823135e-06 1.22284938363801e-05 -1.91646983062057e-06 -4.42774691823033e-07 -4.43881571850352e-06 8.04059931130029e-06 7.84512192016896e-06 -1.91646983062057e-06 2.98822230086672e-05 2.30515405097096e-06 9.31591047746645e-06 3.81871908276798e-06 2.62479619704598e-06 -4.42774691823033e-07 2.30515405097096e-06 3.45075790782321e-05 3.84809692630078e-06 1.93466629514272e-05 1.87475494056424e-05 -4.43881571850352e-06 9.31591047746645e-06 3.84809692630078e-06 3.85637194702269e-05 2732 2732 0 18 30 2732 2761 0 39 31 0 0 0 0 0 15 48 0 610 0 26 24 0 0 2567 +418 420 0.999998993263791 0.000298886772687166 0.00138713305084367 0.00170244603364765 -0.000299449721884939 0.999999872890366 0.000405646539775778 0.00268998657779454 -0.00138701163214057 -0.000406061508003011 0.999998955655847 0.000227499642870785 1.94380864993975e-05 1.17880783340615e-05 -6.98208958141257e-06 5.63014705848739e-06 7.33236053615267e-06 1.20843180803254e-05 1.17880783340615e-05 1.73404762215113e-05 -8.26369734980571e-06 5.60728594672286e-06 4.99202666787638e-06 1.40776465134275e-05 -6.98208958141257e-06 -8.26369734980571e-06 1.15923996793324e-05 -1.05803086187907e-06 -5.48680702845619e-07 -3.64474135656437e-06 5.63014705848739e-06 5.60728594672286e-06 -1.05803086187907e-06 2.2075056021163e-05 8.14064181995168e-06 7.50217689781098e-06 7.33236053615267e-06 4.99202666787638e-06 -5.48680702845619e-07 8.14064181995168e-06 2.4605046531281e-05 9.88122083420153e-06 1.20843180803254e-05 1.40776465134275e-05 -3.64474135656437e-06 7.50217689781098e-06 9.88122083420153e-06 3.4907662558103e-05 2771 2768 0 15 25 2768 2808 0 46 25 0 0 0 0 0 16 47 0 645 0 19 17 0 0 2435 +420 422 0.999998580091573 -0.000283991870050038 0.00166107298325339 0.00259763861794788 0.000281048190884904 0.999998390299555 0.00177212025941449 -0.000664475555040627 -0.00166157357716989 -0.00177165090160913 0.999997050208815 -0.00494478069831355 2.94820805400672e-05 2.05347413048756e-05 -9.77945996071882e-06 5.48775733589853e-06 6.02796547631612e-06 1.79398724402347e-05 2.05347413048756e-05 2.78949326070964e-05 -1.15640474677415e-05 7.48781842907566e-06 4.55558512458922e-06 1.77912392969005e-05 -9.77945996071882e-06 -1.15640474677415e-05 1.47692551176444e-05 -2.07818454510475e-06 -3.48393513738133e-06 -4.30666634983073e-06 5.48775733589853e-06 7.48781842907566e-06 -2.07818454510475e-06 2.81101354500159e-05 -4.2823683021866e-06 1.59551745093394e-06 6.02796547631612e-06 4.55558512458922e-06 -3.48393513738133e-06 -4.2823683021866e-06 3.77152584010162e-05 4.77603087655283e-06 1.79398724402347e-05 1.77912392969005e-05 -4.30666634983073e-06 1.59551745093394e-06 4.77603087655283e-06 4.34413139792147e-05 1644 1641 0 13 43 1734 1771 0 44 36 0 0 0 0 0 20 53 0 595 0 40 39 0 0 2453 +418 421 0.999999683931405 0.000168522435228859 0.000777005327200763 -0.000628308930354796 -0.000168184722255967 0.999999891384068 -0.000434678907281651 0.00277239778635667 -0.000777078495953602 0.000434548089468153 0.999999603658406 0.000684270311170641 3.37101502846665e-05 2.34918814281109e-05 -1.00441755396012e-05 1.00458406283895e-05 1.0237616218134e-05 2.60146639532293e-05 2.34918814281109e-05 2.28434926231392e-05 -1.02032917412342e-05 7.27304686577913e-06 5.46285563496639e-06 2.19440009699086e-05 -1.00441755396012e-05 -1.02032917412342e-05 1.20503597172047e-05 -3.4795758248243e-07 -1.49260344476461e-06 -5.09318637554277e-06 1.00458406283895e-05 7.27304686577913e-06 -3.4795758248243e-07 2.19365312910489e-05 8.80653186199277e-06 1.43624698368729e-05 1.0237616218134e-05 5.46285563496639e-06 -1.49260344476461e-06 8.80653186199277e-06 2.73957554333506e-05 1.1282564830307e-05 2.60146639532293e-05 2.19440009699086e-05 -5.09318637554277e-06 1.43624698368729e-05 1.1282564830307e-05 4.77286401022582e-05 3106 3106 0 21 48 3103 3136 0 46 40 0 0 0 0 0 11 44 0 635 0 32 30 0 0 2562 +420 423 0.999999890912953 0.000238811460774906 0.000401426417096331 0.000164789120052436 -0.000239226570628163 0.999999436437661 0.00103435729239205 -0.00121701181875721 -0.000401179174491561 -0.00103445321142219 0.999999384480722 -0.000842966908161429 3.14524148907161e-05 1.90352453410448e-05 -6.78029626468164e-06 5.07667115871383e-06 4.13364844185002e-06 2.61289093811633e-05 1.90352453410448e-05 2.48578545376861e-05 -7.909109202844e-06 5.95079217723899e-06 -2.36603171085398e-07 2.26673143619134e-05 -6.78029626468164e-06 -7.909109202844e-06 1.23885125138482e-05 2.56928697129377e-06 -2.62776990291739e-07 -2.69417171425528e-06 5.07667115871383e-06 5.95079217723899e-06 2.56928697129377e-06 2.39410090432242e-05 1.35974772738224e-06 6.20044896686089e-06 4.13364844185002e-06 -2.36603171085398e-07 -2.62776990291739e-07 1.35974772738224e-06 2.63497857134205e-05 2.48082418294211e-06 2.61289093811633e-05 2.26673143619134e-05 -2.69417171425528e-06 6.20044896686089e-06 2.48082418294211e-06 4.80512504442461e-05 2394 2392 0 20 46 2389 2423 0 45 48 0 0 0 0 0 11 43 0 600 0 25 24 0 0 2394 +422 424 0.999999959543684 -0.000149447303165532 -0.000242029201138123 0.00111606126853324 0.000149508518027117 0.999999956838044 0.000252925114699566 -0.00126441839038051 0.000241991391715375 -0.000252961289894329 0.999999938725374 0.000252246910077919 2.7578322351214e-05 1.78703376511225e-05 -6.47473909949887e-06 4.85874715984386e-06 5.76874658848665e-06 1.97273961473228e-05 1.78703376511225e-05 2.35995626479697e-05 -8.24537791994851e-06 4.72201307929596e-06 9.45856261278975e-06 1.95382130927476e-05 -6.47473909949887e-06 -8.24537791994851e-06 1.21371594456192e-05 1.39389523783153e-06 -8.03028199634675e-07 -1.34525330341066e-06 4.85874715984386e-06 4.72201307929596e-06 1.39389523783153e-06 3.12766705124221e-05 -4.458419727539e-06 7.15199264777129e-06 5.76874658848665e-06 9.45856261278975e-06 -8.03028199634675e-07 -4.458419727539e-06 5.40228119218584e-05 7.23708873186884e-06 1.97273961473228e-05 1.95382130927476e-05 -1.34525330341066e-06 7.15199264777129e-06 7.23708873186884e-06 4.1812217841336e-05 2441 2446 0 20 42 2448 2473 0 39 42 0 0 0 0 0 17 48 0 625 0 59 58 0 0 2449 +419 422 0.999996921486258 0.000697849088757125 -0.00238118135719258 -0.00408696474859095 -0.000698041986699977 0.999999753154308 -8.01792234210923e-05 0.00432622630719372 0.00238112481641022 8.18411411535188e-05 0.99999716176929 0.00329647358186568 4.262153530001e-05 2.11906537191551e-05 -7.28869588423277e-06 7.68884348900409e-06 4.33159825701493e-06 1.96694850944535e-05 2.11906537191551e-05 3.21180362549733e-05 -9.33634772786747e-06 1.19131377475043e-05 8.84621670199559e-06 1.96554730719908e-05 -7.28869588423277e-06 -9.33634772786747e-06 1.20799804627809e-05 -4.65674769163914e-07 6.90270139818603e-07 -2.54594905456856e-06 7.68884348900409e-06 1.19131377475043e-05 -4.65674769163914e-07 3.18744871323543e-05 1.9670639628304e-06 3.74375433516573e-06 4.33159825701493e-06 8.84621670199559e-06 6.90270139818603e-07 1.9670639628304e-06 3.41331094642561e-05 1.01038615452933e-05 1.96694850944535e-05 1.96554730719908e-05 -2.54594905456856e-06 3.74375433516573e-06 1.01038615452933e-05 4.18728080629235e-05 2977 2989 0 27 26 3023 3066 0 48 29 0 0 0 0 0 17 51 0 600 0 39 38 0 0 2561 +422 425 0.999998021461011 2.7014233096298e-05 -0.00198905613180311 -0.00100060093246443 -2.65462791993014e-05 0.999999971966879 0.00023529032442514 -0.00460148919744713 0.00198906243223133 -0.000235237056854642 0.999997994145072 0.00134744334950425 4.44047738215465e-05 2.12697170305964e-05 -7.3694163712596e-06 2.19681927271857e-06 4.03179398203815e-06 1.72333540588694e-05 2.12697170305964e-05 4.60120990410939e-05 -1.03061350790014e-05 8.69314167884644e-06 1.78036528679502e-05 3.83343278013589e-05 -7.3694163712596e-06 -1.03061350790014e-05 1.41421787022892e-05 -2.67952675230763e-07 -1.65862846452087e-06 -3.71092766715354e-06 2.19681927271857e-06 8.69314167884644e-06 -2.67952675230763e-07 3.24618895302188e-05 3.93721526919674e-06 4.83230206767149e-06 4.03179398203815e-06 1.78036528679502e-05 -1.65862846452087e-06 3.93721526919674e-06 4.55720572547447e-05 1.47897163317892e-05 1.72333540588694e-05 3.83343278013589e-05 -3.71092766715354e-06 4.83230206767149e-06 1.47897163317892e-05 6.14526450925679e-05 2692 2700 0 28 26 2702 2737 0 54 26 0 0 0 0 0 18 49 0 631 0 61 60 0 0 2207 +420 424 0.999999352934056 -0.000148566820676177 0.00112785609449161 -0.00220078327484008 0.000148446740863657 0.999999983305301 0.000106550283904399 0.000816989916441072 -0.00112787190549931 -0.000106382788397948 0.999999358293628 -0.00200995569549077 2.76695763800027e-05 2.08446408606517e-05 -7.80742434402235e-06 5.63547763051749e-06 1.27381744888845e-05 2.1297985266438e-05 2.08446408606517e-05 2.60612209927389e-05 -9.62930166894046e-06 5.40206070774868e-06 1.02810420683691e-05 2.11333685975999e-05 -7.80742434402235e-06 -9.62930166894046e-06 1.47214722456717e-05 -2.513216503658e-07 -3.9357873094674e-06 -3.30024191170158e-06 5.63547763051749e-06 5.40206070774868e-06 -2.513216503658e-07 2.44961862855817e-05 2.09197894882392e-06 7.43791120473292e-06 1.27381744888845e-05 1.02810420683691e-05 -3.9357873094674e-06 2.09197894882392e-06 4.20165926484075e-05 1.2732441391954e-05 2.1297985266438e-05 2.11333685975999e-05 -3.30024191170158e-06 7.43791120473292e-06 1.2732441391954e-05 4.16370495103626e-05 2739 2737 0 10 35 2769 2803 0 41 39 0 0 0 0 0 12 42 0 622 0 30 29 0 0 2366 +421 425 0.999999046007048 0.000113205569324781 0.00137665155107442 -0.00598864193281481 -0.000114949878390485 0.99999919068078 0.00126705339663629 0.00676166091881479 -0.00137650699942273 -0.00126721043380466 0.999998249701567 -0.00491027069962923 2.74817704298434e-05 1.44929767637733e-05 -6.74232066765706e-06 3.27128792477425e-06 7.73754498914642e-06 1.40403818604979e-05 1.44929767637733e-05 2.73210597431899e-05 -8.17871778480041e-06 9.82664647594357e-06 2.95592072431745e-06 1.54308409358978e-05 -6.74232066765706e-06 -8.17871778480041e-06 1.40917874325041e-05 -1.91894469875154e-06 -2.68834015989551e-06 -1.57967755782646e-06 3.27128792477425e-06 9.82664647594357e-06 -1.91894469875154e-06 3.57256321154758e-05 -9.33748347750024e-06 1.5345847605031e-06 7.73754498914642e-06 2.95592072431745e-06 -2.68834015989551e-06 -9.33748347750024e-06 4.40923200791004e-05 3.97281846371151e-06 1.40403818604979e-05 1.54308409358978e-05 -1.57967755782646e-06 1.5345847605031e-06 3.97281846371151e-06 4.35149896024746e-05 2685 2686 0 21 37 2703 2739 0 38 37 0 0 0 0 0 18 49 0 619 0 35 33 0 0 2162 +421 424 0.999999882630828 -0.000189788576530748 0.000445778673805763 -0.0015488641594596 0.000190114192980373 0.999999715101848 -0.000730515445511495 0.00111316449501351 -0.000445639903317705 0.000730600108624321 0.999999633814212 -0.00263878520010765 3.52250969091533e-05 2.57994005854462e-05 -6.4453330548896e-06 7.39406326589562e-06 1.00646194710338e-05 2.60601622844992e-05 2.57994005854462e-05 2.67496802880128e-05 -8.12517356162106e-06 6.97768600311469e-06 6.24970671925665e-06 2.35944045682993e-05 -6.4453330548896e-06 -8.12517356162106e-06 1.20821589321027e-05 -2.60980464820222e-08 6.72619435034809e-07 -1.93903086657728e-06 7.39406326589562e-06 6.97768600311469e-06 -2.60980464820222e-08 3.06644137291819e-05 -2.95397062476833e-06 9.66331351908489e-06 1.00646194710338e-05 6.24970671925665e-06 6.72619435034809e-07 -2.95397062476833e-06 3.66058788227907e-05 9.15376083521631e-06 2.60601622844992e-05 2.35944045682993e-05 -1.93903086657728e-06 9.66331351908489e-06 9.15376083521631e-06 4.55293176626163e-05 2879 2875 0 16 42 2902 2937 0 39 34 0 0 0 0 0 8 39 0 628 0 36 35 0 0 2460 +422 426 0.99999284094237 0.000930957303060375 0.00366761264419709 -0.000255547648785156 -0.000938038178893284 0.999997698741625 0.00192940297226163 0.00971935584015861 -0.0036658080122852 -0.00193282952024021 0.999991412973963 0.00100290733167537 3.98942749645731e-05 2.65076851968697e-05 -8.27271873649336e-06 1.41131570976127e-05 -2.71869037685137e-06 2.60581361278738e-05 2.65076851968697e-05 4.22840478099676e-05 -1.02144613243748e-05 1.69606633563102e-05 3.00705482891366e-06 2.88254546943231e-05 -8.27271873649336e-06 -1.02144613243748e-05 1.46859434747659e-05 -4.99666906076072e-07 -8.05931859441199e-07 -4.98378892804507e-06 1.41131570976127e-05 1.69606633563102e-05 -4.99666906076072e-07 3.79823479355119e-05 -5.35782635461841e-06 1.25393433615172e-05 -2.71869037685137e-06 3.00705482891366e-06 -8.05931859441199e-07 -5.35782635461841e-06 4.75089495448844e-05 4.32460254678485e-06 2.60581361278738e-05 2.88254546943231e-05 -4.98378892804507e-06 1.25393433615172e-05 4.32460254678485e-06 4.96168208095667e-05 2011 2016 0 27 53 2058 2084 0 38 53 0 0 0 0 0 12 42 0 651 0 52 51 0 0 2219 +423 397 0.99999967491851 0.000708764957683692 -0.000384467304691805 0.00212351744860999 -0.000708274749235364 0.999998938050105 0.00127367403285118 0.00164190369946657 0.000385369631928788 -0.00127340131031951 0.999999114969283 -0.00107751049173563 2.40696453883326e-05 1.83028477212469e-05 -3.15216811485672e-06 2.03177619516694e-06 5.19849619201975e-06 1.9917501765746e-05 1.83028477212469e-05 2.80107713079271e-05 -4.73438104306712e-06 4.06347396093143e-06 1.86076183749592e-06 2.62900131890418e-05 -3.15216811485672e-06 -4.73438104306712e-06 1.14336669317901e-05 4.04134932870751e-06 4.28389979844747e-06 1.33291359746462e-06 2.03177619516694e-06 4.06347396093143e-06 4.04134932870751e-06 2.25916248542731e-05 1.41728423850308e-06 6.70014502372635e-06 5.19849619201975e-06 1.86076183749592e-06 4.28389979844747e-06 1.41728423850308e-06 2.28991616470671e-05 8.58622411924631e-06 1.9917501765746e-05 2.62900131890418e-05 1.33291359746462e-06 6.70014502372635e-06 8.58622411924631e-06 5.35102818342666e-05 2322 2311 0 18 39 2321 2342 0 46 40 0 0 0 0 0 11 42 0 457 0 39 30 0 0 2372 +422 389 0.99999691234795 0.000324022118310894 0.00246379874038786 0.00588938571108012 -0.000319387573015579 0.999998179504288 -0.00188121760765372 -0.00304494279158362 -0.00246440381116705 0.00188042489240822 0.999995195346497 0.00149306209092415 3.23729026890583e-05 2.66510861827039e-05 1.83282908528646e-07 1.02516164497178e-05 -6.49752681479168e-06 1.83169574947619e-05 2.66510861827039e-05 5.57683092248308e-05 -2.13565206963846e-06 2.01832363993265e-05 -1.20417299677771e-05 4.16002690625858e-05 1.83282908528646e-07 -2.13565206963846e-06 9.76281541794476e-06 3.43950467260005e-06 2.91176724609225e-06 -1.08740902544533e-06 1.02516164497178e-05 2.01832363993265e-05 3.43950467260005e-06 3.31344341366533e-05 -7.16175925705138e-06 1.60066886350285e-05 -6.49752681479168e-06 -1.20417299677771e-05 2.91176724609225e-06 -7.16175925705138e-06 3.10900974303689e-05 -1.22047279816144e-05 1.83169574947619e-05 4.16002690625858e-05 -1.08740902544533e-06 1.60066886350285e-05 -1.22047279816144e-05 5.62100249099211e-05 2305 2284 0 21 48 2358 2377 0 53 48 0 0 0 0 0 15 47 0 497 0 69 49 0 0 2448 +423 425 0.99999739747837 0.000219400152914641 0.00227088089928356 -0.00180595419839422 -0.000219473553511903 0.999999975401329 3.20733727460101e-05 0.00284332461707123 -0.00227087380652003 -3.25716875749318e-05 0.999997421032294 -0.00094029701615393 4.24191380937088e-05 2.443693982948e-05 -8.0757689926743e-06 5.96152237806297e-06 8.46254010467086e-06 2.41507470287324e-05 2.443693982948e-05 3.46428509967927e-05 -9.82163625062021e-06 1.00047398616784e-05 2.24856818051058e-06 3.03827025435743e-05 -8.0757689926743e-06 -9.82163625062021e-06 1.4084079102572e-05 -1.08335454644393e-06 9.16997242533501e-07 -2.1828720148678e-06 5.96152237806297e-06 1.00047398616784e-05 -1.08335454644393e-06 3.12433996128273e-05 -2.86160348257993e-06 6.40311057870318e-06 8.46254010467086e-06 2.24856818051058e-06 9.16997242533501e-07 -2.86160348257993e-06 3.46059928217791e-05 6.7652898466683e-06 2.41507470287324e-05 3.03827025435743e-05 -2.1828720148678e-06 6.40311057870318e-06 6.7652898466683e-06 5.66476723906136e-05 2866 2860 0 19 60 2863 2884 0 43 58 0 0 0 0 0 23 54 0 623 0 57 61 0 0 2159 +421 423 0.999999692541472 -0.000560965082050516 -0.000547937166849408 -0.00112013698155436 0.000561824015133125 0.999998611794576 0.00156868183396974 -0.00101569278832911 0.000547056430466357 -0.00156898919592425 0.99999861950013 -0.00207016142913061 4.94407513366264e-05 3.13879036833637e-05 -1.07125550590527e-05 1.01860077721891e-05 9.68549731235527e-06 4.27320870272549e-05 3.13879036833637e-05 3.54475474598334e-05 -1.17445060478509e-05 1.00035219394882e-05 1.17332049983945e-05 3.76754028209089e-05 -1.07125550590527e-05 -1.17445060478509e-05 1.29980486351858e-05 1.7258954324117e-06 -2.13526355848695e-06 -7.16707641807039e-06 1.01860077721891e-05 1.00035219394882e-05 1.7258954324117e-06 2.66217405826406e-05 5.75847852025234e-06 1.56260048897792e-05 9.68549731235527e-06 1.17332049983945e-05 -2.13526355848695e-06 5.75847852025234e-06 3.75314702280386e-05 1.67726666023435e-05 4.27320870272549e-05 3.76754028209089e-05 -7.16707641807039e-06 1.56260048897792e-05 1.67726666023435e-05 7.97540204643876e-05 2910 2914 0 20 22 2910 2942 0 40 20 0 0 0 0 0 17 45 0 606 0 27 27 0 0 2424 +423 426 0.999998715870525 -0.000238846048218894 0.00158467973631575 0.000676540666294203 0.000236626795356675 0.999998991328139 0.00140048222584902 0.00582070771449483 -0.00158501263753913 -0.00140010544976084 0.999997763717334 -0.000567726591985867 2.72720901638612e-05 1.70302898080612e-05 -8.69465251040005e-06 9.5205281761038e-06 1.09549910392123e-05 1.76685737095395e-05 1.70302898080612e-05 2.29331543189e-05 -9.64554415135288e-06 7.39090881310761e-06 7.93684514497857e-06 2.04745107945056e-05 -8.69465251040005e-06 -9.64554415135288e-06 1.4442973286275e-05 -2.60988896961651e-07 -4.034837191848e-06 -4.89251415126666e-06 9.5205281761038e-06 7.39090881310761e-06 -2.60988896961651e-07 2.48702806784196e-05 9.07421349438857e-06 1.12390231180491e-05 1.09549910392123e-05 7.93684514497857e-06 -4.034837191848e-06 9.07421349438857e-06 4.23148755477368e-05 1.08549583450704e-05 1.76685737095395e-05 2.04745107945056e-05 -4.89251415126666e-06 1.12390231180491e-05 1.08549583450704e-05 4.31171528655953e-05 2950 2948 0 19 43 2941 2974 0 44 35 0 0 0 0 0 20 50 0 653 0 28 28 0 0 2217 +423 427 0.999999503624666 6.82586948881295e-05 -0.000994027752299461 0.000371839707000174 -6.67186427869406e-05 0.999998797676995 0.00154925568840092 0.00521666500265806 0.000994132307328365 -0.00154918859920608 0.999998305856385 0.00111795488594736 3.70357140586162e-05 2.24110617478233e-05 -7.65701663883673e-06 9.42461178934234e-06 2.22209845725507e-06 2.02615705259171e-05 2.24110617478233e-05 4.10177724547489e-05 -1.07451540947378e-05 1.46340270331626e-05 8.04006206665395e-06 3.18048410484113e-05 -7.65701663883673e-06 -1.07451540947378e-05 1.5617818269491e-05 -1.15541478227959e-06 -1.99530505301645e-06 -2.40263131283947e-06 9.42461178934234e-06 1.46340270331626e-05 -1.15541478227959e-06 3.63765538459395e-05 1.84660818316166e-06 1.17578026338411e-05 2.22209845725507e-06 8.04006206665395e-06 -1.99530505301645e-06 1.84660818316166e-06 4.42925103873635e-05 6.7293528278149e-06 2.02615705259171e-05 3.18048410484113e-05 -2.40263131283947e-06 1.17578026338411e-05 6.7293528278149e-06 4.83425177463889e-05 2251 2249 0 22 28 2271 2295 0 44 26 0 0 0 0 0 22 53 0 656 0 59 75 0 0 2416 +425 428 0.99999630628392 0.00061606207903967 0.00264724121129807 0.00461116519653408 -0.00061991078023465 0.999998751844442 0.00145327911391383 0.00705075134490597 -0.0026463425969769 -0.00145491479927817 0.999995440036496 -0.00238996038403713 2.742960568928e-05 1.81577267699765e-05 -9.62156166319351e-06 6.0079305187534e-06 6.55165586882138e-06 1.31670937060411e-05 1.81577267699765e-05 2.90691682017014e-05 -1.06763361280724e-05 7.29186235543121e-06 9.12761319680954e-06 2.06683132890358e-05 -9.62156166319351e-06 -1.06763361280724e-05 1.41670056275848e-05 -2.68070982899726e-06 -2.9349808070213e-06 -4.84164660001833e-06 6.0079305187534e-06 7.29186235543121e-06 -2.68070982899726e-06 2.93446482173158e-05 6.90558249381409e-06 1.11641108697089e-05 6.55165586882138e-06 9.12761319680954e-06 -2.9349808070213e-06 6.90558249381409e-06 3.80165657871675e-05 9.53414539135702e-06 1.31670937060411e-05 2.06683132890358e-05 -4.84164660001833e-06 1.11641108697089e-05 9.53414539135702e-06 4.22478263141293e-05 2183 2182 0 16 28 2279 2333 0 47 27 0 0 0 0 0 18 50 0 651 0 54 54 0 0 2364 +424 427 0.999995397212311 -0.000805612367612992 0.00292515690272594 0.00733883631181794 0.00079487876780652 0.999992954304912 0.00366872025072488 -0.0017425654397314 -0.00292809185936962 -0.00366637821926999 0.999988991913819 -0.0043431859777094 3.64520818127876e-05 2.23182346993362e-05 -1.1655756250927e-05 5.03504806035919e-06 9.77149278219003e-06 1.59518589026069e-05 2.23182346993362e-05 3.29120005398276e-05 -1.18224369070477e-05 8.00611096263758e-06 1.03705932852587e-05 2.37396860239241e-05 -1.1655756250927e-05 -1.18224369070477e-05 1.80120632210206e-05 -6.4293183513803e-07 -5.57860982391379e-06 -3.68796404068507e-06 5.03504806035919e-06 8.00611096263758e-06 -6.4293183513803e-07 2.78545420126051e-05 -9.36339965897932e-07 1.29284412839325e-05 9.77149278219003e-06 1.03705932852587e-05 -5.57860982391379e-06 -9.36339965897932e-07 4.81142530342217e-05 7.4398435165171e-06 1.59518589026069e-05 2.37396860239241e-05 -3.68796404068507e-06 1.29284412839325e-05 7.4398435165171e-06 4.08360152880953e-05 2116 2117 0 17 36 2215 2260 0 48 48 0 0 0 0 0 11 42 0 646 0 53 50 0 0 2405 +424 426 0.999999478555869 0.000145405883770876 0.00101081408684263 0.00237088309592528 -0.000146002550362557 0.999999815153234 0.00059023449028 0.00503967170432796 -0.00101072807642923 -0.000590381763940311 0.99999931493883 0.00134448200625584 2.36016410525069e-05 1.67503793713949e-05 -8.46778823747525e-06 6.23541320223057e-06 7.56352561036154e-06 1.10656497923609e-05 1.67503793713949e-05 2.24024843587695e-05 -1.04426337554568e-05 8.24503157034809e-06 5.40956504974238e-06 1.82945139573858e-05 -8.46778823747525e-06 -1.04426337554568e-05 1.42255831328325e-05 -2.18885370728245e-06 -9.96364980267459e-07 -4.30726864285068e-06 6.23541320223057e-06 8.24503157034809e-06 -2.18885370728245e-06 3.22499841014193e-05 -2.04050935210657e-08 1.07113801195516e-05 7.56352561036154e-06 5.40956504974238e-06 -9.96364980267459e-07 -2.04050935210657e-08 4.03380651799769e-05 6.45876424936225e-06 1.10656497923609e-05 1.82945139573858e-05 -4.30726864285068e-06 1.07113801195516e-05 6.45876424936225e-06 4.02022880134199e-05 2842 2836 0 17 27 2855 2890 0 43 26 0 0 0 0 0 16 46 0 640 0 31 30 0 0 2218 +425 429 0.999972329038464 -0.00721703992114022 -0.00180429824790576 0.00164767810129873 0.00721999386996411 0.999972597129831 0.0016360556036743 0.0052772350423089 0.0017924413263502 -0.00164903735473209 0.999997033910548 0.000332280567096929 3.64070319424654e-05 1.37222747658213e-05 -3.62397048680945e-06 2.41172103963286e-08 -2.93834475226635e-06 9.06158179001325e-06 1.37222747658213e-05 2.81233011642993e-05 -6.00291591944222e-06 6.78472576528488e-06 1.97034992954466e-06 1.83950962323092e-05 -3.62397048680945e-06 -6.00291591944222e-06 1.11357392870638e-05 2.35294829810049e-06 2.66221595243525e-06 1.19427726104372e-06 2.41172103963286e-08 6.78472576528488e-06 2.35294829810049e-06 2.97997232988948e-05 2.2149791130662e-06 9.41725387854265e-06 -2.93834475226635e-06 1.97034992954466e-06 2.66221595243525e-06 2.2149791130662e-06 3.77011887670702e-05 5.86398942748393e-07 9.06158179001325e-06 1.83950962323092e-05 1.19427726104372e-06 9.41725387854265e-06 5.86398942748393e-07 4.07415631285252e-05 2846 2841 0 7 41 2846 2867 0 37 39 0 0 0 0 0 33 65 0 620 0 20 18 0 0 2459 +424 428 0.999999811312415 1.87710623633792e-05 0.000614021809325326 0.00578488554956457 -1.92664583233689e-05 0.999999674343816 0.000806809188268207 -0.000673787725469076 -0.000614006464699738 -0.000806820866058928 0.999999486017944 -0.000569345422589083 2.87149063893329e-05 1.99877413728956e-05 -8.35918959452455e-06 5.51549394085262e-06 7.33993848242416e-06 1.74128349700209e-05 1.99877413728956e-05 2.26528571069809e-05 -9.96101675439401e-06 4.84316540574998e-06 3.24021258228324e-06 1.8499785731915e-05 -8.35918959452455e-06 -9.96101675439401e-06 1.56826145032577e-05 -2.49748686403769e-07 -4.44195101670995e-06 -2.25451186464901e-06 5.51549394085262e-06 4.84316540574998e-06 -2.49748686403769e-07 2.9202311330698e-05 1.6019564203992e-06 8.62737735272644e-06 7.33993848242416e-06 3.24021258228324e-06 -4.44195101670995e-06 1.6019564203992e-06 4.33964722917233e-05 2.19317679673844e-06 1.74128349700209e-05 1.8499785731915e-05 -2.25451186464901e-06 8.62737735272644e-06 2.19317679673844e-06 4.506658050799e-05 2395 2395 0 20 53 2491 2540 0 49 43 0 0 0 0 0 13 45 0 632 0 52 51 0 0 2396 +426 429 0.9999725828737 -0.00732553772456883 -0.00108166443365215 0.00215817604650068 0.00732990063678875 0.99996478713027 0.00408620314810839 0.00402297617780321 0.00105169270983163 -0.00409401960898161 0.999991066433038 -0.00167665776128217 2.89720400134163e-05 1.31855684404807e-05 -3.14640229579352e-06 2.88006890388485e-06 5.08951873485827e-07 1.18917319470656e-05 1.31855684404807e-05 2.55907180807625e-05 -5.82193605607281e-06 4.03147530419738e-06 4.72988319830548e-06 1.48060378353829e-05 -3.14640229579352e-06 -5.82193605607281e-06 9.86053193087127e-06 1.70545439683426e-06 2.76955449274108e-06 -6.11312040832893e-07 2.88006890388485e-06 4.03147530419738e-06 1.70545439683426e-06 2.31484122904757e-05 3.75684507358739e-06 4.52375404503384e-06 5.08951873485827e-07 4.72988319830548e-06 2.76955449274108e-06 3.75684507358739e-06 2.75306826658143e-05 6.15894335354173e-08 1.18917319470656e-05 1.48060378353829e-05 -6.11312040832893e-07 4.52375404503384e-06 6.15894335354173e-08 4.61211922113386e-05 2882 2879 0 6 63 2884 2908 0 32 58 0 0 0 0 0 33 65 0 618 0 20 19 0 0 2468 +424 397 0.999999704665946 0.000727516247498146 0.000247766281525991 -0.00522496052932928 -0.00072789015205523 0.999998591455253 0.00151237013856755 0.00876523402400344 -0.000246665658688058 -0.00151255003854948 0.999998825673527 0.0020002123494009 2.81342984398132e-05 2.1931180447491e-05 -2.14394638808807e-06 1.63125265470706e-06 1.61886700361856e-06 2.17374039125808e-05 2.1931180447491e-05 3.22960040443375e-05 -4.66236755348817e-06 5.63144359542128e-06 2.74459699200494e-06 2.57777506341436e-05 -2.14394638808807e-06 -4.66236755348817e-06 1.00869494840118e-05 1.67197904510843e-06 4.33321578438838e-06 4.5155933220327e-07 1.63125265470706e-06 5.63144359542128e-06 1.67197904510843e-06 3.59844636410143e-05 -8.26916438113281e-06 6.71261695580948e-06 1.61886700361856e-06 2.74459699200494e-06 4.33321578438838e-06 -8.26916438113281e-06 3.3775106804806e-05 2.99652809145731e-06 2.17374039125808e-05 2.57777506341436e-05 4.5155933220327e-07 6.71261695580948e-06 2.99652809145731e-06 5.18757683486083e-05 2631 2618 0 15 42 2647 2673 0 47 47 0 0 0 0 0 12 43 0 468 0 41 28 0 0 2381 +424 398 0.999999841804864 9.92993596459128e-06 0.000562398118846839 0.00209768429878412 -1.04984533663705e-05 0.999999488998735 0.00101088676532293 -0.00175516758138067 -0.000562387793419842 -0.00101089250971598 0.999999330907928 -0.000229498020005026 3.02070321780868e-05 2.64577674078873e-05 -3.41201002190923e-06 8.71098265534309e-06 -3.14924664249149e-06 2.7238348758137e-05 2.64577674078873e-05 3.04218058004659e-05 -4.27785991048503e-06 8.82338067259963e-06 -4.07775744047463e-06 3.14204387724445e-05 -3.41201002190923e-06 -4.27785991048503e-06 1.08953797978318e-05 3.93868047968658e-06 1.76159195694399e-07 -1.75630295100197e-06 8.71098265534309e-06 8.82338067259963e-06 3.93868047968658e-06 2.70003372076932e-05 -1.03555669495597e-05 1.35798902270925e-05 -3.14924664249149e-06 -4.07775744047463e-06 1.76159195694399e-07 -1.03555669495597e-05 3.66191019743373e-05 -5.52762115842163e-06 2.7238348758137e-05 3.14204387724445e-05 -1.75630295100197e-06 1.35798902270925e-05 -5.52762115842163e-06 4.81968230352882e-05 2406 2391 0 18 41 2510 2545 0 50 42 0 0 0 0 0 7 39 0 466 0 65 51 0 0 2301 +430 427 0.996635219924739 0.0797792549983328 0.0188018317585864 0.00292182004253121 -0.0804446743170206 0.996042575438616 0.0377868004419281 0.00243229739015403 -0.0157128221397583 -0.0391721634010762 0.999108927412264 0.0139937234492583 6.1994217218963e-05 3.48064673339517e-05 -5.7925130068487e-06 1.74921757626647e-05 -7.73273888367846e-06 3.40613925927499e-05 3.48064673339517e-05 6.19109157229495e-05 -7.22267484172029e-06 2.25415112115114e-05 -9.87802179927297e-06 3.7947365204419e-05 -5.7925130068487e-06 -7.22267484172029e-06 1.24839902808052e-05 1.41788341102768e-06 1.52925253020295e-06 -2.6207813292979e-06 1.74921757626647e-05 2.25415112115114e-05 1.41788341102768e-06 4.15650602612145e-05 -8.76938032972833e-06 2.15813319963331e-05 -7.73273888367846e-06 -9.87802179927297e-06 1.52925253020295e-06 -8.76938032972833e-06 4.02807247542664e-05 -6.06159564173181e-06 3.40613925927499e-05 3.7947365204419e-05 -2.6207813292979e-06 2.15813319963331e-05 -6.06159564173181e-06 6.26060661801774e-05 2366 2391 0 147 0 2337 2362 0 170 0 0 0 0 0 0 0 0 0 437 0 268 288 0 0 2465 +430 426 0.996522770984078 0.0799740868277654 0.0233776035187408 0.00294209564577845 -0.0808393338538876 0.995973086697632 0.0387635482902558 0.00532349847491109 -0.0201833845594365 -0.0405185884509362 0.998974912086219 0.00898890352809293 6.95166379784497e-05 1.21645601976963e-05 -4.54642139315063e-06 1.28212761498552e-06 -6.43210723576157e-06 3.25118911827945e-05 1.21645601976963e-05 3.65696813956321e-05 -4.19841718942445e-06 1.91949757246159e-06 1.38433346258762e-06 2.39654328746432e-05 -4.54642139315063e-06 -4.19841718942445e-06 1.13890527990574e-05 3.11874022059394e-06 5.9497015649023e-07 7.55460511695152e-07 1.28212761498552e-06 1.91949757246159e-06 3.11874022059394e-06 2.76525895054074e-05 -2.25894026364312e-06 6.6261197017522e-06 -6.43210723576157e-06 1.38433346258762e-06 5.9497015649023e-07 -2.25894026364312e-06 4.53993418899011e-05 -6.22362779264757e-07 3.25118911827945e-05 2.39654328746432e-05 7.55460511695152e-07 6.6261197017522e-06 -6.22362779264757e-07 6.7514790005569e-05 2057 2080 0 147 0 2038 2061 0 167 0 0 0 0 0 0 0 0 0 436 0 169 180 0 0 2196 +430 393 0.996284760499504 0.0806673033938135 0.0301572903228467 0.00580683547935212 -0.0817263907999131 0.996014844884121 0.0357103040771183 0.0126961710843565 -0.0271564549097613 -0.0380422782392277 0.998907058751265 0.0221249735895477 7.45470174807219e-05 2.18429989219604e-05 -3.13379978466012e-06 9.04410329412599e-06 -9.59575803402906e-06 4.73318970356582e-05 2.18429989219604e-05 3.83885186037202e-05 -4.73649764794273e-06 6.76436829749541e-06 -1.2161470836697e-07 3.09014609947509e-05 -3.13379978466012e-06 -4.73649764794273e-06 9.39923235561859e-06 2.23556263698886e-06 3.096267161401e-06 -2.52353460776468e-06 9.04410329412599e-06 6.76436829749541e-06 2.23556263698886e-06 2.64819992356058e-05 -3.88893224939239e-07 1.74314536470979e-05 -9.59575803402906e-06 -1.2161470836697e-07 3.096267161401e-06 -3.88893224939239e-07 3.2778507862494e-05 -3.48306067870951e-06 4.73318970356582e-05 3.09014609947509e-05 -2.52353460776468e-06 1.74314536470979e-05 -3.48306067870951e-06 8.72792098679497e-05 2625 2649 0 148 0 2609 2633 0 169 0 0 0 0 0 0 0 0 0 246 0 171 166 0 0 2116 +430 372 0.99636710913805 0.0799031113020863 0.029463140228624 0.0107595505590281 -0.0809591898697845 0.996045741656253 0.0365853810158301 0.00284351246955948 -0.0264233495892049 -0.038837782283386 0.998896107342398 0.00443630405980798 5.37836932797342e-05 2.46037196719973e-05 -2.26321660606695e-06 1.50921734332225e-05 -8.42355733263954e-06 3.25435816788718e-05 2.46037196719973e-05 6.48312832400502e-05 -5.48319128163366e-06 1.70386084293169e-05 9.9158856665736e-06 3.21591932365951e-05 -2.26321660606695e-06 -5.48319128163366e-06 1.14263100287509e-05 1.74934828574738e-06 3.81587028561317e-06 -1.17153145458199e-06 1.50921734332225e-05 1.70386084293169e-05 1.74934828574738e-06 4.81995163771075e-05 -7.10231186575092e-06 1.92692641817012e-05 -8.42355733263954e-06 9.9158856665736e-06 3.81587028561317e-06 -7.10231186575092e-06 5.50628010588841e-05 -9.14028441491975e-06 3.25435816788718e-05 3.21591932365951e-05 -1.17153145458199e-06 1.92692641817012e-05 -9.14028441491975e-06 8.12315633954477e-05 1882 1908 0 147 0 1856 1882 0 168 0 0 0 0 0 0 0 0 0 455 0 264 265 0 0 2517 +426 428 0.999999347454 0.000241265763533391 -0.00111663888810002 -0.000797514262972996 -0.000240245363711121 0.999999553573166 0.000913857556624159 0.00341995880759272 0.00111685887214362 -0.00091358869297426 0.999998958990438 0.00311306731341007 2.60183690540333e-05 1.96890864084384e-05 -8.69132594144666e-06 7.4482648012082e-06 7.71255851523299e-06 1.8943808874057e-05 1.96890864084384e-05 2.35024135357923e-05 -9.21674151796535e-06 5.50570140413291e-06 3.41621273178007e-06 2.19866533485799e-05 -8.69132594144666e-06 -9.21674151796535e-06 1.34199882736809e-05 -6.40413338182507e-07 -2.48852259609336e-06 -4.06611542516486e-06 7.4482648012082e-06 5.50570140413291e-06 -6.40413338182507e-07 2.36084153167411e-05 5.27364469273646e-06 8.19630789474029e-06 7.71255851523299e-06 3.41621273178007e-06 -2.48852259609336e-06 5.27364469273646e-06 3.00169281726601e-05 4.17676131799904e-06 1.8943808874057e-05 2.19866533485799e-05 -4.06611542516486e-06 8.19630789474029e-06 4.17676131799904e-06 4.27126267851064e-05 2981 2975 0 16 52 3077 3123 0 42 44 0 0 0 0 0 25 57 0 642 0 29 29 0 0 2398 +427 429 0.999970022552118 -0.00759785910946343 0.00149215752181528 0.00471796687175022 0.00759281417127199 0.99996553583729 0.00335802182859173 -0.00405331244375852 -0.00151761987259581 -0.00334659148888997 0.999993248554873 -0.00241001667983748 3.81693728471089e-05 1.75218977424346e-05 -3.64342587448869e-06 3.42652612644728e-06 -2.75093510259414e-06 2.10068420734923e-05 1.75218977424346e-05 3.3307288741761e-05 -6.02369993968633e-06 7.71154579341215e-06 -1.18423245001577e-06 2.1364084550965e-05 -3.64342587448869e-06 -6.02369993968633e-06 1.11919601589715e-05 1.99679877506987e-06 1.46444893150801e-06 -4.56362180942204e-07 3.42652612644728e-06 7.71154579341215e-06 1.99679877506987e-06 2.67910573691338e-05 1.62714017471427e-07 3.24145834358238e-06 -2.75093510259414e-06 -1.18423245001577e-06 1.46444893150801e-06 1.62714017471427e-07 2.90558645884824e-05 -2.91974102081676e-06 2.10068420734923e-05 2.1364084550965e-05 -4.56362180942204e-07 3.24145834358238e-06 -2.91974102081676e-06 5.21244599459885e-05 2102 2098 0 2 72 2153 2182 0 40 66 0 0 0 0 0 32 64 0 617 0 29 26 0 0 2561 +430 373 0.996625635217787 0.0792995951621594 0.0211876717423271 0.0141955300095402 -0.0801139338560704 0.995948798572164 0.0408380732254644 -0.00969146053747902 -0.0178633935423301 -0.0423976984019279 0.998941106543009 0.00407757092043555 5.67792447793105e-05 2.56146514471555e-05 -2.2555282712572e-06 8.57978821716922e-06 -1.52278428850955e-05 2.27127136449211e-05 2.56146514471555e-05 5.76244462626934e-05 -7.46988056765911e-06 2.80633146379982e-05 -1.46565137556747e-05 2.35000117167993e-05 -2.2555282712572e-06 -7.46988056765911e-06 1.18084900717112e-05 9.75160896293692e-07 3.33584655360742e-06 -2.89661515775258e-07 8.57978821716922e-06 2.80633146379982e-05 9.75160896293692e-07 7.62452658070789e-05 -4.27636037617844e-05 1.33909720319755e-05 -1.52278428850955e-05 -1.46565137556747e-05 3.33584655360742e-06 -4.27636037617844e-05 7.25858472367171e-05 -1.35256088501116e-05 2.27127136449211e-05 2.35000117167993e-05 -2.89661515775258e-07 1.33909720319755e-05 -1.35256088501116e-05 5.75144363371668e-05 2056 2081 0 154 0 2027 2052 0 166 0 0 0 0 0 0 0 0 0 453 0 279 284 0 0 2454 +430 392 0.996358324351529 0.0801191950214241 0.0291719742995336 0.00881090237459076 -0.081066638992027 0.996165940367002 0.0328879810153114 0.00758766654215062 -0.0264251686456303 -0.0351330875649456 0.999033220979265 0.0289003269785222 5.74184772800964e-05 4.90370894463514e-05 -6.07053513869423e-07 2.61598936685412e-05 -1.12726721493121e-05 3.54601791282065e-05 4.90370894463514e-05 9.47714206647943e-05 -4.33380803726156e-06 3.93602459644969e-05 -1.49104112320054e-05 5.82264755418223e-05 -6.07053513869423e-07 -4.33380803726156e-06 1.09315266733743e-05 1.89967084556847e-06 3.95771462048268e-06 -2.2987602620968e-06 2.61598936685412e-05 3.93602459644969e-05 1.89967084556847e-06 5.14871162514566e-05 -1.39526706080759e-05 3.85712084530253e-05 -1.12726721493121e-05 -1.49104112320054e-05 3.95771462048268e-06 -1.39526706080759e-05 4.76059120915634e-05 -1.20503021508576e-05 3.54601791282065e-05 5.82264755418223e-05 -2.2987602620968e-06 3.85712084530253e-05 -1.20503021508576e-05 9.41852831973035e-05 2088 2112 0 150 0 2060 2085 0 166 0 0 0 0 0 0 0 0 0 244 0 268 275 0 0 2123 +430 428 0.996696071474781 0.07967899043167 0.0157543514791659 0.00036717650358408 -0.080293604165315 0.995832448073541 0.0432512715882671 0.00479312708071819 -0.0122424767462697 -0.044373346139864 0.998940002160024 0.00672875467091504 7.31657287109439e-05 4.37696771252811e-05 -3.87760987441701e-06 2.54876461187578e-05 -1.66352740304556e-05 5.22172500859892e-05 4.37696771252811e-05 7.17591706234805e-05 -5.97517375358442e-06 2.96560053297042e-05 -1.79908969415182e-05 6.08646763259988e-05 -3.87760987441701e-06 -5.97517375358442e-06 1.09252329071163e-05 4.83090622192406e-07 2.60590432063983e-06 -7.58655676724758e-07 2.54876461187578e-05 2.96560053297042e-05 4.83090622192406e-07 5.01082326464206e-05 -2.41751753694702e-05 3.5345236307399e-05 -1.66352740304556e-05 -1.79908969415182e-05 2.60590432063983e-06 -2.41751753694702e-05 5.51242538506376e-05 -2.23184869077081e-05 5.22172500859892e-05 6.08646763259988e-05 -7.58655676724758e-07 3.5345236307399e-05 -2.23184869077081e-05 9.9298147790699e-05 1982 2006 0 152 0 1954 1978 0 163 0 0 0 0 0 0 0 0 0 426 0 264 287 0 0 2460 +430 388 0.996576327039135 0.0791675529923135 0.0238353296263411 0.00762989541235576 -0.080015348172664 0.996106399432089 0.0370079054696077 -0.00224819970797624 -0.0208126990559719 -0.0387883947031751 0.999030676202866 0.0119767895893947 0.000138882481335499 0.000142556125869168 8.37122909554929e-07 4.59349042787663e-05 -3.51061540159929e-05 0.000144837754618415 0.000142556125869168 0.000213686141266853 -1.06808492626153e-06 6.92155796612664e-05 -4.88075915543019e-05 0.000194568842317009 8.37122909554929e-07 -1.06808492626153e-06 1.04940482718041e-05 3.24032472580714e-06 2.67343076761937e-06 2.68106323109897e-06 4.59349042787663e-05 6.92155796612664e-05 3.24032472580714e-06 6.53740322422002e-05 -3.64887338663767e-05 7.21044382347426e-05 -3.51061540159929e-05 -4.88075915543019e-05 2.67343076761937e-06 -3.64887338663767e-05 6.05101605899109e-05 -5.4663572440564e-05 0.000144837754618415 0.000194568842317009 2.68106323109897e-06 7.21044382347426e-05 -5.4663572440564e-05 0.000223373800093636 2180 2206 0 153 0 2152 2178 0 170 0 0 0 0 0 0 0 0 0 446 0 274 281 0 0 2388 +430 380 0.996398154052147 0.0796854254685958 0.0289991649769818 0.0183321270677616 -0.0807588027673213 0.996011174399684 0.0379441200523918 -0.00732848927564991 -0.0258598990149275 -0.0401493890221293 0.998858995146005 0.00739534163164593 7.93713038980572e-05 6.05749707801503e-05 -2.59889579306416e-06 -6.05407515973012e-06 1.53320705111336e-05 6.53823198792238e-05 6.05749707801503e-05 7.14397717327913e-05 -7.44677150667754e-06 4.44661575241984e-06 2.94716881060521e-06 5.81767018377592e-05 -2.59889579306416e-06 -7.44677150667754e-06 1.12898373042816e-05 1.33661052127493e-06 1.45885815556536e-06 -2.01751362531863e-06 -6.05407515973012e-06 4.44661575241984e-06 1.33661052127493e-06 6.86899893228836e-05 -4.26088435362877e-05 -7.38319617321608e-06 1.53320705111336e-05 2.94716881060521e-06 1.45885815556536e-06 -4.26088435362877e-05 6.63471824444695e-05 1.91594505774791e-05 6.53823198792238e-05 5.81767018377592e-05 -2.01751362531863e-06 -7.38319617321608e-06 1.91594505774791e-05 0.000105559779795585 2092 2119 0 151 0 2064 2091 0 169 0 0 0 0 0 0 0 0 0 439 0 264 264 0 0 2493 +430 389 0.996517001124363 0.0797617777162739 0.0243295147022175 0.00608828258194522 -0.0806817302278059 0.995956172521538 0.0395191197231952 0.00450567547482025 -0.0210790150992227 -0.0413444220154109 0.998922576524657 0.00951186029501525 4.88417037855483e-05 9.79257136647879e-06 -1.02898252114006e-06 6.32114674023409e-07 -2.43214659108878e-06 2.3715796492656e-05 9.79257136647879e-06 3.02681895801685e-05 -4.48757590088579e-06 1.23886204137199e-06 -3.85257155237387e-07 1.73697050947902e-05 -1.02898252114006e-06 -4.48757590088579e-06 1.04351663575864e-05 4.39936163970909e-06 2.45044168754127e-06 -1.69589675140281e-06 6.32114674023409e-07 1.23886204137199e-06 4.39936163970909e-06 2.74705039749415e-05 -5.25897535008396e-06 8.29585807236989e-06 -2.43214659108878e-06 -3.85257155237387e-07 2.45044168754127e-06 -5.25897535008396e-06 3.672515536187e-05 -5.56226402822106e-06 2.3715796492656e-05 1.73697050947902e-05 -1.69589675140281e-06 8.29585807236989e-06 -5.56226402822106e-06 5.39061888964193e-05 2661 2685 0 150 0 2646 2670 0 169 0 0 0 0 0 0 0 0 0 309 0 175 167 0 0 2295 +430 391 0.996239345899159 0.0802470331831537 0.0326738327674805 0.0129622299944545 -0.0812469469130182 0.996226642949175 0.0305190022040253 0.00447381673504397 -0.0301014833476467 -0.0330588799495375 0.999000005583961 0.0248084186191351 5.81809989622667e-05 4.09890473040648e-05 2.59536871154145e-06 7.84602095625281e-06 3.19454282152827e-06 3.56504025450589e-05 4.09890473040648e-05 6.71356540194235e-05 -3.0779598068787e-06 1.48090595548565e-05 -2.63430265440397e-06 4.69945836163409e-05 2.59536871154145e-06 -3.0779598068787e-06 1.12871829217422e-05 1.97096137808607e-06 4.0461756235958e-06 -1.71867641032388e-06 7.84602095625281e-06 1.48090595548565e-05 1.97096137808607e-06 3.49247253987312e-05 -6.05559557806995e-06 1.67899168526869e-05 3.19454282152827e-06 -2.63430265440397e-06 4.0461756235958e-06 -6.05559557806995e-06 3.03720087504512e-05 2.75210276563619e-06 3.56504025450589e-05 4.69945836163409e-05 -1.71867641032388e-06 1.67899168526869e-05 2.75210276563619e-06 0.000103993283424719 2346 2369 0 145 0 2319 2342 0 166 0 0 0 0 0 0 0 0 0 219 0 261 263 0 0 2233 +430 379 0.996576459608043 0.0793568357197341 0.0231916532323443 0.0177855260309423 -0.0802202691615427 0.996012651391809 0.0390321237330103 -0.0116576003614705 -0.0200017141952338 -0.0407589363454263 0.998968788570114 0.00630736678471619 4.47031343182246e-05 1.82010339131904e-05 -1.46977395374328e-06 1.29467289499088e-05 -9.24067251805252e-06 1.58151191564769e-05 1.82010339131904e-05 5.05841039495245e-05 -5.6788150104556e-06 1.72144749371223e-05 4.98897698610733e-06 1.7765388815174e-05 -1.46977395374328e-06 -5.6788150104556e-06 1.11887511007052e-05 2.00363704126654e-06 4.10259012666493e-06 -6.12953321148601e-07 1.29467289499088e-05 1.72144749371223e-05 2.00363704126654e-06 6.53021130370676e-05 -2.24624247614704e-05 1.44414324863724e-05 -9.24067251805252e-06 4.98897698610733e-06 4.10259012666493e-06 -2.24624247614704e-05 5.5514679860513e-05 -6.22169107316444e-06 1.58151191564769e-05 1.7765388815174e-05 -6.12953321148601e-07 1.44414324863724e-05 -6.22169107316444e-06 6.00899130357175e-05 1582 1607 0 155 0 1550 1575 0 174 0 0 0 0 0 0 0 0 0 438 0 276 275 0 0 2608 +430 390 0.996430990166474 0.0802865068957694 0.0260645093246872 0.00931737646231753 -0.0811817042569886 0.996073119608553 0.0353252216867305 0.00798966224681893 -0.0231260184595611 -0.0373151069107593 0.999035920308397 0.0201115494903351 4.37847804497489e-05 1.38421637532379e-05 4.25712005971467e-07 9.45075703548825e-06 3.69000560981584e-06 2.11554088251145e-05 1.38421637532379e-05 4.400889578212e-05 -5.19099799019043e-06 1.3308581012009e-05 9.51512085173515e-06 3.34620235285711e-05 4.25712005971467e-07 -5.19099799019043e-06 1.2053810176746e-05 3.57180438791144e-06 2.03910311973819e-06 -3.34246888958975e-06 9.45075703548825e-06 1.3308581012009e-05 3.57180438791144e-06 3.67909508053479e-05 1.37954464597633e-06 2.62785417596891e-05 3.69000560981584e-06 9.51512085173515e-06 2.03910311973819e-06 1.37954464597633e-06 4.6377838580836e-05 1.63199779187028e-05 2.11554088251145e-05 3.34620235285711e-05 -3.34246888958975e-06 2.62785417596891e-05 1.63199779187028e-05 8.60147690377138e-05 2115 2141 0 151 0 2096 2122 0 166 0 0 0 0 0 0 0 0 0 219 0 176 166 0 0 2302 +430 387 0.996442995562683 0.0796188952821736 0.0276077544924195 0.0120116807114803 -0.0806892974545622 0.995932041091385 0.0401074407540068 0.00303277789471882 -0.0243021371561559 -0.0421924287235667 0.998813899126384 0.00654817708402497 8.55516530445599e-05 3.7595063014777e-05 -5.88739524365194e-06 6.33679572851709e-06 3.44722626904881e-06 4.81596692671873e-05 3.7595063014777e-05 5.34758753342888e-05 -1.05511976817657e-05 7.95836853472198e-06 1.10197634991704e-05 4.09773639974299e-05 -5.88739524365194e-06 -1.05511976817657e-05 1.23413064275586e-05 -8.17634321695543e-07 4.56036569939081e-07 -3.92054792838533e-06 6.33679572851709e-06 7.95836853472198e-06 -8.17634321695543e-07 3.97485602854116e-05 -8.9922029124356e-06 7.39823083289139e-06 3.44722626904881e-06 1.10197634991704e-05 4.56036569939081e-07 -8.9922029124356e-06 4.78724918333262e-05 7.89733572668217e-06 4.81596692671873e-05 4.09773639974299e-05 -3.92054792838533e-06 7.39823083289139e-06 7.89733572668217e-06 8.00722896327736e-05 2101 2125 0 153 0 2075 2099 0 164 0 0 0 0 0 0 0 0 0 439 0 262 263 0 0 2501 +430 385 0.996675545059584 0.0796522014804206 0.0171284756912135 0.00135676669592758 -0.0803290389245752 0.995825960079953 0.0433347751383705 0.00733733984665753 -0.0136052705094786 -0.044566624621588 0.998913766340319 0.00427895577036842 8.12901351862491e-05 3.99741019379774e-05 -1.47339070625346e-06 1.62252358981355e-05 -1.81312599355342e-05 5.44522373840792e-05 3.99741019379774e-05 6.45568996989382e-05 -5.23099223245744e-06 1.78487156816377e-05 -1.03999151265194e-05 4.77935313339831e-05 -1.47339070625346e-06 -5.23099223245744e-06 1.11674501653685e-05 9.55674659089272e-07 2.02102415755905e-06 -5.91463706618593e-07 1.62252358981355e-05 1.78487156816377e-05 9.55674659089272e-07 3.77051968215448e-05 -1.13824584120989e-05 2.14222128367763e-05 -1.81312599355342e-05 -1.03999151265194e-05 2.02102415755905e-06 -1.13824584120989e-05 4.31464161063367e-05 -1.84954468311996e-05 5.44522373840792e-05 4.77935313339831e-05 -5.91463706618593e-07 2.14222128367763e-05 -1.84954468311996e-05 8.76184093200096e-05 2308 2329 0 141 0 2279 2300 0 164 0 0 0 0 0 0 0 0 0 438 0 270 277 0 0 2454 +430 394 0.996361394083298 0.0797287072706505 0.0301215141939711 0.00579292251028901 -0.0808357918704952 0.996020945032681 0.0375213513732622 0.00903801973997484 -0.0270101301932564 -0.0398197224143608 0.99884175051596 0.0167400868971978 7.50499531720047e-05 2.23528920968594e-05 2.24771303314097e-06 -4.98116047734936e-07 -2.06036446742521e-06 3.53226876767496e-05 2.23528920968594e-05 3.95385135337544e-05 -3.21062600578956e-07 4.3800471118486e-07 5.1519420781278e-06 2.32613183086572e-05 2.24771303314097e-06 -3.21062600578956e-07 1.10253087448501e-05 2.61534745509645e-06 3.11997495180242e-06 2.50976012497916e-06 -4.98116047734936e-07 4.3800471118486e-07 2.61534745509645e-06 3.379198138685e-05 -1.37977017381411e-05 6.28005997057592e-06 -2.06036446742521e-06 5.1519420781278e-06 3.11997495180242e-06 -1.37977017381411e-05 5.12093729208288e-05 -2.14582072427539e-06 3.53226876767496e-05 2.32613183086572e-05 2.50976012497916e-06 6.28005997057592e-06 -2.14582072427539e-06 7.4771264309611e-05 2468 2493 0 146 0 2442 2467 0 164 0 0 0 0 0 0 0 0 0 263 0 200 199 0 0 2240 +430 371 0.996381548887229 0.0794241545110292 0.0302590931340281 0.00861744427405065 -0.0806588544589358 0.99585483955708 0.0420391214003656 0.00938922942492476 -0.0267947426645198 -0.0443276686839115 0.998657648823956 -0.00149845585127324 7.49467037416066e-05 3.55498914080148e-05 -6.9951141185613e-06 1.42489990154279e-06 8.16119446878039e-06 2.93811252430654e-05 3.55498914080148e-05 5.37802307758036e-05 -7.5224309509532e-06 6.76833031314217e-06 3.75409964112369e-06 1.16380724887395e-05 -6.9951141185613e-06 -7.5224309509532e-06 1.15587919111673e-05 1.29205019755766e-06 2.47004621632836e-06 -2.46741236649212e-06 1.42489990154279e-06 6.76833031314217e-06 1.29205019755766e-06 3.50831316076094e-05 -1.4780374311404e-06 1.7750312891098e-06 8.16119446878039e-06 3.75409964112369e-06 2.47004621632836e-06 -1.4780374311404e-06 3.84414480647957e-05 -1.49980910111864e-06 2.93811252430654e-05 1.16380724887395e-05 -2.46741236649212e-06 1.7750312891098e-06 -1.49980910111864e-06 5.97695020465116e-05 1920 1942 0 143 0 1893 1915 0 160 0 0 0 0 0 0 0 0 0 445 0 265 266 0 0 2235 +430 378 0.996486663327674 0.079253987141357 0.0270764719318577 0.0149440324004152 -0.0802033814778794 0.996128639668697 0.0359882040577757 -0.00545815505670127 -0.0241194404908736 -0.0380333899881143 0.998985342152936 0.00989146407254027 4.94546671365471e-05 2.16019487887335e-05 -8.17329718248987e-07 3.41738146794077e-06 5.14285241815313e-07 2.34992839122951e-05 2.16019487887335e-05 3.21250417576381e-05 -7.05090059398687e-06 2.25768393468845e-06 -2.2824133346921e-06 1.30742451267674e-05 -8.17329718248987e-07 -7.05090059398687e-06 1.099251272003e-05 1.59627793671329e-06 2.98541457904281e-06 -3.8616930816882e-07 3.41738146794077e-06 2.25768393468845e-06 1.59627793671329e-06 5.52021367482854e-05 -2.96887418300224e-05 4.25919056504072e-06 5.14285241815313e-07 -2.2824133346921e-06 2.98541457904281e-06 -2.96887418300224e-05 6.08783317891258e-05 7.39233505540056e-06 2.34992839122951e-05 1.30742451267674e-05 -3.8616930816882e-07 4.25919056504072e-06 7.39233505540056e-06 5.38350658068647e-05 2503 2526 0 153 0 2476 2499 0 166 0 0 0 0 0 0 0 0 0 457 0 202 197 0 0 2637 +430 397 0.996453833230497 0.0799923832768724 0.0260955332947048 0.00589370350426188 -0.0809065949202202 0.996068027098809 0.0360916651029117 0.0060358007628104 -0.0231058680569353 -0.0380749787809696 0.999007715111432 0.0181653304779812 4.64437407112984e-05 2.81033661593679e-05 -1.98948638358052e-06 7.6956025568176e-06 -5.74637450552192e-06 4.00792782494229e-05 2.81033661593679e-05 4.19609225499462e-05 -3.89954748134538e-06 6.60017225237073e-06 -2.49826459125421e-06 4.07209955888739e-05 -1.98948638358052e-06 -3.89954748134538e-06 1.00722395601104e-05 4.3963892227754e-06 2.5120847071033e-06 3.41190596708239e-07 7.6956025568176e-06 6.60017225237073e-06 4.3963892227754e-06 2.36527676464123e-05 -2.52161707510788e-06 1.61098079413544e-05 -5.74637450552192e-06 -2.49826459125421e-06 2.5120847071033e-06 -2.52161707510788e-06 4.06802896075124e-05 -7.8134744246866e-06 4.00792782494229e-05 4.07209955888739e-05 3.41190596708239e-07 1.61098079413544e-05 -7.8134744246866e-06 8.87250439884698e-05 2597 2622 0 148 0 2580 2605 0 170 0 0 0 0 0 0 0 0 0 264 0 164 163 0 0 2268 +430 381 0.996570171852519 0.079749826884156 0.022087500668647 0.0117469563740438 -0.0805861416151655 0.995945083318197 0.0399908088676718 0.0003479736855342 -0.0188086776095722 -0.0416335937225856 0.998955893681158 0.0113872252116178 8.06368995734414e-05 6.01557077363966e-05 -5.18915052122062e-06 2.52949793873706e-05 -1.78103744275375e-05 6.76338942083247e-05 6.01557077363966e-05 7.86348411648269e-05 -1.00266869228463e-05 3.3248309686122e-05 -2.2278618849021e-05 7.02669072327509e-05 -5.18915052122062e-06 -1.00266869228463e-05 1.11872223215822e-05 3.86708184257704e-07 4.35797983211872e-06 -2.38725559920508e-06 2.52949793873706e-05 3.3248309686122e-05 3.86708184257704e-07 6.89488724888617e-05 -3.37775289545022e-05 3.62632138196875e-05 -1.78103744275375e-05 -2.2278618849021e-05 4.35797983211872e-06 -3.37775289545022e-05 5.64264978980709e-05 -2.03579885581695e-05 6.76338942083247e-05 7.02669072327509e-05 -2.38725559920508e-06 3.62632138196875e-05 -2.03579885581695e-05 0.000106964127571717 2299 2322 0 149 0 2271 2294 0 165 0 0 0 0 0 0 0 0 0 438 0 271 278 0 0 2581 +430 374 0.996572725092376 0.079220506169582 0.0238099769884715 0.0153541377783564 -0.0800757484087959 0.996086351021397 0.0374146472073254 -0.0134252918835488 -0.0207527858064294 -0.0391930186527222 0.999016130585568 0.00836867294398709 5.00447864175894e-05 1.7096845836237e-05 -7.59838302544338e-07 -3.63647827207579e-07 -2.94322747713637e-06 2.75646525001543e-05 1.7096845836237e-05 3.72037405855763e-05 -5.32777191239739e-06 7.32007862136967e-06 4.85199955244749e-06 2.22846302063983e-05 -7.59838302544338e-07 -5.32777191239739e-06 1.04588050133741e-05 7.22730308644928e-07 3.44222847865098e-06 -1.98489131650514e-06 -3.63647827207579e-07 7.32007862136967e-06 7.22730308644928e-07 4.80180140787533e-05 -1.1331887396866e-05 7.84851417950937e-06 -2.94322747713637e-06 4.85199955244749e-06 3.44222847865098e-06 -1.1331887396866e-05 5.37216088993753e-05 -6.61502102116204e-06 2.75646525001543e-05 2.22846302063983e-05 -1.98489131650514e-06 7.84851417950937e-06 -6.61502102116204e-06 7.12825058663288e-05 1942 1965 0 153 0 1917 1940 0 172 0 0 0 0 0 0 0 0 0 458 0 176 168 0 0 2540 +430 384 0.996534557658176 0.0792018222573469 0.025415482370794 0.0130731901681964 -0.0801163779194429 0.996089374018186 0.0372468113685998 -0.00266372327131374 -0.0223660765914257 -0.0391539310820086 0.9989828468491 0.00805474830748401 6.55260953904829e-05 2.57901187647868e-05 -4.78289244184866e-06 1.05298160435191e-05 -3.51930901764867e-06 3.52509468930813e-05 2.57901187647868e-05 5.00885129384913e-05 -7.27840427645095e-06 1.02002182122313e-05 5.21779793981708e-06 3.35358389295485e-05 -4.78289244184866e-06 -7.27840427645095e-06 1.08031283133639e-05 4.02664164735451e-07 4.08935165038884e-06 -3.54362484654555e-06 1.05298160435191e-05 1.02002182122313e-05 4.02664164735451e-07 4.12849944280278e-05 -1.56821746416407e-05 9.06218087959533e-06 -3.51930901764867e-06 5.21779793981708e-06 4.08935165038884e-06 -1.56821746416407e-05 5.30362404423191e-05 7.0603733986364e-07 3.52509468930813e-05 3.35358389295485e-05 -3.54362484654555e-06 9.06218087959533e-06 7.0603733986364e-07 7.50975400257618e-05 2103 2130 0 157 0 2076 2103 0 179 0 0 0 0 0 0 0 0 0 453 0 265 266 0 0 2675 +430 383 0.996572130944327 0.0793469872791682 0.0234103275244656 0.0107212068225465 -0.0802390055055745 0.995972528802708 0.0400052979718328 -0.00131249570448593 -0.0201417432353713 -0.041746586447975 0.998925188740069 0.00313762564531819 7.92425106797345e-05 6.32038641587373e-05 -4.36808507078713e-06 2.32036886215766e-05 -4.87333830110395e-06 6.85757304988034e-05 6.32038641587373e-05 8.90563935774503e-05 -7.80944086430758e-06 2.51792368367189e-05 -9.8264798763017e-06 6.99896471584144e-05 -4.36808507078713e-06 -7.80944086430758e-06 1.10306662286943e-05 1.6768989294882e-07 3.28163915488363e-06 -2.04354526208155e-06 2.32036886215766e-05 2.51792368367189e-05 1.6768989294882e-07 5.89885115234379e-05 -2.88249698289948e-05 3.14613515102155e-05 -4.87333830110395e-06 -9.8264798763017e-06 3.28163915488363e-06 -2.88249698289948e-05 5.94493861159184e-05 -1.44405594803052e-05 6.85757304988034e-05 6.99896471584144e-05 -2.04354526208155e-06 3.14613515102155e-05 -1.44405594803052e-05 0.000115501145735531 1591 1614 0 153 0 1558 1581 0 170 0 0 0 0 0 0 0 0 0 437 0 277 279 0 0 2502 +430 395 0.996256344146768 0.079936463420913 0.0329159317515521 0.0081720428494358 -0.0810834062130013 0.996088303703677 0.0351222502358392 0.0102318172003482 -0.0299796261519922 -0.0376597004832557 0.99884081262997 0.0180318210391868 9.80502576527065e-05 3.39052831118393e-05 -9.90936083683601e-07 -5.07321660150022e-07 -1.31296269859906e-05 5.69131461578504e-05 3.39052831118393e-05 6.19896945214533e-05 -3.67419050649715e-06 1.03547096330159e-05 5.31295372146411e-06 4.19106496356646e-05 -9.90936083683601e-07 -3.67419050649715e-06 1.17481915340455e-05 1.13730262421823e-06 3.76637699198932e-06 -1.5433409984821e-06 -5.07321660150022e-07 1.03547096330159e-05 1.13730262421823e-06 3.91652615278237e-05 -3.2365015330406e-06 1.25557517692484e-06 -1.31296269859906e-05 5.31295372146411e-06 3.76637699198932e-06 -3.2365015330406e-06 4.16216935882327e-05 4.17566991897465e-06 5.69131461578504e-05 4.19106496356646e-05 -1.5433409984821e-06 1.25557517692484e-06 4.17566991897465e-06 0.000100745964823866 2292 2318 0 153 0 2265 2291 0 171 0 0 0 0 0 0 0 0 0 245 0 253 256 0 0 2261 +430 396 0.99625023208866 0.0799976284554446 0.0329523065170769 0.00853057025936568 -0.0810753944950371 0.996168718008943 0.0327820937082097 0.00781763965577276 -0.0302035671860933 -0.0353307897155496 0.998919155801565 0.0205804421698073 7.77572277441651e-05 3.30021823160217e-05 -5.16080760353701e-06 3.83587933284862e-06 1.29071584415431e-06 3.95004781606002e-05 3.30021823160217e-05 5.04928134180513e-05 -6.8624302182071e-06 3.30107023035431e-06 2.33862191794801e-06 2.87245838865655e-05 -5.16080760353701e-06 -6.8624302182071e-06 1.22142798942941e-05 1.36197497497884e-06 4.29603203074798e-06 -1.81523660932094e-06 3.83587933284862e-06 3.30107023035431e-06 1.36197497497884e-06 4.01007643435372e-05 -1.64453108387948e-05 9.60355617333488e-06 1.29071584415431e-06 2.33862191794801e-06 4.29603203074798e-06 -1.64453108387948e-05 4.5249876682909e-05 3.61714190361906e-06 3.95004781606002e-05 2.87245838865655e-05 -1.81523660932094e-06 9.60355617333488e-06 3.61714190361906e-06 7.12637821556605e-05 2028 2053 0 155 0 2001 2026 0 166 0 0 0 0 0 0 0 0 0 257 0 199 199 0 0 2233 +430 399 0.996501547906887 0.0796587317915564 0.0252814451434222 0.00703150194765227 -0.080588736422621 0.996015609610928 0.0381884926800812 0.00389655651627606 -0.0221386671004445 -0.040092291786978 0.998950693256821 0.0121165950057098 0.000191009892120532 0.000128515710939719 -9.41508967525931e-06 5.35630333430229e-05 -4.05033195420281e-05 0.000212037269268557 0.000128515710939719 0.000116055377553928 -9.79929449554883e-06 3.76528594120239e-05 -2.03928774234157e-05 0.000164322300427088 -9.41508967525931e-06 -9.79929449554883e-06 1.08050261890145e-05 9.98292677760026e-07 2.4825450902749e-06 -8.23199093492405e-06 5.35630333430229e-05 3.76528594120239e-05 9.98292677760026e-07 4.14915309034576e-05 -1.62583664987514e-05 7.06153345032734e-05 -4.05033195420281e-05 -2.03928774234157e-05 2.4825450902749e-06 -1.62583664987514e-05 5.17793399861174e-05 -5.43357705432043e-05 0.000212037269268557 0.000164322300427088 -8.23199093492405e-06 7.06153345032734e-05 -5.43357705432043e-05 0.000301585955191583 2615 2637 0 150 0 2599 2621 0 166 0 0 0 0 0 0 0 0 0 288 0 166 164 0 0 2250 +430 386 0.996502202868919 0.0798924071491645 0.024506386051475 0.00681447609322133 -0.0807753811029526 0.996028594165757 0.0374483298941113 0.00399253579914403 -0.0214172240279774 -0.0392968559060079 0.998998027841316 0.00620839156879801 5.17280721136891e-05 2.93434068563769e-05 -3.0705533476901e-06 -5.85716721105824e-07 1.05887700164002e-05 3.45713565774634e-05 2.93434068563769e-05 4.31390491861864e-05 -6.19944289236574e-06 4.12304549016052e-06 9.13644071931148e-06 3.1168383687775e-05 -3.0705533476901e-06 -6.19944289236574e-06 1.08967944646871e-05 -1.41407345435849e-07 6.62991778575283e-07 -4.71386081451761e-06 -5.85716721105824e-07 4.12304549016052e-06 -1.41407345435849e-07 3.55977642084539e-05 -4.65658167951539e-06 4.77868525434424e-06 1.05887700164002e-05 9.13644071931148e-06 6.62991778575283e-07 -4.65658167951539e-06 4.05158269026422e-05 8.03433557459032e-06 3.45713565774634e-05 3.1168383687775e-05 -4.71386081451761e-06 4.77868525434424e-06 8.03433557459032e-06 7.49892235480037e-05 2558 2581 0 151 0 2533 2556 0 162 0 0 0 0 0 0 0 0 0 427 0 204 201 0 0 2535 +431 429 0.978632553012017 0.200950870523243 0.043555410928284 0.0139838538615199 -0.204537125369247 0.973082338649951 0.106185340575935 0.00704611629982555 -0.021044964501413 -0.112825129485826 0.993391966761178 0.0393319856491109 7.59760907673447e-05 4.02089612183802e-05 -3.4458987770609e-06 1.05318874915545e-05 -1.06797032125862e-06 4.40295564637347e-05 4.02089612183802e-05 5.28783324081853e-05 -3.51768873477771e-06 9.0283753360278e-06 -8.93474788968849e-07 2.87928198027595e-05 -3.4458987770609e-06 -3.51768873477771e-06 1.15501724738068e-05 -6.63826814007067e-07 3.90462268786862e-07 1.35298806329094e-06 1.05318874915545e-05 9.0283753360278e-06 -6.63826814007067e-07 3.73367605457398e-05 5.95432234699791e-06 8.59545617592644e-06 -1.06797032125862e-06 -8.93474788968849e-07 3.90462268786862e-07 5.95432234699791e-06 4.02933755774176e-05 -6.86856232012738e-06 4.40295564637347e-05 2.87928198027595e-05 1.35298806329094e-06 8.59545617592644e-06 -6.86856232012738e-06 7.01795853427329e-05 1801 1818 0 225 0 1779 1796 0 225 0 0 0 0 0 0 0 0 0 281 0 345 353 0 0 2535 +430 377 0.996524630266873 0.0799238516633903 0.0234699639275689 0.0121497179415667 -0.0808172480359705 0.995927297624134 0.0399673650242518 -0.00395236244777707 -0.0201800319961448 -0.0417252415496633 0.998925307781446 0.00853662922446585 6.00493769396913e-05 1.86869872621118e-05 -6.55710371765777e-07 5.85162556247504e-06 -9.98954829351948e-06 3.29381072013611e-05 1.86869872621118e-05 3.95331397336194e-05 -5.50888994512412e-06 1.31989253845055e-05 -3.48532647204033e-06 2.04538296775871e-05 -6.55710371765777e-07 -5.50888994512412e-06 1.01473952550992e-05 7.14996549680906e-07 3.87316670769563e-06 9.77762681993646e-09 5.85162556247504e-06 1.31989253845055e-05 7.14996549680906e-07 4.64894371800291e-05 -2.06433557788319e-05 5.91285497001515e-06 -9.98954829351948e-06 -3.48532647204033e-06 3.87316670769563e-06 -2.06433557788319e-05 5.35754303204187e-05 -1.97151077337098e-06 3.29381072013611e-05 2.04538296775871e-05 9.77762681993646e-09 5.91285497001515e-06 -1.97151077337098e-06 7.45670754208981e-05 2545 2571 0 152 0 2526 2552 0 170 0 0 0 0 0 0 0 0 0 432 0 174 168 0 0 2475 +430 376 0.996530784354759 0.0794862573795721 0.0246643613555391 0.0179883839982956 -0.0803959160649483 0.996023509152297 0.0383883562558031 -0.0110702037584886 -0.0215149369826169 -0.0402380926950209 0.998958459287923 0.00549514404522125 7.7694655069818e-05 4.05511044550606e-05 -4.3494596956726e-06 -2.50363478396111e-06 6.3590592072562e-06 4.28657283439824e-05 4.05511044550606e-05 6.6891409154219e-05 -6.15729807444898e-06 5.75010856271286e-06 1.20324676179909e-05 3.6041985100108e-05 -4.3494596956726e-06 -6.15729807444898e-06 1.11009694842136e-05 1.05959208094341e-06 3.01478483477182e-06 -2.66287368294778e-06 -2.50363478396111e-06 5.75010856271286e-06 1.05959208094341e-06 6.4336971848774e-05 -3.77258227434e-05 1.15240989219364e-05 6.3590592072562e-06 1.20324676179909e-05 3.01478483477182e-06 -3.77258227434e-05 6.87664397385797e-05 -4.97520814959497e-06 4.28657283439824e-05 3.6041985100108e-05 -2.66287368294778e-06 1.15240989219364e-05 -4.97520814959497e-06 7.61109392082791e-05 1436 1459 0 151 0 1409 1432 0 173 0 0 0 0 0 0 0 0 0 426 0 259 261 0 0 2422 +430 382 0.996567533670475 0.0800370544425915 0.0211475944282371 0.00560790650943065 -0.0808254041106823 0.995945023620911 0.0395065054780731 0.00391005217541393 -0.017899857102571 -0.0410801635938534 0.998995503130424 0.0123595589439768 5.55820368505322e-05 3.87327499098947e-05 -2.42036792025501e-06 1.33598612375367e-05 -5.37422980699331e-06 3.14918471841982e-05 3.87327499098947e-05 6.71568801292898e-05 -7.89043309451068e-06 1.94166746020961e-05 -1.05424054634209e-05 4.19131928312308e-05 -2.42036792025501e-06 -7.89043309451068e-06 1.13326375760816e-05 2.10940484806992e-06 2.82270452918802e-06 -1.54815664568366e-06 1.33598612375367e-05 1.94166746020961e-05 2.10940484806992e-06 4.10529372827363e-05 -1.34995382946945e-05 2.00067398677575e-05 -5.37422980699331e-06 -1.05424054634209e-05 2.82270452918802e-06 -1.34995382946945e-05 3.99017880852987e-05 -6.46231233553647e-06 3.14918471841982e-05 4.19131928312308e-05 -1.54815664568366e-06 2.00067398677575e-05 -6.46231233553647e-06 6.24907531862641e-05 2215 2239 0 148 0 2187 2211 0 165 0 0 0 0 0 0 0 0 0 457 0 273 280 0 0 2531 +431 380 0.97694558374866 0.208872879378757 0.0441525384776169 0.0238675095582876 -0.212444543781569 0.971577688751876 0.104422749135442 -8.99156661276759e-05 -0.021086541002046 -0.11139530950444 0.993552435862838 0.0366851512765747 7.78894434541648e-05 4.08531607964234e-05 -7.00951682542762e-06 2.43885662667371e-06 3.35756330543568e-06 4.42811541927333e-05 4.08531607964234e-05 4.07363489803325e-05 -8.89027924629065e-06 2.5312272781143e-06 -6.16821383430961e-07 2.40875351879499e-05 -7.00951682542762e-06 -8.89027924629065e-06 1.10044712936424e-05 5.94443508697177e-07 1.38181621775154e-06 -2.58153598432217e-06 2.43885662667371e-06 2.5312272781143e-06 5.94443508697177e-07 4.54294609427445e-05 -1.8547668232966e-05 1.55598096444046e-06 3.35756330543568e-06 -6.16821383430961e-07 1.38181621775154e-06 -1.8547668232966e-05 4.95496946332469e-05 8.75752258373719e-06 4.42811541927333e-05 2.40875351879499e-05 -2.58153598432217e-06 1.55598096444046e-06 8.75752258373719e-06 5.96603758419226e-05 1993 2009 0 235 0 1950 1966 0 235 0 0 0 0 0 0 0 0 0 279 0 527 528 0 0 2367 +431 393 0.975463718778798 0.21104110826834 0.0627071285190914 0.0272095884429654 -0.215924083318516 0.972672429399042 0.085353004223776 0.00976794385311765 -0.0429805024318846 -0.0967987381520882 0.994375522980562 0.0639075563069132 9.9226444970867e-05 8.8261322643175e-05 -2.56744026496571e-06 6.06459366595466e-05 -4.23344648940859e-05 7.1668300201478e-05 8.8261322643175e-05 0.000130220756206849 -1.12450068671034e-05 7.02685612080512e-05 -5.20858883988142e-05 7.98728843321965e-05 -2.56744026496571e-06 -1.12450068671034e-05 1.11258253942903e-05 -7.23245041586062e-07 5.7750757434239e-06 -3.61443962879654e-06 6.06459366595466e-05 7.02685612080512e-05 -7.23245041586062e-07 8.3474249805422e-05 -4.56987021604553e-05 6.32723314372626e-05 -4.23344648940859e-05 -5.20858883988142e-05 5.7750757434239e-06 -4.56987021604553e-05 7.91750409853625e-05 -3.37622676192463e-05 7.1668300201478e-05 7.98728843321965e-05 -3.61443962879654e-06 6.32723314372626e-05 -3.37622676192463e-05 0.000104174876812473 1935 1949 0 241 0 1944 1958 0 241 0 0 0 0 0 0 0 0 0 76 0 307 303 0 0 1971 +430 375 0.996608685293556 0.0794573425050602 0.0213929689263608 0.010962476844265 -0.080247541202046 0.996010369362593 0.0390342958591133 -0.00789707817002776 -0.0182060574665857 -0.0406186514328628 0.999008841115682 0.00967279697631353 0.000112511342462316 8.14257954511779e-05 -3.58111352158892e-06 4.63331428645922e-05 -5.41234225901651e-05 7.90588640945413e-05 8.14257954511779e-05 0.000113049368791915 -8.46766828697944e-06 5.19902390887146e-05 -5.17373696796971e-05 8.71000119410092e-05 -3.58111352158892e-06 -8.46766828697944e-06 1.13041994353416e-05 -7.00103737678479e-07 2.99616671769172e-06 -1.00130396647404e-06 4.63331428645922e-05 5.19902390887146e-05 -7.00103737678479e-07 7.3696493519615e-05 -5.28122610276389e-05 4.65511289166966e-05 -5.41234225901651e-05 -5.17373696796971e-05 2.99616671769172e-06 -5.28122610276389e-05 9.74215708286314e-05 -4.46891943789551e-05 7.90588640945413e-05 8.71000119410092e-05 -1.00130396647404e-06 4.65511289166966e-05 -4.46891943789551e-05 0.00011268684801127 2073 2096 0 150 0 2044 2067 0 172 0 0 0 0 0 0 0 0 0 452 0 280 284 0 0 2354 +430 370 0.99654204510844 0.0795357618070614 0.0240419409544775 0.012411975424734 -0.080461130472094 0.99594088855624 0.0403454208673105 0.000877392566784979 -0.0207354482527109 -0.0421403499698109 0.998896507196907 0.0132116426668755 0.000130084201559598 8.17391316784264e-05 -4.58076970181576e-06 3.68548654825854e-05 -4.74574908932307e-05 0.000101793692506416 8.17391316784264e-05 9.00214697152764e-05 -7.75126466480619e-06 3.67578094230947e-05 -4.01844211794508e-05 8.28308029744814e-05 -4.58076970181576e-06 -7.75126466480619e-06 1.12615889956655e-05 1.90599245170094e-06 5.43025760693974e-06 -2.46379599009636e-06 3.68548654825854e-05 3.67578094230947e-05 1.90599245170094e-06 5.26490643366088e-05 -2.41766476356605e-05 4.79270319458364e-05 -4.74574908932307e-05 -4.01844211794508e-05 5.43025760693974e-06 -2.41766476356605e-05 7.01719183028056e-05 -5.93068788476167e-05 0.000101793692506416 8.28308029744814e-05 -2.46379599009636e-06 4.79270319458364e-05 -5.93068788476167e-05 0.000142868631990505 2073 2095 0 149 0 2047 2069 0 170 0 0 0 0 0 0 0 0 0 436 0 269 277 0 0 2012 +431 427 0.977004787876257 0.208841703945996 0.0429742615969547 0.0161331245967517 -0.212265490978391 0.971706121139026 0.103588491062721 0.000884014526322685 -0.0201247560624573 -0.110328404474467 0.993691419586355 0.0369971602873074 7.97081138335758e-05 3.87475412995646e-05 -6.69587557683713e-06 1.95338325917755e-05 -1.32752235125147e-06 4.70887843399089e-05 3.87475412995646e-05 4.84548711326891e-05 -7.81996580863837e-06 1.7794429110935e-05 -3.21076411595223e-06 4.11966462790399e-05 -6.69587557683713e-06 -7.81996580863837e-06 1.13276229795444e-05 -1.83355909268573e-06 -9.09172529957169e-07 -2.70963911926462e-06 1.95338325917755e-05 1.7794429110935e-05 -1.83355909268573e-06 4.09346720791742e-05 6.34943824686703e-06 2.23625159805766e-05 -1.32752235125147e-06 -3.21076411595223e-06 -9.09172529957169e-07 6.34943824686703e-06 3.98817832412857e-05 -1.6159413108068e-06 4.70887843399089e-05 4.11966462790399e-05 -2.70963911926462e-06 2.23625159805766e-05 -1.6159413108068e-06 6.8126267054682e-05 1978 1992 0 235 0 1999 2013 0 235 0 0 0 0 0 0 0 0 0 278 0 385 405 0 0 2472 +431 385 0.977055235846779 0.209381933918576 0.0390163023992801 0.0138468944246478 -0.212416865187272 0.971338343804999 0.106681288135147 0.00976541099200606 -0.0155608961312497 -0.112521231786178 0.993527468623245 0.0345282116584057 6.72145678313303e-05 4.47867169397038e-05 -6.72110655197034e-06 2.20091306443471e-05 -6.20307676773615e-06 4.30827965470305e-05 4.47867169397038e-05 5.45559432547001e-05 -9.34632068760343e-06 2.08166326496116e-05 -8.06976913024955e-06 3.83981810028159e-05 -6.72110655197034e-06 -9.34632068760343e-06 1.13233608086849e-05 -1.58802928616673e-06 -4.84809915921692e-07 -3.59084106457637e-06 2.20091306443471e-05 2.08166326496116e-05 -1.58802928616673e-06 4.72178414297676e-05 -1.43313837037679e-05 1.94098765414465e-05 -6.20307676773615e-06 -8.06976913024955e-06 -4.84809915921692e-07 -1.43313837037679e-05 5.53878587238834e-05 -8.78079922426473e-07 4.30827965470305e-05 3.83981810028159e-05 -3.59084106457637e-06 1.94098765414465e-05 -8.78079922426473e-07 6.03219840199757e-05 1656 1660 0 221 0 1681 1685 0 221 0 0 0 0 0 0 0 0 0 272 0 389 397 0 0 2298 +431 373 0.97695581738017 0.209213674556059 0.0422725592529738 0.0268294049096374 -0.212575631799975 0.971541167857751 0.104495741168901 -0.0120876566784683 -0.0192075935995655 -0.111073838217413 0.993626524812903 0.0376187003469865 6.34893703961311e-05 2.93134648712924e-05 -3.78453785247582e-06 -1.32467413492677e-06 6.42633493952714e-06 3.01401915629795e-05 2.93134648712924e-05 5.24328923460547e-05 -6.79143949147262e-06 3.57803240568987e-06 1.37729449256692e-05 2.81094529820355e-05 -3.78453785247582e-06 -6.79143949147262e-06 1.10874682974294e-05 2.59539514118415e-06 1.01882831839454e-06 -2.04497795867049e-06 -1.32467413492677e-06 3.57803240568987e-06 2.59539514118415e-06 7.52964836316662e-05 -4.49898245959344e-05 4.20903113349742e-06 6.42633493952714e-06 1.37729449256692e-05 1.01882831839454e-06 -4.49898245959344e-05 8.43095994497825e-05 1.14906524176807e-05 3.01401915629795e-05 2.81094529820355e-05 -2.04497795867049e-06 4.20903113349742e-06 1.14906524176807e-05 5.49645530841975e-05 1576 1593 0 230 0 1589 1606 0 230 0 0 0 0 0 0 0 0 0 287 0 393 399 0 0 2333 +431 392 0.975712412437556 0.210314159215949 0.0612637139632687 0.0319578243797561 -0.215132908723639 0.972691401058505 0.0871164157374963 0.0044143427009295 -0.0412688720392407 -0.0981804091462767 0.994312570301954 0.0632358794176249 8.1707928819274e-05 5.01811529443483e-05 -9.64394439273328e-07 1.57757183573913e-05 -8.39671317144749e-06 5.26504122041491e-05 5.01811529443483e-05 5.5644154276163e-05 -7.24231398877012e-06 1.00250335042955e-05 -1.32964254755692e-05 4.05359113244278e-05 -9.64394439273328e-07 -7.24231398877012e-06 1.16884585030142e-05 1.29241123887404e-06 1.08539118543635e-06 -2.05564184935256e-06 1.57757183573913e-05 1.00250335042955e-05 1.29241123887404e-06 3.06024146866119e-05 -4.17907738125008e-06 1.25673239151287e-05 -8.39671317144749e-06 -1.32964254755692e-05 1.08539118543635e-06 -4.17907738125008e-06 5.07969103553187e-05 -4.06223311585902e-06 5.26504122041491e-05 4.05359113244278e-05 -2.05564184935256e-06 1.25673239151287e-05 -4.06223311585902e-06 7.83137277867938e-05 2145 2159 0 235 0 2130 2144 0 235 0 0 0 0 0 0 0 0 0 69 0 444 453 0 0 1906 +431 384 0.97699946926641 0.208810197040158 0.0432474122370793 0.0196020487801053 -0.212304497163084 0.971484736628039 0.105566126115721 0.00637512783855039 -0.0199709172919933 -0.112319669296168 0.993471415971147 0.0372441449935973 6.3795433991561e-05 3.62288959254311e-05 -4.74507889956821e-06 1.19753556397252e-05 -2.42183842185754e-06 3.79137464679638e-05 3.62288959254311e-05 4.01868448706648e-05 -7.87970940359507e-06 7.2438745507303e-06 -4.87246015442208e-06 2.8043151426876e-05 -4.74507889956821e-06 -7.87970940359507e-06 1.18946579429061e-05 1.27169067138897e-07 -7.61453343972503e-09 -2.18970489101766e-06 1.19753556397252e-05 7.2438745507303e-06 1.27169067138897e-07 3.98349129223715e-05 -7.30639214963939e-06 1.13293280211046e-05 -2.42183842185754e-06 -4.87246015442208e-06 -7.61453343972503e-09 -7.30639214963939e-06 4.25850180243764e-05 3.55138452104472e-06 3.79137464679638e-05 2.8043151426876e-05 -2.18970489101766e-06 1.13293280211046e-05 3.55138452104472e-06 4.98935010425726e-05 2084 2097 0 234 0 2041 2054 0 234 0 0 0 0 0 0 0 0 0 289 0 519 523 0 0 2402 +431 381 0.976876777689141 0.209582402674113 0.0422726590247858 0.0210857907131933 -0.212995610239231 0.971143244715209 0.107301762626875 0.00876326548512712 -0.0185642460255623 -0.113824490920726 0.993327415324947 0.0370497778240029 6.03433901452509e-05 3.81106935632765e-05 -7.57866080646874e-06 1.19160332985158e-05 2.68924051237897e-06 3.4876240994425e-05 3.81106935632765e-05 4.83148831792866e-05 -8.87800206775103e-06 1.3798205605228e-05 -4.24052556779101e-06 2.45855612913764e-05 -7.57866080646874e-06 -8.87800206775103e-06 1.09906150821925e-05 2.93369046109225e-07 1.22047033273118e-06 -1.96908514733121e-06 1.19160332985158e-05 1.3798205605228e-05 2.93369046109225e-07 3.86165214678137e-05 -5.19790652708213e-06 8.87918636534121e-06 2.68924051237897e-06 -4.24052556779101e-06 1.22047033273118e-06 -5.19790652708213e-06 3.71373244712211e-05 5.98085979886222e-06 3.4876240994425e-05 2.45855612913764e-05 -1.96908514733121e-06 8.87918636534121e-06 5.98085979886222e-06 4.94539909072459e-05 1812 1816 0 227 0 1835 1839 0 227 0 0 0 0 0 0 0 0 0 269 0 383 395 0 0 2419 +431 382 0.976767067942945 0.20953319930184 0.0449659134509479 0.0207154679858372 -0.213155514898435 0.971597907785419 0.102772720385219 0.00361266800698235 -0.0221544905273329 -0.109969741189706 0.993687996592564 0.0391790005459156 6.65320109209821e-05 3.94822702088626e-05 -7.27807575027827e-06 1.93696459106663e-05 -6.50649138847754e-06 3.89134511641682e-05 3.94822702088626e-05 4.19114708254594e-05 -9.32845016177848e-06 1.2082769130029e-05 -4.16314175300918e-06 2.93056241805539e-05 -7.27807575027827e-06 -9.32845016177848e-06 1.10254139508178e-05 6.07008392695168e-08 5.2571777703451e-07 -3.56836257015896e-06 1.93696459106663e-05 1.2082769130029e-05 6.07008392695168e-08 4.11383565088701e-05 -5.77480816638712e-06 1.45363286329619e-05 -6.50649138847754e-06 -4.16314175300918e-06 5.2571777703451e-07 -5.77480816638712e-06 5.05554450833933e-05 1.06279440202666e-06 3.89134511641682e-05 2.93056241805539e-05 -3.56836257015896e-06 1.45363286329619e-05 1.06279440202666e-06 4.98762807700247e-05 1850 1863 0 233 0 1874 1887 0 233 0 0 0 0 0 0 0 0 0 287 0 385 394 0 0 2406 +431 394 0.976650242771547 0.20961014397168 0.0470944884084048 0.0183529705337924 -0.213410807976851 0.971780158480749 0.100494530307861 0.00724849123683605 -0.0247008164428923 -0.108198480244879 0.993822397885937 0.0442909424941033 8.49140956584551e-05 4.63459050427007e-05 -1.43406204551451e-07 7.32221545236612e-06 -1.01536794559829e-05 6.09659900258519e-05 4.63459050427007e-05 5.6875037038451e-05 -3.91570492783989e-06 8.87990389727272e-06 -2.46900134572827e-06 4.76034790384791e-05 -1.43406204551451e-07 -3.91570492783989e-06 1.03843211217459e-05 3.87786855551565e-06 1.47809873962044e-06 -7.91385577745041e-07 7.32221545236612e-06 8.87990389727272e-06 3.87786855551565e-06 3.41983496709155e-05 -2.99003980108864e-06 1.00586526233433e-05 -1.01536794559829e-05 -2.46900134572827e-06 1.47809873962044e-06 -2.99003980108864e-06 5.38788257042127e-05 -2.74985681958901e-07 6.09659900258519e-05 4.76034790384791e-05 -7.91385577745041e-07 1.00586526233433e-05 -2.74985681958901e-07 8.94900174371998e-05 2012 2014 0 220 0 1982 1984 0 220 0 0 0 0 0 0 0 0 0 88 0 433 434 0 0 2043 +431 388 0.976792427182367 0.208865335160001 0.0474534083884452 0.0178315845098916 -0.212691939395314 0.972005458806706 0.0998375028044275 0.00053688776512275 -0.0252723785077684 -0.107613474149219 0.993871544549946 0.0431004832790857 0.000135853433740374 0.000107237298663408 -3.1280646989036e-06 3.66870881282252e-05 -2.99762448702371e-05 0.000114799558096223 0.000107237298663408 0.000121362899634267 -3.87991630951903e-06 3.90743774622982e-05 -3.05207673473152e-05 0.000108016327644617 -3.1280646989036e-06 -3.87991630951903e-06 1.06662804478384e-05 3.12298220725636e-07 2.24450211166422e-06 -1.9880527983028e-06 3.66870881282252e-05 3.90743774622982e-05 3.12298220725636e-07 5.47359930823605e-05 -1.48053570229469e-05 4.14930868714915e-05 -2.99762448702371e-05 -3.05207673473152e-05 2.24450211166422e-06 -1.48053570229469e-05 5.59496677688824e-05 -2.07192663835112e-05 0.000114799558096223 0.000108016327644617 -1.9880527983028e-06 4.14930868714915e-05 -2.07192663835112e-05 0.000136570989181282 1782 1792 0 235 0 1799 1809 0 234 0 0 0 0 0 0 0 0 0 280 0 388 398 0 0 2242 +431 383 0.976947095751559 0.209429267274526 0.0413975133486233 0.0160952339781104 -0.212730423269496 0.971283297277237 0.106557606231745 0.00715603557178776 -0.0178924318686874 -0.112907654475299 0.993444373099325 0.0352938537933898 4.75553200575792e-05 2.60696882106285e-05 -3.01174220911133e-06 5.49090267633394e-06 6.33148185881384e-07 2.4279027240912e-05 2.60696882106285e-05 4.14455412944917e-05 -5.66287918681522e-06 6.18982173512697e-06 -3.68236513928795e-08 1.9758554289872e-05 -3.01174220911133e-06 -5.66287918681522e-06 9.92515140059234e-06 1.52648190171052e-07 1.3462020927265e-06 -9.47972896604415e-08 5.49090267633394e-06 6.18982173512697e-06 1.52648190171052e-07 4.03497555916887e-05 -1.47226904775211e-06 7.85244092693283e-06 6.33148185881384e-07 -3.68236513928795e-08 1.3462020927265e-06 -1.47226904775211e-06 3.21412996514434e-05 7.07114793507907e-06 2.4279027240912e-05 1.9758554289872e-05 -9.47972896604415e-08 7.85244092693283e-06 7.07114793507907e-06 4.55156691274401e-05 2073 2085 0 232 0 2029 2041 0 232 0 0 0 0 0 0 0 0 0 263 0 517 522 0 0 2334 +431 387 0.976965990765086 0.209416035074065 0.0410167909794386 0.0194412914766688 -0.212648508158415 0.971458935950495 0.105110169536221 0.00929845176754328 -0.017834373170751 -0.111411220331664 0.993614349291422 0.0372648368986122 6.55263300020411e-05 4.15663043728009e-05 -5.90869494435169e-06 1.45319894168906e-05 -1.32162957498998e-06 4.04932385204162e-05 4.15663043728009e-05 4.38267007151464e-05 -7.13868707413062e-06 1.31904424137466e-05 -3.23997121461896e-06 2.83811345565813e-05 -5.90869494435169e-06 -7.13868707413062e-06 1.0191966856685e-05 9.88031771646557e-08 -9.4207702312111e-08 -2.3007332692182e-06 1.45319894168906e-05 1.31904424137466e-05 9.88031771646557e-08 3.69570383471865e-05 -6.31785690669143e-06 8.44570872280777e-06 -1.32162957498998e-06 -3.23997121461896e-06 -9.4207702312111e-08 -6.31785690669143e-06 4.56137655383427e-05 3.79468804481916e-06 4.04932385204162e-05 2.83811345565813e-05 -2.3007332692182e-06 8.44570872280777e-06 3.79468804481916e-06 5.80205309913144e-05 2034 2048 0 237 0 1990 2004 0 237 0 0 0 0 0 0 0 0 0 268 0 515 518 0 0 2337 +431 390 0.976230672270617 0.210183481395124 0.052882687778557 0.0266558952879905 -0.214389427389963 0.972276231310876 0.0933600741822982 0.00804545869342935 -0.0317938349599826 -0.102478457133907 0.994226995148488 0.0554797886570903 6.35711673877245e-05 2.46189923742791e-05 -4.77374594858663e-06 6.73705687626884e-06 8.22875887441309e-07 2.45111178776942e-05 2.46189923742791e-05 3.88880917165592e-05 -7.3207666396084e-06 9.9669883856308e-06 -5.90174537266684e-06 2.29385408803978e-05 -4.77374594858663e-06 -7.3207666396084e-06 1.04649063020178e-05 2.01713512155828e-06 2.71743118413355e-06 -4.52555905213894e-06 6.73705687626884e-06 9.9669883856308e-06 2.01713512155828e-06 5.10294250650977e-05 -2.69995663929686e-06 2.12844955068476e-05 8.22875887441309e-07 -5.90174537266684e-06 2.71743118413355e-06 -2.69995663929686e-06 4.52416638185259e-05 9.4226245192415e-06 2.45111178776942e-05 2.29385408803978e-05 -4.52555905213894e-06 2.12844955068476e-05 9.4226245192415e-06 5.48036035716043e-05 1769 1779 0 225 0 1777 1787 0 225 0 0 0 0 0 0 0 0 0 48 0 311 304 0 0 2115 +431 379 0.976913181956873 0.209310056846235 0.0427777397944769 0.0259445116718673 -0.212712574744301 0.971592497310866 0.103737070109413 -0.00339195212292346 -0.0198493189945671 -0.110441474420895 0.993684399225021 0.0375312823742944 7.07024952960119e-05 3.21054130915388e-05 -7.16210978696604e-06 3.37112509226245e-07 5.36592747219167e-06 3.39882150978649e-05 3.21054130915388e-05 5.10010137508645e-05 -6.07484722707921e-06 5.82573538805034e-06 4.48215307798348e-06 2.5905354776993e-05 -7.16210978696604e-06 -6.07484722707921e-06 1.1304911722432e-05 9.52452944697306e-07 2.70369420245057e-06 -2.66270878174559e-06 3.37112509226245e-07 5.82573538805034e-06 9.52452944697306e-07 5.67146394712911e-05 -2.03977730154044e-05 1.20192078353349e-05 5.36592747219167e-06 4.48215307798348e-06 2.70369420245057e-06 -2.03977730154044e-05 4.2359313800861e-05 2.31863996417178e-06 3.39882150978649e-05 2.5905354776993e-05 -2.66270878174559e-06 1.20192078353349e-05 2.31863996417178e-06 5.46397174217998e-05 2157 2167 0 231 0 2113 2123 0 231 0 0 0 0 0 0 0 0 0 278 0 531 533 0 0 2374 +431 391 0.976078093738294 0.209750366532698 0.0572393104746834 0.0269028589509795 -0.214257284974103 0.972689094723168 0.0892734050103994 0.00297637911240655 -0.0369509236656449 -0.0994017542401727 0.994361061433035 0.0599872516386977 0.000104756818557783 3.6416197793686e-05 -4.35579862911626e-06 1.56353001945165e-05 -3.3994310196646e-06 6.36253201338777e-05 3.6416197793686e-05 5.05637104633691e-05 -7.47203432977178e-06 1.05035929435573e-05 -1.88550193269575e-06 4.58007720723663e-05 -4.35579862911626e-06 -7.47203432977178e-06 1.03549197391852e-05 9.01036267734069e-07 3.58112007940557e-06 -5.65781900415754e-06 1.56353001945165e-05 1.05035929435573e-05 9.01036267734069e-07 3.13435033585738e-05 5.17284388365454e-06 1.83399036480271e-05 -3.3994310196646e-06 -1.88550193269575e-06 3.58112007940557e-06 5.17284388365454e-06 4.1752862786253e-05 3.46569911164094e-06 6.36253201338777e-05 4.58007720723663e-05 -5.65781900415754e-06 1.83399036480271e-05 3.46569911164094e-06 9.58067287361602e-05 2145 2150 0 223 0 2098 2103 0 223 0 0 0 0 0 0 0 0 0 50 0 523 528 0 0 2050 +431 428 0.976941543489001 0.208988235119446 0.0436936858938203 0.0162087313446107 -0.212472408727944 0.971753372294763 0.102717374202719 0.00230379303937871 -0.0209927638645782 -0.109632572784803 0.993750473131918 0.0395957171525924 8.52522892768734e-05 4.75539118169904e-05 -9.78799721002153e-06 1.82403160342631e-05 2.62483247113325e-06 5.32837412064129e-05 4.75539118169904e-05 5.41820204669406e-05 -1.02963839917367e-05 1.97169467798966e-05 1.03022699435365e-06 4.66702633189266e-05 -9.78799721002153e-06 -1.02963839917367e-05 1.28585544257354e-05 -2.74789885504705e-06 -4.0353172317639e-06 -5.62811591515352e-06 1.82403160342631e-05 1.97169467798966e-05 -2.74789885504705e-06 4.26917547430557e-05 9.48683755702065e-06 2.37181353933043e-05 2.62483247113325e-06 1.03022699435365e-06 -4.0353172317639e-06 9.48683755702065e-06 4.56265744932614e-05 3.33601431256691e-06 5.32837412064129e-05 4.66702633189266e-05 -5.62811591515352e-06 2.37181353933043e-05 3.33601431256691e-06 7.54418499059804e-05 1973 1980 0 220 0 1994 2001 0 220 0 0 0 0 0 0 0 0 0 270 0 385 408 0 0 2396 +431 372 0.976837153451439 0.208816861891147 0.046740708454446 0.0257568346496942 -0.212705421931797 0.971395934263724 0.105576239640945 0.00523144660831241 -0.0233576351051651 -0.113072795516162 0.993312118015508 0.0377145366020649 5.08823296979578e-05 2.64979753543745e-05 -4.36241243886615e-06 8.55932363326455e-06 -7.0720637052997e-06 3.33949373586376e-05 2.64979753543745e-05 3.65212455354503e-05 -6.77020395614841e-06 4.51085106615168e-06 1.02710924237559e-06 2.08523885913096e-05 -4.36241243886615e-06 -6.77020395614841e-06 1.18379159960674e-05 1.53370524020397e-06 1.3583659282747e-06 -9.18111611815839e-07 8.55932363326455e-06 4.51085106615168e-06 1.53370524020397e-06 4.35890125088397e-05 -6.47433675724277e-06 1.01815455627645e-05 -7.0720637052997e-06 1.02710924237559e-06 1.3583659282747e-06 -6.47433675724277e-06 5.03207535812808e-05 -9.3742238171449e-06 3.33949373586376e-05 2.08523885913096e-05 -9.18111611815839e-07 1.01815455627645e-05 -9.3742238171449e-06 5.24952998999909e-05 1777 1792 0 236 0 1733 1748 0 236 0 0 0 0 0 0 0 0 0 288 0 521 524 0 0 2347 +431 386 0.97713665498127 0.209446525517578 0.0365528444943549 0.0121908598912281 -0.212204753466758 0.971381567403098 0.106709854819571 0.0115883377337277 -0.0131567510475239 -0.112026797946365 0.993618083794653 0.0337366090651513 6.35645571954426e-05 3.62721578951799e-05 -4.54686451274886e-06 3.27011013232107e-06 4.85868856654527e-06 3.99998553645495e-05 3.62721578951799e-05 4.24128607862805e-05 -7.62428229010659e-06 9.62843225365148e-06 7.85485122597037e-06 2.6478407006225e-05 -4.54686451274886e-06 -7.62428229010659e-06 1.14374895707797e-05 -4.30470688747501e-07 1.1358553608566e-06 -1.52866853869705e-06 3.27011013232107e-06 9.62843225365148e-06 -4.30470688747501e-07 4.9563730728082e-05 -4.40661492150121e-06 -2.69024117992341e-06 4.85868856654527e-06 7.85485122597037e-06 1.1358553608566e-06 -4.40661492150121e-06 5.3208224627868e-05 1.58877627771545e-05 3.99998553645495e-05 2.6478407006225e-05 -1.52866853869705e-06 -2.69024117992341e-06 1.58877627771545e-05 5.61826177639372e-05 1948 1955 0 225 0 1919 1926 0 225 0 0 0 0 0 0 0 0 0 265 0 443 441 0 0 2364 +431 389 0.976838019115211 0.209443452327608 0.0438283548420764 0.0167517943976039 -0.212895962883358 0.971875707519781 0.100662396757144 0.00731634222247529 -0.0215126334751834 -0.107661736053335 0.993954806412718 0.0423430769895155 4.6015770563529e-05 2.51318918653724e-05 1.2626337308473e-08 7.4328631746666e-06 -6.94041094248657e-06 1.88888593866259e-05 2.51318918653724e-05 4.76326112939196e-05 -4.47526816984796e-06 1.09812036114959e-05 -1.17652182919808e-06 2.41669971040669e-05 1.2626337308473e-08 -4.47526816984796e-06 9.60883293639392e-06 2.01906188864665e-06 3.24432029621931e-06 6.27587923643029e-07 7.4328631746666e-06 1.09812036114959e-05 2.01906188864665e-06 3.29056663609434e-05 6.38476363269345e-06 8.84730793667877e-06 -6.94041094248657e-06 -1.17652182919808e-06 3.24432029621931e-06 6.38476363269345e-06 4.0575453404124e-05 4.48838359284565e-06 1.88888593866259e-05 2.41669971040669e-05 6.27587923643029e-07 8.84730793667877e-06 4.48838359284565e-06 4.33533551841774e-05 1739 1748 0 226 0 1718 1727 0 226 0 0 0 0 0 0 0 0 0 134 0 361 354 0 0 2175 +431 377 0.976842644511371 0.209407603270246 0.0438965096179836 0.0283225846022948 -0.212939201590231 0.971513338340129 0.104013123466863 -0.00606584561452717 -0.0208649057065988 -0.11095174230191 0.993606746449532 0.0410449125164666 7.49313746690478e-05 3.96967053028497e-05 -5.52052452856752e-06 3.6130464904131e-06 2.37239469731264e-06 5.01642479329394e-05 3.96967053028497e-05 4.8734109531054e-05 -8.78964359415873e-06 6.03436725338086e-06 7.75962159195413e-07 2.54659406712603e-05 -5.52052452856752e-06 -8.78964359415873e-06 1.09070296720472e-05 1.81207114953738e-06 1.03126492575771e-06 -2.76702026891282e-06 3.6130464904131e-06 6.03436725338086e-06 1.81207114953738e-06 5.41849166144476e-05 -2.51226076997705e-05 8.6253870188647e-06 2.37239469731264e-06 7.75962159195413e-07 1.03126492575771e-06 -2.51226076997705e-05 6.00109203968846e-05 3.18578164044049e-06 5.01642479329394e-05 2.54659406712603e-05 -2.76702026891282e-06 8.6253870188647e-06 3.18578164044049e-06 7.41651754095324e-05 1729 1741 0 231 0 1713 1725 0 231 0 0 0 0 0 0 0 0 0 267 0 363 359 0 0 2327 +431 378 0.976954607018836 0.209172154887906 0.0425053578295965 0.0276679040838198 -0.212572956520727 0.971471297930021 0.105148730159703 -0.0018379517094265 -0.0192985486684662 -0.111761025933511 0.993547703485635 0.041129330905191 6.94353975579761e-05 3.87775930720675e-05 -7.60187504321299e-06 1.51679085009967e-06 9.21678336047431e-06 3.12966109309537e-05 3.87775930720675e-05 4.42264582230007e-05 -7.05622145849263e-06 5.5565324858007e-06 -1.44407140101746e-06 1.24543528825085e-05 -7.60187504321299e-06 -7.05622145849263e-06 1.10696067302245e-05 1.57947975118363e-06 -1.12572391399946e-06 -3.62455852516651e-06 1.51679085009967e-06 5.5565324858007e-06 1.57947975118363e-06 5.37258831724498e-05 -2.2707274023363e-05 1.57353914896371e-06 9.21678336047431e-06 -1.44407140101746e-06 -1.12572391399946e-06 -2.2707274023363e-05 5.40470762924225e-05 1.36421685266559e-05 3.12966109309537e-05 1.24543528825085e-05 -3.62455852516651e-06 1.57353914896371e-06 1.36421685266559e-05 4.91903672138078e-05 1867 1873 0 225 0 1837 1843 0 225 0 0 0 0 0 0 0 0 0 288 0 437 434 0 0 2389 +431 371 0.976699032604447 0.209322400953914 0.0473617162740868 0.0221688985288507 -0.213246769262263 0.971418815041319 0.104265532094394 0.00907506630717836 -0.0241829507865607 -0.111935777312747 0.993421142642256 0.0360907660992682 5.73754622931635e-05 2.83913934463532e-05 -5.29925600080232e-06 8.24847102688643e-06 1.98442593639369e-06 2.84503728915706e-05 2.83913934463532e-05 3.7149964108342e-05 -7.03066772166579e-06 3.53679807707427e-06 4.07141230525681e-06 1.22274660926176e-05 -5.29925600080232e-06 -7.03066772166579e-06 1.12710749160672e-05 1.92664314839819e-06 -2.77975861253034e-07 -2.14344286355073e-06 8.24847102688643e-06 3.53679807707427e-06 1.92664314839819e-06 3.63938270499456e-05 2.75250920687596e-07 5.68853007159094e-06 1.98442593639369e-06 4.07141230525681e-06 -2.77975861253034e-07 2.75250920687596e-07 3.67760415579892e-05 1.76323507745494e-06 2.84503728915706e-05 1.22274660926176e-05 -2.14344286355073e-06 5.68853007159094e-06 1.76323507745494e-06 5.32733069185392e-05 1752 1765 0 239 0 1707 1720 0 239 0 0 0 0 0 0 0 0 0 284 0 517 521 0 0 2089 +431 375 0.976853397856474 0.209054079801235 0.0453192102173023 0.0278655676538157 -0.212736269377923 0.971603189470326 0.103588232450669 -0.00930884337772794 -0.0223767465781961 -0.110831556560165 0.993587262037425 0.0399578900658593 8.71613514745103e-05 5.39857515666922e-05 -5.42541334497428e-06 1.78375850396249e-05 -2.88643909154873e-06 5.2392467262728e-05 5.39857515666922e-05 6.07577859017459e-05 -9.67613988767477e-06 1.02100166102692e-05 1.29700389296707e-06 4.55727103580933e-05 -5.42541334497428e-06 -9.67613988767477e-06 1.13726577422299e-05 1.29331891652579e-06 2.93836489902929e-07 -3.32247064241414e-06 1.78375850396249e-05 1.02100166102692e-05 1.29331891652579e-06 6.39116096915261e-05 -2.48865736000871e-05 1.77602710305754e-05 -2.88643909154873e-06 1.29700389296707e-06 2.93836489902929e-07 -2.48865736000871e-05 6.66560297918685e-05 9.3819523573068e-06 5.2392467262728e-05 4.55727103580933e-05 -3.32247064241414e-06 1.77602710305754e-05 9.3819523573068e-06 6.92952973587274e-05 1763 1771 0 226 0 1776 1784 0 226 0 0 0 0 0 0 0 0 0 291 0 393 398 0 0 2217 +432 338 0.949710731102959 0.248914197508143 -0.189976970990593 0.0461327367384962 -0.239136603313191 0.968227354143156 0.0731401096852728 0.0617529498306291 0.20214651167832 -0.0240314994917319 0.979060404085706 0.0144792192752348 6.15254829356099e-05 1.27155084201354e-06 -1.15741744082735e-06 1.00563306174215e-06 1.46261175718673e-06 8.92055367742773e-06 1.27155084201354e-06 3.97371056358311e-05 -3.51991925242038e-06 1.0578848618384e-05 -3.13138248516396e-06 5.28922608800306e-06 -1.15741744082735e-06 -3.51991925242038e-06 1.61039769619499e-05 1.08756898264561e-05 -2.16298527983361e-05 -1.51188653412334e-06 1.00563306174215e-06 1.0578848618384e-05 1.08756898264561e-05 0.00011668948228299 -0.000136415509385421 -3.45268240569152e-06 1.46261175718673e-06 -3.13138248516396e-06 -2.16298527983361e-05 -0.000136415509385421 0.000309729106741211 1.49355467295083e-05 8.92055367742773e-06 5.28922608800306e-06 -1.51188653412334e-06 -3.45268240569152e-06 1.49355467295083e-05 5.82010402751302e-05 1661 1646 0 52 0 1648 1633 0 52 0 0 0 0 0 0 0 0 0 379 0 428 425 0 0 1926 +431 395 0.976246042196862 0.210729651389597 0.0503654556236845 0.0216285522508424 -0.214528809468437 0.972703297343886 0.0884629032102544 0.00890138302497922 -0.0303488880029765 -0.0971664003735394 0.994805325496115 0.0569380065650797 7.98489039133266e-05 4.60003622380945e-05 -3.31108087885094e-06 1.47868523323039e-05 -9.62772775930502e-06 4.24361881953233e-05 4.60003622380945e-05 5.35458533945052e-05 -5.97543722810562e-06 1.48255594938395e-05 -8.35723431723729e-06 3.05482751553031e-05 -3.31108087885094e-06 -5.97543722810562e-06 1.04026181295157e-05 2.26782948860398e-06 2.67750871680722e-06 -4.71288852435411e-06 1.47868523323039e-05 1.48255594938395e-05 2.26782948860398e-06 3.61018431501378e-05 2.17060179840811e-06 1.57381972346758e-05 -9.62772775930502e-06 -8.35723431723729e-06 2.67750871680722e-06 2.17060179840811e-06 4.28387598767651e-05 3.78237555917845e-07 4.24361881953233e-05 3.05482751553031e-05 -4.71288852435411e-06 1.57381972346758e-05 3.78237555917845e-07 7.28431109341415e-05 1965 1979 0 233 0 1918 1932 0 231 0 0 0 0 0 0 0 0 0 88 0 517 523 0 0 2075 +431 397 0.976635292272833 0.20956232744879 0.0476144600032879 0.0204527631994456 -0.213419807461095 0.971777282556245 0.10050322826093 0.00741898249349056 -0.0252089601219005 -0.108316868593243 0.993796741948637 0.0424630344801693 9.15771982125121e-05 6.84269113839026e-05 -7.93494394421058e-06 2.09201508606679e-05 -5.66945227889998e-06 7.62266997503592e-05 6.84269113839026e-05 6.79019485418459e-05 -8.87703967110303e-06 1.76129524247378e-05 -7.69093415083952e-06 6.29155471128843e-05 -7.93494394421058e-06 -8.87703967110303e-06 1.1024490099962e-05 1.10432694758963e-06 1.65990595531032e-06 -5.79163201824626e-06 2.09201508606679e-05 1.76129524247378e-05 1.10432694758963e-06 3.45122417182242e-05 -4.6205306125938e-06 2.16509748247508e-05 -5.66945227889998e-06 -7.69093415083952e-06 1.65990595531032e-06 -4.6205306125938e-06 5.27209219080439e-05 -7.97741836919827e-07 7.62266997503592e-05 6.29155471128843e-05 -5.79163201824626e-06 2.16509748247508e-05 -7.97741836919827e-07 9.47122740139119e-05 1855 1867 0 227 0 1842 1854 0 227 0 0 0 0 0 0 0 0 0 95 0 329 330 0 0 2049 +431 374 0.976917497003779 0.209076183506396 0.0438104272778841 0.0321085972372866 -0.212543110045868 0.971883246283914 0.101333025044509 -0.0179473895083341 -0.0213922981444514 -0.108305609656383 0.993887450618559 0.0416841773853188 8.18136958314681e-05 4.57093457466042e-05 -7.75392925950048e-06 1.90488317069557e-05 -9.55620552034466e-06 4.44400143375921e-05 4.57093457466042e-05 4.81764026012635e-05 -9.11574682188434e-06 1.5736829043794e-05 -5.15302283925255e-06 3.01614260565938e-05 -7.75392925950048e-06 -9.11574682188434e-06 1.08498856940038e-05 -6.21392238240036e-07 2.22777142897446e-06 -3.36526739995792e-06 1.90488317069557e-05 1.5736829043794e-05 -6.21392238240036e-07 5.14264223660195e-05 -2.10994804971022e-05 1.61264986014898e-05 -9.55620552034466e-06 -5.15302283925255e-06 2.22777142897446e-06 -2.10994804971022e-05 5.70494179949449e-05 -8.2532477156464e-07 4.44400143375921e-05 3.01614260565938e-05 -3.36526739995792e-06 1.61264986014898e-05 -8.2532477156464e-07 6.1387562591677e-05 1821 1830 0 228 0 1811 1820 0 228 0 0 0 0 0 0 0 0 0 292 0 368 361 0 0 2340 +431 396 0.976459223869772 0.210126414725844 0.0487265220809575 0.0202964324622746 -0.213984496665485 0.972095098378215 0.0961340464968982 0.0119587432795817 -0.0271665107524359 -0.104297696731575 0.994175020381234 0.0511134894671303 0.000100430205323563 6.44391703518374e-05 -8.3501797923593e-07 1.87142715860021e-05 -1.86278859276256e-05 8.14472360516229e-05 6.44391703518374e-05 7.21851977764052e-05 -5.07027788597059e-06 1.5222794857111e-05 -1.080128505078e-05 6.70568005030955e-05 -8.3501797923593e-07 -5.07027788597059e-06 1.12128644443824e-05 3.59866189290221e-06 2.6524243166011e-06 -1.5182769699056e-06 1.87142715860021e-05 1.5222794857111e-05 3.59866189290221e-06 3.12168431157297e-05 -2.62372133879724e-06 2.14838934635665e-05 -1.86278859276256e-05 -1.080128505078e-05 2.6524243166011e-06 -2.62372133879724e-06 4.60630838833438e-05 -8.10391949032378e-06 8.14472360516229e-05 6.70568005030955e-05 -1.5182769699056e-06 2.14838934635665e-05 -8.10391949032378e-06 0.000108234114140037 2002 2016 0 239 0 1972 1986 0 239 0 0 0 0 0 0 0 0 0 92 0 428 431 0 0 2099 +432 340 0.938306279336313 0.299746467276422 -0.172433701791008 0.0563666328760188 -0.295277480522673 0.954015687645791 0.0516263229555467 0.0438307473595698 0.179979264511855 0.00247448601381286 0.98366729195635 0.0341706142733154 7.17766654326632e-05 5.71333390010651e-06 -3.83001362647899e-06 2.17451245838221e-05 -1.79938791203695e-05 1.32900073672979e-05 5.71333390010651e-06 7.97198809730518e-05 -9.0708269374989e-06 1.20962213689827e-05 2.78681518012148e-05 4.36440651675798e-05 -3.83001362647899e-06 -9.0708269374989e-06 1.5992017342253e-05 -2.82912010127226e-07 -6.88253826387908e-06 -4.40653211523426e-06 2.17451245838221e-05 1.20962213689827e-05 -2.82912010127226e-07 9.1923582265698e-05 -5.84166915885025e-05 7.7859133932944e-06 -1.79938791203695e-05 2.78681518012148e-05 -6.88253826387908e-06 -5.84166915885025e-05 0.000182164323171994 4.18294947385723e-05 1.32900073672979e-05 4.36440651675798e-05 -4.40653211523426e-06 7.7859133932944e-06 4.18294947385723e-05 0.000109967325382521 1813 1802 0 104 0 1800 1789 0 104 0 0 0 0 0 0 0 0 0 267 0 608 595 0 0 1785 +432 341 0.93058358252501 0.318169464521645 -0.181059072628045 0.0595683567709271 -0.31075438631433 0.948002700259504 0.0687211152928568 0.0392686822923891 0.193509450211927 -0.00768584066317106 0.981068305742255 0.0280400937301641 7.81070914160559e-05 2.68886960551934e-05 -1.21982054948536e-05 8.13056958041763e-06 1.57391878136754e-05 2.72940253103586e-05 2.68886960551934e-05 7.689212675035e-05 -7.85820312057869e-06 1.82001887093674e-05 2.45968198737983e-06 3.23938687859559e-05 -1.21982054948536e-05 -7.85820312057869e-06 1.81931934008937e-05 -5.48369698865101e-07 -6.71755352257453e-06 -3.3351470710516e-06 8.13056958041763e-06 1.82001887093674e-05 -5.48369698865101e-07 6.80168444033217e-05 -1.90284852008118e-05 1.92983589747769e-05 1.57391878136754e-05 2.45968198737983e-06 -6.71755352257453e-06 -1.90284852008118e-05 9.30300870529354e-05 -2.91635646694058e-07 2.72940253103586e-05 3.23938687859559e-05 -3.3351470710516e-06 1.92983589747769e-05 -2.91635646694058e-07 7.91778149305383e-05 1558 1552 0 119 0 1552 1546 0 119 0 0 0 0 0 0 0 0 0 208 0 561 557 0 0 1843 +431 376 0.976948562676929 0.209039934307454 0.0432875472649852 0.0274176458265752 -0.212486607240585 0.971712772788967 0.103071474919898 -0.00756778201895081 -0.0205170082338643 -0.109893553330089 0.99373158312978 0.041886098162862 5.92004011343634e-05 4.0466522714187e-05 -5.16169269242179e-06 1.56566815576679e-05 2.72717929093932e-06 3.46282752531603e-05 4.0466522714187e-05 5.74727272867994e-05 -7.54471069238207e-06 1.21695496103602e-05 4.10754297834412e-06 2.98815310124126e-05 -5.16169269242179e-06 -7.54471069238207e-06 1.02806144553439e-05 -4.37959803631576e-07 1.79711517370795e-06 -2.8356816865394e-06 1.56566815576679e-05 1.21695496103602e-05 -4.37959803631576e-07 5.5535855299974e-05 -2.31883218747853e-05 1.10061735128134e-05 2.72717929093932e-06 4.10754297834412e-06 1.79711517370795e-06 -2.31883218747853e-05 5.88522783479493e-05 1.74383810739336e-06 3.46282752531603e-05 2.98815310124126e-05 -2.8356816865394e-06 1.10061735128134e-05 1.74383810739336e-06 5.28847275836713e-05 1887 1896 0 227 0 1843 1852 0 227 0 0 0 0 0 0 0 0 0 263 0 535 540 0 0 2306 +432 380 0.938383795442986 0.345100163888277 0.0184859225980543 0.0437474692285442 -0.344429066719168 0.929489324952343 0.131978076962051 0.00671255011901079 0.0283631882724767 -0.130213177842806 0.991080247945189 0.0851429867920088 5.31887217904419e-05 2.07572555427367e-05 -6.01214376675676e-06 -2.65228733600743e-06 7.54394809366693e-06 1.60676433647843e-05 2.07572555427367e-05 3.90459778985746e-05 -6.80350274765132e-06 1.2756948465952e-06 9.67369293422128e-06 7.45404061771805e-06 -6.01214376675676e-06 -6.80350274765132e-06 1.1599129916217e-05 8.03046880233987e-07 1.31367113127994e-06 -7.58978365303456e-07 -2.65228733600743e-06 1.2756948465952e-06 8.03046880233987e-07 5.63041043956024e-05 -1.6080756717626e-05 3.77869888624462e-06 7.54394809366693e-06 9.67369293422128e-06 1.31367113127994e-06 -1.6080756717626e-05 5.93733667181776e-05 1.38045443428129e-05 1.60676433647843e-05 7.45404061771805e-06 -7.58978365303456e-07 3.77869888624462e-06 1.38045443428129e-05 4.19063179175869e-05 1819 1837 0 225 0 1802 1820 0 225 0 0 0 0 0 0 0 0 0 271 0 779 779 0 0 1797 +432 382 0.938253503351469 0.345550813167366 0.0165830928378208 0.0380476835618754 -0.344579513153306 0.929206125539054 0.133569964347268 0.0118877147276684 0.0307460983496485 -0.131036681047987 0.990900633593602 0.0826304824466661 5.59020051600415e-05 2.1478842868733e-05 -3.52549589131882e-06 4.24375534395696e-06 1.0725796870989e-06 2.58336165373187e-05 2.1478842868733e-05 3.62354874948729e-05 -6.74705218094498e-06 5.42358972243854e-06 -2.21439360146507e-06 1.83094521169425e-05 -3.52549589131882e-06 -6.74705218094498e-06 1.08920792683135e-05 3.34709935623896e-06 2.90160536596281e-06 -1.02302734755355e-06 4.24375534395696e-06 5.42358972243854e-06 3.34709935623896e-06 4.18647311769736e-05 2.67688662701956e-06 1.01169412912645e-05 1.0725796870989e-06 -2.21439360146507e-06 2.90160536596281e-06 2.67688662701956e-06 4.26602086292847e-05 4.44169037769921e-06 2.58336165373187e-05 1.83094521169425e-05 -1.02302734755355e-06 1.01169412912645e-05 4.44169037769921e-06 4.70989680160424e-05 1854 1871 0 224 0 1859 1876 0 224 0 0 0 0 0 0 0 0 0 281 0 607 616 0 0 1798 +432 393 0.937382001877075 0.347337665704853 0.0259138677088425 0.0408386532752912 -0.347843051158274 0.929727272398969 0.120881804745281 0.0324999971324649 0.017893974344166 -0.122326386933801 0.992328605222026 0.0970814275813365 8.82117930410252e-05 3.79404414625701e-05 -5.14890987957343e-06 1.11260078933699e-05 -7.06290615161885e-06 3.15239279070817e-05 3.79404414625701e-05 6.16475876678821e-05 -6.41524075659368e-06 2.10972586630753e-05 -8.09876565828516e-06 3.14469243582399e-05 -5.14890987957343e-06 -6.41524075659368e-06 1.35506225381637e-05 4.76389417523514e-06 3.06194084116166e-06 -5.63586263636166e-07 1.11260078933699e-05 2.10972586630753e-05 4.76389417523514e-06 5.3403891281648e-05 -1.14979419387769e-05 1.96548091189676e-05 -7.06290615161885e-06 -8.09876565828516e-06 3.06194084116166e-06 -1.14979419387769e-05 5.13818951365626e-05 1.75052831107598e-06 3.15239279070817e-05 3.14469243582399e-05 -5.63586263636166e-07 1.96548091189676e-05 1.75052831107598e-06 6.29130484732869e-05 1874 1891 0 228 0 1880 1897 0 228 0 0 0 0 0 0 0 0 0 75 0 477 473 0 0 1508 +432 373 0.938320581159614 0.34526466749744 0.0186224689599987 0.0436914368176662 -0.344659009599771 0.929650257685111 0.130232735852822 -0.000930182905189758 0.0276523791741107 -0.128618458099482 0.991308548415741 0.0868014542677831 4.636634467308e-05 6.24996692385123e-06 -2.84821680325787e-06 1.03502835145519e-05 -8.32470415261566e-06 9.65003627383744e-06 6.24996692385123e-06 3.52682834716351e-05 -5.0067191681791e-06 1.12347998935902e-05 -1.69016119863499e-06 1.10855816395786e-05 -2.84821680325787e-06 -5.0067191681791e-06 1.23428045469695e-05 2.86164257870593e-06 3.60677933007855e-06 9.30262702731038e-07 1.03502835145519e-05 1.12347998935902e-05 2.86164257870593e-06 8.57769150337838e-05 -3.96944778330642e-05 1.83094909654091e-05 -8.32470415261566e-06 -1.69016119863499e-06 3.60677933007855e-06 -3.96944778330642e-05 6.60668418178451e-05 -4.46211050323196e-06 9.65003627383744e-06 1.10855816395786e-05 9.30262702731038e-07 1.83094909654091e-05 -4.46211050323196e-06 4.41582549445311e-05 1800 1814 0 224 0 1789 1803 0 224 0 0 0 0 0 0 0 0 0 275 0 636 640 0 0 1815 +432 384 0.938420534173291 0.3450994539022 0.0165308184406699 0.0380502639000337 -0.34413638426267 0.929420063903957 0.133223473304746 0.0140539699808041 0.0306112735529102 -0.130708499070136 0.990948151117051 0.0825599945410393 6.03950335574629e-05 2.33997102269665e-05 -4.82511013561677e-06 7.36770721256505e-07 6.20800387993974e-06 2.54736361684414e-05 2.33997102269665e-05 3.40120732340641e-05 -4.55827460785882e-06 8.44644342395483e-06 -1.12389835078771e-06 1.96346009798306e-05 -4.82511013561677e-06 -4.55827460785882e-06 1.20015956699317e-05 1.95489198919913e-06 1.03865935588799e-06 9.7458677474245e-08 7.36770721256505e-07 8.44644342395483e-06 1.95489198919913e-06 4.49389659576277e-05 -3.12390154414299e-06 1.18750830804292e-05 6.20800387993974e-06 -1.12389835078771e-06 1.03865935588799e-06 -3.12390154414299e-06 5.04761158179057e-05 9.54373746236907e-06 2.54736361684414e-05 1.96346009798306e-05 9.7458677474245e-08 1.18750830804292e-05 9.54373746236907e-06 4.75439897558571e-05 1922 1939 0 225 0 1907 1924 0 225 0 0 0 0 0 0 0 0 0 288 0 773 777 0 0 1786 +432 392 0.937455314144079 0.346740151767646 0.0308026157197004 0.0469813777755036 -0.347843141148274 0.929638210185475 0.121564580858278 0.0278197968774403 0.0135160326696764 -0.124675840944814 0.992105463922851 0.10216732503282 7.25331082434672e-05 2.28481056388342e-05 -2.47218475066016e-06 1.71862067373991e-05 -1.33329721270216e-05 3.17322233945427e-05 2.28481056388342e-05 3.39065095979961e-05 -5.5979254819181e-06 9.01115745939146e-06 -1.65004647543727e-06 1.62049032743398e-05 -2.47218475066016e-06 -5.5979254819181e-06 1.22731979781412e-05 1.24553817746548e-06 4.29748485318158e-06 -1.32134741466067e-06 1.71862067373991e-05 9.01115745939146e-06 1.24553817746548e-06 4.27270561323361e-05 -3.53046693130715e-06 1.27669577292724e-05 -1.33329721270216e-05 -1.65004647543727e-06 4.29748485318158e-06 -3.53046693130715e-06 4.7132265104365e-05 8.06956105173915e-06 3.17322233945427e-05 1.62049032743398e-05 -1.32134741466067e-06 1.27669577292724e-05 8.06956105173915e-06 5.42319544695062e-05 1812 1821 0 220 0 1795 1804 0 220 0 0 0 0 0 0 0 0 0 67 0 650 661 0 0 1425 +432 388 0.938485494705105 0.344946760666282 0.0160221263867339 0.0341712643487265 -0.343988956272657 0.929797041598811 0.130954417247173 0.0119471902262163 0.0302749763098455 -0.128410255587073 0.991258912731432 0.0839551611234274 7.26000580596199e-05 4.13498418890739e-05 2.59000717009595e-06 2.28521822020125e-06 -1.40843499230508e-05 4.6342101770767e-05 4.13498418890739e-05 6.14712700014318e-05 -1.94883896889892e-06 1.39300881887434e-05 3.11306409984906e-07 4.43583947097673e-05 2.59000717009595e-06 -1.94883896889892e-06 1.23184084589388e-05 3.32436476211426e-07 1.39422282946265e-06 1.99964464227669e-06 2.28521822020125e-06 1.39300881887434e-05 3.32436476211426e-07 4.8873334410647e-05 6.7915255371856e-06 1.48137164035409e-05 -1.40843499230508e-05 3.11306409984906e-07 1.39422282946265e-06 6.7915255371856e-06 4.87869668300127e-05 1.69962115144401e-06 4.6342101770767e-05 4.43583947097673e-05 1.99964464227669e-06 1.48137164035409e-05 1.69962115144401e-06 7.29656945826128e-05 2006 2022 0 221 0 1995 2011 0 221 0 0 0 0 0 0 0 0 0 277 0 631 637 0 0 1695 +432 381 0.93819208531791 0.345553634390941 0.0197052481852786 0.0433743770186896 -0.344996651780713 0.929070690516715 0.133435236286714 0.0147394870513928 0.0278014623163881 -0.131986127233149 0.990861615419159 0.0872655344150484 5.63228814956639e-05 1.27952692600734e-05 -5.86060267448228e-06 -6.80129219724088e-06 7.09533202145568e-06 1.52087549219991e-05 1.27952692600734e-05 2.84167063503633e-05 -6.35559406218141e-06 5.72997431654641e-06 2.34369384481159e-06 7.60509975151757e-06 -5.86060267448228e-06 -6.35559406218141e-06 1.22859086489749e-05 2.70841244112411e-06 1.28538798228962e-06 -2.0859298709688e-06 -6.80129219724088e-06 5.72997431654641e-06 2.70841244112411e-06 5.01471150226531e-05 -6.01480340715939e-06 4.04485306707079e-06 7.09533202145568e-06 2.34369384481159e-06 1.28538798228962e-06 -6.01480340715939e-06 4.66982288274273e-05 1.10685329712936e-05 1.52087549219991e-05 7.60509975151757e-06 -2.0859298709688e-06 4.04485306707079e-06 1.10685329712936e-05 3.90542552652038e-05 2000 2015 0 229 0 1986 2001 0 229 0 0 0 0 0 0 0 0 0 262 0 629 635 0 0 1824 +432 379 0.938212896933298 0.345610584123103 0.0176035272066691 0.0440994604160992 -0.344864432184054 0.929542556113036 0.130457501851036 0.00220298013079991 0.0287242657416849 -0.128467741152906 0.991297612244008 0.0866796087321336 5.51901546542918e-05 8.6831743503406e-06 -6.16981841658115e-06 -1.67978483202485e-06 4.74882096646672e-06 5.54287891391816e-06 8.6831743503406e-06 3.69345762708987e-05 -4.70473815199606e-06 1.1231249915097e-05 1.52494220279298e-06 1.60900755316855e-05 -6.16981841658115e-06 -4.70473815199606e-06 1.26501345797302e-05 2.72113499018209e-06 1.74109878601726e-06 -5.0325793950194e-07 -1.67978483202485e-06 1.1231249915097e-05 2.72113499018209e-06 6.80152187240078e-05 -2.4370935333874e-05 1.20549823648667e-05 4.74882096646672e-06 1.52494220279298e-06 1.74109878601726e-06 -2.4370935333874e-05 5.54013835671383e-05 8.12576256460153e-07 5.54287891391816e-06 1.60900755316855e-05 -5.0325793950194e-07 1.20549823648667e-05 8.12576256460153e-07 4.31248390589344e-05 1850 1866 0 224 0 1836 1852 0 224 0 0 0 0 0 0 0 0 0 269 0 780 780 0 0 1819 +432 429 0.941123196451807 0.337846215756811 0.0121269781535307 0.0301391905442382 -0.336211082653565 0.931612710698912 0.138057470515514 0.0110091796729551 0.0353445469804268 -0.134006312399927 0.9903499741181 0.0776350939838503 6.74609333860212e-05 2.75670336390884e-05 -2.95256439052742e-06 4.03148712695777e-06 -6.25086681294817e-06 3.79925033462466e-05 2.75670336390884e-05 5.33613318787043e-05 -4.34952105311256e-06 1.45495537293656e-05 1.39842764668196e-05 2.49565546341959e-05 -2.95256439052742e-06 -4.34952105311256e-06 1.15127356175316e-05 1.25261800699949e-06 -1.72256625832477e-06 -9.03867574224571e-07 4.03148712695777e-06 1.45495537293656e-05 1.25261800699949e-06 4.59240767471962e-05 7.2664903640828e-06 6.75754485171927e-06 -6.25086681294817e-06 1.39842764668196e-05 -1.72256625832477e-06 7.2664903640828e-06 7.0167692516528e-05 -5.49155237353234e-06 3.79925033462466e-05 2.49565546341959e-05 -9.03867574224571e-07 6.75754485171927e-06 -5.49155237353234e-06 7.03618635497162e-05 1780 1799 0 215 0 1788 1807 0 215 0 0 0 0 0 0 0 0 0 274 0 473 481 0 0 1990 +432 385 0.938337273793837 0.345280239546359 0.017456138976251 0.0360857603637363 -0.344414661130057 0.929213148160735 0.133945759484518 0.0176022278471416 0.0300283500681797 -0.131698448981092 0.990834908916797 0.0827034521041227 5.08511458466722e-05 1.12644198191864e-05 -6.85877184462438e-06 2.43751616774029e-06 -3.67297822589127e-08 1.61121652633007e-05 1.12644198191864e-05 2.76020852604158e-05 -5.75702901460512e-06 9.71176157271983e-06 -1.72042329229676e-06 1.15479923296706e-05 -6.85877184462438e-06 -5.75702901460512e-06 1.17464792151768e-05 2.14347828250699e-06 1.84026695135609e-06 -7.22129952820157e-07 2.43751616774029e-06 9.71176157271983e-06 2.14347828250699e-06 4.47646567972577e-05 -5.84324247653091e-06 8.8855566212388e-06 -3.67297822589127e-08 -1.72042329229676e-06 1.84026695135609e-06 -5.84324247653091e-06 4.00262732320427e-05 4.26118235234496e-06 1.61121652633007e-05 1.15479923296706e-05 -7.22129952820157e-07 8.8855566212388e-06 4.26118235234496e-06 3.79947942193033e-05 1997 2010 0 231 0 2004 2017 0 231 0 0 0 0 0 0 0 0 0 260 0 606 614 0 0 1762 +432 378 0.938323153103038 0.345266575674239 0.0184567622555305 0.046260327614783 -0.344545891069222 0.929227798895217 0.133505905141556 0.00551248009237901 0.028944590135076 -0.131630883467885 0.990876138182455 0.0880004018449471 5.54012744355297e-05 1.63956100364198e-05 -4.18730388014839e-06 6.50862525184983e-06 -5.73803093326343e-06 1.53064921702414e-05 1.63956100364198e-05 3.23148535106701e-05 -4.92217792566422e-06 1.5014426546466e-05 -9.44766476745098e-06 3.98663087116974e-06 -4.18730388014839e-06 -4.92217792566422e-06 1.04417692873235e-05 2.08170153066222e-06 1.70678121324633e-06 2.69528208736391e-07 6.50862525184983e-06 1.5014426546466e-05 2.08170153066222e-06 6.86296008211534e-05 -2.2618851697246e-05 7.51458305417391e-06 -5.73803093326343e-06 -9.44766476745098e-06 1.70678121324633e-06 -2.2618851697246e-05 6.42523102268091e-05 5.4957046089095e-06 1.53064921702414e-05 3.98663087116974e-06 2.69528208736391e-07 7.51458305417391e-06 5.4957046089095e-06 4.29434501522242e-05 1899 1916 0 225 0 1862 1879 0 225 0 0 0 0 0 0 0 0 0 286 0 688 684 0 0 1785 +432 391 0.937834517283525 0.346209161602425 0.0246096447378382 0.0426288695188048 -0.346520810488893 0.929926586927216 0.123125427203401 0.0202551080439259 0.0197419879874806 -0.123999029627029 0.992085931037154 0.0941352792610341 5.48982957275211e-05 1.12611971766332e-05 -7.34207868101561e-07 1.1570477531134e-05 -5.27231010690302e-06 2.35801639286369e-05 1.12611971766332e-05 3.13100318751958e-05 -5.4187042128145e-06 6.775636984449e-06 4.96777732923351e-06 2.26130969540048e-05 -7.34207868101561e-07 -5.4187042128145e-06 1.09741883866373e-05 1.49199272944335e-06 5.41685917961083e-06 -1.91140225789458e-06 1.1570477531134e-05 6.775636984449e-06 1.49199272944335e-06 4.66751369403959e-05 -2.02280997344543e-06 1.93504088304867e-05 -5.27231010690302e-06 4.96777732923351e-06 5.41685917961083e-06 -2.02280997344543e-06 4.7800178303958e-05 1.11589505568036e-05 2.35801639286369e-05 2.26130969540048e-05 -1.91140225789458e-06 1.93504088304867e-05 1.11589505568036e-05 6.89729942609263e-05 1862 1878 0 229 0 1845 1861 0 229 0 0 0 0 0 0 0 0 0 48 0 771 774 0 0 1444 +432 394 0.937947174471027 0.346021402196622 0.0228973169541797 0.0364775233372146 -0.346049159422753 0.929653658819202 0.126467600225817 0.0248554910168247 0.0224739218789831 -0.126543525578967 0.991706437898546 0.0913759328995743 8.35882845307e-05 2.56415939670214e-05 -4.7324118082261e-07 1.91475078090554e-06 -5.44480091623858e-06 3.97621259386053e-05 2.56415939670214e-05 4.16463799721467e-05 -2.48429202792977e-06 2.28678005696223e-06 7.29413188589727e-06 2.77882546066008e-05 -4.7324118082261e-07 -2.48429202792977e-06 1.16731829766219e-05 1.83066908663006e-06 4.5204688631113e-06 4.94335001878791e-07 1.91475078090554e-06 2.28678005696223e-06 1.83066908663006e-06 4.2616295154091e-05 1.44213123472204e-06 5.69265928384838e-07 -5.44480091623858e-06 7.29413188589727e-06 4.5204688631113e-06 1.44213123472204e-06 5.05114549934119e-05 1.08847392040397e-05 3.97621259386053e-05 2.77882546066008e-05 4.94335001878791e-07 5.69265928384838e-07 1.08847392040397e-05 7.23595502485356e-05 1590 1609 0 230 0 1564 1583 0 230 0 0 0 0 0 0 0 0 0 85 0 649 651 0 0 1607 +432 383 0.938274359103505 0.345506811913542 0.0163177808003081 0.0364892203049995 -0.344527970517596 0.929348486419429 0.132709714493489 0.0125502510160318 0.0306872054761116 -0.130140054215669 0.991020616187579 0.083327141915628 6.30889645669851e-05 1.90813623860387e-05 -6.23419708768077e-06 2.63785106038274e-06 2.50348390499898e-06 1.82302314936419e-05 1.90813623860387e-05 3.49264851720863e-05 -3.77036476131811e-06 1.21016568013297e-05 1.98694467286872e-06 1.69351759300912e-05 -6.23419708768077e-06 -3.77036476131811e-06 1.1455174315568e-05 2.04728501057302e-06 2.08318100399207e-06 4.39584658923797e-07 2.63785106038274e-06 1.21016568013297e-05 2.04728501057302e-06 4.8004781648937e-05 2.70583850737386e-06 1.40044222620054e-05 2.50348390499898e-06 1.98694467286872e-06 2.08318100399207e-06 2.70583850737386e-06 3.76235656851554e-05 7.23899608331048e-06 1.82302314936419e-05 1.69351759300912e-05 4.39584658923797e-07 1.40044222620054e-05 7.23899608331048e-06 4.75353483895566e-05 1926 1939 0 221 0 1907 1920 0 221 0 0 0 0 0 0 0 0 0 264 0 771 778 0 0 1814 +432 387 0.938303462764259 0.34545031489782 0.0158332467169274 0.0379109976100258 -0.34443106695731 0.929484725725606 0.132005245189139 0.0161551485189214 0.030884492536723 -0.129314440724124 0.991122557275818 0.0838731866123691 5.98540922825764e-05 2.53012864716011e-05 -3.67786358950173e-06 5.52111641381831e-07 4.62296869071225e-06 1.77297552009533e-05 2.53012864716011e-05 3.99335189104735e-05 -5.35004890013778e-06 5.84626436689454e-06 5.57909045143671e-06 1.94061468779724e-05 -3.67786358950173e-06 -5.35004890013778e-06 1.21965671214962e-05 1.60916593314768e-06 2.8302297755809e-07 5.18560608520885e-07 5.52111641381831e-07 5.84626436689454e-06 1.60916593314768e-06 3.65434553602279e-05 5.16326745954544e-06 4.71862554513192e-06 4.62296869071225e-06 5.57909045143671e-06 2.8302297755809e-07 5.16326745954544e-06 4.32343201829644e-05 9.5508976796891e-06 1.77297552009533e-05 1.94061468779724e-05 5.18560608520885e-07 4.71862554513192e-06 9.5508976796891e-06 4.47447698813732e-05 1840 1853 0 217 0 1822 1835 0 217 0 0 0 0 0 0 0 0 0 263 0 772 776 0 0 1802 +432 389 0.938198877213767 0.34558811589841 0.0187542247137506 0.0369124835561197 -0.345041089422068 0.92973448520354 0.128609617189931 0.0162019685130381 0.0270095058314537 -0.127132376572985 0.991517950125788 0.0880893694972732 4.92960217616071e-05 -2.81391682375093e-06 -1.14393051034389e-06 -9.59733528209522e-06 -6.44550860866208e-06 -1.22597098137504e-05 -2.81391682375093e-06 3.77318081984871e-05 -4.36608960723296e-06 2.03724874988588e-05 1.0996731149151e-06 1.09251524214997e-05 -1.14393051034389e-06 -4.36608960723296e-06 1.08490059798763e-05 2.93774404803026e-06 4.04922176228176e-06 1.13326657019887e-06 -9.59733528209522e-06 2.03724874988588e-05 2.93774404803026e-06 5.96858965972525e-05 6.32405118314996e-06 1.49107386556658e-05 -6.44550860866208e-06 1.0996731149151e-06 4.04922176228176e-06 6.32405118314996e-06 3.81909244516565e-05 1.85353946171335e-06 -1.22597098137504e-05 1.09251524214997e-05 1.13326657019887e-06 1.49107386556658e-05 1.85353946171335e-06 3.53777076831424e-05 1754 1768 0 224 0 1763 1777 0 224 0 0 0 0 0 0 0 0 0 132 0 478 474 0 0 1649 +432 372 0.938482679740941 0.344673643095381 0.0212212059417101 0.0436991571428319 -0.34430753345414 0.929228557847446 0.13411416661741 0.0150001792131116 0.0265062678057247 -0.133170443553042 0.990738638961304 0.0836021673783956 4.85627493996319e-05 1.62465605831127e-05 -6.08981161090821e-06 8.56470652308103e-07 1.65022530097439e-06 1.7044897239014e-05 1.62465605831127e-05 3.58521159375258e-05 -6.00267659158949e-06 6.82708850790133e-06 1.19462292172005e-05 8.72162169968167e-06 -6.08981161090821e-06 -6.00267659158949e-06 1.20727804836632e-05 3.08791802613827e-06 2.42811087720108e-06 -2.17546386931191e-06 8.56470652308103e-07 6.82708850790133e-06 3.08791802613827e-06 5.7422568286173e-05 -5.18434701516841e-06 7.99517242563057e-06 1.65022530097439e-06 1.19462292172005e-05 2.42811087720108e-06 -5.18434701516841e-06 5.98688859371614e-05 4.47882960088677e-06 1.7044897239014e-05 8.72162169968167e-06 -2.17546386931191e-06 7.99517242563057e-06 4.47882960088677e-06 3.91245323633398e-05 1511 1528 0 222 0 1501 1518 0 222 0 0 0 0 0 0 0 0 0 283 0 745 748 0 0 1782 +433 337 0.916638689509314 0.370745855448191 -0.149402220741987 0.0691481149745397 -0.355037471103227 0.92688359106168 0.121799847016443 0.0463837194364984 0.183635255349492 -0.0586030655221459 0.981246031178794 0.0758857624531642 8.00204648077366e-05 -3.50884808477678e-05 -6.9890344604564e-06 1.32856728757443e-05 -3.21727416375092e-05 -1.46268921981436e-05 -3.50884808477678e-05 0.000157956655965368 4.21203200744894e-06 1.99090205285396e-05 5.73876263460546e-05 2.88263589855943e-05 -6.9890344604564e-06 4.21203200744894e-06 1.77031701189958e-05 -1.61227379740769e-06 -2.69978913763211e-06 3.66728110709115e-06 1.32856728757443e-05 1.99090205285396e-05 -1.61227379740769e-06 0.000112773924065129 -6.66801069483357e-05 4.86174569520586e-06 -3.21727416375092e-05 5.73876263460546e-05 -2.69978913763211e-06 -6.66801069483357e-05 0.00021553493798586 3.92835703035254e-05 -1.46268921981436e-05 2.88263589855943e-05 3.66728110709115e-06 4.86174569520586e-06 3.92835703035254e-05 9.75740135224054e-05 1418 1403 0 59 0 1392 1377 0 59 0 0 0 0 0 0 0 0 0 428 0 618 591 0 0 1286 +433 336 0.902283092277396 0.395973604384588 -0.170558277491942 0.0619508415245587 -0.382049594032252 0.917650878685747 0.109338797080759 0.0322592929036448 0.199808230786751 -0.0334928272612817 0.979262427254265 0.0373783571960644 7.55509776162291e-05 2.09182453162633e-05 -6.26476250724202e-06 1.46929140992858e-05 -1.3367599112271e-05 -4.6089039472833e-06 2.09182453162633e-05 7.91738112205842e-05 -4.24246428088811e-06 1.43918718147404e-05 9.89080288775212e-06 3.7112090629053e-05 -6.26476250724202e-06 -4.24246428088811e-06 1.66338635487961e-05 -3.2221216941231e-06 -3.18744883147065e-06 -3.17817642137146e-06 1.46929140992858e-05 1.43918718147404e-05 -3.2221216941231e-06 9.67115428086983e-05 -5.36792373235857e-05 2.52652715978845e-05 -1.3367599112271e-05 9.89080288775212e-06 -3.18744883147065e-06 -5.36792373235857e-05 0.000136236699908079 1.37913144325713e-05 -4.6089039472833e-06 3.7112090629053e-05 -3.17817642137146e-06 2.52652715978845e-05 1.37913144325713e-05 9.98724703658367e-05 1707 1692 0 91 0 1679 1664 0 91 0 0 0 0 0 0 0 0 0 417 0 635 612 0 0 1237 +432 390 0.937618218750459 0.346395133138154 0.029706692939765 0.0453172291623702 -0.3474294336841 0.930396183795656 0.116857733113496 0.0162946835915343 0.0128399562757257 -0.119888919073783 0.992704277519825 0.100467645101825 6.76323320439702e-05 1.37303207375318e-05 -3.02690972484286e-06 5.12887572013088e-06 7.67765666152202e-07 8.0184274611868e-06 1.37303207375318e-05 4.56513668211946e-05 -3.61827717875698e-06 2.06220768946142e-05 6.79284646447937e-06 2.29003068597963e-05 -3.02690972484286e-06 -3.61827717875698e-06 1.1912783854193e-05 2.64472068264927e-06 1.5795698907584e-06 -2.0212324326764e-06 5.12887572013088e-06 2.06220768946142e-05 2.64472068264927e-06 5.86360656702806e-05 1.01797961888281e-05 2.07489057734882e-05 7.67765666152202e-07 6.79284646447937e-06 1.5795698907584e-06 1.01797961888281e-05 5.2710308518282e-05 2.13470541357224e-05 8.0184274611868e-06 2.29003068597963e-05 -2.0212324326764e-06 2.07489057734882e-05 2.13470541357224e-05 5.66485075680191e-05 1791 1811 0 226 0 1774 1794 0 226 0 0 0 0 0 0 0 0 0 48 0 542 533 0 0 1544 +432 428 0.938281310124926 0.345622130095652 0.0131729365897275 0.0311788338197025 -0.344272850736325 0.929603233023949 0.131582800537557 0.00931565682098985 0.0332323233635117 -0.1279967669106 0.991217655383668 0.0788463741450404 8.28558287227278e-05 4.10031002221768e-05 -5.52880532756487e-06 1.36836844100947e-05 -5.95702040616741e-08 5.15473602849442e-05 4.10031002221768e-05 5.34026112384755e-05 -6.94953962717179e-06 1.92227815972614e-05 6.78427307463952e-07 4.30898205679039e-05 -5.52880532756487e-06 -6.94953962717179e-06 1.41072242176278e-05 -1.00253951465699e-06 -4.36518476256196e-06 -1.53362127421196e-07 1.36836844100947e-05 1.92227815972614e-05 -1.00253951465699e-06 5.03949184163073e-05 1.48689948952707e-05 2.04090293941382e-05 -5.95702040616741e-08 6.78427307463952e-07 -4.36518476256196e-06 1.48689948952707e-05 5.94722875189332e-05 -9.2863577460552e-06 5.15473602849442e-05 4.30898205679039e-05 -1.53362127421196e-07 2.04090293941382e-05 -9.2863577460552e-06 8.57219806660157e-05 1818 1836 0 220 0 1832 1850 0 220 0 0 0 0 0 0 0 0 0 257 0 599 622 0 0 1947 +433 339 0.903988459939047 0.385067929027857 -0.185815915172052 0.0789773609121501 -0.376206090737179 0.922877485734102 0.082256450308478 0.0586369883776565 0.203159645572833 -0.00445380279078478 0.979135497289023 0.0825979085640211 4.51375767569367e-05 1.67373326710448e-08 -2.4449422772325e-06 6.92687089316936e-07 3.00450559715942e-06 -4.54846495340363e-06 1.67373326710448e-08 5.61452038576983e-05 -2.11992268304319e-06 9.15415207602742e-06 -3.99683730841012e-06 -1.95722852082972e-07 -2.4449422772325e-06 -2.11992268304319e-06 1.52407409208137e-05 1.31554201605815e-06 -1.15378396485864e-05 4.09530761125699e-06 6.92687089316936e-07 9.15415207602742e-06 1.31554201605815e-06 0.000110140062113491 -9.23474430101923e-05 7.17651198960044e-06 3.00450559715942e-06 -3.99683730841012e-06 -1.15378396485864e-05 -9.23474430101923e-05 0.000214173428221062 -9.17991401369857e-06 -4.54846495340363e-06 -1.95722852082972e-07 4.09530761125699e-06 7.17651198960044e-06 -9.17991401369857e-06 7.14468740383882e-05 1164 1153 0 76 0 1143 1132 0 76 0 0 0 0 0 0 0 0 0 341 0 569 539 0 0 1317 +432 386 0.938199898946397 0.345756488290754 0.0152774481447825 0.0349627725671042 -0.34455384955692 0.928955198912249 0.135369432182495 0.0204718991914374 0.032612794613125 -0.132267491163739 0.990677402795063 0.0831094456886319 5.07160699695322e-05 1.37955653868437e-05 -5.01880875130513e-07 1.23098636836579e-06 -5.94002436003763e-06 1.10853995757745e-05 1.37955653868437e-05 3.17075722902914e-05 -2.55888243141775e-06 1.26308849834337e-05 2.26508830355787e-06 1.2977741633822e-05 -5.01880875130513e-07 -2.55888243141775e-06 1.10826292327771e-05 9.93780827982558e-07 2.17088730930738e-06 -8.99466159781781e-08 1.23098636836579e-06 1.26308849834337e-05 9.93780827982558e-07 4.79798777392807e-05 -2.53247855892753e-06 7.41764808501402e-06 -5.94002436003763e-06 2.26508830355787e-06 2.17088730930738e-06 -2.53247855892753e-06 5.38242455673139e-05 1.26356749239158e-05 1.10853995757745e-05 1.2977741633822e-05 -8.99466159781781e-08 7.41764808501402e-06 1.26356749239158e-05 4.50066953884187e-05 2011 2026 0 222 0 1977 1992 0 222 0 0 0 0 0 0 0 0 0 261 0 688 688 0 0 1776 +433 338 0.911513797899365 0.369083499065377 -0.181438603821605 0.0748359613586538 -0.35714532876455 0.929123361260421 0.0957966267767271 0.0542326166550522 0.203935799654542 -0.0225199972867545 0.978725211354784 0.0746581593863405 6.44453304917987e-05 2.2978353357762e-06 -7.16629840172943e-06 7.87731164128343e-06 -8.07560275654211e-08 -3.66401753741729e-06 2.2978353357762e-06 3.4997152353054e-05 7.51860493967429e-08 -4.09221763474016e-07 4.23698168977219e-06 3.35268615007327e-06 -7.16629840172943e-06 7.51860493967429e-08 1.59723297221749e-05 2.13921771087375e-06 -7.54706480411491e-06 -9.77281657581853e-07 7.87731164128343e-06 -4.09221763474016e-07 2.13921771087375e-06 7.76263709803858e-05 -5.12978773273338e-05 -9.1684014991505e-09 -8.07560275654211e-08 4.23698168977219e-06 -7.54706480411491e-06 -5.12978773273338e-05 0.000134903848806314 1.38047869144819e-05 -3.66401753741729e-06 3.35268615007327e-06 -9.77281657581853e-07 -9.1684014991505e-09 1.38047869144819e-05 5.19777806584434e-05 1596 1584 0 63 0 1577 1565 0 63 0 0 0 0 0 0 0 0 0 367 0 523 497 0 0 1238 +433 340 0.891298085357396 0.416350887312825 -0.17955406336829 0.0734707577459678 -0.409248150539882 0.909189825283721 0.0767451163282908 0.0542370186577396 0.195201624783007 0.00507939311145719 0.980749981110218 0.0858978076065625 6.93368650061817e-05 3.18992197775643e-06 -1.04828769306507e-05 5.51657661538715e-06 8.88864002449377e-06 -6.34043402225755e-08 3.18992197775643e-06 6.47550908713693e-05 -7.82767593155377e-06 2.30844008742138e-05 1.04231872085849e-05 1.62814353201003e-05 -1.04828769306507e-05 -7.82767593155377e-06 1.81558774477318e-05 -7.22879875496532e-06 -8.5293654122721e-06 -5.55991277746041e-06 5.51657661538715e-06 2.30844008742138e-05 -7.22879875496532e-06 9.59143659160705e-05 -2.91949530947043e-05 1.55952975234308e-05 8.88864002449377e-06 1.04231872085849e-05 -8.5293654122721e-06 -2.91949530947043e-05 0.00011930450057871 3.02568678202932e-05 -6.34043402225755e-08 1.62814353201003e-05 -5.55991277746041e-06 1.55952975234308e-05 3.02568678202932e-05 7.8245434988921e-05 1387 1377 0 116 0 1357 1347 0 116 0 0 0 0 0 0 0 0 0 262 0 722 690 0 0 1323 +433 430 0.921584026788098 0.387747317865852 -0.0183002474538521 0.0418487467216364 -0.383214405930985 0.916301754697766 0.116352109670415 0.0193409740338165 0.0618837673061049 -0.100215327298934 0.993039418914663 0.1132905602287 7.59437807643615e-05 1.96943413472918e-05 -6.3600989215909e-06 -1.0310796671164e-06 6.67852584255149e-06 4.18517027321068e-05 1.96943413472918e-05 4.16125245917902e-05 -5.46260738511112e-06 1.46725277188779e-05 6.66067520240371e-07 3.21694852605843e-05 -6.3600989215909e-06 -5.46260738511112e-06 1.14508739623296e-05 -2.07733871614205e-06 -5.97612072140714e-07 -9.08829048729814e-07 -1.0310796671164e-06 1.46725277188779e-05 -2.07733871614205e-06 4.74425971790259e-05 7.76467731001034e-07 1.72916546855704e-05 6.67852584255149e-06 6.66067520240371e-07 -5.97612072140714e-07 7.76467731001034e-07 4.97014670267518e-05 1.51455908080348e-05 4.18517027321068e-05 3.21694852605843e-05 -9.08829048729814e-07 1.72916546855704e-05 1.51455908080348e-05 9.48648278829139e-05 2002 2016 0 152 0 2000 2014 0 152 0 0 0 0 0 0 0 0 0 336 0 604 576 0 0 1622 +433 431 0.964239364948969 0.260785559056645 -0.0472582190769216 0.0370324273459212 -0.258771333068761 0.964901419582239 0.0447509516099629 0.0144981727633028 0.0572699246081711 -0.0309215568122621 0.997879758818506 0.100763500055885 4.09631205353484e-05 8.32275890188475e-06 -7.22484708704523e-06 7.66214398982279e-06 2.71895781563485e-06 3.71005823753278e-06 8.32275890188475e-06 3.48778934223775e-05 -2.17461142488332e-06 8.34721650321408e-06 -5.42556032563258e-06 1.44478781670514e-05 -7.22484708704523e-06 -2.17461142488332e-06 1.09387084707532e-05 7.18060097089831e-07 5.830837588687e-07 -6.03248324924427e-07 7.66214398982279e-06 8.34721650321408e-06 7.18060097089831e-07 3.05280853561941e-05 -7.13094584592233e-06 9.3370236500928e-06 2.71895781563485e-06 -5.42556032563258e-06 5.830837588687e-07 -7.13094584592233e-06 4.5237697862091e-05 -1.09138858043965e-06 3.71005823753278e-06 1.44478781670514e-05 -6.03248324924427e-07 9.3370236500928e-06 -1.09138858043965e-06 3.87583464557781e-05 1971 1969 0 0 0 1951 1949 0 0 0 0 0 0 0 0 0 0 0 603 0 552 525 0 0 2140 +432 395 0.937616255090233 0.346893526533424 0.0232516545598749 0.0401963880990613 -0.347091734558941 0.930093919028182 0.120219089946912 0.0252260962611195 0.0200770015548395 -0.120789830018931 0.992475053073156 0.0980685634266766 8.2720078552956e-05 2.15503233912195e-05 -2.94801904512525e-06 1.3092320082639e-05 -1.02310613752786e-05 3.12112726376889e-05 2.15503233912195e-05 4.17809404295929e-05 -3.44313471576163e-06 1.36352260455285e-05 -4.37622615999099e-08 2.4022075485854e-05 -2.94801904512525e-06 -3.44313471576163e-06 1.15345923292306e-05 1.85958673025863e-06 3.49312737443534e-06 -9.248917104757e-07 1.3092320082639e-05 1.36352260455285e-05 1.85958673025863e-06 4.14224619421221e-05 -9.79337927071648e-07 9.54981348804873e-06 -1.02310613752786e-05 -4.37622615999099e-08 3.49312737443534e-06 -9.79337927071648e-07 4.7368797308649e-05 1.14020492942367e-05 3.12112726376889e-05 2.4022075485854e-05 -9.248917104757e-07 9.54981348804873e-06 1.14020492942367e-05 6.77045142988624e-05 2078 2086 0 218 0 2058 2066 0 218 0 0 0 0 0 0 0 0 0 84 0 762 767 0 0 1601 +433 429 0.890762480577832 0.454302003846092 0.0123244673821012 0.0448702471362682 -0.45114966177929 0.880659416075567 0.144578613750006 0.0188507180605293 0.0548286956917542 -0.134345383913505 0.989416561388515 0.120784911867498 7.36269270716681e-05 2.16245611000586e-05 -4.80445686715149e-06 1.13791615756586e-05 4.79949646192834e-06 3.22891678866566e-05 2.16245611000586e-05 4.4298204314306e-05 -5.45091932039154e-06 1.91574399543306e-05 6.26209460736416e-06 2.5800003931897e-05 -4.80445686715149e-06 -5.45091932039154e-06 1.21849085635833e-05 -1.28698244970961e-06 -2.3038943564918e-06 4.09066192705171e-07 1.13791615756586e-05 1.91574399543306e-05 -1.28698244970961e-06 5.21495172963036e-05 6.3637370141927e-06 1.54824226031268e-05 4.79949646192834e-06 6.26209460736416e-06 -2.3038943564918e-06 6.3637370141927e-06 5.15962744107025e-05 1.04862530955711e-06 3.22891678866566e-05 2.5800003931897e-05 4.09066192705171e-07 1.54824226031268e-05 1.04862530955711e-06 8.2229739405511e-05 1849 1871 0 256 0 1846 1868 0 256 0 0 0 0 0 0 0 0 0 271 0 649 647 0 0 1515 +433 385 0.887255653405318 0.460861097556262 0.019607505183984 0.0516775144216039 -0.459260829492782 0.878606321247418 0.13088324093512 0.0195965388148771 0.0430917160705405 -0.125131854550776 0.991203875589063 0.13676379369485 4.33267761181155e-05 -1.91117692494083e-06 -4.8773570372901e-06 -6.43759916708187e-06 4.16391237801642e-07 1.89072957275594e-06 -1.91117692494083e-06 3.10028056486492e-05 -2.96924957616233e-06 4.94664898612694e-06 -7.48172435324673e-07 1.46715595255281e-05 -4.8773570372901e-06 -2.96924957616233e-06 1.0851174088504e-05 8.18792077119829e-07 -7.69055665382487e-07 -2.00542532881668e-08 -6.43759916708187e-06 4.94664898612694e-06 8.18792077119829e-07 4.56960647397422e-05 -8.06199733427516e-06 9.5470749032676e-06 4.16391237801642e-07 -7.48172435324673e-07 -7.69055665382487e-07 -8.06199733427516e-06 4.4079818504636e-05 7.4400257274345e-06 1.89072957275594e-06 1.46715595255281e-05 -2.00542532881668e-08 9.5470749032676e-06 7.4400257274345e-06 4.28229093573313e-05 1867 1878 0 263 0 1859 1870 0 263 0 0 0 0 0 0 0 0 0 259 0 828 816 0 0 1355 +433 341 0.882962983010725 0.434086615554599 -0.17873214828104 0.0847861759960208 -0.425431273361486 0.900871131728889 0.0862521632397413 0.0213829881876538 0.198455542323278 -0.000119221911453138 0.980109883384159 0.0892864613088302 7.89883108515118e-05 -5.33538622893906e-06 -7.88962786338484e-06 1.2719108649319e-06 2.60275130385932e-06 1.65152938599035e-05 -5.33538622893906e-06 6.87987334994329e-05 -1.59650005362745e-06 9.06410778666266e-06 -1.62937504045763e-05 1.51799824635444e-06 -7.88962786338484e-06 -1.59650005362745e-06 1.95492377072732e-05 -1.56249444652338e-06 -4.31099491376979e-06 -5.69411190525683e-07 1.2719108649319e-06 9.06410778666266e-06 -1.56249444652338e-06 5.99790301435575e-05 -1.1689367409528e-05 8.3475100699566e-06 2.60275130385932e-06 -1.62937504045763e-05 -4.31099491376979e-06 -1.1689367409528e-05 7.9906172001525e-05 -4.21778979432618e-06 1.65152938599035e-05 1.51799824635444e-06 -5.69411190525683e-07 8.3475100699566e-06 -4.21778979432618e-06 7.03945751056303e-05 1294 1291 0 134 0 1264 1261 0 134 0 0 0 0 0 0 0 0 0 205 0 672 647 0 0 1269 +433 380 0.887432894752572 0.460521606636368 0.0195629019352835 0.0490453123174164 -0.458854112833957 0.87859672377603 0.132365781474624 0.0151604640000852 0.0437694008004803 -0.126442266632184 0.991007867154687 0.13596023399051 5.35703946816845e-05 9.5364195992286e-06 -4.97475415096272e-06 3.05072287072886e-06 -4.93769257794775e-06 6.68268780013653e-07 9.5364195992286e-06 3.23506431410171e-05 -4.62341364656392e-06 1.24870018834232e-05 -8.03919831807682e-06 2.86004934041615e-06 -4.97475415096272e-06 -4.62341364656392e-06 1.11846071252996e-05 3.63087325115917e-06 -4.0981509102361e-07 -2.77028170194241e-07 3.05072287072886e-06 1.24870018834232e-05 3.63087325115917e-06 8.6684695356093e-05 -4.83481583023223e-05 8.13126810414983e-06 -4.93769257794775e-06 -8.03919831807682e-06 -4.0981509102361e-07 -4.83481583023223e-05 8.13693058827971e-05 1.42667874463412e-05 6.68268780013653e-07 2.86004934041615e-06 -2.77028170194241e-07 8.13126810414983e-06 1.42667874463412e-05 4.59756863997822e-05 1538 1560 0 266 0 1509 1531 0 266 0 0 0 0 0 0 0 0 0 268 0 938 925 0 0 1397 +433 382 0.887329827230015 0.460599727541677 0.0222186564959435 0.0528048642206696 -0.459210548280657 0.878202150094984 0.133741003122922 0.0213726911982346 0.0420885976926088 -0.128875422626193 0.990767215539145 0.13915300926048 6.00259411284999e-05 5.5772949459298e-06 -6.10868484904492e-06 4.42682658092819e-06 -3.71895215349652e-06 1.51820715028557e-05 5.5772949459298e-06 3.19919175568231e-05 -5.1834465231233e-06 4.17983235525291e-06 2.08615640380785e-07 1.36928139782265e-05 -6.10868484904492e-06 -5.1834465231233e-06 1.12205452725954e-05 8.29635894665859e-07 4.33885900165102e-07 4.95873326632513e-07 4.42682658092819e-06 4.17983235525291e-06 8.29635894665859e-07 5.44336558375063e-05 -1.87323185878761e-05 1.03104374699337e-05 -3.71895215349652e-06 2.08615640380785e-07 4.33885900165102e-07 -1.87323185878761e-05 5.32319423054564e-05 1.12607620970169e-05 1.51820715028557e-05 1.36928139782265e-05 4.95873326632513e-07 1.03104374699337e-05 1.12607620970169e-05 4.89838986563079e-05 1604 1628 0 271 0 1600 1624 0 271 0 0 0 0 0 0 0 0 0 276 0 819 808 0 0 1448 +433 383 0.887364849270414 0.460513452867794 0.0226049553655136 0.055807318412243 -0.459168468022171 0.878200806170031 0.133894219503607 0.0198160829936306 0.0418083993172129 -0.129192506632891 0.990737782653131 0.138868133648975 5.48751997187384e-05 8.94653640566252e-06 -3.55273956791803e-06 1.07391806088444e-06 -5.54566818148305e-06 1.25398152762049e-05 8.94653640566252e-06 2.57452821212263e-05 -4.15243474590772e-06 3.76989187318312e-06 -3.33221036678989e-06 1.53594393343174e-05 -3.55273956791803e-06 -4.15243474590772e-06 1.09489677408422e-05 1.65363846645608e-06 1.89586123353822e-06 7.43171526250353e-07 1.07391806088444e-06 3.76989187318312e-06 1.65363846645608e-06 4.74185702441086e-05 -9.22682054937014e-06 9.254396440827e-06 -5.54566818148305e-06 -3.33221036678989e-06 1.89586123353822e-06 -9.22682054937014e-06 4.41340642229842e-05 4.18695514546686e-06 1.25398152762049e-05 1.53594393343174e-05 7.43171526250353e-07 9.254396440827e-06 4.18695514546686e-06 4.97935149395964e-05 1700 1723 0 271 0 1681 1704 0 271 0 0 0 0 0 0 0 0 0 258 0 926 912 0 0 1377 +433 394 0.886265682181231 0.462431750952232 0.0262681613191716 0.0547570861445867 -0.461955928328526 0.87839039559342 0.122584800082899 0.0413878358031868 0.0336134031298054 -0.120777434318202 0.992110351971768 0.141588906452062 5.23707493223818e-05 4.99623228447658e-06 -1.13042023724807e-06 1.49637041739408e-06 -3.66609149533716e-06 6.16642703145335e-06 4.99623228447658e-06 2.82009126473417e-05 -3.39000717545322e-06 2.24275796653191e-06 3.00491505344974e-07 1.20088577717119e-05 -1.13042023724807e-06 -3.39000717545322e-06 1.07781229518762e-05 1.52606891939127e-06 4.17246586489879e-06 -1.5090703848304e-07 1.49637041739408e-06 2.24275796653191e-06 1.52606891939127e-06 5.27283314826528e-05 -2.06793764531208e-05 1.16249555307715e-05 -3.66609149533716e-06 3.00491505344974e-07 4.17246586489879e-06 -2.06793764531208e-05 6.05329400801618e-05 1.52761884475507e-05 6.16642703145335e-06 1.20088577717119e-05 -1.5090703848304e-07 1.16249555307715e-05 1.52761884475507e-05 4.83623300562159e-05 1600 1618 0 265 0 1600 1618 0 265 0 0 0 0 0 0 0 0 0 87 0 678 664 0 0 1333 +433 393 0.886109213388019 0.462512478806841 0.02987756510859 0.0630241849662025 -0.462436177801042 0.877964553955338 0.123818510162125 0.0354143033090759 0.0310361629334195 -0.123533189653455 0.991854983172648 0.151793416071229 7.2264947478587e-05 3.48906103295134e-06 -5.04627444221399e-06 3.21415501793358e-07 -2.73821373748512e-06 1.21338049867573e-05 3.48906103295134e-06 3.20961188405693e-05 -2.97946567283126e-06 9.40608414222976e-06 -2.59506538160739e-06 2.22114158883418e-05 -5.04627444221399e-06 -2.97946567283126e-06 1.01191485929911e-05 2.89133623717464e-06 1.23021912302463e-06 5.61297903923149e-07 3.21415501793358e-07 9.40608414222976e-06 2.89133623717464e-06 3.68834938253673e-05 1.94424113050768e-07 2.08757200105311e-05 -2.73821373748512e-06 -2.59506538160739e-06 1.23021912302463e-06 1.94424113050768e-07 4.47747637683636e-05 1.22893578747418e-05 1.21338049867573e-05 2.22114158883418e-05 5.61297903923149e-07 2.08757200105311e-05 1.22893578747418e-05 6.63973796055463e-05 2026 2049 0 263 0 2018 2041 0 263 0 0 0 0 0 0 0 0 0 75 0 698 683 0 0 1308 +433 389 0.887022998763321 0.461214133281881 0.0217191833633152 0.0521459336143148 -0.459933665047842 0.878463305521007 0.129472949332147 0.0185973987305035 0.0406352484991203 -0.124834867381468 0.991345062258983 0.139865687478262 3.58580827472288e-05 -5.89608405395699e-06 1.3061469121185e-06 -3.67385276250924e-06 -7.16127282004199e-06 -7.51832573785906e-06 -5.89608405395699e-06 2.78785537895851e-05 -4.93656117764799e-06 7.19716358126692e-06 1.22489999351717e-06 8.29806294015541e-06 1.3061469121185e-06 -4.93656117764799e-06 9.71352072072358e-06 1.4642844336499e-06 2.21297359365874e-06 1.54988522387317e-06 -3.67385276250924e-06 7.19716358126692e-06 1.4642844336499e-06 3.94923246606495e-05 -2.35924865558939e-06 7.19941518468985e-06 -7.16127282004199e-06 1.22489999351717e-06 2.21297359365874e-06 -2.35924865558939e-06 4.1367094388905e-05 -3.16525496368674e-07 -7.51832573785906e-06 8.29806294015541e-06 1.54988522387317e-06 7.19941518468985e-06 -3.16525496368674e-07 3.25055069791651e-05 1975 1993 0 271 0 1968 1986 0 271 0 0 0 0 0 0 0 0 0 131 0 676 660 0 0 1336 +433 381 0.887354010244762 0.460488853010901 0.0235133314365228 0.059450781243658 -0.459137191882512 0.877761675192782 0.136848385423438 0.0188235415299207 0.0423780548489472 -0.132228808568576 0.9903129013861 0.142534270012081 5.08256242508932e-05 7.55418826081705e-06 -6.00054466344981e-06 1.11053258797373e-05 -5.51584804330498e-06 1.16634802929535e-05 7.55418826081705e-06 2.40025783904524e-05 -5.0662441866969e-06 2.47298741059986e-06 -1.5975936719475e-06 1.14517450386866e-05 -6.00054466344981e-06 -5.0662441866969e-06 1.21029584349018e-05 3.49380034556341e-07 2.4725621688453e-06 1.03843849496764e-06 1.11053258797373e-05 2.47298741059986e-06 3.49380034556341e-07 4.97047928974572e-05 -1.38974723767574e-05 1.03862874972077e-05 -5.51584804330498e-06 -1.5975936719475e-06 2.4725621688453e-06 -1.38974723767574e-05 5.10153738358751e-05 4.60574076207091e-06 1.16634802929535e-05 1.14517450386866e-05 1.03843849496764e-06 1.03862874972077e-05 4.60574076207091e-06 3.93450650681084e-05 1760 1778 0 267 0 1755 1773 0 267 0 0 0 0 0 0 0 0 0 261 0 839 829 0 0 1372 +433 378 0.887318946652597 0.460635903583923 0.021900941549373 0.0591117268853647 -0.459219307524837 0.878246858907644 0.133416949505172 0.00153914591823147 0.0422222039658687 -0.128440722312977 0.990817978411769 0.141397659569269 5.80976016185543e-05 4.28292284533951e-07 -4.97144691221746e-06 -4.502443830657e-08 9.2729686515374e-06 1.06818917719281e-06 4.28292284533951e-07 3.32656448918253e-05 -2.23843658264764e-06 4.52511676300866e-06 -6.16472727259712e-06 3.86018753473411e-06 -4.97144691221746e-06 -2.23843658264764e-06 1.15548525474876e-05 2.1955104756115e-06 -4.65447225652659e-07 1.56310825547418e-07 -4.502443830657e-08 4.52511676300866e-06 2.1955104756115e-06 7.37165578307837e-05 -3.40441412650229e-05 -5.27202660160186e-06 9.2729686515374e-06 -6.16472727259712e-06 -4.65447225652659e-07 -3.40441412650229e-05 6.65752897276404e-05 1.4482540493037e-05 1.06818917719281e-06 3.86018753473411e-06 1.56310825547418e-07 -5.27202660160186e-06 1.4482540493037e-05 4.27492981715649e-05 1675 1691 0 266 0 1675 1691 0 266 0 0 0 0 0 0 0 0 0 280 0 713 699 0 0 1410 +433 373 0.887292798147387 0.460710191872887 0.0213918082505579 0.0510580386166996 -0.459334168636212 0.878564346378392 0.130907642236763 0.0134795754744781 0.0415164049390231 -0.12597939663753 0.991163750216776 0.139136359240714 5.35710156209617e-05 1.08847012665383e-05 -4.930488445703e-06 7.53397478914793e-06 1.28705529024577e-06 7.4382928977945e-06 1.08847012665383e-05 2.90154483345151e-05 -5.00199313547944e-06 2.05601107501219e-06 1.00436152996062e-05 6.42430045933473e-06 -4.930488445703e-06 -5.00199313547944e-06 1.08464731144649e-05 7.42834295895745e-07 8.72071999577851e-07 -2.74822514592614e-07 7.53397478914793e-06 2.05601107501219e-06 7.42834295895745e-07 7.22213568423234e-05 -3.595885035105e-05 5.86314611837323e-06 1.28705529024577e-06 1.00436152996062e-05 8.72071999577851e-07 -3.595885035105e-05 7.59344564922932e-05 8.04882349772515e-06 7.4382928977945e-06 6.42430045933473e-06 -2.74822514592614e-07 5.86314611837323e-06 8.04882349772515e-06 4.82953369048131e-05 1696 1721 0 275 0 1688 1713 0 275 0 0 0 0 0 0 0 0 0 269 0 800 788 0 0 1335 +433 392 0.886208660273562 0.462311195358293 0.0300427878620736 0.0616955187450921 -0.462227722877102 0.877941440856782 0.124757198710804 0.040724695900621 0.0313008412025601 -0.12444751935135 0.991732359191384 0.153292525397738 5.95551054608273e-05 6.63000355007225e-06 -2.63141795481932e-06 1.30872635658935e-05 -1.19271953752247e-05 1.83564200152585e-05 6.63000355007225e-06 2.87890492643475e-05 -5.1718634781383e-06 -1.90162859725633e-06 -8.53831859203284e-07 1.34945731787363e-05 -2.63141795481932e-06 -5.1718634781383e-06 1.13073394912083e-05 2.2321038214439e-06 1.23752519395463e-06 -1.75168499655669e-06 1.30872635658935e-05 -1.90162859725633e-06 2.2321038214439e-06 3.75150798298791e-05 -4.46433279277779e-06 1.35631344881897e-05 -1.19271953752247e-05 -8.53831859203284e-07 1.23752519395463e-06 -4.46433279277779e-06 5.20313381247748e-05 1.2345891851624e-05 1.83564200152585e-05 1.34945731787363e-05 -1.75168499655669e-06 1.35631344881897e-05 1.2345891851624e-05 5.98563004747807e-05 1677 1696 0 263 0 1675 1694 0 263 0 0 0 0 0 0 0 0 0 67 0 809 800 0 0 1198 +433 384 0.887357893631365 0.460565733780848 0.0217984741900865 0.055889393619985 -0.459169735995032 0.878390443290795 0.13264004931262 0.0214101692782647 0.0419418902335016 -0.127708394408163 0.990924539932951 0.137692431167812 4.7251698791734e-05 1.15883077426895e-06 -3.1345817140824e-06 1.17336454244948e-05 -1.31800689014924e-05 1.58144619925282e-06 1.15883077426895e-06 2.78545711321364e-05 -3.38520821871694e-06 4.17745466564426e-06 -4.38894344068652e-06 7.38876306146955e-06 -3.1345817140824e-06 -3.38520821871694e-06 1.18802889340649e-05 1.42213098944226e-06 9.52967464457146e-07 -2.38809196476111e-07 1.17336454244948e-05 4.17745466564426e-06 1.42213098944226e-06 5.51327886911206e-05 -2.79247408267882e-05 2.14779296525098e-07 -1.31800689014924e-05 -4.38894344068652e-06 9.52967464457146e-07 -2.79247408267882e-05 7.32657887230216e-05 1.26048671571216e-05 1.58144619925282e-06 7.38876306146955e-06 -2.38809196476111e-07 2.14779296525098e-07 1.26048671571216e-05 3.87938836318714e-05 1644 1665 0 268 0 1619 1640 0 268 0 0 0 0 0 0 0 0 0 281 0 923 910 0 0 1400 +433 388 0.887337065536732 0.460786885279206 0.0175607083954063 0.0489923662985901 -0.458906967827972 0.87870755967032 0.131443598007539 0.0140679190242865 0.0451367588955762 -0.124693507982246 0.991168099801181 0.136883454671425 5.54890468687229e-05 6.84333538575023e-07 -3.36363332613104e-07 2.78332081052178e-07 -1.03868582254113e-05 9.36187753984174e-06 6.84333538575023e-07 3.70800718094499e-05 -3.06700703967387e-06 1.04607647162234e-05 3.20434444994701e-06 1.92629108591346e-05 -3.36363332613104e-07 -3.06700703967387e-06 1.07343462416217e-05 2.16763801048131e-07 1.27865066339359e-06 2.60023600049548e-06 2.78332081052178e-07 1.04607647162234e-05 2.16763801048131e-07 5.28842593325687e-05 6.85249689654437e-07 1.59226889861048e-05 -1.03868582254113e-05 3.20434444994701e-06 1.27865066339359e-06 6.85249689654437e-07 4.60125977835676e-05 1.06725234512434e-06 9.36187753984174e-06 1.92629108591346e-05 2.60023600049548e-06 1.59226889861048e-05 1.06725234512434e-06 4.6264856825351e-05 1839 1852 0 262 0 1835 1848 0 262 0 0 0 0 0 0 0 0 0 280 0 824 814 0 0 1383 +433 379 0.88725447616681 0.460837884670047 0.0201974893191175 0.0567620693974193 -0.459133033957981 0.878057496653403 0.134951434595185 0.00926507959577088 0.0444561767418051 -0.129009598959131 0.990646340388893 0.142978684795095 5.26467171735326e-05 2.73830788606109e-06 -5.01720475354669e-06 2.27315035665749e-06 2.15125980073367e-06 -2.5735794588247e-06 2.73830788606109e-06 3.08717043492898e-05 -3.68083566089649e-06 8.54151864496858e-06 2.69257956550041e-06 3.70520408266735e-06 -5.01720475354669e-06 -3.68083566089649e-06 1.25314685065612e-05 1.06343349070968e-06 2.19375053216692e-06 9.80831361776126e-07 2.27315035665749e-06 8.54151864496858e-06 1.06343349070968e-06 7.31629451678709e-05 -3.55089344440381e-05 6.38131989951728e-06 2.15125980073367e-06 2.69257956550041e-06 2.19375053216692e-06 -3.55089344440381e-05 6.7388064776772e-05 -2.42677973469475e-06 -2.5735794588247e-06 3.70520408266735e-06 9.80831361776126e-07 6.38131989951728e-06 -2.42677973469475e-06 4.77076518623566e-05 1760 1776 0 267 0 1720 1736 0 267 0 0 0 0 0 0 0 0 0 266 0 939 926 0 0 1382 +433 387 0.887438431442405 0.460444270565009 0.021073777613462 0.0556242443025201 -0.458897227851624 0.878322633189593 0.134024946547256 0.0187173811019922 0.0432014429057576 -0.128609586465228 0.99075385924058 0.137528735976366 5.52480780655539e-05 4.78103118681527e-06 -5.69432412006899e-06 3.17116556990323e-06 -3.66132136223428e-06 8.91761994743176e-06 4.78103118681527e-06 2.77999799746273e-05 -3.90444502523516e-06 1.42047157874571e-06 -1.22004708729199e-06 1.06230698959246e-05 -5.69432412006899e-06 -3.90444502523516e-06 1.20584641837615e-05 -1.30688997925171e-06 -4.01947553077463e-07 -7.72708101138825e-07 3.17116556990323e-06 1.42047157874571e-06 -1.30688997925171e-06 3.95951484115262e-05 -2.07822466282959e-06 2.89699654761103e-06 -3.66132136223428e-06 -1.22004708729199e-06 -4.01947553077463e-07 -2.07822466282959e-06 5.19591135197882e-05 1.3021110914462e-05 8.91761994743176e-06 1.06230698959246e-05 -7.72708101138825e-07 2.89699654761103e-06 1.3021110914462e-05 4.30983996989477e-05 1606 1629 0 269 0 1582 1605 0 269 0 0 0 0 0 0 0 0 0 254 0 923 910 0 0 1388 +434 334 0.846801702638946 0.520026497960175 -0.111800348063227 0.0564309807180476 -0.518757314792922 0.853865925738563 0.0424715105860769 0.0674333911027561 0.117548818610057 0.0220323008762559 0.992822669443782 0.0793987873754712 5.81480901690244e-05 -1.77419778659864e-05 -9.64129569071428e-06 -1.41319227201135e-05 5.17775530750402e-06 -2.62219684794111e-05 -1.77419778659864e-05 7.69521087049488e-05 -4.13291018965341e-06 1.92781898706316e-05 -1.40756550890911e-07 5.7860005901959e-05 -9.64129569071428e-06 -4.13291018965341e-06 1.79096876811542e-05 6.37798783727891e-06 -5.63767696766666e-06 6.20535001582298e-07 -1.41319227201135e-05 1.92781898706316e-05 6.37798783727891e-06 0.000106586899350667 -7.00941368505615e-05 2.16315301567522e-05 5.17775530750402e-06 -1.40756550890911e-07 -5.63767696766666e-06 -7.00941368505615e-05 0.000155097744705155 1.54046916404743e-05 -2.62219684794111e-05 5.7860005901959e-05 6.20535001582298e-07 2.16315301567522e-05 1.54046916404743e-05 0.00010547371943519 1501 1480 0 52 0 1532 1511 0 52 0 0 0 0 0 0 0 0 0 491 0 916 886 0 0 1252 +434 432 0.970514386599349 0.237975024883459 0.0383368352293929 0.0418603008550963 -0.236133555003027 0.97058160902843 -0.0470349276327198 0.00403544501442808 -0.0484021652957902 0.036595460749932 0.998157303558502 0.13400381802512 4.34695754726587e-05 -4.04995176445703e-06 -6.27559001065419e-06 -5.5873567223889e-07 -3.29228096145452e-06 6.34595012728311e-06 -4.04995176445703e-06 3.68422678709501e-05 5.54659983923667e-06 3.61907933136404e-07 2.49541974317516e-06 3.79972852546662e-06 -6.27559001065419e-06 5.54659983923667e-06 1.47859811440697e-05 5.84065803193855e-07 2.12076760997929e-06 1.60722854797657e-06 -5.5873567223889e-07 3.61907933136404e-07 5.84065803193855e-07 2.78068097792774e-05 4.81832334618915e-06 2.40791904690279e-06 -3.29228096145452e-06 2.49541974317516e-06 2.12076760997929e-06 4.81832334618915e-06 4.995807280783e-05 8.08852410237671e-06 6.34595012728311e-06 3.79972852546662e-06 1.60722854797657e-06 2.40791904690279e-06 8.08852410237671e-06 4.5303599846271e-05 2169 2169 0 0 0 2164 2164 0 0 0 0 0 0 0 0 0 0 0 1054 0 499 465 0 0 2360 +434 335 0.849841798336443 0.514115606088053 -0.115991643565366 0.070735751447364 -0.510132798526616 0.857707790754278 0.0640458706461206 0.0592230558720235 0.132413917953075 0.00474228385177976 0.991183164241698 0.0928493389584175 5.08320860951051e-05 -5.21087239210977e-06 -7.21059509852715e-06 -5.61086494375989e-06 3.83995143059465e-06 -1.05835866694049e-05 -5.21087239210977e-06 5.16564780704057e-05 -3.12888340510529e-06 4.31450840528245e-06 2.07051802876347e-06 2.43915891231734e-05 -7.21059509852715e-06 -3.12888340510529e-06 1.7941316892038e-05 -1.76126800428884e-06 -8.50156693253214e-07 -2.23883592658764e-06 -5.61086494375989e-06 4.31450840528245e-06 -1.76126800428884e-06 8.90688838791303e-05 -4.10476652244258e-05 1.26605368794635e-05 3.83995143059465e-06 2.07051802876347e-06 -8.50156693253214e-07 -4.10476652244258e-05 0.000115606435627428 -3.39822439670056e-06 -1.05835866694049e-05 2.43915891231734e-05 -2.23883592658764e-06 1.26605368794635e-05 -3.39822439670056e-06 7.3177911606024e-05 1542 1519 0 72 0 1573 1550 0 72 0 0 0 0 0 0 0 0 0 438 0 807 775 0 0 1199 +434 338 0.872292161109309 0.470438847724064 -0.133392939165857 0.0991161735088206 -0.466349521491063 0.882398194135109 0.0623822955024431 0.0349481300992372 0.147052743844878 0.00779214599149809 0.989097959247991 0.152466696321418 6.4689685732897e-05 1.07160375011948e-05 -8.84884159274086e-06 2.85906698973629e-05 -2.07753108119872e-05 7.14843161052271e-06 1.07160375011948e-05 7.05711123687857e-05 -4.58864780254019e-06 1.83507588006922e-06 2.16886928690332e-05 1.89276394382489e-05 -8.84884159274086e-06 -4.58864780254019e-06 2.03325807223301e-05 5.09870285969506e-06 -9.80469031755496e-06 -5.80056837113217e-06 2.85906698973629e-05 1.83507588006922e-06 5.09870285969506e-06 0.000116823512391074 -0.000112639403229895 -5.69402788203429e-08 -2.07753108119872e-05 2.16886928690332e-05 -9.80469031755496e-06 -0.000112639403229895 0.000256543152104848 2.11166341557733e-05 7.14843161052271e-06 1.89276394382489e-05 -5.80056837113217e-06 -5.69402788203429e-08 2.11166341557733e-05 7.28094695640384e-05 1351 1336 0 62 0 1386 1371 0 62 0 0 0 0 0 0 0 0 0 385 0 569 547 0 0 886 +434 431 0.930183563282479 0.367010831059534 0.00784783308311918 0.061104315598032 -0.366995408043968 0.93021663223744 -0.00337454937397405 0.000548052413574395 -0.00853868103113433 0.000258831656555569 0.999963511300498 0.184134722459398 5.13787429294321e-05 -2.47298841374078e-06 -8.71030382476057e-06 2.50034606896327e-07 -5.6867447088261e-06 6.38069738782821e-06 -2.47298841374078e-06 3.54335966482715e-05 1.04157423775682e-06 -1.86813869115284e-06 1.26729130581591e-06 1.29807524721937e-05 -8.71030382476057e-06 1.04157423775682e-06 1.4282637976126e-05 1.50300326113136e-06 1.69265429425264e-06 -1.41825669092165e-06 2.50034606896327e-07 -1.86813869115284e-06 1.50300326113136e-06 3.30624972262369e-05 -6.97165499548989e-06 5.62580258238313e-06 -5.6867447088261e-06 1.26729130581591e-06 1.69265429425264e-06 -6.97165499548989e-06 5.72037070429583e-05 -3.72729079516475e-06 6.38069738782821e-06 1.29807524721937e-05 -1.41825669092165e-06 5.62580258238313e-06 -3.72729079516475e-06 5.4875989932368e-05 1584 1582 0 0 0 1590 1588 0 0 0 0 0 0 0 0 0 0 0 627 0 701 665 0 0 1875 +433 391 0.886470618137274 0.461992364318728 0.0270720980071746 0.0620678424353902 -0.461494276970723 0.878118845100808 0.126215396058062 0.0268451702818232 0.0345380298017725 -0.124379858457932 0.991633387551769 0.151828971067052 4.77773279857216e-05 3.99169502569737e-06 -3.64861189394138e-06 1.08867367281846e-05 -1.22066375734697e-06 1.38796849077186e-05 3.99169502569737e-06 2.59338011599021e-05 -6.76661499045842e-06 4.87661911405446e-06 2.45178768391622e-06 1.66693104905182e-05 -3.64861189394138e-06 -6.76661499045842e-06 1.09915881634406e-05 -5.73880962499263e-07 2.79838801369838e-06 -2.88736658591196e-06 1.08867367281846e-05 4.87661911405446e-06 -5.73880962499263e-07 4.14452822673931e-05 -8.00692272424586e-07 1.92718199385296e-05 -1.22066375734697e-06 2.45178768391622e-06 2.79838801369838e-06 -8.00692272424586e-07 4.13865944718526e-05 2.17084177315444e-05 1.38796849077186e-05 1.66693104905182e-05 -2.88736658591196e-06 1.92718199385296e-05 2.17084177315444e-05 7.28006139982913e-05 1583 1603 0 265 0 1569 1589 0 265 0 0 0 0 0 0 0 0 0 48 0 914 902 0 0 1229 +433 372 0.887440285380808 0.460331779028589 0.023332233060822 0.0544918438727932 -0.459128179799004 0.87838934639005 0.132791079003504 0.0249139823409319 0.0406331686886934 -0.128556638742757 0.99086938404488 0.134658882024713 6.24025206899685e-05 9.0358966666101e-06 -4.73094448063602e-06 1.22523563900993e-06 6.28355251678475e-06 1.40315984167573e-06 9.0358966666101e-06 3.55252602515481e-05 -1.89618368754656e-06 4.53101787183855e-06 -4.50986116920106e-07 4.98090696247311e-06 -4.73094448063602e-06 -1.89618368754656e-06 1.14456421655277e-05 2.38477940951009e-06 1.65854076663567e-06 -5.56891279965208e-07 1.22523563900993e-06 4.53101787183855e-06 2.38477940951009e-06 4.53195218092962e-05 -5.11626694597062e-06 9.03907167252331e-06 6.28355251678475e-06 -4.50986116920106e-07 1.65854076663567e-06 -5.11626694597062e-06 4.67562269746321e-05 -9.75522874073768e-07 1.40315984167573e-06 4.98090696247311e-06 -5.56891279965208e-07 9.03907167252331e-06 -9.75522874073768e-07 4.74876909001607e-05 1353 1375 0 261 0 1334 1356 0 261 0 0 0 0 0 0 0 0 0 276 0 867 853 0 0 1406 +434 336 0.859463140261267 0.496125958971715 -0.123215840567024 0.0804016204275131 -0.490952673887816 0.868250062086224 0.0714653880537461 0.0458772064805803 0.142437995403775 -0.000928720444947323 0.989803291034986 0.102638324224697 5.49079780766935e-05 -9.4983665376613e-06 -5.30455725657288e-06 -3.89253846154991e-07 -4.34327294743151e-07 -1.06998856083846e-05 -9.4983665376613e-06 3.81340256284083e-05 -1.83764574780475e-06 1.27962882066266e-05 -2.37960982430961e-06 1.65336448118264e-05 -5.30455725657288e-06 -1.83764574780475e-06 1.85682809362911e-05 3.06226518124712e-06 -1.01673768701024e-05 -6.36100664453936e-06 -3.89253846154991e-07 1.27962882066266e-05 3.06226518124712e-06 0.000127833761747144 -8.48303977225128e-05 2.2631062394247e-05 -4.34327294743151e-07 -2.37960982430961e-06 -1.01673768701024e-05 -8.48303977225128e-05 0.000190089795310198 1.44672987026258e-05 -1.06998856083846e-05 1.65336448118264e-05 -6.36100664453936e-06 2.2631062394247e-05 1.44672987026258e-05 7.766154679084e-05 1510 1492 0 82 0 1536 1518 0 82 0 0 0 0 0 0 0 0 0 419 0 681 652 0 0 1067 +434 341 0.837623368490557 0.53329870853033 -0.118235274086943 0.107745383860733 -0.531498679946409 0.845644622474088 0.0489318474603433 0.0050849005179571 0.126080314774978 0.0218554332041135 0.991779256823666 0.171069752079762 7.74974071184038e-05 1.51689489324335e-05 -1.65894760087647e-05 5.28302195502507e-06 1.70771933261617e-05 1.56671627285262e-05 1.51689489324335e-05 7.35030310526635e-05 -5.87962130717487e-06 -6.97240138387048e-06 2.77852747320596e-05 2.01589273054522e-05 -1.65894760087647e-05 -5.87962130717487e-06 2.32724053120749e-05 -3.13084644515229e-06 -8.64741766161214e-06 -2.03418193019741e-06 5.28302195502507e-06 -6.97240138387048e-06 -3.13084644515229e-06 5.84174395352397e-05 -1.14239782317567e-05 3.99579657852283e-08 1.70771933261617e-05 2.77852747320596e-05 -8.64741766161214e-06 -1.14239782317567e-05 8.97673623966021e-05 2.2080281029096e-05 1.56671627285262e-05 2.01589273054522e-05 -2.03418193019741e-06 3.99579657852283e-08 2.2080281029096e-05 8.43384272282939e-05 1109 1108 0 114 0 1138 1137 0 114 0 0 0 0 0 0 0 0 0 208 0 711 685 0 0 858 +434 337 0.874970782467348 0.471746125714199 -0.109003315096925 0.0882068097268765 -0.464808846531984 0.881445381961911 0.0837064800575603 0.0612316777249215 0.13556867637505 -0.022575019195187 0.990510728106594 0.132577485170854 6.51770686390358e-05 -6.85362840986835e-06 -9.06249098964411e-06 3.45999640316293e-06 7.39888910515481e-06 7.10133189766161e-07 -6.85362840986835e-06 8.40542295335822e-05 3.94027667387357e-06 1.01611324802477e-05 -3.04310980167186e-06 3.26462465022888e-05 -9.06249098964411e-06 3.94027667387357e-06 1.92491545380895e-05 2.63454388773794e-06 -5.90433493309742e-06 -1.17189287979356e-06 3.45999640316293e-06 1.01611324802477e-05 2.63454388773794e-06 0.000116315415739415 -0.000107008153114403 1.2831746901875e-05 7.39888910515481e-06 -3.04310980167186e-06 -5.90433493309742e-06 -0.000107008153114403 0.000205860282012651 1.40211865425145e-05 7.10133189766161e-07 3.26462465022888e-05 -1.17189287979356e-06 1.2831746901875e-05 1.40211865425145e-05 0.0001045857628021 1293 1278 0 61 0 1325 1310 0 61 0 0 0 0 0 0 0 0 0 423 0 660 637 0 0 1011 +434 342 0.83560700034465 0.530926523509337 -0.140989246431439 0.116088494811259 -0.530824408354144 0.846465372044489 0.0414948361252015 -0.0137080879519764 0.141373224022403 0.0401671577768929 0.98914114815108 0.171228782645298 6.5686140906121e-05 -6.3062605030527e-06 -7.02898487719155e-06 3.85363278436568e-06 -3.33650070732367e-06 -1.47507537519577e-05 -6.3062605030527e-06 7.4844192887527e-05 3.3675422035365e-06 1.13294132300375e-05 -2.12047893998444e-06 7.54555086945871e-06 -7.02898487719155e-06 3.3675422035365e-06 1.7510099186676e-05 -5.41390447050482e-07 -3.81508905974513e-06 7.20389394841332e-07 3.85363278436568e-06 1.13294132300375e-05 -5.41390447050482e-07 6.50638373691687e-05 4.59130118058324e-06 2.2091169857523e-05 -3.33650070732367e-06 -2.12047893998444e-06 -3.81508905974513e-06 4.59130118058324e-06 6.93233629567926e-05 1.31652335178349e-05 -1.47507537519577e-05 7.54555086945871e-06 7.20389394841332e-07 2.2091169857523e-05 1.31652335178349e-05 9.60046609513596e-05 1012 1004 0 101 0 1045 1037 0 101 0 0 0 0 0 0 0 0 0 195 0 754 724 0 0 1003 +434 340 0.847545841990734 0.517184020260678 -0.11910808079732 0.103868272015035 -0.516276887977958 0.855450386236331 0.0407775873232848 0.0237337086003552 0.122980570270323 0.0269318747048034 0.992043574376081 0.171083342483006 6.33898634959449e-05 -2.28048061155203e-05 -9.22077739146624e-06 1.33800309116843e-05 -1.0115173200084e-05 2.84873472435255e-06 -2.28048061155203e-05 8.74289031757017e-05 -4.18513322258252e-06 2.07357778208074e-05 5.56632549141757e-06 1.8052858750169e-05 -9.22077739146624e-06 -4.18513322258252e-06 1.87293180638223e-05 -1.01927548347202e-06 -3.57373547324411e-06 3.98608412651853e-07 1.33800309116843e-05 2.07357778208074e-05 -1.01927548347202e-06 0.000106999326965908 -7.2396376546719e-05 2.26700748483193e-05 -1.0115173200084e-05 5.56632549141757e-06 -3.57373547324411e-06 -7.2396376546719e-05 0.000159161957785882 1.04269612076681e-05 2.84873472435255e-06 1.8052858750169e-05 3.98608412651853e-07 2.26700748483193e-05 1.04269612076681e-05 7.83105835774058e-05 1144 1134 0 97 0 1173 1163 0 97 0 0 0 0 0 0 0 0 0 271 0 738 708 0 0 926 +434 436 0.98956863792162 -0.143120599819814 0.0164439882378502 -0.0590746355796549 0.143238206894738 0.989668785447517 -0.00620573899043955 0.0535665976977973 -0.0153859327806296 0.00849641206945418 0.999845530096732 -0.198038957868091 7.23959919379909e-05 8.90921242821284e-07 -7.30795181603921e-06 5.38258646506848e-07 -6.01144929081307e-06 1.27690542487627e-05 8.90921242821284e-07 4.17513389056845e-05 1.63937002304566e-06 7.54187100546649e-06 -8.06198142689981e-06 8.87251563377813e-06 -7.30795181603921e-06 1.63937002304566e-06 1.18307674087177e-05 1.30578478876308e-06 5.34137107323022e-07 3.3601360483487e-07 5.38258646506848e-07 7.54187100546649e-06 1.30578478876308e-06 3.84158068236426e-05 -3.05272989196858e-06 2.3580089580462e-06 -6.01144929081307e-06 -8.06198142689981e-06 5.34137107323022e-07 -3.05272989196858e-06 6.06470061704549e-05 -1.33922086730194e-05 1.27690542487627e-05 8.87251563377813e-06 3.3601360483487e-07 2.3580089580462e-06 -1.33922086730194e-05 7.55388373138013e-05 1794 1791 0 0 206 1794 1791 0 0 201 0 0 0 0 0 0 0 0 2200 0 0 0 0 0 2710 +434 430 0.873823218651411 0.484567053948023 0.0403454182506787 0.0677718622385719 -0.486201644133862 0.871826539917343 0.0593838828074037 0.00514043389663584 -0.00639873325102899 -0.071507024297532 0.997419571538926 0.194973542991378 7.87927834007019e-05 7.49492212337657e-06 -8.55358646124464e-06 3.52106154136898e-06 1.1605128073828e-05 3.27491488474333e-05 7.49492212337657e-06 5.56190423604124e-05 -1.81805681513928e-06 8.46282813893611e-06 1.60452236496162e-05 4.50451304682144e-05 -8.55358646124464e-06 -1.81805681513928e-06 1.30295150319459e-05 6.79959061437505e-07 -2.46013222592952e-07 5.73351863273277e-07 3.52106154136898e-06 8.46282813893611e-06 6.79959061437505e-07 4.11194578604254e-05 7.90418731658462e-06 1.37903729977303e-05 1.1605128073828e-05 1.60452236496162e-05 -2.46013222592952e-07 7.90418731658462e-06 5.91552502538649e-05 2.56859492907176e-05 3.27491488474333e-05 4.50451304682144e-05 5.73351863273277e-07 1.37903729977303e-05 2.56859492907176e-05 0.000126750402375506 1577 1588 0 124 0 1557 1568 0 124 0 0 0 0 0 0 0 0 0 360 0 905 878 0 0 1378 +434 380 0.830224193510917 0.551561436270905 0.080670753857412 0.078046513870375 -0.556659470657702 0.827954009161568 0.0679881786810995 -0.0113504723792262 -0.0292920165955402 -0.101351569953617 0.994419346670057 0.208459043785279 6.94376237551732e-05 -4.86033351739096e-06 -7.6344728321419e-06 1.44014563447615e-05 -1.32933054660398e-05 -3.29190840444309e-06 -4.86033351739096e-06 3.63759591038833e-05 -4.26613817172194e-06 8.72934846361545e-06 5.30006550847289e-06 1.70266469757282e-05 -7.6344728321419e-06 -4.26613817172194e-06 1.28665075572655e-05 -1.07730122628453e-06 3.56268422943665e-06 1.1040855566279e-06 1.44014563447615e-05 8.72934846361545e-06 -1.07730122628453e-06 7.56409496934533e-05 -4.0563947323504e-05 1.12928715040669e-05 -1.32933054660398e-05 5.30006550847289e-06 3.56268422943665e-06 -4.0563947323504e-05 8.6413180167735e-05 1.3317320375398e-05 -3.29190840444309e-06 1.70266469757282e-05 1.1040855566279e-06 1.12928715040669e-05 1.3317320375398e-05 6.134195103258e-05 1416 1429 0 195 0 1409 1422 0 195 0 0 0 0 0 0 0 0 0 278 0 1070 1063 0 0 1135 +434 379 0.830143176735642 0.551702379263838 0.0805406160510109 0.0803806652480488 -0.556910550601089 0.827411589525111 0.0723926802150715 -0.015042563209494 -0.0267010252321574 -0.104950208356866 0.994118961200018 0.214247351838007 5.16450943021722e-05 1.17150310836839e-05 -4.10640447860458e-06 1.56968806236532e-05 -8.60851998561948e-06 -3.03748579181828e-06 1.17150310836839e-05 4.03448416734511e-05 -5.54784191241489e-06 1.04621373252184e-05 2.49021756268763e-06 6.02317574769563e-06 -4.10640447860458e-06 -5.54784191241489e-06 1.20003997836696e-05 -5.11305529534325e-07 3.20117590252892e-06 -1.88511350365861e-06 1.56968806236532e-05 1.04621373252184e-05 -5.11305529534325e-07 7.03444151822464e-05 -3.58841427410955e-05 4.63776712766357e-06 -8.60851998561948e-06 2.49021756268763e-06 3.20117590252892e-06 -3.58841427410955e-05 7.30487203894867e-05 6.28991681394347e-06 -3.03748579181828e-06 6.02317574769563e-06 -1.88511350365861e-06 4.63776712766357e-06 6.28991681394347e-06 6.41989510740386e-05 1232 1240 0 183 0 1230 1238 0 183 0 0 0 0 0 0 0 0 0 283 0 1045 1034 0 0 1106 +434 383 0.830070829017866 0.551774006890514 0.0807951987037509 0.078607957093135 -0.556988445004555 0.827423967680281 0.071648097250582 -0.00408361902174105 -0.0273183261749394 -0.104474987572179 0.994152244893503 0.210266334819473 7.96583551302804e-05 -3.07298659263787e-06 -8.9393633364588e-06 9.4660561410628e-06 -4.27746460623092e-06 -3.9038784070761e-06 -3.07298659263787e-06 3.55584181991736e-05 -3.22706160092198e-06 1.17085322106252e-05 -3.49235959171083e-06 2.06148027340573e-05 -8.9393633364588e-06 -3.22706160092198e-06 1.26972831881217e-05 -8.51991147794178e-07 9.93567233096289e-07 1.74356371158683e-06 9.4660561410628e-06 1.17085322106252e-05 -8.51991147794178e-07 5.69189972959869e-05 -1.57751932539783e-05 1.31174061388378e-05 -4.27746460623092e-06 -3.49235959171083e-06 9.93567233096289e-07 -1.57751932539783e-05 5.1735300671739e-05 6.94722627159367e-06 -3.9038784070761e-06 2.06148027340573e-05 1.74356371158683e-06 1.31174061388378e-05 6.94722627159367e-06 5.81939158177345e-05 1511 1523 0 197 0 1499 1511 0 197 0 0 0 0 0 0 0 0 0 266 0 1095 1085 0 0 1076 +434 381 0.830385595751611 0.55122894362146 0.0812798504071665 0.0837692708151669 -0.556530107800949 0.827624257772642 0.0728857122990991 -0.0103764215417839 -0.0270924616693725 -0.105757929538413 0.994022765765675 0.215762040066613 5.85351120181882e-05 -7.20828860851949e-06 -5.84133445164976e-06 5.95544317597849e-06 -9.06901564491532e-06 -3.01927816908843e-07 -7.20828860851949e-06 4.11331911520787e-05 -4.61522492272178e-06 1.02135533862737e-05 5.01525010437114e-06 2.43254221457074e-05 -5.84133445164976e-06 -4.61522492272178e-06 1.2035768889624e-05 1.1668905393769e-06 2.90262211773949e-06 5.65119563666689e-07 5.95544317597849e-06 1.02135533862737e-05 1.1668905393769e-06 5.73051492905009e-05 -1.42539755608354e-05 1.84254471153501e-05 -9.06901564491532e-06 5.01525010437114e-06 2.90262211773949e-06 -1.42539755608354e-05 6.40675534329046e-05 7.60185883342988e-06 -3.01927816908843e-07 2.43254221457074e-05 5.65119563666689e-07 1.84254471153501e-05 7.60185883342988e-06 5.38280947472362e-05 1263 1275 0 200 0 1262 1274 0 200 0 0 0 0 0 0 0 0 0 265 0 987 973 0 0 1131 +434 387 0.830306589067752 0.551317303511756 0.0814874162015289 0.0810964225229324 -0.556604002861293 0.82768826930197 0.0715829089845826 -0.00814216593865075 -0.0279812821268253 -0.104791983035131 0.994100441676848 0.212547264022825 9.13849074074743e-05 -1.59843702102914e-05 -1.02599246553269e-05 -1.04872038994846e-06 -1.38806739635313e-05 -1.86204032314836e-05 -1.59843702102914e-05 4.32926823502056e-05 -3.21917925293645e-06 5.11391922759967e-06 1.01280590334799e-05 3.83390140358776e-05 -1.02599246553269e-05 -3.21917925293645e-06 1.2810826004164e-05 2.4994651392156e-06 1.63040848726687e-06 3.99206448154902e-06 -1.04872038994846e-06 5.11391922759967e-06 2.4994651392156e-06 4.03442371607137e-05 -5.25636842809131e-06 7.40885285062222e-06 -1.38806739635313e-05 1.01280590334799e-05 1.63040848726687e-06 -5.25636842809131e-06 5.5639843714369e-05 2.16075057110641e-05 -1.86204032314836e-05 3.83390140358776e-05 3.99206448154902e-06 7.40885285062222e-06 2.16075057110641e-05 8.53435643853897e-05 1422 1433 0 197 0 1408 1419 0 197 0 0 0 0 0 0 0 0 0 265 0 1105 1094 0 0 1124 +434 388 0.830080732124776 0.552214367786199 0.0776226137519508 0.0758982123344859 -0.556968894072417 0.827849045710815 0.0667203758340769 -0.0099547515338874 -0.0274158565604593 -0.0986166797564253 0.994747767669209 0.212303926550583 9.37514792058746e-05 3.37197981376564e-05 -3.82344775119836e-06 -2.31498252399315e-06 -5.62089870266972e-06 3.6561041353269e-05 3.37197981376564e-05 6.54220476772459e-05 -4.57344894500551e-06 6.66104084500199e-06 1.2489015048081e-05 5.66124835924253e-05 -3.82344775119836e-06 -4.57344894500551e-06 1.35267811611492e-05 -2.85362431183368e-06 2.57655863536058e-07 9.00058828631988e-07 -2.31498252399315e-06 6.66104084500199e-06 -2.85362431183368e-06 4.71443350456051e-05 3.31315643629648e-06 8.61405515940427e-06 -5.62089870266972e-06 1.2489015048081e-05 2.57655863536058e-07 3.31315643629648e-06 5.34098715417284e-05 1.79879031317368e-05 3.6561041353269e-05 5.66124835924253e-05 9.00058828631988e-07 8.61405515940427e-06 1.79879031317368e-05 8.71911633057357e-05 1457 1475 0 214 0 1458 1476 0 214 0 0 0 0 0 0 0 0 0 285 0 1001 986 0 0 1125 +434 385 0.830217184253502 0.551844558247043 0.0787845829037161 0.0769517622054939 -0.556922044011401 0.827211421011176 0.0745593846731237 0.0084562099899237 -0.0240263160794445 -0.105777353350318 0.994099536089748 0.211636736649368 4.87968435023688e-05 -2.17219512024536e-06 -5.6118682633664e-06 -5.55114643758051e-06 5.06123680274627e-06 2.14814223704617e-06 -2.17219512024536e-06 3.55376508662107e-05 -5.69471286590958e-06 9.433054940255e-06 -1.79526468497621e-06 1.50378308535558e-05 -5.6118682633664e-06 -5.69471286590958e-06 1.24816297052704e-05 6.1806240343026e-07 1.90557806423174e-06 2.09490854430802e-07 -5.55114643758051e-06 9.433054940255e-06 6.1806240343026e-07 5.05036532613206e-05 -1.16079733612168e-05 7.33629421466665e-06 5.06123680274627e-06 -1.79526468497621e-06 1.90557806423174e-06 -1.16079733612168e-05 4.71792150488974e-05 1.25615871561733e-05 2.14814223704617e-06 1.50378308535558e-05 2.09490854430802e-07 7.33629421466665e-06 1.25615871561733e-05 4.87026071299078e-05 1470 1482 0 197 0 1465 1477 0 197 0 0 0 0 0 0 0 0 0 274 0 1010 996 0 0 1070 +434 382 0.830337571075837 0.551082221167143 0.0827520608406111 0.0820567481117219 -0.556543292059207 0.82760705597279 0.0729803053429561 -0.00601529040893083 -0.0282680406781268 -0.106653393839761 0.993894346225332 0.216497808097995 5.9295983080756e-05 -9.62033390048797e-06 -5.99283659821596e-06 -1.79975543149735e-06 -9.66531665506015e-06 -3.09172670734608e-06 -9.62033390048797e-06 3.52147768043466e-05 -4.43103748487845e-06 6.47269496004201e-06 4.21640607242235e-06 2.18775184415631e-05 -5.99283659821596e-06 -4.43103748487845e-06 1.2900380063352e-05 3.17426510444348e-06 3.9601033084947e-06 -4.08205752177971e-07 -1.79975543149735e-06 6.47269496004201e-06 3.17426510444348e-06 5.0655931035374e-05 -6.90399583665001e-06 1.28441075232874e-05 -9.66531665506015e-06 4.21640607242235e-06 3.9601033084947e-06 -6.90399583665001e-06 5.15633720693506e-05 1.28899374988505e-05 -3.09172670734608e-06 2.18775184415631e-05 -4.08205752177971e-07 1.28441075232874e-05 1.28899374988505e-05 5.36415674048496e-05 1134 1153 0 202 0 1131 1150 0 202 0 0 0 0 0 0 0 0 0 281 0 992 978 0 0 1182 +434 384 0.830108245178731 0.551353178469577 0.0832464646563578 0.0823197823569691 -0.556853376199081 0.827437749278838 0.0725333611799117 -0.00611601415678549 -0.0288897681190509 -0.106566616066502 0.993885776957374 0.213411451913161 7.03788393269345e-05 -5.86579906148452e-06 -1.00803121049529e-05 8.37526192876427e-06 -7.17425365450382e-06 -2.39526388737192e-06 -5.86579906148452e-06 3.14849907203012e-05 -3.93366426112063e-06 8.51179109253222e-06 4.55123322692676e-07 1.62323666637267e-05 -1.00803121049529e-05 -3.93366426112063e-06 1.2673355017748e-05 -6.21222082968373e-07 2.48025664651907e-06 -2.01156063439452e-06 8.37526192876427e-06 8.51179109253222e-06 -6.21222082968373e-07 5.76722600731126e-05 -1.71012359442721e-05 6.95777857471718e-06 -7.17425365450382e-06 4.55123322692676e-07 2.48025664651907e-06 -1.71012359442721e-05 5.20150015524946e-05 9.25305150897792e-06 -2.39526388737192e-06 1.62323666637267e-05 -2.01156063439452e-06 6.95777857471718e-06 9.25305150897792e-06 5.50764905256109e-05 1463 1473 0 184 0 1450 1460 0 184 0 0 0 0 0 0 0 0 0 287 0 1104 1094 0 0 1091 +434 393 0.828987607412446 0.552640781972955 0.0858353823135323 0.0825079060729385 -0.558285890432284 0.826815643597125 0.0685036936763528 0.00813412448113198 -0.0331121020296331 -0.104709395965181 0.993951473209727 0.218162781224048 0.000110921225516002 -2.42315648521078e-06 -1.10725193451862e-05 1.94323773304506e-07 6.47766842054519e-06 1.1704762365114e-05 -2.42315648521078e-06 4.88743295678079e-05 -4.01914858023224e-06 1.90645918509884e-05 1.01883231606182e-05 3.62972213042571e-05 -1.10725193451862e-05 -4.01914858023224e-06 1.3733926471517e-05 1.56531275457263e-06 1.22878864584301e-06 -4.69743849130064e-07 1.94323773304506e-07 1.90645918509884e-05 1.56531275457263e-06 5.3091392728457e-05 7.08284285259445e-06 2.81752527124569e-05 6.47766842054519e-06 1.01883231606182e-05 1.22878864584301e-06 7.08284285259445e-06 5.53445707597794e-05 2.83021026156104e-05 1.1704762365114e-05 3.62972213042571e-05 -4.69743849130064e-07 2.81752527124569e-05 2.83021026156104e-05 8.90384174366715e-05 1560 1572 0 193 0 1546 1558 0 193 0 0 0 0 0 0 0 0 0 77 0 931 918 0 0 1112 +434 378 0.829954516722022 0.551613566793715 0.083054037239801 0.0836963729538531 -0.557063973260404 0.827380816943591 0.07155916048339 -0.0216512540420144 -0.0292443134309233 -0.105657260436147 0.99397249129394 0.218058036874605 6.67953752520941e-05 -3.99363453919806e-06 -8.09135653943015e-06 3.56154496997022e-07 -5.72035368592296e-06 -1.72053098125049e-05 -3.99363453919806e-06 3.45448081827477e-05 -4.01834834743013e-06 5.53139935116923e-06 -7.74360750371789e-08 1.44698771359219e-05 -8.09135653943015e-06 -4.01834834743013e-06 1.25649828178962e-05 3.01977423371301e-06 1.58229296861238e-06 3.02877063415148e-06 3.56154496997022e-07 5.53139935116923e-06 3.01977423371301e-06 7.28352994528423e-05 -3.92035325043597e-05 9.26515902810353e-06 -5.72035368592296e-06 -7.74360750371789e-08 1.58229296861238e-06 -3.92035325043597e-05 8.12919849923612e-05 1.52185522546133e-05 -1.72053098125049e-05 1.44698771359219e-05 3.02877063415148e-06 9.26515902810353e-06 1.52185522546133e-05 6.51599245367128e-05 1535 1548 0 201 0 1524 1537 0 201 0 0 0 0 0 0 0 0 0 288 0 916 903 0 0 1054 +435 433 0.979983221778974 0.192130682591859 0.0521410187710989 0.0444281585505255 -0.191340341519845 0.981324115313252 -0.0197953128727958 -0.0236769077559472 -0.05497052609145 0.00942239414635051 0.99844351855765 0.176668506005015 4.82385322567446e-05 -3.37196925815841e-06 -3.83825022243461e-06 1.0720952396471e-06 -8.57983346858675e-06 1.07956029336002e-05 -3.37196925815841e-06 2.88701730406561e-05 8.39874657750941e-06 2.46409250544732e-06 -4.68982158232017e-07 5.96391624883381e-06 -3.83825022243461e-06 8.39874657750941e-06 1.35425882839478e-05 2.19974726177348e-06 1.38777674364534e-07 2.04873655138574e-06 1.0720952396471e-06 2.46409250544732e-06 2.19974726177348e-06 3.13680994106063e-05 1.65621604832983e-06 -1.68758508942896e-06 -8.57983346858675e-06 -4.68982158232017e-07 1.38777674364534e-07 1.65621604832983e-06 4.74161719108904e-05 -1.21425379395494e-05 1.07956029336002e-05 5.96391624883381e-06 2.04873655138574e-06 -1.68758508942896e-06 -1.21425379395494e-05 4.04128861113555e-05 1703 1703 0 0 0 1703 1703 0 0 0 0 0 0 0 0 0 0 0 1400 0 456 426 0 0 2620 +435 333 0.805495203668145 0.586648019792294 -0.0837948551009809 0.0766270100922525 -0.581075541108718 0.809645085036718 0.0826199237538709 0.0521588313576602 0.116312907249472 -0.0178588115412418 0.993052048211729 0.146266255720643 4.71599879565699e-05 -1.38237307977973e-05 -1.76608306075555e-06 3.04593161993513e-06 -2.71904507451889e-06 -1.24437583715737e-05 -1.38237307977973e-05 4.13892384884734e-05 5.18611783614208e-07 8.25971516878577e-06 1.4935951215486e-07 1.9052349244429e-05 -1.76608306075555e-06 5.18611783614208e-07 1.5686379573945e-05 1.92918731574003e-06 -4.21365224697581e-06 2.73176244550461e-07 3.04593161993513e-06 8.25971516878577e-06 1.92918731574003e-06 7.28793727375951e-05 -3.01349987804589e-05 6.59754360279282e-06 -2.71904507451889e-06 1.4935951215486e-07 -4.21365224697581e-06 -3.01349987804589e-05 8.56051587151574e-05 -6.88857241452311e-06 -1.24437583715737e-05 1.9052349244429e-05 2.73176244550461e-07 6.59754360279282e-06 -6.88857241452311e-06 6.66734806764125e-05 1810 1782 0 48 0 1789 1761 0 48 0 0 0 0 0 0 0 0 0 526 0 839 818 0 0 1080 +434 394 0.829143038416642 0.552745955293684 0.0836285283362794 0.0792661544804523 -0.558207467444635 0.826741322484759 0.0700229175713123 0.0112024193274913 -0.0304342756487839 -0.104741083642592 0.994033731954358 0.215732075665629 6.53693565223706e-05 2.83166805874256e-06 -5.69016028091749e-07 -7.51728730517515e-06 -6.47806157342155e-06 2.27549083176774e-06 2.83166805874256e-06 3.4720856294294e-05 -3.18608449654842e-06 6.78276596228344e-07 5.15712866797714e-06 1.75817571670905e-05 -5.69016028091749e-07 -3.18608449654842e-06 1.36893631167303e-05 1.506977169198e-06 3.89593300861778e-06 3.60371089366833e-06 -7.51728730517515e-06 6.78276596228344e-07 1.506977169198e-06 4.4856439022383e-05 -5.60663997911475e-06 9.24576476262768e-06 -6.47806157342155e-06 5.15712866797714e-06 3.89593300861778e-06 -5.60663997911475e-06 4.9919417780613e-05 1.2499015661788e-05 2.27549083176774e-06 1.75817571670905e-05 3.60371089366833e-06 9.24576476262768e-06 1.2499015661788e-05 5.85143545864964e-05 1328 1343 0 205 0 1311 1326 0 205 0 0 0 0 0 0 0 0 0 88 0 949 937 0 0 1098 +434 392 0.829218139540892 0.552022084050592 0.0875722317677404 0.0840822971456219 -0.557979427094408 0.82670161775904 0.072273052612869 0.0070680478656416 -0.0324997845491066 -0.108793629937727 0.993532943635607 0.222494402924676 7.11875127310822e-05 2.29212388910007e-06 -9.14666648019127e-06 1.27139233050147e-05 -5.82611764058444e-06 1.20302997960426e-05 2.29212388910007e-06 3.18338315590411e-05 -3.16709614527473e-06 1.56467527648106e-06 5.76241277025163e-06 1.58609326908896e-05 -9.14666648019127e-06 -3.16709614527473e-06 1.38812215286849e-05 3.54928020772158e-08 3.1771728034612e-06 -3.62235212674245e-06 1.27139233050147e-05 1.56467527648106e-06 3.54928020772158e-08 4.24630575988686e-05 -6.65353057669871e-06 1.02073375680447e-05 -5.82611764058444e-06 5.76241277025163e-06 3.1771728034612e-06 -6.65353057669871e-06 5.46447419197216e-05 2.32365619659951e-05 1.20302997960426e-05 1.58609326908896e-05 -3.62235212674245e-06 1.02073375680447e-05 2.32365619659951e-05 5.77241690643904e-05 1225 1235 0 192 0 1220 1230 0 192 0 0 0 0 0 0 0 0 0 73 0 1010 997 0 0 1069 +435 334 0.803795168023776 0.586890730297388 -0.0973272754813773 0.0834220475387768 -0.57914936384951 0.809366488836651 0.0975289756992193 0.0557992389740396 0.136012286997671 -0.0220262897290951 0.990462265988176 0.183036755656553 4.6939855119856e-05 -1.72265152576528e-05 -6.46204538225154e-06 1.26273888659735e-07 -2.18912943988086e-06 -1.38763532715755e-05 -1.72265152576528e-05 5.23832399077095e-05 3.07932749537028e-06 2.12268307474531e-05 -1.07408327571796e-05 2.67678282590553e-05 -6.46204538225154e-06 3.07932749537028e-06 2.15502383168144e-05 9.03314922589474e-06 -7.19402756096263e-06 3.02980665337767e-06 1.26273888659735e-07 2.12268307474531e-05 9.03314922589474e-06 9.33500894386156e-05 -4.40098768081382e-05 2.2584224974623e-05 -2.18912943988086e-06 -1.07408327571796e-05 -7.19402756096263e-06 -4.40098768081382e-05 0.000113422764896213 -1.87616057845041e-05 -1.38763532715755e-05 2.67678282590553e-05 3.02980665337767e-06 2.2584224974623e-05 -1.87616057845041e-05 7.19978533084212e-05 1469 1448 0 61 0 1442 1421 0 61 0 0 0 0 0 0 0 0 0 492 0 996 973 0 0 1096 +435 437 0.993940444422378 -0.100570144285234 0.0443625858116217 -0.0795778912524594 0.096563180448094 0.991713999037083 0.0847283677148657 0.068931595573312 -0.0525161415490056 -0.0799311590828245 0.995416025933118 -0.216530667212648 4.4106519371947e-05 -8.63524802953836e-06 -8.75076510480473e-06 -3.75830181719952e-07 2.38122149266979e-07 -1.62640981915201e-05 -8.63524802953836e-06 4.7490834589639e-05 1.5212960859923e-06 8.87351034748904e-06 -5.85625181265463e-06 8.60381466678608e-06 -8.75076510480473e-06 1.5212960859923e-06 1.29203908681421e-05 1.24194515801255e-06 -3.10614121949299e-06 1.61372947952446e-06 -3.75830181719952e-07 8.87351034748904e-06 1.24194515801255e-06 3.19822431306293e-05 -2.90439599730497e-06 2.88279862709004e-06 2.38122149266979e-07 -5.85625181265463e-06 -3.10614121949299e-06 -2.90439599730497e-06 7.5129789754247e-05 5.96519595918112e-06 -1.62640981915201e-05 8.60381466678608e-06 1.61372947952446e-06 2.88279862709004e-06 5.96519595918112e-06 6.57886142350526e-05 1277 1299 0 0 230 1277 1299 0 0 203 0 0 0 0 0 0 0 0 2137 0 0 0 0 0 2760 +435 340 0.805239411655353 0.582349233802881 -0.111619262702002 0.126677578366794 -0.574760167990712 0.812851461288296 0.0944629619097962 -0.0091226208584748 0.145740314286165 -0.0119109936898644 0.989251175900787 0.269874697158413 4.16204837723308e-05 -9.04866913230583e-06 -4.54855262866886e-06 3.55196872233944e-06 -1.12976513871818e-06 -2.80797767977759e-06 -9.04866913230583e-06 4.10201913166746e-05 -1.59598470034223e-06 9.1933273238823e-06 6.69813815773703e-06 2.88468051439031e-06 -4.54855262866886e-06 -1.59598470034223e-06 1.51564459388112e-05 2.86420696575569e-06 -9.82975939469337e-06 9.16407794075623e-07 3.55196872233944e-06 9.1933273238823e-06 2.86420696575569e-06 9.31535307324751e-05 -5.94775304611715e-05 -6.02028253059589e-06 -1.12976513871818e-06 6.69813815773703e-06 -9.82975939469337e-06 -5.94775304611715e-05 0.000158077033862779 7.45205495520899e-06 -2.80797767977759e-06 2.88468051439031e-06 9.16407794075623e-07 -6.02028253059589e-06 7.45205495520899e-06 4.75903541120974e-05 1232 1222 0 97 0 1212 1202 0 97 0 0 0 0 0 0 0 0 0 273 0 773 745 0 0 847 +435 341 0.794186381404606 0.598611974760388 -0.104554747691945 0.133272693526386 -0.59008814800556 0.800795050799582 0.102582962514556 -0.0249698074644583 0.145134314256918 -0.0197734743624714 0.989214355201546 0.280245226246027 5.24028941831118e-05 -6.35019580978957e-06 -1.01610370915813e-05 -8.78200129411378e-06 1.67929516933902e-05 5.62988867718793e-06 -6.35019580978957e-06 6.23739137264679e-05 1.40605869131801e-06 2.08234455755894e-05 -9.46528545818823e-06 -2.3748318866283e-06 -1.01610370915813e-05 1.40605869131801e-06 1.76645101469691e-05 6.44773125568582e-08 -7.92268637457666e-06 -2.42916717396211e-06 -8.78200129411378e-06 2.08234455755894e-05 6.44773125568582e-08 7.42057706702445e-05 -2.59327253352281e-06 1.10548778086687e-05 1.67929516933902e-05 -9.46528545818823e-06 -7.92268637457666e-06 -2.59327253352281e-06 7.81673209461949e-05 1.56702070980676e-05 5.62988867718793e-06 -2.3748318866283e-06 -2.42916717396211e-06 1.10548778086687e-05 1.56702070980676e-05 6.79533880058971e-05 903 900 0 113 0 882 879 0 113 0 0 0 0 0 0 0 0 0 221 0 717 696 0 0 752 +435 432 0.948822514091838 0.312983936174738 0.0421532021204956 0.0653666069081879 -0.312905647533236 0.949745163541338 -0.00861278535922447 -0.0178283952403618 -0.0427304633048793 -0.00501797034724033 0.999074035034113 0.236449064086671 2.78043935746652e-05 -1.03239418017418e-05 -4.20063149109142e-06 9.58934412102548e-07 2.82208425186909e-06 -1.01008697992884e-06 -1.03239418017418e-05 5.48982240133378e-05 3.56695310772884e-06 3.29764701103913e-06 -6.50980938059926e-06 6.74886155021296e-06 -4.20063149109142e-06 3.56695310772884e-06 1.30234008269016e-05 -3.74360197227906e-07 2.80747606456091e-06 8.30786579971069e-07 9.58934412102548e-07 3.29764701103913e-06 -3.74360197227906e-07 2.87433213567541e-05 2.40452500541841e-06 4.60110316889102e-06 2.82208425186909e-06 -6.50980938059926e-06 2.80747606456091e-06 2.40452500541841e-06 5.24893686222593e-05 -5.17739119747898e-06 -1.01008697992884e-06 6.74886155021296e-06 8.30786579971069e-07 4.60110316889102e-06 -5.17739119747898e-06 3.99314369249259e-05 1648 1648 0 0 0 1603 1603 0 0 0 0 0 0 0 0 0 0 0 984 0 702 659 0 0 2211 +435 335 0.808432713376433 0.579852523616481 -0.101032662037666 0.0951152147600784 -0.568919880074744 0.813822986302413 0.118415864737631 0.036303520983121 0.150886440737919 -0.0382517688665592 0.987810753221497 0.198993372454572 4.3130440276563e-05 -9.44494619376339e-06 -5.37441841151655e-06 -3.95051741142158e-06 8.52717624425508e-06 -1.12280161087909e-05 -9.44494619376339e-06 5.67450554672569e-05 -3.90707944001464e-06 1.254069656952e-05 -4.45098053288469e-06 1.45033334506973e-05 -5.37441841151655e-06 -3.90707944001464e-06 2.15901449827029e-05 5.71876832150659e-06 -9.20790240333483e-06 -8.64987999600553e-07 -3.95051741142158e-06 1.254069656952e-05 5.71876832150659e-06 0.000105620535558717 -5.7331020927007e-05 1.10262076055606e-05 8.52717624425508e-06 -4.45098053288469e-06 -9.20790240333483e-06 -5.7331020927007e-05 0.000148017454964505 -7.2726383981126e-06 -1.12280161087909e-05 1.45033334506973e-05 -8.64987999600553e-07 1.10262076055606e-05 -7.2726383981126e-06 6.16256311188766e-05 1375 1354 0 76 0 1351 1330 0 76 0 0 0 0 0 0 0 0 0 428 0 853 826 0 0 1012 +435 385 0.783567593395484 0.613924439295925 0.0954914101665354 0.10406268745474 -0.621285486619473 0.775496813532466 0.112289965344177 -0.0114125546115096 -0.00511573029138733 -0.147314205140495 0.989076515881057 0.311542590293851 5.87355927798779e-05 -8.06895963420492e-06 -6.22479189900393e-06 8.6925753739232e-06 -7.31936017682268e-06 7.91007826095658e-06 -8.06895963420492e-06 3.71381679575817e-05 -4.97250769194188e-07 4.15191700534039e-06 1.01201938580849e-05 1.68899461759182e-05 -6.22479189900393e-06 -4.97250769194188e-07 1.10552754722501e-05 -5.23330063516039e-07 1.20354564015645e-06 1.04306205671227e-06 8.6925753739232e-06 4.15191700534039e-06 -5.23330063516039e-07 4.83404875828585e-05 -9.13403606697127e-06 7.98835951643595e-09 -7.31936017682268e-06 1.01201938580849e-05 1.20354564015645e-06 -9.13403606697127e-06 6.10333291700031e-05 1.10618960575534e-05 7.91007826095658e-06 1.68899461759182e-05 1.04306205671227e-06 7.98835951643595e-09 1.10618960575534e-05 5.01921514540616e-05 1186 1195 0 167 0 1186 1195 0 167 0 0 0 0 0 0 0 0 0 277 0 1077 1063 0 0 986 +435 382 0.783589606073227 0.613328339527436 0.0990740994736882 0.109298973125782 -0.621236602917371 0.775367812640151 0.113445309807468 -0.0181054617696684 -0.00723964430681619 -0.150443022617021 0.988592172989532 0.317460661355132 4.24538816401993e-05 -8.08959783582673e-06 -2.95836886331649e-06 -3.79029397321001e-06 -1.00069125096303e-06 3.80723440450946e-06 -8.08959783582673e-06 3.60094884967004e-05 -2.07581022904456e-06 5.64219490638942e-06 1.58066906344341e-05 1.72308058233484e-05 -2.95836886331649e-06 -2.07581022904456e-06 1.04002266709815e-05 2.44218249434198e-06 1.29108619853363e-06 7.34679292761724e-07 -3.79029397321001e-06 5.64219490638942e-06 2.44218249434198e-06 5.54822944420863e-05 -8.7040134989017e-06 6.64592157911744e-06 -1.00069125096303e-06 1.58066906344341e-05 1.29108619853363e-06 -8.7040134989017e-06 7.31337025554431e-05 1.39491531032532e-05 3.80723440450946e-06 1.72308058233484e-05 7.34679292761724e-07 6.64592157911744e-06 1.39491531032532e-05 4.63870303349129e-05 1297 1310 0 166 0 1297 1310 0 166 0 0 0 0 0 0 0 0 0 290 0 1071 1057 0 0 982 +435 384 0.783878749527892 0.613237877057809 0.097331455245571 0.107746341355365 -0.620885932240063 0.775641686088791 0.113492880603698 -0.0206353978684666 -0.00589620089356337 -0.149396388654373 0.988759805954942 0.316584617460267 3.82411682433348e-05 -4.8219727300832e-06 -4.47525400027306e-06 -1.43557876678748e-07 9.61587014048878e-07 6.3679500040997e-06 -4.8219727300832e-06 2.85561510410029e-05 -3.16710648983337e-06 1.02754853418785e-05 -1.04883923003203e-06 8.56376700573886e-06 -4.47525400027306e-06 -3.16710648983337e-06 1.04191468180408e-05 1.92721509401506e-07 1.97167777561965e-06 1.71704202874173e-07 -1.43557876678748e-07 1.02754853418785e-05 1.92721509401506e-07 5.18989989945893e-05 -8.4584165803152e-06 5.12849955874442e-06 9.61587014048878e-07 -1.04883923003203e-06 1.97167777561965e-06 -8.4584165803152e-06 5.472427842225e-05 1.35428626395732e-05 6.3679500040997e-06 8.56376700573886e-06 1.71704202874173e-07 5.12849955874442e-06 1.35428626395732e-05 4.81644655111604e-05 1369 1385 0 177 0 1334 1350 0 177 0 0 0 0 0 0 0 0 0 296 0 1247 1237 0 0 960 +435 339 0.824188407775013 0.552775167007867 -0.123097860374235 0.124410051222715 -0.543927109549471 0.833191942556264 0.0996718935130506 -0.0100921960186825 0.157660292992395 -0.0151921558293601 0.987376539327732 0.265745209991322 5.16319684902387e-05 6.75892463483721e-06 -8.35343288401776e-06 -5.12240403229017e-06 1.88634913970785e-05 8.13569366262372e-06 6.75892463483721e-06 4.91927463984463e-05 -6.12661991225223e-06 -8.98211913691763e-06 1.75225029585607e-05 1.60520794802751e-05 -8.35343288401776e-06 -6.12661991225223e-06 1.983503962865e-05 8.3647194253343e-06 -7.69607010913103e-06 -1.41686334786648e-08 -5.12240403229017e-06 -8.98211913691763e-06 8.3647194253343e-06 0.00015516291371225 -0.000140014482045145 2.47694949755375e-06 1.88634913970785e-05 1.75225029585607e-05 -7.69607010913103e-06 -0.000140014482045145 0.000311335909332741 2.33781942783809e-05 8.13569366262372e-06 1.60520794802751e-05 -1.41686334786648e-08 2.47694949755375e-06 2.33781942783809e-05 6.98548475354281e-05 1062 1051 0 65 0 1053 1042 0 65 0 0 0 0 0 0 0 0 0 349 0 591 564 0 0 842 +435 336 0.819170376777554 0.563294679518645 -0.107976839350424 0.103665608170947 -0.550531608792217 0.825033588147413 0.127414779948243 0.0323356002167439 0.160856586842982 -0.0449297502173437 0.985954601396349 0.207585206635379 4.71995119058008e-05 1.99296849502186e-06 -5.85582965008122e-06 3.76101243122637e-06 -5.14147185130286e-06 -6.6026470263903e-06 1.99296849502186e-06 4.19475441021157e-05 -2.97031623995601e-06 7.88378771134078e-06 -2.55827983692359e-06 1.31845710472044e-05 -5.85582965008122e-06 -2.97031623995601e-06 2.01555160426359e-05 6.2964899859595e-06 -1.75208066590672e-06 -2.30468045246807e-06 3.76101243122637e-06 7.88378771134078e-06 6.2964899859595e-06 9.85289160801182e-05 -7.64850179182141e-05 1.56102792988196e-05 -5.14147185130286e-06 -2.55827983692359e-06 -1.75208066590672e-06 -7.64850179182141e-05 0.000186881398617304 -6.14747562844076e-06 -6.6026470263903e-06 1.31845710472044e-05 -2.30468045246807e-06 1.56102792988196e-05 -6.14747562844076e-06 5.87708699210941e-05 1460 1447 0 84 0 1446 1433 0 84 0 0 0 0 0 0 0 0 0 421 0 695 668 0 0 1049 +435 337 0.834793185280459 0.53981677284159 -0.108250586918484 0.112168487423273 -0.526310157723505 0.840156101359087 0.130902036753289 0.0170850165432049 0.161610506113818 -0.052302744746248 0.985467638842415 0.237664362393113 4.88587201191163e-05 -1.85857032854323e-05 -8.81959756103051e-06 1.19413838174019e-05 -7.56073550232504e-06 4.83987901903269e-07 -1.85857032854323e-05 5.69663154283969e-05 -2.09275223820569e-06 -8.03003670783945e-06 -3.05451304669883e-06 2.09053864869458e-06 -8.81959756103051e-06 -2.09275223820569e-06 2.10366027777108e-05 3.05192722318795e-06 -3.46365596427554e-06 9.14088403349161e-08 1.19413838174019e-05 -8.03003670783945e-06 3.05192722318795e-06 9.01698211802633e-05 -4.10523419799567e-05 1.88769153666425e-05 -7.56073550232504e-06 -3.05451304669883e-06 -3.46365596427554e-06 -4.10523419799567e-05 0.000162896686487095 -1.04069879374553e-05 4.83987901903269e-07 2.09053864869458e-06 9.14088403349161e-08 1.88769153666425e-05 -1.04069879374553e-05 6.82864380715672e-05 1310 1293 0 53 0 1296 1279 0 53 0 0 0 0 0 0 0 0 0 434 0 735 708 0 0 908 +435 342 0.794242694608909 0.596817352274662 -0.113963108435326 0.144305945296645 -0.588686704545156 0.802295939306909 0.0988392111634241 -0.02872984044398 0.150421095435926 -0.0114137546629423 0.988556129034841 0.282514841221306 5.63690316684257e-05 4.50286483613679e-06 -8.58242543754219e-06 -1.11748683159258e-06 -3.8462512822356e-06 -1.34366650159592e-05 4.50286483613679e-06 4.44246435554624e-05 -2.679767353426e-06 -7.9067869139342e-06 9.23853358213147e-06 5.49390785954794e-06 -8.58242543754219e-06 -2.679767353426e-06 1.84575593459678e-05 3.13542786005803e-06 -4.73736820145068e-07 -2.21677708730547e-06 -1.11748683159258e-06 -7.9067869139342e-06 3.13542786005803e-06 6.96036214910381e-05 -1.53138959875562e-05 -3.49965917242614e-08 -3.8462512822356e-06 9.23853358213147e-06 -4.73736820145068e-07 -1.53138959875562e-05 8.55233807463396e-05 2.71406765736897e-05 -1.34366650159592e-05 5.49390785954794e-06 -2.21677708730547e-06 -3.49965917242614e-08 2.71406765736897e-05 6.56494604457496e-05 924 916 0 96 0 916 908 0 96 0 0 0 0 0 0 0 0 0 206 0 849 826 0 0 835 +435 431 0.898319190786759 0.43913265094377 0.0136068489856983 0.0865716430960473 -0.439304440685318 0.897396123261742 0.041131573626061 -0.0200962568948433 0.00585148343432734 -0.0429268311187009 0.999061082873177 0.275025075375081 4.90618399512661e-05 -5.24034261945852e-06 -8.96644622889405e-06 -1.30295265111072e-06 1.72295843645807e-06 1.45529393049145e-05 -5.24034261945852e-06 4.97877487489125e-05 1.97520129570764e-06 2.13874432087041e-06 5.22571127325403e-06 9.20064533001076e-06 -8.96644622889405e-06 1.97520129570764e-06 1.40895935915146e-05 9.76723094934758e-07 3.45561972380878e-07 -2.42898355338802e-06 -1.30295265111072e-06 2.13874432087041e-06 9.76723094934758e-07 3.28520925081845e-05 -8.38398358966156e-06 1.89537257478894e-06 1.72295843645807e-06 5.22571127325403e-06 3.45561972380878e-07 -8.38398358966156e-06 6.4515423747371e-05 2.79164190821738e-06 1.45529393049145e-05 9.20064533001076e-06 -2.42898355338802e-06 1.89537257478894e-06 2.79164190821738e-06 5.41323915790716e-05 1705 1703 0 0 0 1694 1692 0 0 0 0 0 0 0 0 0 0 0 636 0 737 705 0 0 1651 +435 381 0.783483829418159 0.6134242609697 0.0993164895374104 0.110187888912823 -0.621348348049773 0.775623750252133 0.111058671073607 -0.024997210164147 -0.0089061448492785 -0.148722809611014 0.988838817242391 0.320365520641515 5.12634494595988e-05 -1.2888513950494e-05 -6.61079694353333e-06 -4.45486595058117e-07 -7.57302297497891e-06 -5.78284697119724e-07 -1.2888513950494e-05 4.32311380782744e-05 -8.2724634169052e-07 8.93486218598976e-06 1.85139511452492e-05 1.58462440549451e-05 -6.61079694353333e-06 -8.2724634169052e-07 1.21213866939417e-05 7.28839615515679e-07 2.26621065845302e-06 9.99258285205875e-07 -4.45486595058117e-07 8.93486218598976e-06 7.28839615515679e-07 5.71177011056591e-05 -4.53328534538454e-06 5.41190609961522e-06 -7.57302297497891e-06 1.85139511452492e-05 2.26621065845302e-06 -4.53328534538454e-06 7.02592351507016e-05 1.81818174807039e-05 -5.78284697119724e-07 1.58462440549451e-05 9.99258285205875e-07 5.41190609961522e-06 1.81818174807039e-05 5.99843959650813e-05 1189 1199 0 165 0 1189 1199 0 165 0 0 0 0 0 0 0 0 0 271 0 1067 1053 0 0 976 +435 383 0.783709830422065 0.613329489676187 0.0981113591454434 0.105892182891304 -0.621078382893638 0.775789172754893 0.111412753931057 -0.0181973843025839 -0.00778100263734795 -0.148250114771713 0.988919288652078 0.313631423248273 5.83976762487642e-05 -5.15608255106221e-06 -9.23090516137989e-06 7.55057580960807e-06 2.34868540016059e-06 9.01960952567526e-06 -5.15608255106221e-06 3.17497869353838e-05 -1.12215730977286e-06 1.09450100937439e-05 -2.40303605828969e-06 7.0751918733543e-06 -9.23090516137989e-06 -1.12215730977286e-06 1.22488465209838e-05 8.4346267229707e-07 7.27920398358586e-07 -8.79675829439721e-07 7.55057580960807e-06 1.09450100937439e-05 8.4346267229707e-07 6.66311160458892e-05 -1.78755247685377e-05 1.14331590348841e-05 2.34868540016059e-06 -2.40303605828969e-06 7.27920398358586e-07 -1.78755247685377e-05 6.28301940177534e-05 6.85940274079057e-06 9.01960952567526e-06 7.0751918733543e-06 -8.79675829439721e-07 1.14331590348841e-05 6.85940274079057e-06 5.07510439249418e-05 1412 1426 0 178 0 1376 1390 0 178 0 0 0 0 0 0 0 0 0 273 0 1238 1226 0 0 940 +435 380 0.783678328237852 0.613522710934201 0.0971501982410494 0.107160913296436 -0.6211147022842 0.775996168509293 0.109756426077507 -0.0304133286247236 -0.00805012153545151 -0.146355148959122 0.989199356002832 0.316479306615904 5.29526229238139e-05 -6.33843085102098e-06 -5.63914088757217e-06 -2.60055598396635e-06 -3.99210724183529e-06 3.81249922246777e-06 -6.33843085102098e-06 3.30936686188104e-05 -2.43004856734706e-06 1.22634201747781e-05 -1.42078748695279e-06 9.35737652766859e-06 -5.63914088757217e-06 -2.43004856734706e-06 1.1436439741431e-05 5.40908955053387e-07 2.21999539336051e-06 -1.40773214830908e-07 -2.60055598396635e-06 1.22634201747781e-05 5.40908955053387e-07 7.23366332720501e-05 -3.27227507837992e-05 6.44042397985882e-06 -3.99210724183529e-06 -1.42078748695279e-06 2.21999539336051e-06 -3.27227507837992e-05 6.49769134547382e-05 1.05749436273469e-05 3.81249922246777e-06 9.35737652766859e-06 -1.40773214830908e-07 6.44042397985882e-06 1.05749436273469e-05 4.09813930936703e-05 1414 1431 0 170 0 1372 1389 0 170 0 0 0 0 0 0 0 0 0 287 0 1232 1221 0 0 960 +435 378 0.78375663179793 0.61344897222834 0.0969840223168612 0.107266155690282 -0.621030106818877 0.775820862663591 0.111461183738806 -0.0499217210214893 -0.00686647925052741 -0.147588439682502 0.989025026950677 0.319735623657683 4.22250867513922e-05 -4.72921483035814e-06 -6.76774298089372e-06 -2.56993812360582e-06 4.01710509221174e-06 3.18652806156371e-06 -4.72921483035814e-06 3.69673389531907e-05 -3.50477266621866e-06 1.83712645638052e-05 -9.99775742427238e-06 2.34384648991366e-06 -6.76774298089372e-06 -3.50477266621866e-06 1.16831277530696e-05 -1.39370519329635e-08 1.76501607459459e-06 -6.46741593881233e-07 -2.56993812360582e-06 1.83712645638052e-05 -1.39370519329635e-08 9.13004018789174e-05 -4.40230483837444e-05 6.02549100795619e-06 4.01710509221174e-06 -9.99775742427238e-06 1.76501607459459e-06 -4.40230483837444e-05 8.79809688795412e-05 7.36946991515286e-06 3.18652806156371e-06 2.34384648991366e-06 -6.46741593881233e-07 6.02549100795619e-06 7.36946991515286e-06 4.51705068446529e-05 1196 1208 0 167 0 1159 1171 0 167 0 0 0 0 0 0 0 0 0 293 0 942 929 0 0 963 +436 438 0.993994578807213 -0.107822997588975 0.0186809660563782 -0.0772416667654903 0.106259384593059 0.991823943682238 0.0706697100922134 0.0925171587624064 -0.0261480494067174 -0.0682602807607829 0.997324828520118 -0.201957193133594 2.81114737285314e-05 -6.18315807391832e-06 -5.78274145078906e-06 3.98126905484306e-06 8.44974295939302e-07 3.03180848345551e-06 -6.18315807391832e-06 3.62536161650053e-05 4.89961596811979e-07 3.25747742362588e-06 -8.19114982245779e-07 -1.33034932338026e-06 -5.78274145078906e-06 4.89961596811979e-07 1.06051383090696e-05 -2.15400509082771e-06 3.4235630792365e-07 -2.51464246915587e-06 3.98126905484306e-06 3.25747742362588e-06 -2.15400509082771e-06 3.08293695581816e-05 6.9968558866748e-06 7.05422251023256e-06 8.44974295939302e-07 -8.19114982245779e-07 3.4235630792365e-07 6.9968558866748e-06 6.36278470077938e-05 8.78964936591384e-06 3.03180848345551e-06 -1.33034932338026e-06 -2.51464246915587e-06 7.05422251023256e-06 8.78964936591384e-06 6.70770625225929e-05 1001 999 0 0 237 1001 999 0 0 238 0 0 0 0 0 0 0 0 2042 0 0 0 0 0 2869 +436 332 0.778397455553939 0.623352086948006 -0.0743611248215027 0.0889680826277709 -0.618258787046563 0.781747922040285 0.0814018342877399 0.0219014641127989 0.108873658094446 -0.0173885618514398 0.993903498580155 0.207465932991294 3.92175037316449e-05 1.07290219576173e-06 -6.50662998764362e-06 -1.60744852325869e-06 1.37679554946152e-05 -1.86917105758809e-06 1.07290219576173e-06 5.11855295431262e-05 -2.29591140191579e-06 5.53945262877232e-06 1.90076229836292e-06 2.79459652786931e-06 -6.50662998764362e-06 -2.29591140191579e-06 1.91642178871112e-05 6.89191977729031e-07 -4.12226388680015e-06 -4.74949147829897e-06 -1.60744852325869e-06 5.53945262877232e-06 6.89191977729031e-07 6.4519941694719e-05 -1.68939752782408e-05 7.31058636999809e-06 1.37679554946152e-05 1.90076229836292e-06 -4.12226388680015e-06 -1.68939752782408e-05 8.62274869307383e-05 2.04088662259109e-05 -1.86917105758809e-06 2.79459652786931e-06 -4.74949147829897e-06 7.31058636999809e-06 2.04088662259109e-05 7.40383976164835e-05 1259 1242 0 8 0 1277 1260 0 8 0 0 0 0 0 0 0 0 0 552 0 846 819 0 0 886 +435 379 0.784056001916936 0.613070775372209 0.0969557127896446 0.107691602222421 -0.620651381852964 0.776127451101486 0.111436268111943 -0.0404927796080492 -0.0069316709411803 -0.147547971965826 0.989030610197043 0.318218198505664 6.57903092841104e-05 -1.96814431798563e-05 -8.13647669478568e-06 7.20785436879542e-07 -1.18483217423255e-05 -7.61569717811554e-06 -1.96814431798563e-05 4.37292310054063e-05 3.3799850133761e-07 7.32985885848548e-06 1.27853913091905e-05 1.49021872368327e-05 -8.13647669478568e-06 3.3799850133761e-07 1.26275641875246e-05 2.27364800907659e-06 4.08274471756393e-06 1.72532164305774e-06 7.20785436879542e-07 7.32985885848548e-06 2.27364800907659e-06 8.29696580831148e-05 -5.17113327505543e-05 -1.94330383502891e-06 -1.18483217423255e-05 1.27853913091905e-05 4.08274471756393e-06 -5.17113327505543e-05 9.80195970557246e-05 1.67817695842058e-05 -7.61569717811554e-06 1.49021872368327e-05 1.72532164305774e-06 -1.94330383502891e-06 1.67817695842058e-05 5.37076585271425e-05 1322 1336 0 177 0 1322 1336 0 177 0 0 0 0 0 0 0 0 0 285 0 1132 1121 0 0 973 +436 334 0.761134986183924 0.637224323131001 -0.120907794690975 0.105911791046199 -0.634181412389804 0.770256106557401 0.0672269773997586 0.0103123065223737 0.135968632360816 0.0255086714917067 0.990384692275005 0.284999676620844 6.86451756983143e-05 -2.24935598098888e-05 -6.86403596158557e-06 -1.72956375348495e-05 8.47501152998003e-06 -2.46696095892925e-05 -2.24935598098888e-05 8.81010123606742e-05 4.47920763540085e-06 1.55390272450004e-05 5.42491658989291e-06 4.35419243215277e-05 -6.86403596158557e-06 4.47920763540085e-06 1.69370151288666e-05 7.11113057443776e-06 -7.20168612614478e-06 1.85611798309085e-06 -1.72956375348495e-05 1.55390272450004e-05 7.11113057443776e-06 0.00010137798977657 -5.06490392384614e-05 1.25480335542067e-05 8.47501152998003e-06 5.42491658989291e-06 -7.20168612614478e-06 -5.06490392384614e-05 9.82571687168969e-05 1.34176469752393e-05 -2.46696095892925e-05 4.35419243215277e-05 1.85611798309085e-06 1.25480335542067e-05 1.34176469752393e-05 0.000106987197300277 832 810 0 52 0 854 832 0 52 0 0 0 0 0 0 0 0 0 498 0 852 831 0 0 794 +435 387 0.784208204354574 0.613042714336023 0.0958964161087126 0.104424114224884 -0.620483141892685 0.775829427482979 0.114408784970453 -0.0201470136634953 -0.00426178952511901 -0.14922241738745 0.9887944717175 0.314745620120162 5.54021776691615e-05 -5.60201957043935e-06 -5.17616196903736e-06 -1.59295113534637e-06 3.79873528500473e-06 1.36066438276406e-05 -5.60201957043935e-06 3.30638640261367e-05 -1.98385109812344e-06 1.30422212681073e-05 -1.41246439434052e-06 1.65533081594288e-05 -5.17616196903736e-06 -1.98385109812344e-06 1.14559123985494e-05 3.62291006927421e-07 1.57747782361122e-06 -1.31163122724495e-06 -1.59295113534637e-06 1.30422212681073e-05 3.62291006927421e-07 5.24404390780049e-05 -6.37105783866682e-06 5.1458556761704e-06 3.79873528500473e-06 -1.41246439434052e-06 1.57747782361122e-06 -6.37105783866682e-06 4.54491763047132e-05 1.30979047326826e-05 1.36066438276406e-05 1.65533081594288e-05 -1.31163122724495e-06 5.1458556761704e-06 1.30979047326826e-05 6.40044490268841e-05 1344 1360 0 175 0 1308 1324 0 175 0 0 0 0 0 0 0 0 0 276 0 1246 1236 0 0 964 +435 388 0.783811594866569 0.613647776374435 0.0952669423432722 0.10223528755641 -0.620971396877865 0.775937869445641 0.11097273097348 -0.0223963101262983 -0.00582305867036487 -0.146139759514207 0.989246815853784 0.316264444705466 7.93790413330883e-05 -2.90394276133874e-06 -5.6576881005181e-06 -8.94705804778276e-06 9.2708676415618e-06 3.29804838344399e-05 -2.90394276133874e-06 4.91719077431123e-05 -2.66866036855417e-06 1.56945076089626e-05 -1.86393908745235e-06 3.09382711605353e-05 -5.6576881005181e-06 -2.66866036855417e-06 1.27449106011155e-05 2.16563897577594e-07 -8.05683516517473e-07 -1.67761532313021e-07 -8.94705804778276e-06 1.56945076089626e-05 2.16563897577594e-07 6.01601276405122e-05 -1.81242314030896e-06 1.1216506155756e-05 9.2708676415618e-06 -1.86393908745235e-06 -8.05683516517473e-07 -1.81242314030896e-06 5.67635417298981e-05 3.99704017911245e-06 3.29804838344399e-05 3.09382711605353e-05 -1.67761532313021e-07 1.1216506155756e-05 3.99704017911245e-06 7.96249751282116e-05 1197 1210 0 178 0 1197 1210 0 178 0 0 0 0 0 0 0 0 0 291 0 1075 1060 0 0 963 +436 335 0.765166173435861 0.631480112159058 -0.125513325894526 0.117201512214742 -0.625047495645053 0.775336376785911 0.090383245241266 -0.00143754039606969 0.154390269179665 0.00929358811648009 0.987966231205577 0.316254144516705 4.99831176152509e-05 -5.72586743331943e-06 -3.71614241962349e-06 4.96143157281735e-06 5.52405188586528e-06 1.14298457964688e-06 -5.72586743331943e-06 4.87558533435552e-05 -3.0675872624803e-06 9.28409313821288e-06 3.80315059985201e-06 3.64626586899195e-06 -3.71614241962349e-06 -3.0675872624803e-06 1.52631876625406e-05 -2.88006889509483e-07 -3.91525323247149e-06 -2.16528454660051e-06 4.96143157281735e-06 9.28409313821288e-06 -2.88006889509483e-07 9.76330646437629e-05 -5.62604614662997e-05 -3.59435255017402e-06 5.52405188586528e-06 3.80315059985201e-06 -3.91525323247149e-06 -5.62604614662997e-05 0.000121064503304589 1.70921014894005e-06 1.14298457964688e-06 3.64626586899195e-06 -2.16528454660051e-06 -3.59435255017402e-06 1.70921014894005e-06 7.81649181434236e-05 757 736 0 60 0 779 758 0 60 0 0 0 0 0 0 0 0 0 428 0 644 621 0 0 791 +435 393 0.781990852624044 0.614703431353113 0.103101881142049 0.108225650307484 -0.623145520182242 0.774599722928869 0.108096854326672 -0.00074372009058768 -0.0134151812929935 -0.148778226636921 0.98877958726384 0.320106692724318 4.61152057934831e-05 -2.27069822246615e-06 -3.58553437501704e-06 9.3229506163005e-06 -5.72433387833148e-07 1.95545181268646e-05 -2.27069822246615e-06 3.66469599928481e-05 -3.70771139087094e-06 7.81476761520297e-06 1.50596282717431e-06 1.11087856411021e-05 -3.58553437501704e-06 -3.70771139087094e-06 1.25887784985021e-05 1.14937301322447e-06 1.40614035204057e-06 -2.70038079658253e-06 9.3229506163005e-06 7.81476761520297e-06 1.14937301322447e-06 5.3712529246423e-05 -4.94196511433357e-06 1.48779189324464e-05 -5.72433387833148e-07 1.50596282717431e-06 1.40614035204057e-06 -4.94196511433357e-06 5.60061037841303e-05 1.40985016725993e-05 1.95545181268646e-05 1.11087856411021e-05 -2.70038079658253e-06 1.48779189324464e-05 1.40985016725993e-05 6.57337350267267e-05 1222 1233 0 163 0 1210 1221 0 163 0 0 0 0 0 0 0 0 0 80 0 1012 999 0 0 952 +436 338 0.793960993579853 0.591720886021993 -0.139614948050128 0.140311432857123 -0.585525326752022 0.806035764043435 0.0864085575325369 -0.0437893055518352 0.163664389546504 0.0131430638841829 0.986428521214845 0.364336742241737 5.19389568870605e-05 8.29008824020481e-06 -4.56170121221673e-06 1.47217956259645e-05 -1.15491172793016e-05 -5.85242776595645e-07 8.29008824020481e-06 7.82115648481665e-05 4.69151894237868e-07 1.89499576086283e-05 5.15954024840951e-06 1.06338331531222e-05 -4.56170121221673e-06 4.69151894237868e-07 1.6392894635829e-05 3.99688085618207e-06 -8.61392504905286e-06 -1.73014824614902e-06 1.47217956259645e-05 1.89499576086283e-05 3.99688085618207e-06 0.000104667892720138 -7.6793323322289e-05 -3.0320538289736e-06 -1.15491172793016e-05 5.15954024840951e-06 -8.61392504905286e-06 -7.6793323322289e-05 0.000200333219998064 2.32676179854529e-05 -5.85242776595645e-07 1.06338331531222e-05 -1.73014824614902e-06 -3.0320538289736e-06 2.32676179854529e-05 9.40594570279697e-05 794 783 0 22 0 792 781 0 22 0 0 0 0 0 0 0 0 0 381 0 588 561 0 0 633 +436 439 0.97859617342107 -0.202296538735354 -0.0377576453361975 -0.115357184007737 0.204728656435195 0.975632502856383 0.0789138555922178 0.138208465061926 0.0208735861767508 -0.0849548691122836 0.996166132537257 -0.285035940082208 5.54986425928913e-05 -1.07742737840946e-05 -3.35721211242549e-06 -2.57562839929091e-07 1.27121829452875e-05 -1.27163302786965e-05 -1.07742737840946e-05 5.17289721070279e-05 9.0918292668528e-07 3.54148199467009e-06 -5.77567246784776e-06 2.43929859668232e-05 -3.35721211242549e-06 9.0918292668528e-07 1.29652935448641e-05 1.90829884224579e-06 -9.30918615482811e-07 2.49043906403497e-06 -2.57562839929091e-07 3.54148199467009e-06 1.90829884224579e-06 4.02302222376065e-05 2.9216820088128e-05 1.79082709677254e-06 1.27121829452875e-05 -5.77567246784776e-06 -9.30918615482811e-07 2.9216820088128e-05 8.8857382139929e-05 -6.34669663028235e-06 -1.27163302786965e-05 2.43929859668232e-05 2.49043906403497e-06 1.79082709677254e-06 -6.34669663028235e-06 0.000114290549009611 496 491 0 0 297 496 491 0 0 297 0 0 0 0 0 0 0 0 1732 0 0 0 0 0 2533 +436 340 0.762406712571391 0.633162602396543 -0.133570668758235 0.14261232255477 -0.631110774710067 0.773156901590355 0.0626705318954685 -0.0403314745281514 0.142951721468979 0.0365174540410267 0.989055752159309 0.383578635536465 6.73596424699348e-05 -1.27810704724444e-05 -8.90155702315016e-06 -2.6812811592256e-06 1.18546326089494e-05 6.31343910846184e-06 -1.27810704724444e-05 5.98589737709269e-05 5.08578871366863e-08 1.88671807100389e-05 -1.08083254483578e-05 -2.02473350343612e-06 -8.90155702315016e-06 5.08578871366863e-08 1.60725523382194e-05 -6.122858385012e-07 -4.46742751308628e-06 2.14223889154352e-07 -2.6812811592256e-06 1.88671807100389e-05 -6.122858385012e-07 8.65878577492204e-05 -2.55665914249078e-05 -8.23506474250158e-06 1.18546326089494e-05 -1.08083254483578e-05 -4.46742751308628e-06 -2.55665914249078e-05 0.000103924314020381 -1.12460683870551e-05 6.31343910846184e-06 -2.02473350343612e-06 2.14223889154352e-07 -8.23506474250158e-06 -1.12460683870551e-05 6.41314237911661e-05 844 840 0 64 0 850 846 0 64 0 0 0 0 0 0 0 0 0 270 0 630 607 0 0 621 +436 341 0.74996398674807 0.64862353148232 -0.129774932049087 0.149270406634769 -0.644995497100824 0.760588426633635 0.0740679012166004 -0.072656342899751 0.146747495040297 0.0281559883217629 0.988773185832334 0.388453297441441 5.25367601463243e-05 2.29499726450378e-06 -1.01328221917592e-05 8.53868772528011e-06 4.09644124688095e-06 1.25174303914339e-05 2.29499726450378e-06 5.8188512804726e-05 -6.89289428912171e-07 -6.63622985770067e-06 1.45857327889883e-06 6.84302391185757e-06 -1.01328221917592e-05 -6.89289428912171e-07 2.11547752858789e-05 2.17920426709455e-06 -4.65237028472641e-06 -2.93854461908175e-06 8.53868772528011e-06 -6.63622985770067e-06 2.17920426709455e-06 6.80409190196846e-05 -1.36211799726967e-05 -2.47985269807175e-06 4.09644124688095e-06 1.45857327889883e-06 -4.65237028472641e-06 -1.36211799726967e-05 8.22531515368936e-05 1.30609201655267e-05 1.25174303914339e-05 6.84302391185757e-06 -2.93854461908175e-06 -2.47985269807175e-06 1.30609201655267e-05 7.41256211845417e-05 662 661 0 64 0 651 650 0 64 0 0 0 0 0 0 0 0 0 210 0 722 702 0 0 588 +436 336 0.778563256628071 0.615774278897564 -0.121083825826894 0.129779459134096 -0.607390288904741 0.787904035386264 0.10141137986565 -0.0114415458620003 0.157848954297795 -0.00541003421665819 0.987448448860429 0.32187508959663 4.46313296868847e-05 1.02715259112654e-06 -1.71010241013368e-06 -3.50274009566294e-06 -2.41405872696786e-06 -1.27331458007596e-05 1.02715259112654e-06 5.02822514497459e-05 9.10034786618463e-07 5.79180171579172e-06 4.24507676587831e-06 1.15088324917973e-05 -1.71010241013368e-06 9.10034786618463e-07 1.50611871430546e-05 2.4902894116592e-06 -5.28691340468646e-06 9.243505049697e-07 -3.50274009566294e-06 5.79180171579172e-06 2.4902894116592e-06 8.14543460551218e-05 -6.41711677812563e-05 -3.48182204108924e-07 -2.41405872696786e-06 4.24507676587831e-06 -5.28691340468646e-06 -6.41711677812563e-05 0.000182986422502834 1.05385031653968e-05 -1.27331458007596e-05 1.15088324917973e-05 9.243505049697e-07 -3.48182204108924e-07 1.05385031653968e-05 8.997314228657e-05 859 848 0 49 0 869 858 0 49 0 0 0 0 0 0 0 0 0 438 0 662 634 0 0 777 +436 333 0.763798542541124 0.636935283351713 -0.10452383093691 0.102054796233016 -0.635027934946259 0.770531244619504 0.0549647423627913 0.0243285504728629 0.115547861295414 0.0243935624046894 0.993002339304024 0.259160248891067 4.58425709149164e-05 -6.9620410527311e-06 -6.97115850026613e-06 -9.17674662476913e-06 9.89491326020355e-06 -7.55233896251807e-06 -6.9620410527311e-06 5.72651037956722e-05 -1.20727570470087e-06 2.41505569101513e-05 -1.00192159401299e-05 3.74957730303789e-06 -6.97115850026613e-06 -1.20727570470087e-06 1.57260230030254e-05 4.9212836773374e-06 -4.48542176787481e-06 -6.40492618454031e-07 -9.17674662476913e-06 2.41505569101513e-05 4.9212836773374e-06 9.95766665165273e-05 -4.71578099884527e-05 9.53465789086294e-06 9.89491326020355e-06 -1.00192159401299e-05 -4.48542176787481e-06 -4.71578099884527e-05 0.000117527017162232 -8.24401237770628e-06 -7.55233896251807e-06 3.74957730303789e-06 -6.40492618454031e-07 9.53465789086294e-06 -8.24401237770628e-06 6.16339908469299e-05 1209 1181 0 45 0 1231 1203 0 45 0 0 0 0 0 0 0 0 0 531 0 612 594 0 0 787 +436 337 0.797291081581758 0.593253757030571 -0.11125156627798 0.142002499069506 -0.584101888003313 0.804787004542218 0.105559754409193 -0.0194006879644318 0.152157535669964 -0.0191796008581162 0.988170140841023 0.351274284559358 6.92484001340483e-05 6.18854088095718e-06 -5.69439429948366e-06 -1.38506785377904e-05 8.2837535531307e-06 -1.66973919186558e-05 6.18854088095718e-06 0.000134585998930191 4.28900393433708e-06 -1.42798558528796e-05 3.33701367279545e-05 -1.9444445641492e-06 -5.69439429948366e-06 4.28900393433708e-06 1.69682249522443e-05 -4.11072827762496e-06 2.01046282271631e-06 -5.8060113759936e-07 -1.38506785377904e-05 -1.42798558528796e-05 -4.11072827762496e-06 8.90657538656847e-05 -5.81724911797836e-05 1.5609043662933e-05 8.2837535531307e-06 3.33701367279545e-05 2.01046282271631e-06 -5.81724911797836e-05 0.000173496800605001 -2.951409561301e-06 -1.66973919186558e-05 -1.9444445641492e-06 -5.8060113759936e-07 1.5609043662933e-05 -2.951409561301e-06 8.65849907839565e-05 661 645 0 24 0 675 659 0 24 0 0 0 0 0 0 0 0 0 439 0 486 459 0 0 779 +436 339 0.781225915307045 0.604543812275785 -0.155604782354945 0.132463496047947 -0.601292109663338 0.795720642424843 0.0726392323445634 -0.032532175841489 0.167731535822224 0.0368162770803269 0.985145011474282 0.372207294954575 4.4241749976495e-05 3.07298327709832e-06 -7.11159647848704e-06 1.57260464491275e-07 5.72840552585783e-06 1.90798595038537e-05 3.07298327709832e-06 5.19904071741155e-05 2.48858566273679e-07 9.49053211727179e-06 -2.62403116193975e-06 -2.18171452731481e-06 -7.11159647848704e-06 2.48858566273679e-07 1.53263428908717e-05 -9.93924475612989e-07 -3.73652759300587e-06 -3.91467551657889e-06 1.57260464491275e-07 9.49053211727179e-06 -9.93924475612989e-07 8.55806416299543e-05 -3.36740446024831e-05 2.06783252687991e-05 5.72840552585783e-06 -2.62403116193975e-06 -3.73652759300587e-06 -3.36740446024831e-05 0.00012604137210485 5.94765333303682e-06 1.90798595038537e-05 -2.18171452731481e-06 -3.91467551657889e-06 2.06783252687991e-05 5.94765333303682e-06 8.5488452705074e-05 654 645 0 36 0 651 642 0 36 0 0 0 0 0 0 0 0 0 325 0 521 493 0 0 700 +436 380 0.742049616207706 0.666316599072692 0.073379539969926 0.123031010101788 -0.670262481678867 0.739216726145241 0.0656264995318113 -0.0736540660561851 -0.0105153573255304 -0.0978816713553319 0.995142505208678 0.421721850889135 0.000137869763495617 -3.78071639814495e-05 -1.08718690062542e-05 4.55933459588139e-06 -2.84182929260483e-05 -5.60303558297876e-05 -3.78071639814495e-05 5.03585484371194e-05 2.23320835183503e-07 1.09553213819494e-05 5.37810753870095e-06 3.81164615119756e-05 -1.08718690062542e-05 2.23320835183503e-07 1.1211381654794e-05 2.502481278427e-07 5.17936484588306e-06 4.68343768159551e-06 4.55933459588139e-06 1.09553213819494e-05 2.502481278427e-07 0.00012057510586014 -8.08842321886298e-05 -2.32128297871746e-06 -2.84182929260483e-05 5.37810753870095e-06 5.17936484588306e-06 -8.08842321886298e-05 0.000114900422485529 3.15917334115873e-05 -5.60303558297876e-05 3.81164615119756e-05 4.68343768159551e-06 -2.32128297871746e-06 3.15917334115873e-05 0.000126671543595071 986 1005 0 134 0 958 977 0 134 0 0 0 0 0 0 0 0 0 274 0 890 876 0 0 789 +436 381 0.742330043142438 0.666204526321544 0.0715376555167514 0.123185696860453 -0.669996927361946 0.739174907325359 0.0687355345225301 -0.0715508452193044 -0.00708691566882783 -0.0989544616944291 0.995066726474697 0.425334763449704 9.76989666179438e-05 -3.19076085265094e-05 -8.87523774591493e-06 1.73589174324244e-05 -3.02849381043642e-05 -3.87924794858332e-05 -3.19076085265094e-05 5.04597275486598e-05 -5.24368763579355e-07 1.33551327765747e-07 1.43207342224738e-05 4.66278077404312e-05 -8.87523774591493e-06 -5.24368763579355e-07 1.21418461603438e-05 5.78767275325418e-07 6.27375824256326e-06 4.16024453161378e-06 1.73589174324244e-05 1.33551327765747e-07 5.78767275325418e-07 7.15343095062958e-05 -3.42580552162656e-05 -8.48300868456645e-06 -3.02849381043642e-05 1.43207342224738e-05 6.27375824256326e-06 -3.42580552162656e-05 8.95027942856577e-05 4.43786853242018e-05 -3.87924794858332e-05 4.66278077404312e-05 4.16024453161378e-06 -8.48300868456645e-06 4.43786853242018e-05 0.000140673070668238 1129 1148 0 136 0 1111 1130 0 136 0 0 0 0 0 0 0 0 0 263 0 852 838 0 0 755 +436 432 0.927794468929103 0.372953915365314 0.0101390550963202 0.0804925863160084 -0.372163657795614 0.927060406290164 -0.0453124144722471 -0.0596772329165175 -0.0262989589290734 0.0382672196899361 0.998921410650732 0.341347282047598 3.91030430363269e-05 -7.88269642045341e-06 -3.73074023551182e-06 -4.96249181924535e-07 5.27222976511685e-07 -6.97473314861213e-06 -7.88269642045341e-06 3.57031731652885e-05 3.68866076144797e-06 3.34961974200842e-06 -4.88601962172369e-08 1.58679100562806e-05 -3.73074023551182e-06 3.68866076144797e-06 1.18259989783509e-05 1.24062281992264e-06 2.3323222375902e-06 -7.31427572290991e-07 -4.96249181924535e-07 3.34961974200842e-06 1.24062281992264e-06 3.08878746017566e-05 -2.90431311037974e-07 7.33112309993135e-06 5.27222976511685e-07 -4.88601962172369e-08 2.3323222375902e-06 -2.90431311037974e-07 4.74304458778797e-05 -1.83610120280299e-06 -6.97473314861213e-06 1.58679100562806e-05 -7.31427572290991e-07 7.33112309993135e-06 -1.83610120280299e-06 7.48796254162983e-05 1677 1677 0 0 0 1661 1661 0 0 0 0 0 0 0 0 0 0 0 865 0 656 644 0 0 1796 +436 433 0.966842592642918 0.254696127769503 0.0185818069826536 0.0675671971590069 -0.253340907740807 0.965767585592268 -0.0557795220878207 -0.0569607274495208 -0.0321525351501803 0.0492224859033216 0.998270184551714 0.283029586758876 2.72685719216649e-05 2.61302441399613e-06 -1.18534342333964e-06 -4.17066476557459e-06 8.60032877534097e-07 1.61108890031384e-06 2.61302441399613e-06 2.82087548359955e-05 6.03111956649757e-06 -2.29735164744994e-06 1.08056743032067e-06 3.86462229434995e-06 -1.18534342333964e-06 6.03111956649757e-06 1.38415285039374e-05 5.44989300339725e-07 8.18542165444589e-07 3.7589975535579e-06 -4.17066476557459e-06 -2.29735164744994e-06 5.44989300339725e-07 2.78225707669444e-05 3.87716184890122e-06 -8.91289203276569e-06 8.60032877534097e-07 1.08056743032067e-06 8.18542165444589e-07 3.87716184890122e-06 4.98682487924945e-05 -7.90811250267197e-06 1.61108890031384e-06 3.86462229434995e-06 3.7589975535579e-06 -8.91289203276569e-06 -7.90811250267197e-06 4.84025762898083e-05 1540 1540 0 0 0 1526 1526 0 0 0 0 0 0 0 0 0 0 0 1248 0 541 504 0 0 2148 +436 384 0.742143549077936 0.666431506048121 0.0713582532608479 0.121956553361209 -0.670163323982944 0.73946043113982 0.0638701022908434 -0.0763710345363851 -0.0102015562605167 -0.0952224685930039 0.995403742068975 0.416670153131067 8.74356906304734e-05 -1.58933563131244e-05 -6.53928457975715e-06 1.84894725578193e-05 -2.2314525354843e-05 -1.72201343808178e-05 -1.58933563131244e-05 4.18513994090532e-05 -1.2888665434498e-08 6.98077942602359e-06 5.16462910673949e-06 1.59339128826051e-05 -6.53928457975715e-06 -1.2888665434498e-08 1.22467974361036e-05 1.30362124332879e-06 5.25003312098565e-06 2.92677064008049e-06 1.84894725578193e-05 6.98077942602359e-06 1.30362124332879e-06 8.29591220795737e-05 -4.56885097516859e-05 -1.01393229183183e-05 -2.2314525354843e-05 5.16462910673949e-06 5.25003312098565e-06 -4.56885097516859e-05 9.71471402606906e-05 2.25966745343348e-05 -1.72201343808178e-05 1.59339128826051e-05 2.92677064008049e-06 -1.01393229183183e-05 2.25966745343348e-05 7.7747572542049e-05 1002 1020 0 132 0 983 1001 0 132 0 0 0 0 0 0 0 0 0 288 0 946 932 0 0 805 +436 342 0.748979734554476 0.647163740636526 -0.142156428036323 0.155853415953125 -0.645314420502766 0.761138496572986 0.0650959885537774 -0.0764484097044942 0.150328493366648 0.0429800167514339 0.98770140338169 0.396017517596348 6.9901140102615e-05 1.76298740637818e-05 -2.76858118706845e-06 -1.68548045204754e-05 6.25376241936187e-06 -2.99534012358198e-05 1.76298740637818e-05 0.000209391725612951 6.12761940392156e-06 1.81925930913808e-05 2.05044489804105e-05 3.19244043604373e-05 -2.76858118706845e-06 6.12761940392156e-06 1.62783059965936e-05 1.55823714771209e-06 -3.7802753735876e-06 3.46798608746281e-06 -1.68548045204754e-05 1.81925930913808e-05 1.55823714771209e-06 6.04885105630208e-05 -1.47151099492168e-05 2.92021975723037e-05 6.25376241936187e-06 2.05044489804105e-05 -3.7802753735876e-06 -1.47151099492168e-05 8.30162354429182e-05 1.21197125316755e-07 -2.99534012358198e-05 3.19244043604373e-05 3.46798608746281e-06 2.92021975723037e-05 1.21197125316755e-07 0.000123224482578734 465 464 0 63 0 446 445 0 63 0 0 0 0 0 0 0 0 0 204 0 657 637 0 0 546 +436 385 0.742182028396863 0.666500243877394 0.070308332622052 0.119071739650738 -0.670162672753615 0.739129958414297 0.0675936137679534 -0.0634952245756132 -0.00691583490622055 -0.0972847854798183 0.995232556612622 0.421379799426844 0.000130301641930832 -5.30577426355121e-05 -1.46496282227999e-05 1.02094333893026e-05 -2.43377520331644e-05 -6.99482042823571e-05 -5.30577426355121e-05 6.11954683680421e-05 5.75566370053643e-06 1.08532421312897e-05 1.38388556824553e-05 5.2361675242715e-05 -1.46496282227999e-05 5.75566370053643e-06 1.20431096167139e-05 3.93079516110042e-07 3.29576323393888e-06 7.5383385482827e-06 1.02094333893026e-05 1.08532421312897e-05 3.93079516110042e-07 5.85199374801481e-05 -1.70432072902329e-05 3.2510516103204e-06 -2.43377520331644e-05 1.38388556824553e-05 3.29576323393888e-06 -1.70432072902329e-05 6.10393658113641e-05 2.69197989291525e-05 -6.99482042823571e-05 5.2361675242715e-05 7.5383385482827e-06 3.2510516103204e-06 2.69197989291525e-05 0.000142113235954302 1140 1158 0 134 0 1139 1157 0 134 0 0 0 0 0 0 0 0 0 265 0 855 841 0 0 791 +436 382 0.742296140608529 0.666562947912592 0.0684855905118595 0.118856245875356 -0.670048116443017 0.739244938666517 0.0674717889721446 -0.0703055709966353 -0.00565343159927074 -0.0959726894799353 0.995367912676082 0.42277623759219 9.16698405890406e-05 -3.2606811262515e-05 -7.64762901689174e-06 1.85961473139046e-05 -2.64077179798198e-05 -4.24530827465404e-05 -3.2606811262515e-05 5.72772388515719e-05 6.7714829450392e-07 -7.55588002130182e-07 2.87876012651142e-05 4.54078183459e-05 -7.64762901689174e-06 6.7714829450392e-07 1.15379477715149e-05 -4.78365372279282e-07 2.85170598389614e-06 3.27727234153087e-06 1.85961473139046e-05 -7.55588002130182e-07 -4.78365372279282e-07 5.2017765964218e-05 -2.06069655017186e-05 -6.78871518149491e-06 -2.64077179798198e-05 2.87876012651142e-05 2.85170598389614e-06 -2.06069655017186e-05 8.58472227300252e-05 5.32556835400908e-05 -4.24530827465404e-05 4.54078183459e-05 3.27727234153087e-06 -6.78871518149491e-06 5.32556835400908e-05 0.000114714152053474 1031 1043 0 125 0 1013 1025 0 125 0 0 0 0 0 0 0 0 0 278 0 851 837 0 0 823 +436 387 0.742305846261747 0.665985813037002 0.0737897515856738 0.12406385931397 -0.670029196561617 0.738832324400609 0.0720254967062878 -0.0634837855082188 -0.00655029469765591 -0.102906235254414 0.994669493040345 0.422243800055981 9.62696563461151e-05 -2.22996019926635e-05 -1.25217864727777e-05 1.40489925187655e-05 -3.85646098125817e-06 -1.50779592753003e-05 -2.22996019926635e-05 5.14602567399644e-05 2.4555020858591e-06 5.50966149549529e-06 1.06708727488364e-05 3.11325957502259e-05 -1.25217864727777e-05 2.4555020858591e-06 1.31214912231804e-05 -3.04254856077624e-06 4.31495620699137e-07 1.04289507853559e-06 1.40489925187655e-05 5.50966149549529e-06 -3.04254856077624e-06 6.67308243348932e-05 -1.44088801478946e-05 -5.14106660127061e-06 -3.85646098125817e-06 1.06708727488364e-05 4.31495620699137e-07 -1.44088801478946e-05 6.71885998972433e-05 2.75600742927672e-05 -1.50779592753003e-05 3.11325957502259e-05 1.04289507853559e-06 -5.14106660127061e-06 2.75600742927672e-05 0.00010207223290949 1012 1028 0 137 0 1000 1016 0 137 0 0 0 0 0 0 0 0 0 263 0 903 889 0 0 803 +436 378 0.742216954542387 0.66639701854607 0.070915485352162 0.119738350897446 -0.670107574404912 0.739311843862049 0.0661349850719136 -0.0760258241673553 -0.00835650136056691 -0.0966075110858663 0.995287474896979 0.418220499318495 9.48759613088256e-05 -2.98934550359465e-05 -6.69004623574646e-06 1.99598041884647e-05 -3.85103412162548e-05 -4.34599223709059e-05 -2.98934550359465e-05 4.62169971250749e-05 -2.6894520474635e-06 3.26196981142483e-06 1.77762528594884e-05 3.27562930223041e-05 -6.69004623574646e-06 -2.6894520474635e-06 1.19305154016952e-05 7.73215987519862e-07 2.50618733583055e-06 4.02415938199541e-06 1.99598041884647e-05 3.26196981142483e-06 7.73215987519862e-07 8.80930542920648e-05 -6.2212426796153e-05 -2.20226508892539e-05 -3.85103412162548e-05 1.77762528594884e-05 2.50618733583055e-06 -6.2212426796153e-05 0.000129797322844786 6.32439304133503e-05 -4.34599223709059e-05 3.27562930223041e-05 4.02415938199541e-06 -2.20226508892539e-05 6.32439304133503e-05 0.00010858717110057 1001 1018 0 136 0 963 980 0 136 0 0 0 0 0 0 0 0 0 285 0 967 953 0 0 803 +437 332 0.754644560144 0.64955178637967 -0.0927041782016745 0.124674682912704 -0.649566129208707 0.759537133499026 0.0341641130559431 -0.0360252224624957 0.0926036264402476 0.0344357321261238 0.995107405621651 0.319541784231452 4.33872288093339e-05 3.10097281537664e-06 -4.75779163427499e-06 -6.16972841431277e-07 5.41981286884257e-07 -4.62728014914844e-06 3.10097281537664e-06 6.87078704289673e-05 8.87862270043177e-08 5.59799558071724e-06 8.90942438244147e-06 -8.31177006720417e-06 -4.75779163427499e-06 8.87862270043177e-08 1.48686016881506e-05 3.28961764265038e-06 -4.65758775254986e-06 -2.92725396512848e-06 -6.16972841431277e-07 5.59799558071724e-06 3.28961764265038e-06 9.76477430627169e-05 -7.761470877638e-05 -2.58445474546412e-05 5.41981286884257e-07 8.90942438244147e-06 -4.65758775254986e-06 -7.761470877638e-05 0.000143281026573906 4.78575849704769e-05 -4.62728014914844e-06 -8.31177006720417e-06 -2.92725396512848e-06 -2.58445474546412e-05 4.78575849704769e-05 0.000110918680822827 758 758 0 0 0 758 758 0 0 0 0 0 0 0 0 0 0 0 526 0 784 770 0 0 725 +437 439 0.984276714426158 -0.16780263272891 -0.0551509373237935 -0.067852335290437 0.169969282819603 0.984745380655461 0.0372421558924917 0.100849300409952 0.0480602989611639 -0.0460305521037625 0.997783240958068 -0.16572137746584 5.50905495001346e-05 -1.83533749093699e-05 -2.18435175135617e-06 2.72157813941153e-06 5.78000859838229e-06 6.19080720016419e-07 -1.83533749093699e-05 4.88423858215514e-05 3.5839675988182e-07 4.06047406881892e-06 -5.57032949303002e-06 1.56936859739061e-05 -2.18435175135617e-06 3.5839675988182e-07 1.03226849498918e-05 1.75433577898632e-06 -1.00020628861658e-06 -7.27246070757327e-07 2.72157813941153e-06 4.06047406881892e-06 1.75433577898632e-06 2.75167976352318e-05 1.45871636535448e-05 7.89863916852644e-06 5.78000859838229e-06 -5.57032949303002e-06 -1.00020628861658e-06 1.45871636535448e-05 8.28485824488397e-05 -5.86762327849088e-08 6.19080720016419e-07 1.56936859739061e-05 -7.27246070757327e-07 7.89863916852644e-06 -5.86762327849088e-08 0.00012521896243054 651 630 0 0 345 651 630 0 0 345 0 0 0 0 0 0 0 0 1900 0 0 0 0 0 2394 +436 379 0.742330684848619 0.666335795151778 0.0702976701721205 0.119685499963082 -0.669981372620305 0.73948727763067 0.0654486559387753 -0.0952213644751 -0.00837345054278122 -0.0956826751393795 0.995376667902247 0.420369266258085 0.000172298925015571 -5.95399795106972e-05 -1.77108924897789e-05 1.23445084132873e-05 -1.79807607008009e-05 -0.000114991200029533 -5.95399795106972e-05 6.09657400117658e-05 4.36761783693111e-06 1.7969956852437e-05 -5.81163909626105e-07 5.98828927490469e-05 -1.77108924897789e-05 4.36761783693111e-06 1.40398949023942e-05 -1.26482107177994e-07 3.5555010496145e-06 1.22053954946681e-05 1.23445084132873e-05 1.7969956852437e-05 -1.26482107177994e-07 0.000118543074097028 -8.39120254744634e-05 9.98982214532126e-06 -1.79807607008009e-05 -5.81163909626105e-07 3.5555010496145e-06 -8.39120254744634e-05 0.000113694743867004 2.04937647981376e-05 -0.000114991200029533 5.98828927490469e-05 1.22053954946681e-05 9.98982214532126e-06 2.04937647981376e-05 0.000217398876964772 888 905 0 132 0 871 888 0 132 0 0 0 0 0 0 0 0 0 267 0 851 837 0 0 772 +437 434 0.982996005026362 0.176935196347447 -0.0491201628224365 0.0706055636304019 -0.178909147151143 0.983085088884264 -0.0391819483827708 -0.110056059255367 0.0413566339039234 0.0473037451679002 0.998024040053759 0.299568102885735 2.48180893265741e-05 -2.64594516987796e-06 -2.61955779509088e-06 3.60670825417228e-07 2.47293482005863e-06 3.98659608626775e-06 -2.64594516987796e-06 3.41970497252184e-05 1.34682015528563e-06 -2.33422822117799e-06 3.36760966650454e-06 -3.03821580456113e-06 -2.61955779509088e-06 1.34682015528563e-06 1.0802158002135e-05 2.88176025910051e-06 1.45352432646198e-06 8.93632970882931e-07 3.60670825417228e-07 -2.33422822117799e-06 2.88176025910051e-06 2.13480189773006e-05 9.20497259591344e-07 4.49370832318614e-06 2.47293482005863e-06 3.36760966650454e-06 1.45352432646198e-06 9.20497259591344e-07 6.13258182357139e-05 -2.44455782952699e-06 3.98659608626775e-06 -3.03821580456113e-06 8.93632970882931e-07 4.49370832318614e-06 -2.44455782952699e-06 4.8909474871593e-05 1106 1106 0 0 0 1122 1122 0 0 0 0 0 0 0 0 0 0 0 1416 0 405 390 0 0 2647 +437 440 0.957392522828261 -0.283084623112212 -0.0571196410173726 -0.111504059253371 0.28532295189839 0.957767941801412 0.035656454920203 0.166421364010672 0.0446135669110412 -0.0504347679176184 0.997730406388705 -0.236490857932343 6.16075643729464e-05 8.43774496824889e-07 -5.45765114838288e-06 1.14346016383514e-05 3.66821680715887e-06 4.31441481723519e-05 8.43774496824889e-07 4.51095764669295e-05 3.41563301264413e-06 -3.78117256390885e-06 -7.7592085868169e-06 1.23486332058769e-05 -5.45765114838288e-06 3.41563301264413e-06 1.39980552711759e-05 -1.3224337182406e-06 -2.03939327139254e-06 -3.30194746293829e-07 1.14346016383514e-05 -3.78117256390885e-06 -1.3224337182406e-06 4.40486833069794e-05 3.5385299792778e-05 -1.35968897988228e-06 3.66821680715887e-06 -7.7592085868169e-06 -2.03939327139254e-06 3.5385299792778e-05 0.000106354434603532 -3.48885292863377e-05 4.31441481723519e-05 1.23486332058769e-05 -3.30194746293829e-07 -1.35968897988228e-06 -3.48885292863377e-05 0.000163621461848786 232 189 0 0 482 232 189 0 0 489 0 0 0 0 0 330 224 0 1842 0 0 0 0 0 2122 +436 388 0.741723704816529 0.667726119631001 0.0631488311512521 0.112713003440045 -0.670628405542117 0.739771899336812 0.0547273115696728 -0.0755841040166536 -0.010172875369407 -0.0829419442389187 0.996502456842223 0.411551588935891 0.000203832175736205 -7.18864796498125e-06 -1.51553410066432e-05 1.43329759751889e-05 6.40200525116593e-06 -6.67953673248724e-07 -7.18864796498125e-06 7.91646529264621e-05 -1.44235995565621e-06 1.20565559500155e-05 1.87483381015848e-05 8.07532542891253e-05 -1.51553410066432e-05 -1.44235995565621e-06 1.37690873605663e-05 -2.90754283513636e-06 -8.28988880453619e-07 5.92334070390506e-06 1.43329759751889e-05 1.20565559500155e-05 -2.90754283513636e-06 7.4483322676054e-05 -2.46860145351667e-05 5.85013236966268e-07 6.40200525116593e-06 1.87483381015848e-05 -8.28988880453619e-07 -2.46860145351667e-05 8.88215163947254e-05 3.6172489757929e-05 -6.67953673248724e-07 8.07532542891253e-05 5.92334070390506e-06 5.85013236966268e-07 3.6172489757929e-05 0.000193752018828342 1136 1151 0 122 0 1151 1166 0 122 0 0 0 0 0 0 0 0 0 284 0 769 757 0 0 752 +437 335 0.740515547128328 0.656688213940482 -0.142819165845807 0.144546654775214 -0.657798899461127 0.75178424028328 0.0460550098189366 -0.0872827834165198 0.137612980234291 0.0598418393212579 0.98867670243497 0.411041503715553 4.69786126892842e-05 -2.07333642595599e-05 -4.73174308564443e-06 -1.55662617788155e-06 2.97447369112857e-06 -2.91210985890756e-06 -2.07333642595599e-05 7.09691090044933e-05 1.83120426600402e-07 2.10891877792737e-05 -2.30295972750729e-05 2.7942828309006e-05 -4.73174308564443e-06 1.83120426600402e-07 1.89629661495155e-05 1.27634848419185e-05 -1.55387999485072e-05 6.7438103615462e-07 -1.55662617788155e-06 2.10891877792737e-05 1.27634848419185e-05 0.000206395220636681 -0.000197561960926134 1.22304892610513e-05 2.97447369112857e-06 -2.30295972750729e-05 -1.55387999485072e-05 -0.000197561960926134 0.000294981905097263 -8.78343329703642e-06 -2.91210985890756e-06 2.7942828309006e-05 6.7438103615462e-07 1.22304892610513e-05 -8.78343329703642e-06 0.000114720169094891 495 493 0 19 0 495 493 0 19 0 0 0 0 0 0 0 0 0 329 0 818 803 0 0 602 +436 383 0.742258839468807 0.666494105993247 0.0695515773126874 0.119642525753759 -0.670043358331359 0.739672352927766 0.0626634524291139 -0.0777683621922706 -0.00968055713552037 -0.0931150739169791 0.995608291359097 0.415277535584997 8.94210169713094e-05 -2.06073162247608e-05 -8.85309454872735e-06 6.64813750859601e-06 5.3416457934552e-07 -2.26282431461798e-05 -2.06073162247608e-05 4.46090104559865e-05 -1.01139828439711e-06 8.30259679214049e-06 -3.9426172661929e-06 2.22182614011e-05 -8.85309454872735e-06 -1.01139828439711e-06 1.284525515711e-05 1.00025581457547e-06 2.72659932898696e-06 1.07548281634204e-06 6.64813750859601e-06 8.30259679214049e-06 1.00025581457547e-06 7.88223136690287e-05 -4.5721770665607e-05 2.28120813387848e-06 5.3416457934552e-07 -3.9426172661929e-06 2.72659932898696e-06 -4.5721770665607e-05 8.15847884296146e-05 2.30176324834155e-05 -2.26282431461798e-05 2.22182614011e-05 1.07548281634204e-06 2.28120813387848e-06 2.30176324834155e-05 0.000105635294946946 974 990 0 129 0 945 961 0 129 0 0 0 0 0 0 0 0 0 264 0 955 941 0 0 769 +437 338 0.770426350050501 0.617330257850214 -0.15920613019118 0.165061927740933 -0.619367923607231 0.783946249904405 0.0425635109840313 -0.138831899481811 0.15108479193595 0.0658151198692921 0.986327407934232 0.466983076348525 4.27462235426235e-05 4.91316352730271e-07 -7.57438024600601e-06 7.72005675327772e-06 9.12646866147334e-06 2.29781057481227e-05 4.91316352730271e-07 7.41895346908261e-05 2.56632234597435e-07 -4.60699705091851e-06 8.33784502454583e-06 -1.45862029005558e-05 -7.57438024600601e-06 2.56632234597435e-07 1.90375293124268e-05 6.51397449163696e-06 -4.27595615092364e-06 -5.08600058950693e-06 7.72005675327772e-06 -4.60699705091851e-06 6.51397449163696e-06 9.47361789705177e-05 -5.35254240335813e-05 1.12148782119559e-05 9.12646866147334e-06 8.33784502454583e-06 -4.27595615092364e-06 -5.35254240335813e-05 0.000136380849354266 7.86652099483491e-06 2.29781057481227e-05 -1.45862029005558e-05 -5.08600058950693e-06 1.12148782119559e-05 7.86652099483491e-06 0.000116996936803344 428 426 0 11 0 428 426 0 11 0 0 0 0 0 0 0 0 0 293 0 534 511 0 0 559 +437 337 0.772330145670094 0.619665648791442 -0.139716247434196 0.159443221698065 -0.617792131907627 0.783914364224596 0.0617345228812561 -0.112403098162313 0.147780336453268 0.038636165314751 0.988265257351249 0.46208772250283 5.97902969930029e-05 -8.00628339663436e-07 -7.41573287119289e-06 -7.70309373407217e-06 2.12724153263695e-05 2.86170232419082e-05 -8.00628339663436e-07 3.4556525358641e-05 -1.00861057506394e-06 5.74762077092518e-06 -5.04087818290024e-06 8.29000767409174e-06 -7.41573287119289e-06 -1.00861057506394e-06 1.51594101997231e-05 1.57905077471883e-06 4.32544623179686e-07 -6.4523736613494e-06 -7.70309373407217e-06 5.74762077092518e-06 1.57905077471883e-06 0.000115312869219684 -7.97238461699088e-05 2.46770270465352e-05 2.12724153263695e-05 -5.04087818290024e-06 4.32544623179686e-07 -7.97238461699088e-05 0.000179723932152288 -8.46684140472147e-06 2.86170232419082e-05 8.29000767409174e-06 -6.4523736613494e-06 2.46770270465352e-05 -8.46684140472147e-06 0.000160478402505192 508 503 0 10 0 508 503 0 10 0 0 0 0 0 0 0 0 0 301 0 612 589 0 0 584 +437 333 0.738231133616734 0.661894858292002 -0.130038417114186 0.128865206409485 -0.666392554902045 0.745511981947716 0.0115259508724128 -0.0481391619553341 0.104574165691517 0.0781478172375884 0.991441961251854 0.357195791034857 3.15719740002345e-05 -6.92007555450187e-06 -2.01589312611781e-06 3.47172882397198e-06 -2.16415928789693e-06 -4.749240259211e-06 -6.92007555450187e-06 7.36747637175332e-05 -7.57092746411977e-07 4.32410467837704e-06 2.5588482768442e-05 1.49076329181586e-05 -2.01589312611781e-06 -7.57092746411977e-07 1.6331199816144e-05 4.50048532884337e-06 -3.53446626173966e-06 -5.73174696961754e-06 3.47172882397198e-06 4.32410467837704e-06 4.50048532884337e-06 0.000111379509235857 -7.34639681465314e-05 2.25720866718348e-06 -2.16415928789693e-06 2.5588482768442e-05 -3.53446626173966e-06 -7.34639681465314e-05 0.000140610972032082 1.88666777580184e-05 -4.749240259211e-06 1.49076329181586e-05 -5.73174696961754e-06 2.25720866718348e-06 1.88666777580184e-05 0.0001077420693925 765 767 0 19 0 765 767 0 19 0 0 0 0 0 0 0 0 0 430 0 837 822 0 0 750 +437 433 0.958295863964533 0.285694706882725 -0.00689721448571203 0.0927286812028888 -0.284873014082453 0.953063936277473 -0.102549983982778 -0.120262086882362 -0.0227245012276852 0.100238055779643 0.994703940485545 0.385854959828898 3.49837600790305e-05 7.43379191749868e-07 5.41998289634214e-07 -4.69824363382267e-06 -1.94359725349591e-06 1.57291883406987e-05 7.43379191749868e-07 3.45444456716629e-05 5.65219257220646e-06 1.35193144586542e-06 -5.0688596147087e-06 9.28604973809233e-06 5.41998289634214e-07 5.65219257220646e-06 1.30807998708085e-05 -5.97350358540542e-07 1.23386656038468e-07 1.98409727394285e-06 -4.69824363382267e-06 1.35193144586542e-06 -5.97350358540542e-07 2.85830276700712e-05 8.14150802047363e-06 -1.59138423295229e-06 -1.94359725349591e-06 -5.0688596147087e-06 1.23386656038468e-07 8.14150802047363e-06 5.64336209820856e-05 -1.56657227399974e-05 1.57291883406987e-05 9.28604973809233e-06 1.98409727394285e-06 -1.59138423295229e-06 -1.56657227399974e-05 6.37553644113873e-05 1109 1109 0 0 0 1123 1123 0 0 0 0 0 0 0 0 0 0 0 906 0 616 579 0 0 2285 +437 341 0.724841428708496 0.67325958270168 -0.146035740584918 0.176990401237167 -0.676646931671076 0.735581166488411 0.0326998068444965 -0.158369007735188 0.129436598719004 0.0751124610694413 0.988738734501763 0.488294421511482 5.66151394073083e-05 1.45946722996948e-05 -5.87386194556833e-06 -4.91524064501212e-07 1.05719727477955e-05 1.03772001706264e-05 1.45946722996948e-05 8.31545375638694e-05 2.40359648398523e-06 1.08003894369226e-05 4.03647460969309e-06 -2.09947792947813e-06 -5.87386194556833e-06 2.40359648398523e-06 1.77558472567535e-05 3.17215283224532e-06 -3.01867370761251e-06 1.94857255527459e-06 -4.91524064501212e-07 1.08003894369226e-05 3.17215283224532e-06 6.96889657459515e-05 -8.76956744197926e-06 1.84281635855386e-05 1.05719727477955e-05 4.03647460969309e-06 -3.01867370761251e-06 -8.76956744197926e-06 6.25854812783778e-05 -5.55314732712941e-06 1.03772001706264e-05 -2.09947792947813e-06 1.94857255527459e-06 1.84281635855386e-05 -5.55314732712941e-06 8.66936329663015e-05 277 289 0 40 0 277 289 0 40 0 0 0 0 0 0 0 0 0 159 0 568 556 0 0 499 +437 339 0.75785296307802 0.631494927807208 -0.163929992703087 0.163630453948482 -0.635902100935103 0.771152559038092 0.0308585274328612 -0.1037808086405 0.145902036929533 0.080857200314951 0.98598920317468 0.484026673967616 4.88512671533993e-05 1.59407593564862e-05 -6.43196479583375e-06 -6.30052865805922e-06 1.95364048376522e-05 1.05843996565741e-05 1.59407593564862e-05 8.41677186343342e-05 -3.62463710247302e-06 1.60788353865356e-05 7.91165256662833e-06 -2.62335293789054e-06 -6.43196479583375e-06 -3.62463710247302e-06 1.66922295962753e-05 2.72815198903439e-06 -1.24737319324906e-05 -2.85048861160729e-06 -6.30052865805922e-06 1.60788353865356e-05 2.72815198903439e-06 0.000103765373965662 -6.57940438904958e-05 1.53651749833778e-05 1.95364048376522e-05 7.91165256662833e-06 -1.24737319324906e-05 -6.57940438904958e-05 0.000154681035470331 9.35733134271347e-06 1.05843996565741e-05 -2.62335293789054e-06 -2.85048861160729e-06 1.53651749833778e-05 9.35733134271347e-06 0.000120215554263618 453 450 0 9 0 453 450 0 9 0 0 0 0 0 0 0 0 0 248 0 599 573 0 0 582 +437 340 0.737082951646407 0.656976386086487 -0.158400601378148 0.164701726827662 -0.662749644882742 0.748554490638678 0.0207143127442894 -0.140962646684336 0.132180295808488 0.0897117755336926 0.987157620003297 0.48463984452301 5.06086992956639e-05 6.03896137855123e-06 -5.56793764502214e-06 1.95501392065158e-06 2.06931780253201e-06 2.63728475145423e-05 6.03896137855123e-06 4.39070505580293e-05 -3.13655968928774e-06 7.86908938865705e-06 -4.95341904054394e-06 -2.27213528956465e-06 -5.56793764502214e-06 -3.13655968928774e-06 1.78218871111769e-05 6.56012081176543e-06 -5.18314107031756e-06 -1.1889137415067e-06 1.95501392065158e-06 7.86908938865705e-06 6.56012081176543e-06 8.59628906852114e-05 -5.35843609152369e-05 1.65006411045085e-06 2.06931780253201e-06 -4.95341904054394e-06 -5.18314107031756e-06 -5.35843609152369e-05 0.000135076851200667 -9.03025889280885e-06 2.63728475145423e-05 -2.27213528956465e-06 -1.1889137415067e-06 1.65006411045085e-06 -9.03025889280885e-06 0.00010371165034881 310 307 0 28 0 311 308 0 28 0 0 0 0 0 0 0 0 0 197 0 756 742 0 0 525 +437 336 0.753298466101122 0.640416039830901 -0.149695413747387 0.146868078685296 -0.640190487750464 0.766160615359774 0.0561609371837265 -0.101779371175337 0.150657095297628 0.0535276321056445 0.987135873240176 0.416343213734832 4.70731984190672e-05 7.30654126938534e-06 -2.13833117984011e-06 3.97921099886062e-06 3.23463237770795e-06 1.88894793553218e-06 7.30654126938534e-06 4.35012680486633e-05 -7.49990144371664e-07 7.48636506899269e-06 3.46745011518263e-06 1.42396352048496e-05 -2.13833117984011e-06 -7.49990144371664e-07 1.44317524447275e-05 3.56027312140239e-06 -5.66221907967513e-06 -6.58492459742903e-07 3.97921099886062e-06 7.48636506899269e-06 3.56027312140239e-06 0.000117694576788474 -9.62148851729325e-05 1.5919247524139e-05 3.23463237770795e-06 3.46745011518263e-06 -5.66221907967513e-06 -9.62148851729325e-05 0.000189043598632382 1.83230317367805e-05 1.88894793553218e-06 1.42396352048496e-05 -6.58492459742903e-07 1.5919247524139e-05 1.83230317367805e-05 0.000133075175268619 930 926 0 13 0 930 926 0 13 0 0 0 0 0 0 0 0 0 329 0 537 514 0 0 602 +437 441 0.911024683783073 -0.410146037361038 -0.0425940556297463 -0.158892209154186 0.411343235074406 0.911155232535446 0.0243492337004555 0.249972554281987 0.0288230549469296 -0.0397035295699967 0.998795705458934 -0.29389320440463 3.52965944813268e-05 5.72896326981353e-07 -3.73065127745486e-06 2.35400328904941e-06 3.57831930293924e-06 5.38823871213986e-06 5.72896326981353e-07 3.60139838267672e-05 3.24927481939392e-06 -2.68676118109074e-06 2.4699786766585e-06 3.71466655366892e-06 -3.73065127745486e-06 3.24927481939392e-06 1.38538648239151e-05 3.77891841858878e-06 -1.04652976129232e-06 -1.6606245275054e-06 2.35400328904941e-06 -2.68676118109074e-06 3.77891841858878e-06 4.66766753368162e-05 1.45996350510957e-05 -4.59792642708614e-06 3.57831930293924e-06 2.4699786766585e-06 -1.04652976129232e-06 1.45996350510957e-05 6.30381393587371e-05 1.77187759365169e-06 5.38823871213986e-06 3.71466655366892e-06 -1.6606245275054e-06 -4.59792642708614e-06 1.77187759365169e-06 9.14066036413941e-05 0 0 0 0 512 0 0 0 0 523 0 0 0 0 0 647 615 0 1773 0 0 0 0 0 1705 +437 380 0.719661137849839 0.692648234474417 0.0482314207560586 0.137240485769164 -0.694028330622214 0.719647499843645 0.0207882722354233 -0.160728913888947 -0.020310661299365 -0.0484344840817419 0.998619836468973 0.520333852958791 7.06000535656508e-05 -7.39495123494937e-06 -4.65930848043288e-06 -1.64671246406199e-06 3.60038337750943e-07 4.45783941222144e-05 -7.39495123494937e-06 4.50000469416254e-05 9.09353224037729e-07 1.14738912638579e-05 4.97404491792445e-06 1.60102035425649e-06 -4.65930848043288e-06 9.09353224037729e-07 9.8950828483972e-06 -4.01446387442188e-07 4.87032143546231e-07 -3.05916911791226e-07 -1.64671246406199e-06 1.14738912638579e-05 -4.01446387442188e-07 7.12932923691968e-05 -4.10390080167363e-05 1.19516355757204e-05 3.60038337750943e-07 4.97404491792445e-06 4.87032143546231e-07 -4.10390080167363e-05 8.68549164029978e-05 8.34558075647428e-06 4.45783941222144e-05 1.60102035425649e-06 -3.05916911791226e-07 1.19516355757204e-05 8.34558075647428e-06 0.000118642823211936 878 903 0 78 0 888 913 0 78 0 0 0 0 0 0 0 0 0 222 0 1108 1098 0 0 720 +437 342 0.725100850047274 0.671629459023725 -0.152127009542093 0.18498368159829 -0.676511147377804 0.736011294553348 0.0249006378125508 -0.159312439761317 0.128691199132995 0.0848601441278758 0.988047231261901 0.49020114186465 3.67364626541429e-05 7.37388573361751e-06 -3.36173698807322e-06 3.065531609931e-06 5.85080135632449e-06 -1.10217950959142e-06 7.37388573361751e-06 4.14260589974242e-05 2.81204996139318e-07 2.73106335094381e-07 -4.13636170470033e-06 -1.31956484166426e-05 -3.36173698807322e-06 2.81204996139318e-07 1.50667938876299e-05 4.19048847171715e-07 -4.58752677398461e-06 -1.03139331369556e-07 3.065531609931e-06 2.73106335094381e-07 4.19048847171715e-07 6.02081038401707e-05 -1.66271621069189e-05 7.30356776266183e-06 5.85080135632449e-06 -4.13636170470033e-06 -4.58752677398461e-06 -1.66271621069189e-05 6.85189602517905e-05 9.75616808600453e-07 -1.10217950959142e-06 -1.31956484166426e-05 -1.03139331369556e-07 7.30356776266183e-06 9.75616808600453e-07 6.94906367499242e-05 366 370 0 28 0 366 370 0 28 0 0 0 0 0 0 0 0 0 129 0 660 646 0 0 496 +437 384 0.719629112533443 0.692551716229402 0.0500605707322577 0.143066968416891 -0.693979505328704 0.719746700790912 0.0188979597926854 -0.154473910937034 -0.0229431161365941 -0.0483405321475477 0.998567376982462 0.521703693635898 6.12511644003315e-05 -1.02926517116104e-05 -5.48612668411084e-06 1.06450541300325e-05 -1.56954480070211e-05 1.41671467643387e-05 -1.02926517116104e-05 4.52538465409551e-05 1.18650429257696e-06 3.64146272075865e-06 1.0154722209769e-05 1.32931017734862e-05 -5.48612668411084e-06 1.18650429257696e-06 1.07709636196187e-05 1.64270153692107e-06 1.88934654707378e-06 -1.69256467575934e-06 1.06450541300325e-05 3.64146272075865e-06 1.64270153692107e-06 5.55202773849274e-05 -8.29594372057221e-06 1.26592187611508e-05 -1.56954480070211e-05 1.0154722209769e-05 1.88934654707378e-06 -8.29594372057221e-06 7.33046052937635e-05 9.8298526357226e-06 1.41671467643387e-05 1.32931017734862e-05 -1.69256467575934e-06 1.26592187611508e-05 9.8298526357226e-06 0.000106431718403561 936 959 0 78 0 959 982 0 78 0 0 0 0 0 0 0 0 0 224 0 1117 1109 0 0 748 +437 382 0.719364554371624 0.692743362054154 0.0511983617279121 0.141480647250829 -0.694284202546703 0.719382514745578 0.0214066244984251 -0.158873061527654 -0.0220019091854093 -0.0509453806368714 0.998459054835981 0.525964780498219 5.83614690426562e-05 -1.44124402173862e-05 -6.08041992674745e-06 3.35154751979889e-06 1.38028514798355e-05 3.39725283507486e-05 -1.44124402173862e-05 4.21796674688476e-05 3.86000993467723e-06 3.9025105785332e-06 1.04381084742167e-05 4.43943178856197e-06 -6.08041992674745e-06 3.86000993467723e-06 1.24247067715425e-05 1.22680509797423e-06 -2.6545983520138e-06 -2.94722382960591e-06 3.35154751979889e-06 3.9025105785332e-06 1.22680509797423e-06 6.59998242556735e-05 -3.00114051309489e-05 -3.1649628527721e-07 1.38028514798355e-05 1.04381084742167e-05 -2.6545983520138e-06 -3.00114051309489e-05 9.93359874544839e-05 3.25249048304324e-05 3.39725283507486e-05 4.43943178856197e-06 -2.94722382960591e-06 -3.1649628527721e-07 3.25249048304324e-05 0.000127094112895556 874 900 0 82 0 890 916 0 82 0 0 0 0 0 0 0 0 0 214 0 1045 1037 0 0 768 +437 381 0.719284319529266 0.692464695141191 0.0558812460700182 0.146925303328408 -0.694200278533981 0.719519824275085 0.0194215282223918 -0.165247935723568 -0.0267589417328777 -0.0527623772982941 0.998248511433485 0.529097347273965 4.6674851408742e-05 -1.23296090683797e-05 -4.28733312225244e-06 -1.36587371340257e-06 -1.1804095354405e-06 2.63610677315635e-05 -1.23296090683797e-05 4.03904275506109e-05 2.25869230084362e-06 5.38336866794417e-06 1.86526036292117e-05 1.07740288111538e-05 -4.28733312225244e-06 2.25869230084362e-06 1.0956652817859e-05 1.89144141699007e-06 2.24426472939624e-06 -4.26748484436538e-06 -1.36587371340257e-06 5.38336866794417e-06 1.89144141699007e-06 6.17580824972164e-05 -1.98791779127357e-05 -5.89582887502449e-06 -1.1804095354405e-06 1.86526036292117e-05 2.24426472939624e-06 -1.98791779127357e-05 7.16360066252352e-05 2.4822345519583e-05 2.63610677315635e-05 1.07740288111538e-05 -4.26748484436538e-06 -5.89582887502449e-06 2.4822345519583e-05 0.00010206596582432 731 758 0 79 0 751 778 0 79 0 0 0 0 0 0 0 0 0 218 0 1117 1110 0 0 726 +438 440 0.975955130547577 -0.212015856147408 -0.0506049394816719 -0.0680363044248127 0.213185638323624 0.976828898443265 0.0188993856690372 0.120030775371383 0.0454253978563887 -0.0292331987336228 0.998539910730357 -0.136387408973605 2.39595278873197e-05 -4.36817081132447e-06 3.39037158358521e-07 6.42722324650022e-06 5.42295218978402e-06 -2.45207554594913e-06 -4.36817081132447e-06 4.16699652879341e-05 -6.57291544067268e-07 -1.4342328058558e-06 -1.26561258188037e-05 3.27999491635547e-06 3.39037158358521e-07 -6.57291544067268e-07 1.39798716502604e-05 5.08902360674245e-06 -2.41421775719285e-07 -2.35221138902113e-06 6.42722324650022e-06 -1.4342328058558e-06 5.08902360674245e-06 4.13873204115035e-05 2.30782325064652e-05 9.02382837528885e-06 5.42295218978402e-06 -1.26561258188037e-05 -2.41421775719285e-07 2.30782325064652e-05 9.28301795351728e-05 -9.49089775027097e-06 -2.45207554594913e-06 3.27999491635547e-06 -2.35221138902113e-06 9.02382837528885e-06 -9.49089775027097e-06 8.74298124177061e-05 55 53 0 0 224 55 53 0 0 231 0 0 0 0 0 366 246 0 2187 0 0 0 0 0 2446 +438 435 0.983403260805536 0.169038162845087 -0.0659099851236321 0.0825040029522948 -0.174835611668315 0.979975557097644 -0.0952912188175215 -0.134623696432253 0.0484823218256458 0.105233107875424 0.993265048955853 0.281776885977264 4.3687994588386e-05 -1.80049424811503e-05 -3.6454701170272e-06 6.03200616428501e-06 1.16715697062966e-05 3.4282484984529e-05 -1.80049424811503e-05 3.48734823414113e-05 7.3737912132696e-06 -3.40529170658625e-06 -6.08605609856851e-06 -8.79653816345577e-06 -3.6454701170272e-06 7.3737912132696e-06 1.29012450414328e-05 -2.72359950291264e-06 -3.04911300007386e-06 -3.56941418548386e-06 6.03200616428501e-06 -3.40529170658625e-06 -2.72359950291264e-06 2.82843753982595e-05 3.27977821877133e-06 1.18832009625908e-05 1.16715697062966e-05 -6.08605609856851e-06 -3.04911300007386e-06 3.27977821877133e-06 6.65361338091299e-05 -8.13526960901607e-07 3.4282484984529e-05 -8.79653816345577e-06 -3.56941418548386e-06 1.18832009625908e-05 -8.13526960901607e-07 9.89847881531154e-05 750 750 0 0 0 741 741 0 0 0 0 0 0 0 0 0 0 0 1365 0 342 305 0 0 2205 +437 385 0.719613254068827 0.692521664795832 0.05070018103404 0.138199198683025 -0.694032752686814 0.719631116158715 0.0212036519054135 -0.157763131819671 -0.0218014395496869 -0.0504460151505719 0.998488806541661 0.517741959637057 4.69879387229545e-05 -7.05782243591331e-06 -2.87988561888468e-06 1.18964171882371e-06 6.1863635071347e-06 2.48942339957481e-05 -7.05782243591331e-06 3.57206026476641e-05 5.61573572091177e-07 6.85858852315727e-06 6.46803760053438e-06 1.21131770044021e-05 -2.87988561888468e-06 5.61573572091177e-07 1.09410836388649e-05 2.91951631557546e-08 1.29961766422922e-06 -3.92821584172871e-07 1.18964171882371e-06 6.85858852315727e-06 2.91951631557546e-08 4.47062967428733e-05 -1.00495234763895e-05 4.98740226361038e-06 6.1863635071347e-06 6.46803760053438e-06 1.29961766422922e-06 -1.00495234763895e-05 5.25035469371602e-05 8.9571694623367e-06 2.48942339957481e-05 1.21131770044021e-05 -3.92821584172871e-07 4.98740226361038e-06 8.9571694623367e-06 8.89469965305476e-05 904 929 0 73 0 920 945 0 73 0 0 0 0 0 0 0 0 0 218 0 1061 1053 0 0 712 +437 383 0.719603818987724 0.692456099982205 0.0517193706044225 0.141901246625024 -0.694023721708572 0.719633666278139 0.0214116805708307 -0.153536508326314 -0.0223923514635161 -0.0513023971810213 0.998432094155339 0.521181658776438 5.18784706998311e-05 -7.7618349286624e-06 -2.78844853788327e-06 9.30506051882646e-07 -5.09508269127246e-06 1.27418171165311e-05 -7.7618349286624e-06 4.20147112963975e-05 -1.45087295267363e-06 1.0009128753888e-05 9.94315767141852e-06 5.20918822200623e-06 -2.78844853788327e-06 -1.45087295267363e-06 1.08652094597961e-05 3.17180283671648e-06 1.64778038752094e-07 -1.80578904229873e-07 9.30506051882646e-07 1.0009128753888e-05 3.17180283671648e-06 5.75680852437476e-05 -1.16052065661057e-05 2.22591740773329e-05 -5.09508269127246e-06 9.94315767141852e-06 1.64778038752094e-07 -1.16052065661057e-05 6.47383599288669e-05 2.56917904062294e-06 1.27418171165311e-05 5.20918822200623e-06 -1.80578904229873e-07 2.22591740773329e-05 2.56917904062294e-06 0.000122613542242723 939 966 0 76 0 970 997 0 76 0 0 0 0 0 0 0 0 0 217 0 1100 1093 0 0 733 +438 333 0.68817162123439 0.714336916183568 -0.127053492297458 0.15842583963421 -0.720263565946162 0.693699758606024 -0.00102003944147477 -0.121619161665418 0.0874083251077901 0.0922139636242429 0.991895342067175 0.458744123994025 3.15374864756184e-05 -3.07627899748124e-06 -2.04099113168992e-06 1.36958776545392e-06 3.66779374743783e-06 -4.87316064638627e-07 -3.07627899748124e-06 4.51918904382783e-05 -1.35271161506746e-06 1.40879205554708e-05 -2.02838851078729e-05 9.31077325559535e-06 -2.04099113168992e-06 -1.35271161506746e-06 1.67184098008659e-05 6.25448540710078e-06 -2.59828434035156e-06 2.81248576910991e-06 1.36958776545392e-06 1.40879205554708e-05 6.25448540710078e-06 0.000148898630971654 -0.000120679030327567 1.97558217433441e-05 3.66779374743783e-06 -2.02838851078729e-05 -2.59828434035156e-06 -0.000120679030327567 0.000197886856519036 -2.03804493086145e-05 -4.87316064638627e-07 9.31077325559535e-06 2.81248576910991e-06 1.97558217433441e-05 -2.03804493086145e-05 9.22628380831333e-05 661 661 0 0 0 649 649 0 0 0 0 0 0 0 0 0 0 0 279 0 693 681 0 0 601 +438 331 0.711302222605722 0.699046287273567 -0.0733719044675929 0.142387374866301 -0.699545192273656 0.714219489470199 0.0229574569092921 -0.113045679042833 0.068451969167984 0.034997272893312 0.997040379727449 0.338622330625287 3.06498527347125e-05 -7.93031001080738e-06 -5.12018131387697e-06 -2.038590173243e-06 5.0015373510399e-06 -6.74718734622997e-07 -7.93031001080738e-06 6.72200581282373e-05 9.62973713486112e-07 1.54670391813574e-05 2.59131433238047e-07 9.37437716927808e-06 -5.12018131387697e-06 9.62973713486112e-07 1.62407793514556e-05 5.39872437953556e-06 -7.93856582086481e-06 -1.28645696638729e-06 -2.038590173243e-06 1.54670391813574e-05 5.39872437953556e-06 0.000119082199894093 -8.97674903663419e-05 1.12660670187327e-05 5.0015373510399e-06 2.59131433238047e-07 -7.93856582086481e-06 -8.97674903663419e-05 0.000149292075077841 -2.84379134249431e-07 -6.74718734622997e-07 9.37437716927808e-06 -1.28645696638729e-06 1.12660670187327e-05 -2.84379134249431e-07 7.20212295760662e-05 904 904 0 0 0 898 898 0 0 0 0 0 0 0 0 0 0 0 458 0 842 819 0 0 653 +438 337 0.728144600917161 0.675384234472493 -0.116882744582735 0.191249245781926 -0.675379880858161 0.736051644770942 0.0457164386408965 -0.237847026500192 0.116907898309754 0.0456520761411327 0.99209295494767 0.556279342032874 3.34970169277348e-05 7.34932683572806e-06 -3.53591380640701e-06 4.14571505136458e-06 4.01543261268621e-06 7.43427014774484e-06 7.34932683572806e-06 4.18240996570962e-05 1.62691899814833e-06 -2.10277842408421e-06 3.12049022714132e-06 -8.80041588993857e-06 -3.53591380640701e-06 1.62691899814833e-06 1.6672496687671e-05 -2.07796803885531e-06 4.75481950488796e-07 -2.61632117669853e-06 4.14571505136458e-06 -2.10277842408421e-06 -2.07796803885531e-06 7.59089675946255e-05 -4.37270901031182e-05 5.75742304822041e-06 4.01543261268621e-06 3.12049022714132e-06 4.75481950488796e-07 -4.37270901031182e-05 0.00011294677483666 -4.96621961540229e-06 7.43427014774484e-06 -8.80041588993857e-06 -2.61632117669853e-06 5.75742304822041e-06 -4.96621961540229e-06 9.43621270282363e-05 351 351 0 0 0 349 349 0 0 0 0 0 0 0 0 0 0 0 167 0 376 349 0 0 591 +438 332 0.705660131621904 0.703276143187646 -0.0862927868507366 0.148946651261749 -0.704672658364206 0.709298305985667 0.0182306796303714 -0.133946256567331 0.0740285295901469 0.0479435037202397 0.996103005345204 0.405214015697453 3.39841969614865e-05 -3.79402519873361e-06 -5.64027172092762e-06 -1.47247710412686e-06 3.16663790846427e-06 3.26411053415916e-06 -3.79402519873361e-06 6.08350642864679e-05 -3.20859397563316e-07 7.53204058967906e-06 -1.01079162316598e-05 -2.75088984710054e-06 -5.64027172092762e-06 -3.20859397563316e-07 1.96875541071975e-05 5.92845709863419e-06 -3.86488111736354e-06 -2.56662686989297e-06 -1.47247710412686e-06 7.53204058967906e-06 5.92845709863419e-06 0.000132226663648122 -0.000112159025656623 4.49987340726903e-06 3.16663790846427e-06 -1.01079162316598e-05 -3.86488111736354e-06 -0.000112159025656623 0.000174891105489757 7.98246412183713e-06 3.26411053415916e-06 -2.75088984710054e-06 -2.56662686989297e-06 4.49987340726903e-06 7.98246412183713e-06 0.000115090393528587 874 874 0 0 0 859 859 0 0 0 0 0 0 0 0 0 0 0 375 0 515 495 0 0 602 +438 338 0.723544818237847 0.672569352323031 -0.155349162588473 0.183931099315776 -0.67684980412885 0.735443523735046 0.0315779360775318 -0.238339466655053 0.135488887558719 0.0822999982500446 0.987354785087986 0.555856920343695 4.36146555978222e-05 6.33520086620797e-06 -4.68622127078724e-06 -4.80802081888982e-07 -1.8276407141344e-06 -2.91715052726778e-06 6.33520086620797e-06 0.000126782197920208 7.36405116793988e-06 -1.79443321327681e-05 4.60853458151179e-05 -1.91003154328514e-05 -4.68622127078724e-06 7.36405116793988e-06 1.62361621805118e-05 -5.17637265976848e-07 4.79245692088574e-06 -9.21908999646099e-07 -4.80802081888982e-07 -1.79443321327681e-05 -5.17637265976848e-07 7.77659391299647e-05 -5.1539991118342e-05 4.93845671362171e-06 -1.8276407141344e-06 4.60853458151179e-05 4.79245692088574e-06 -5.1539991118342e-05 0.000166088805861402 1.58808604674653e-05 -2.91715052726778e-06 -1.91003154328514e-05 -9.21908999646099e-07 4.93845671362171e-06 1.58808604674653e-05 0.000122727148714624 461 461 0 0 0 453 453 0 0 0 0 0 0 0 0 0 0 0 150 0 486 458 0 0 563 +438 341 0.673720371712701 0.724618039560698 -0.145015714605384 0.19236736678305 -0.730000000444084 0.683097683044432 0.0218530265859457 -0.2534930109715 0.114894995935146 0.0911386425317985 0.989187994137881 0.571287484486592 4.91913503626309e-05 6.27948008720637e-06 -5.94652941124259e-06 2.26449347011307e-05 -3.17301986301691e-06 4.64050317302393e-05 6.27948008720637e-06 5.37399380023221e-05 -1.15601705228976e-07 9.09894270061559e-07 -5.28212387844901e-06 -2.147742242642e-06 -5.94652941124259e-06 -1.15601705228976e-07 1.65299129559301e-05 2.85645282851327e-06 -1.27988721268182e-06 -1.90532909811383e-06 2.26449347011307e-05 9.09894270061559e-07 2.85645282851327e-06 6.87459570701321e-05 -2.47733199927624e-05 4.77223705199132e-05 -3.17301986301691e-06 -5.28212387844901e-06 -1.27988721268182e-06 -2.47733199927624e-05 7.96227947343123e-05 -1.48129229760197e-05 4.64050317302393e-05 -2.147742242642e-06 -1.90532909811383e-06 4.77223705199132e-05 -1.48129229760197e-05 0.000191684421611458 523 523 0 2 0 522 522 0 2 0 0 0 0 0 0 0 0 0 75 0 609 596 0 0 549 +438 441 0.938628635735654 -0.342185377309117 -0.0434217886877291 -0.107715835946207 0.342629055231558 0.939466007481224 0.00299187205932058 0.202037604887873 0.039769519586675 -0.0176858232238766 0.9990523494636 -0.19750228471782 2.86370791363315e-05 -8.09980849737426e-06 -2.99265995883323e-06 8.95143985686739e-07 -1.02285642004215e-06 5.16811712555942e-06 -8.09980849737426e-06 3.75543934201266e-05 9.80027781409916e-07 -4.19748220956777e-06 -1.92713598789382e-06 -3.28579365660662e-06 -2.99265995883323e-06 9.80027781409916e-07 1.30492820058915e-05 1.94501629728676e-06 -1.83102388717996e-06 2.24435833955354e-07 8.95143985686739e-07 -4.19748220956777e-06 1.94501629728676e-06 4.20473180167987e-05 1.33889953993918e-05 -1.1670240677394e-05 -1.02285642004215e-06 -1.92713598789382e-06 -1.83102388717996e-06 1.33889953993918e-05 6.38189276141928e-05 -1.45078754204202e-05 5.16811712555942e-06 -3.28579365660662e-06 2.24435833955354e-07 -1.1670240677394e-05 -1.45078754204202e-05 6.3176648355878e-05 0 0 0 0 383 0 0 0 0 394 0 0 0 0 0 845 799 0 2086 0 0 0 0 0 2040 +438 434 0.967465623428073 0.247877346984269 -0.0506664419213676 0.0947290247868733 -0.25057811926049 0.96644151168106 -0.0565810096013004 -0.186371260349392 0.0349410021723254 0.067436083454389 0.997111579019884 0.392056425239398 3.51643852428239e-05 -2.07590201925433e-05 -3.58795591690151e-06 2.15273948843498e-06 1.04368285013174e-06 1.70250532289188e-05 -2.07590201925433e-05 5.26498097829121e-05 6.53908742508768e-06 2.78665493543786e-06 -6.11939698816964e-06 -8.74301606326867e-06 -3.58795591690151e-06 6.53908742508768e-06 1.1450446100662e-05 1.09723571718606e-06 7.8657121354423e-07 -1.69066166302285e-06 2.15273948843498e-06 2.78665493543786e-06 1.09723571718606e-06 2.8462963452387e-05 -1.39825937953508e-06 7.01968669329793e-06 1.04368285013174e-06 -6.11939698816964e-06 7.8657121354423e-07 -1.39825937953508e-06 6.45856199184942e-05 -1.5216226106495e-05 1.70250532289188e-05 -8.74301606326867e-06 -1.69066166302285e-06 7.01968669329793e-06 -1.5216226106495e-05 8.73431792732623e-05 922 922 0 0 0 916 916 0 0 0 0 0 0 0 0 0 0 0 1151 0 467 452 0 0 2174 +438 442 0.88925070661469 -0.456294115597305 -0.0320758609634542 -0.140045503097628 0.455985071540761 0.889828964117073 -0.0167937235389726 0.270770019095735 0.0362049073640749 0.000307716767570933 0.999344340051591 -0.216594802100829 2.5956614096632e-05 -3.35852629665186e-06 -1.44157803809245e-06 3.04848268624057e-06 -2.40085007965478e-06 -1.87430156874515e-06 -3.35852629665186e-06 4.63550314427244e-05 4.16245340258219e-06 -9.65284626807555e-06 -1.63475781515056e-05 1.52570106176873e-05 -1.44157803809245e-06 4.16245340258219e-06 1.31328260923771e-05 -1.45073599064797e-06 -2.37439477320718e-06 -1.65759369541725e-07 3.04848268624057e-06 -9.65284626807555e-06 -1.45073599064797e-06 4.76260711847383e-05 3.1035893063266e-05 -1.99257877137176e-06 -2.40085007965478e-06 -1.63475781515056e-05 -2.37439477320718e-06 3.1035893063266e-05 7.81419557606979e-05 -5.46921657625018e-06 -1.87430156874515e-06 1.52570106176873e-05 -1.65759369541725e-07 -1.99257877137176e-06 -5.46921657625018e-06 0.000129800922666362 0 0 0 0 330 0 0 0 0 344 0 0 0 0 0 1307 1317 0 1998 0 0 0 0 0 1636 +438 334 0.686466856005864 0.713805375225094 -0.138726860791948 0.162206080391654 -0.719166658073133 0.694661664690341 0.0156361608320558 -0.152853783286366 0.107529407704805 0.0890340266943388 0.990207235163047 0.48952958023103 3.50326804443596e-05 -5.99997994221548e-06 -6.98620906117561e-06 1.59148618534434e-05 -7.47748978708063e-06 1.90220769138913e-05 -5.99997994221548e-06 5.21274554217702e-05 -1.6547483414828e-06 5.25677673460837e-06 -8.53889627323381e-06 8.92220891584323e-06 -6.98620906117561e-06 -1.6547483414828e-06 1.63999550006389e-05 2.83799674186441e-06 -6.151355515811e-07 -3.20871887838469e-07 1.59148618534434e-05 5.25677673460837e-06 2.83799674186441e-06 0.000119770047664934 -8.39533516855515e-05 3.49173369315312e-05 -7.47748978708063e-06 -8.53889627323381e-06 -6.151355515811e-07 -8.39533516855515e-05 0.00013748330452779 1.94805556068445e-06 1.90220769138913e-05 8.92220891584323e-06 -3.20871887838469e-07 3.49173369315312e-05 1.94805556068445e-06 0.000146980469486282 511 511 0 0 0 503 503 0 0 0 0 0 0 0 0 0 0 0 217 0 858 841 0 0 549 +438 380 0.666784688638446 0.743368619839834 0.0529270633490149 0.161122538022647 -0.74430824454564 0.667830169467015 -0.00284637507112689 -0.226057131971828 -0.0374621955939341 -0.0374961302947116 0.998594324094727 0.61644830980455 4.45622428226196e-05 -1.54146145684819e-05 -3.23685759391383e-06 1.2522690717753e-05 -1.54382807095925e-05 3.1399867734531e-05 -1.54146145684819e-05 3.87671130150266e-05 3.88876392464736e-07 1.81789818152253e-05 -4.77752109890457e-06 6.42698908522728e-06 -3.23685759391383e-06 3.88876392464736e-07 1.23616351283307e-05 -2.17684127630633e-06 1.09751402549393e-06 -1.51648857380782e-06 1.2522690717753e-05 1.81789818152253e-05 -2.17684127630633e-06 0.000116716490205558 -7.45588040759272e-05 1.90573523511831e-05 -1.54382807095925e-05 -4.77752109890457e-06 1.09751402549393e-06 -7.45588040759272e-05 0.000108024332554692 -1.33630546112248e-05 3.1399867734531e-05 6.42698908522728e-06 -1.51648857380782e-06 1.90573523511831e-05 -1.33630546112248e-05 0.000107080458365089 447 447 0 6 0 445 445 0 6 0 0 0 0 0 0 0 0 0 107 0 764 757 0 0 697 +438 342 0.674335127994412 0.723733202396214 -0.146568710515171 0.208103948683762 -0.730135986216941 0.683156375760204 0.0140999251486442 -0.24660618637958 0.110333933056766 0.0975070151707174 0.989099997577961 0.588469345355404 4.21924594792176e-05 2.99309432116724e-05 -1.79642557612542e-06 3.31129983254613e-07 7.56677471004234e-06 -3.19545251247154e-06 2.99309432116724e-05 0.0002133263218621 1.50422421706456e-05 1.08173614071292e-05 1.32201817602228e-05 -7.00101649838561e-06 -1.79642557612542e-06 1.50422421706456e-05 1.70835015108103e-05 7.03503537601875e-07 6.57914030869315e-07 5.01905145066988e-07 3.31129983254613e-07 1.08173614071292e-05 7.03503537601875e-07 4.46242326370774e-05 1.13169357146839e-05 2.22635748947272e-05 7.56677471004234e-06 1.32201817602228e-05 6.57914030869315e-07 1.13169357146839e-05 5.06572880878861e-05 1.73227070642954e-05 -3.19545251247154e-06 -7.00101649838561e-06 5.01905145066988e-07 2.22635748947272e-05 1.73227070642954e-05 0.00016366230081736 312 312 0 2 0 312 312 0 2 0 0 0 0 0 0 0 0 0 56 0 471 458 0 0 463 +438 335 0.691263612519516 0.70878171795969 -0.140652388150996 0.166892010967868 -0.711872691830168 0.701392815090013 0.0358523300020748 -0.196762435934508 0.124064050526088 0.0753431830109148 0.989409680638331 0.510484544116794 3.84517837151652e-05 -1.31354478742162e-05 -5.57009166155321e-06 1.68254153463618e-06 8.51006718969848e-06 1.45359246451828e-05 -1.31354478742162e-05 4.53048161078254e-05 -2.06014792464114e-06 3.31988074088227e-06 -6.2345166572056e-06 7.16346937577559e-06 -5.57009166155321e-06 -2.06014792464114e-06 1.55316156201978e-05 3.00349085568178e-06 1.64220250630778e-06 -1.76739132174786e-06 1.68254153463618e-06 3.31988074088227e-06 3.00349085568178e-06 5.82421131511969e-05 -1.85850916281643e-05 1.13662739166592e-05 8.51006718969848e-06 -6.2345166572056e-06 1.64220250630778e-06 -1.85850916281643e-05 6.79441431647887e-05 7.47036520696318e-06 1.45359246451828e-05 7.16346937577559e-06 -1.76739132174786e-06 1.13662739166592e-05 7.47036520696318e-06 0.000106359237602902 549 548 0 0 0 541 540 0 0 0 0 0 0 0 0 0 0 0 180 0 619 599 0 0 532 +438 381 0.666784273153697 0.74327450388238 0.0542378553530527 0.164198811354093 -0.744247680258359 0.667895735701256 -0.00326751620172925 -0.226652536043077 -0.0386538937876534 -0.03818766961311 0.99852269798166 0.624519906440996 3.3503702632828e-05 -1.50115130995387e-05 -4.4282455971873e-06 5.5172257033233e-06 -4.40198056827933e-06 1.89408371691421e-05 -1.50115130995387e-05 3.35199497080029e-05 5.18008807016853e-06 5.29050608490959e-06 5.76968692814224e-06 6.38364042894538e-06 -4.4282455971873e-06 5.18008807016853e-06 1.09255925797587e-05 1.38798596759551e-06 6.26824159869108e-07 1.26108644052306e-08 5.5172257033233e-06 5.29050608490959e-06 1.38798596759551e-06 6.84196070092486e-05 -3.94614358910977e-05 9.82064322672735e-06 -4.40198056827933e-06 5.76968692814224e-06 6.26824159869108e-07 -3.94614358910977e-05 8.51218653319264e-05 3.22648040670582e-06 1.89408371691421e-05 6.38364042894538e-06 1.26108644052306e-08 9.82064322672735e-06 3.22648040670582e-06 7.64952387028856e-05 948 948 0 2 0 946 946 0 2 0 0 0 0 0 0 0 0 0 91 0 748 745 0 0 643 +438 340 0.68729863422036 0.710047826252566 -0.153142651906105 0.1895884275702 -0.717292145123528 0.696685547292966 0.0110103014122473 -0.236320352861692 0.114510112841253 0.102280656172644 0.98814275356852 0.580376852952798 3.6907445700563e-05 -1.11795162648313e-05 -7.99335104012738e-06 5.90754159697337e-06 3.88734840615266e-06 1.50198891344385e-05 -1.11795162648313e-05 6.27676932847012e-05 6.58265218024115e-07 -6.69262186722236e-06 -6.21179571734523e-06 -2.07114390516401e-05 -7.99335104012738e-06 6.58265218024115e-07 1.68064768660178e-05 1.91208755151589e-06 -5.54529721850802e-06 -1.35345571148713e-06 5.90754159697337e-06 -6.69262186722236e-06 1.91208755151589e-06 0.000102026257196383 -0.000100519002354598 -1.32952034502948e-05 3.88734840615266e-06 -6.21179571734523e-06 -5.54529721850802e-06 -0.000100519002354598 0.000201053375519322 3.73712304152127e-05 1.50198891344385e-05 -2.07114390516401e-05 -1.35345571148713e-06 -1.32952034502948e-05 3.73712304152127e-05 0.00010015732667554 483 483 0 1 0 480 480 0 1 0 0 0 0 0 0 0 0 0 83 0 571 548 0 0 539 +438 384 0.666811378574491 0.743208878799145 0.0548009842767875 0.166189218298407 -0.74417317445453 0.667974517881896 -0.00404102495868858 -0.224832523519271 -0.0396089866804868 -0.0380868210089327 0.998489119740209 0.615561774668993 3.91289502517474e-05 -1.35592302741371e-05 -4.04678327429515e-06 7.47124023411302e-06 -3.32608500882289e-06 2.88951567888754e-05 -1.35592302741371e-05 2.87093494559162e-05 2.3124351670513e-06 7.84405603363693e-06 -2.48668059786708e-06 -6.11043148277442e-06 -4.04678327429515e-06 2.3124351670513e-06 1.2537012874837e-05 -1.69156794833505e-06 1.71014641701495e-06 -3.38648162700725e-06 7.47124023411302e-06 7.84405603363693e-06 -1.69156794833505e-06 7.24513090638584e-05 -3.79227896692032e-05 -1.68276377803384e-05 -3.32608500882289e-06 -2.48668059786708e-06 1.71014641701495e-06 -3.79227896692032e-05 8.45338391424689e-05 1.92851743006273e-05 2.88951567888754e-05 -6.11043148277442e-06 -3.38648162700725e-06 -1.68276377803384e-05 1.92851743006273e-05 0.000104710829055611 386 386 0 8 0 382 382 0 8 0 0 0 0 0 0 0 0 0 105 0 867 860 0 0 675 +438 382 0.666859950348061 0.743221863379838 0.0540284037889582 0.161479096323506 -0.744194795222495 0.667955628029016 -0.00306361683502389 -0.226309823783316 -0.0383655233970671 -0.0381646535234325 0.998534699364977 0.612891865267208 3.99806033506092e-05 -1.35794335991731e-05 -2.93781249147256e-06 8.39449030422605e-06 -1.25741557426417e-05 2.1288899203236e-05 -1.35794335991731e-05 3.62117029443106e-05 1.57532810462718e-06 4.41881992053416e-06 1.14702347658133e-05 7.92144509306047e-06 -2.93781249147256e-06 1.57532810462718e-06 1.13073430814677e-05 3.01469728466164e-07 2.38336100014653e-06 -6.04219246191997e-07 8.39449030422605e-06 4.41881992053416e-06 3.01469728466164e-07 6.02617162836325e-05 -2.81023346521221e-05 1.15084715059571e-06 -1.25741557426417e-05 1.14702347658133e-05 2.38336100014653e-06 -2.81023346521221e-05 8.90052262319102e-05 1.06744389412326e-05 2.1288899203236e-05 7.92144509306047e-06 -6.04219246191997e-07 1.15084715059571e-06 1.06744389412326e-05 0.000100682239329632 466 465 0 5 0 461 460 0 5 0 0 0 0 0 0 0 0 0 103 0 738 732 0 0 728 +439 442 0.929830326278673 -0.367963275730944 0.00431184946978559 -0.104472851735897 0.367893418189133 0.929259760096763 -0.0336263455942194 0.209201688703081 0.00836643207184345 0.0328530969355889 0.999425173205142 -0.151607350537244 2.52880692916966e-05 -1.17738152072452e-05 -1.01169733731242e-06 1.39091402943412e-07 2.07768357012554e-06 -2.03621111453584e-06 -1.17738152072452e-05 4.67475956370569e-05 1.67629377188598e-06 -8.78248182877314e-06 -1.82991037671891e-05 7.64325186469612e-06 -1.01169733731242e-06 1.67629377188598e-06 1.19248073224182e-05 2.79143111744331e-06 -1.94430444233634e-07 7.112570341298e-07 1.39091402943412e-07 -8.78248182877314e-06 2.79143111744331e-06 4.76513593247322e-05 3.0148958028263e-05 -1.00542067576874e-05 2.07768357012554e-06 -1.82991037671891e-05 -1.94430444233634e-07 3.0148958028263e-05 7.15415917376015e-05 -2.07239168719939e-05 -2.03621111453584e-06 7.64325186469612e-06 7.112570341298e-07 -1.00542067576874e-05 -2.07239168719939e-05 0.00010701921709722 0 0 0 0 94 0 0 0 0 52 0 0 0 0 0 1307 1317 0 2517 0 0 0 0 0 1837 +438 385 0.667029151984465 0.743103772041529 0.0535620610183768 0.162775619344884 -0.744081252417934 0.668084568699312 -0.00246958822733476 -0.221673637308636 -0.0376191467612303 -0.0382072381036097 0.998561468690561 0.616263716058106 4.19335101222838e-05 -1.94207573186825e-05 -5.75487526845688e-06 -5.0303002884016e-07 4.43529160517604e-06 2.18412191038208e-05 -1.94207573186825e-05 4.02849122717967e-05 4.58300112292979e-06 1.25015199135352e-05 9.37755900967582e-07 -1.09602475810314e-05 -5.75487526845688e-06 4.58300112292979e-06 1.26268978279181e-05 -4.87576438962808e-07 4.08482763913826e-07 -5.64863786238726e-07 -5.0303002884016e-07 1.25015199135352e-05 -4.87576438962808e-07 4.2333204719999e-05 -4.36103801778121e-06 -8.4274718508226e-06 4.43529160517604e-06 9.37755900967582e-07 4.08482763913826e-07 -4.36103801778121e-06 5.07683150108432e-05 2.11139989290218e-05 2.18412191038208e-05 -1.09602475810314e-05 -5.64863786238726e-07 -8.4274718508226e-06 2.11139989290218e-05 0.00012086741808139 968 968 0 2 0 962 962 0 2 0 0 0 0 0 0 0 0 0 102 0 762 755 0 0 686 +439 331 0.641937676320825 0.766517964024388 -0.0191371509824746 0.166187997233487 -0.766573425502233 0.642130060921639 0.00584535495461287 -0.198494366410182 0.0167691095050527 0.0109176778061544 0.999799780594959 0.409029262365775 2.74033042318696e-05 -2.60343872458369e-06 -4.22740440509171e-06 -1.23294666816108e-06 1.70803994346612e-07 1.09488456913595e-06 -2.60343872458369e-06 6.98517987472726e-05 -1.25385036353007e-06 -3.84677772643891e-06 -4.50601221939875e-06 -1.08677006065892e-05 -4.22740440509171e-06 -1.25385036353007e-06 1.89172169288182e-05 9.78587853497199e-06 9.48999964042537e-08 -2.78814392425045e-06 -1.23294666816108e-06 -3.84677772643891e-06 9.78587853497199e-06 0.000129567644738179 -0.00010674234671881 -1.74694386384601e-05 1.70803994346612e-07 -4.50601221939875e-06 9.48999964042537e-08 -0.00010674234671881 0.000173583842786358 2.92695508451258e-05 1.09488456913595e-06 -1.08677006065892e-05 -2.78814392425045e-06 -1.74694386384601e-05 2.92695508451258e-05 9.8020080342788e-05 174 174 0 0 0 152 152 0 0 0 0 0 0 0 0 0 0 0 374 0 955 941 0 0 500 +439 337 0.661733374929868 0.744770080379959 -0.0861769567503758 0.2007749274745 -0.745021693540168 0.666085340454286 0.0356790608962361 -0.316834785310954 0.0839739046279596 0.0405936768811082 0.995640766912849 0.612466704703424 3.90312290012099e-05 -1.25933460321339e-05 -6.06341908474052e-06 2.56763998723111e-06 7.3204830641799e-06 2.00805596633252e-05 -1.25933460321339e-05 3.8167574112518e-05 1.74396970650621e-06 -6.33875959537112e-06 -5.97057732385784e-06 -1.3109700220286e-05 -6.06341908474052e-06 1.74396970650621e-06 1.51751274002809e-05 5.0423499323781e-06 -4.63250676576584e-06 -8.25231655471845e-06 2.56763998723111e-06 -6.33875959537112e-06 5.0423499323781e-06 6.18148566886191e-05 -3.70530431643037e-05 -7.59120201932392e-06 7.3204830641799e-06 -5.97057732385784e-06 -4.63250676576584e-06 -3.70530431643037e-05 0.00011658082781962 3.09252774071722e-05 2.00805596633252e-05 -1.3109700220286e-05 -8.25231655471845e-06 -7.59120201932392e-06 3.09252774071722e-05 0.000115441022792405 212 212 0 0 0 200 200 0 0 0 0 0 0 0 0 0 0 0 124 0 384 357 0 0 571 +439 441 0.968096278442941 -0.250557592297444 0.00323861189961075 -0.0766259770495323 0.250578453397185 0.968005592422676 -0.0132518576621765 0.141200540617675 0.00018535911879354 0.0136406004461668 0.999906945501163 -0.117605409831743 2.14032882128034e-05 -9.50006996662298e-06 -1.16969061477159e-06 -1.65950386625594e-06 -7.81739825101027e-07 1.98994853534604e-06 -9.50006996662298e-06 2.67008356267241e-05 -9.00160394217244e-07 -7.71557209981715e-07 -3.7141964060308e-06 1.72556403040653e-06 -1.16969061477159e-06 -9.00160394217244e-07 1.1132197840793e-05 3.71545094091562e-06 -9.63545939193167e-07 -2.53024291470655e-06 -1.65950386625594e-06 -7.71557209981715e-07 3.71545094091562e-06 3.86557279001501e-05 1.79688889873841e-05 -1.62847594030596e-06 -7.81739825101027e-07 -3.7141964060308e-06 -9.63545939193167e-07 1.79688889873841e-05 6.26954575500738e-05 -9.62512599801359e-06 1.98994853534604e-06 1.72556403040653e-06 -2.53024291470655e-06 -1.62847594030596e-06 -9.62512599801359e-06 7.09918541992907e-05 0 0 0 0 196 0 0 0 0 173 0 0 0 0 0 845 799 0 2529 0 0 0 0 0 2347 +439 336 0.640396510931167 0.76292043846616 -0.0885703864606491 0.193823518692152 -0.763586410652813 0.644838721050467 0.0334487264384016 -0.300018947956618 0.0826323317687506 0.0462106957813761 0.995508146296082 0.574136250489602 2.93929551048173e-05 -8.39310441914216e-06 -5.04782057525182e-06 3.34594238655269e-06 7.31668478671369e-07 6.30798580884433e-06 -8.39310441914216e-06 5.57290909076579e-05 3.8111478588262e-06 -1.80169019045264e-06 1.26735673347773e-05 1.27782041384868e-06 -5.04782057525182e-06 3.8111478588262e-06 1.56629777563436e-05 4.62300409232185e-06 1.06332580783944e-06 -5.79524839660471e-06 3.34594238655269e-06 -1.80169019045264e-06 4.62300409232185e-06 6.61300466906013e-05 -4.33618860770867e-05 3.75401982041306e-06 7.31668478671369e-07 1.26735673347773e-05 1.06332580783944e-06 -4.33618860770867e-05 9.53388970154268e-05 2.93435777023421e-05 6.30798580884433e-06 1.27782041384868e-06 -5.79524839660471e-06 3.75401982041306e-06 2.93435777023421e-05 0.000117426556375749 336 336 0 0 0 306 306 0 0 0 0 0 0 0 0 0 0 0 127 0 706 687 0 0 528 +439 340 0.618754816510884 0.778386756223528 -0.106096817956039 0.217138466549503 -0.782549614181091 0.622576855970661 0.00376294495209729 -0.318972053588621 0.068982449866673 0.0806976836439643 0.994348684046442 0.640834248320208 4.36256969726047e-05 -9.21316341143373e-06 -7.73136978594923e-06 2.06088973281355e-06 1.45808469762678e-05 2.28858485191263e-05 -9.21316341143373e-06 4.08026821191205e-05 -6.17735830182097e-07 -1.0900271448843e-05 -1.44025863952168e-06 -6.30024107956076e-06 -7.73136978594923e-06 -6.17735830182097e-07 1.43516990308354e-05 1.46906742812039e-06 -1.7657433577589e-06 -3.56161991347888e-06 2.06088973281355e-06 -1.0900271448843e-05 1.46906742812039e-06 5.26687084319376e-05 -2.44723708104668e-05 1.71134915458072e-06 1.45808469762678e-05 -1.44025863952168e-06 -1.7657433577589e-06 -2.44723708104668e-05 7.7521864798875e-05 2.25561952646676e-05 2.28858485191263e-05 -6.30024107956076e-06 -3.56161991347888e-06 1.71134915458072e-06 2.25561952646676e-05 9.90197115297003e-05 318 318 0 0 0 292 292 0 0 0 0 0 0 0 0 0 0 0 64 0 612 604 0 0 466 +439 333 0.619057263431736 0.781214478769503 -0.0804490071617091 0.189749951826672 -0.784272650570256 0.620312633866828 -0.0113422146295902 -0.2176563652239 0.0410428332345039 0.0701154364323087 0.99669419152215 0.528796739518798 3.75765442780414e-05 -9.96671618624111e-06 -2.32852112461357e-06 1.11905214001875e-05 -1.77174243067532e-06 1.12132386695154e-05 -9.96671618624111e-06 5.58385376324818e-05 3.90690801980154e-06 1.2663503469316e-05 -2.58804924005712e-05 -1.3230887147805e-05 -2.32852112461357e-06 3.90690801980154e-06 1.82729361488457e-05 1.39526436781786e-05 -1.0568592917398e-05 5.69015591678953e-07 1.11905214001875e-05 1.2663503469316e-05 1.39526436781786e-05 0.000181783926437392 -0.000174903838711062 3.28690414505639e-05 -1.77174243067532e-06 -2.58804924005712e-05 -1.0568592917398e-05 -0.000174903838711062 0.00024196915452018 -2.02193918294734e-05 1.12132386695154e-05 -1.3230887147805e-05 5.69015591678953e-07 3.28690414505639e-05 -2.02193918294734e-05 0.000103103713593195 325 325 0 0 0 315 315 0 0 0 0 0 0 0 0 0 0 0 185 0 697 691 0 0 413 +439 335 0.624665482104715 0.775980710295809 -0.0874469708777654 0.191538646589513 -0.777103550350068 0.62874255468366 0.0281579822285558 -0.290413674481457 0.0768316829192453 0.0503660319925737 0.995771136015259 0.57243159567836 2.75815573587466e-05 -1.43309252224725e-05 -1.11257155193937e-06 2.6287434174776e-06 -3.58633251349462e-06 1.27534102393075e-05 -1.43309252224725e-05 4.32956614828437e-05 -3.44698363329219e-06 2.02107182091982e-06 -2.44642466727743e-06 -9.80791438324338e-07 -1.11257155193937e-06 -3.44698363329219e-06 1.55687307313704e-05 3.58835911948548e-06 4.04074800427463e-07 -4.13780384016851e-06 2.6287434174776e-06 2.02107182091982e-06 3.58835911948548e-06 5.9524956193866e-05 -1.36168440385274e-05 4.67274396149545e-06 -3.58633251349462e-06 -2.44642466727743e-06 4.04074800427463e-07 -1.36168440385274e-05 6.64278192011028e-05 2.05064392259388e-06 1.27534102393075e-05 -9.80791438324338e-07 -4.13780384016851e-06 4.67274396149545e-06 2.05064392259388e-06 0.000103756827679377 294 294 0 0 0 266 266 0 0 0 0 0 0 0 0 0 0 0 132 0 732 721 0 0 475 +439 334 0.619049305131881 0.780395142208986 -0.0880986937040093 0.185379938202877 -0.783102194645562 0.621864871410735 0.00591899033735094 -0.284705382463386 0.0594046341377481 0.0653261335295974 0.996094165087334 0.551575422506188 4.21183039866561e-05 -1.96701901557748e-05 -8.59922922838428e-06 3.90613858576505e-06 9.52357057603565e-06 1.73085534715936e-05 -1.96701901557748e-05 7.63875666641473e-05 3.70430387793456e-06 -7.83524495975725e-06 -6.42110109488992e-06 -1.07658784277123e-05 -8.59922922838428e-06 3.70430387793456e-06 1.85810930759898e-05 3.98867149265041e-06 6.55549144479042e-07 -8.38119726701584e-06 3.90613858576505e-06 -7.83524495975725e-06 3.98867149265041e-06 6.2293820544365e-05 -2.77062321584515e-05 -5.04923053311298e-06 9.52357057603565e-06 -6.42110109488992e-06 6.55549144479042e-07 -2.77062321584515e-05 7.87071299641283e-05 4.48601156387207e-05 1.73085534715936e-05 -1.07658784277123e-05 -8.38119726701584e-06 -5.04923053311298e-06 4.48601156387207e-05 0.00015390215769089 310 310 0 0 0 282 282 0 0 0 0 0 0 0 0 0 0 0 142 0 903 893 0 0 404 +440 442 0.966674572877602 -0.255961957703365 0.00487302376017431 -0.0534334671732672 0.255978135395318 0.966093019512119 -0.0337560638921874 0.141943356245541 0.00393247395958307 0.0338785161808758 0.999418221661952 -0.0752109669648058 2.58302908483458e-05 -7.61850095130292e-07 -6.82139902864208e-07 2.11466928626179e-06 -6.76700752935617e-07 -1.15810103274635e-05 -7.61850095130292e-07 5.02272849508287e-05 1.55975447854744e-06 2.53262119057179e-07 -6.80297820732646e-06 -1.36903190452471e-06 -6.82139902864208e-07 1.55975447854744e-06 1.08233628816656e-05 1.5994652807693e-06 1.50445277213023e-06 -6.08179033618933e-07 2.11466928626179e-06 2.53262119057179e-07 1.5994652807693e-06 4.59699270641782e-05 3.45862670459301e-05 -4.27580968035707e-06 -6.76700752935617e-07 -6.80297820732646e-06 1.50445277213023e-06 3.45862670459301e-05 6.72492413339746e-05 -1.44433011191e-05 -1.15810103274635e-05 -1.36903190452471e-06 -6.08179033618933e-07 -4.27580968035707e-06 -1.44433011191e-05 0.000102189351850472 378 378 0 0 0 186 186 0 0 0 0 0 0 0 0 596 599 0 2892 0 0 0 0 0 1978 +439 339 0.644857756823208 0.755140138850688 -0.117990864737501 0.204241558495552 -0.759222581761115 0.650661965765522 0.0148350143287309 -0.324354089189945 0.0879746827725258 0.0800148548877663 0.9929038615034 0.627839644604893 3.72925167909773e-05 -4.48064666090759e-06 -4.54089345943821e-06 7.2073016715601e-06 8.93433890773651e-07 1.91788150498187e-05 -4.48064666090759e-06 5.01742759222574e-05 4.14550911159491e-06 -4.58756531815409e-06 1.42622669898229e-05 2.35368088523634e-05 -4.54089345943821e-06 4.14550911159491e-06 1.27438359774753e-05 -2.17903426066613e-06 1.27263352083904e-06 1.13037803119633e-06 7.2073016715601e-06 -4.58756531815409e-06 -2.17903426066613e-06 6.29233099133284e-05 -4.33546134355573e-05 1.99634771883449e-05 8.93433890773651e-07 1.42622669898229e-05 1.27263352083904e-06 -4.33546134355573e-05 0.000118338747110747 4.43763098480924e-05 1.91788150498187e-05 2.35368088523634e-05 1.13037803119633e-06 1.99634771883449e-05 4.43763098480924e-05 0.000195467446752627 208 208 0 0 0 197 197 0 0 0 0 0 0 0 0 0 0 0 96 0 541 516 0 0 532 +439 338 0.659406370003031 0.743416162765728 -0.111873357588417 0.19882024940652 -0.746100675282117 0.665400216951875 0.0240069494931574 -0.327251360997841 0.0922877106823812 0.0676384522226669 0.993432442714615 0.611067667278557 4.30383128231629e-05 -9.0441271164365e-06 -7.48365125422021e-06 1.56300257744936e-07 1.79895523805976e-05 4.02864381699602e-05 -9.0441271164365e-06 8.15693393220292e-05 4.36916711432781e-06 -1.61596880660824e-05 3.32567182875518e-05 3.11621726924588e-05 -7.48365125422021e-06 4.36916711432781e-06 1.64072861119808e-05 2.456310180016e-06 5.19000760248652e-07 -3.81042179455057e-06 1.56300257744936e-07 -1.61596880660824e-05 2.456310180016e-06 6.4701656353705e-05 -4.7077366540697e-05 1.42762465864749e-05 1.79895523805976e-05 3.32567182875518e-05 5.19000760248652e-07 -4.7077366540697e-05 0.00014125191461698 8.41623466306133e-05 4.02864381699602e-05 3.11621726924588e-05 -3.81042179455057e-06 1.42762465864749e-05 8.41623466306133e-05 0.000266233098718483 266 266 0 0 0 249 249 0 0 0 0 0 0 0 0 0 0 0 108 0 560 532 0 0 578 +439 341 0.604009037866619 0.790845036220539 -0.0986773067162636 0.217584405246543 -0.793872155838151 0.607945333790615 0.0130181145756341 -0.335358049999449 0.0702857194622683 0.0704741073554765 0.99503432997667 0.645181154398154 3.94214550748997e-05 -1.13740404939964e-05 -8.10227965502534e-06 1.07207557145084e-05 1.26873879333113e-05 4.53533853880116e-05 -1.13740404939964e-05 5.70186358995745e-05 4.5613540852879e-06 2.97389341036395e-06 -1.23325759972551e-05 -3.43704317926981e-06 -8.10227965502534e-06 4.5613540852879e-06 1.62131177653502e-05 -7.1747615745799e-07 -3.14591107639222e-06 -1.1270075594936e-05 1.07207557145084e-05 2.97389341036395e-06 -7.1747615745799e-07 5.60489920558914e-05 -8.23385469308241e-06 1.9364524848337e-05 1.26873879333113e-05 -1.23325759972551e-05 -3.14591107639222e-06 -8.23385469308241e-06 6.35091712384626e-05 3.68098394176886e-05 4.53533853880116e-05 -3.43704317926981e-06 -1.1270075594936e-05 1.9364524848337e-05 3.68098394176886e-05 0.000186136514582191 217 217 0 0 0 190 190 0 0 0 0 0 0 0 0 0 0 0 69 0 627 620 0 0 449 +440 444 0.891685590123451 -0.448352430617079 0.0622648080857177 -0.092889635512794 0.452256620650407 0.888203379414916 -0.080985837489009 0.340987162401415 -0.0189936158765987 0.100373575983322 0.994768509654509 -0.151069939349443 2.92280607771784e-05 -2.10959859526279e-05 -1.61944259096586e-06 3.6499342653366e-06 1.01015503900886e-05 -1.51404387855357e-05 -2.10959859526279e-05 7.63884765123239e-05 1.5671966342206e-06 7.61637995906835e-06 9.04583810091844e-06 6.19937862682373e-05 -1.61944259096586e-06 1.5671966342206e-06 2.11895222040485e-05 9.51180647621249e-06 -1.6752171619773e-05 -1.0221218642544e-05 3.6499342653366e-06 7.61637995906835e-06 9.51180647621249e-06 0.000114912266151688 3.65384439296119e-05 -2.29958029845965e-05 1.01015503900886e-05 9.04583810091844e-06 -1.6752171619773e-05 3.65384439296119e-05 0.000114108520072825 -1.06324618752271e-05 -1.51404387855357e-05 6.19937862682373e-05 -1.0221218642544e-05 -2.29958029845965e-05 -1.06324618752271e-05 0.000234595582004868 297 297 0 0 0 46 46 0 0 0 0 0 0 0 0 1114 1125 0 2836 0 0 0 0 0 1439 +440 333 0.523730650520299 0.848961211739526 -0.0705057917290465 0.178210579166149 -0.851277043683022 0.52468547030414 -0.00570544915127684 -0.371844957924637 0.0321496594675343 0.0630080805411423 0.997495053212116 0.599129606964055 2.67197270030013e-05 -9.70841363298747e-06 -2.10962570741511e-06 1.00378597163416e-06 1.20919605434083e-06 6.65574539596144e-07 -9.70841363298747e-06 4.57617037460746e-05 -7.96123685659533e-07 4.92658818738914e-06 -1.02489128064238e-05 -5.43050293991246e-06 -2.10962570741511e-06 -7.96123685659533e-07 1.63465714776294e-05 6.86456890142304e-06 1.95406308442836e-06 1.13017330491121e-06 1.00378597163416e-06 4.92658818738914e-06 6.86456890142304e-06 9.44569216185638e-05 -3.60276541397573e-05 1.90652608650742e-06 1.20919605434083e-06 -1.02489128064238e-05 1.95406308442836e-06 -3.60276541397573e-05 8.53696242736654e-05 1.34731307432206e-05 6.65574539596144e-07 -5.43050293991246e-06 1.13017330491121e-06 1.90652608650742e-06 1.34731307432206e-05 9.62463525386812e-05 106 106 0 27 0 81 81 0 19 0 0 0 0 0 0 0 0 0 123 0 1080 1073 0 0 402 +440 337 0.570903995738445 0.817487923977153 -0.0760402643433278 0.186026166080725 -0.816946405251512 0.574842974764657 0.0464125555249069 -0.430228616887259 0.0816529154195399 0.0356237072080546 0.996023972044973 0.675883705693279 3.28222168805179e-05 8.6423042038258e-06 -2.75634603924921e-06 7.52923185895942e-06 5.9617007694408e-06 8.50406218335122e-06 8.6423042038258e-06 7.03002052846339e-05 5.17416312941523e-06 -1.05636445136019e-05 6.47166427777866e-06 -1.64538479987448e-05 -2.75634603924921e-06 5.17416312941523e-06 1.78199453341001e-05 4.47769608033081e-06 5.25135142094997e-06 -5.24072695561914e-06 7.52923185895942e-06 -1.05636445136019e-05 4.47769608033081e-06 7.37197536493516e-05 -3.9582813316117e-05 1.11777554637041e-05 5.9617007694408e-06 6.47166427777866e-06 5.25135142094997e-06 -3.9582813316117e-05 0.000100632346517369 1.81402815875788e-05 8.50406218335122e-06 -1.64538479987448e-05 -5.24072695561914e-06 1.11777554637041e-05 1.81402815875788e-05 9.32167318048293e-05 59 59 0 6 0 50 50 0 5 0 0 0 0 0 0 0 0 0 115 0 593 568 0 0 530 +440 332 0.541854027229515 0.83984453502544 -0.0324864612270801 0.160635121660496 -0.84007754198096 0.54237959246081 0.00970057427547999 -0.343409312154938 0.0257669678927078 0.0220348512576973 0.999425099092307 0.534081627356764 2.32711269567206e-05 -5.57235560854557e-06 -1.18099696463097e-06 1.40544680138955e-06 4.56837368267973e-06 1.98029882188378e-06 -5.57235560854557e-06 5.35650679020007e-05 -4.98582498358473e-06 -6.66807639080102e-06 4.09628028079104e-06 1.20938192622303e-07 -1.18099696463097e-06 -4.98582498358473e-06 1.91409518044332e-05 3.30965056111076e-06 -2.90149187211382e-07 -1.11586921888038e-06 1.40544680138955e-06 -6.66807639080102e-06 3.30965056111076e-06 8.44148440489212e-05 -3.98570853108619e-05 1.75146009405592e-06 4.56837368267973e-06 4.09628028079104e-06 -2.90149187211382e-07 -3.98570853108619e-05 0.000107902527974567 1.45999384161739e-05 1.98029882188378e-06 1.20938192622303e-07 -1.11586921888038e-06 1.75146009405592e-06 1.45999384161739e-05 8.65281327154696e-05 175 175 0 98 0 148 148 0 71 0 0 0 0 0 0 0 0 0 188 0 789 780 0 0 455 +440 335 0.530618057893961 0.84452501735476 -0.0722632112404589 0.185326108740602 -0.844898866879118 0.533809201743878 0.0345491082366388 -0.406459314451412 0.0677523533408575 0.0427227245796165 0.996787032129366 0.644417378464727 3.6375773436315e-05 -1.83965462144667e-05 -8.39485767915362e-06 -6.72484156832769e-07 8.95718696765236e-06 2.17858490342614e-05 -1.83965462144667e-05 5.53857075619283e-05 7.17223077798146e-07 -1.51814261879573e-06 -1.65366447507843e-05 -1.85253818786663e-05 -8.39485767915362e-06 7.17223077798146e-07 1.99241777374992e-05 4.77442759294278e-06 5.5035547743251e-07 -9.58554700337441e-06 -6.72484156832769e-07 -1.51814261879573e-06 4.77442759294278e-06 4.45236480475111e-05 -7.71812673633176e-06 1.18790024742888e-07 8.95718696765236e-06 -1.65366447507843e-05 5.5035547743251e-07 -7.71812673633176e-06 6.49309615412865e-05 3.09652751530762e-05 2.17858490342614e-05 -1.85253818786663e-05 -9.58554700337441e-06 1.18790024742888e-07 3.09652751530762e-05 0.000159512686200082 109 109 0 10 0 91 91 0 7 0 0 0 0 0 0 0 0 0 107 0 967 959 0 0 395 +440 331 0.548791481386577 0.83588620096814 -0.0110530081234143 0.162270623441299 -0.835872044251956 0.54887725274336 0.00718937124915709 -0.327568542877494 0.0120762409541372 0.00529343479718879 0.999913068197664 0.472278911088603 2.73467219763232e-05 -7.27353048998232e-06 -4.02127894192529e-06 7.74923139775035e-06 -2.23864674977222e-06 2.52622796860728e-06 -7.27353048998232e-06 6.56503049731588e-05 1.62827953951781e-06 1.46945734551796e-05 -1.31687161099008e-05 -3.9042435176174e-06 -4.02127894192529e-06 1.62827953951781e-06 1.62901825099308e-05 6.20986558592243e-07 3.51617942149488e-07 5.87053853025393e-07 7.74923139775035e-06 1.46945734551796e-05 6.20986558592243e-07 7.79314303585136e-05 -6.1201444655511e-05 -1.24296017632736e-05 -2.23864674977222e-06 -1.31687161099008e-05 3.51617942149488e-07 -6.1201444655511e-05 0.000130935039261068 4.62809200258706e-05 2.52622796860728e-06 -3.9042435176174e-06 5.87053853025393e-07 -1.24296017632736e-05 4.62809200258706e-05 0.000127929297375906 180 180 0 134 0 147 147 0 94 0 0 0 0 0 0 0 0 0 198 0 1176 1167 0 0 475 +441 443 0.971603443029648 -0.234238064071775 0.0334556248311318 -0.0334099675060578 0.235711091059205 0.970515638131249 -0.0503952149948191 0.153700565559482 -0.0206647294831982 0.056850026232199 0.998168845172391 -0.06535243334646 4.85008940367733e-05 -1.30844516461294e-05 -3.2398241474082e-06 -4.78552745634043e-06 -7.28286839947264e-06 -7.19977266865247e-05 -1.30844516461294e-05 4.50164221536653e-05 5.71727464367245e-06 3.70923156752853e-06 -2.75861560629137e-07 -1.57784232013082e-05 -3.2398241474082e-06 5.71727464367245e-06 1.56425240228562e-05 4.16347835924895e-06 -5.68118150522513e-06 2.72303542495267e-06 -4.78552745634043e-06 3.70923156752853e-06 4.16347835924895e-06 6.84620413799066e-05 3.83183791604818e-05 2.88627647060462e-05 -7.28286839947264e-06 -2.75861560629137e-07 -5.68118150522513e-06 3.83183791604818e-05 8.24165982969066e-05 2.72738936322472e-05 -7.19977266865247e-05 -1.57784232013082e-05 2.72303542495267e-06 2.88627647060462e-05 2.72738936322472e-05 0.000398783926900815 994 994 0 0 0 930 930 0 0 0 0 0 0 0 0 618 650 0 3087 0 0 0 0 0 1235 +440 336 0.546555667904284 0.833949695629781 -0.0761892842904869 0.179325403375939 -0.833909414191166 0.55033062728401 0.04160876826506 -0.426662317892842 0.0766289162460802 0.0407934533005396 0.996224825710928 0.648219125893221 5.03035972537388e-05 -9.31633561983622e-06 -7.37193853520197e-06 4.06018874433417e-06 1.15347862345606e-05 3.46020750392759e-05 -9.31633561983622e-06 5.67993241113565e-05 2.50022896726876e-06 -1.05608701457891e-05 1.16637109785783e-05 2.12664776090566e-05 -7.37193853520197e-06 2.50022896726876e-06 1.70578662131281e-05 -2.21311267775617e-06 -5.92267214583317e-06 -5.36291973499386e-06 4.06018874433417e-06 -1.05608701457891e-05 -2.21311267775617e-06 5.18769091529929e-05 -5.82655534272592e-06 1.28294647038356e-05 1.15347862345606e-05 1.16637109785783e-05 -5.92267214583317e-06 -5.82655534272592e-06 8.12896919873296e-05 5.7110889768486e-05 3.46020750392759e-05 2.12664776090566e-05 -5.36291973499386e-06 1.28294647038356e-05 5.7110889768486e-05 0.000197601464778825 145 145 0 14 0 123 123 0 11 0 0 0 0 0 0 0 0 0 110 0 907 890 0 0 445 +441 330 0.468389927336714 0.883459116334954 0.0105292798505003 0.1199722832118 -0.881815597318074 0.46671188376842 0.0676850786798803 -0.383343387299742 0.054882859765837 -0.040987892285347 0.997651173702476 0.437093360649022 4.67138688906061e-05 -1.3228703476744e-05 -4.10241272968544e-06 5.48077894578244e-06 3.39570331916597e-06 1.21807543807281e-05 -1.3228703476744e-05 6.10197379364746e-05 3.59029152097118e-06 -1.0258702070281e-05 5.89049381482207e-06 -3.41798014095662e-05 -4.10241272968544e-06 3.59029152097118e-06 1.80146021978055e-05 3.25363977435025e-06 1.7017490758868e-06 -9.2396805705594e-06 5.48077894578244e-06 -1.0258702070281e-05 3.25363977435025e-06 5.86745577352509e-05 -2.24429946218436e-05 4.00549567689076e-06 3.39570331916597e-06 5.89049381482207e-06 1.7017490758868e-06 -2.24429946218436e-05 7.29658812691831e-05 3.18077497250335e-05 1.21807543807281e-05 -3.41798014095662e-05 -9.2396805705594e-06 4.00549567689076e-06 3.18077497250335e-05 0.000189044243447309 0 0 0 329 0 0 0 0 312 0 0 0 0 0 0 0 0 0 262 0 1037 1016 0 0 393 +442 446 0.936566710959386 -0.349433576093373 0.0271840361483359 0.00788484842735152 0.350391863751502 0.935315043263963 -0.0491051082972101 0.351797836685522 -0.00826666434942346 0.0555152748595262 0.998423615765275 -0.0590548381194692 2.66024047641902e-05 -1.49929319535779e-05 1.26095341781486e-06 -1.19104004905466e-06 -3.52308574864492e-06 1.69184163295761e-05 -1.49929319535779e-05 7.94229462562056e-05 1.83632673938821e-06 1.39835584419201e-05 4.43857699792966e-06 4.8882104111152e-05 1.26095341781486e-06 1.83632673938821e-06 1.39024348217338e-05 1.48598554945186e-06 -1.87937670327463e-06 -3.25803592581208e-06 -1.19104004905466e-06 1.39835584419201e-05 1.48598554945186e-06 7.06769285587799e-05 3.22997903384269e-05 2.58314648934762e-06 -3.52308574864492e-06 4.43857699792966e-06 -1.87937670327463e-06 3.22997903384269e-05 5.29922155380375e-05 2.17355246353852e-06 1.69184163295761e-05 4.8882104111152e-05 -3.25803592581208e-06 2.58314648934762e-06 2.17355246353852e-06 0.000187342210586352 1985 1985 0 0 0 1997 1997 0 0 0 0 0 0 0 0 756 789 0 3455 0 0 0 0 0 1281 +441 444 0.944487263598907 -0.325033413801278 0.0479279543913163 -0.0382258671971212 0.327848417705427 0.941908878423166 -0.0729594391128487 0.252494284319677 -0.0214295102019657 0.0846223650124565 0.996182629557554 -0.107330159160384 3.9701375067728e-05 -1.57628522364819e-05 -2.0213980466163e-06 7.55735558993361e-06 1.2137105399071e-05 -3.12171652907502e-05 -1.57628522364819e-05 5.77379194110712e-05 8.42042591015643e-06 1.53166304049115e-05 -5.65173177536353e-06 2.37794497341375e-05 -2.0213980466163e-06 8.42042591015643e-06 1.99733707334227e-05 1.20343188490977e-05 -1.00026871309145e-05 3.43668917963595e-07 7.55735558993361e-06 1.53166304049115e-05 1.20343188490977e-05 0.000118218908054873 3.32197670137294e-05 -1.81377749662624e-06 1.2137105399071e-05 -5.65173177536353e-06 -1.00026871309145e-05 3.32197670137294e-05 8.22509067457863e-05 -3.07275432910772e-05 -3.12171652907502e-05 2.37794497341375e-05 3.43668917963595e-07 -1.81377749662624e-06 -3.07275432910772e-05 0.000318434096940616 1071 1071 0 0 0 993 993 0 0 0 0 0 0 0 0 851 870 0 3063 0 0 0 0 0 1273 +441 331 0.430607617309406 0.902279974498346 -0.0216316327257015 0.123955294199106 -0.901821388586543 0.431097258396636 0.029552273867559 -0.417186824970001 0.0359897624742822 0.00678243482590165 0.999329142762722 0.523367600559777 4.22981253284286e-05 -2.77742759437962e-05 -5.11111004426658e-06 8.63540721196275e-06 7.28942277898542e-06 1.31351911668908e-05 -2.77742759437962e-05 7.70155990161999e-05 3.41808836298215e-06 -7.65404363163691e-06 -6.93051974610222e-06 -1.00637776177466e-05 -5.11111004426658e-06 3.41808836298215e-06 1.85785769832951e-05 6.96679130625989e-06 -1.50840576319769e-06 -7.59546656878244e-06 8.63540721196275e-06 -7.65404363163691e-06 6.96679130625989e-06 5.90617292582136e-05 -1.77301346091226e-05 -1.32439254341665e-05 7.28942277898542e-06 -6.93051974610222e-06 -1.50840576319769e-06 -1.77301346091226e-05 7.40234628732383e-05 3.91096983460113e-05 1.31351911668908e-05 -1.00637776177466e-05 -7.59546656878244e-06 -1.32439254341665e-05 3.91096983460113e-05 0.000128031982061099 0 0 0 174 0 0 0 0 164 0 0 0 0 0 0 0 0 0 149 0 1211 1204 0 0 384 +442 445 0.960428438526518 -0.27819998796676 0.013490039466535 0.0020483918966319 0.278525235628859 0.959130013629432 -0.0499330559158395 0.263312236914942 0.00095267381753085 0.0517144433451664 0.998661458534421 -0.0770110382235161 0.000117905092077456 1.32704305326652e-05 -1.0596758091083e-05 3.03719617167956e-06 2.04489203607026e-05 -0.000118125419858058 1.32704305326652e-05 0.000103236178823558 -1.0174878698573e-05 6.50944987939412e-06 3.42933329331937e-05 -7.55663359141951e-05 -1.0596758091083e-05 -1.0174878698573e-05 2.19857141451791e-05 1.29540444316163e-05 -1.01298298759604e-05 2.06059552753643e-05 3.03719617167956e-06 6.50944987939412e-06 1.29540444316163e-05 9.19607601104012e-05 1.68461243499553e-05 8.85406065056771e-06 2.04489203607026e-05 3.42933329331937e-05 -1.01298298759604e-05 1.68461243499553e-05 6.7887751486938e-05 -4.79508459145281e-05 -0.000118125419858058 -7.55663359141951e-05 2.06059552753643e-05 8.85406065056771e-06 -4.79508459145281e-05 0.000388272146631425 1775 1775 0 0 0 1797 1797 0 0 0 0 0 0 0 0 522 540 0 3403 0 0 0 0 0 913 +443 445 0.985794499005009 -0.165972922400121 -0.0257331451910974 0.010299207312204 0.165900065980231 0.986130117881648 -0.00495567497736239 0.16577708704604 0.0261987373592205 0.000616146646458675 0.999656564288002 -0.026448062670133 3.97805182673672e-05 -8.28640597097274e-06 -7.08053664200453e-06 -1.27881588019786e-05 4.37613355167107e-06 -2.72993344752672e-05 -8.28640597097274e-06 4.72965356286244e-05 -4.18258140211812e-06 -1.73575879162894e-05 1.18731840082472e-05 -5.18905592285793e-06 -7.08053664200453e-06 -4.18258140211812e-06 2.06559786427404e-05 1.60823906527391e-05 -7.61419211248438e-06 6.35842031907617e-06 -1.27881588019786e-05 -1.73575879162894e-05 1.60823906527391e-05 7.90364507590933e-05 -7.28835914017271e-06 1.97686188882111e-05 4.37613355167107e-06 1.18731840082472e-05 -7.61419211248438e-06 -7.28835914017271e-06 4.72863885907438e-05 5.32592263571277e-07 -2.72993344752672e-05 -5.18905592285793e-06 6.35842031907617e-06 1.97686188882111e-05 5.32592263571277e-07 0.000207913537283095 2109 2109 0 0 0 2137 2137 0 0 0 0 0 0 0 0 286 331 0 3649 0 0 0 0 0 1133 +443 446 0.970326048129257 -0.241477691243322 -0.0124853896075721 0.0412441213232944 0.241301338212369 0.970347501839641 -0.0141205471029516 0.2574605852254 0.0155249637287155 0.0106887934474201 0.999822346817604 -0.0455243895562421 5.37024155066878e-05 -2.70896563417775e-05 1.30682890655523e-06 3.60455751192206e-06 -6.06918161224154e-06 2.73246654054223e-05 -2.70896563417775e-05 0.000105721652763397 5.30204715029422e-06 -3.37894218469385e-06 -4.89809999026455e-06 7.01682660566126e-05 1.30682890655523e-06 5.30204715029422e-06 1.85495705884478e-05 2.34040248708481e-06 -1.13141033054742e-05 3.14908761342959e-06 3.60455751192206e-06 -3.37894218469385e-06 2.34040248708481e-06 7.31688693306935e-05 2.28709168776719e-05 -2.28885919098786e-05 -6.06918161224154e-06 -4.89809999026455e-06 -1.13141033054742e-05 2.28709168776719e-05 6.62159751626024e-05 -2.878819458458e-05 2.73246654054223e-05 7.01682660566126e-05 3.14908761342959e-06 -2.28885919098786e-05 -2.878819458458e-05 0.000260786647834022 2375 2375 0 0 0 2377 2377 0 0 0 0 0 0 0 0 283 324 0 3631 0 0 0 0 0 1093 +442 444 0.977331964432218 -0.208934922464133 0.0341822976695191 -0.00454208948897838 0.210371289013334 0.976544246037254 -0.0458830719372585 0.162544521015904 -0.0237939500278742 0.0520339668527998 0.99836181529325 -0.0472486559004991 2.63350888250356e-05 -1.15845652906757e-05 -1.06070100541989e-06 -4.96183680013675e-06 -2.93626631122646e-06 -1.02817477468612e-05 -1.15845652906757e-05 4.03116748983507e-05 5.10930581248144e-07 -3.18723411152316e-10 1.65349460122654e-06 2.86622922043906e-05 -1.06070100541989e-06 5.10930581248144e-07 1.71873256513178e-05 7.05312464590606e-06 -8.20666569883505e-06 1.7393684292549e-06 -4.96183680013675e-06 -3.18723411152316e-10 7.05312464590606e-06 6.9408003557227e-05 1.80415578954134e-05 2.93628502462481e-05 -2.93626631122646e-06 1.65349460122654e-06 -8.20666569883505e-06 1.80415578954134e-05 6.55960248284098e-05 1.35480296912612e-05 -1.02817477468612e-05 2.86622922043906e-05 1.7393684292549e-06 2.93628502462481e-05 1.35480296912612e-05 0.000208571269156995 1609 1609 0 0 0 1621 1621 0 0 0 0 0 0 0 0 453 477 0 3383 0 0 0 0 0 1412 +446 450 0.959521141212022 -0.280055666166568 -0.0297993861544074 0.190768183273587 0.27956793905134 0.959927410852781 -0.0195226368112081 0.331006025589493 0.0340726726536933 0.0104014297803755 0.999365230151999 -0.0389113134580635 4.91784358589878e-05 -2.79520380469097e-05 1.98266143994395e-06 -7.57810486340242e-06 -3.18259367671926e-06 -3.13077786189264e-06 -2.79520380469097e-05 3.92291377352358e-05 -1.14933966159893e-07 7.04920691540377e-06 4.0012117110558e-06 -2.41713390424287e-06 1.98266143994395e-06 -1.14933966159893e-07 1.23516425024698e-05 8.85781064906855e-07 -3.25116052628136e-07 -4.48391015047852e-06 -7.57810486340242e-06 7.04920691540377e-06 8.85781064906855e-07 6.20177561006261e-05 1.33451625428238e-05 3.87129801536167e-05 -3.18259367671926e-06 4.0012117110558e-06 -3.25116052628136e-07 1.33451625428238e-05 2.3773361527458e-05 1.60090892926559e-05 -3.13077786189264e-06 -2.41713390424287e-06 -4.48391015047852e-06 3.87129801536167e-05 1.60090892926559e-05 0.000136744762176218 2494 2593 0 0 1719 2518 2617 0 0 1719 0 0 0 0 0 752 752 0 3781 0 0 0 0 0 1071 +445 328 0.175197981002712 0.984355616998443 0.0186999127320875 -0.0968198571601502 -0.974609626057796 0.170710823607162 0.144892689597675 -0.62842991129222 0.139433655363607 -0.0436100216346986 0.989270651422028 0.399973277949022 3.60506688671523e-05 -2.00641739156387e-05 -6.50076715527063e-06 -2.40450910352505e-06 -1.74622603326592e-07 7.12409597964587e-06 -2.00641739156387e-05 4.69343428198623e-05 9.24323398623344e-06 -4.85340498950221e-07 6.87096842448509e-06 4.52239004725302e-06 -6.50076715527063e-06 9.24323398623344e-06 1.62661495841998e-05 4.61379827955056e-06 -4.45026048265702e-06 -2.8462289367484e-06 -2.40450910352505e-06 -4.85340498950221e-07 4.61379827955056e-06 5.18239881010215e-05 -2.81402183157431e-05 1.51358964304199e-05 -1.74622603326592e-07 6.87096842448509e-06 -4.45026048265702e-06 -2.81402183157431e-05 6.51024793383083e-05 3.57589877048569e-06 7.12409597964587e-06 4.52239004725302e-06 -2.8462289367484e-06 1.51358964304199e-05 3.57589877048569e-06 0.000155245099217989 0 0 0 728 0 0 0 0 733 0 0 0 0 0 0 0 0 0 119 0 351 326 0 0 204 +445 449 0.95903932159964 -0.282118124120505 -0.0255527624422519 0.129699377972741 0.282422629196995 0.959246528400678 0.00914091180921516 0.334007732604313 0.0219325817714106 -0.0159831722124989 0.999631682202433 -0.0393382750806525 2.37295450079878e-05 -9.05242206061097e-06 3.26840437117263e-06 -2.39247588758065e-06 -2.58784360606644e-07 -2.39740609445442e-06 -9.05242206061097e-06 2.76133155887212e-05 -3.27702199038444e-06 -4.31499526589231e-07 1.51516978708667e-07 -1.22793914803565e-06 3.26840437117263e-06 -3.27702199038444e-06 1.43700026988437e-05 1.26501986217017e-05 1.11035691683019e-06 1.34056099831946e-06 -2.39247588758065e-06 -4.31499526589231e-07 1.26501986217017e-05 0.000141046112020559 2.49582962709882e-05 -2.35717970186373e-05 -2.58784360606644e-07 1.51516978708667e-07 1.11035691683019e-06 2.49582962709882e-05 3.0139150681293e-05 -1.12566267533127e-05 -2.39740609445442e-06 -1.22793914803565e-06 1.34056099831946e-06 -2.35717970186373e-05 -1.12566267533127e-05 0.000103507562198161 2669 2786 0 0 1221 2677 2794 0 0 1221 0 0 0 0 0 636 650 0 3742 0 0 0 0 0 1050 +446 329 0.0557247933334301 0.996826587222359 0.0568463051971892 -0.225330126476318 -0.989393811883809 0.0474806479673994 0.137278815097674 -0.748303890606454 0.134144073346428 -0.0638932161909335 0.988899906214379 0.522690060976891 3.97771562602752e-05 -2.48933651121802e-05 -5.96024966004311e-06 -1.16583113525576e-06 -2.30654317697217e-06 7.65887967569647e-06 -2.48933651121802e-05 6.03039469380405e-05 6.34763313748785e-06 1.31226170825221e-06 -1.41504232320775e-05 -3.92132360426322e-05 -5.96024966004311e-06 6.34763313748785e-06 1.82975205672326e-05 -1.01200320120651e-06 -3.56662347903478e-06 -5.46483664676818e-06 -1.16583113525576e-06 1.31226170825221e-06 -1.01200320120651e-06 3.42621353151321e-05 -8.30540845198525e-06 1.15841184320826e-06 -2.30654317697217e-06 -1.41504232320775e-05 -3.56662347903478e-06 -8.30540845198525e-06 6.20859843581929e-05 3.47726392432781e-05 7.65887967569647e-06 -3.92132360426322e-05 -5.46483664676818e-06 1.15841184320826e-06 3.47726392432781e-05 0.000187643371790394 0 0 0 623 0 0 0 0 630 0 0 0 0 0 0 0 0 0 20 0 250 220 0 0 100 +446 449 0.977071253730989 -0.209986382682735 -0.0351778939161012 0.118584779194797 0.210453460275357 0.97755164499391 0.0101055642013904 0.241452268501311 0.0322661771934879 -0.0172771657837544 0.999329972207278 -0.0274164705925478 4.81563222740074e-05 -3.00502491484484e-05 8.95239426960116e-07 -2.90841513190515e-06 -2.46796655386721e-06 1.55752910660767e-05 -3.00502491484484e-05 5.24118541232062e-05 2.12247320627873e-06 5.79311199283049e-06 2.30435412018972e-06 -3.38721025232563e-05 8.95239426960116e-07 2.12247320627873e-06 1.19728741540694e-05 5.10700067379576e-06 2.79250689149935e-06 -5.71969094400755e-06 -2.90841513190515e-06 5.79311199283049e-06 5.10700067379576e-06 7.73271739864585e-05 1.5939019444832e-05 -1.42847132905597e-05 -2.46796655386721e-06 2.30435412018972e-06 2.79250689149935e-06 1.5939019444832e-05 2.23918654376732e-05 -5.93056514788819e-06 1.55752910660767e-05 -3.38721025232563e-05 -5.71969094400755e-06 -1.42847132905597e-05 -5.93056514788819e-06 0.000120841007047901 2566 2683 0 0 1225 2596 2713 0 0 1225 0 0 0 0 0 527 541 0 3769 0 0 0 0 0 1506 +447 327 0.075617835984733 0.997115881373888 0.00647008446312298 -0.224154552942328 -0.990166198692914 0.0743217383846047 0.118520792140096 -0.729550901438574 0.117698096191108 -0.0153687447589029 0.992930490939585 0.332894421325854 3.57641528330008e-05 -7.67567826355452e-06 -2.69179390164999e-06 1.45252514246144e-06 -1.45640345783919e-06 1.46360304500972e-05 -7.67567826355452e-06 4.26161573414709e-05 4.9526849004375e-06 -4.16980165101081e-06 4.07388707314841e-06 4.95601381833591e-07 -2.69179390164999e-06 4.9526849004375e-06 1.6388165873323e-05 -1.29091765884723e-06 -2.68079768190105e-06 -8.86038075485294e-06 1.45252514246144e-06 -4.16980165101081e-06 -1.29091765884723e-06 3.33825078726916e-05 -5.72765841736168e-06 -7.60637619089379e-06 -1.45640345783919e-06 4.07388707314841e-06 -2.68079768190105e-06 -5.72765841736168e-06 5.8335289418588e-05 3.66111655625343e-05 1.46360304500972e-05 4.95601381833591e-07 -8.86038075485294e-06 -7.60637619089379e-06 3.66111655625343e-05 0.000170341765421286 0 0 0 990 0 0 0 0 1042 0 0 0 0 0 0 0 0 0 33 0 287 241 0 0 250 +447 451 0.961988831515064 -0.272632888991218 -0.0157732647407952 0.248229456900509 0.271332212797232 0.960745986849517 -0.0578444383766041 0.316279126520408 0.030924397145922 0.051365908858398 0.998200994323444 -0.0179284235992504 3.27376372603353e-05 -1.87385856620675e-05 3.79658438959001e-06 8.25598026112054e-06 -2.413911588093e-06 1.80059030909098e-05 -1.87385856620675e-05 4.54444886046347e-05 -1.659145725268e-06 2.09060100196629e-06 3.45193891848648e-06 7.4247170637458e-06 3.79658438959001e-06 -1.659145725268e-06 1.25873250973179e-05 3.31352869413388e-06 -1.52492512487274e-06 -2.23696178277198e-06 8.25598026112054e-06 2.09060100196629e-06 3.31352869413388e-06 8.06985674950225e-05 6.33735892140645e-06 1.86503759347333e-05 -2.413911588093e-06 3.45193891848648e-06 -1.52492512487274e-06 6.33735892140645e-06 2.32557148749637e-05 5.56110571214827e-06 1.80059030909098e-05 7.4247170637458e-06 -2.23696178277198e-06 1.86503759347333e-05 5.56110571214827e-06 0.000189417962337893 2546 2635 0 0 1732 2584 2673 0 0 1991 0 0 0 0 0 749 738 0 3786 0 0 0 0 0 1694 +448 451 0.978656171360764 -0.205479187456238 -0.00322517903609911 0.215533510627585 0.204671996970497 0.97598278878624 -0.074612128029847 0.223496712745959 0.0184789586719407 0.0723595157208634 0.997207415020086 -0.0192765241217911 3.71929432420292e-05 -1.45911815841896e-05 5.11800206623391e-06 7.87413005920326e-06 7.40394349036045e-07 6.9955597064576e-06 -1.45911815841896e-05 4.55328853794892e-05 2.62774972622747e-07 1.76394167671284e-05 2.36395692676152e-06 -9.20881180687473e-06 5.11800206623391e-06 2.62774972622747e-07 1.70623710984936e-05 -1.03672088587054e-06 -4.90969764720964e-06 5.00922298244869e-07 7.87413005920326e-06 1.76394167671284e-05 -1.03672088587054e-06 0.000135665706121141 3.22384816896841e-05 1.41370722570597e-05 7.40394349036045e-07 2.36395692676152e-06 -4.90969764720964e-06 3.22384816896841e-05 3.09574120769911e-05 6.53139141567935e-06 6.9955597064576e-06 -9.20881180687473e-06 5.00922298244869e-07 1.41370722570597e-05 6.53139141567935e-06 0.000134861107316349 2805 2894 0 0 1169 2836 2925 0 0 1315 0 0 0 0 0 538 527 0 3786 0 0 0 0 0 2449 +447 450 0.978494523148954 -0.205440352365826 -0.0185129626831005 0.169690379421233 0.204570560999578 0.978009761939285 -0.0405929935306725 0.239193763678186 0.0264452971210151 0.0359328146861379 0.999004243779231 -0.0179225858645165 6.39225919517426e-05 -4.38257071808103e-05 -2.05064374494401e-06 -8.77422546736984e-06 1.23061949586202e-06 2.90661587004904e-05 -4.38257071808103e-05 8.89691213185067e-05 1.40174289469758e-05 9.69488711426468e-06 -9.56780178603567e-06 1.64890272634167e-05 -2.05064374494401e-06 1.40174289469758e-05 1.83191667649975e-05 -5.67870035573387e-06 -4.95124884675428e-06 1.43115880993447e-07 -8.77422546736984e-06 9.69488711426468e-06 -5.67870035573387e-06 6.87645808679324e-05 2.08157083661751e-05 1.39062689560187e-05 1.23061949586202e-06 -9.56780178603567e-06 -4.95124884675428e-06 2.08157083661751e-05 3.23619742978756e-05 -7.98071784137361e-07 2.90661587004904e-05 1.64890272634167e-05 1.43115880993447e-07 1.39062689560187e-05 -7.98071784137361e-07 0.000231799793338735 2581 2680 0 0 1279 2610 2709 0 0 1573 0 0 0 0 0 553 553 0 3781 0 0 0 0 0 2091 +446 448 0.988927819983524 -0.145096687979684 -0.0311242349297454 0.0633234784329876 0.145962292983619 0.988904774681456 0.0276107884563745 0.149514215092448 0.026772670572805 -0.0318480415338952 0.999134088278873 -0.0264015904311766 3.45449052196935e-05 -1.32179805700954e-05 5.45141702100153e-06 3.99782907879331e-06 -3.16126559976702e-06 -2.5715599560893e-06 -1.32179805700954e-05 3.34733850909742e-05 -7.00536151713036e-07 1.29990315344485e-06 -8.57730421620022e-07 5.3904074519036e-06 5.45141702100153e-06 -7.00536151713036e-07 1.40672374609828e-05 2.10443750582505e-06 -1.01967418561846e-06 -3.65187076816307e-06 3.99782907879331e-06 1.29990315344485e-06 2.10443750582505e-06 6.04977997044361e-05 1.83623161256824e-05 -1.80954983943843e-06 -3.16126559976702e-06 -8.57730421620022e-07 -1.01967418561846e-06 1.83623161256824e-05 3.27348213234086e-05 -2.9100531458486e-07 -2.5715599560893e-06 5.3904074519036e-06 -3.65187076816307e-06 -1.80954983943843e-06 -2.9100531458486e-07 0.000163503232448422 2940 3074 0 0 404 2972 3106 0 0 404 0 0 0 0 0 343 371 0 3744 0 0 0 0 0 1797 +447 449 0.990726024256972 -0.134256573973261 -0.0209073481086245 0.0901487697440111 0.134075151391258 0.990922148929689 -0.0098563958919137 0.153501001426232 0.0220408402603917 0.00696183205264485 0.999732831438023 -0.00916022544309869 2.43978064446626e-05 -1.26005451037468e-05 7.03729013237554e-07 -7.48626293994042e-07 1.42232792405584e-06 3.52976059506278e-07 -1.26005451037468e-05 1.95377901531591e-05 4.4909623219277e-07 -1.76072444045006e-06 -3.38919404027926e-07 -8.73196712223714e-06 7.03729013237554e-07 4.4909623219277e-07 1.37853513255839e-05 9.5689604540991e-07 1.98229619609198e-06 -1.75057981518219e-06 -7.48626293994042e-07 -1.76072444045006e-06 9.5689604540991e-07 6.62418771259438e-05 1.32462811169523e-05 1.88855119180662e-06 1.42232792405584e-06 -3.38919404027926e-07 1.98229619609198e-06 1.32462811169523e-05 2.22743340988513e-05 -1.3685946506495e-06 3.52976059506278e-07 -8.73196712223714e-06 -1.75057981518219e-06 1.88855119180662e-06 -1.3685946506495e-06 0.000104193475668701 3061 3178 0 0 762 3095 3212 0 0 1022 0 0 0 0 0 367 381 0 3778 0 0 0 0 0 2401 +449 327 -0.0550280665243578 0.997331883536625 0.0479690105784893 -0.440872474973405 -0.990884750772309 -0.060462375347097 0.120381526216799 -0.835809821473494 0.12296065460744 -0.0409073984588989 0.991568082468287 0.351244996646156 7.46369935467594e-05 -1.26915871514782e-05 -6.17463487685541e-06 -2.56599579275226e-06 -2.17999850291607e-05 -4.20516553524027e-05 -1.26915871514782e-05 4.52317946621262e-05 5.72642833729123e-06 -3.84670091083031e-06 -5.86417666592196e-06 -1.13211400349222e-05 -6.17463487685541e-06 5.72642833729123e-06 2.06688312724115e-05 1.81291454256426e-06 7.05404530421405e-07 -8.73132535872849e-06 -2.56599579275226e-06 -3.84670091083031e-06 1.81291454256426e-06 3.06959923791263e-05 -2.93380767512097e-06 5.69429360549778e-07 -2.17999850291607e-05 -5.86417666592196e-06 7.05404530421405e-07 -2.93380767512097e-06 6.68098488344023e-05 4.80015445350346e-05 -4.20516553524027e-05 -1.13211400349222e-05 -8.73132535872849e-06 5.69429360549778e-07 4.80015445350346e-05 0.000175919794706512 0 0 0 843 0 0 0 0 863 0 0 0 0 0 0 0 0 0 0 0 207 207 0 187 2 +448 328 -0.037958466956265 0.996902301669835 0.0688836389261997 -0.381142652025522 -0.993606651235866 -0.0449878173627378 0.103546699168949 -0.840822962084944 0.106324867299132 -0.064512767839567 0.99223642615029 0.411284405083388 3.45946585243724e-05 -1.53447938918772e-05 -9.69020569561593e-07 -1.34291039496557e-06 -1.20396558498028e-06 -9.43983890945483e-07 -1.53447938918772e-05 2.71217517247274e-05 2.64919531236783e-06 -6.40570577393613e-06 4.8870989731846e-06 -1.49912562796546e-05 -9.69020569561593e-07 2.64919531236783e-06 1.52293694423191e-05 -1.96250913644082e-06 -5.12396298807976e-07 -3.4542139801704e-06 -1.34291039496557e-06 -6.40570577393613e-06 -1.96250913644082e-06 4.60354106332637e-05 -3.73406297826431e-05 5.4241915131958e-06 -1.20396558498028e-06 4.8870989731846e-06 -5.12396298807976e-07 -3.73406297826431e-05 0.000101472523997561 1.19111007679379e-05 -9.43983890945483e-07 -1.49912562796546e-05 -3.4542139801704e-06 5.4241915131958e-06 1.19111007679379e-05 9.95639647256769e-05 0 0 0 723 0 0 0 0 746 0 0 0 0 0 0 0 0 0 0 0 296 296 0 111 10 +450 325 0.0210843248836389 0.99915592994271 0.0352544877217098 -0.450706948574363 -0.992606355811069 0.0167041304448364 0.120223102728015 -0.763540727878648 0.119532730445138 -0.0375286515398691 0.992120721820651 0.23161166409125 4.60412294186174e-05 -1.59057716439265e-05 -1.16959638844049e-06 -4.56144440113278e-06 -1.17080367237156e-06 -1.27185529302187e-06 -1.59057716439265e-05 4.45550686455778e-05 8.89366114873393e-06 7.87508035130036e-06 -3.50400078729882e-06 7.40140675899668e-06 -1.16959638844049e-06 8.89366114873393e-06 1.81181996677663e-05 3.51879037101887e-06 1.84696103574293e-06 9.30594373474006e-06 -4.56144440113278e-06 7.87508035130036e-06 3.51879037101887e-06 3.50892920228676e-05 -9.55369440609163e-06 4.30737600409708e-05 -1.17080367237156e-06 -3.50400078729882e-06 1.84696103574293e-06 -9.55369440609163e-06 7.05760047941296e-05 -1.58784466517125e-05 -1.27185529302187e-06 7.40140675899668e-06 9.30594373474006e-06 4.30737600409708e-05 -1.58784466517125e-05 0.00022698838627763 0 0 0 1223 0 0 0 0 1252 0 0 0 0 0 0 0 0 0 0 0 50 50 0 327 0 +450 327 -0.12376281360567 0.990559169869188 0.0589516493108755 -0.581395275651165 -0.98049501731054 -0.131213974674985 0.146329811997408 -0.858984881179029 0.152683617318993 -0.0396916091643638 0.987477741098163 0.374764568804567 6.17955088786291e-05 -1.72801938351113e-05 4.3836879569945e-06 -3.21573208249339e-06 -2.99332499649662e-06 -3.57370784020723e-05 -1.72801938351113e-05 3.84336196352466e-05 9.27190256405308e-06 5.30751069132836e-06 -4.74278780971163e-06 -5.8768161134913e-06 4.3836879569945e-06 9.27190256405308e-06 1.95358308714373e-05 3.30568490355597e-08 -1.80456625224565e-06 -1.01849862139347e-05 -3.21573208249339e-06 5.30751069132836e-06 3.30568490355597e-08 3.32575441238832e-05 -8.84284613262032e-06 2.68726731777408e-05 -2.99332499649662e-06 -4.74278780971163e-06 -1.80456625224565e-06 -8.84284613262032e-06 5.92136405332419e-05 8.59095023663985e-06 -3.57370784020723e-05 -5.8768161134913e-06 -1.01849862139347e-05 2.68726731777408e-05 8.59095023663985e-06 0.000217132681666451 0 0 0 718 0 0 0 0 732 0 0 0 0 0 0 0 0 0 0 0 68 68 0 258 0 +450 324 0.115239756574726 0.993030645533664 0.0246968729921779 -0.392307357980847 -0.987470367246325 0.111825360420178 0.111343444249334 -0.719101159171602 0.107805715595256 -0.0372186216549065 0.993475063545685 0.171610047762243 6.42674173563921e-05 -1.8570097259864e-05 -1.98809720993749e-06 -5.77209095030239e-06 6.47864642370594e-06 -1.28835614557224e-05 -1.8570097259864e-05 4.81848570674556e-05 5.34467240284988e-06 -2.05934324514855e-07 8.1941340537932e-06 1.9145421384989e-05 -1.98809720993749e-06 5.34467240284988e-06 2.3342993270801e-05 9.59958929912013e-06 1.07416654723726e-05 -2.57245784400509e-06 -5.77209095030239e-06 -2.05934324514855e-07 9.59958929912013e-06 3.57016093054942e-05 -8.88866711425016e-06 6.13732863813452e-06 6.47864642370594e-06 8.1941340537932e-06 1.07416654723726e-05 -8.88866711425016e-06 0.000177410305909827 1.34374006317186e-05 -1.28835614557224e-05 1.9145421384989e-05 -2.57245784400509e-06 6.13732863813452e-06 1.34374006317186e-05 0.000179437838184128 0 0 0 1380 0 0 0 0 1421 0 0 0 0 0 0 0 0 0 43 0 56 56 0 315 0 +449 452 0.979038986274033 -0.20343118283313 -0.00992054467393805 0.24344677626427 0.202608566606244 0.977739778612874 -0.0545407559152848 0.190880987801511 0.0207950016416748 0.0513875390455801 0.998462262049779 -0.024607225085238 4.39758388393295e-05 -2.47661610565191e-05 -2.58920366662273e-07 9.06128252999448e-07 1.16390174097807e-06 1.02077840720995e-05 -2.47661610565191e-05 3.12767550467786e-05 2.72715035789957e-07 1.3579255607705e-06 1.32177315712211e-06 -1.55961950537949e-05 -2.58920366662273e-07 2.72715035789957e-07 1.52503170068151e-05 5.41816177857206e-06 4.10685213635423e-08 8.99704815609168e-08 9.06128252999448e-07 1.3579255607705e-06 5.41816177857206e-06 0.000112755869794417 9.59923039425457e-06 5.09360252156858e-05 1.16390174097807e-06 1.32177315712211e-06 4.10685213635423e-08 9.59923039425457e-06 1.86627585445144e-05 9.14234176609972e-06 1.02077840720995e-05 -1.55961950537949e-05 8.99704815609168e-08 5.09360252156858e-05 9.14234176609972e-06 0.000187884478966346 2743 2822 0 0 1142 2759 2838 0 0 1278 0 0 0 0 0 477 460 0 3787 0 0 0 0 0 2561 +450 453 0.982790606008368 -0.184683725334302 -0.00381396622286454 0.29374788410046 0.184527272957596 0.982489904419696 -0.02575409187312 0.162761119168476 0.0085035449394918 0.0246070987729212 0.999661032757325 0.0377589687018388 0.000101245317032468 -5.08992760904168e-05 8.11513502008546e-07 -2.06055533310344e-05 -1.0591208620381e-06 -5.76068265002237e-05 -5.08992760904168e-05 7.5843807602947e-05 1.89965506680543e-07 1.10180084196435e-05 1.65278552374117e-06 1.00480892491468e-05 8.11513502008546e-07 1.89965506680543e-07 1.953681437143e-05 8.1905657628751e-06 -1.963713236024e-06 -4.62201900811123e-06 -2.06055533310344e-05 1.10180084196435e-05 8.1905657628751e-06 0.000116616333348496 1.94339253986564e-08 4.69308445529488e-05 -1.0591208620381e-06 1.65278552374117e-06 -1.963713236024e-06 1.94339253986564e-08 2.0647552092757e-05 1.0273530157504e-05 -5.76068265002237e-05 1.00480892491468e-05 -4.62201900811123e-06 4.69308445529488e-05 1.0273530157504e-05 0.000249621381153395 2821 2889 0 0 1121 2821 2889 0 0 1243 0 0 0 0 0 360 333 0 3799 0 0 0 0 0 2544 +450 326 -0.0665735000235002 0.997245570094449 0.032699266377364 -0.525160714075947 -0.989300954171878 -0.0702359167742722 0.127869222526336 -0.816346874453246 0.12981367866767 -0.0238367137389846 0.99125184484514 0.294737783716076 5.35843026241329e-05 -2.28835767748564e-05 -5.36723220033643e-06 -5.59390529599032e-06 8.84329597157568e-07 -3.27392800770563e-06 -2.28835767748564e-05 4.98935633923896e-05 1.06875804960831e-05 8.67518338277397e-06 -1.52788114635781e-05 -3.71499995983729e-06 -5.36723220033643e-06 1.06875804960831e-05 1.98963414930118e-05 1.53161567068452e-06 -5.40914239986927e-06 -1.80936023042352e-06 -5.59390529599032e-06 8.67518338277397e-06 1.53161567068452e-06 3.60297483276473e-05 -2.28186390178373e-05 2.14696919786281e-05 8.84329597157568e-07 -1.52788114635781e-05 -5.40914239986927e-06 -2.28186390178373e-05 9.16772832570636e-05 -5.83134904948658e-06 -3.27392800770563e-06 -3.71499995983729e-06 -1.80936023042352e-06 2.14696919786281e-05 -5.83134904948658e-06 0.000132261992224373 0 0 0 932 0 0 0 0 954 0 0 0 0 0 0 0 0 0 0 0 39 39 0 346 0 +450 452 0.991217039251322 -0.13219546511429 -0.00362492773176228 0.183648182916092 0.132081387111968 0.990981285391486 -0.0225964418087726 0.110485716924758 0.00657938267791171 0.0219191926643145 0.999738096061425 0.00259835971233531 4.9382324480334e-05 -2.65773025141364e-06 7.94429342661779e-06 -2.27615030787381e-05 -6.60102082372493e-06 8.73053117561998e-06 -2.65773025141364e-06 3.01900583937639e-05 5.97914348828606e-06 -5.74586444389529e-06 -3.14162244930286e-06 -7.30645008421767e-06 7.94429342661779e-06 5.97914348828606e-06 1.70543404794751e-05 -6.09749324173732e-07 -1.30714849686804e-07 -3.02567951218905e-07 -2.27615030787381e-05 -5.74586444389529e-06 -6.09749324173732e-07 0.000106895413969447 1.2185721962117e-05 2.3649720516442e-05 -6.60102082372493e-06 -3.14162244930286e-06 -1.30714849686804e-07 1.2185721962117e-05 1.95739495870111e-05 1.84208876098688e-06 8.73053117561998e-06 -7.30645008421767e-06 -3.02567951218905e-07 2.3649720516442e-05 1.84208876098688e-06 9.7599524961562e-05 3164 3243 0 0 688 3164 3243 0 0 806 0 0 0 0 0 274 257 0 3787 0 0 0 0 0 3065 +451 324 0.0476671179046695 0.998125133016695 0.0383935503837208 -0.552563916822931 -0.991050029107465 0.0424611015147529 0.126557870811132 -0.745438284708393 0.124690359197316 -0.0440825781750436 0.991215940461354 0.20537284342891 6.37483522437417e-05 -2.14796570369394e-05 9.36560213873687e-07 5.14530184885739e-06 -3.69214159625931e-05 -1.68038985924723e-05 -2.14796570369394e-05 5.12529704412916e-05 4.17345456777988e-06 -5.18913473465307e-07 -1.1229954775571e-05 8.22360514411717e-06 9.36560213873687e-07 4.17345456777988e-06 1.61707674202044e-05 1.7647197727666e-06 -9.30256633699814e-06 2.61059227530363e-06 5.14530184885739e-06 -5.18913473465307e-07 1.7647197727666e-06 7.46916350227097e-05 -0.000220084881119881 3.21134628016667e-05 -3.69214159625931e-05 -1.1229954775571e-05 -9.30256633699814e-06 -0.000220084881119881 0.00101146467004819 -1.12747616416208e-05 -1.68038985924723e-05 8.22360514411717e-06 2.61059227530363e-06 3.21134628016667e-05 -1.12747616416208e-05 0.000246603144901435 0 0 0 1487 0 0 0 0 1511 0 0 0 0 0 0 0 0 0 0 0 46 46 0 463 0 +451 453 0.993092539531038 -0.117109869263672 0.00724475319376955 0.203051261611959 0.117141703722697 0.993106595480359 -0.00413657616333465 0.0886468975756784 -0.00671037828567259 0.00495666565917818 0.999965200538902 0.0235162401747981 6.17495231792825e-05 -1.23381523697908e-05 1.00911640992594e-06 -2.19971623045632e-05 1.23241077555719e-06 -7.38885850932346e-05 -1.23381523697908e-05 2.76864276379892e-05 -1.23585791761577e-06 1.12138184417378e-05 4.47526840902068e-06 4.13202136035159e-05 1.00911640992594e-06 -1.23585791761577e-06 1.59455108775422e-05 7.91271761019539e-06 -2.8385630714221e-06 -4.29009122392055e-06 -2.19971623045632e-05 1.12138184417378e-05 7.91271761019539e-06 0.0001436395928248 8.27024752478603e-06 0.00011847757134139 1.23241077555719e-06 4.47526840902068e-06 -2.8385630714221e-06 8.27024752478603e-06 1.87428944201852e-05 2.31054448206531e-05 -7.38885850932346e-05 4.13202136035159e-05 -4.29009122392055e-06 0.00011847757134139 2.31054448206531e-05 0.000420005898473258 3373 3441 0 0 630 3359 3427 0 0 741 0 0 0 0 0 183 156 0 3799 0 0 0 0 0 3060 +452 454 0.995053652881691 -0.0993092684764168 -0.00242839071858359 0.20573890581453 0.0992538553300844 0.994915767349152 -0.0170671638582029 0.0727339420557428 0.00411097177292842 0.0167417166003679 0.999851396376659 -0.0224802562492889 9.91650668292573e-05 -9.08222466081548e-06 6.54825996915429e-07 -1.218524897936e-05 2.37063384475548e-06 -6.97623365404733e-05 -9.08222466081548e-06 3.93327512320528e-05 5.6806418877093e-06 1.31817055899074e-05 -2.21422903113312e-06 2.23911838856473e-05 6.54825996915429e-07 5.6806418877093e-06 1.90302096452081e-05 8.90310200392608e-06 -1.06708779332023e-06 8.17983824646593e-06 -1.218524897936e-05 1.31817055899074e-05 8.90310200392608e-06 0.000175113550085872 4.44769555915935e-06 0.000110173633875845 2.37063384475548e-06 -2.21422903113312e-06 -1.06708779332023e-06 4.44769555915935e-06 1.68488412657253e-05 2.95337246881604e-06 -6.97623365404733e-05 2.23911838856473e-05 8.17983824646593e-06 0.000110173633875845 2.95337246881604e-06 0.000293203470468101 3301 3365 0 0 558 3283 3347 0 0 650 0 0 0 0 0 97 64 0 3803 0 0 0 0 0 3141 +453 455 0.996034042442869 -0.0879526626272591 0.0134356031384333 0.202745458630223 0.0880496977087864 0.996092811933735 -0.00680887269197198 0.0558504422752363 -0.0127842492274388 0.00796486978673798 0.999886555475655 -0.0365877302353653 0.000144859262917897 -4.83921825760879e-05 -1.27950915848453e-05 -8.82490649618021e-05 1.36736304562662e-05 -0.000104154122437118 -4.83921825760879e-05 8.27144855908156e-05 4.47159453882285e-06 7.46213474459476e-05 -1.92912844309915e-06 0.000151739985558187 -1.27950915848453e-05 4.47159453882285e-06 1.93649837684946e-05 7.25734835062155e-06 -2.82627344680332e-06 2.38522222276589e-06 -8.82490649618021e-05 7.46213474459476e-05 7.25734835062155e-06 0.000296265397099637 3.63933913308379e-06 0.000336834931706224 1.36736304562662e-05 -1.92912844309915e-06 -2.82627344680332e-06 3.63933913308379e-06 1.75439878319488e-05 1.63652621066474e-05 -0.000104154122437118 0.000151739985558187 2.38522222276589e-06 0.000336834931706224 1.63652621066474e-05 0.000869007839162348 3233 3287 0 0 497 3199 3255 0 0 581 0 0 0 0 0 27 0 0 3813 0 0 0 0 0 3211 +453 325 -0.159728906848231 0.984351883496515 0.074418047367097 -0.869717544152211 -0.97626870076235 -0.168684786466567 0.13581187991675 -0.765727904989618 0.146239872226633 -0.0509589273002411 0.987935770938347 0.291120058953178 4.76802172801403e-05 -1.35511289959976e-05 2.53343952546631e-06 -7.3201160392777e-06 1.02960474680165e-05 -1.09987327114431e-06 -1.35511289959976e-05 6.58740856171258e-05 1.59089539583827e-05 1.8446815056721e-05 -2.17716227864301e-05 4.80018829666114e-05 2.53343952546631e-06 1.59089539583827e-05 1.98566165336609e-05 1.02138596883504e-07 -3.61276187693087e-06 1.10251003213964e-05 -7.3201160392777e-06 1.8446815056721e-05 1.02138596883504e-07 5.54013392149144e-05 -7.7659350050549e-05 9.98781016253578e-05 1.02960474680165e-05 -2.17716227864301e-05 -3.61276187693087e-06 -7.7659350050549e-05 0.000242358204427637 -0.000110978219030546 -1.09987327114431e-06 4.80018829666114e-05 1.10251003213964e-05 9.98781016253578e-05 -0.000110978219030546 0.000424115440069251 0 0 0 963 0 0 0 0 975 0 0 0 0 0 0 0 0 0 0 0 0 0 0 510 0 +454 320 0.274652647172108 0.955872584073623 0.104276202547697 -0.755359755721366 -0.959750308005148 0.265903620074991 0.0904135560358009 -0.545248675710348 0.0586964196981206 -0.124911440018236 0.990430140124579 0.0769037677074604 5.14400033350517e-05 -5.90120115933347e-06 1.39729039105512e-05 6.18721200556057e-06 1.05917437566296e-06 -2.22274264882216e-06 -5.90120115933347e-06 5.25963555013308e-05 9.44601995234044e-06 -3.56543159744152e-07 -2.21992233281539e-05 8.42316964744073e-06 1.39729039105512e-05 9.44601995234044e-06 1.88874065672771e-05 -7.22152300162955e-07 -3.59006435380914e-06 -5.35236627385492e-07 6.18721200556057e-06 -3.56543159744152e-07 -7.22152300162955e-07 2.09939541663831e-05 1.59873773293837e-05 1.82312293642106e-05 1.05917437566296e-06 -2.21992233281539e-05 -3.59006435380914e-06 1.59873773293837e-05 0.000192658778657921 -3.48637915287557e-05 -2.22274264882216e-06 8.42316964744073e-06 -5.35236627385492e-07 1.82312293642106e-05 -3.48637915287557e-05 0.000315381012308273 0 0 0 1465 0 0 0 0 1464 0 0 0 0 0 0 0 0 0 542 0 142 18 0 771 0 +454 325 -0.206478202056117 0.976022171940897 0.068901900956704 -1.03583893758431 -0.963977112923085 -0.214986396831957 0.156617288118799 -0.745200038518768 0.167674917134758 -0.0340817994974812 0.98525304014089 0.27829855995401 4.00916568112095e-05 3.3758879807211e-07 1.16328738176244e-05 -3.4838108516625e-06 4.18308893269434e-06 -3.32116017726821e-06 3.3758879807211e-07 5.13070065175584e-05 6.82636221372215e-06 4.86572601306205e-06 3.83104534101359e-06 1.48837882269457e-05 1.16328738176244e-05 6.82636221372215e-06 1.96583943249412e-05 -2.32360340579161e-06 1.15088175343759e-06 5.72584105636304e-06 -3.4838108516625e-06 4.86572601306205e-06 -2.32360340579161e-06 2.13619107360377e-05 -8.21249238170469e-06 1.82390024560224e-05 4.18308893269434e-06 3.83104534101359e-06 1.15088175343759e-06 -8.21249238170469e-06 8.94357734726172e-05 2.78636105284002e-05 -3.32116017726821e-06 1.48837882269457e-05 5.72584105636304e-06 1.82390024560224e-05 2.78636105284002e-05 0.000204371963910852 0 0 0 860 0 0 0 0 870 0 0 0 0 0 0 0 0 0 0 0 0 0 0 629 0 +454 322 0.075442470334651 0.992949994405016 0.0914261575309996 -0.862185462542641 -0.992084093125072 0.0655124696247988 0.107132014318151 -0.644160838024918 0.100387179649644 -0.0987847403941401 0.990032317264064 0.161007833094817 5.85558819587662e-05 -4.80603688332936e-06 7.62648444615286e-06 -1.11872058570854e-06 3.01765985745344e-05 -1.87039020321428e-05 -4.80603688332936e-06 8.13242524228914e-05 1.93660607496732e-05 9.33343356370447e-06 -1.75473767748403e-05 3.70351262906423e-05 7.62648444615286e-06 1.93660607496732e-05 2.20211474667555e-05 2.00316968218664e-06 -3.00815462754572e-06 -3.33647249392647e-06 -1.11872058570854e-06 9.33343356370447e-06 2.00316968218664e-06 2.06882001486724e-05 -9.42929162807117e-06 2.8739576341793e-05 3.01765985745344e-05 -1.75473767748403e-05 -3.00815462754572e-06 -9.42929162807117e-06 0.000281068614851556 -3.17999469472299e-05 -1.87039020321428e-05 3.70351262906423e-05 -3.33647249392647e-06 2.8739576341793e-05 -3.17999469472299e-05 0.000284204870462871 0 0 0 1313 0 0 0 0 1323 0 0 0 0 0 0 0 0 0 141 0 0 0 0 694 0 +454 324 -0.113259805224416 0.991901361044388 0.057479617942517 -1.01497070273478 -0.981558959851106 -0.120670303792729 0.148258848365232 -0.723482220079929 0.153994236439361 -0.0396278657116536 0.987276763325562 0.230284320269025 4.54646976193559e-05 -3.09434149473185e-06 1.08859940714751e-05 -1.81179453092092e-06 1.22155208793231e-05 1.52731635868592e-05 -3.09434149473185e-06 3.70365368536078e-05 7.75876123169185e-06 2.59985348303985e-06 1.5556937250585e-05 1.93804547122912e-05 1.08859940714751e-05 7.75876123169185e-06 1.85736091939627e-05 -6.02495320381646e-07 2.56986620592141e-06 5.15340696955825e-06 -1.81179453092092e-06 2.59985348303985e-06 -6.02495320381646e-07 2.26994728907005e-05 -1.50450153340132e-05 2.05554641867119e-05 1.22155208793231e-05 1.5556937250585e-05 2.56986620592141e-06 -1.50450153340132e-05 0.000177612912504596 5.46560360410331e-05 1.52731635868592e-05 1.93804547122912e-05 5.15340696955825e-06 2.05554641867119e-05 5.46560360410331e-05 0.000224402595376466 0 0 0 1082 0 0 0 0 1091 0 0 0 0 0 0 0 0 0 0 0 0 0 0 694 0 +454 323 -0.0224819901226899 0.998169660037927 0.0561416948434315 -0.92884875791054 -0.99273017633722 -0.0289306727684471 0.116832414862644 -0.680959145996419 0.118242788827037 -0.0531069294248382 0.991563561723337 0.169246256069104 5.77495263545683e-05 -1.11594276060316e-05 7.32301759453256e-06 -4.1033742050841e-06 -6.95161656443322e-06 -2.0182295888317e-05 -1.11594276060316e-05 8.59838727723579e-05 2.31769763787933e-05 2.92581124389574e-05 -4.57039519184298e-05 0.000132947196480165 7.32301759453256e-06 2.31769763787933e-05 2.62596345172937e-05 7.82486200056482e-06 -8.65838827047935e-06 4.06763803250431e-05 -4.1033742050841e-06 2.92581124389574e-05 7.82486200056482e-06 3.44885877386782e-05 -3.3171564694648e-05 0.000102475537665079 -6.95161656443322e-06 -4.57039519184298e-05 -8.65838827047935e-06 -3.3171564694648e-05 0.000209852238112061 -0.000170084341690061 -2.0182295888317e-05 0.000132947196480165 4.06763803250431e-05 0.000102475537665079 -0.000170084341690061 0.00060032825378183 0 0 0 1406 0 0 0 0 1410 0 0 0 0 0 0 0 0 0 13 0 0 0 0 746 0 +455 458 0.997440354430671 -0.0460705085912427 0.0546831563770926 0.334984686708365 0.0449689953586714 0.998763271058321 0.0212065518487762 0.0626885995922167 -0.0555925247641183 -0.0186932239869767 0.998278535563759 -0.0911041200370028 6.84263174518909e-05 -1.27279269515404e-05 9.62529774084656e-06 -1.18406352747404e-06 -7.70370516364838e-07 7.27221870177729e-07 -1.27279269515404e-05 4.29631523907905e-05 4.83461891062255e-07 4.03906146916232e-06 -9.16818184506682e-07 -1.08507178767576e-07 9.62529774084656e-06 4.83461891062255e-07 1.55224450031495e-05 7.30764099501362e-06 3.52353791089225e-07 3.14946645452136e-06 -1.18406352747404e-06 4.03906146916232e-06 7.30764099501362e-06 0.000300056831415644 -5.30402706398648e-06 -3.37389772755278e-06 -7.70370516364838e-07 -9.16818184506682e-07 3.52353791089225e-07 -5.30402706398648e-06 1.38252363624275e-05 -6.79981727146608e-06 7.27221870177729e-07 -1.08507178767576e-07 3.14946645452136e-06 -3.37389772755278e-06 -6.79981727146608e-06 0.000248686327928855 3183 3173 0 219 600 3183 3173 0 163 682 0 0 0 0 0 0 0 0 3563 0 0 0 0 0 3116 +454 303 0.997916830536813 0.00212722380986743 0.0644784789695376 -0.978977108836353 -0.00342789329932778 0.999792736193498 0.0200682386433396 -0.0998815817477327 -0.0644224252794847 -0.0202474584474284 0.997717290392188 0.0951649418270144 6.60913074412733e-05 -9.70279204117977e-05 8.48859561605467e-07 1.42778798195653e-05 6.94978937504918e-06 4.03402025385695e-05 -9.70279204117977e-05 0.00148357066115599 2.2729241210919e-05 -0.000226933413454482 -1.5594401479203e-05 4.89150160761702e-05 8.48859561605467e-07 2.2729241210919e-05 1.39560957570978e-05 -1.18709861281903e-06 2.90210602015731e-06 -1.49233543708439e-05 1.42778798195653e-05 -0.000226933413454482 -1.18709861281903e-06 0.000155914508137398 3.52876554829046e-06 3.06381797709947e-05 6.94978937504918e-06 -1.5594401479203e-05 2.90210602015731e-06 3.52876554829046e-06 1.23672535792511e-05 5.63140787640741e-06 4.03402025385695e-05 4.89150160761702e-05 -1.49233543708439e-05 3.06381797709947e-05 5.63140787640741e-06 0.000833092710008441 1607 1607 0 0 0 1619 1619 0 0 0 0 0 0 0 0 536 504 0 1836 0 848 913 0 0 1829 +455 304 0.994840900069469 0.064743836870482 0.0781013388890175 -1.01241213544473 -0.0657861356305689 0.997774815066182 0.0108444814741353 -0.0833765186316899 -0.0772254356269043 -0.0159265189835974 0.996886441920693 0.130212998354374 4.74155810228874e-05 -1.16828157360953e-05 1.07807806431147e-05 3.09101980691946e-06 1.04513930807373e-06 1.44956552024532e-05 -1.16828157360953e-05 7.79516300647465e-05 -1.51300816507863e-06 3.26103498693584e-05 3.42294732943846e-06 9.53870944726295e-05 1.07807806431147e-05 -1.51300816507863e-06 1.47095012042351e-05 -1.01669887594979e-06 3.20188657386694e-06 -8.8727317915923e-06 3.09101980691946e-06 3.26103498693584e-05 -1.01669887594979e-06 0.000158371647802513 7.50990394237509e-06 0.000139699221016486 1.04513930807373e-06 3.42294732943846e-06 3.20188657386694e-06 7.50990394237509e-06 1.33249705030874e-05 1.58402555803773e-05 1.44956552024532e-05 9.53870944726295e-05 -8.8727317915923e-06 0.000139699221016486 1.58402555803773e-05 0.000547083316329112 1626 1626 0 0 0 1634 1634 0 0 0 0 0 0 0 0 438 407 0 2017 0 996 1066 0 0 1637 +455 302 0.997892534202718 0.0456263116069867 0.0461381606874393 -1.16923502457555 -0.0466466039353355 0.998684680215646 0.021283886954055 -0.0735698407406821 -0.0451063689934998 -0.0233912203981579 0.998708298896383 0.176298239526292 6.01948359324694e-05 -9.62104036850643e-06 9.50168548843732e-06 1.22222963370135e-05 1.63643501970614e-06 -6.37553133005075e-07 -9.62104036850643e-06 5.26442128014204e-05 1.41104803733351e-06 3.05499322312135e-05 3.65208877318103e-07 4.32198198725932e-05 9.50168548843732e-06 1.41104803733351e-06 2.0945025895327e-05 -2.84194061252009e-06 -3.60826282774335e-07 1.3712235409122e-06 1.22222963370135e-05 3.05499322312135e-05 -2.84194061252009e-06 0.000201495225625818 1.51513308544191e-05 0.000140061370860449 1.63643501970614e-06 3.65208877318103e-07 -3.60826282774335e-07 1.51513308544191e-05 1.56375173259488e-05 9.57729044498076e-06 -6.37553133005075e-07 4.32198198725932e-05 1.3712235409122e-06 0.000140061370860449 9.57729044498076e-06 0.000240541547218246 1437 1437 0 0 0 1444 1444 0 0 0 0 0 0 0 0 547 513 0 1574 0 875 931 0 0 1266 +455 325 -0.245632576743685 0.966935205044877 0.068563448622998 -1.21468167475276 -0.956760203945747 -0.253200177995843 0.143176750935921 -0.72594123506265 0.155802918419236 -0.0304299048255843 0.987319336134138 0.296911971011662 5.56148865426693e-05 9.95916319104223e-06 1.19007174131242e-05 -6.2129554532384e-06 3.03932185222796e-06 -8.74010494815376e-06 9.95916319104223e-06 4.31871809112934e-05 4.15764300638381e-06 -2.07369901888459e-06 1.59182704275317e-06 -1.6566136514448e-05 1.19007174131242e-05 4.15764300638381e-06 1.63241279620332e-05 -4.19893800799072e-06 -1.50562166936871e-06 -5.35756663873587e-06 -6.2129554532384e-06 -2.07369901888459e-06 -4.19893800799072e-06 2.2553042421767e-05 -2.1267994314381e-05 6.40329864975362e-06 3.03932185222796e-06 1.59182704275317e-06 -1.50562166936871e-06 -2.1267994314381e-05 0.000111468985460091 1.82432546324136e-06 -8.74010494815376e-06 -1.6566136514448e-05 -5.35756663873587e-06 6.40329864975362e-06 1.82432546324136e-06 0.000100106372489643 0 0 0 835 0 0 0 0 844 0 0 0 0 0 0 0 0 0 0 0 0 0 0 615 0 +455 301 0.998264453378691 0.0588190422390469 -0.00289851524497937 -1.31679680545176 -0.0586756286076989 0.997617910050318 0.0362722504723301 -0.0790763683497525 0.00502510975358257 -0.0360392260865474 0.999337741934651 0.146965726628095 7.77235429854806e-05 -2.79882727011082e-06 7.3771915887703e-06 3.26129849870991e-05 7.10230505745786e-06 -2.65111689569867e-06 -2.79882727011082e-06 5.16650538668504e-05 5.95503262239323e-06 1.98237246292955e-05 -1.01574159259173e-06 2.18521650060774e-05 7.3771915887703e-06 5.95503262239323e-06 1.68284925368834e-05 -3.39039258910878e-06 2.63320744035704e-06 -2.78465651054126e-06 3.26129849870991e-05 1.98237246292955e-05 -3.39039258910878e-06 0.000337899562002444 2.47664301474233e-05 0.000144039476829915 7.10230505745786e-06 -1.01574159259173e-06 2.63320744035704e-06 2.47664301474233e-05 1.6208351923066e-05 5.0635036379713e-06 -2.65111689569867e-06 2.18521650060774e-05 -2.78465651054126e-06 0.000144039476829915 5.0635036379713e-06 0.000260885637266628 1293 1293 0 0 0 1295 1295 0 0 0 0 0 0 0 0 535 508 0 1237 0 867 923 0 0 864 +455 300 0.998431636807789 0.0540479788514866 -0.0145973491904443 -1.43267922465891 -0.0534642033715402 0.997854377304709 0.0377918066739065 -0.0728809208382023 0.016608599554601 -0.0369520997495487 0.999179011361295 0.183297330692768 8.65801012765966e-05 -2.02449113292911e-05 1.77581960725919e-06 2.8645568292559e-06 1.18030241159941e-05 -5.36384176086799e-05 -2.02449113292911e-05 5.56960335858628e-05 7.38898064265104e-06 2.16325038999411e-07 -5.94395067142483e-06 3.12923074648293e-05 1.77581960725919e-06 7.38898064265104e-06 1.65312502853043e-05 -1.34530460175649e-06 7.71734359211061e-07 3.8351047926981e-06 2.8645568292559e-06 2.16325038999411e-07 -1.34530460175649e-06 0.0002099040703732 1.65071686831346e-05 3.20834074391565e-05 1.18030241159941e-05 -5.94395067142483e-06 7.71734359211061e-07 1.65071686831346e-05 1.77199004572111e-05 -1.77586170043946e-05 -5.36384176086799e-05 3.12923074648293e-05 3.8351047926981e-06 3.20834074391565e-05 -1.77586170043946e-05 0.000315857258806544 1157 1157 0 0 0 1159 1159 0 0 0 0 0 0 0 0 557 528 0 932 0 798 854 0 0 614 +456 459 0.997854081876529 0.000535140646564471 0.0654747654202595 0.341757536104475 -0.00198373460498233 0.999754648491438 0.0220614509218974 0.0555577427401444 -0.0654468951086804 -0.0221439934124513 0.997610318449234 -0.0549538617383747 4.59223759150833e-05 -1.15471163788673e-07 7.01829782679679e-06 4.204508499895e-06 1.82360099848498e-06 4.45130332589214e-06 -1.15471163788673e-07 4.10357351646275e-05 3.62456500011141e-06 2.44971293394982e-05 -1.32297418128823e-06 1.22365906371732e-06 7.01829782679679e-06 3.62456500011141e-06 1.38059955936054e-05 6.28571917172503e-07 2.67617979858049e-06 -5.31684917801536e-06 4.204508499895e-06 2.44971293394982e-05 6.28571917172503e-07 0.000234019977762679 -2.09623984982441e-06 7.9199003875457e-05 1.82360099848498e-06 -1.32297418128823e-06 2.67617979858049e-06 -2.09623984982441e-06 1.25835482426927e-05 6.4996907820193e-06 4.45130332589214e-06 1.22365906371732e-06 -5.31684917801536e-06 7.9199003875457e-05 6.4996907820193e-06 0.000203865839432067 3225 3221 0 379 488 3225 3221 0 312 559 0 0 0 0 0 0 0 0 3437 0 0 0 0 0 3264 +456 302 0.997393277290842 0.0647035627829658 0.0319389946339018 -1.29306048541922 -0.0655544412246239 0.997500939738025 0.0263531868563408 -0.0703943258822522 -0.0301540320813143 -0.0283782343522053 0.999142337289483 0.176990204394936 5.19094153911948e-05 -3.46759575127067e-05 1.01290176849318e-05 1.56025348135998e-05 3.84466058243285e-06 -1.95827719191117e-05 -3.46759575127067e-05 0.000109191742735024 2.54651269440122e-06 -0.000109922659928694 -1.88837103936236e-05 0.000160271196232265 1.01290176849318e-05 2.54651269440122e-06 1.72561420263687e-05 -1.23617120816531e-05 -1.4951748578501e-07 1.40959522020029e-05 1.56025348135998e-05 -0.000109922659928694 -1.23617120816531e-05 0.000343995837494876 4.10973358682159e-05 -0.000324605252393271 3.84466058243285e-06 -1.88837103936236e-05 -1.4951748578501e-07 4.10973358682159e-05 1.927929060358e-05 -6.01097692695789e-05 -1.95827719191117e-05 0.000160271196232265 1.40959522020029e-05 -0.000324605252393271 -6.01097692695789e-05 0.000761658665085383 1366 1366 0 0 0 1369 1369 0 0 0 0 0 0 0 0 563 533 0 1364 0 892 948 0 0 894 +456 304 0.99449152494877 0.0844354956997844 0.0621067940808481 -1.09779121568084 -0.0852944302474885 0.99629163573715 0.011306490567392 -0.0810298684178006 -0.0609218103295159 -0.0165415726618086 0.99800546561632 0.118940254384313 3.96553720502048e-05 -9.03442404281271e-06 1.61916448241688e-05 1.09377841545002e-05 6.76427079579317e-07 4.21291654403764e-06 -9.03442404281271e-06 5.70186266602223e-05 2.75552681432697e-06 -4.7350896309576e-06 -2.32363825235096e-06 -2.0321729161192e-05 1.61916448241688e-05 2.75552681432697e-06 1.70871754470945e-05 1.56630145888816e-06 2.65303600034295e-06 -3.40803818389584e-06 1.09377841545002e-05 -4.7350896309576e-06 1.56630145888816e-06 0.000204108534804055 1.3628197019511e-05 -6.52351282749715e-06 6.76427079579317e-07 -2.32363825235096e-06 2.65303600034295e-06 1.3628197019511e-05 1.48320498737668e-05 -3.43611154977255e-06 4.21291654403764e-06 -2.0321729161192e-05 -3.40803818389584e-06 -6.52351282749715e-06 -3.43611154977255e-06 0.000173522551735523 1605 1605 0 0 0 1608 1608 0 0 0 0 0 0 0 0 483 452 0 1967 0 1062 1132 0 0 1292 +456 305 0.990311376235055 0.122771692108101 0.0648882864340296 -1.00094109679038 -0.124835012339294 0.991760966341632 0.028747266571994 -0.0881363516104871 -0.0608243190975395 -0.0365690751595751 0.99747837317322 0.1167084423753 4.90078872802387e-05 -2.35676137170945e-05 7.89285848515711e-06 -4.45324944599715e-06 2.93639612411199e-06 -1.74203917479139e-05 -2.35676137170945e-05 7.62350348862952e-05 -5.76727359525677e-06 -1.13451728069042e-05 -4.171069352159e-06 8.89961971989175e-05 7.89285848515711e-06 -5.76727359525677e-06 1.60884963746957e-05 9.70229496259759e-07 2.38318620045915e-06 5.48109010575961e-06 -4.45324944599715e-06 -1.13451728069042e-05 9.70229496259759e-07 8.1831233249721e-05 1.105621212744e-07 3.86651150953391e-06 2.93639612411199e-06 -4.171069352159e-06 2.38318620045915e-06 1.105621212744e-07 1.31681849217936e-05 -1.09631552250335e-05 -1.74203917479139e-05 8.89961971989175e-05 5.48109010575961e-06 3.86651150953391e-06 -1.09631552250335e-05 0.000474041370504598 1671 1671 0 0 0 1670 1670 0 0 0 0 0 0 0 0 339 315 0 2301 0 1122 1199 0 0 1462 +457 461 0.997057557157873 0.0611197033026829 0.0462667221938894 0.487316805711496 -0.0612747172348405 0.998119057017575 0.00193831012419485 0.0555883740868579 -0.0460612281877597 -0.00476758707725759 0.998927241280012 -0.113042196703116 4.20145405247929e-05 -2.65605058232361e-06 1.03514131669781e-05 -3.46920530121778e-06 -2.35355057215635e-06 1.11612949065246e-06 -2.65605058232361e-06 0.000115732450173481 8.66428997663638e-07 7.4555970369052e-07 1.23196426127132e-06 -8.07756573471616e-05 1.03514131669781e-05 8.66428997663638e-07 1.54296616371098e-05 1.14527137902207e-06 7.6224132201061e-07 1.95403910687657e-06 -3.46920530121778e-06 7.4555970369052e-07 1.14527137902207e-06 0.000315732940165662 1.08566500136884e-05 -5.0311952948552e-05 -2.35355057215635e-06 1.23196426127132e-06 7.6224132201061e-07 1.08566500136884e-05 1.62008441005167e-05 -7.8194097314457e-06 1.11612949065246e-06 -8.07756573471616e-05 1.95403910687657e-06 -5.0311952948552e-05 -7.8194097314457e-06 0.00016941250590265 3238 3240 0 806 572 3238 3240 0 732 652 0 0 0 0 0 0 0 0 2969 0 0 0 0 0 3173 +457 318 0.422546605141488 0.901045395050423 0.097834362786446 -1.00207327404903 -0.906177053345457 0.417947271493402 0.0645230675136098 -0.423292970410897 0.0172486078727749 -0.115919257716943 0.99310886171497 0.125443889328998 5.3019365559836e-05 1.15203917315885e-05 1.30521761465499e-05 -6.93959495370774e-06 -1.00520222331545e-05 -1.90591181904524e-05 1.15203917315885e-05 5.5961132231564e-05 1.00603863041337e-05 -2.36791802751952e-06 -4.88079247662662e-06 -2.36180351316383e-05 1.30521761465499e-05 1.00603863041337e-05 1.69754658729161e-05 -2.24515847468063e-06 6.6227473972565e-07 1.57561645705977e-06 -6.93959495370774e-06 -2.36791802751952e-06 -2.24515847468063e-06 3.52264382913052e-05 4.29447068163758e-05 -1.34998025438675e-05 -1.00520222331545e-05 -4.88079247662662e-06 6.6227473972565e-07 4.29447068163758e-05 0.000141240759612175 -6.42013118747427e-05 -1.90591181904524e-05 -2.36180351316383e-05 1.57561645705977e-06 -1.34998025438675e-05 -6.42013118747427e-05 0.000204711346222552 0 0 0 1583 0 0 0 0 1576 0 0 0 0 0 0 0 0 0 1190 0 1278 1227 0 188 0 +458 306 0.978814961841145 0.204746735809466 -0.000211308509396171 -1.17929735040938 -0.204729685632657 0.978745770278762 0.0119362046809586 -0.108447344771916 0.00265071625617535 -0.0116400746046204 0.999928738644174 0.0637558122963353 4.4784824575667e-05 4.85232663524027e-06 1.16873494267478e-05 -7.43684721426595e-06 -4.86263139839077e-06 1.02097731920717e-07 4.85232663524027e-06 6.55892128572437e-05 3.3027961476202e-06 9.60933283782847e-06 3.57233200689862e-07 -3.96532450872755e-05 1.16873494267478e-05 3.3027961476202e-06 1.68879632540404e-05 -3.5376586206436e-06 -7.95261157669019e-08 -6.36336747060141e-06 -7.43684721426595e-06 9.60933283782847e-06 -3.5376586206436e-06 0.000573703915633157 0.000106979407945527 0.000112495057145166 -4.86263139839077e-06 3.57233200689862e-07 -7.95261157669019e-08 0.000106979407945527 3.67465655936116e-05 2.59104721555356e-05 1.02097731920717e-07 -3.96532450872755e-05 -6.36336747060141e-06 0.000112495057145166 2.59104721555356e-05 0.000167231963534731 1413 1413 0 0 0 1410 1410 0 0 0 0 0 0 0 0 212 199 0 1982 0 1347 1435 0 0 798 +458 318 0.418165791177165 0.906565220772268 0.0572439654051436 -1.14779176728725 -0.908134400707219 0.415788669678917 0.0491089851124721 -0.437345138900139 0.0207191057074397 -0.0725209118307693 0.997151661486816 0.0633050837648927 4.81189569236441e-05 1.05733405275389e-05 5.97678193410946e-06 1.44861063183939e-06 1.7866977510539e-06 1.20075263601388e-05 1.05733405275389e-05 5.36740473572632e-05 1.35389581642041e-05 -8.00315882859019e-07 -7.56004628711025e-06 -1.45892404376382e-05 5.97678193410946e-06 1.35389581642041e-05 1.64757186660264e-05 -3.01834482783034e-06 -1.15934965358128e-06 -7.50630924204815e-06 1.44861063183939e-06 -8.00315882859019e-07 -3.01834482783034e-06 2.91721743126166e-05 3.0195499953864e-05 2.96237626868779e-07 1.7866977510539e-06 -7.56004628711025e-06 -1.15934965358128e-06 3.0195499953864e-05 0.000104859703140348 -1.81497143794786e-05 1.20075263601388e-05 -1.45892404376382e-05 -7.50630924204815e-06 2.96237626868779e-07 -1.81497143794786e-05 0.000179653542856445 0 0 0 1495 0 0 0 0 1489 0 0 0 0 0 0 0 0 0 1289 0 1278 1227 0 227 0 +458 307 0.96177139769821 0.273168698845051 -0.0193556333126445 -1.124133187838 -0.273150043068126 0.961964507695227 0.00365238368211472 -0.122494988940108 0.0196171491688536 0.00177423391408209 0.999805990956498 0.0597115501654416 4.24814326312635e-05 -5.93516378795645e-06 3.67837392911129e-06 4.72468556055449e-06 2.03567950396272e-06 5.62909706250615e-06 -5.93516378795645e-06 5.84375283230937e-05 1.67849061347275e-07 1.02178462443347e-05 1.70114026320221e-06 3.65184062066706e-05 3.67837392911129e-06 1.67849061347275e-07 1.27599121075943e-05 -4.34605437767346e-06 3.72401999138369e-06 8.70701236927362e-07 4.72468556055449e-06 1.02178462443347e-05 -4.34605437767346e-06 6.94186837491352e-05 5.2190359018672e-06 0.000128916943734446 2.03567950396272e-06 1.70114026320221e-06 3.72401999138369e-06 5.2190359018672e-06 1.36212182339044e-05 2.33085050204054e-05 5.62909706250615e-06 3.65184062066706e-05 8.70701236927362e-07 0.000128916943734446 2.33085050204054e-05 0.000496973678300798 1511 1511 0 0 0 1509 1509 0 0 0 0 0 0 0 0 23 20 0 2282 0 1484 1580 0 0 768 +458 320 0.188419797631596 0.981007462159032 0.0460688511769371 -1.26426523275273 -0.980934550667959 0.185717806869328 0.0572390034635138 -0.542126723433334 0.0475960835186836 -0.0559754892782674 0.997297025681788 0.106774349128303 4.98362417562295e-05 1.76963066388006e-05 5.00647527964832e-06 -7.45343831664865e-07 8.22433582501269e-06 -2.67596759765923e-06 1.76963066388006e-05 7.4612817277067e-05 4.73181802890322e-06 -8.4613428449961e-06 -1.05218104978727e-05 -4.72914215164016e-05 5.00647527964832e-06 4.73181802890322e-06 1.56736125727505e-05 -2.75020225856518e-06 -1.67638764228587e-06 -3.17720012095857e-06 -7.45343831664865e-07 -8.4613428449961e-06 -2.75020225856518e-06 1.78426963616949e-05 1.65581338690553e-05 9.56528335797734e-06 8.22433582501269e-06 -1.05218104978727e-05 -1.67638764228587e-06 1.65581338690553e-05 0.000185424314057761 -1.8329831286596e-05 -2.67596759765923e-06 -4.72914215164016e-05 -3.17720012095857e-06 9.56528335797734e-06 -1.8329831286596e-05 0.000172789044856058 0 0 0 1377 0 0 0 0 1363 0 0 0 0 0 0 0 0 0 636 0 142 18 0 932 0 +459 309 0.91874356195371 0.39400163517454 -0.0259418358717683 -1.14228516790139 -0.392910676576883 0.918756388517403 0.0388316725155479 -0.195768627723153 0.0391339699047452 -0.0254835248395315 0.998908966003032 0.0424906774478146 5.05597444381047e-05 -9.35177805243196e-06 2.07385378429899e-06 -1.47708432292358e-06 2.03216553221963e-06 7.13031765257063e-07 -9.35177805243196e-06 4.65830245261811e-05 3.08976023807216e-06 -8.49215644447173e-06 -1.35892729867677e-06 -3.15932765781891e-05 2.07385378429899e-06 3.08976023807216e-06 1.59355267855469e-05 -3.45963607266332e-06 1.59903430376364e-06 -5.23653161164844e-06 -1.47708432292358e-06 -8.49215644447173e-06 -3.45963607266332e-06 3.21270658020511e-05 -1.97171393493736e-06 3.85162432941975e-05 2.03216553221963e-06 -1.35892729867677e-06 1.59903430376364e-06 -1.97171393493736e-06 1.39368494556768e-05 1.02678692508783e-05 7.13031765257063e-07 -3.15932765781891e-05 -5.23653161164844e-06 3.85162432941975e-05 1.02678692508783e-05 0.000168556787616405 1213 1228 0 268 0 1229 1244 0 249 0 0 0 0 0 0 0 0 0 2093 0 1880 1999 0 0 415 +459 318 0.441406749833661 0.896555372100803 0.0367225538119774 -1.24028000080002 -0.896750439434878 0.439321956884909 0.053243474456203 -0.484416544446722 0.0316026988505314 -0.0564329952776258 0.997906101028227 0.0382379058928935 4.97957889130743e-05 8.57388117152782e-06 8.02593747719294e-06 -2.41470521877576e-06 -4.37310671172382e-06 -1.02371943590407e-05 8.57388117152782e-06 4.29303836132931e-05 7.07873893413579e-06 -3.3057719122082e-06 -4.92309334755519e-06 -3.36416595976931e-05 8.02593747719294e-06 7.07873893413579e-06 1.49282899356432e-05 -4.0294843332513e-06 -2.42957969019291e-06 -5.21993864577532e-06 -2.41470521877576e-06 -3.3057719122082e-06 -4.0294843332513e-06 2.8786191247061e-05 3.46676756990136e-05 4.12870746346241e-07 -4.37310671172382e-06 -4.92309334755519e-06 -2.42957969019291e-06 3.46676756990136e-05 0.000119342002127634 -1.29639331357002e-05 -1.02371943590407e-05 -3.36416595976931e-05 -5.21993864577532e-06 4.12870746346241e-07 -1.29639331357002e-05 0.000100226341935074 0 0 0 1339 0 0 0 0 1333 0 0 0 0 0 0 0 0 0 1329 0 1278 1227 0 254 0 +459 305 0.992507443375342 0.121563696707177 -0.0122980684429885 -1.39892413486196 -0.12156139712135 0.992583471831325 0.000937111081128134 -0.151862623852552 0.012320778159208 0.000564880658534484 0.999923936774889 0.0285919197273503 3.79856636477226e-05 -1.64411158704897e-05 5.19754784439568e-06 1.95288380836474e-06 8.29393211050504e-07 5.59799761765406e-06 -1.64411158704897e-05 5.98523352093257e-05 2.18476635156686e-06 -3.00778993499202e-06 -1.87896859957608e-08 -2.45405108764988e-05 5.19754784439568e-06 2.18476635156686e-06 1.3226070856265e-05 -4.98665665085461e-06 3.34182424171968e-06 1.58164111894789e-06 1.95288380836474e-06 -3.00778993499202e-06 -4.98665665085461e-06 6.777432940871e-05 2.58188677578911e-07 -1.02632256106578e-05 8.29393211050504e-07 -1.87896859957608e-08 3.34182424171968e-06 2.58188677578911e-07 1.24130235357653e-05 -8.84927268171387e-06 5.59799761765406e-06 -2.45405108764988e-05 1.58164111894789e-06 -1.02632256106578e-05 -8.84927268171387e-06 0.000220355811348142 1311 1311 0 0 0 1308 1308 0 0 0 0 0 0 0 0 435 415 0 1225 0 1250 1327 0 0 518 +459 307 0.967919092513834 0.249213328831488 -0.0320210412061433 -1.26127569458831 -0.249056598189527 0.968448428674775 0.00885730747006982 -0.169407925023534 0.0332180861197198 -0.000598105415257247 0.999447948131595 0.0724684427923689 5.11055095755754e-05 2.69921413565571e-06 1.33773289881906e-05 3.53745677257897e-06 -1.58377265506282e-06 -3.39580979225032e-06 2.69921413565571e-06 5.80087025198699e-05 4.93530813552115e-06 -8.2310182349736e-06 -3.16063300000636e-06 -6.02232786737247e-06 1.33773289881906e-05 4.93530813552115e-06 1.79276428023879e-05 -9.79171754609865e-07 2.00192371282495e-06 -9.32942121781854e-06 3.53745677257897e-06 -8.2310182349736e-06 -9.79171754609865e-07 3.43604204682819e-05 -2.77031205426013e-06 -3.99516261161987e-05 -1.58377265506282e-06 -3.16063300000636e-06 2.00192371282495e-06 -2.77031205426013e-06 1.39451291480215e-05 -1.75928569184291e-05 -3.39580979225032e-06 -6.02232786737247e-06 -9.32942121781854e-06 -3.99516261161987e-05 -1.75928569184291e-05 0.000325645757510875 1389 1389 0 0 0 1385 1385 0 0 0 0 0 0 0 0 89 86 0 1792 0 1482 1578 0 0 518 +459 306 0.983819667959181 0.178120897766474 -0.0192822902050851 -1.33174526025195 -0.17798585826698 0.983996157823344 0.00852030785022621 -0.160825966153966 0.0204913443593674 -0.0049504714686145 0.999777774127123 0.048692836526156 4.25656240941126e-05 -1.76800742685699e-05 9.5430462710289e-06 -7.48463697277046e-06 -1.12747989551268e-06 1.41276146974039e-05 -1.76800742685699e-05 9.60490784058985e-05 7.81838596793324e-07 4.97760659766902e-05 8.92976630243037e-06 1.79104095406411e-05 9.5430462710289e-06 7.81838596793324e-07 1.40525856111746e-05 -1.3391226546485e-07 3.42868714634772e-06 2.26682785986532e-06 -7.48463697277046e-06 4.97760659766902e-05 -1.3391226546485e-07 0.00019970296979683 2.14997970556741e-05 0.000188564887932998 -1.12747989551268e-06 8.92976630243037e-06 3.42868714634772e-06 2.14997970556741e-05 1.61309955310574e-05 2.28316675168169e-05 1.41276146974039e-05 1.79104095406411e-05 2.26682785986532e-06 0.000188564887932998 2.28316675168169e-05 0.000507770917791494 1422 1422 0 0 0 1422 1422 0 0 0 0 0 0 0 0 271 258 0 1511 0 1369 1457 0 0 518 +460 463 0.999564811245338 0.00780412939934054 0.0284479117755602 0.378026381713293 -0.00777334013176197 0.999969075805838 -0.00119273434355943 0.0383404677923215 -0.0284563402999691 0.000971079984716032 0.999594564661291 0.00676842889265217 6.15113856280444e-05 -8.49876717630195e-06 -5.585596899989e-06 -1.53604048472946e-05 7.46539776075528e-07 -3.30829037031433e-06 -8.49876717630195e-06 0.00023257926743238 3.80911361224111e-06 -2.09949051726582e-05 -1.03151639969626e-06 -0.000116924029551743 -5.585596899989e-06 3.80911361224111e-06 1.4567816037226e-05 -1.49909433058001e-06 2.74778203945639e-06 -7.03248025749243e-07 -1.53604048472946e-05 -2.09949051726582e-05 -1.49909433058001e-06 0.00020395187393538 1.72876140090809e-06 5.6613680665315e-05 7.46539776075528e-07 -1.03151639969626e-06 2.74778203945639e-06 1.72876140090809e-06 1.29951138016134e-05 5.10877204535647e-06 -3.30829037031433e-06 -0.000116924029551743 -7.03248025749243e-07 5.6613680665315e-05 5.10877204535647e-06 0.000559702575224066 3224 3224 0 473 497 3224 3224 0 412 560 0 0 0 0 0 0 0 0 3300 0 0 0 0 0 3266 +460 313 0.785540928599294 0.618544985267878 -0.0180983616749985 -1.17967794841584 -0.616505103646875 0.784802393666686 0.0632981838001328 -0.338929991826406 0.0533564117301208 -0.0385655817407216 0.997830541340706 0.0339990112781292 4.65534613549992e-05 -3.84034938599341e-06 3.38237006075278e-06 -5.87667066218683e-06 -4.33462790493102e-06 2.07960255919614e-05 -3.84034938599341e-06 3.79881569455301e-05 9.81881755827101e-07 -1.43916316282634e-06 1.3460753734808e-06 -1.65512832666095e-05 3.38237006075278e-06 9.81881755827101e-07 1.56021606301291e-05 -2.89465179260269e-06 2.22516115389103e-06 -3.58608429123399e-06 -5.87667066218683e-06 -1.43916316282634e-06 -2.89465179260269e-06 3.75995683613882e-05 1.36430583358909e-05 2.64809315173677e-07 -4.33462790493102e-06 1.3460753734808e-06 2.22516115389103e-06 1.36430583358909e-05 3.01611015080986e-05 -5.1618614220969e-06 2.07960255919614e-05 -1.65512832666095e-05 -3.58608429123399e-06 2.64809315173677e-07 -5.1618614220969e-06 0.000132400777705392 668 677 0 822 0 681 690 0 809 0 0 0 0 0 0 0 0 0 1866 0 2658 2658 0 0 0 +460 307 0.97416791829053 0.222145284828359 -0.0405997463295291 -1.39061994534875 -0.221487071315947 0.974956019935798 0.020105631818804 -0.224253769025316 0.044049338398883 -0.0105939425841423 0.998973184908957 0.0903508564465714 4.59148133440802e-05 -8.14230673895881e-06 3.87111142793101e-08 4.86628156434157e-07 2.85412658030062e-06 -8.64395281837637e-07 -8.14230673895881e-06 3.76137914370377e-05 1.39505749692e-06 -2.00110928846523e-06 -1.01686516770911e-06 -2.2682126451518e-05 3.87111142793101e-08 1.39505749692e-06 1.49418968923241e-05 -9.63793486857238e-07 2.44897896223145e-06 6.94675381958596e-07 4.86628156434157e-07 -2.00110928846523e-06 -9.63793486857238e-07 2.62930925562134e-05 -6.18246438842469e-06 1.30460521607246e-05 2.85412658030062e-06 -1.01686516770911e-06 2.44897896223145e-06 -6.18246438842469e-06 1.1638348386354e-05 4.01020411980014e-07 -8.64395281837637e-07 -2.2682126451518e-05 6.94675381958596e-07 1.30460521607246e-05 4.01020411980014e-07 0.000135453237610349 1314 1314 0 0 0 1310 1310 0 0 0 0 0 0 0 0 154 151 0 1437 0 1497 1593 0 0 363 +460 306 0.98822053398565 0.149813394653745 -0.0312429670716188 -1.4576136486633 -0.149254647945685 0.988606061756997 0.0195219036963414 -0.218980494169825 0.033811629297129 -0.0146287880441619 0.999321155727543 0.0269530206050643 3.79756298074351e-05 -1.83782570268542e-05 4.36965143938568e-06 6.46868969709626e-06 1.97319876708124e-06 1.0520861038425e-05 -1.83782570268542e-05 7.2676767183977e-05 2.33220231547495e-06 7.06645550427874e-06 -2.64053564098546e-07 6.74820839652963e-06 4.36965143938568e-06 2.33220231547495e-06 1.3827467155677e-05 -2.04538786689275e-06 4.40297302334193e-06 4.62985978941517e-06 6.46868969709626e-06 7.06645550427874e-06 -2.04538786689275e-06 0.000114586242337123 9.39046305403773e-06 8.65673745234094e-05 1.97319876708124e-06 -2.64053564098546e-07 4.40297302334193e-06 9.39046305403773e-06 1.35682794346031e-05 3.42301582869971e-06 1.0520861038425e-05 6.74820839652963e-06 4.62985978941517e-06 8.65673745234094e-05 3.42301582869971e-06 0.000391038328181467 1240 1240 0 0 0 1241 1241 0 0 0 0 0 0 0 0 296 285 0 1139 0 1414 1502 0 0 386 +460 318 0.466440681903675 0.884104846907917 0.0281373406554962 -1.34112962134974 -0.883441280702965 0.464025036460913 0.0649019960197901 -0.537554525470721 0.044323738731515 -0.0551306195446477 0.997494872655235 0.0620325199425672 4.95232253701192e-05 1.23187062244173e-05 1.91771245711796e-06 9.30583844043147e-07 7.23140155261698e-06 4.91801901970729e-06 1.23187062244173e-05 5.52501716963256e-05 9.95510686018775e-06 5.78229222300268e-06 1.46344398097909e-05 -3.82617944793181e-05 1.91771245711796e-06 9.95510686018775e-06 1.76196711367305e-05 1.86567305616118e-07 5.06824613069987e-06 -1.3164142369542e-05 9.30583844043147e-07 5.78229222300268e-06 1.86567305616118e-07 4.23537466001919e-05 5.74933802664214e-05 1.35678156423489e-05 7.23140155261698e-06 1.46344398097909e-05 5.06824613069987e-06 5.74933802664214e-05 0.000153374427119368 2.89524426742438e-05 4.91801901970729e-06 -3.82617944793181e-05 -1.3164142369542e-05 1.35678156423489e-05 2.89524426742438e-05 0.000127449914928972 0 0 0 1198 0 0 0 0 1192 0 0 0 0 0 0 0 0 0 1370 0 1278 1227 0 269 0 +460 302 0.998586180653815 0.0342698367925562 -0.040635182950711 -1.80605925672667 -0.0339769267558337 0.999391573000736 0.00787732590048997 -0.204579331526812 0.0408804140812553 -0.00648553014990944 0.999142997595049 0.117030602966115 4.46062492992663e-05 -1.67433575559852e-05 6.92445460191298e-08 -6.15873860457436e-06 2.50082086179363e-08 1.95155548684326e-05 -1.67433575559852e-05 6.30141817403554e-05 1.47274036800711e-08 -4.11224932348859e-05 -1.60755567959591e-06 -4.6999907863108e-05 6.92445460191298e-08 1.47274036800711e-08 1.63488563190058e-05 9.61131347436901e-07 2.17851162282906e-06 5.73895153314714e-07 -6.15873860457436e-06 -4.11224932348859e-05 9.61131347436901e-07 0.000462456638372009 3.62389236994187e-05 -4.92339256170521e-05 2.50082086179363e-08 -1.60755567959591e-06 2.17851162282906e-06 3.62389236994187e-05 1.59833387537603e-05 -9.09297093601422e-06 1.95155548684326e-05 -4.6999907863108e-05 5.73895153314714e-07 -4.92339256170521e-05 -9.09297093601422e-06 0.000117160767618449 1018 1018 0 0 0 1017 1017 0 0 0 0 0 0 0 0 619 589 0 279 0 1057 1121 0 0 78 +460 322 0.0354430722045205 0.999371106241799 -0.00108657339712022 -1.60620550420532 -0.9957647490021 0.035407421037219 0.0848462089917864 -0.746761406262078 0.0848313225023042 -0.00192523882551995 0.996393466547214 0.132530160489697 5.41100443397643e-05 1.80325609210712e-06 1.24273611044601e-06 -6.79082617193143e-06 -1.76865551964443e-05 -1.34702227749561e-05 1.80325609210712e-06 5.7096291500541e-05 1.20119444275034e-05 7.36395638476037e-07 5.16164793499308e-05 -2.42435968173675e-05 1.24273611044601e-06 1.20119444275034e-05 1.73306058533125e-05 -7.84666069068026e-07 -1.33870305979659e-05 -8.78299378520914e-06 -6.79082617193143e-06 7.36395638476037e-07 -7.84666069068026e-07 1.6920564558669e-05 -8.6126251942334e-05 2.81862819159067e-06 -1.76865551964443e-05 5.16164793499308e-05 -1.33870305979659e-05 -8.6126251942334e-05 0.00376039178210479 0.000308498563875879 -1.34702227749561e-05 -2.42435968173675e-05 -8.78299378520914e-06 2.81862819159067e-06 0.000308498563875879 0.000176678584790996 0 0 0 1008 0 0 0 0 1002 0 0 0 0 0 0 0 0 0 323 0 0 0 0 870 0 +460 320 0.239693168904274 0.970671245413863 0.0185611989733362 -1.47166932863144 -0.968809960456892 0.237907750837414 0.0693337047257595 -0.64955990991057 0.0628843804147179 -0.034601089840981 0.997420833591154 0.104973138727951 4.49577926330436e-05 1.69598715847489e-05 6.39730879417435e-06 -3.32041486503216e-07 -3.90798758912255e-06 5.59613396965972e-06 1.69598715847489e-05 5.12513456787579e-05 1.28876007414203e-05 -1.35715345216403e-06 -1.38513634942077e-05 -1.28155931889822e-05 6.39730879417435e-06 1.28876007414203e-05 1.75279931163188e-05 -3.21093018395677e-06 -7.01880353353795e-06 -8.15030232184993e-06 -3.32041486503216e-07 -1.35715345216403e-06 -3.21093018395677e-06 1.49041941597613e-05 1.15286590832013e-05 -1.39682830485907e-07 -3.90798758912255e-06 -1.38513634942077e-05 -7.01880353353795e-06 1.15286590832013e-05 0.000180724668864423 -3.66380660569528e-05 5.59613396965972e-06 -1.28155931889822e-05 -8.15030232184993e-06 -1.39682830485907e-07 -3.66380660569528e-05 0.000144318000176423 0 0 0 1174 0 0 0 0 1170 0 0 0 0 0 0 0 0 0 755 0 142 18 0 957 0 +461 313 0.790852334521014 0.611659382962544 -0.0206248446428489 -1.29687483057297 -0.609598385915037 0.790279340699392 0.0620352444463348 -0.366273464662996 0.0542438279663538 -0.0364878458889366 0.997860834099596 0.0379338454946464 4.87299716408729e-05 -7.55109236645515e-06 1.49214805564647e-06 -4.8145314416511e-06 -1.75912505932791e-06 6.75734510752586e-06 -7.55109236645515e-06 3.5596238989052e-05 -2.70685428493788e-07 -6.29064440289698e-06 -4.40962175080712e-06 -1.21364449893352e-05 1.49214805564647e-06 -2.70685428493788e-07 1.5472625892846e-05 1.09705584083664e-06 4.22940679680374e-06 -4.57151124323644e-06 -4.8145314416511e-06 -6.29064440289698e-06 1.09705584083664e-06 5.16525153714795e-05 2.73532415799178e-05 -2.37234658969847e-05 -1.75912505932791e-06 -4.40962175080712e-06 4.22940679680374e-06 2.73532415799178e-05 4.40245148829296e-05 -2.93163394716788e-05 6.75734510752586e-06 -1.21364449893352e-05 -4.57151124323644e-06 -2.37234658969847e-05 -2.93163394716788e-05 0.000147616302620122 577 589 0 755 0 591 603 0 741 0 0 0 0 0 0 0 0 0 1628 0 2477 2477 0 0 0 +461 463 0.999313870992689 -0.00273141580672899 0.0369367920818399 0.234172878852877 0.00289227738020758 0.999986562308136 -0.00430231736537134 0.0232935515614293 -0.0369245443189521 0.00440619686886404 0.999308342532969 0.0183931784140215 4.31783886729496e-05 -2.3713891788497e-05 1.52742131491653e-06 5.76723371886349e-06 -2.28725362884165e-06 1.49352546962485e-05 -2.3713891788497e-05 0.000134139486403631 7.295236419253e-07 -5.18907282239205e-05 -7.73236400135812e-07 -0.000100047908402608 1.52742131491653e-06 7.295236419253e-07 1.33480210653824e-05 -4.46376999937224e-06 3.24528118586831e-06 -5.00839061285706e-06 5.76723371886349e-06 -5.18907282239205e-05 -4.46376999937224e-06 0.000186943913994491 2.30226046811916e-06 -3.18292806993253e-07 -2.28725362884165e-06 -7.73236400135812e-07 3.24528118586831e-06 2.30226046811916e-06 1.15596807756972e-05 8.61629282694563e-07 1.49352546962485e-05 -0.000100047908402608 -5.00839061285706e-06 -3.18292806993253e-07 8.61629282694563e-07 0.000343333747398012 3191 3191 0 246 285 3191 3191 0 179 341 0 0 0 0 0 0 0 0 3539 0 0 0 0 0 3491 +461 308 0.958834579431841 0.279190442036057 -0.0518550514557207 -1.44545634643988 -0.27765931116708 0.960047558903813 0.0348423817362172 -0.268943720070655 0.0595109755254198 -0.0190100425707205 0.998046623196268 0.0560465615840843 4.66932476587795e-05 -6.9476865721174e-06 -5.9098420604331e-07 -3.22969314431589e-07 -6.34597739225797e-07 2.60776833991336e-05 -6.9476865721174e-06 5.01435140817639e-05 1.12125785010823e-06 -3.69414169035975e-06 -1.07587715321014e-06 -2.95073854898633e-05 -5.9098420604331e-07 1.12125785010823e-06 1.3182351997158e-05 -2.91300419836565e-06 4.28685725381999e-06 -2.62068281978583e-06 -3.22969314431589e-07 -3.69414169035975e-06 -2.91300419836565e-06 5.5749193517144e-05 5.34249357404055e-06 2.81141217983135e-05 -6.34597739225797e-07 -1.07587715321014e-06 4.28685725381999e-06 5.34249357404055e-06 1.3368558637298e-05 1.11895680530488e-05 2.60776833991336e-05 -2.95073854898633e-05 -2.62068281978583e-06 2.81141217983135e-05 1.11895680530488e-05 0.000111464458644782 1133 1134 0 0 0 1132 1132 0 0 0 0 0 0 0 0 16 20 0 1392 0 1707 1813 0 0 103 +461 306 0.989778301964671 0.140041323159164 -0.0269692559734873 -1.57179419106708 -0.13959624460051 0.990049533188667 0.0177428950945628 -0.250811236700398 0.0291856377927136 -0.013796725725065 0.9994787886223 0.0732650297220168 4.59959037470622e-05 -2.63611560534867e-05 2.94959783449611e-06 2.95256916473253e-06 -1.57423383977162e-07 -2.59474777103011e-05 -2.63611560534867e-05 8.54118239766451e-05 3.57696626121955e-07 -1.397568464817e-05 -4.27831279118701e-06 2.77011547976238e-05 2.94959783449611e-06 3.57696626121955e-07 1.37167465265135e-05 -3.30424521462828e-06 3.62780930952309e-06 -8.64410582415416e-06 2.95256916473253e-06 -1.397568464817e-05 -3.30424521462828e-06 4.42988604205084e-05 -3.11604823344911e-06 1.41347559854679e-05 -1.57423383977162e-07 -4.27831279118701e-06 3.62780930952309e-06 -3.11604823344911e-06 1.15045290654795e-05 -8.57524054816507e-06 -2.59474777103011e-05 2.77011547976238e-05 -8.64410582415416e-06 1.41347559854679e-05 -8.57524054816507e-06 0.000505475744944943 1133 1133 0 0 0 1136 1136 0 0 0 0 0 0 0 0 333 322 0 917 0 1439 1527 0 0 213 +461 307 0.976354248870396 0.211913498782075 -0.0427206009632955 -1.51151914349451 -0.211355134483014 0.977257270547478 0.0172404840349798 -0.256911002729056 0.0454025091860872 -0.00780360147834225 0.998938294372367 0.103754668346541 3.82114006696511e-05 -2.37293085187046e-06 3.53962993323009e-06 2.23778560185164e-06 -9.72509862977139e-07 7.70215677017988e-06 -2.37293085187046e-06 5.61592559695189e-05 5.74105527218159e-06 -9.04753839023583e-06 -3.33000749502247e-06 -2.13440758619537e-05 3.53962993323009e-06 5.74105527218159e-06 1.47222154498392e-05 -5.68440987806072e-06 2.55084459805692e-06 -9.80784521429397e-07 2.23778560185164e-06 -9.04753839023583e-06 -5.68440987806072e-06 5.32292513995652e-05 3.86160512587703e-06 -6.88157368489595e-07 -9.72509862977139e-07 -3.33000749502247e-06 2.55084459805692e-06 3.86160512587703e-06 1.43136911411472e-05 -6.17463265565992e-06 7.70215677017988e-06 -2.13440758619537e-05 -9.80784521429397e-07 -6.88157368489595e-07 -6.17463265565992e-06 0.000157218053347796 1193 1193 0 0 0 1192 1192 0 0 0 0 0 0 0 0 162 159 0 1173 0 1525 1621 0 0 163 +461 320 0.249434597676602 0.968275609801645 0.0149908287017239 -1.5919233516538 -0.966379711528163 0.247889199934455 0.0682729646536689 -0.682663854219653 0.0623909819497726 -0.0315164721869169 0.997554047333895 0.117156907132414 4.81489802132732e-05 9.34803292235634e-06 1.97976811359028e-06 -9.95339606503569e-07 -5.19082143620359e-07 2.24162478862888e-06 9.34803292235634e-06 4.47160943899681e-05 1.2390053669833e-05 1.89606653211628e-06 -2.27292994561598e-06 -2.15549746297226e-05 1.97976811359028e-06 1.2390053669833e-05 1.96149340558328e-05 5.37834890720377e-07 8.99891272953272e-07 -8.63929956226965e-06 -9.95339606503569e-07 1.89606653211628e-06 5.37834890720377e-07 1.43206027433637e-05 -4.79209141835479e-06 1.121081636325e-06 -5.19082143620359e-07 -2.27292994561598e-06 8.99891272953272e-07 -4.79209141835479e-06 4.89832733905802e-05 -9.54935097836203e-06 2.24162478862888e-06 -2.15549746297226e-05 -8.63929956226965e-06 1.121081636325e-06 -9.54935097836203e-06 9.75297691067302e-05 0 0 0 1102 0 0 0 0 1097 0 0 0 0 0 0 0 0 0 799 0 142 18 0 979 0 +461 303 0.998977127920483 0.021683223789605 -0.0396804195773218 -1.82623733444339 -0.0219817259970991 0.999733148202994 -0.00710183823525656 -0.238479962056027 0.039515840038279 0.00796681807381109 0.999187183762806 0.106010687139333 3.94351626906611e-05 -1.14644195588884e-05 2.8530954952149e-06 -1.84833810291723e-06 -6.83452891702148e-07 1.4259146932259e-05 -1.14644195588884e-05 8.47265397511219e-05 2.58233924575566e-06 8.81254356427076e-06 1.45507482919515e-06 -2.98437472403962e-05 2.8530954952149e-06 2.58233924575566e-06 1.48256003256374e-05 1.35668573842951e-06 4.0123163241101e-06 -4.1383760761866e-06 -1.84833810291723e-06 8.81254356427076e-06 1.35668573842951e-06 0.000219253582124989 8.0264468505248e-06 7.19668613677633e-05 -6.83452891702148e-07 1.45507482919515e-06 4.0123163241101e-06 8.0264468505248e-06 1.21381394207247e-05 6.69411966605475e-06 1.4259146932259e-05 -2.98437472403962e-05 -4.1383760761866e-06 7.19668613677633e-05 6.69411966605475e-06 0.00020141964686284 894 894 0 0 0 895 895 0 0 0 0 0 0 0 0 622 595 0 224 0 1121 1186 0 0 96 +462 309 0.93454818353578 0.351639178741049 -0.0544938585924524 -1.50986090703938 -0.349060132442917 0.935681698249906 0.0515439957619252 -0.303630877099542 0.0691137944907316 -0.0291487141138761 0.997182849770593 0.0595949061676262 4.25745845710606e-05 -1.14374290208933e-05 1.14184192035789e-06 6.39376623518514e-06 1.04076254188386e-06 6.41601394888857e-06 -1.14374290208933e-05 4.75360687577052e-05 2.94278113174444e-07 -7.68720709371926e-10 2.81867435551206e-06 -1.51969997355889e-05 1.14184192035789e-06 2.94278113174444e-07 1.41617949629557e-05 -4.33639420584951e-06 1.86071284972293e-06 -4.49702181317815e-06 6.39376623518514e-06 -7.68720709371926e-10 -4.33639420584951e-06 0.000101985621934462 2.71969495621061e-05 9.30891487290217e-05 1.04076254188386e-06 2.81867435551206e-06 1.86071284972293e-06 2.71969495621061e-05 2.51940675685125e-05 3.07828572936459e-05 6.41601394888857e-06 -1.51969997355889e-05 -4.49702181317815e-06 9.30891487290217e-05 3.07828572936459e-05 0.000230726045411796 1017 1032 0 131 0 1026 1041 0 121 0 0 0 0 0 0 0 0 0 1301 0 1875 1883 0 0 0 +462 318 0.480975747763656 0.876641243440472 0.0127459939720396 -1.61698741826315 -0.875116015054115 0.479154644423328 0.0676962844132566 -0.595699422352207 0.0532380527348426 -0.0437144944692023 0.997624554987649 0.0600430723180964 5.08165654562485e-05 -4.9774652174486e-07 4.29029225985456e-07 -3.63043560256269e-06 -7.95681057035283e-06 2.92534752941441e-06 -4.9774652174486e-07 3.75393501303883e-05 6.07175926459854e-06 -3.18859575865194e-06 -4.39557773391194e-06 -2.39898870522836e-05 4.29029225985456e-07 6.07175926459854e-06 1.46227725616541e-05 -3.4665968048657e-06 2.98434866014874e-06 -1.72510945267079e-06 -3.63043560256269e-06 -3.18859575865194e-06 -3.4665968048657e-06 1.61637107353914e-05 3.8768343082348e-06 7.28172003040237e-06 -7.95681057035283e-06 -4.39557773391194e-06 2.98434866014874e-06 3.8768343082348e-06 3.99442647486616e-05 -1.21423495512713e-05 2.92534752941441e-06 -2.39898870522836e-05 -1.72510945267079e-06 7.28172003040237e-06 -1.21423495512713e-05 0.000169634205399551 0 0 0 1070 0 0 0 0 1062 0 0 0 0 0 0 0 0 0 1164 0 1275 1224 0 323 0 +462 320 0.255641950368479 0.966754926167276 -0.00566621064782352 -1.73981426250771 -0.963609742474955 0.25527513011072 0.0793150184662776 -0.710707198591912 0.0781246274816802 -0.0148162302310731 0.996833497582514 0.0778176446249928 5.27016719242304e-05 1.38581499549013e-06 3.27230342317578e-06 1.83402077471951e-06 1.32443948937571e-05 -7.77257460764829e-06 1.38581499549013e-06 4.42420895130532e-05 8.10273584267492e-06 3.0860152294897e-06 9.38715451500242e-06 -1.74895587154549e-05 3.27230342317578e-06 8.10273584267492e-06 1.60929579229407e-05 -7.32648475017622e-07 8.76207496018933e-06 -3.73929045757104e-06 1.83402077471951e-06 3.0860152294897e-06 -7.32648475017622e-07 2.32675991890844e-05 4.95756848118631e-05 2.73965115412751e-06 1.32443948937571e-05 9.38715451500242e-06 8.76207496018933e-06 4.95756848118631e-05 0.0003422488710633 -2.703820176945e-05 -7.77257460764829e-06 -1.74895587154549e-05 -3.73929045757104e-06 2.73965115412751e-06 -2.703820176945e-05 0.000116037743997062 0 0 0 974 0 0 0 0 971 0 0 0 0 0 0 0 0 0 791 0 107 11 0 997 0 +462 306 0.990186462439399 0.132617285318761 -0.044084296937021 -1.69152230529045 -0.131896940925477 0.991083643918942 0.0188787640181284 -0.277068519696726 0.0461948760822051 -0.0128789126494953 0.998849421601032 0.0763674915265057 5.04794979860681e-05 -1.69342926732351e-05 3.51758364750423e-07 -3.65058256210441e-06 1.4514706972975e-06 8.19468350654197e-06 -1.69342926732351e-05 8.49510643606037e-05 1.73264527274932e-08 -9.51427360187029e-06 -6.43082292787718e-07 -6.39721598121501e-05 3.51758364750423e-07 1.73264527274932e-08 1.36036700848558e-05 -4.32634616259443e-06 2.77271947465016e-06 -2.38044859954785e-06 -3.65058256210441e-06 -9.51427360187029e-06 -4.32634616259443e-06 5.48472223733786e-05 3.9885495290716e-07 1.76414194273698e-05 1.4514706972975e-06 -6.43082292787718e-07 2.77271947465016e-06 3.9885495290716e-07 1.23537394861666e-05 -1.31121850077736e-06 8.19468350654197e-06 -6.39721598121501e-05 -2.38044859954785e-06 1.76414194273698e-05 -1.31121850077736e-06 0.000194920028044925 1036 1036 0 0 0 1034 1034 0 0 0 0 0 0 0 0 325 312 0 711 0 1405 1493 0 0 30 +463 318 0.470316396543034 0.882485119676952 -0.0047434893835288 -1.74868815643796 -0.880011332582715 0.469387665219662 0.0724932704851205 -0.588398764089946 0.066200767886564 -0.0299204493346902 0.99735762143919 0.00547558450484018 5.38404155828863e-05 6.2158251271643e-08 2.256054657679e-06 -2.47354494740779e-06 -7.70919735068297e-06 8.53488080770855e-06 6.2158251271643e-08 3.94527273814804e-05 6.25134113416739e-06 -2.70926672524919e-06 -1.46306083181418e-06 -3.16791061421763e-05 2.256054657679e-06 6.25134113416739e-06 1.37929757135802e-05 -2.71392008993799e-06 6.6965210812096e-06 -5.06044200474808e-06 -2.47354494740779e-06 -2.70926672524919e-06 -2.71392008993799e-06 2.06976312656234e-05 1.64268408801677e-05 -1.11353866517103e-05 -7.70919735068297e-06 -1.46306083181418e-06 6.6965210812096e-06 1.64268408801677e-05 6.85234410399571e-05 -3.53925507263224e-05 8.53488080770855e-06 -3.16791061421763e-05 -5.06044200474808e-06 -1.11353866517103e-05 -3.53925507263224e-05 9.76366674211499e-05 0 0 0 1046 0 0 0 0 1043 0 0 0 0 0 0 0 0 0 1030 0 976 925 0 342 0 +463 310 0.895397571995274 0.441684798670627 -0.0563713286011175 -1.60163830527336 -0.43863056681003 0.896731127599738 0.0589619424172502 -0.318421044344911 0.0765925187265677 -0.0280681922643884 0.996667327977661 -0.0133274420090489 7.27282109363321e-05 -9.44830695037037e-06 -4.61389379822679e-06 -1.33782013482002e-06 1.12358550611195e-06 2.19126926071069e-05 -9.44830695037037e-06 8.53178336673521e-05 7.14778002349299e-06 -1.89122508320163e-05 -1.13320913327522e-05 -1.3886252733846e-05 -4.61389379822679e-06 7.14778002349299e-06 1.83191813686704e-05 -5.81083779224653e-06 -7.58641025755991e-07 -2.0317745140352e-06 -1.33782013482002e-06 -1.89122508320163e-05 -5.81083779224653e-06 4.48675193611746e-05 1.68296988846361e-05 -6.85530159574605e-05 1.12358550611195e-06 -1.13320913327522e-05 -7.58641025755991e-07 1.68296988846361e-05 3.66960921783598e-05 -8.03371483908584e-05 2.19126926071069e-05 -1.3886252733846e-05 -2.0317745140352e-06 -6.85530159574605e-05 -8.03371483908584e-05 0.000493118156578489 846 874 0 301 0 855 883 0 291 0 0 0 0 0 0 0 0 0 1224 0 1757 1757 0 0 0 +464 313 0.763635778437657 0.642646961742545 -0.0621713796934765 -1.70046532742227 -0.638699890594494 0.765996461590523 0.0728825808089946 -0.33562715116624 0.0944608259782597 -0.0159468929222898 0.995400848383017 -0.0391861177094444 4.57354307687414e-05 1.784191825279e-07 -2.15580523922764e-06 1.7598554514173e-06 4.05601156895077e-06 -7.80468486181423e-07 1.784191825279e-07 3.43641692811284e-05 1.58672342464855e-06 -2.01800207528389e-05 -2.01191465222253e-05 2.33280618656047e-06 -2.15580523922764e-06 1.58672342464855e-06 1.4185051793712e-05 -4.30331859110463e-06 -9.49701841784516e-07 2.51949138780789e-06 1.7598554514173e-06 -2.01800207528389e-05 -4.30331859110463e-06 0.000135953530694126 0.000120763771071573 -0.000134149824316572 4.05601156895077e-06 -2.01191465222253e-05 -9.49701841784516e-07 0.000120763771071573 0.000148027823282352 -0.000156287892959308 -7.80468486181423e-07 2.33280618656047e-06 2.51949138780789e-06 -0.000134149824316572 -0.000156287892959308 0.000330373589852034 457 472 0 616 0 465 480 0 606 0 0 0 0 0 0 0 0 0 1236 0 1386 1386 0 0 0 +464 306 0.981266653872787 0.178489706830721 -0.0725064035295315 -1.97895859108089 -0.176801519753288 0.983815602026199 0.0291218787641773 -0.210409461817812 0.0765308866421383 -0.0157570861935469 0.99694269525608 -0.0395010465453177 5.13148486106271e-05 -1.48234592375765e-05 8.34317612704618e-07 9.69830406967206e-06 1.10082115532422e-06 1.04979386081529e-05 -1.48234592375765e-05 9.19364389031083e-05 5.40700623005394e-07 1.30603168642741e-05 5.59125971828791e-06 -9.13989608064016e-05 8.34317612704618e-07 5.40700623005394e-07 1.54709357531917e-05 -2.15482107560731e-06 2.34572703656632e-06 6.19984368241235e-07 9.69830406967206e-06 1.30603168642741e-05 -2.15482107560731e-06 0.000151565420155032 2.54376266559153e-05 -8.33482948895264e-05 1.10082115532422e-06 5.59125971828791e-06 2.34572703656632e-06 2.54376266559153e-05 1.896552385781e-05 -2.6237948543417e-05 1.04979386081529e-05 -9.13989608064016e-05 6.19984368241235e-07 -8.33482948895264e-05 -2.6237948543417e-05 0.000218969341049418 908 908 0 0 0 906 906 0 0 0 0 0 0 0 0 382 371 0 535 0 1035 1035 0 0 0 +465 312 0.783830382632285 0.619414418035637 -0.0439967043322323 -1.87743910871182 -0.615284909732265 0.784265680102328 0.0796983241316368 -0.262746722425235 0.0838713963057926 -0.035399459645678 0.995847612407898 -0.0182308560778432 5.49578073876547e-05 1.42835634043835e-06 -7.39127519299862e-07 -1.93935459765238e-06 1.28013509363266e-06 -7.25310863145805e-06 1.42835634043835e-06 4.82848568558286e-05 4.2626777128685e-06 2.30275304572329e-06 3.55673419426187e-06 -2.74115147162388e-05 -7.39127519299862e-07 4.2626777128685e-06 1.58621653953855e-05 -8.56499689958084e-07 2.58188249685331e-06 1.27426835556737e-06 -1.93935459765238e-06 2.30275304572329e-06 -8.56499689958084e-07 2.99588341518541e-05 -1.41687904249088e-07 4.86916947754028e-05 1.28013509363266e-06 3.55673419426187e-06 2.58188249685331e-06 -1.41687904249088e-07 1.65943823795009e-05 1.52356007445496e-05 -7.25310863145805e-06 -2.74115147162388e-05 1.27426835556737e-06 4.86916947754028e-05 1.52356007445496e-05 0.000229284584769027 451 477 0 514 0 457 483 0 506 0 0 0 0 0 0 0 0 0 986 0 1063 1063 0 0 0 +465 315 0.647315523811447 0.761702016553656 -0.0281540514101617 -1.91103403515826 -0.757414737909168 0.646935833401737 0.0883002959156181 -0.345260712689322 0.0854723781738792 -0.0358338588334152 0.995695941103713 -0.0254319928840915 5.31052177336669e-05 1.47119349923995e-05 2.15459709436268e-06 -3.94644319324815e-06 1.81196738896977e-06 -2.23978440721271e-05 1.47119349923995e-05 6.3771439914382e-05 7.65844444851047e-06 2.74462395664503e-06 1.06673968735059e-05 -4.68627102389667e-05 2.15459709436268e-06 7.65844444851047e-06 1.54191627308475e-05 -3.59093158530606e-06 2.73229081162363e-06 -6.05522394195267e-06 -3.94644319324815e-06 2.74462395664503e-06 -3.59093158530606e-06 2.22357807692643e-05 5.43708395112797e-06 1.39744384088023e-05 1.81196738896977e-06 1.06673968735059e-05 2.73229081162363e-06 5.43708395112797e-06 3.03504634893824e-05 -1.15510053851648e-05 -2.23978440721271e-05 -4.68627102389667e-05 -6.05522394195267e-06 1.39744384088023e-05 -1.15510053851648e-05 0.000220793468267649 276 313 0 707 0 282 319 0 697 0 0 0 0 0 0 0 0 0 950 0 999 999 0 0 0 +465 307 0.957409562128424 0.277987863287034 -0.0780363902943264 -2.05894788763714 -0.276139061275165 0.960523989469134 0.0337769816941846 -0.163023669828244 0.0843454158987284 -0.0107895096926714 0.996378159785461 -0.0389542885182235 5.19763742930085e-05 1.04635893895935e-05 8.2971789289981e-07 3.47216346587482e-06 7.78165855445202e-07 -7.77530742876755e-06 1.04635893895935e-05 0.000118440706092162 9.08397419945375e-07 -7.70824060973231e-06 3.16413396897672e-06 -8.53154432505122e-05 8.2971789289981e-07 9.08397419945375e-07 1.52711119284223e-05 -5.44975921263361e-06 2.8052168614721e-06 -1.09150649287205e-06 3.47216346587482e-06 -7.70824060973231e-06 -5.44975921263361e-06 5.64253472788885e-05 5.04977105247505e-06 7.58030114207694e-06 7.78165855445202e-07 3.16413396897672e-06 2.8052168614721e-06 5.04977105247505e-06 1.57161398087525e-05 -7.6459583329586e-06 -7.77530742876755e-06 -8.53154432505122e-05 -1.09150649287205e-06 7.58030114207694e-06 -7.6459583329586e-06 0.000267217237853469 911 911 0 0 0 909 909 0 0 0 0 0 0 0 0 219 216 0 626 0 904 904 0 0 0 +466 313 0.73795808297341 0.674135513473549 -0.0309705868198313 -2.01602969537876 -0.671513048430918 0.738094997796698 0.0654675493241295 -0.2593678490266 0.0669932351900228 -0.0275151540291224 0.99737396333448 -0.0016021386755663 5.11710523401279e-05 1.29215642508438e-05 3.90660345002835e-06 2.89238849675419e-06 7.83428895472164e-06 -3.73554101780925e-05 1.29215642508438e-05 9.57923908933024e-05 5.76588706189999e-06 -4.08059622353313e-06 2.27121687548662e-06 -7.50598212367356e-05 3.90660345002835e-06 5.76588706189999e-06 1.48621590586487e-05 -3.85170336039754e-06 3.3759459082165e-06 -9.68745294544158e-06 2.89238849675419e-06 -4.08059622353313e-06 -3.85170336039754e-06 2.47267766939056e-05 8.7299820592278e-06 -3.3974326867946e-05 7.83428895472164e-06 2.27121687548662e-06 3.3759459082165e-06 8.7299820592278e-06 3.33773442402021e-05 -6.74334962595599e-05 -3.73554101780925e-05 -7.50598212367356e-05 -9.68745294544158e-06 -3.3974326867946e-05 -6.74334962595599e-05 0.000377153714656703 370 384 0 507 0 375 389 0 499 0 0 0 0 0 0 0 0 0 942 0 874 874 0 0 0 +466 307 0.956229735841895 0.289084814256809 -0.0453283846816391 -2.21207280824169 -0.288373881238458 0.95727306396535 0.0216514578229515 -0.134962289404874 0.0496507493519298 -0.0076322455737187 0.998737478978482 0.0238120012587075 4.66621368858704e-05 -4.65688633482664e-06 7.15032571024579e-06 2.54878530621502e-05 7.92693272620532e-06 5.52142647828781e-06 -4.65688633482664e-06 0.000846559642213263 3.20363173756266e-05 -0.00026576455166099 -4.9046240838145e-05 -0.000680250333304803 7.15032571024579e-06 3.20363173756266e-05 1.69751614399386e-05 -1.35013112795857e-05 9.94020867761758e-07 -2.86989970827357e-05 2.54878530621502e-05 -0.00026576455166099 -1.35013112795857e-05 0.000254311155614438 5.38838467225075e-05 0.000255229310470352 7.92693272620532e-06 -4.9046240838145e-05 9.94020867761758e-07 5.38838467225075e-05 2.73050147731668e-05 4.88040546427064e-05 5.52142647828781e-06 -0.000680250333304803 -2.86989970827357e-05 0.000255229310470352 4.88040546427064e-05 0.000696117342377738 761 761 0 0 0 758 758 0 0 0 0 0 0 0 0 256 253 0 496 0 700 700 0 0 0 +466 309 0.901608561198025 0.431215737056906 -0.0339851510059311 -2.07208684104603 -0.429283474817515 0.901669549829948 0.0520357680644696 -0.168002033612854 0.0530820178876632 -0.0323266302594165 0.998066775498035 0.0259789840944941 5.04611472151311e-05 1.95371567803033e-05 6.88101855106585e-06 7.2190514624241e-06 6.78155793624425e-06 -3.23194171513911e-05 1.95371567803033e-05 0.000353332765954585 2.41989812467825e-05 -1.49334380349898e-05 1.78408541555589e-05 -0.000330526832560261 6.88101855106585e-06 2.41989812467825e-05 1.64293431223089e-05 -5.21346095720072e-06 4.64913588694986e-06 -2.28690930577688e-05 7.2190514624241e-06 -1.49334380349898e-05 -5.21346095720072e-06 0.000136705777949785 6.51203790869253e-05 -0.000204995595613909 6.78155793624425e-06 1.78408541555589e-05 4.64913588694986e-06 6.51203790869253e-05 5.6845908068171e-05 -0.000161346653998313 -3.23194171513911e-05 -0.000330526832560261 -2.28690930577688e-05 -0.000204995595613909 -0.000161346653998313 0.000929189288197019 804 816 0 39 0 809 821 0 32 0 0 0 0 0 0 0 0 0 845 0 833 833 0 0 0 +466 308 0.932160198733732 0.356331474122002 -0.0640721815355962 -2.10033688864575 -0.354231581929049 0.934215069404679 0.0419784523446694 -0.150309956559492 0.0748154413255225 -0.0164342522571421 0.99706196652566 0.0393120515007735 3.75486394745444e-05 6.48379014401806e-06 -9.25521982102395e-07 -2.1469209560227e-06 -2.79225424345975e-06 -1.56175138399898e-06 6.48379014401806e-06 4.58909867553924e-05 4.54812850699187e-06 -1.31968799790011e-05 -4.35983741472495e-06 -3.70852735830052e-05 -9.25521982102395e-07 4.54812850699187e-06 1.33864815249647e-05 -1.72168231079131e-06 4.78946654627623e-06 -6.65773632882694e-06 -2.1469209560227e-06 -1.31968799790011e-05 -1.72168231079131e-06 0.000271056856648918 9.51231551318277e-05 -0.000113692544912436 -2.79225424345975e-06 -4.35983741472495e-06 4.78946654627623e-06 9.51231551318277e-05 4.99603253196973e-05 -4.54859364079593e-05 -1.56175138399898e-06 -3.70852735830052e-05 -6.65773632882694e-06 -0.000113692544912436 -4.54859364079593e-05 0.000147727882716801 843 843 0 0 0 840 840 0 0 0 0 0 0 0 0 106 111 0 700 0 729 729 0 0 0 +467 314 0.68903905644999 0.724719944504555 -0.00248610615673725 -2.16705500151969 -0.722544252127993 0.687228270086982 0.0751472455253874 -0.266223732710929 0.0561692300401761 -0.0499830654378981 0.997169349090777 0.0898129326806476 4.54150568870523e-05 1.37771391606676e-05 5.87230253980112e-06 2.87443709616213e-07 1.57777031915288e-06 -2.23881229971022e-05 1.37771391606676e-05 0.000115598369714002 6.56380294011714e-06 -1.44458887506356e-05 -5.89500388407506e-06 -7.32664597192678e-05 5.87230253980112e-06 6.56380294011714e-06 1.56383629628659e-05 -3.88120594049324e-06 3.5175043418914e-06 -5.29330278238866e-06 2.87443709616213e-07 -1.44458887506356e-05 -3.88120594049324e-06 1.66215751230223e-05 -6.75294353244592e-07 -5.94709855759132e-06 1.57777031915288e-06 -5.89500388407506e-06 3.5175043418914e-06 -6.75294353244592e-07 2.07030227352745e-05 -2.24150279111541e-05 -2.23881229971022e-05 -7.32664597192678e-05 -5.29330278238866e-06 -5.94709855759132e-06 -2.24150279111541e-05 0.0001573647660973 278 287 0 510 0 282 291 0 500 0 0 0 0 0 0 0 0 0 786 0 710 710 0 0 0 +467 308 0.929199733668165 0.36665349274004 -0.0464011983955122 -2.26360704434075 -0.364659275981837 0.929993735562321 0.0462089196502423 -0.127011903311993 0.060095485615916 -0.0260166884205018 0.997853528596366 0.0709526976376755 3.90386112962231e-05 1.34637204510982e-05 4.1141175994085e-06 6.60145769083869e-07 2.0229871078763e-06 -1.51060031807203e-05 1.34637204510982e-05 0.000195528150457594 1.02905042031378e-05 -3.19124276475428e-05 1.93434450130605e-07 -0.000194639843095705 4.1141175994085e-06 1.02905042031378e-05 1.60038302645055e-05 -4.25450540135963e-06 3.5915735886527e-06 -1.37366997580292e-05 6.60145769083869e-07 -3.19124276475428e-05 -4.25450540135963e-06 9.62862130773591e-05 3.05677968075503e-05 -0.000127769222684831 2.0229871078763e-06 1.93434450130605e-07 3.5915735886527e-06 3.05677968075503e-05 2.99335882149607e-05 -8.14429755114253e-05 -1.51060031807203e-05 -0.000194639843095705 -1.37366997580292e-05 -0.000127769222684831 -8.14429755114253e-05 0.000582017368222923 787 787 0 0 0 787 787 0 0 0 0 0 0 0 0 99 104 0 576 0 639 639 0 0 0 +467 317 0.49130787572259 0.870481360717419 0.0296440870412099 -2.3014484466553 -0.86965167135252 0.488387804159906 0.0719953002746203 -0.376743694567439 0.048192756371929 -0.0611518878810415 0.996964344819743 0.0568770246396745 4.02991496635443e-05 1.95733579310669e-05 6.81251539179422e-06 -4.50015306858987e-07 3.72980522200843e-06 -3.13742292711015e-06 1.95733579310669e-05 4.98862813975039e-05 6.09118593622527e-06 -3.24688494084324e-06 -2.63262347600728e-06 -2.0486026795588e-05 6.81251539179422e-06 6.09118593622527e-06 1.55294936225924e-05 -3.43073589977006e-06 2.52069457348136e-06 1.63977701903599e-07 -4.50015306858987e-07 -3.24688494084324e-06 -3.43073589977006e-06 1.98092057844789e-05 7.13107598492146e-06 1.5207922043307e-05 3.72980522200843e-06 -2.63262347600728e-06 2.52069457348136e-06 7.13107598492146e-06 3.85299824749465e-05 -6.03736239543744e-06 -3.13742292711015e-06 -2.0486026795588e-05 1.63977701903599e-07 1.5207922043307e-05 -6.03736239543744e-06 0.000209716707006967 0 0 0 768 0 0 0 0 763 0 0 0 0 0 0 0 0 0 724 0 435 435 0 139 0 +468 312 0.756951927418596 0.653128558763618 -0.0211391888357012 -2.28111778518099 -0.650604515431573 0.756264013502774 0.0691267414299528 -0.169887045244749 0.0611354567932507 -0.0385723684525018 0.997383892147174 0.020980805195572 4.55365475512122e-05 1.67961527932283e-05 3.59785180562101e-06 -5.00230724778168e-06 -6.66718895760553e-07 -1.62786850046571e-05 1.67961527932283e-05 7.45224886452375e-05 6.7799690484263e-06 -1.35715628331976e-05 -6.39046833622355e-06 -3.99614919771052e-05 3.59785180562101e-06 6.7799690484263e-06 1.53016577783978e-05 -3.0194649626393e-06 3.39108416220892e-06 -3.32635238478054e-07 -5.00230724778168e-06 -1.35715628331976e-05 -3.0194649626393e-06 0.00010309700137796 5.69768923094275e-05 7.90005766414095e-05 -6.66718895760553e-07 -6.39046833622355e-06 3.39108416220892e-06 5.69768923094275e-05 5.83235633560049e-05 3.03094688608795e-05 -1.62786850046571e-05 -3.99614919771052e-05 -3.32635238478054e-07 7.90005766414095e-05 3.03094688608795e-05 0.000331522726563543 358 386 0 424 0 363 391 0 415 0 0 0 0 0 0 0 0 0 727 0 615 615 0 0 0 +468 310 0.843378660561942 0.536649003218791 -0.0268380746891836 -2.31450779855397 -0.53431050843988 0.842887420711128 0.063663777594938 -0.123097618162235 0.0567865783390849 -0.039352806141607 0.997610465647449 0.0413289424828529 4.37499186234272e-05 2.23381227138361e-05 5.18204548767965e-06 4.43594523156161e-08 4.00666612539834e-06 -3.69815792435539e-05 2.23381227138361e-05 7.54228185397889e-05 6.3537589238084e-06 -1.68334128588929e-05 -5.29230748185136e-06 -4.64438267709059e-05 5.18204548767965e-06 6.3537589238084e-06 1.48760188521115e-05 -4.51892911206845e-06 3.96625170728327e-06 -2.99487966195738e-06 4.43594523156161e-08 -1.68334128588929e-05 -4.51892911206845e-06 0.000118482927041972 5.15620257874882e-05 4.21770965147165e-05 4.00666612539834e-06 -5.29230748185136e-06 3.96625170728327e-06 5.15620257874882e-05 4.4791686565234e-05 6.68983152640493e-06 -3.69815792435539e-05 -4.64438267709059e-05 -2.99487966195738e-06 4.21770965147165e-05 6.68983152640493e-06 0.000223081967002625 585 608 0 168 0 588 611 0 160 0 0 0 0 0 0 0 0 0 738 0 617 617 0 0 0 +469 312 0.755140236611919 0.654593630450792 -0.0356426994340669 -2.44433928110578 -0.651490756500717 0.755390008606628 0.070325877821765 -0.165618667346183 0.0729590107102513 -0.0298850108002406 0.996887089336426 -0.036246571231797 4.82528963853242e-05 2.37907213971931e-05 4.20490303182873e-07 -1.01833453846357e-06 4.20930059604346e-06 -2.12372079181504e-05 2.37907213971931e-05 0.000147650365635973 1.58244065458751e-05 -1.20383873060155e-05 -1.03640858960376e-06 -7.31661167051088e-05 4.20490303182873e-07 1.58244065458751e-05 2.14386144574468e-05 -2.70701699056419e-06 2.36010382507823e-06 -1.26955606416715e-05 -1.01833453846357e-06 -1.20383873060155e-05 -2.70701699056419e-06 4.96071549265097e-05 3.53162265547785e-05 -0.000121213871474164 4.20930059604346e-06 -1.03640858960376e-06 2.36010382507823e-06 3.53162265547785e-05 6.41081433277539e-05 -0.000162013292587591 -2.12372079181504e-05 -7.31661167051088e-05 -1.26955606416715e-05 -0.000121213871474164 -0.000162013292587591 0.000632314328511516 364 383 0 368 0 367 386 0 362 0 0 0 0 0 0 0 0 0 580 0 517 517 0 0 0 +469 311 0.800162813993001 0.599550743427124 -0.0166846384073681 -2.48026195337321 -0.597359300561436 0.799119382379094 0.0676023574944564 -0.141058336466466 0.053864061632542 -0.0441261686761792 0.99757282646552 -0.0447252823716994 6.27677006074321e-05 0.000141956816099778 1.47465230651596e-05 -1.36872218174985e-05 8.97577537418191e-06 -0.000173532635439327 0.000141956816099778 0.00141319103982626 9.82883851136919e-05 -0.000126589493438624 8.95614223701582e-05 -0.00169314099497761 1.47465230651596e-05 9.82883851136919e-05 2.15494384374553e-05 -1.28718717245718e-05 9.18490673177777e-06 -0.000120266010613553 -1.36872218174985e-05 -0.000126589493438624 -1.28718717245718e-05 4.02414648857746e-05 -8.19441561695372e-06 0.000202340857240455 8.97577537418191e-06 8.95614223701582e-05 9.18490673177777e-06 -8.19441561695372e-06 2.17093272890533e-05 -0.0001076404447321 -0.000173532635439327 -0.00169314099497761 -0.000120266010613553 0.000202340857240455 -0.0001076404447321 0.00247212375359119 384 417 0 274 0 388 421 0 267 0 0 0 0 0 0 0 0 0 559 0 509 509 0 0 0 +469 310 0.841561186296859 0.53834586266904 -0.0442549643062735 -2.48149645634391 -0.535405313480901 0.842195057655869 0.0636288861795155 -0.118047696283901 0.0715256598364619 -0.0298532578984944 0.996991907177688 -0.0242579396702436 5.07545416164449e-05 1.31006072417207e-05 4.71894763360667e-06 3.39024145675691e-06 1.58766430589087e-06 -2.13876316936422e-05 1.31006072417207e-05 0.000122381275346587 1.18554474057528e-05 -5.69246377001585e-05 -3.54734592191832e-05 -1.97340991029808e-05 4.71894763360667e-06 1.18554474057528e-05 1.86722005430776e-05 -1.2216311282825e-05 -3.66722820966851e-06 5.34526138430417e-06 3.39024145675691e-06 -5.69246377001585e-05 -1.2216311282825e-05 0.000174161313113509 0.000105920948105057 -0.000177659235136129 1.58766430589087e-06 -3.54734592191832e-05 -3.66722820966851e-06 0.000105920948105057 9.14732370018493e-05 -0.00013437672904091 -2.13876316936422e-05 -1.97340991029808e-05 5.34526138430417e-06 -0.000177659235136129 -0.00013437672904091 0.000358632110460436 562 585 0 143 0 567 590 0 138 0 0 0 0 0 0 0 0 0 605 0 514 514 0 0 0 +470 314 0.693796437729838 0.719426279790362 -0.0327464645479056 -2.60870857873903 -0.716245432688677 0.694042044048055 0.0727881944150843 -0.293100590016825 0.0750931631108772 -0.0270456843248333 0.996809684851328 -0.0373600391187159 6.11551812755324e-05 2.73318089410426e-05 -2.72558205830794e-06 -2.7124314452884e-06 8.85018472361449e-07 -1.73495182810674e-05 2.73318089410426e-05 8.4525049996068e-05 7.1855227783311e-06 -1.99253781078198e-05 -1.4014145062151e-05 -6.47383731816382e-05 -2.72558205830794e-06 7.1855227783311e-06 1.71229003928837e-05 -5.60137839197557e-06 -6.11845333032482e-07 -6.22030933336522e-06 -2.7124314452884e-06 -1.99253781078198e-05 -5.60137839197557e-06 4.45652188380507e-05 2.67563539176153e-05 8.64423529223659e-06 8.85018472361449e-07 -1.4014145062151e-05 -6.11845333032482e-07 2.67563539176153e-05 4.74166618251694e-05 -2.51364273401589e-07 -1.73495182810674e-05 -6.47383731816382e-05 -6.22030933336522e-06 8.64423529223659e-06 -2.51364273401589e-07 9.93101141384568e-05 229 240 0 428 0 233 244 0 424 0 0 0 0 0 0 0 0 0 543 0 462 462 0 0 0 +470 312 0.774677966444135 0.631029501019986 -0.0409367456992821 -2.57682930819306 -0.628006676405249 0.775315604256601 0.0670322921184617 -0.240371763171214 0.0740382515758765 -0.0262198901349661 0.996910655307133 -0.0570186955758648 4.85544465146482e-05 2.04858106929945e-05 3.97447856670949e-06 -1.2323041530253e-06 4.49889127692872e-06 -3.93058958480338e-05 2.04858106929945e-05 0.000230852782927827 2.44867328485825e-05 -8.06445045416537e-05 -5.31262237881908e-05 -0.000106232192991591 3.97447856670949e-06 2.44867328485825e-05 1.63282689758242e-05 -1.13504483894053e-05 -6.26162655283054e-07 -1.05291992444214e-05 -1.2323041530253e-06 -8.06445045416537e-05 -1.13504483894053e-05 0.000127937428187434 0.000102751460512186 -0.000140912355915005 4.49889127692872e-06 -5.31262237881908e-05 -6.26162655283054e-07 0.000102751460512186 0.000119642210423255 -0.000195222290577348 -3.93058958480338e-05 -0.000106232192991591 -1.05291992444214e-05 -0.000140912355915005 -0.000195222290577348 0.000762670567983064 329 355 0 377 0 332 358 0 370 0 0 0 0 0 0 0 0 0 472 0 474 474 0 0 0 +471 311 0.836948894113289 0.546611116192643 -0.0270709493216631 -2.74638280032612 -0.541973024852664 0.834689307819349 0.0977701372818382 -0.310102201837905 0.0760380758212452 -0.067156883985844 0.994840773168608 0.0101969893028527 5.04186529429241e-05 -1.04564492095207e-05 -2.19052846029407e-06 -5.17524275637249e-06 1.28738646076456e-06 9.55010883519335e-06 -1.04564492095207e-05 0.000232370692402388 2.38450314021025e-05 -4.69529644628614e-05 -1.09722229926088e-05 -0.000253063371699338 -2.19052846029407e-06 2.38450314021025e-05 2.09657270132174e-05 -7.56903440401153e-06 -1.38224863455645e-07 -2.86944446293665e-05 -5.17524275637249e-06 -4.69529644628614e-05 -7.56903440401153e-06 7.98862338657741e-05 3.6766634065899e-05 2.32559776465419e-05 1.28738646076456e-06 -1.09722229926088e-05 -1.38224863455645e-07 3.6766634065899e-05 4.45415164324826e-05 -1.91445561605672e-05 9.55010883519335e-06 -0.000253063371699338 -2.86944446293665e-05 2.32559776465419e-05 -1.91445561605672e-05 0.000412827907575441 426 454 0 226 0 428 456 0 223 0 0 0 0 0 0 0 0 0 345 0 425 425 0 0 0 +471 313 0.758334119015737 0.650566564583328 -0.0411401140357183 -2.74357123492827 -0.644813458797675 0.757892722026214 0.0990667716899777 -0.357166436577332 0.0956293223337091 -0.0485980138065501 0.994229986353285 -0.0294760559498947 4.98526198021781e-05 -6.51002055252757e-06 -6.55097198779359e-07 -1.74401868240267e-06 -5.25375281997177e-07 7.98366172289449e-06 -6.51002055252757e-06 4.32900653269055e-05 9.43028710716268e-07 -6.38196533262535e-06 -5.51254526505727e-06 -2.43028880595234e-05 -6.55097198779359e-07 9.43028710716268e-07 1.50111664705499e-05 -3.78798917464187e-06 3.27995224112101e-06 2.44964359182624e-07 -1.74401868240267e-06 -6.38196533262535e-06 -3.78798917464187e-06 3.23524885871169e-05 1.62744150302256e-05 -3.85499353729033e-05 -5.25375281997177e-07 -5.51254526505727e-06 3.27995224112101e-06 1.62744150302256e-05 3.73680862066386e-05 -4.40879395315088e-05 7.98366172289449e-06 -2.43028880595234e-05 2.44964359182624e-07 -3.85499353729033e-05 -4.40879395315088e-05 0.000136616962058928 273 291 0 392 0 275 293 0 388 0 0 0 0 0 0 0 0 0 381 0 432 432 0 0 0 +470 308 0.930335680068108 0.358290049415125 -0.0781265824308139 -2.71822138020368 -0.355886831178913 0.933527473515007 0.0432552839098402 -0.156268984122301 0.0884312489205215 -0.0124377121206598 0.996004627264131 -0.0216060240054436 4.71038084341124e-05 8.94203646755654e-06 1.32064759724983e-06 -6.44761799168109e-06 -9.85257806190583e-07 -6.02110590584432e-06 8.94203646755654e-06 0.000190681208037207 5.45327316438546e-06 -5.98696115556917e-05 -1.19847428906481e-05 -0.000136360192724725 1.32064759724983e-06 5.45327316438546e-06 1.45831224177652e-05 -7.71955583638196e-06 2.91071883448635e-06 -2.81647418623489e-06 -6.44761799168109e-06 -5.98696115556917e-05 -7.71955583638196e-06 9.26104074784628e-05 2.42641390967956e-05 -2.91396572708132e-05 -9.85257806190583e-07 -1.19847428906481e-05 2.91071883448635e-06 2.42641390967956e-05 2.37340031290007e-05 -2.66584623927447e-05 -6.02110590584432e-06 -0.000136360192724725 -2.81647418623489e-06 -2.91396572708132e-05 -2.66584623927447e-05 0.000245239950756539 614 614 0 0 0 614 614 0 0 0 0 0 0 0 0 153 158 0 271 0 432 432 0 0 0 +471 310 0.874085753966582 0.484194686506822 -0.0391101044646056 -2.76805947249463 -0.479257016090697 0.872705330004883 0.0932637094957586 -0.279699256920213 0.0792893892050712 -0.0627766878676181 0.994872997030203 -0.0162189975228513 5.65634035954342e-05 1.3217326052891e-07 7.40132627669282e-06 3.27542583749496e-06 1.37990042484255e-06 -5.72585599709729e-06 1.3217326052891e-07 5.46476561672434e-05 5.04799979917853e-06 -1.77484951464249e-05 -1.08981395709022e-05 -1.26818041421649e-07 7.40132627669282e-06 5.04799979917853e-06 1.51177908756602e-05 -5.07228385764202e-06 3.5426959281264e-06 -3.94286719384172e-06 3.27542583749496e-06 -1.77484951464249e-05 -5.07228385764202e-06 0.000126999925828616 8.03261858956688e-05 -0.000218021064155053 1.37990042484255e-06 -1.08981395709022e-05 3.5426959281264e-06 8.03261858956688e-05 7.89578113028496e-05 -0.000178842263868175 -5.72585599709729e-06 -1.26818041421649e-07 -3.94286719384172e-06 -0.000218021064155053 -0.000178842263868175 0.000587263035419332 585 608 0 93 0 588 611 0 88 0 0 0 0 0 0 0 0 0 402 0 453 453 0 0 0 +471 316 0.599117890615383 0.80057419678111 -0.0117774612228273 -2.83912536697018 -0.79455695226349 0.596299036725379 0.114484533497494 -0.456226982049636 0.0986762522308589 -0.0592318685224937 0.993355214914084 -0.0278615081709685 5.58990295906545e-05 -4.58153149298731e-06 -7.17777735553551e-07 3.5858604771877e-08 3.20111796878565e-06 1.49089753596618e-06 -4.58153149298731e-06 8.05769690783508e-05 6.79531508068855e-06 -1.55881499057677e-07 4.30754153360187e-06 -5.86577666740423e-05 -7.17777735553551e-07 6.79531508068855e-06 1.83522765016681e-05 -2.02136430191979e-06 1.70689839738223e-06 -8.92522579572681e-06 3.5858604771877e-08 -1.55881499057677e-07 -2.02136430191979e-06 1.40018924125083e-05 -4.31627900586595e-06 7.89241727366358e-06 3.20111796878565e-06 4.30754153360187e-06 1.70689839738223e-06 -4.31627900586595e-06 1.60073933010336e-05 9.53280815230276e-06 1.49089753596618e-06 -5.86577666740423e-05 -8.92522579572681e-06 7.89241727366358e-06 9.53280815230276e-06 9.57062648269282e-05 3 14 0 569 0 4 16 0 570 0 0 0 0 0 0 0 0 0 377 0 358 366 0 16 0 +473 477 0.996851056152959 -0.0674094065567755 0.0417605526111978 0.592035063648236 0.0672745941508408 0.997723770317646 0.0046267834377733 0.0256339611328106 -0.0419773847275997 -0.00180278972810217 0.999116934658115 0.0404809821216478 4.96254683738167e-05 -1.45639665146063e-05 -6.74183387382615e-06 -8.96976969508359e-06 5.19027517528562e-06 2.28399151907661e-05 -1.45639665146063e-05 9.89524987894043e-05 -1.4338725094681e-06 8.4236110760284e-06 1.42999125468892e-06 -2.79375690750511e-05 -6.74183387382615e-06 -1.4338725094681e-06 1.23129627490879e-05 -2.67108122213198e-06 3.21345541067401e-06 -3.79685069810835e-06 -8.96976969508359e-06 8.4236110760284e-06 -2.67108122213198e-06 0.000349331798309785 1.74393958038865e-06 -5.88980594706861e-05 5.19027517528562e-06 1.42999125468892e-06 3.21345541067401e-06 1.74393958038865e-06 1.11589698813857e-05 1.60620678742101e-07 2.28399151907661e-05 -2.79375690750511e-05 -3.79685069810835e-06 -5.88980594706861e-05 1.60620678742101e-07 0.000235305031079407 3221 3211 0 695 1040 3221 3211 0 610 1117 0 0 0 0 0 0 0 0 3097 0 0 0 0 0 2646 +473 312 0.817286189364914 0.570120947431533 -0.0836982077057121 -3.02146226238898 -0.566277360995791 0.82153169373646 0.0664501814154537 -0.453075033891143 0.106645370724755 -0.00691241537197519 0.994273092976323 -0.121551850700005 4.83367220407636e-05 -2.10349070126753e-05 -4.60667561761136e-06 6.12007601123221e-06 2.25995779227457e-06 -1.33966679219383e-06 -2.10349070126753e-05 7.99824089530917e-05 5.87929798260565e-06 -2.67922486063298e-05 -2.2657085542842e-05 1.15953857335471e-05 -4.60667561761136e-06 5.87929798260565e-06 1.76905651844964e-05 -4.71785324235985e-06 1.34144375512385e-06 1.83129222374489e-06 6.12007601123221e-06 -2.67922486063298e-05 -4.71785324235985e-06 5.26486726809544e-05 3.78138479617379e-05 -0.000113801476277977 2.25995779227457e-06 -2.2657085542842e-05 1.34144375512385e-06 3.78138479617379e-05 6.19630680246348e-05 -0.000135748011917603 -1.33966679219383e-06 1.15953857335471e-05 1.83129222374489e-06 -0.000113801476277977 -0.000135748011917603 0.00045365372494703 295 327 0 279 0 297 329 0 276 0 0 0 0 0 0 0 0 0 249 0 344 344 0 0 0 +475 312 0.784913513230769 0.603125005439778 -0.141954234036886 -3.3312891654301 -0.599309648530857 0.797167272583488 0.0731593104097044 -0.329235301043642 0.157285479067686 0.0276508107488917 0.98716599958638 -0.354892134915131 3.62176096997847e-05 1.12861676124768e-05 -7.28427667626842e-06 2.36540527849794e-08 -3.33226065001783e-06 -4.90845722660399e-06 1.12861676124768e-05 0.000166783366617152 7.82656306202111e-06 -2.10703336029141e-05 2.26731560240042e-06 -0.000164291739337495 -7.28427667626842e-06 7.82656306202111e-06 1.48057562591939e-05 -4.05657646983401e-06 4.17838645163072e-06 -6.13801937209901e-06 2.36540527849794e-08 -2.10703336029141e-05 -4.05657646983401e-06 1.96657970215221e-05 -5.9577632467266e-06 3.47852814378921e-05 -3.33226065001783e-06 2.26731560240042e-06 4.17838645163072e-06 -5.9577632467266e-06 1.11575797914308e-05 4.87070922087798e-06 -4.90845722660399e-06 -0.000164291739337495 -6.13801937209901e-06 3.47852814378921e-05 4.87070922087798e-06 0.000235672755214685 270 301 0 252 0 271 302 0 248 0 0 0 0 0 0 0 0 0 193 0 220 220 0 0 0 +475 479 0.999389225329103 -0.0332010683328779 -0.0109025390461041 0.596623034028164 0.0328976556877322 0.999096121382173 -0.0269199645124347 0.0157497767251001 0.0117864560554763 0.0265448545043083 0.99957813609192 0.0491399958414331 3.03196600217909e-05 -4.80596443058727e-06 -8.04463782246639e-06 -1.29837847799489e-06 -1.31733696730491e-06 3.34976007543376e-06 -4.80596443058727e-06 3.71762519236223e-05 -3.39198563245584e-07 6.92790784368033e-06 -3.3807928423724e-07 -2.95081714578468e-05 -8.04463782246639e-06 -3.39198563245584e-07 1.14946009334153e-05 1.06737787859584e-06 3.22267482330277e-06 -6.8091942503357e-07 -1.29837847799489e-06 6.92790784368033e-06 1.06737787859584e-06 0.000306765093023386 -4.22629498515656e-06 -2.30947774176923e-06 -1.31733696730491e-06 -3.3807928423724e-07 3.22267482330277e-06 -4.22629498515656e-06 1.23702418786819e-05 4.10508903924474e-07 3.34976007543376e-06 -2.95081714578468e-05 -6.8091942503357e-07 -2.30947774176923e-06 4.10508903924474e-07 5.78103118001215e-05 3323 3307 0 830 933 3323 3307 0 743 1008 0 0 0 0 0 0 0 0 2945 0 0 0 0 0 2788 +475 477 0.999462041515513 -0.0243431368364124 -0.021978154121901 0.315333978953737 0.0244822487189448 0.999681758960169 0.0060827871873512 0.000679077725350984 0.0218230856504313 -0.00661758953597012 0.999739946406778 0.0223860857452795 3.54020616482583e-05 -3.17656848536802e-06 -1.14451825323045e-05 -8.74923770222433e-06 -7.53999511695222e-07 -3.03627149525668e-06 -3.17656848536802e-06 3.85443037936272e-05 -3.06178999405433e-07 -9.018031041707e-06 8.72534477458879e-07 -1.25978964533044e-05 -1.14451825323045e-05 -3.06178999405433e-07 1.36273807650039e-05 7.10394013754898e-06 1.71844697905206e-06 -3.78006421286941e-06 -8.74923770222433e-06 -9.018031041707e-06 7.10394013754898e-06 0.000486533515547303 -2.35577832842625e-06 -0.000164695613760075 -7.53999511695222e-07 8.72534477458879e-07 1.71844697905206e-06 -2.35577832842625e-06 1.21766069213021e-05 2.79394347683333e-06 -3.03627149525668e-06 -1.25978964533044e-05 -3.78006421286941e-06 -0.000164695613760075 2.79394347683333e-06 0.000240331912239063 3408 3398 0 342 401 3408 3398 0 269 464 0 0 0 0 0 0 0 0 3451 0 0 0 0 0 3312 +477 479 0.999921477261839 -0.00888271814809072 0.00883949256481743 0.260642754455404 0.00915288746037717 0.999477230341522 -0.0310079131832249 0.00755283517436889 -0.00855943699314114 0.0310863852376297 0.999480051172217 0.0451480481423375 3.22594078306936e-05 -1.15638027511414e-06 -4.56856558457586e-06 -1.87830306976118e-06 -1.64479218101526e-06 1.55371786581247e-05 -1.15638027511414e-06 5.59122848577538e-05 -4.05237839896533e-06 -2.88397610770686e-05 -9.05908787956105e-07 -3.36870158411398e-05 -4.56856558457586e-06 -4.05237839896533e-06 1.12427956231152e-05 6.49625232313751e-06 4.75583831255908e-06 4.08780638123239e-06 -1.87830306976118e-06 -2.88397610770686e-05 6.49625232313751e-06 0.0003995921139694 -3.71591949328332e-06 -2.26846046240479e-05 -1.64479218101526e-06 -9.05908787956105e-07 4.75583831255908e-06 -3.71591949328332e-06 1.01971762277255e-05 1.62927172849637e-06 1.55371786581247e-05 -3.36870158411398e-05 4.08780638123239e-06 -2.26846046240479e-05 1.62927172849637e-06 0.000157219798794772 3372 3356 0 297 289 3372 3356 0 222 348 0 0 0 0 0 0 0 0 3486 0 0 0 0 0 3456 +477 480 0.999593021681429 -0.00818411694077402 0.0273278472567851 0.418423067183692 0.0090936060904361 0.999403231721396 -0.0333239666471784 0.0110372487569642 -0.0270388116244487 0.033558913193517 0.999070919410233 0.0717661105070222 2.75390522530857e-05 -1.54322140275804e-06 -5.84690574678895e-06 8.5691446353769e-07 -1.69224894130512e-06 2.89532361353016e-06 -1.54322140275804e-06 2.6346494152195e-05 -1.17298429536319e-06 1.74212270580536e-05 7.71953739255351e-07 -2.43046372209742e-05 -5.84690574678895e-06 -1.17298429536319e-06 1.10255626792539e-05 -3.21217037227106e-06 4.05847200385983e-06 2.16206271954586e-06 8.5691446353769e-07 1.74212270580536e-05 -3.21217037227106e-06 0.000290769728558128 -5.12563918895321e-07 -5.52217667559006e-07 -1.69224894130512e-06 7.71953739255351e-07 4.05847200385983e-06 -5.12563918895321e-07 9.90024784425716e-06 -4.01629144485352e-07 2.89532361353016e-06 -2.43046372209742e-05 2.16206271954586e-06 -5.52217667559006e-07 -4.01629144485352e-07 7.8614360603121e-05 3399 3384 0 575 533 3399 3384 0 489 601 0 0 0 0 0 0 0 0 3230 0 0 0 0 0 3184 +478 481 0.998900248705296 0.0108156500601082 0.0456214297263411 0.42242260246191 -0.0100878409598571 0.999818634966747 -0.0161534094853035 0.00862467018385826 -0.0457878652184924 0.0156754230248676 0.998828189686156 0.0485947769891355 3.2690136606201e-05 1.51082978238086e-05 -5.66650752118496e-06 -1.57677094066687e-05 4.94606292793978e-07 8.56323233379762e-06 1.51082978238086e-05 0.00016734267010993 -2.2232157946118e-07 1.9135245658972e-06 2.14568058259224e-06 -2.5084489628404e-05 -5.66650752118496e-06 -2.2232157946118e-07 1.23660840275532e-05 4.82264035055532e-06 3.41137198473537e-06 -6.75277194143349e-06 -1.57677094066687e-05 1.9135245658972e-06 4.82264035055532e-06 0.000279920559744198 -1.87930160839148e-06 -0.000106735777846202 4.94606292793978e-07 2.14568058259224e-06 3.41137198473537e-06 -1.87930160839148e-06 1.17841418426443e-05 7.80898012351281e-06 8.56323233379762e-06 -2.5084489628404e-05 -6.75277194143349e-06 -0.000106735777846202 7.80898012351281e-06 0.000442397550193593 3278 3265 0 651 499 3278 3265 0 572 558 0 0 0 0 0 0 0 0 3171 0 0 0 0 0 3233 +476 479 0.99954602648151 -0.0208903767379953 -0.0217102073866206 0.443888921206574 0.0206512745012229 0.999724230104915 -0.0111798301690693 0.00897078400314195 0.021937771229106 0.0107264113700118 0.999701794683105 0.002259007493608 2.69828847392166e-05 -1.21647985476572e-06 -7.2449331062018e-06 8.67129917825257e-06 -1.97503566763777e-06 6.29897869184698e-06 -1.21647985476572e-06 5.66899449766841e-05 -1.92339809509424e-06 6.66750596510372e-06 1.35560442670939e-06 -1.37842098994814e-05 -7.2449331062018e-06 -1.92339809509424e-06 1.05046222171759e-05 -9.17414459206404e-07 3.58981277039844e-06 -9.72363520531676e-07 8.67129917825257e-06 6.66750596510372e-06 -9.17414459206404e-07 0.000341512900530361 -2.22350113029694e-06 4.52606812936753e-06 -1.97503566763777e-06 1.35560442670939e-06 3.58981277039844e-06 -2.22350113029694e-06 1.06468201041121e-05 4.36423788915626e-06 6.29897869184698e-06 -1.37842098994814e-05 -9.72363520531676e-07 4.52606812936753e-06 4.36423788915626e-06 0.000205389367261919 3321 3305 0 576 613 3321 3305 0 495 677 0 0 0 0 0 0 0 0 3205 0 0 0 0 0 3124 +477 481 0.999276437982238 0.0106409446813048 0.0365153500574792 0.567562100188916 -0.00977785954307619 0.999670492084642 -0.0237339570658743 0.0104682856320335 -0.0367558696848097 0.023359742111982 0.999051214148792 0.0679831242350937 4.11462259415422e-05 4.01133266519605e-06 -1.25610050410033e-05 -2.939641711321e-05 4.17692112275816e-06 1.5450192072071e-05 4.01133266519605e-06 5.80238155427219e-05 -6.24434176592539e-06 2.7212883866787e-05 1.44746442450449e-06 -4.096068027128e-05 -1.25610050410033e-05 -6.24434176592539e-06 1.4206211113042e-05 2.87413503955119e-06 2.22360909061949e-06 1.28456740755991e-07 -2.939641711321e-05 2.7212883866787e-05 2.87413503955119e-06 0.000281555522903879 -4.33202235540053e-06 -9.46275240793963e-05 4.17692112275816e-06 1.44746442450449e-06 2.22360909061949e-06 -4.33202235540053e-06 1.3170298606319e-05 4.98489355982065e-06 1.5450192072071e-05 -4.096068027128e-05 1.28456740755991e-07 -9.46275240793963e-05 4.98489355982065e-06 0.000216036088215243 3340 3327 0 930 763 3340 3327 0 829 833 0 0 0 0 0 0 0 0 2878 0 0 0 0 0 2959 +480 482 0.998806745670118 0.0488371043620902 0.000148463447678682 0.26748450427067 -0.0488346362630321 0.998778967370481 -0.00746676900764339 -0.0033721497520323 -0.000512937546238677 0.00745060909472904 0.999972112270733 0.0414577688717597 2.61624240422482e-05 4.12865095451219e-06 -9.00208632871003e-06 3.08764715380141e-06 -1.8968613287763e-06 1.98924227541583e-06 4.12865095451219e-06 4.0901514712731e-05 5.12302832072522e-07 1.50344463522103e-05 2.36364458468532e-07 -1.20405532367217e-05 -9.00208632871003e-06 5.12302832072522e-07 1.20338925035261e-05 -1.85315799371881e-06 4.79110960991744e-06 7.66637802358857e-07 3.08764715380141e-06 1.50344463522103e-05 -1.85315799371881e-06 0.000422661043606874 1.07303565642537e-05 5.86986523458333e-05 -1.8968613287763e-06 2.36364458468532e-07 4.79110960991744e-06 1.07303565642537e-05 1.13888005576912e-05 1.16245856351979e-05 1.98924227541583e-06 -1.20405532367217e-05 7.66637802358857e-07 5.86986523458333e-05 1.16245856351979e-05 0.000344764974021069 3406 3405 0 481 157 3406 3405 0 402 204 0 0 0 0 0 0 0 0 3323 0 0 0 0 0 3611 +483 485 0.999200517635759 0.0252987263041281 0.0309564210434484 0.235915537018938 -0.0262407632147008 0.99919291160904 0.0304129534271122 0.0024253151999689 -0.0301620274905458 -0.0312009589217785 0.999057932384314 0.0610391493577831 4.00571330919751e-05 -2.02622133763816e-05 -1.62113753002956e-06 3.63464693194255e-06 7.6811934830645e-07 1.82139800258126e-05 -2.02622133763816e-05 0.000202266478567622 3.71398903792158e-06 -5.51671070885065e-05 -5.77179537361469e-06 -0.000189398143086668 -1.62113753002956e-06 3.71398903792158e-06 1.24701463568908e-05 -8.17664142465963e-06 4.26859113510301e-06 -3.76331243709334e-06 3.63464693194255e-06 -5.51671070885065e-05 -8.17664142465963e-06 0.000299876375616271 1.7695732690541e-05 -8.91706458309524e-05 7.6811934830645e-07 -5.77179537361469e-06 4.26859113510301e-06 1.7695732690541e-05 1.2672089394754e-05 -1.12306100516544e-05 1.82139800258126e-05 -0.000189398143086668 -3.76331243709334e-06 -8.91706458309524e-05 -1.12306100516544e-05 0.000582042474066751 3210 3223 0 345 191 3210 3223 0 269 247 0 0 0 0 0 0 0 0 3460 0 0 0 0 0 3568 +482 486 0.999342837801337 0.0348957972836872 -0.00980692954533775 0.507890047787927 -0.0345666353175521 0.998891949154812 0.0319377775764618 -0.000486025391499718 0.010910557180766 -0.0315777967191506 0.999441745424099 0.0849635035061373 3.5773402678961e-05 -4.43027963882881e-06 -8.99927053799095e-06 1.08847651328498e-06 3.0821399297205e-07 -1.21777150815668e-05 -4.43027963882881e-06 2.80391720046012e-05 -1.33057905440312e-06 1.04715447677392e-05 2.5004211548486e-07 -9.15648340254036e-06 -8.99927053799095e-06 -1.33057905440312e-06 1.1835113021244e-05 -6.63787810336399e-06 3.72315194146377e-06 6.36147858906227e-07 1.08847651328498e-06 1.04715447677392e-05 -6.63787810336399e-06 0.000210649625161823 8.66372223718265e-06 -1.00765063294066e-05 3.0821399297205e-07 2.5004211548486e-07 3.72315194146377e-06 8.66372223718265e-06 1.19896614405999e-05 2.62971543978058e-07 -1.21777150815668e-05 -9.15648340254036e-06 6.36147858906227e-07 -1.00765063294066e-05 2.62971543978058e-07 0.000143732308029313 3301 3312 0 811 588 3301 3312 0 750 665 0 0 0 0 0 0 0 0 2951 0 0 0 0 0 3135 +483 486 0.999351979179933 0.0103207132386934 0.0344833958216789 0.395264344607058 -0.0111482004735633 0.999652403190983 0.0238912205777416 0.0110765925852263 -0.034224835066822 -0.0242601663790197 0.9991196650011 0.0813930607476542 3.79226035495463e-05 -1.74247336530925e-05 -9.00428888285756e-06 -8.19130888101451e-06 2.01930113250381e-06 1.26547633792037e-05 -1.74247336530925e-05 6.14829206779648e-05 3.8735426248397e-06 2.52365297319374e-05 9.34020032733046e-07 -4.49080279867729e-05 -9.00428888285756e-06 3.8735426248397e-06 1.53396630009672e-05 4.703721230127e-06 9.41930569934736e-07 -1.49660193995794e-06 -8.19130888101451e-06 2.52365297319374e-05 4.703721230127e-06 0.000151094417018435 1.38237920118556e-06 -1.6548090756666e-05 2.01930113250381e-06 9.34020032733046e-07 9.41930569934736e-07 1.38237920118556e-06 1.21596529402533e-05 -1.51326015459915e-06 1.26547633792037e-05 -4.49080279867729e-05 -1.49660193995794e-06 -1.6548090756666e-05 -1.51326015459915e-06 7.21095462027648e-05 3222 3233 0 529 481 3222 3233 0 452 552 0 0 0 0 0 0 0 0 3247 0 0 0 0 0 3237 +480 483 0.996150870505566 0.0733434670140126 -0.0480018649363473 0.418808353163512 -0.0733813777522244 0.997303476387042 0.000974364155204437 -0.0118302523760344 0.0479438900193572 0.00255182928230903 0.998846770819792 0.00660525004488932 2.37007721953473e-05 7.18602188589646e-07 -9.59337960616823e-06 -2.67233172946292e-06 -1.16915369935337e-06 4.13610956344249e-06 7.18602188589646e-07 3.82620862997096e-05 1.73522407163197e-06 5.09429752000272e-07 -5.43645456544287e-07 -3.28177647720316e-05 -9.59337960616823e-06 1.73522407163197e-06 1.0501973827412e-05 -3.98364293807162e-06 2.80954645926361e-06 -3.91644287067033e-06 -2.67233172946292e-06 5.09429752000272e-07 -3.98364293807162e-06 0.000208879783782278 4.70457856970118e-06 -2.40758550244248e-05 -1.16915369935337e-06 -5.43645456544287e-07 2.80954645926361e-06 4.70457856970118e-06 1.15772469186313e-05 3.2047288636989e-06 4.13610956344249e-06 -3.28177647720316e-05 -3.91644287067033e-06 -2.40758550244248e-05 3.2047288636989e-06 0.000103411127206498 3393 3401 0 814 305 3393 3401 0 725 366 0 0 0 0 0 0 0 0 2995 0 0 0 0 0 3439 +484 487 0.999142812378377 -0.0295214916660856 0.0290193384217645 0.383176436440158 0.0294593879944364 0.999562686011383 0.0025653835392867 0.0167171827059688 -0.0290823818079076 -0.00170829257436349 0.999575558327063 0.0683148578775497 3.25817294404632e-05 -1.40038318579771e-05 -6.16676151375809e-06 -1.06566652484875e-05 -7.04694917937808e-09 1.30194926788452e-05 -1.40038318579771e-05 4.15842898189174e-05 -1.07649001662692e-07 1.49842317672059e-05 -4.02631513216247e-08 -2.31158661231746e-05 -6.16676151375809e-06 -1.07649001662692e-07 1.39485952406747e-05 1.10180155504824e-06 1.44340361278725e-06 -2.0142429304022e-07 -1.06566652484875e-05 1.49842317672059e-05 1.10180155504824e-06 0.000184662698591026 4.37821027259501e-07 -1.254823251887e-05 -7.04694917937808e-09 -4.02631513216247e-08 1.44340361278725e-06 4.37821027259501e-07 1.20517423437778e-05 3.64109877813607e-06 1.30194926788452e-05 -2.31158661231746e-05 -2.0142429304022e-07 -1.254823251887e-05 3.64109877813607e-06 0.000134632934365125 3255 3260 0 407 549 3255 3260 0 347 621 0 0 0 0 0 0 0 0 3354 0 0 0 0 0 3140 +485 487 0.999289837065755 -0.0369742861715599 0.00726110867574071 0.25889021241494 0.0370479621825689 0.99926052183545 -0.0102887316644837 0.0140928585197771 -0.00687532073551956 0.0105504342682375 0.999920706006999 0.0310841354008619 3.65053798701178e-05 -1.64725819305779e-05 -8.27348150004599e-06 -1.65739973597394e-05 -9.79320987302647e-07 3.9940920931336e-05 -1.64725819305779e-05 5.51104095427977e-05 -1.09123160809484e-06 2.25477353985377e-05 1.80866199768795e-06 -3.14491200996844e-05 -8.27348150004599e-06 -1.09123160809484e-06 1.38710067727377e-05 -5.01562309832934e-06 2.35555319675846e-06 -2.3872172534826e-06 -1.65739973597394e-05 2.25477353985377e-05 -5.01562309832934e-06 0.000175330919110957 2.23779674318328e-06 -3.18914630079675e-05 -9.79320987302647e-07 1.80866199768795e-06 2.35555319675846e-06 2.23779674318328e-06 1.17783401938274e-05 4.47310627622419e-06 3.9940920931336e-05 -3.14491200996844e-05 -2.3872172534826e-06 -3.18914630079675e-05 4.47310627622419e-06 0.000235168173794586 3314 3319 0 187 356 3314 3319 0 135 424 0 0 0 0 0 0 0 0 3574 0 0 0 0 0 3341 +482 484 0.998680047682772 0.0433572001157985 -0.0275375299991669 0.231276191209343 -0.0426887887507638 0.998790081262803 0.0244139485957446 -0.00500513492941901 0.0285627322805273 -0.0232061795468707 0.999322592337184 0.0166761488215169 3.55510435322631e-05 -4.99858629852115e-06 -5.8262839414264e-06 -1.15013197600062e-06 -1.25376004159168e-06 1.03885458718228e-05 -4.99858629852115e-06 0.000102139354496063 -1.98656053317102e-06 9.54104981812857e-05 1.31578108157228e-05 0.000271846798322969 -5.8262839414264e-06 -1.98656053317102e-06 1.19689101246561e-05 -5.32226326354289e-06 4.02032055882513e-06 -1.12201933615143e-05 -1.15013197600062e-06 9.54104981812857e-05 -5.32226326354289e-06 0.000377145045632006 3.01330202820629e-05 0.000612865967237099 -1.25376004159168e-06 1.31578108157228e-05 4.02032055882513e-06 3.01330202820629e-05 1.4554758942931e-05 8.05455633073167e-05 1.03885458718228e-05 0.000271846798322969 -1.12201933615143e-05 0.000612865967237099 8.05455633073167e-05 0.00215612376133881 3254 3265 0 405 126 3254 3265 0 346 183 0 0 0 0 0 0 0 0 3419 0 0 0 0 0 3639 +485 489 0.998164909035128 -0.0525908495362324 -0.0300169438143122 0.526001444113488 0.0532647934191901 0.99833557778246 0.0221118953455666 0.0237560663645324 0.0288040995850453 -0.0236701643175465 0.999304781920048 0.0723926324015375 3.8872639331917e-05 -9.5596439967957e-06 -4.19295679459699e-06 1.74406423992065e-05 -1.70695595600173e-06 2.63678308221758e-05 -9.5596439967957e-06 0.000489587038208521 1.37091765997823e-05 8.3790686424169e-05 1.67651351049865e-05 -0.000439575491998329 -4.19295679459699e-06 1.37091765997823e-05 1.23594577098095e-05 -2.3794394352018e-07 3.72342372149785e-06 -1.40385812683553e-05 1.74406423992065e-05 8.3790686424169e-05 -2.3794394352018e-07 0.000436338791420869 1.23822666995717e-05 -3.67002742937765e-05 -1.70695595600173e-06 1.67651351049865e-05 3.72342372149785e-06 1.23822666995717e-05 1.33095876097239e-05 -2.09607698396354e-05 2.63678308221758e-05 -0.000439575491998329 -1.40385812683553e-05 -3.67002742937765e-05 -2.09607698396354e-05 0.00067269525562064 3274 3287 0 551 868 3274 3287 0 488 947 0 0 0 0 0 0 0 0 3225 0 0 0 0 0 2773 +487 489 0.99938720571471 -0.0150075969066171 -0.0316225408345462 0.272593828398436 0.0162496498147311 0.999091631624867 0.0393936606329023 0.00110000823426378 0.0310026117390561 -0.0398833756376032 0.998723262176819 0.0353194542190772 3.11325116203643e-05 -2.90746108051252e-06 -8.18284217808407e-06 -1.85892058163334e-05 -2.59532754513016e-06 6.35078971783259e-06 -2.90746108051252e-06 2.73881636833054e-05 -7.09541658720106e-07 -2.0505086082423e-06 -3.21247570082041e-07 -1.00860347927773e-05 -8.18284217808407e-06 -7.09541658720106e-07 1.25013662329643e-05 5.84915947748921e-07 3.58595175464202e-06 4.80936634555035e-06 -1.85892058163334e-05 -2.0505086082423e-06 5.84915947748921e-07 0.000260033595649302 -2.03204546460741e-06 -2.8701832319408e-06 -2.59532754513016e-06 -3.21247570082041e-07 3.58595175464202e-06 -2.03204546460741e-06 1.25009426558173e-05 -6.07069812572578e-06 6.35078971783259e-06 -1.00860347927773e-05 4.80936634555035e-06 -2.8701832319408e-06 -6.07069812572578e-06 0.000171316319854377 3463 3476 0 285 329 3463 3476 0 218 399 0 0 0 0 0 0 0 0 3507 0 0 0 0 0 3328 +486 490 0.998898905156589 -0.0362287645005447 -0.0298069438173751 0.541395573753483 0.0373905727927201 0.998524080187162 0.0393904347857945 0.0185727642783717 0.0283358843730062 -0.0404615608837042 0.998779224727694 0.0420238299147232 3.72185037424164e-05 -1.5067722267628e-05 -9.15598482330013e-06 -6.15954969564927e-06 1.51054620095061e-06 1.33119702059376e-05 -1.5067722267628e-05 4.95706904959611e-05 -8.49158138317835e-07 -5.43665456406891e-06 -2.14111147473992e-06 1.51074036813885e-06 -9.15598482330013e-06 -8.49158138317835e-07 1.26179728939915e-05 -4.90059265228417e-06 2.22485472630421e-06 2.13353252700198e-06 -6.15954969564927e-06 -5.43665456406891e-06 -4.90059265228417e-06 0.000232107259225531 9.44504187715185e-06 -1.90585835596811e-05 1.51054620095061e-06 -2.14111147473992e-06 2.22485472630421e-06 9.44504187715185e-06 1.40202663691344e-05 -5.89144229725891e-06 1.33119702059376e-05 1.51074036813885e-06 2.13353252700198e-06 -1.90585835596811e-05 -5.89144229725891e-06 0.000272922686701551 3286 3296 0 650 880 3286 3296 0 572 957 0 0 0 0 0 0 0 0 3145 0 0 0 0 0 2751 +484 488 0.999040125284263 -0.042927282628241 0.00872218310737543 0.501310373049726 0.0426228850610235 0.99856206616199 0.0325129157623956 0.0176094853325168 -0.0101053323091446 -0.0321099428285535 0.999433256316033 0.0772628706063197 4.54823590576269e-05 -2.28795400300706e-05 -3.4914520574776e-06 5.32055268382811e-06 -1.19123650495793e-06 1.99712679859607e-05 -2.28795400300706e-05 6.29164249745756e-05 -1.92459992817364e-07 -2.04761163843892e-05 -9.19172747305703e-07 -4.20430555874508e-05 -3.4914520574776e-06 -1.92459992817364e-07 1.24972089824439e-05 2.13065282287461e-06 3.70915502407607e-06 -1.10425527218144e-06 5.32055268382811e-06 -2.04761163843892e-05 2.13065282287461e-06 0.00145314183742541 5.39544075786439e-05 -2.03164248022406e-05 -1.19123650495793e-06 -9.19172747305703e-07 3.70915502407607e-06 5.39544075786439e-05 1.35444519453327e-05 -2.6847113080682e-06 1.99712679859607e-05 -4.20430555874508e-05 -1.10425527218144e-06 -2.03164248022406e-05 -2.6847113080682e-06 0.000135591395309273 3325 3330 0 550 790 3325 3330 0 480 870 0 0 0 0 0 0 0 0 3228 0 0 0 0 0 2868 +485 488 0.998776199904638 -0.0493918281006348 -0.00255926179345603 0.391386741041316 0.0494328764835861 0.998581699031976 0.0197732415393014 0.0169115630987208 0.00157899544287543 -0.0198755547165451 0.999801214791271 0.0612038647211368 3.47959595976238e-05 -7.4412904240267e-06 -5.47351726261256e-06 2.11121629972046e-05 -2.65165465424346e-07 1.96551447419287e-07 -7.4412904240267e-06 3.04792920609369e-05 -2.12564710533827e-06 5.11395651737627e-06 2.05921405253162e-07 -1.03256315906002e-05 -5.47351726261256e-06 -2.12564710533827e-06 1.196327364672e-05 -3.65247445065601e-06 2.5996729385491e-06 2.20863629872322e-06 2.11121629972046e-05 5.11395651737627e-06 -3.65247445065601e-06 0.000234988094243477 7.49332363175368e-06 -6.29874224491442e-05 -2.65165465424346e-07 2.05921405253162e-07 2.5996729385491e-06 7.49332363175368e-06 1.2258507360143e-05 -6.57384140510175e-06 1.96551447419287e-07 -1.03256315906002e-05 2.20863629872322e-06 -6.29874224491442e-05 -6.57384140510175e-06 0.000161366615372006 3449 3454 0 356 601 3449 3454 0 293 677 0 0 0 0 0 0 0 0 3428 0 0 0 0 0 3058 +486 488 0.99936697968477 -0.0329651582394683 -0.0133767805539074 0.252633801342084 0.0333825743499426 0.998921105511476 0.0322835669265676 0.0036867096302566 0.0122981155268248 -0.0327096821442587 0.999389230004261 0.034093564445265 3.0673290806805e-05 -5.94079280550196e-06 -7.0267122284066e-06 2.00402135124043e-05 -6.6124960998568e-07 9.57821961730859e-06 -5.94079280550196e-06 2.85816923235336e-05 1.39959166013628e-07 -3.21443800474013e-07 -6.29752649057362e-07 -8.8171981561015e-06 -7.0267122284066e-06 1.39959166013628e-07 1.24340668023994e-05 2.69385059048171e-06 3.47725189993299e-06 -1.97395033590212e-06 2.00402135124043e-05 -3.21443800474013e-07 2.69385059048171e-06 0.000509709047935034 1.67194404496507e-05 -4.40524821399538e-05 -6.6124960998568e-07 -6.29752649057362e-07 3.47725189993299e-06 1.67194404496507e-05 1.26181280065571e-05 -4.06984326915053e-06 9.57821961730859e-06 -8.8171981561015e-06 -1.97395033590212e-06 -4.40524821399538e-05 -4.06984326915053e-06 0.00015289418684061 3402 3407 0 199 347 3402 3407 0 137 410 0 0 0 0 0 0 0 0 3585 0 0 0 0 0 3319 +487 490 0.999277326687631 -0.0136489296405199 -0.0354757817065211 0.410600925024377 0.0149417828534854 0.999224230274931 0.0364373538642906 0.00559785240795612 0.0349509297899196 -0.036941092987896 0.99870605693351 0.0354035357340805 3.20454071762397e-05 -1.27713498587366e-05 -1.05804606316591e-05 -9.70729261786907e-07 -8.18939435335884e-07 1.92579417655472e-05 -1.27713498587366e-05 0.000160277387978195 5.2477598081132e-06 4.85957400759135e-05 8.94605772346188e-06 -0.000154456988403144 -1.05804606316591e-05 5.2477598081132e-06 1.63924240514462e-05 7.41126971638545e-06 9.74611926455654e-07 -3.77464510693257e-06 -9.70729261786907e-07 4.85957400759135e-05 7.41126971638545e-06 0.000166555888191917 -2.03611400504191e-06 -4.48330884607438e-05 -8.18939435335884e-07 8.94605772346188e-06 9.74611926455654e-07 -2.03611400504191e-06 1.40665069523332e-05 -1.22441500290132e-05 1.92579417655472e-05 -0.000154456988403144 -3.77464510693257e-06 -4.48330884607438e-05 -1.22441500290132e-05 0.000262191645276038 3130 3140 0 499 563 3130 3140 0 425 643 0 0 0 0 0 0 0 0 3312 0 0 0 0 0 3090 +488 491 0.999898980660574 0.0135856110868016 0.00417847404492982 0.417822442595842 -0.0135815688481887 0.999907271922248 -0.000994255816940536 0.00654909279047605 -0.00419159415591344 0.000937405144953104 0.999990775862471 0.0490488881332587 3.5438349105723e-05 -1.72570068349917e-05 -4.76248237453743e-06 4.73878548586971e-06 -1.2597508146808e-06 1.98779485263543e-05 -1.72570068349917e-05 0.000209835349098331 3.90664982411665e-06 5.13758843879259e-05 7.5238651044934e-06 -0.000140739323902851 -4.76248237453743e-06 3.90664982411665e-06 1.20951094840583e-05 3.08161413891214e-06 3.83379728067306e-06 -1.7806912097489e-06 4.73878548586971e-06 5.13758843879259e-05 3.08161413891214e-06 0.000113077981287513 -1.88423792037792e-06 -3.68721280645754e-05 -1.2597508146808e-06 7.5238651044934e-06 3.83379728067306e-06 -1.88423792037792e-06 1.20697834552903e-05 -7.58023600433303e-06 1.98779485263543e-05 -0.000140739323902851 -1.7806912097489e-06 -3.68721280645754e-05 -7.58023600433303e-06 0.000187622065689356 3386 3398 0 587 510 3386 3398 0 525 585 0 0 0 0 0 0 0 0 3219 0 0 0 0 0 3184 +486 489 0.998966195048121 -0.037672187844396 -0.0254430228961857 0.406482379371539 0.0385226568755103 0.998685675007747 0.0338072099051775 0.0106882871565114 0.024135990933272 -0.0347523926850738 0.999104461577633 0.039133247492088 3.58787230196965e-05 -7.61439249535025e-06 -7.43281550835691e-06 2.70973393127e-06 -1.14494383958214e-07 6.18015728667983e-06 -7.61439249535025e-06 2.73763528105365e-05 1.6569004268596e-06 -7.90074473543491e-06 -7.44184107015462e-07 -2.24900072115678e-05 -7.43281550835691e-06 1.6569004268596e-06 1.45501160657249e-05 5.59297701508909e-06 9.6298226916549e-07 -5.35112322285957e-06 2.70973393127e-06 -7.90074473543491e-06 5.59297701508909e-06 0.000344391047194847 6.01172955502341e-06 -1.39883202077721e-05 -1.14494383958214e-07 -7.44184107015462e-07 9.6298226916549e-07 6.01172955502341e-06 1.38754930087076e-05 1.9640532142417e-06 6.18015728667983e-06 -2.24900072115678e-05 -5.35112322285957e-06 -1.39883202077721e-05 1.9640532142417e-06 7.03339960662048e-05 3359 3372 0 414 611 3359 3372 0 352 684 0 0 0 0 0 0 0 0 3371 0 0 0 0 0 3021 +488 490 0.996383172547293 0.000184382702580443 -0.0849737575231941 0.276000529470831 0.000908214085967396 0.99991741805105 0.0128192131309306 0.0029054555214514 0.0849691038658502 -0.0128500226124767 0.996300721824035 0.00914994674044149 3.64386733877121e-05 -9.73697199393357e-06 -9.12781896493501e-06 2.24375511956634e-05 1.00795410982216e-06 -4.12937290156523e-05 -9.73697199393357e-06 0.000812431796641063 2.75248969466607e-05 -0.000132677115548302 -1.60927064569266e-05 0.000381853477458835 -9.12781896493501e-06 2.75248969466607e-05 1.24910484412928e-05 -6.57540865088855e-06 2.81985538507747e-06 1.61518947276738e-05 2.24375511956634e-05 -0.000132677115548302 -6.57540865088855e-06 0.000236524619988118 1.21108087358834e-05 -0.000247160264331342 1.00795410982216e-06 -1.60927064569266e-05 2.81985538507747e-06 1.21108087358834e-05 1.40026849754868e-05 -5.17454848610499e-05 -4.12937290156523e-05 0.000381853477458835 1.61518947276738e-05 -0.000247160264331342 -5.17454848610499e-05 0.00128270781459547 3043 3053 0 330 286 3043 3053 0 260 353 0 0 0 0 0 0 0 0 3482 0 0 0 0 0 3381 +487 491 0.999969022949669 0.00179387505438905 -0.00766388631003014 0.549191832330272 -0.00157977686956405 0.999610829689627 0.02785127415859 0.0111456123407051 0.00771086545896225 -0.027838304177945 0.999582698616963 0.108797368281796 3.35250864788775e-05 -3.2973139936858e-06 -8.14013636009844e-06 3.55446522481708e-06 6.78993176077077e-07 -1.90791078397775e-06 -3.2973139936858e-06 0.000146068533675242 8.44687360612667e-07 6.42150575988811e-06 -9.73997989490235e-07 4.87528856941314e-05 -8.14013636009844e-06 8.44687360612667e-07 1.6152737885892e-05 3.50023129413746e-06 1.91884445687913e-06 -7.01828673996727e-06 3.55446522481708e-06 6.42150575988811e-06 3.50023129413746e-06 0.000179225253743494 2.09653885473156e-06 -0.00012890392159586 6.78993176077077e-07 -9.73997989490235e-07 1.91884445687913e-06 2.09653885473156e-06 1.3967064784724e-05 -1.32492155168384e-05 -1.90791078397775e-06 4.87528856941314e-05 -7.01828673996727e-06 -0.00012890392159586 -1.32492155168384e-05 0.000658693241081306 3258 3270 0 779 797 3258 3270 0 703 885 0 0 0 0 0 0 0 0 3039 0 0 0 0 0 2882 +492 494 0.998069381119692 0.04232355601111 -0.0454557705679772 0.28893385322661 -0.0422310186221073 0.999103384785677 0.00299459111449606 0.00972705259315431 0.0455417559772719 -0.00106916620701313 0.998961863809689 0.0390513832089963 3.80278459967728e-05 -2.68815647273341e-05 -9.69343381806613e-06 -7.9766562428317e-06 -4.7463278875567e-07 3.50246574355464e-05 -2.68815647273341e-05 0.000125047620449973 1.63980491785118e-06 -3.7698998269452e-06 -8.23540042933345e-08 -0.000108575804209304 -9.69343381806613e-06 1.63980491785118e-06 1.49403314964958e-05 -1.613174549769e-06 1.68791369151437e-06 -2.72901298634159e-07 -7.9766562428317e-06 -3.7698998269452e-06 -1.613174549769e-06 4.99579171140988e-05 -4.6678905105792e-06 4.87418032373312e-06 -4.7463278875567e-07 -8.23540042933345e-08 1.68791369151437e-06 -4.6678905105792e-06 1.22432998628602e-05 -2.1672005050428e-06 3.50246574355464e-05 -0.000108575804209304 -2.72901298634159e-07 4.87418032373312e-06 -2.1672005050428e-06 0.000322279602853718 3281 3308 0 419 229 3281 3308 0 377 310 0 0 0 0 0 0 0 0 3408 0 0 0 0 0 3492 +490 494 0.996258169260174 0.0758419534329077 -0.0414446411716466 0.586144935264353 -0.0768558549777768 0.99676659633625 -0.0234420558800319 0.00534646981658699 0.0395327426066144 0.0265396030062294 0.998865762619918 0.0449751299375787 3.37989500408994e-05 -5.83810016965202e-06 -1.00514885620269e-05 4.31335425535126e-06 5.99152818085477e-07 -1.20005314189836e-07 -5.83810016965202e-06 3.88189539388679e-05 3.21463917813402e-06 -2.38538159774446e-06 -1.83868800495492e-06 -3.00192419420913e-05 -1.00514885620269e-05 3.21463917813402e-06 1.300122943018e-05 -2.01807996695865e-06 1.67528075618475e-06 -2.71365321495706e-06 4.31335425535126e-06 -2.38538159774446e-06 -2.01807996695865e-06 0.000105974021100263 -6.75615756711522e-08 -8.18838844016672e-06 5.99152818085477e-07 -1.83868800495492e-06 1.67528075618475e-06 -6.75615756711522e-08 1.43645820131145e-05 -1.82738165107818e-06 -1.20005314189836e-07 -3.00192419420913e-05 -2.71365321495706e-06 -8.18838844016672e-06 -1.82738165107818e-06 0.000118316111500044 3341 3368 0 1042 676 3341 3368 0 968 775 0 0 0 0 0 0 0 0 2772 0 0 0 0 0 3021 +492 495 0.997339785191293 0.0487118608922756 -0.0542264463430586 0.418433323605391 -0.0483703276924431 0.998800603658067 0.00759378240450902 0.0127723444348947 0.0545313146138133 -0.00495063033289201 0.998499788175139 0.0328858867412932 3.4748207465644e-05 -8.34656996043324e-06 -5.98525012177698e-06 8.82809788391809e-07 -1.87918737013896e-06 1.90349824759367e-05 -8.34656996043324e-06 0.000826152364378707 1.95817983421239e-05 2.71887500382734e-05 1.77717138596034e-05 -0.000497949665313982 -5.98525012177698e-06 1.95817983421239e-05 1.21673856697714e-05 -8.51608838691029e-07 4.46431941873247e-06 -1.32927311533903e-05 8.82809788391809e-07 2.71887500382734e-05 -8.51608838691029e-07 8.40084973504585e-05 2.64749844235668e-07 -2.18437475917259e-05 -1.87918737013896e-06 1.77717138596034e-05 4.46431941873247e-06 2.64749844235668e-07 1.25985165291804e-05 -1.1952440501557e-05 1.90349824759367e-05 -0.000497949665313982 -1.32927311533903e-05 -2.18437475917259e-05 -1.1952440501557e-05 0.000380908686932998 3348 3381 0 616 442 3348 3381 0 570 529 0 0 0 0 0 0 0 0 3171 0 0 0 0 0 3277 +492 496 0.99959191226162 0.0252701602086427 -0.0133202081134757 0.568640077957925 -0.0252987295948155 0.99967797376275 -0.0019806702125459 0.0208196292045813 0.013265866803386 0.00231684626852787 0.999909320389265 0.092650379619038 4.59373908826022e-05 -2.53520803250531e-05 -1.04473045181357e-07 -1.82628440446216e-06 -2.08783572396971e-06 2.35241970325654e-05 -2.53520803250531e-05 6.62989164505665e-05 1.96828492563701e-06 1.0573819799988e-05 -3.36876117762122e-07 -6.36952094123273e-05 -1.04473045181357e-07 1.96828492563701e-06 1.42255291793258e-05 2.41681106348533e-06 3.3790074630737e-06 -1.18849096765072e-06 -1.82628440446216e-06 1.0573819799988e-05 2.41681106348533e-06 0.000120376520515214 -1.13527717385943e-06 -2.4758161903056e-05 -2.08783572396971e-06 -3.36876117762122e-07 3.3790074630737e-06 -1.13527717385943e-06 1.20079332908232e-05 -3.04080338472773e-06 2.35241970325654e-05 -6.36952094123273e-05 -1.18849096765072e-06 -2.4758161903056e-05 -3.04080338472773e-06 0.000155194094102799 3226 3256 0 791 811 3226 3256 0 744 914 0 0 0 0 0 0 0 0 2977 0 0 0 0 0 2883 +491 495 0.997264768468884 0.0633187348879834 -0.0381276721409681 0.56818400161078 -0.063412384080157 0.997986625820549 -0.00125069124327596 0.0112748390790158 0.0379717146830972 0.00366503690303703 0.999272093270159 0.0445340463200531 3.63263910457466e-05 -2.25240055524464e-05 -6.98867853556296e-06 -1.04844589202181e-06 -1.40329976296144e-06 2.96058226188452e-05 -2.25240055524464e-05 0.000212614582352316 -2.54181355716582e-06 -6.2530470936156e-06 7.01953497614809e-06 -0.000229195132712095 -6.98867853556296e-06 -2.54181355716582e-06 1.15838565316725e-05 -2.34817613495349e-06 2.63968609481744e-06 -1.95586939561994e-07 -1.04844589202181e-06 -6.2530470936156e-06 -2.34817613495349e-06 6.76736215520039e-05 -3.21543805552784e-06 -2.05775021872558e-05 -1.40329976296144e-06 7.01953497614809e-06 2.63968609481744e-06 -3.21543805552784e-06 1.21697891984257e-05 -1.10119123685393e-05 2.96058226188452e-05 -0.000229195132712095 -1.95586939561994e-07 -2.05775021872558e-05 -1.10119123685393e-05 0.000466807617180328 3237 3270 0 941 687 3237 3270 0 878 777 0 0 0 0 0 0 0 0 2836 0 0 0 0 0 3017 +490 492 0.999433429850559 0.0336258967568738 -0.00145546021730866 0.294177861051957 -0.0336507030520799 0.999161794786066 -0.0233096122659483 0.00623196797785945 0.000670433627468296 0.0233453829950202 0.999727234605303 0.0236286173460728 3.4616639019039e-05 -2.49458913431899e-06 -3.36330906035731e-06 -4.27378618540458e-06 -2.61464602096861e-06 2.50812165866042e-06 -2.49458913431899e-06 0.000119730856822092 1.78921964919286e-06 2.40434134418733e-06 -5.22684948727546e-07 -8.86877128032964e-05 -3.36330906035731e-06 1.78921964919286e-06 1.06813905079864e-05 -4.16505408902359e-06 4.85585002048002e-06 2.73908443118981e-06 -4.27378618540458e-06 2.40434134418733e-06 -4.16505408902359e-06 9.45610877166152e-05 -9.5139356939866e-08 -8.73549059320513e-05 -2.61464602096861e-06 -5.22684948727546e-07 4.85585002048002e-06 -9.5139356939866e-08 1.03319302462253e-05 -9.99546814158157e-06 2.50812165866042e-06 -8.86877128032964e-05 2.73908443118981e-06 -8.73549059320513e-05 -9.99546814158157e-06 0.000410370945282344 3202 3223 0 447 251 3202 3223 0 389 319 0 0 0 0 0 0 0 0 3378 0 0 0 0 0 3486 +491 494 0.995872269032497 0.0585352027128844 -0.0693689686778472 0.4407926322537 -0.0592974145656306 0.998199983738604 -0.00897825651683544 0.0100098298893443 0.0687185593409696 0.0130545971830573 0.997550668935914 0.0395253543535427 3.59167005308679e-05 -4.8458372276347e-05 -7.91561900051564e-06 -8.10843924528959e-07 -1.57666890598915e-06 1.65077768488721e-05 -4.8458372276347e-05 0.000783896263108455 1.36071114130754e-05 6.63507628049743e-06 2.97873307848618e-06 2.56531892229627e-05 -7.91561900051564e-06 1.36071114130754e-05 1.25007649549904e-05 -3.2744703602313e-06 3.24811950583648e-06 6.80974939233871e-06 -8.10843924528959e-07 6.63507628049743e-06 -3.2744703602313e-06 3.84818999642381e-05 -5.26398916872555e-06 -1.52486199650085e-05 -1.57666890598915e-06 2.97873307848618e-06 3.24811950583648e-06 -5.26398916872555e-06 1.12699771578596e-05 -6.18910946772392e-06 1.65077768488721e-05 2.56531892229627e-05 6.80974939233871e-06 -1.52486199650085e-05 -6.18910946772392e-06 0.000344258503142538 3109 3136 0 717 448 3109 3136 0 661 531 0 0 0 0 0 0 0 0 3096 0 0 0 0 0 3263 +495 499 0.990925186121729 -0.13395819066916 -0.0110670078278588 0.594317935497903 0.13303482857125 0.989190364674725 -0.0616778470903743 0.0837728605224146 0.0192096303096933 0.0596458346184409 0.998034751156509 0.0430590959803576 4.61283240978808e-05 -1.26556086423733e-05 -2.1161371485889e-06 3.9934055898003e-06 3.2386243138756e-06 2.07853208458471e-05 -1.26556086423733e-05 0.000124112664898763 -8.69515600536927e-06 6.30089371296201e-05 2.50446354142044e-07 -8.64269092038041e-05 -2.1161371485889e-06 -8.69515600536927e-06 1.77827845060504e-05 -1.26715773632181e-05 1.23950372443329e-07 1.69075435182933e-06 3.9934055898003e-06 6.30089371296201e-05 -1.26715773632181e-05 0.000225120498729964 7.75833651394917e-06 -4.79403616892345e-05 3.2386243138756e-06 2.50446354142044e-07 1.23950372443329e-07 7.75833651394917e-06 1.4613275372142e-05 5.92277243409571e-06 2.07853208458471e-05 -8.64269092038041e-05 1.69075435182933e-06 -4.79403616892345e-05 5.92277243409571e-06 0.000192237811825366 3335 3334 0 356 1376 3335 3334 0 291 1485 0 0 0 0 0 0 0 0 3435 0 0 0 0 0 2268 +494 496 0.999618265309119 -0.0152608767763398 0.023031050788125 0.270825959744285 0.0153027114703541 0.999881559581079 -0.0016412895428778 0.0208922615995746 -0.0230032754633533 0.00199310053079125 0.999733402897108 0.0390306662695456 4.20350780538855e-05 -1.32016663379025e-05 3.08727011199546e-08 4.66816318623441e-06 2.08296314635641e-07 1.25467801299442e-05 -1.32016663379025e-05 5.17504687722236e-05 -2.35294869499377e-06 2.02606512831431e-05 1.81151535214885e-06 -5.0336728715536e-05 3.08727011199546e-08 -2.35294869499377e-06 1.08655901975701e-05 -4.27356331558268e-06 4.23114297528788e-06 2.64805532655031e-06 4.66816318623441e-06 2.02606512831431e-05 -4.27356331558268e-06 8.83797527945359e-05 -7.28022439220728e-07 -1.83662459410706e-05 2.08296314635641e-07 1.81151535214885e-06 4.23114297528788e-06 -7.28022439220728e-07 1.05406073976626e-05 -1.62330491138299e-06 1.25467801299442e-05 -5.0336728715536e-05 2.64805532655031e-06 -1.83662459410706e-05 -1.62330491138299e-06 0.000105194111795431 3266 3296 0 232 371 3266 3296 0 187 454 0 0 0 0 0 0 0 0 3555 0 0 0 0 0 3344 +493 495 0.999583854726952 0.0275355870289474 -0.00859702368142054 0.272789221111867 -0.0272689110416201 0.999185876807745 0.0297319706468002 0.0103319542370871 0.0094087119103442 -0.0294851663537657 0.999520935801386 0.0432301340900682 4.33938306123738e-05 -1.23062544519786e-05 -4.79898390839622e-06 -4.32359992215382e-06 1.65347841980121e-06 1.96659882563447e-05 -1.23062544519786e-05 5.4602572197305e-05 8.97187413379648e-07 7.09541080626457e-06 6.77840091264167e-07 -1.49297945947824e-05 -4.79898390839622e-06 8.97187413379648e-07 1.21037579514158e-05 -1.25292008300216e-06 3.60584049141267e-06 -2.4742818996355e-07 -4.32359992215382e-06 7.09541080626457e-06 -1.25292008300216e-06 8.32480324607653e-05 -3.79402270414246e-07 1.2513802687648e-05 1.65347841980121e-06 6.77840091264167e-07 3.60584049141267e-06 -3.79402270414246e-07 1.138655606655e-05 3.59154712848448e-07 1.96659882563447e-05 -1.49297945947824e-05 -2.4742818996355e-07 1.2513802687648e-05 3.59154712848448e-07 0.000129306489041155 3270 3303 0 369 266 3270 3303 0 321 333 0 0 0 0 0 0 0 0 3427 0 0 0 0 0 3481 +493 497 0.998695451157989 -0.0389336323474746 0.0330388878228733 0.566918138968192 0.0391585748459461 0.999213844291484 -0.00618865027844799 0.0377221930520253 -0.0327719674779401 0.00747433264353243 0.999434906584295 0.0350802426100106 6.72901281786221e-05 -0.000192945042979074 1.60170469313851e-06 4.41816747357247e-08 9.78852655780396e-07 4.3785996975831e-05 -0.000192945042979074 0.00176276147782866 8.54302754378206e-07 -0.000151547396147932 -8.0170209172593e-06 -0.000229975684884878 1.60170469313851e-06 8.54302754378206e-07 1.17531653697191e-05 -3.57059582786744e-06 3.35164544013857e-06 -1.46016981541799e-06 4.41816747357247e-08 -0.000151547396147932 -3.57059582786744e-06 0.000125605076181948 -2.50717295022615e-06 1.36769598310421e-05 9.78852655780396e-07 -8.0170209172593e-06 3.35164544013857e-06 -2.50717295022615e-06 1.22010783797438e-05 1.19070811275465e-05 4.3785996975831e-05 -0.000229975684884878 -1.46016981541799e-06 1.36769598310421e-05 1.19070811275465e-05 0.000489365514790344 3223 3237 0 626 1012 3223 3237 0 563 1104 0 0 0 0 0 0 0 0 3146 0 0 0 0 0 2655 +494 498 0.995302909600257 -0.0924241651822308 0.0288078432311365 0.58642723064908 0.0940802483876618 0.993586801675831 -0.0627229973686595 0.0656679484078115 -0.0228259721496781 0.0651386308265743 0.997615123065735 0.0246579345340715 3.85558001194873e-05 -1.51775391652494e-05 -2.57979624802049e-06 -1.66665495034936e-05 1.32263511126069e-06 2.44750120420501e-05 -1.51775391652494e-05 3.24503042019757e-05 6.03740358517636e-07 1.37925616066756e-05 -5.81940994028337e-07 -2.79335398210189e-05 -2.57979624802049e-06 6.03740358517636e-07 1.11401979679602e-05 1.02001356258131e-06 3.58944799473694e-06 -2.06022683187767e-06 -1.66665495034936e-05 1.37925616066756e-05 1.02001356258131e-06 0.000203586774025007 -3.50094947359359e-06 -9.03218331710548e-06 1.32263511126069e-06 -5.81940994028337e-07 3.58944799473694e-06 -3.50094947359359e-06 1.13685707733562e-05 2.06372464575878e-06 2.44750120420501e-05 -2.79335398210189e-05 -2.06022683187767e-06 -9.03218331710548e-06 2.06372464575878e-06 5.27906867941148e-05 3256 3264 0 466 1243 3256 3264 0 405 1345 0 0 0 0 0 0 0 0 3321 0 0 0 0 0 2409 +496 499 0.993337679350961 -0.113783032395327 -0.0182668092608393 0.427300476948837 0.112702091096509 0.992262750843684 -0.0520852373576106 0.0585622246040534 0.0240518906558767 0.0496795212038952 0.998475563911721 0.0513055891634247 4.09584030965861e-05 -1.87626683598187e-05 -1.16918790178076e-06 -1.38189686492261e-05 -1.50390630269604e-07 2.24536240087508e-05 -1.87626683598187e-05 4.59878488193447e-05 -5.01602318702881e-07 8.87071068811116e-06 -9.2920754650722e-07 -3.14833443285028e-05 -1.16918790178076e-06 -5.01602318702881e-07 1.28899613211948e-05 4.34054598245543e-06 3.27225927307604e-06 5.93693831699737e-07 -1.38189686492261e-05 8.87071068811116e-06 4.34054598245543e-06 0.00027066406460119 -3.80465569675019e-06 -7.39209332067336e-06 -1.50390630269604e-07 -9.2920754650722e-07 3.27225927307604e-06 -3.80465569675019e-06 1.17898992326338e-05 1.91529302761595e-06 2.24536240087508e-05 -3.14833443285028e-05 5.93693831699737e-07 -7.39209332067336e-06 1.91529302761595e-06 8.31925864660833e-05 3258 3257 0 164 944 3258 3257 0 115 1031 0 0 0 0 0 0 0 0 3613 0 0 0 0 0 2725 +494 497 0.997554116243304 -0.0604983834599897 0.0350104379402511 0.4318438106011 0.0614819498151196 0.997722824920349 -0.0277332738761635 0.0429096283520012 -0.0332528948058848 0.0298179515005176 0.999002069444974 0.0320467530748825 3.41270964544379e-05 -1.4650318957437e-05 -6.7394948645686e-07 1.1600155371984e-07 1.21564719026645e-06 1.29962726663663e-05 -1.4650318957437e-05 2.94778588037116e-05 -9.4204639102685e-07 1.04497393731349e-05 -1.34071313430321e-06 -2.20472226249091e-05 -6.7394948645686e-07 -9.4204639102685e-07 1.22143387164895e-05 -7.38665340791572e-07 4.27452026139459e-06 1.27405633591849e-06 1.1600155371984e-07 1.04497393731349e-05 -7.38665340791572e-07 0.000183595273654569 1.87544478782421e-06 1.58741115530218e-05 1.21564719026645e-06 -1.34071313430321e-06 4.27452026139459e-06 1.87544478782421e-06 1.1499287645472e-05 3.19658583828338e-06 1.29962726663663e-05 -2.20472226249091e-05 1.27405633591849e-06 1.58741115530218e-05 3.19658583828338e-06 7.09970825865538e-05 3356 3370 0 334 797 3356 3370 0 285 901 0 0 0 0 0 0 0 0 3444 0 0 0 0 0 2860 +495 497 0.997567175524135 -0.066149290689801 0.0220000376825823 0.292280106329368 0.0669683831923025 0.996998413825827 -0.0388509778692199 0.0343963269157203 -0.0193640380449889 0.0402297672131206 0.999002802729087 0.0104551978359361 4.2781765452713e-05 -7.04177328427986e-06 -8.64982123559209e-06 9.24411132685567e-06 2.36660774800811e-06 2.22105105627411e-05 -7.04177328427986e-06 3.1637185808987e-05 -4.59100626666196e-09 -1.86045800465711e-06 1.89628954955918e-06 -9.70909785308452e-07 -8.64982123559209e-06 -4.59100626666196e-09 1.28561154777172e-05 -1.49429179190042e-06 3.29549972002349e-06 -3.34562033818498e-06 9.24411132685567e-06 -1.86045800465711e-06 -1.49429179190042e-06 0.000194859706910878 2.49308268977277e-06 -2.60042071095709e-05 2.36660774800811e-06 1.89628954955918e-06 3.29549972002349e-06 2.49308268977277e-06 1.18266241974203e-05 3.7447617893194e-06 2.22105105627411e-05 -9.70909785308452e-07 -3.34562033818498e-06 -2.60042071095709e-05 3.7447617893194e-06 0.000157790777170452 3380 3394 0 123 546 3380 3394 0 82 629 0 0 0 0 0 0 0 0 3667 0 0 0 0 0 3138 +497 499 0.996643196728549 -0.0701646294783104 -0.0421813132188883 0.302582406730983 0.0692223990952299 0.997326783145156 -0.0233997240333369 0.0291290267208158 0.0437103863881259 0.020401284065152 0.998835917320905 0.0093540204008759 4.74001853961208e-05 -1.24435631390362e-05 -1.02362167647695e-05 -1.07959621752914e-05 1.66154195194094e-06 7.76712647016219e-06 -1.24435631390362e-05 5.62581485654616e-05 -4.48644659096338e-06 1.11350161398262e-05 1.42017004192732e-07 -3.31622196327049e-05 -1.02362167647695e-05 -4.48644659096338e-06 1.6046201431383e-05 -1.5935919092111e-06 1.04827373229569e-06 8.22921167614884e-07 -1.07959621752914e-05 1.11350161398262e-05 -1.5935919092111e-06 0.000262208080549898 -2.51596217243455e-06 -6.65579643825058e-05 1.66154195194094e-06 1.42017004192732e-07 1.04827373229569e-06 -2.51596217243455e-06 1.5058461511962e-05 9.86864189259804e-06 7.76712647016219e-06 -3.31622196327049e-05 8.22921167614884e-07 -6.65579643825058e-05 9.86864189259804e-06 0.000282730726328041 3291 3290 0 137 545 3291 3290 0 86 616 0 0 0 0 0 0 0 0 3637 0 0 0 0 0 3142 +498 501 0.997429282473704 -0.0668022574645497 -0.0259284565994914 0.435358932945563 0.0677244404380429 0.997036676174035 0.0364865253372668 0.0396124587063817 0.0234142399267127 -0.0381487190017313 0.998997722023019 0.0547992508410345 3.52271721025351e-05 -6.45398870968438e-06 -8.9455030173377e-06 1.07853085028793e-05 -1.24535119752684e-06 -4.99808370531242e-06 -6.45398870968438e-06 2.93297558995529e-05 5.00029984108751e-07 1.97694158954015e-06 -1.2186032334914e-06 -5.94632733871073e-06 -8.9455030173377e-06 5.00029984108751e-07 1.20333946372684e-05 2.34720350872653e-06 2.15568649565139e-06 -4.81867629461305e-07 1.07853085028793e-05 1.97694158954015e-06 2.34720350872653e-06 0.000252686183760324 -8.08709418436309e-06 -6.60608652137946e-05 -1.24535119752684e-06 -1.2186032334914e-06 2.15568649565139e-06 -8.08709418436309e-06 1.33912612254221e-05 7.17086560517757e-06 -4.99808370531242e-06 -5.94632733871073e-06 -4.81867629461305e-07 -6.60608652137946e-05 7.17086560517757e-06 0.000142457383918633 3324 3308 0 362 776 3324 3308 0 297 857 0 0 0 0 0 0 0 0 3427 0 0 0 0 0 2896 +499 503 0.999502994690246 0.0177402512171044 0.0260585320381619 0.602783086446901 -0.0191444776566996 0.998321195165636 0.0546651649435708 0.0236732817367892 -0.0250450110896765 -0.0551368730507062 0.998164652073849 0.0101810335183321 4.12650993447918e-05 1.53857666560217e-06 -7.08298419322896e-06 -4.94347522619052e-06 1.96020266018171e-06 2.84456889168422e-06 1.53857666560217e-06 4.48903997456461e-05 6.76644615722179e-07 -7.53846772674602e-06 7.59987088786864e-09 -5.78380318764049e-06 -7.08298419322896e-06 6.76644615722179e-07 1.19268409404049e-05 3.82042794612147e-07 2.97863530418547e-06 -8.30538466557946e-07 -4.94347522619052e-06 -7.53846772674602e-06 3.82042794612147e-07 0.000405651214916084 2.05096487368244e-06 -9.0654479380298e-05 1.96020266018171e-06 7.59987088786864e-09 2.97863530418547e-06 2.05096487368244e-06 1.19815289836085e-05 -1.69952704001331e-06 2.84456889168422e-06 -5.78380318764049e-06 -8.30538466557946e-07 -9.0654479380298e-05 -1.69952704001331e-06 0.000305141876570534 3404 3395 0 957 851 3404 3395 0 867 938 0 0 0 0 0 0 0 0 2852 0 0 0 0 0 2847 +499 502 0.999192597329757 -0.0106872357281226 0.0387290128186435 0.440015699052761 0.00871558801525133 0.998674639830097 0.0507247699430501 0.0230711413966481 -0.0392197905012702 -0.0503462685083859 0.997961452802821 0.0558799622499653 3.90152949221356e-05 5.84348422327434e-06 -5.06839554769526e-06 7.77036147137189e-06 2.60051196560523e-07 4.49537041203661e-06 5.84348422327434e-06 4.66861369375869e-05 -6.76047635781718e-06 2.39098694831458e-05 -6.29061933403451e-07 -2.89206624430101e-05 -5.06839554769526e-06 -6.76047635781718e-06 1.39848764938406e-05 2.22959923907783e-06 3.4568056781898e-06 7.4912367372668e-06 7.77036147137189e-06 2.39098694831458e-05 2.22959923907783e-06 0.000408278874880661 -1.36474460511704e-05 1.55805763877669e-05 2.60051196560523e-07 -6.29061933403451e-07 3.4568056781898e-06 -1.36474460511704e-05 1.17507589731439e-05 -1.44235319115787e-07 4.49537041203661e-06 -2.89206624430101e-05 7.4912367372668e-06 1.55805763877669e-05 -1.44235319115787e-07 0.000111670080489853 3428 3418 0 572 606 3428 3418 0 495 685 0 0 0 0 0 0 0 0 3227 0 0 0 0 0 3065 +499 501 0.999463751356203 -0.0318248257122806 0.00770650331663225 0.290784186011981 0.0315971187117264 0.999106801216811 0.0280574740742895 0.0165413697129725 -0.00859254409958828 -0.0277989249917208 0.999576604345661 -3.76544562411363e-05 4.32140469800106e-05 1.4287608552812e-07 -7.29757878038493e-06 -3.38854133984922e-06 -5.86841213607003e-08 3.71860663426055e-06 1.4287608552812e-07 4.06238078727723e-05 -5.88478349747132e-08 1.22225076505624e-05 -6.7931441616571e-07 -3.90825126599003e-05 -7.29757878038493e-06 -5.88478349747132e-08 1.25490770760643e-05 4.36394454184704e-06 3.16739304760365e-06 -4.57391318820762e-07 -3.38854133984922e-06 1.22225076505624e-05 4.36394454184704e-06 0.00033577080403016 -8.23261176427686e-06 -3.61179863405144e-05 -5.86841213607003e-08 -6.7931441616571e-07 3.16739304760365e-06 -8.23261176427686e-06 1.17706173664642e-05 4.47631710120598e-06 3.71860663426055e-06 -3.90825126599003e-05 -4.57391318820762e-07 -3.61179863405144e-05 4.47631710120598e-06 0.000121599490708836 3266 3250 0 270 406 3266 3250 0 196 475 0 0 0 0 0 0 0 0 3525 0 0 0 0 0 3287 +500 503 0.997283459867726 0.0462346001240095 0.0573416290807133 0.447395235252893 -0.048989094856685 0.997664481671545 0.047598850786226 0.00223830259152507 -0.0550069928225483 -0.050278661104087 0.997219277279677 0.0246601000794851 5.01847087052422e-05 2.0332000315208e-05 4.71670467763638e-06 -5.2843342425448e-06 6.36174048138911e-07 -2.85769179461476e-05 2.0332000315208e-05 0.000125377208256788 3.18893125978758e-06 6.19457718058177e-05 5.72239918705359e-08 -0.000128196826411717 4.71670467763638e-06 3.18893125978758e-06 1.28850146943396e-05 -1.74388092716104e-07 3.36815667574845e-06 -2.1394577792253e-06 -5.2843342425448e-06 6.19457718058177e-05 -1.74388092716104e-07 0.000192428727647294 -2.44591032058303e-06 -4.56168261069249e-05 6.36174048138911e-07 5.72239918705359e-08 3.36815667574845e-06 -2.44591032058303e-06 1.19651544414299e-05 -2.7404733672509e-07 -2.85769179461476e-05 -0.000128196826411717 -2.1394577792253e-06 -4.56168261069249e-05 -2.7404733672509e-07 0.000187768758217123 3224 3215 0 780 438 3224 3215 0 698 501 0 0 0 0 0 0 0 0 3034 0 0 0 0 0 3281 +505 508 0.99870184551558 -0.00184188558544968 0.0509041375652824 0.400807369171539 0.00124275596769714 0.999929618178715 0.0117989087027097 0.00582007316163603 -0.0509222870792332 -0.0117203304757263 0.998633844075074 0.0491167220615031 4.49902151392109e-05 -7.78613640686795e-06 -2.29303863088077e-06 -3.18426532263326e-05 4.9728349726251e-07 1.12001542574896e-05 -7.78613640686795e-06 6.37928310864749e-05 5.43593287746226e-06 -3.41501240213462e-05 -1.62250711148911e-06 -3.18117426562958e-05 -2.29303863088077e-06 5.43593287746226e-06 1.61849897672762e-05 -2.65357088586875e-06 1.61910001819863e-06 -1.99786912462025e-06 -3.18426532263326e-05 -3.41501240213462e-05 -2.65357088586875e-06 0.000709819995924047 2.77891271075382e-05 -0.000177794894645974 4.9728349726251e-07 -1.62250711148911e-06 1.61910001819863e-06 2.77891271075382e-05 1.38180676115289e-05 -1.15926402186714e-05 1.12001542574896e-05 -3.18117426562958e-05 -1.99786912462025e-06 -0.000177794894645974 -1.15926402186714e-05 0.000186035260732247 3210 3218 0 527 508 3210 3218 0 463 586 0 0 0 0 0 0 0 0 3270 0 0 0 0 0 3208 +506 510 0.999317844569274 -0.0358311510087956 -0.00894282633204383 0.54022179480158 0.0359024726578602 0.999323705144329 0.00794636984170205 0.0209759616958948 0.00865205076683055 -0.00826201876023017 0.999928437971205 0.0390314110688756 4.6434044151141e-05 -6.58371502969438e-06 -1.60000648701933e-06 -4.28689889821422e-06 -1.48603889929317e-06 1.57216257765366e-05 -6.58371502969438e-06 2.98864304327094e-05 3.10319366525742e-06 3.79815989055596e-06 -6.32462979424659e-07 -1.70512471664238e-05 -1.60000648701933e-06 3.10319366525742e-06 1.20215960064523e-05 1.45492403342713e-06 3.40049827629128e-06 -2.30224902495188e-06 -4.28689889821422e-06 3.79815989055596e-06 1.45492403342713e-06 0.000398564800677837 5.42775563944605e-06 3.69734371547319e-06 -1.48603889929317e-06 -6.32462979424659e-07 3.40049827629128e-06 5.42775563944605e-06 1.21894188173411e-05 -1.09754298667502e-06 1.57216257765366e-05 -1.70512471664238e-05 -2.30224902495188e-06 3.69734371547319e-06 -1.09754298667502e-06 0.000127473584323879 3298 3296 0 659 879 3298 3296 0 578 956 0 0 0 0 0 0 0 0 3151 0 0 0 0 0 2822 +504 507 0.999667704573752 0.0250847893125202 0.00593580469622697 0.395689557074066 -0.0252859997605513 0.999007183532494 0.0366778607143746 -0.00104550493782578 -0.00500985512312261 -0.0368157655851421 0.999309511991167 0.0548867277130626 4.96986475831158e-05 -2.29335776059563e-05 -1.94189900866958e-06 -4.3047570911968e-06 -3.00886498216839e-06 2.12877880126101e-05 -2.29335776059563e-05 0.000116641903306329 1.48007867455044e-06 1.71720727331135e-06 9.91581820795087e-07 -0.000111659866588651 -1.94189900866958e-06 1.48007867455044e-06 1.36192814830897e-05 3.65983547987173e-06 3.55153871062113e-06 -6.12481525281267e-07 -4.3047570911968e-06 1.71720727331135e-06 3.65983547987173e-06 0.00048475904297353 1.93150959016962e-05 -4.43527857185996e-05 -3.00886498216839e-06 9.91581820795087e-07 3.55153871062113e-06 1.93150959016962e-05 1.37157048452702e-05 -4.64936779323866e-06 2.12877880126101e-05 -0.000111659866588651 -6.12481525281267e-07 -4.43527857185996e-05 -4.64936779323866e-06 0.000258722724025618 3282 3288 0 602 428 3282 3288 0 528 492 0 0 0 0 0 0 0 0 3214 0 0 0 0 0 3298 +507 510 0.998657363381978 -0.0389658140252192 -0.03413408707302 0.430469047052552 0.0390089272021942 0.999238683344588 0.000597751041325942 0.021322199791032 0.0340848083681044 -0.00192848259663419 0.99941708350087 0.0445181038805912 3.99783299636604e-05 -9.18639528281884e-06 -4.23699589617356e-06 4.21806563850917e-06 -2.13633442742803e-06 3.50269581068729e-06 -9.18639528281884e-06 2.93127199171645e-05 1.35339381196179e-06 4.91981111304327e-06 1.02422150492453e-07 -6.77771469067751e-06 -4.23699589617356e-06 1.35339381196179e-06 1.28633149877564e-05 -1.59693106784946e-06 3.2274691014778e-06 -1.3572809730328e-06 4.21806563850917e-06 4.91981111304327e-06 -1.59693106784946e-06 0.000284298578966699 2.90599037064707e-06 -1.31676483774281e-05 -2.13633442742803e-06 1.02422150492453e-07 3.2274691014778e-06 2.90599037064707e-06 1.15566487856916e-05 -5.84016858340383e-06 3.50269581068729e-06 -6.77771469067751e-06 -1.3572809730328e-06 -1.31676483774281e-05 -5.84016858340383e-06 0.000200070321264685 3287 3285 0 449 677 3287 3285 0 389 754 0 0 0 0 0 0 0 0 3359 0 0 0 0 0 3018 +505 509 0.99919954501127 -0.0193744324256269 0.0349985802205728 0.543997626371848 0.0187796650785598 0.99967493827862 0.017243606269381 0.0111574527207405 -0.0353212886062807 -0.0165725419239516 0.999238588839207 0.0203747122657603 4.68121306168134e-05 -1.56650471336176e-05 -1.45012418572504e-06 5.66237456309112e-06 -2.50926154734043e-06 -4.04137866395974e-06 -1.56650471336176e-05 0.000131501667039683 5.68046974068534e-06 -4.43038165857795e-05 7.35846705592034e-07 -0.000144966903502605 -1.45012418572504e-06 5.68046974068534e-06 1.53959321116361e-05 4.21213604406305e-06 2.0780873429673e-06 -6.43817684974374e-06 5.66237456309112e-06 -4.43038165857795e-05 4.21213604406305e-06 0.0012324883980189 2.05225873182451e-05 -0.000129675390707641 -2.50926154734043e-06 7.35846705592034e-07 2.0780873429673e-06 2.05225873182451e-05 1.36172215724911e-05 -7.60273334512194e-06 -4.04137866395974e-06 -0.000144966903502605 -6.43817684974374e-06 -0.000129675390707641 -7.60273334512194e-06 0.000389403867937075 3179 3181 0 737 832 3179 3181 0 664 915 0 0 0 0 0 0 0 0 3064 0 0 0 0 0 2860 +508 510 0.998606421329173 -0.0270147401220677 -0.0453367301013038 0.240673106573314 0.0275404152271122 0.999560050327368 0.0110105094645298 0.00906864038298965 0.0450193381699416 -0.0122437578254145 0.998911081921235 0.0142991734636007 4.15156324970916e-05 -9.12271177075327e-06 -6.75655385366292e-06 2.05101654353158e-05 1.69628651259755e-06 -1.00170553490726e-05 -9.12271177075327e-06 5.18024079459429e-05 6.441993536399e-07 -2.10016853639491e-06 2.99223936615428e-07 -2.65189599813405e-05 -6.75655385366292e-06 6.441993536399e-07 1.40020795889375e-05 7.11106825588382e-06 2.18888196146344e-06 -4.08231669558045e-06 2.05101654353158e-05 -2.10016853639491e-06 7.11106825588382e-06 0.000712840215449954 2.54244480426527e-07 -1.20492891786271e-05 1.69628651259755e-06 2.99223936615428e-07 2.18888196146344e-06 2.54244480426527e-07 1.1933899890869e-05 -7.79975575599283e-06 -1.00170553490726e-05 -2.65189599813405e-05 -4.08231669558045e-06 -1.20492891786271e-05 -7.79975575599283e-06 0.000300875508890499 3245 3243 0 192 312 3245 3243 0 140 388 0 0 0 0 0 0 0 0 3619 0 0 0 0 0 3384 +514 516 0.998774390892761 0.0342452939670568 -0.03573480009603 0.272145271756461 -0.0343614622845256 0.999405979502707 -0.00264159873997885 -0.00936519595066913 0.0356231105669128 0.00386626115825025 0.999357816809472 0.00310722542637409 3.96173257933258e-05 -5.72904457560311e-06 -7.3938042370996e-06 1.54301899219928e-05 -9.80011763956681e-07 1.08728940056819e-05 -5.72904457560311e-06 8.33557127354909e-05 4.3896651896458e-06 3.24434473855789e-05 1.54520417243374e-06 -7.17618891458843e-05 -7.3938042370996e-06 4.3896651896458e-06 1.23025523940066e-05 -6.18331802134066e-06 3.85709814186581e-06 -1.69236244932748e-06 1.54301899219928e-05 3.24434473855789e-05 -6.18331802134066e-06 0.000196811649149498 8.09414263072521e-06 3.07525924296991e-05 -9.80011763956681e-07 1.54520417243374e-06 3.85709814186581e-06 8.09414263072521e-06 1.19681713842938e-05 2.4969542539815e-06 1.08728940056819e-05 -7.17618891458843e-05 -1.69236244932748e-06 3.07525924296991e-05 2.4969542539815e-06 0.000155881383816775 2990 3010 0 427 197 2990 3010 0 370 262 0 0 0 0 0 0 0 0 3409 0 0 0 0 0 3540 +512 515 0.998283894881908 0.0544787802941491 -0.0214785408505852 0.408225529892055 -0.054906294465143 0.998294309024948 -0.0198436739670201 -0.0119308828805823 0.020360845943021 0.0209889272251874 0.9995723590048 0.0648332572366011 4.84739033194558e-05 4.49482629617313e-06 1.29041131915316e-06 2.19369273569958e-05 -1.4490484824215e-06 5.65008682068374e-06 4.49482629617313e-06 6.35371448984144e-05 -1.13126884764378e-06 1.32085067117467e-05 1.4779203409637e-06 -1.26066978955469e-05 1.29041131915316e-06 -1.13126884764378e-06 1.4220222957821e-05 -1.10969593495328e-05 3.28398595064211e-06 -1.61751053509464e-06 2.19369273569958e-05 1.32085067117467e-05 -1.10969593495328e-05 0.000537315164389936 2.7563272803366e-05 1.21027723572289e-05 -1.4490484824215e-06 1.4779203409637e-06 3.28398595064211e-06 2.7563272803366e-05 1.31222797467359e-05 -1.74849264655247e-06 5.65008682068374e-06 -1.26066978955469e-05 -1.61751053509464e-06 1.21027723572289e-05 -1.74849264655247e-06 0.00018670620666918 3131 3143 0 736 355 3131 3143 0 659 424 0 0 0 0 0 0 0 0 3096 0 0 0 0 0 3367 +516 519 0.998751945586797 -0.0498685941822606 0.00277028895110714 0.407667509219204 0.0499223352820307 0.998440740287335 -0.0249769608732956 0.00178342217088999 -0.00152040342545665 0.0250840875608946 0.999684188593909 0.0365719449539354 5.16062646815144e-05 -1.65986396879885e-05 -1.38836418469987e-06 -9.01691451808662e-06 -1.69447589602326e-06 2.19759525138135e-05 -1.65986396879885e-05 0.000153634869769252 2.45065985331744e-06 8.74551675614727e-05 -1.45686309015117e-06 -0.000167517165991848 -1.38836418469987e-06 2.45065985331744e-06 1.69982443363302e-05 -2.26568871012659e-06 2.25380242133661e-06 1.63826486252359e-07 -9.01691451808662e-06 8.74551675614727e-05 -2.26568871012659e-06 0.000298293887069349 1.35505527478425e-06 -5.597352068862e-05 -1.69447589602326e-06 -1.45686309015117e-06 2.25380242133661e-06 1.35505527478425e-06 1.32541759229067e-05 2.77703881866809e-06 2.19759525138135e-05 -0.000167517165991848 1.63826486252359e-07 -5.597352068862e-05 2.77703881866809e-06 0.000355273122296313 2990 3003 0 402 656 2990 3003 0 352 738 0 0 0 0 0 0 0 0 3422 0 0 0 0 0 3011 +514 517 0.999509185216616 0.0312690172784588 -0.00190715129355627 0.398682002414619 -0.0312682625046903 0.999510938270633 0.000424308020824654 -0.0154901730882414 0.00191948627368104 -0.000364466456892248 0.999998091366502 0.0488151621214111 4.41739768596956e-05 -9.6667942839669e-06 -1.9001422240627e-07 4.16389412046217e-06 -3.32526873473395e-06 4.84686240586271e-06 -9.6667942839669e-06 4.93376774128243e-05 1.97935340259251e-06 2.63552472859693e-05 1.33001881323223e-06 -3.96925591483513e-05 -1.9001422240627e-07 1.97935340259251e-06 1.41963542986184e-05 -1.68512837567571e-06 3.84093816968785e-06 -1.57059053284301e-06 4.16389412046217e-06 2.63552472859693e-05 -1.68512837567571e-06 0.000241456097753627 7.19033603313198e-06 6.95475086872939e-07 -3.32526873473395e-06 1.33001881323223e-06 3.84093816968785e-06 7.19033603313198e-06 1.22460022481046e-05 -1.29037431273494e-07 4.84686240586271e-06 -3.96925591483513e-05 -1.57059053284301e-06 6.95475086872939e-07 -1.29037431273494e-07 0.00014268435590501 3080 3099 0 623 403 3080 3099 0 563 479 0 0 0 0 0 0 0 0 3202 0 0 0 0 0 3309 +515 519 0.998448013189562 -0.0344461066358183 0.0437610636919495 0.538721118214954 0.0353868588157083 0.999154963412443 -0.0209076376340366 -0.00495136483902675 -0.0430038972765743 0.0224237558386834 0.998823227599916 0.0179426319138796 5.14232628280764e-05 -3.48961714754249e-05 2.63531947502779e-06 1.6727037838454e-05 4.44478320660264e-06 3.10894102109728e-05 -3.48961714754249e-05 0.00077806886855828 -7.89024477225836e-06 -0.000251725964779156 -2.20997729761894e-05 -0.000954356648355073 2.63531947502779e-06 -7.89024477225836e-06 1.51098289255505e-05 -3.82639802348149e-06 4.24796670742934e-06 1.52091591119392e-05 1.6727037838454e-05 -0.000251725964779156 -3.82639802348149e-06 0.000354917375773649 9.59296360413855e-06 0.000290705043631032 4.44478320660264e-06 -2.20997729761894e-05 4.24796670742934e-06 9.59296360413855e-06 1.15419825437111e-05 2.72852473848112e-05 3.10894102109728e-05 -0.000954356648355073 1.52091591119392e-05 0.000290705043631032 2.72852473848112e-05 0.00133756004333242 2999 3012 0 684 859 2999 3012 0 612 954 0 0 0 0 0 0 0 0 3129 0 0 0 0 0 2806 +515 517 0.998659320582253 0.0108498096100635 0.050614652479477 0.262937067819504 -0.0109217406404529 0.999939700710449 0.00114478141169669 -0.00561664532098839 -0.0505991797915296 -0.00169604673380771 0.998717600941278 0.00801623989426913 5.05256230413143e-05 -4.46774891402872e-05 -2.59852361811651e-06 2.01223121904332e-06 4.9587879803503e-06 3.51678190077307e-05 -4.46774891402872e-05 0.000504368388433945 -6.19813871300864e-06 6.47918399265693e-05 6.50576422500069e-06 -0.000225571740527639 -2.59852361811651e-06 -6.19813871300864e-06 1.54691001648596e-05 1.59086708719425e-06 3.44255623858403e-06 8.62328150382467e-06 2.01223121904332e-06 6.47918399265693e-05 1.59086708719425e-06 0.000195562377503734 5.19218992593425e-06 -2.92466045120653e-05 4.9587879803503e-06 6.50576422500069e-06 3.44255623858403e-06 5.19218992593425e-06 1.24413539833657e-05 -1.79712614301797e-07 3.51678190077307e-05 -0.000225571740527639 8.62328150382467e-06 -2.92466045120653e-05 -1.79712614301797e-07 0.000288563912271376 3040 3059 0 337 249 3040 3059 0 280 324 0 0 0 0 0 0 0 0 3483 0 0 0 0 0 3463 +517 520 0.996313445898331 -0.0790798416043284 -0.0332550172759972 0.417230090652453 0.0783652563810745 0.996675924442524 -0.0222707931823094 0.0090850690617683 0.0349056458831664 0.0195826527435652 0.999198736787134 0.0109544423322584 6.03091892680572e-05 -3.481932872912e-07 -4.03051040189084e-06 -3.3713420583323e-06 -2.64178124788032e-06 4.44171154396914e-06 -3.481932872912e-07 0.00011198600423766 -3.13832015440572e-06 1.48185716754138e-05 -9.88544530181327e-07 -8.75238942052124e-05 -4.03051040189084e-06 -3.13832015440572e-06 1.4623829467271e-05 -2.72349609237152e-06 4.03103082000457e-06 -5.4680800397583e-07 -3.3713420583323e-06 1.48185716754138e-05 -2.72349609237152e-06 0.000244830632170981 -2.65532956769381e-06 -1.47979756342043e-05 -2.64178124788032e-06 -9.88544530181327e-07 4.03103082000457e-06 -2.65532956769381e-06 1.14587707481706e-05 3.69248078335078e-06 4.44171154396914e-06 -8.75238942052124e-05 -5.4680800397583e-07 -1.47979756342043e-05 3.69248078335078e-06 0.000144991216510496 2980 3031 0 317 758 2980 3031 0 258 850 0 0 0 0 0 0 0 0 3480 0 0 0 0 0 2889 +519 521 0.998093328813597 -0.0543337351595416 -0.0292839922381727 0.277209810030377 0.0540238409657222 0.998476019293095 -0.0112722448485031 0.00397627448521921 0.0298518271652327 0.00966871864452786 0.999507570904128 0.00297324223364004 4.76580773569911e-05 -2.33979603518262e-06 -4.52571495091524e-06 1.00487565827612e-05 7.75041345696903e-07 3.11879822043067e-06 -2.33979603518262e-06 2.36679504239479e-05 1.8242763833738e-07 -6.54553087427492e-06 4.32437101279366e-07 1.20477439393798e-05 -4.52571495091524e-06 1.8242763833738e-07 1.32023398130385e-05 -2.53023049376354e-06 2.81890181996756e-06 -4.05577412889617e-07 1.00487565827612e-05 -6.54553087427492e-06 -2.53023049376354e-06 0.000210968599506612 -5.77531266925085e-06 4.73054744076116e-05 7.75041345696903e-07 4.32437101279366e-07 2.81890181996756e-06 -5.77531266925085e-06 1.44506695362392e-05 9.60509932719987e-06 3.11879822043067e-06 1.20477439393798e-05 -4.05577412889617e-07 4.73054744076116e-05 9.60509932719987e-06 0.000249433872087345 3296 3346 0 91 430 3296 3346 0 19 505 0 0 0 0 0 0 0 0 3630 0 0 0 0 0 3240 +518 522 0.995637748280854 -0.0867022537615229 -0.0344701811846494 0.563163008366792 0.086181870852053 0.996145924490935 -0.016308962460596 0.0164120739532813 0.0357513543053983 0.0132671139579625 0.999272647655562 0.00650929639933158 4.02061676307972e-05 -8.4008999937431e-06 -6.08705070656951e-06 1.45738772572761e-05 -3.12831202216089e-06 1.30383509344607e-05 -8.4008999937431e-06 7.62390079293456e-05 1.9080401159392e-06 -1.37759912236276e-06 -3.90055541662917e-07 -6.59855674377402e-05 -6.08705070656951e-06 1.9080401159392e-06 1.29371576887341e-05 -3.19757635872947e-06 3.76357233009839e-06 -2.59287783129297e-06 1.45738772572761e-05 -1.37759912236276e-06 -3.19757635872947e-06 0.000335619306833914 -1.0336861831431e-05 -2.29224707655748e-06 -3.12831202216089e-06 -3.90055541662917e-07 3.76357233009839e-06 -1.0336861831431e-05 1.22033834173657e-05 2.14486538900329e-06 1.30383509344607e-05 -6.59855674377402e-05 -2.59287783129297e-06 -2.29224707655748e-06 2.14486538900329e-06 0.00017270874415654 3109 3155 0 278 1079 3109 3155 0 217 1175 0 0 0 0 0 0 0 0 3265 0 0 0 0 0 2554 +516 520 0.996633402669045 -0.0818686073582892 -0.00440361369049511 0.537682003986138 0.0817626415949929 0.99644239008447 -0.020431193850528 0.0080166711476713 0.00606062073797561 0.0200023591599439 0.999781563394878 0.00664367820914177 7.27489701205663e-05 -2.47123661719813e-05 -6.21940316191594e-06 -2.75519045475636e-05 4.01555252329419e-06 4.72053054508464e-05 -2.47123661719813e-05 6.34494585058998e-05 1.2931715045547e-06 2.51929052481281e-05 -2.54175043321249e-06 -3.75069431114553e-05 -6.21940316191594e-06 1.2931715045547e-06 1.31212626825769e-05 -1.67504733237575e-07 3.62918261160322e-06 -3.72383816404215e-06 -2.75519045475636e-05 2.51929052481281e-05 -1.67504733237575e-07 0.000306360372863711 -6.28119516273169e-06 -3.13201368276058e-05 4.01555252329419e-06 -2.54175043321249e-06 3.62918261160322e-06 -6.28119516273169e-06 1.17925123504141e-05 7.14422070008122e-06 4.72053054508464e-05 -3.75069431114553e-05 -3.72383816404215e-06 -3.13201368276058e-05 7.14422070008122e-06 0.000249208307466641 2874 2925 0 516 1001 2874 2925 0 451 1090 0 0 0 0 0 0 0 0 3290 0 0 0 0 0 2645 +519 522 0.998083363493112 -0.0611949885432676 -0.00920721974681545 0.39862508623864 0.0611621646894942 0.998120587468536 -0.00380558562628738 0.00539784972219715 0.00942279835144443 0.00323515821145886 0.999950371079773 -0.0327190644174337 6.55353434261268e-05 -1.04410316427108e-05 -4.68202664841014e-06 4.22933187535402e-06 2.5904817163234e-07 2.83772228658399e-05 -1.04410316427108e-05 8.29783704463956e-05 2.4286206742202e-06 6.49512322602496e-06 2.010471622644e-07 -5.26797156307917e-05 -4.68202664841014e-06 2.4286206742202e-06 1.29750869990347e-05 3.53291393721805e-06 3.86834834945496e-06 -4.41189495292469e-06 4.22933187535402e-06 6.49512322602496e-06 3.53291393721805e-06 0.000165825434303628 -8.95599982504912e-06 1.00841134960724e-05 2.5904817163234e-07 2.010471622644e-07 3.86834834945496e-06 -8.95599982504912e-06 1.1999700440278e-05 2.11774668144407e-06 2.83772228658399e-05 -5.26797156307917e-05 -4.41189495292469e-06 1.00841134960724e-05 2.11774668144407e-06 0.000232198201891573 3236 3289 0 94 661 3236 3289 0 32 749 0 0 0 0 0 0 0 0 3462 0 0 0 0 0 2984 +520 522 0.999361376268532 -0.0280987246965139 0.0220749018819022 0.272371308362239 0.0282782117208707 0.999569179990006 -0.00786111671305454 -0.00159036653346071 -0.0218445042181256 0.00848033516649961 0.999725413076475 0.0248834787548872 6.31761643580009e-05 4.46735756863025e-06 -1.05828604673842e-06 2.71938585378531e-05 -6.43889499818076e-07 1.33444222891256e-05 4.46735756863025e-06 4.92880198554548e-05 8.08361218777535e-07 2.72355760605121e-06 -9.5922470262494e-07 1.33284089404433e-05 -1.05828604673842e-06 8.08361218777535e-07 1.1629764004948e-05 -3.68175800821611e-06 5.21803527370611e-06 -2.68663157264506e-07 2.71938585378531e-05 2.72355760605121e-06 -3.68175800821611e-06 0.000131582785981688 -4.36570721952075e-06 4.83453556876697e-05 -6.43889499818076e-07 -9.5922470262494e-07 5.21803527370611e-06 -4.36570721952075e-06 1.11250648088255e-05 2.75625005525315e-06 1.33444222891256e-05 1.33284089404433e-05 -2.68663157264506e-07 4.83453556876697e-05 2.75625005525315e-06 0.000298625461694907 3309 3371 0 67 360 3309 3371 0 67 427 0 0 0 0 0 1 3 0 3559 0 0 0 0 0 3312 +520 524 0.999156143079577 0.000175609415767868 0.041072751401341 0.580908757443749 4.01236272725658e-05 0.999986209563568 -0.00525157812296841 -0.0111757248860304 -0.0410731072167398 0.00524879453019449 0.999142357234214 0.0365301890528799 4.87741021584241e-05 -3.27280451882081e-06 1.83227246089557e-06 -3.82667984415164e-05 1.23710135386037e-06 -3.76148090385735e-06 -3.27280451882081e-06 5.43597210718201e-05 3.17238111431149e-06 -3.04477587404735e-05 -7.31551685695446e-07 -4.03544482103062e-05 1.83227246089557e-06 3.17238111431149e-06 1.39635958682245e-05 -1.28236189624547e-05 3.82656647998237e-06 -1.7131659946549e-06 -3.82667984415164e-05 -3.04477587404735e-05 -1.28236189624547e-05 0.00191735926629229 -7.42014973289013e-06 0.000148980213806656 1.23710135386037e-06 -7.31551685695446e-07 3.82656647998237e-06 -7.42014973289013e-06 1.1696124971881e-05 -1.93144336135294e-06 -3.76148090385735e-06 -4.03544482103062e-05 -1.7131659946549e-06 0.000148980213806656 -1.93144336135294e-06 8.29473756992254e-05 3314 3321 0 254 850 3314 3321 0 254 937 0 0 0 0 0 0 0 0 2984 0 0 0 0 0 2811 +518 520 0.997195390110363 -0.0577341353161873 -0.047624820859862 0.263695784152456 0.0569269053472872 0.998213600300945 -0.0181365824180452 0.00154750864728491 0.048586843797707 0.0153745827103605 0.998700626222022 0.0142213257509664 5.51696841026592e-05 -2.22363914412253e-05 -2.01549764733979e-06 -3.32353141957688e-05 -2.28218564080304e-06 4.95556746590505e-05 -2.22363914412253e-05 0.000221530497207677 -1.81962890838919e-07 0.000117579220933702 -4.92645931309592e-06 -0.000299014101282314 -2.01549764733979e-06 -1.81962890838919e-07 1.54461010771458e-05 4.5279630138008e-06 3.62264219052682e-06 2.62784122198693e-06 -3.32353141957688e-05 0.000117579220933702 4.5279630138008e-06 0.000244155191948227 -8.22094146591371e-06 -0.000237153124953265 -2.28218564080304e-06 -4.92645931309592e-06 3.62264219052682e-06 -8.22094146591371e-06 1.23590093559003e-05 6.20144757313635e-06 4.95556746590505e-05 -0.000299014101282314 2.62784122198693e-06 -0.000237153124953265 6.20144757313635e-06 0.000726873290458385 3083 3134 0 154 419 3083 3134 0 99 495 0 0 0 0 0 0 0 0 3656 0 0 0 0 0 3247 +518 521 0.995304732559875 -0.0799675470656212 -0.0545314657809821 0.412886390261501 0.0784370264693192 0.996477894179662 -0.0296553416759535 0.0100921630176366 0.0567108651191822 0.025238815890883 0.998071580574189 0.017151093380715 4.61602546726706e-05 -6.34279015362641e-07 -3.33093415469328e-06 5.2671416470035e-06 -3.57514125991521e-06 2.57104238813493e-06 -6.34279015362641e-07 5.86104992311078e-05 -4.25361800526024e-07 1.44505307370579e-05 -1.98826253150796e-06 -5.46290650413249e-05 -3.33093415469328e-06 -4.25361800526024e-07 1.21899659832752e-05 -2.11236484037481e-06 3.70675222450833e-06 1.30974632860767e-06 5.2671416470035e-06 1.44505307370579e-05 -2.11236484037481e-06 0.000237274231712472 -5.07654811427891e-06 1.14789962016139e-05 -3.57514125991521e-06 -1.98826253150796e-06 3.70675222450833e-06 -5.07654811427891e-06 1.13151849040957e-05 3.74348774894612e-06 2.57104238813493e-06 -5.46290650413249e-05 1.30974632860767e-06 1.14789962016139e-05 3.74348774894612e-06 0.000207100770317418 3065 3113 0 220 741 3065 3113 0 164 831 0 0 0 0 0 0 0 0 3486 0 0 0 0 0 2914 +521 524 0.99763656292479 0.0224447792271733 0.064942437597111 0.436263522331391 -0.02281328001127 0.999727547145922 0.0049381912403738 -0.020714814860052 -0.0648139072324651 -0.00640807014962915 0.997876793029189 0.0121846002835066 4.9589674778087e-05 -1.74060959383953e-05 3.90564749019993e-06 -1.23811168512346e-05 1.19042275274575e-06 6.68555816598348e-06 -1.74060959383953e-05 0.000534727643378186 -1.10847426099181e-05 9.07356921576137e-05 -1.37045835393511e-05 -0.000678132717164474 3.90564749019993e-06 -1.10847426099181e-05 1.33387754050342e-05 -4.11071707983295e-06 4.26631856989201e-06 1.55195702263532e-05 -1.23811168512346e-05 9.07356921576137e-05 -4.11071707983295e-06 0.00020572575853613 -5.46014105092198e-06 -9.68002083440681e-05 1.19042275274575e-06 -1.37045835393511e-05 4.26631856989201e-06 -5.46014105092198e-06 1.20838694109984e-05 2.00418738319441e-05 6.68555816598348e-06 -0.000678132717164474 1.55195702263532e-05 -9.68002083440681e-05 2.00418738319441e-05 0.00111941521740205 3210 3217 0 213 484 3210 3217 0 244 562 0 0 0 0 0 0 0 0 3179 0 0 0 0 0 3203 +522 526 0.99745581659254 0.0703212000641115 -0.0116971264528161 0.542734190680992 -0.0704934041150867 0.997399073464364 -0.0150255858020928 -0.0385676056559254 0.0106100858609648 0.0158119282180314 0.999818688065017 0.0576961599291543 6.62839817543473e-05 -3.22999948717258e-06 -7.71047191793106e-07 -9.86008472167071e-06 3.00317990202273e-07 -4.81501154273525e-06 -3.22999948717258e-06 3.14334612523904e-05 -1.80589676887869e-07 -2.57891550148931e-06 -2.74602789045315e-06 -1.93777172137983e-05 -7.71047191793106e-07 -1.80589676887869e-07 1.27347575282121e-05 -7.01284099310664e-07 3.81455833019031e-06 1.3431045066877e-06 -9.86008472167071e-06 -2.57891550148931e-06 -7.01284099310664e-07 0.000106102073007272 -9.30130995555327e-07 3.04634688995823e-05 3.00317990202273e-07 -2.74602789045315e-06 3.81455833019031e-06 -9.30130995555327e-07 1.2756693029442e-05 6.02468290225728e-06 -4.81501154273525e-06 -1.93777172137983e-05 1.3431045066877e-06 3.04634688995823e-05 6.02468290225728e-06 0.000128645121489167 3185 3234 0 719 534 3185 3234 0 719 609 0 0 0 0 0 0 0 0 2392 0 0 0 0 0 3150 +522 524 0.999412833762029 0.0291823497919924 0.0179548927139338 0.290300437018779 -0.0291652450023011 0.999573866763668 -0.0012138233330286 -0.0171478960402954 -0.0179826637544837 0.000689451771956677 0.999838061118173 0.0277620724600312 6.48835946888662e-05 -1.37432152708013e-05 -6.41290275385059e-06 -1.18296857151e-05 -1.04421545649721e-06 -7.56123169394074e-05 -1.37432152708013e-05 8.97430181172819e-05 -3.94221606210455e-06 -2.6310468342694e-05 1.01177028338086e-05 0.000436771767623371 -6.41290275385059e-06 -3.94221606210455e-06 1.28188582072272e-05 -1.42472261503485e-06 3.8235360090848e-06 -2.94391732514628e-05 -1.18296857151e-05 -2.6310468342694e-05 -1.42472261503485e-06 0.000181867763069325 -8.34407051524606e-06 -0.000223092445820159 -1.04421545649721e-06 1.01177028338086e-05 3.8235360090848e-06 -8.34407051524606e-06 1.33717971403439e-05 9.5898331857913e-05 -7.56123169394074e-05 0.000436771767623371 -2.94391732514628e-05 -0.000223092445820159 9.5898331857913e-05 0.00380120666756391 3355 3362 0 190 226 3355 3362 0 212 287 0 0 0 0 0 0 0 0 3310 0 0 0 0 0 3477 +520 523 0.999279887763028 -0.0232870504856589 0.0299569556528763 0.417126441974832 0.0235935213561538 0.999672437264493 -0.00991785882567055 -0.00464570119354765 -0.0297161851913522 0.0106175069271271 0.99950198443241 -0.016903837036794 5.78012041642282e-05 5.44288101667864e-07 -7.44592905762886e-06 1.27519154937628e-05 -3.7348296254852e-07 3.07385777555417e-06 5.44288101667864e-07 2.33090807286711e-05 6.07927051151467e-08 8.11791588098811e-06 4.35643024087273e-07 1.74819195144043e-05 -7.44592905762886e-06 6.07927051151467e-08 1.30031038644897e-05 -9.43331734728993e-07 3.9112307190537e-06 3.61350670224339e-06 1.27519154937628e-05 8.11791588098811e-06 -9.43331734728993e-07 0.000168708664377962 -6.39958445819298e-06 4.11783302297419e-05 -3.7348296254852e-07 4.35643024087273e-07 3.9112307190537e-06 -6.39958445819298e-06 1.21670941943488e-05 3.29302062714462e-06 3.07385777555417e-06 1.74819195144043e-05 3.61350670224339e-06 4.11783302297419e-05 3.29302062714462e-06 0.000348508621632349 3482 3514 0 128 578 3482 3514 0 128 663 0 0 0 0 0 5 7 0 3330 0 0 0 0 0 3076 +521 523 0.998795788242059 -0.000243537159070831 0.0490603106347336 0.292911509019389 0.000224804373816107 0.999999899711784 0.000387349216813755 -0.0100216719505028 -0.0490604000484903 -0.000375853793920973 0.998795742822829 0.0286017671848736 7.2385279320794e-05 6.21029036254489e-06 -3.57345550604048e-06 1.03250436562525e-05 1.01047187775923e-06 2.97528566537255e-05 6.21029036254489e-06 0.000247834830109446 -6.01658896276223e-06 1.42337849032418e-05 -3.35610035867258e-06 -0.000193323172921891 -3.57345550604048e-06 -6.01658896276223e-06 1.52547785021817e-05 -2.31230390612762e-06 3.69673373143214e-06 8.76882324936843e-06 1.03250436562525e-05 1.42337849032418e-05 -2.31230390612762e-06 0.000155896757642224 -6.54550669310427e-06 2.38327392305062e-06 1.01047187775923e-06 -3.35610035867258e-06 3.69673373143214e-06 -6.54550669310427e-06 1.37467148472653e-05 8.94587277587679e-06 2.97528566537255e-05 -0.000193323172921891 8.76882324936843e-06 2.38327392305062e-06 8.94587277587679e-06 0.000505054211700699 3183 3225 0 112 315 3183 3233 0 150 378 0 0 0 0 0 0 17 0 3494 0 0 0 0 0 3377 +523 526 0.996889700775342 0.0645770695306614 -0.0451744018098895 0.415307325516709 -0.0651534932405354 0.997810080982434 -0.0114045871641238 -0.0324653167803866 0.0443389987099928 0.0143123855684755 0.998914014724358 -0.0058857173922783 7.19607418400043e-05 7.64123693931196e-06 -4.56367243233402e-06 1.15244227500381e-05 2.65515481610007e-06 8.89059154364962e-06 7.64123693931196e-06 0.000120457668478734 -1.70054150152035e-06 -1.58839541340502e-05 -5.42108262799492e-06 -0.000110008978231615 -4.56367243233402e-06 -1.70054150152035e-06 1.52728740541318e-05 -1.96595536978689e-06 4.47875603572688e-06 4.4401714886732e-06 1.15244227500381e-05 -1.58839541340502e-05 -1.96595536978689e-06 0.00014736872293102 5.99304068735249e-06 4.06776639182178e-05 2.65515481610007e-06 -5.42108262799492e-06 4.47875603572688e-06 5.99304068735249e-06 1.33043528934766e-05 9.02626242695728e-06 8.89059154364962e-06 -0.000110008978231615 4.4401714886732e-06 4.06776639182178e-05 9.02626242695728e-06 0.000278212861681157 2994 3043 0 709 318 2994 3043 0 683 390 0 0 0 0 0 0 0 0 2487 0 0 0 0 0 3371 +523 525 0.998952446192953 0.045746061555659 0.00114372079655864 0.282288332277247 -0.0457226567405197 0.998831981966815 -0.0156240347168609 -0.0201833784128714 -0.0018571229639486 0.0155553737464238 0.999877283191245 -0.00862074293717961 8.3820029322564e-05 -2.49153438819169e-06 -1.61356674597735e-06 2.57569215103606e-05 4.43395176291501e-06 5.12476992196403e-05 -2.49153438819169e-06 2.88100879878068e-05 3.53426286016671e-06 -1.68053417497682e-06 -6.84247211050491e-07 -1.37271057826061e-05 -1.61356674597735e-06 3.53426286016671e-06 1.13381647853978e-05 -3.84706809723334e-06 5.47347569071918e-06 -2.92178399464062e-06 2.57569215103606e-05 -1.68053417497682e-06 -3.84706809723334e-06 0.000140847505647087 2.14712762219543e-06 6.25413892619884e-06 4.43395176291501e-06 -6.84247211050491e-07 5.47347569071918e-06 2.14712762219543e-06 1.27795077568927e-05 6.93039811309442e-06 5.12476992196403e-05 -1.37271057826061e-05 -2.92178399464062e-06 6.25413892619884e-06 6.93039811309442e-06 0.000119014878020576 3356 3370 0 436 175 3356 3370 0 420 233 0 0 0 0 0 0 0 0 2977 0 0 0 0 0 3550 +526 529 0.998717764276969 -0.00894536856305028 0.0498277803928987 0.429096363742874 0.00770414328976498 0.999656590301001 0.0250469088701164 0.00168790419754906 -0.0500347228810405 -0.0246309124688538 0.998443711311343 0.00217534116893037 6.87560573031298e-05 -2.97392459911752e-06 -6.91755564099471e-06 1.7143575437962e-05 3.61711928292147e-06 2.40321249985447e-05 -2.97392459911752e-06 3.95125534396025e-05 -4.07416832205413e-07 7.60570348882552e-06 4.43563506677332e-07 -1.60040587776411e-05 -6.91755564099471e-06 -4.07416832205413e-07 1.38427752276884e-05 -8.71141788054718e-06 3.68491403936008e-06 -8.24443691083564e-07 1.7143575437962e-05 7.60570348882552e-06 -8.71141788054718e-06 0.000202445969100011 4.15254205122537e-06 -5.95641834842172e-06 3.61711928292147e-06 4.43563506677332e-07 3.68491403936008e-06 4.15254205122537e-06 1.20488614007343e-05 1.45451151552325e-06 2.40321249985447e-05 -1.60040587776411e-05 -8.24443691083564e-07 -5.95641834842172e-06 1.45451151552325e-06 9.60181224521015e-05 3261 3298 0 193 595 3261 3298 0 163 697 0 0 0 0 0 0 0 0 2455 0 0 0 0 0 3063 +522 525 0.998337555814754 0.0519887677848142 0.0248855916955968 0.422133786090518 -0.0515020423980415 0.998476275817035 -0.0198158083199859 -0.0268096547818411 -0.025877872374939 0.0185012068460614 0.999493892460872 0.0424048057630475 7.35795320524879e-05 1.89561948894313e-05 -7.88664276134888e-06 3.10540671659788e-05 -1.22692332414977e-06 -1.09284866622542e-05 1.89561948894313e-05 0.000153067661398169 -6.12811412633257e-06 2.86123788860255e-06 -2.644106211526e-06 -0.000176794319918279 -7.88664276134888e-06 -6.12811412633257e-06 1.46668991017062e-05 -4.600000776881e-06 5.29316888160668e-06 8.94965243358843e-06 3.10540671659788e-05 2.86123788860255e-06 -4.600000776881e-06 0.000167674765783411 2.45539995841934e-07 -1.49122279738839e-05 -1.22692332414977e-06 -2.644106211526e-06 5.29316888160668e-06 2.45539995841934e-07 1.1532534166987e-05 7.06599688216677e-06 -1.09284866622542e-05 -0.000176794319918279 8.94965243358843e-06 -1.49122279738839e-05 7.06599688216677e-06 0.000402117491152673 3077 3091 0 445 378 3077 3091 0 445 444 0 0 0 0 0 0 0 0 2828 0 0 0 0 0 3331 +526 528 0.999042381310061 0.0150934305873431 0.0410671243140684 0.268980347824139 -0.0166109560602943 0.999182169022658 0.0368655563628096 -0.00557078922720084 -0.0404771106316282 -0.0375124174145252 0.998476049815234 0.0269659740626333 0.000175393687970406 -1.23668752442235e-05 -4.59116149248437e-06 5.68533986559492e-05 1.13698483328134e-05 0.000111725309888912 -1.23668752442235e-05 6.24520615521911e-05 -1.57560640970422e-07 1.18975695119896e-05 3.19450924717827e-06 -1.67288760026255e-05 -4.59116149248437e-06 -1.57560640970422e-07 1.35928570039874e-05 -5.81615401418071e-06 3.84716776432918e-06 -4.91809857905813e-06 5.68533986559492e-05 1.18975695119896e-05 -5.81615401418071e-06 0.000161507438911196 1.1599810034695e-05 5.06560954788173e-05 1.13698483328134e-05 3.19450924717827e-06 3.84716776432918e-06 1.1599810034695e-05 1.54521082805619e-05 7.76887717819638e-06 0.000111725309888912 -1.67288760026255e-05 -4.91809857905813e-06 5.06560954788173e-05 7.76887717819638e-06 0.000272569041120565 3359 3447 0 169 265 3359 3447 0 161 343 0 0 0 0 0 0 0 0 2785 0 0 0 0 0 3438 +525 527 0.998853206678308 0.0355797374480819 -0.032036756883099 0.28910756686123 -0.034713359465991 0.999026956460862 0.0272052005898188 -0.0130407186549509 0.0329735376180071 -0.0260618983896595 0.999116371234743 0.0360205173416538 7.23162226696251e-05 5.52528542811725e-06 -6.44600188178073e-06 -1.80644008701214e-06 4.12700525507384e-06 3.61567095853004e-05 5.52528542811725e-06 0.000230958259033428 2.84672731136888e-06 5.42424017368117e-06 1.09126668323297e-06 -0.000142547048665574 -6.44600188178073e-06 2.84672731136888e-06 1.69079112549068e-05 -6.39670000315821e-06 1.22636612632177e-06 -2.58376003315315e-06 -1.80644008701214e-06 5.42424017368117e-06 -6.39670000315821e-06 0.000150360977412892 5.05844610778288e-06 1.61916464693012e-05 4.12700525507384e-06 1.09126668323297e-06 1.22636612632177e-06 5.05844610778288e-06 1.47976151272885e-05 3.14315996794574e-06 3.61567095853004e-05 -0.000142547048665574 -2.58376003315315e-06 1.61916464693012e-05 3.14315996794574e-06 0.000234444936257816 3185 3243 0 309 223 3185 3243 0 259 294 0 0 0 0 0 0 0 0 2791 0 0 0 0 0 3478 +526 530 0.997339347629606 -0.0417529338974904 0.05975716007897 0.55917528707237 0.0403997604921486 0.998903031334337 0.0236768524776581 0.0126526228942837 -0.0606801864032146 -0.0211996816491086 0.997932106145527 0.0168371390748471 5.08039898708521e-05 -4.61215759739803e-06 1.9454760742366e-06 -1.79359509454741e-05 5.54772281441089e-07 -7.23695384255331e-06 -4.61215759739803e-06 7.15038748451161e-05 2.43279725621975e-06 2.74504182759694e-06 -2.15949178854233e-06 -4.87701900090611e-05 1.9454760742366e-06 2.43279725621975e-06 1.09646748675248e-05 -3.19032026070826e-06 4.34359207560686e-06 -6.73156138962661e-06 -1.79359509454741e-05 2.74504182759694e-06 -3.19032026070826e-06 0.000421500735692109 -2.95575404807296e-06 8.7795934663666e-05 5.54772281441089e-07 -2.15949178854233e-06 4.34359207560686e-06 -2.95575404807296e-06 1.09736783333852e-05 1.13534794229873e-06 -7.23695384255331e-06 -4.87701900090611e-05 -6.73156138962661e-06 8.7795934663666e-05 1.13534794229873e-06 0.000340076137157144 3306 3315 0 159 974 3306 3315 0 141 1080 0 0 0 0 0 0 0 0 2212 0 0 0 0 0 2670 +527 529 0.998581183336426 -0.0239054498023643 0.0475830826678022 0.286804712383865 0.0241290065744979 0.99970032495674 -0.00412932477716096 0.0122575148396447 -0.0474701098392672 0.00527159853688409 0.998858748232559 0.0205826084920006 3.28880003153656e-05 1.8367943591958e-06 -1.52752611673743e-06 1.75789634559886e-05 2.99785706312835e-06 3.34562709025424e-06 1.8367943591958e-06 9.09601968461978e-05 -1.63456757962204e-06 1.44634812391924e-05 -4.23192034962979e-07 -2.74541584617585e-05 -1.52752611673743e-06 -1.63456757962204e-06 1.84784906584091e-05 -2.37168432867168e-06 7.30026357740866e-07 -8.76761109777397e-06 1.75789634559886e-05 1.44634812391924e-05 -2.37168432867168e-06 0.000237518081155634 5.21790369730733e-06 -1.13123809395698e-05 2.99785706312835e-06 -4.23192034962979e-07 7.30026357740866e-07 5.21790369730733e-06 1.48553175913022e-05 3.438826609602e-06 3.34562709025424e-06 -2.74541584617585e-05 -8.76761109777397e-06 -1.13123809395698e-05 3.438826609602e-06 0.0001946882151163 3086 3109 0 59 403 3091 3129 0 91 478 0 0 0 0 0 5 25 0 2823 0 0 0 0 0 3282 +530 532 0.997639882514432 -0.0621799899556179 -0.0291258247215239 0.278479556007943 0.0617793181589328 0.997985067096887 -0.0144610407454082 0.0243703091525864 0.0299663255072594 0.0126275373981731 0.999471142472283 0.00936969664612004 5.58472638394793e-05 3.39184353872876e-06 -1.63970251282199e-06 2.98782063367376e-05 7.52757724723474e-07 1.64207180903651e-05 3.39184353872876e-06 3.89570656872428e-05 -1.97707983726003e-06 7.32615183976168e-06 4.28308806991323e-07 -1.20518301127616e-05 -1.63970251282199e-06 -1.97707983726003e-06 1.22821380847616e-05 -7.07886940371292e-07 3.65289541812285e-06 -3.28527180662212e-07 2.98782063367376e-05 7.32615183976168e-06 -7.07886940371292e-07 0.000234813287633617 -7.55169368521609e-06 9.22547975722138e-06 7.52757724723474e-07 4.28308806991323e-07 3.65289541812285e-06 -7.55169368521609e-06 1.43496292690767e-05 1.54438748644319e-06 1.64207180903651e-05 -1.20518301127616e-05 -3.28527180662212e-07 9.22547975722138e-06 1.54438748644319e-06 0.000243404251593597 3378 3369 0 126 478 3378 3369 0 83 546 0 0 0 0 0 0 0 0 2921 0 0 0 0 0 3209 +528 532 0.993149187234854 -0.116574691624778 -0.00806431443694166 0.539352667733386 0.116300684362221 0.992799566036916 -0.02869098279582 0.0607178211981972 0.0113508903452154 0.0275565409567094 0.999555798511955 0.0304922431580239 4.74256710290166e-05 -1.28322668525566e-06 -4.02727707670116e-06 1.15158073192935e-05 -1.38819973514799e-06 4.29859519026839e-05 -1.28322668525566e-06 5.12089366756996e-05 2.71676090720962e-06 2.00076844439922e-08 -2.22428125763606e-07 -1.24647622542547e-05 -4.02727707670116e-06 2.71676090720962e-06 1.37018737124204e-05 2.69795770697062e-06 1.87778492132507e-06 -6.49870548463548e-06 1.15158073192935e-05 2.00076844439922e-08 2.69795770697062e-06 0.000195483376867392 -7.18540674143293e-06 -3.40650674275393e-06 -1.38819973514799e-06 -2.22428125763606e-07 1.87778492132507e-06 -7.18540674143293e-06 1.43261144107747e-05 1.14311606971669e-05 4.29859519026839e-05 -1.24647622542547e-05 -6.49870548463548e-06 -3.40650674275393e-06 1.14311606971669e-05 0.000336089154587288 3333 3324 0 215 1177 3333 3324 0 215 1279 0 0 0 0 0 0 0 0 2374 0 0 0 0 0 2464 +534 538 0.993782577514197 0.108785358318525 -0.0237051565012827 0.597857987711624 -0.108852226059349 0.994056741605996 -0.00154510504339813 -0.0540567305253827 0.0233961858251394 0.00411585752680825 0.999717799284205 0.0633408174641247 3.4868919795026e-05 1.61167843518894e-05 -6.2516145405071e-06 -3.24257935411611e-06 -9.66103828098109e-07 -1.36214404548879e-05 1.61167843518894e-05 0.000117631059647539 -1.75876782450517e-06 -2.84736368712739e-05 2.12570746497444e-06 -0.000109349916910346 -6.2516145405071e-06 -1.75876782450517e-06 1.14466158857518e-05 1.70860779759441e-06 4.04615183074684e-06 2.9708256242884e-06 -3.24257935411611e-06 -2.84736368712739e-05 1.70860779759441e-06 0.000218401472376702 -5.69243755008752e-07 7.9872253943094e-06 -9.66103828098109e-07 2.12570746497444e-06 4.04615183074684e-06 -5.69243755008752e-07 1.22052175944858e-05 -2.48435535910886e-06 -1.36214404548879e-05 -0.000109349916910346 2.9708256242884e-06 7.9872253943094e-06 -2.48435535910886e-06 0.000157472069342154 3233 3246 0 1304 486 3233 3246 0 1209 560 0 0 0 0 0 0 0 0 1730 0 0 0 0 0 3241 +535 539 0.996582458149143 0.0804837485864036 -0.0185949004539655 0.597368845656834 -0.0807701748853019 0.99661681386414 -0.0152021436740692 -0.0476098443959317 0.0173084649351138 0.0166521030734819 0.99971152064224 0.0726080658600788 3.86452409965658e-05 6.6655006642454e-06 -5.77361612494128e-06 -5.1559632676098e-06 -2.26997007060235e-06 -8.99314695480142e-06 6.6655006642454e-06 3.97323111796107e-05 -6.76171813969592e-07 2.10257254407175e-05 -1.28005327590209e-06 -3.10468545444109e-05 -5.77361612494128e-06 -6.76171813969592e-07 1.36791520414594e-05 -3.25811148491958e-06 2.08200243757325e-06 2.11258019278926e-06 -5.1559632676098e-06 2.10257254407175e-05 -3.25811148491958e-06 0.000302655603270694 7.39736982744845e-06 -8.03857925108504e-06 -2.26997007060235e-06 -1.28005327590209e-06 2.08200243757325e-06 7.39736982744845e-06 1.38283033903489e-05 9.57695516083924e-07 -8.99314695480142e-06 -3.10468545444109e-05 2.11258019278926e-06 -8.03857925108504e-06 9.57695516083924e-07 8.72699772559036e-05 3314 3329 0 1199 567 3314 3329 0 1111 639 0 0 0 0 0 0 0 0 1773 0 0 0 0 0 3148 +532 534 0.999394023120092 0.000547837871306554 0.0348035404162301 0.295599477859409 -0.00161634728586939 0.999527937037942 0.0306804579843263 -0.00235228358915575 -0.0347703030370583 -0.0307181209442133 0.998923131713531 0.0462759208143097 7.24633472977462e-05 4.23731424886023e-06 3.75592469729707e-06 -4.25812189791895e-05 -9.64686277477817e-07 3.05429864782755e-05 4.23731424886023e-06 4.21018161416355e-05 4.16454264434938e-06 1.70222331459035e-05 -2.20361645313481e-06 -2.14426370859532e-05 3.75592469729707e-06 4.16454264434938e-06 1.39199662594992e-05 -2.69412287079963e-06 4.84513938316764e-07 3.54040618883808e-06 -4.25812189791895e-05 1.70222331459035e-05 -2.69412287079963e-06 0.000413055665858923 -2.19324256518126e-05 3.70618151904354e-05 -9.64686277477817e-07 -2.20361645313481e-06 4.84513938316764e-07 -2.19324256518126e-05 1.64476614589552e-05 -6.96176278035064e-06 3.05429864782755e-05 -2.14426370859532e-05 3.54040618883808e-06 3.70618151904354e-05 -6.96176278035064e-06 0.000135835083934848 3411 3395 0 394 300 3411 3395 0 327 365 0 0 0 0 0 0 0 0 2443 0 0 0 0 0 3389 +537 539 0.999728711108421 0.00938231373632845 0.0213184515021406 0.301921870691123 -0.00965570600947648 0.999871996413537 0.0127576694370867 -0.00614485594198475 -0.0211960262066874 -0.0129600531233679 0.999691335111036 0.0712499807863061 4.24894993349815e-05 -1.91750981475023e-06 3.03681824099092e-06 -2.20258444830988e-05 -1.46458171019172e-06 1.39651014623807e-05 -1.91750981475023e-06 3.18216195588083e-05 1.33008057306843e-07 2.23865769953034e-06 -1.43888739049748e-06 -1.34247068994882e-05 3.03681824099092e-06 1.33008057306843e-07 1.30983903936974e-05 -4.33701040553275e-06 1.76514933219584e-06 2.50086709402253e-06 -2.20258444830988e-05 2.23865769953034e-06 -4.33701040553275e-06 0.000171883538431437 3.66342035939735e-06 4.7927105940797e-06 -1.46458171019172e-06 -1.43888739049748e-06 1.76514933219584e-06 3.66342035939735e-06 1.38131848822451e-05 -4.87382339834243e-07 1.39651014623807e-05 -1.34247068994882e-05 2.50086709402253e-06 4.7927105940797e-06 -4.87382339834243e-07 8.35910802752196e-05 3350 3365 0 409 312 3350 3365 0 350 382 0 0 0 0 0 0 0 0 2867 0 0 0 0 0 3399 +533 536 0.996926009370829 0.0758301908634824 0.0197056842957025 0.458559667350629 -0.0758464851728452 0.997119503533512 7.97496548581073e-05 -0.0262206822600394 -0.0196428747101698 -0.00157411139692116 0.999805820970468 0.0535490273648674 9.34476375661394e-05 2.15614654756333e-05 1.19772606010905e-07 -1.09229189621287e-05 7.10157451934926e-08 4.29559562112202e-05 2.15614654756333e-05 0.000114921003894851 -5.6374508483318e-07 -5.07058555984518e-05 -6.87909277972269e-07 4.46971285294595e-05 1.19772606010905e-07 -5.6374508483318e-07 1.38694093742875e-05 -7.41683494259658e-06 2.3822077525637e-06 4.10019537542196e-06 -1.09229189621287e-05 -5.07058555984518e-05 -7.41683494259658e-06 0.000482601436660538 3.49230958960054e-06 -0.000152101507438298 7.10157451934926e-08 -6.87909277972269e-07 2.3822077525637e-06 3.49230958960054e-06 1.2257490320943e-05 -2.42540382905363e-06 4.29559562112202e-05 4.46971285294595e-05 4.10019537542196e-06 -0.000152101507438298 -2.42540382905363e-06 0.000282267851794839 3271 3272 0 920 345 3271 3272 0 839 407 0 0 0 0 0 0 0 0 2000 0 0 0 0 0 3385 +534 536 0.997982131965101 0.0628290386022094 0.00917475812833322 0.28531012678433 -0.0626837954061057 0.997915502022701 -0.0153425101031535 -0.0150518729010747 -0.0101195885230983 0.0147364422810243 0.999840202830943 0.0216457910031245 6.69632650207926e-05 -6.35229936315179e-06 -4.46105276531078e-07 1.4911395267558e-05 8.09656295214172e-07 3.2448487833619e-05 -6.35229936315179e-06 2.79235449346386e-05 1.35812291559656e-06 2.53991523890686e-06 -1.93952551472861e-06 -5.63698589207201e-06 -4.46105276531078e-07 1.35812291559656e-06 1.28829488728783e-05 2.01114854492027e-06 2.34263719276544e-06 3.30604113234688e-06 1.4911395267558e-05 2.53991523890686e-06 2.01114854492027e-06 0.000256335575387729 -3.59789945932405e-06 3.23139546388011e-05 8.09656295214172e-07 -1.93952551472861e-06 2.34263719276544e-06 -3.59789945932405e-06 1.3355849083133e-05 -1.58220145107512e-07 3.2448487833619e-05 -5.63698589207201e-06 3.30604113234688e-06 3.23139546388011e-05 -1.58220145107512e-07 0.000151620306488375 3411 3412 0 558 135 3411 3412 0 488 185 0 0 0 0 0 0 0 0 2543 0 0 0 0 0 3612 +538 540 0.99919215296021 -0.0246486534625169 0.0317409096470991 0.292534223734573 0.0254179308861816 0.999387212233518 -0.0240650953370691 0.00722928329085558 -0.0311282870104645 0.0248524426687133 0.999206378002659 0.0475488558472256 0.000167066531064008 1.39630747823073e-05 -6.00367212658769e-06 -7.71553846331669e-05 1.54298487472226e-05 0.000133653486410911 1.39630747823073e-05 0.000332225637362756 7.6849248676284e-06 -6.05915130851665e-05 -4.32031106378617e-06 -0.000209908696739772 -6.00367212658769e-06 7.6849248676284e-06 1.3752591584898e-05 8.31813984438008e-08 1.29850521804966e-06 -5.25341207094943e-06 -7.71553846331669e-05 -6.05915130851665e-05 8.31813984438008e-08 0.000186624681263174 -8.76996663329404e-06 -5.26756949123094e-05 1.54298487472226e-05 -4.32031106378617e-06 1.29850521804966e-06 -8.76996663329404e-06 1.41399453654404e-05 1.93192620289709e-05 0.000133653486410911 -0.000209908696739772 -5.25341207094943e-06 -5.26756949123094e-05 1.93192620289709e-05 0.000757129024281055 3296 3302 0 280 393 3296 3302 0 228 467 0 0 0 0 0 0 0 0 3111 0 0 0 0 0 3300 +537 541 0.998741409404387 -0.0411713822188713 0.0286446230054751 0.601692058208612 0.0416791955383702 0.998980173076798 -0.0173625591064255 0.0053888241895281 -0.0279005698904608 0.0185345915961864 0.999438856115846 0.0824747281114347 4.62005140037614e-05 -6.87709779338317e-05 1.99244167655566e-06 -6.85103696181658e-05 6.45896094507684e-09 4.6978793402149e-05 -6.87709779338317e-05 0.000625921325611645 -1.0866558761683e-05 0.000599212797307848 -1.28452485150959e-05 -0.000323882828281674 1.99244167655566e-06 -1.0866558761683e-05 1.4619105050759e-05 -1.01165815717669e-05 3.38249524160039e-06 4.02740805723973e-06 -6.85103696181658e-05 0.000599212797307848 -1.01165815717669e-05 0.00108324466133514 -2.02716438202159e-05 -0.00038798204664411 6.45896094507684e-09 -1.28452485150959e-05 3.38249524160039e-06 -2.02716438202159e-05 1.3430034776909e-05 8.63328518031691e-06 4.6978793402149e-05 -0.000323882828281674 4.02740805723973e-06 -0.00038798204664411 8.63328518031691e-06 0.000315301169128166 3211 3214 0 771 1006 3211 3214 0 704 1103 0 0 0 0 0 0 0 0 2401 0 0 0 0 0 2653 +536 538 0.998128231987332 0.0470786170727998 -0.0390337843970538 0.302039431714923 -0.0465015762057223 0.998796989681855 0.0155620311286338 -0.0177995065845262 0.0397194652560479 -0.0137177701168177 0.99911670332489 0.0206379651743608 8.80564806154059e-05 7.16451529436813e-06 2.65434705768619e-06 -2.28152112022233e-05 5.15341501336447e-08 5.58811360020978e-05 7.16451529436813e-06 2.3863360150474e-05 2.19869532186408e-06 -2.22255443171767e-06 3.1079794625273e-07 -7.21879055863173e-06 2.65434705768619e-06 2.19869532186408e-06 1.15970074842181e-05 -4.97794949122076e-06 1.77114078922702e-06 1.26658006404633e-06 -2.28152112022233e-05 -2.22255443171767e-06 -4.97794949122076e-06 0.00016130504204915 3.8012464205104e-06 -2.2461118233129e-05 5.15341501336447e-08 3.1079794625273e-07 1.77114078922702e-06 3.8012464205104e-06 1.31374877123375e-05 -2.34552918886254e-07 5.58811360020978e-05 -7.21879055863173e-06 1.26658006404633e-06 -2.2461118233129e-05 -2.34552918886254e-07 0.00011006070557417 3395 3408 0 509 201 3395 3408 0 433 263 0 0 0 0 0 0 0 0 2693 0 0 0 0 0 3529 +539 541 0.998724973881155 -0.0496801062604654 -0.0089617848688357 0.276077343731663 0.0494339021734493 0.998442288647673 -0.0258705538383579 0.0137544130980298 0.0102330768585151 0.0253945522099995 0.999625130164334 -0.00740383638812834 7.01667907053809e-05 1.28010666706964e-05 -9.7678723197129e-07 -8.39724597945056e-06 5.55194741647625e-06 5.5453270020273e-05 1.28010666706964e-05 0.000100253706224389 -3.64488315096826e-06 -2.82900908378041e-05 2.34781683128369e-06 -6.88432695080853e-06 -9.7678723197129e-07 -3.64488315096826e-06 1.24179060418164e-05 8.49185344656312e-07 4.1867026736943e-06 1.05238567158018e-06 -8.39724597945056e-06 -2.82900908378041e-05 8.49185344656312e-07 0.000214948875008552 -8.18421247211203e-06 -8.27716365517352e-05 5.55194741647625e-06 2.34781683128369e-06 4.1867026736943e-06 -8.18421247211203e-06 1.21646169072992e-05 8.16118970345997e-06 5.5453270020273e-05 -6.88432695080853e-06 1.05238567158018e-06 -8.27716365517352e-05 8.16118970345997e-06 0.000272290882573213 3274 3277 0 179 443 3274 3277 0 126 508 0 0 0 0 0 0 0 0 3312 0 0 0 0 0 3255 +539 542 0.996711637395884 -0.0769344969054398 -0.0254360976866086 0.446704193768097 0.0765263531888523 0.996928544720501 -0.0166491437941859 0.025986207002365 0.0266388653517912 0.014647863577031 0.999537798657658 0.0375912563785305 5.05431216612968e-05 5.76040480796519e-06 -3.26729463303984e-06 1.25703172128945e-06 1.76954153504357e-06 3.48142539038237e-05 5.76040480796519e-06 3.34691794601516e-05 -8.80044383694815e-07 -2.73305131320739e-06 3.40126022529159e-07 -9.30216651195104e-06 -3.26729463303984e-06 -8.80044383694815e-07 1.19139969547117e-05 -7.46546291957545e-06 3.98774640086424e-06 3.59691253539433e-06 1.25703172128945e-06 -2.73305131320739e-06 -7.46546291957545e-06 0.000388283787850619 -8.92416654183026e-06 -3.69773115881577e-05 1.76954153504357e-06 3.40126022529159e-07 3.98774640086424e-06 -8.92416654183026e-06 1.22986555596757e-05 4.10360346410972e-06 3.48142539038237e-05 -9.30216651195104e-06 3.59691253539433e-06 -3.69773115881577e-05 4.10360346410972e-06 0.000197270072490674 3430 3427 0 369 825 3430 3427 0 308 908 0 0 0 0 0 0 0 0 3084 0 0 0 0 0 2851 +539 543 0.993451947804652 -0.0932041164205347 -0.0660773795289389 0.57505588276491 0.0935398746462131 0.995613527266503 0.0019990435519484 0.0411052371123287 0.0656012138173888 -0.00816682350851666 0.997812499290055 0.00365150546077739 6.74740246175338e-05 1.26234774800349e-05 5.88617297192136e-06 -3.79094588612596e-05 -1.10421210608756e-05 -3.59030466143587e-05 1.26234774800349e-05 0.000784929659871707 2.26166735964224e-05 0.00033558206948499 1.20537340753918e-06 -0.00136393280139539 5.88617297192136e-06 2.26166735964224e-05 1.76079324647371e-05 4.89858482718629e-08 -6.2561207946955e-07 -4.88629692204394e-05 -3.79094588612596e-05 0.00033558206948499 4.89858482718629e-08 0.000752545251117445 -6.35800348749719e-06 -0.0010155447952997 -1.10421210608756e-05 1.20537340753918e-06 -6.2561207946955e-07 -6.35800348749719e-06 1.63068132817784e-05 1.48750085029765e-05 -3.59030466143587e-05 -0.00136393280139539 -4.88629692204394e-05 -0.0010155447952997 1.48750085029765e-05 0.00315238642005427 3282 3268 0 522 1136 3282 3268 0 458 1234 0 0 0 0 0 0 0 0 2893 0 0 0 0 0 2527 +542 546 0.999922364372831 0.00719740192049564 -0.0101716583034725 0.540681823770024 -0.00723273196426899 0.999967923473059 -0.00344087391687328 0.00191399567425066 0.0101465666794634 0.00351417566060988 0.999942347215101 0.0403790730001488 4.25263794924814e-05 3.86118706916547e-05 -1.00727892838862e-05 1.52346255764698e-05 4.75838857976325e-06 -3.54479644582681e-05 3.86118706916547e-05 0.000302343693840773 -8.73801393688029e-06 -5.89775086642819e-05 7.12575363062434e-06 -0.000165377122318648 -1.00727892838862e-05 -8.73801393688029e-06 1.52786352548333e-05 -8.17875463824963e-06 -1.55408039152748e-07 9.53243966034601e-06 1.52346255764698e-05 -5.89775086642819e-05 -8.17875463824963e-06 0.000477672906288858 -3.53140173406858e-06 -0.000188228614560624 4.75838857976325e-06 7.12575363062434e-06 -1.55408039152748e-07 -3.53140173406858e-06 1.54616358867973e-05 -1.59165049021403e-06 -3.54479644582681e-05 -0.000165377122318648 9.53243966034601e-06 -0.000188228614560624 -1.59165049021403e-06 0.000419136892900727 3277 3264 0 846 718 3277 3264 0 763 803 0 0 0 0 0 0 0 0 2984 0 0 0 0 0 2972 +543 545 0.999998264150202 0.000131993274552124 -0.00185856782480071 0.269695091553486 -0.000112787470972401 0.999946638041911 0.0103299732654662 -0.00199278854999712 0.00185983213497969 -0.0103297457110196 0.999944917171929 0.0113322272839661 7.99991919666656e-05 2.86828424279871e-05 -7.32167638784285e-07 -2.85795632664469e-05 5.11931595609171e-06 2.02466196928393e-05 2.86828424279871e-05 6.9746375645827e-05 9.69424636743989e-07 -1.91571232720796e-05 3.00863465207745e-06 -2.48335209257255e-06 -7.32167638784285e-07 9.69424636743989e-07 1.2458983573795e-05 -9.6783459291817e-06 2.09579917478616e-06 2.5715947048382e-06 -2.85795632664469e-05 -1.91571232720796e-05 -9.6783459291817e-06 0.000221959110948607 8.21902876093043e-08 -9.01960068480419e-05 5.11931595609171e-06 3.00863465207745e-06 2.09579917478616e-06 8.21902876093043e-08 1.2637002363258e-05 -2.49374838273594e-06 2.02466196928393e-05 -2.48335209257255e-06 2.5715947048382e-06 -9.01960068480419e-05 -2.49374838273594e-06 0.000356886842565975 3316 3298 0 352 264 3316 3298 0 283 324 0 0 0 0 0 0 0 0 3449 0 0 0 0 0 3442 +541 543 0.998329187771444 -0.0439326465722087 -0.0375333905845121 0.304204738477639 0.0448146184585875 0.99873077215215 0.0229890132189471 0.0141471508786491 0.0364757839671662 -0.0246326474730405 0.999030905359013 -0.0067230308939209 9.22803078407253e-05 1.18217599055433e-05 4.10037815541527e-06 6.04125359052744e-06 -5.12929341837295e-06 4.48878381333391e-05 1.18217599055433e-05 2.98480533444632e-05 3.34189203297861e-06 -1.11409116088163e-05 -3.92496004873632e-07 1.30625409766022e-05 4.10037815541527e-06 3.34189203297861e-06 1.42879937715908e-05 -1.13992648172189e-05 -1.10820058390472e-06 3.53324485099263e-07 6.04125359052744e-06 -1.11409116088163e-05 -1.13992648172189e-05 0.000877852980241118 -3.49444556676474e-05 -4.29619534384209e-05 -5.12929341837295e-06 -3.92496004873632e-07 -1.10820058390472e-06 -3.49444556676474e-05 1.84239548546459e-05 2.01644962946808e-06 4.48878381333391e-05 1.30625409766022e-05 3.53324485099263e-07 -4.29619534384209e-05 2.01644962946808e-06 0.000261340032282672 3316 3302 0 250 463 3316 3302 0 184 537 0 0 0 0 0 0 0 0 3256 0 0 0 0 0 3235 +541 545 0.998389241264665 -0.0441327902217331 -0.0356541688195254 0.515953107688843 0.0451582762757277 0.998573578231502 0.028487522562338 0.0243724816023025 0.0343460770798029 -0.0300517168424562 0.998958077851142 0.0508969736595578 3.55227005651176e-05 2.77084899376296e-06 -3.21634159574099e-06 -2.30289770317117e-06 -1.45131511931462e-06 -1.19138757540696e-05 2.77084899376296e-06 0.000115908559670822 6.70497828281311e-06 -8.8462405733872e-05 4.19283219588829e-06 -0.000115938863684994 -3.21634159574099e-06 6.70497828281311e-06 1.21974422767355e-05 -9.11110199005403e-06 2.73718939931123e-06 -9.02457825064174e-06 -2.30289770317117e-06 -8.8462405733872e-05 -9.11110199005403e-06 0.000472921000009855 -1.31848755794679e-05 0.00019385119644774 -1.45131511931462e-06 4.19283219588829e-06 2.73718939931123e-06 -1.31848755794679e-05 1.32646926820069e-05 -1.14920397596764e-05 -1.19138757540696e-05 -0.000115938863684994 -9.02457825064174e-06 0.00019385119644774 -1.14920397596764e-05 0.000378731198789326 3252 3234 0 601 845 3252 3234 0 527 931 0 0 0 0 0 0 0 0 3137 0 0 0 0 0 2820 +543 546 0.999617190722579 0.024708267165645 0.0124488371171783 0.415415407461188 -0.0245927477916461 0.999653839196678 -0.00934871838265248 -0.00949616387199428 -0.0126755184491764 0.00903898849500156 0.999878806615598 0.0623108281308815 9.26839235203593e-05 4.67968144652354e-05 2.50635740972524e-07 -6.53022449732928e-05 4.93089959457343e-06 0.000232067186525884 4.67968144652354e-05 0.00037659626382502 -8.22797295890211e-06 -0.000145451059132306 1.5599253227253e-05 0.00154685595845946 2.50635740972524e-07 -8.22797295890211e-06 1.39468194248836e-05 -1.90902950794457e-06 -1.66977168447073e-08 -4.14823040213028e-05 -6.53022449732928e-05 -0.000145451059132306 -1.90902950794457e-06 0.000435116392878835 -1.34318543065666e-05 -0.0010346703472928 4.93089959457343e-06 1.5599253227253e-05 -1.66977168447073e-08 -1.34318543065666e-05 1.72317725904563e-05 0.000153498811841486 0.000232067186525884 0.00154685595845946 -4.14823040213028e-05 -0.0010346703472928 0.000153498811841486 0.015585312431617 3265 3252 0 689 415 3265 3252 0 603 483 0 0 0 0 0 0 0 0 3139 0 0 0 0 0 3291 +542 545 0.999788260728301 -0.0172866715998342 -0.0111626473060465 0.412476280981851 0.0175058431345519 0.999649806868003 0.0198446235769946 0.00652506454013669 0.0108156907328272 -0.0200358332435572 0.999740759507288 0.0191563801934665 4.90203578176699e-05 2.20993054756289e-05 1.28654672509075e-06 -2.60731533444572e-05 2.68224815380023e-07 -1.12254070713103e-05 2.20993054756289e-05 0.000110266244603974 -2.49209277139999e-06 -1.57091179318441e-05 3.41573100207615e-06 -3.70851869048887e-05 1.28654672509075e-06 -2.49209277139999e-06 1.24116599426877e-05 -6.26761630174921e-06 2.29675363563039e-06 8.60786554590185e-07 -2.60731533444572e-05 -1.57091179318441e-05 -6.26761630174921e-06 0.000222046666253392 -4.11393825103024e-07 -4.96118797242649e-05 2.68224815380023e-07 3.41573100207615e-06 2.29675363563039e-06 -4.11393825103024e-07 1.21042922213297e-05 -9.92953961719509e-06 -1.12254070713103e-05 -3.70851869048887e-05 8.60786554590185e-07 -4.96118797242649e-05 -9.92953961719509e-06 0.000734459616392819 3302 3284 0 529 553 3302 3284 0 459 623 0 0 0 0 0 0 0 0 3244 0 0 0 0 0 3129 +544 548 0.993768576229653 0.0936289056118046 -0.0604784666838097 0.539656387799546 -0.096033072160954 0.994646983059682 -0.0381448311256059 -0.0515357173783472 0.0565832656340893 0.043715067473444 0.99744038765531 0.00351411086747082 4.75023231927904e-05 5.41355304638086e-05 -2.69061234690439e-06 -3.0641651385364e-06 -2.55349241627658e-06 -1.48059638692278e-05 5.41355304638086e-05 0.000417420175351361 -6.23038439695084e-06 0.000171031422153942 3.11603067605923e-06 -0.000236552595862353 -2.69061234690439e-06 -6.23038439695084e-06 1.30360520900192e-05 -3.48390713864101e-06 9.06643508419916e-07 -5.21190946155696e-06 -3.0641651385364e-06 0.000171031422153942 -3.48390713864101e-06 0.000473205786507023 1.18627506829468e-05 3.11832552497362e-05 -2.55349241627658e-06 3.11603067605923e-06 9.06643508419916e-07 1.18627506829468e-05 1.32389789973393e-05 8.58679941377264e-06 -1.48059638692278e-05 -0.000236552595862353 -5.21190946155696e-06 3.11832552497362e-05 8.58679941377264e-06 0.000446865315117185 3221 3229 0 1161 412 3221 3229 0 1063 477 0 0 0 0 0 0 0 0 2663 0 0 0 0 0 3308 +545 549 0.994118069640805 0.0989370207847932 -0.0440537118966139 0.562435688285701 -0.099997275654738 0.99473222604133 -0.0225464705994335 -0.0666993109611786 0.0415909662699823 0.026819105001662 0.998774712901583 0.0591918252179461 4.17871852394415e-05 1.54382723076949e-05 -4.59062925355889e-06 -1.51221217229747e-05 -1.43160507735337e-06 -1.57115912386123e-05 1.54382723076949e-05 6.27237425453893e-05 1.11147450792294e-06 -1.80067332629286e-05 -9.83498418681657e-07 -3.85109011304021e-05 -4.59062925355889e-06 1.11147450792294e-06 1.22763026414897e-05 -5.23071724759034e-06 3.58437651490962e-06 -1.0194618508907e-06 -1.51221217229747e-05 -1.80067332629286e-05 -5.23071724759034e-06 0.000296409660822934 2.47069006067776e-06 -4.81244119235387e-05 -1.43160507735337e-06 -9.83498418681657e-07 3.58437651490962e-06 2.47069006067776e-06 1.18732993991773e-05 -7.04938600589467e-07 -1.57115912386123e-05 -3.85109011304021e-05 -1.0194618508907e-06 -4.81244119235387e-05 -7.04938600589467e-07 0.000345872395238565 3288 3302 0 1233 417 3288 3302 0 1139 491 0 0 0 0 0 0 0 0 2588 0 0 0 0 0 3300 +545 547 0.997954654906944 0.058255865971543 -0.0263203501015586 0.284712953145985 -0.0595623394803111 0.996872904451741 -0.0519301462118391 -0.0227251860726328 0.0232128082143278 0.0533916327700927 0.998303811013936 0.0213179623863204 4.10172877582947e-05 8.82969227603441e-06 -7.091659518868e-06 1.85960767135275e-05 1.07200724120159e-06 -6.45298480340608e-06 8.82969227603441e-06 5.31250164642016e-05 9.54405524921657e-07 3.70486255838479e-06 -8.21226490464307e-07 -2.15823172281307e-05 -7.091659518868e-06 9.54405524921657e-07 1.49591445768504e-05 -1.05071560720391e-05 -1.54772107156317e-07 4.97462251630276e-06 1.85960767135275e-05 3.70486255838479e-06 -1.05071560720391e-05 0.000275736622559271 1.13774904187886e-05 4.03085999008621e-05 1.07200724120159e-06 -8.21226490464307e-07 -1.54772107156317e-07 1.13774904187886e-05 1.52937999109502e-05 -1.89255333407262e-06 -6.45298480340608e-06 -2.15823172281307e-05 4.97462251630276e-06 4.03085999008621e-05 -1.89255333407262e-06 0.00018368914421756 3360 3360 0 569 133 3360 3360 0 497 183 0 0 0 0 0 0 0 0 3273 0 0 0 0 0 3608 +548 551 0.999656072805435 -0.00722086313211636 0.0252110142366766 0.455538208089046 0.00720087720612945 0.99997368310242 0.000883442155807061 -0.0044246686228021 -0.0252167299758893 -0.000701596898264564 0.999681761507689 0.0256032587530475 4.2551036316051e-05 -1.60703311945562e-05 -1.20697691967261e-06 -1.58656818237916e-05 2.6812913619478e-06 5.98727751848866e-07 -1.60703311945562e-05 0.00120479270992083 -1.92935938844015e-05 0.00126469489012686 2.52397832826758e-05 -2.62743626926656e-05 -1.20697691967261e-06 -1.92935938844015e-05 1.29419273162547e-05 -1.25102700947307e-05 3.08716884053809e-06 7.69034489726974e-06 -1.58656818237916e-05 0.00126469489012686 -1.25102700947307e-05 0.00461212239687522 9.56019692662241e-05 0.00133648649510396 2.6812913619478e-06 2.52397832826758e-05 3.08716884053809e-06 9.56019692662241e-05 1.35238300688027e-05 3.31735794314456e-05 5.98727751848866e-07 -2.62743626926656e-05 7.69034489726974e-06 0.00133648649510396 3.31735794314456e-05 0.000898955440544274 3153 3167 0 604 622 3153 3167 0 541 701 0 0 0 0 0 0 0 0 3211 0 0 0 0 0 3054 +548 552 0.997902021539089 -0.0332268899415827 0.0555655396177367 0.582668882087706 0.0318066878316904 0.999149241849012 0.0262512308610908 0.00096571954663616 -0.0563905135406454 -0.024428800571351 0.998109885576366 0.0341562937338271 3.31033822931583e-05 -6.17479253125666e-06 5.84001154298595e-06 6.45579203948494e-06 1.4103197438138e-06 8.50618666554423e-06 -6.17479253125666e-06 5.9963842377733e-05 6.66566774688942e-07 4.5298476502756e-05 6.008376390775e-07 -2.57974706707466e-05 5.84001154298595e-06 6.66566774688942e-07 1.19670035326619e-05 -3.13653420672216e-06 4.52017577543664e-06 -2.76814595491992e-07 6.45579203948494e-06 4.5298476502756e-05 -3.13653420672216e-06 0.000599922295809848 -1.89847745842947e-06 9.38323877721149e-05 1.4103197438138e-06 6.008376390775e-07 4.52017577543664e-06 -1.89847745842947e-06 1.02245851783655e-05 -8.02499973359687e-07 8.50618666554423e-06 -2.57974706707466e-05 -2.76814595491992e-07 9.38323877721149e-05 -8.02499973359687e-07 0.000141485182963578 3200 3203 0 764 954 3200 3203 0 698 1040 0 0 0 0 0 0 0 0 3035 0 0 0 0 0 2706 +549 551 0.99901891006444 -0.0203138478676342 0.0393518095958693 0.277908513346608 0.020688143967444 0.999744309810773 -0.00912774343218086 0.00585091142994014 -0.0391563281327711 0.00993290419726396 0.999183726539502 -0.0265569186582265 5.27497028659524e-05 -1.83394988832839e-05 6.80883456072623e-07 -1.86967593352715e-05 1.15092796256979e-07 1.19660510231521e-05 -1.83394988832839e-05 0.000523351938653222 7.23128627505388e-06 -0.000441482297235181 -2.06393172147607e-05 -0.000377685923421518 6.80883456072623e-07 7.23128627505388e-06 1.37749703163726e-05 -1.07735533671583e-05 3.12137766731901e-06 -5.76936855405762e-06 -1.86967593352715e-05 -0.000441482297235181 -1.07735533671583e-05 0.00192677623848474 4.5639919957953e-05 0.0005235073851802 1.15092796256979e-07 -2.06393172147607e-05 3.12137766731901e-06 4.5639919957953e-05 1.25321673801876e-05 2.05879976391569e-05 1.19660510231521e-05 -0.000377685923421518 -5.76936855405762e-06 0.0005235073851802 2.05879976391569e-05 0.000378330293546213 3168 3182 0 282 371 3168 3182 0 216 438 0 0 0 0 0 0 0 0 3541 0 0 0 0 0 3319 +549 553 0.997246131112366 -0.0672763241097232 0.0312097772453051 0.566837229353834 0.0665522550820715 0.99750173702905 0.0236871688371402 0.0313896349385735 -0.0327253926624107 -0.0215448564235593 0.999232139113219 0.0176964001336265 3.75289556381287e-05 -1.59828261753565e-05 1.70918790178254e-06 5.65690132142836e-06 1.84747490383251e-08 3.33951243999928e-05 -1.59828261753565e-05 0.000334461319843316 4.47110334847626e-06 -0.000287275555714884 9.80773002154779e-06 -0.000198750027449342 1.70918790178254e-06 4.47110334847626e-06 1.14330716602053e-05 7.96251772407592e-06 3.76150429641792e-06 3.56969187665331e-06 5.65690132142836e-06 -0.000287275555714884 7.96251772407592e-06 0.00144093210986873 -3.98870258137114e-05 0.000118012380990542 1.84747490383251e-08 9.80773002154779e-06 3.76150429641792e-06 -3.98870258137114e-05 1.1874235862773e-05 -2.73676685006296e-05 3.33951243999928e-05 -0.000198750027449342 3.56969187665331e-06 0.000118012380990542 -2.73676685006296e-05 0.00111021851300322 3148 3145 0 602 1059 3148 3145 0 525 1156 0 0 0 0 0 0 0 0 3191 0 0 0 0 0 2606 +551 555 0.997519807765446 -0.0692990986101048 0.0123234754600156 0.54450046967705 0.0686419066374979 0.996509278507297 0.0475136454298698 0.0529533438100919 -0.0155731104393326 -0.0465498956034634 0.99879456618994 0.0285225229480995 4.20461316405864e-05 -1.18736866212931e-06 -1.51459633032262e-06 1.01225013319121e-05 -2.59241125964039e-06 8.99302491960461e-06 -1.18736866212931e-06 4.09280522170669e-05 3.85444467467994e-07 -5.3765510610366e-06 -9.72891988053205e-08 -2.60558146982425e-05 -1.51459633032262e-06 3.85444467467994e-07 1.3802343496525e-05 -1.17966999937282e-05 2.91175739346121e-06 -5.53606659403078e-06 1.01225013319121e-05 -5.3765510610366e-06 -1.17966999937282e-05 0.00126500271942921 -5.33744145779989e-05 1.18457736858554e-05 -2.59241125964039e-06 -9.72891988053205e-08 2.91175739346121e-06 -5.33744145779989e-05 1.46356167135783e-05 -3.17559685537605e-06 8.99302491960461e-06 -2.60558146982425e-05 -5.53606659403078e-06 1.18457736858554e-05 -3.17559685537605e-06 0.000283847348568163 3216 3199 0 532 1023 3216 3199 0 462 1113 0 0 0 0 0 0 0 0 3272 0 0 0 0 0 2658 +554 557 0.996746552722176 0.0364570754814553 0.0718831780307364 0.42176356804677 -0.0354924110353978 0.999262528075208 -0.0146522607006333 0.00384181869029504 -0.0723643447794109 0.0120532830417453 0.997305429631546 0.00940235476325622 4.24537879405163e-05 4.27954899421068e-06 -6.2329646705418e-06 4.91385067065555e-05 4.18831814909484e-07 7.68221102114104e-06 4.27954899421068e-06 6.18163616350624e-05 7.43300524050457e-07 0.000124747688475622 -7.83419467694519e-07 -1.1863353522974e-05 -6.2329646705418e-06 7.43300524050457e-07 1.40881343994087e-05 5.93375771938657e-06 2.7791877472297e-06 3.27239965874256e-06 4.91385067065555e-05 0.000124747688475622 5.93375771938657e-06 0.00246991087593121 -2.08116859381328e-05 0.000448742468795035 4.18831814909484e-07 -7.83419467694519e-07 2.7791877472297e-06 -2.08116859381328e-05 1.09300509610547e-05 -5.93428019203334e-06 7.68221102114104e-06 -1.1863353522974e-05 3.27239965874256e-06 0.000448742468795035 -5.93428019203334e-06 0.000262689109872823 3260 3257 0 720 441 3260 3257 0 632 503 0 0 0 0 0 0 0 0 3105 0 0 0 0 0 3285 +554 558 0.997206556153398 0.071683138299428 0.0209907610206391 0.51835249694299 -0.0712846017684321 0.997272039071732 -0.0191568691707559 -0.0123214562265288 -0.0223067235468716 0.0176070374922781 0.999596119597985 0.000376307332274121 4.88950143358968e-05 -5.00925247926201e-06 1.73677626889216e-06 1.41867178386465e-05 -5.81222978800866e-08 -5.4454050186911e-05 -5.00925247926201e-06 5.26614788401829e-05 -1.95284597595591e-06 -5.47980941711168e-05 -3.01674266349415e-06 0.000103247859002869 1.73677626889216e-06 -1.95284597595591e-06 1.16702209565546e-05 -6.03776460828974e-06 4.30245934542368e-06 7.30132213376184e-06 1.41867178386465e-05 -5.47980941711168e-05 -6.03776460828974e-06 0.00121889833587304 3.13687862923249e-05 -0.000506720710338633 -5.81222978800866e-08 -3.01674266349415e-06 4.30245934542368e-06 3.13687862923249e-05 1.21434512277283e-05 -2.08685449711187e-05 -5.4454050186911e-05 0.000103247859002869 7.30132213376184e-06 -0.000506720710338633 -2.08685449711187e-05 0.0014740412337558 3320 3321 0 1004 496 3320 3321 0 912 566 0 0 0 0 0 0 0 0 2824 0 0 0 0 0 3214 +555 559 0.993762141313307 0.108972017951553 -0.0237045522201266 0.526684289493632 -0.109385653737733 0.993855511670862 -0.0169115545653762 -0.0487374993113484 0.0217160136479757 0.0193990006189839 0.999575956856819 0.032384563625706 5.24010021715084e-05 3.27144691789021e-06 6.94454391923056e-06 -9.05227014323061e-06 -1.98707266379561e-06 -1.74834440266196e-05 3.27144691789021e-06 6.44118264488894e-05 1.71202493745348e-06 3.22990120981989e-05 2.12264710207514e-06 -2.1524412429116e-05 6.94454391923056e-06 1.71202493745348e-06 1.50620985970077e-05 -8.16360206962525e-06 2.38689772674622e-06 -5.61459494351094e-06 -9.05227014323061e-06 3.22990120981989e-05 -8.16360206962525e-06 0.000343196903808059 1.28464193944205e-05 9.13465247978259e-05 -1.98707266379561e-06 2.12264710207514e-06 2.38689772674622e-06 1.28464193944205e-05 1.2042218443695e-05 4.57582326274362e-06 -1.74834440266196e-05 -2.1524412429116e-05 -5.61459494351094e-06 9.13465247978259e-05 4.57582326274362e-06 0.000150829939787549 3283 3296 0 1175 357 3283 3296 0 1079 419 0 0 0 0 0 0 0 0 2654 0 0 0 0 0 3359 +553 555 0.998850976945972 -0.0244726330736319 0.0412045638797523 0.263509146596614 0.0241461199836565 0.999673120554816 0.00840338800311411 0.0216465456290261 -0.0413967479859478 -0.00739880197325185 0.999115392227319 0.0490089831576211 5.34037374213447e-05 2.35406650103288e-05 3.12008637362356e-07 5.99370907487249e-05 5.13867450226063e-07 -3.86562912797342e-06 2.35406650103288e-05 0.000190401658688602 4.549318497947e-06 0.00024153200263294 -1.54749048672668e-05 0.000124713433994096 3.12008637362356e-07 4.549318497947e-06 1.32556166452994e-05 2.90776637635239e-06 1.51046062210018e-06 4.00672675545272e-06 5.99370907487249e-05 0.00024153200263294 2.90776637635239e-06 0.00121630485431888 -6.85000008084701e-05 0.000599498120797211 5.13867450226063e-07 -1.54749048672668e-05 1.51046062210018e-06 -6.85000008084701e-05 1.69831960434006e-05 -5.66627544141473e-05 -3.86562912797342e-06 0.000124713433994096 4.00672675545272e-06 0.000599498120797211 -5.66627544141473e-05 0.000892545458009258 3382 3365 0 240 372 3382 3365 0 177 428 0 0 0 0 0 0 0 0 3563 0 0 0 0 0 3348 +552 556 0.998905517954709 -0.0363142805858345 0.0294794712498096 0.535875364265023 0.0355785712956529 0.999051400373399 0.0251090556674284 0.0435767940378392 -0.030363324327142 -0.0240327367872067 0.999249966774241 0.0529512503779513 4.59461680010539e-05 2.34890102313332e-07 -5.94287375319405e-06 -7.34334442943972e-07 8.24222466460447e-07 1.34026864354298e-05 2.34890102313332e-07 3.90208630993312e-05 1.45013107776672e-06 2.45872871096367e-06 2.65557078969729e-07 -2.80868289076668e-05 -5.94287375319405e-06 1.45013107776672e-06 1.22956798785677e-05 -2.60736028317284e-06 3.74174328279022e-06 -1.67730251528674e-06 -7.34334442943972e-07 2.45872871096367e-06 -2.60736028317284e-06 0.000718747257155629 -2.15914117824658e-05 2.49525661434958e-05 8.24222466460447e-07 2.65557078969729e-07 3.74174328279022e-06 -2.15914117824658e-05 1.21198761694463e-05 -1.09580709822038e-07 1.34026864354298e-05 -2.80868289076668e-05 -1.67730251528674e-06 2.49525661434958e-05 -1.09580709822038e-07 9.89592352325476e-05 3346 3330 0 641 894 3346 3330 0 558 976 0 0 0 0 0 0 0 0 3181 0 0 0 0 0 2795 +559 562 0.99867506103661 -0.0246970383254456 0.0451461932113201 0.460604147951964 0.0251870119460182 0.999629523194684 -0.0103165297847699 0.0122523348604046 -0.0448746798624069 0.0114399587202218 0.998927119689783 0.0322516657056374 3.82335643324429e-05 -1.82927398461565e-05 -2.32678031008275e-06 -3.38406890024396e-06 8.63778790953655e-07 2.13431289354427e-05 -1.82927398461565e-05 0.000376036226764843 7.61685607433166e-07 -0.000128550104067811 -2.31266320762883e-06 -0.00017806703985066 -2.32678031008275e-06 7.61685607433166e-07 1.31976426830594e-05 -2.47218611274427e-07 4.34779445277031e-06 -1.96137727531544e-06 -3.38406890024396e-06 -0.000128550104067811 -2.47218611274427e-07 0.00027523282682785 1.59671726077352e-06 6.47766015597776e-05 8.63778790953655e-07 -2.31266320762883e-06 4.34779445277031e-06 1.59671726077352e-06 1.07284254858407e-05 3.92630773549663e-07 2.13431289354427e-05 -0.00017806703985066 -1.96137727531544e-06 6.47766015597776e-05 3.92630773549663e-07 0.00018306445863764 3319 3330 0 537 705 3319 3330 0 468 805 0 0 0 0 0 0 0 0 3283 0 0 0 0 0 2984 +557 560 0.995949782947295 0.0691840011202881 -0.0574247667494025 0.399826818510535 -0.0692480262386384 0.99759908901154 0.000876621581972219 -0.0433664621360937 0.0573475431844134 0.00310348068031817 0.998349451694335 0.0289634387049776 3.16852178194149e-05 -3.23680476791344e-06 -7.55879658231618e-06 -1.49537886099478e-05 -3.33444060683843e-06 4.79085699284442e-06 -3.23680476791344e-06 3.6247065981262e-05 2.18057899007033e-06 2.0491105349359e-05 2.58390597425485e-06 -3.15265224814384e-05 -7.55879658231618e-06 2.18057899007033e-06 1.23621303958565e-05 -3.09104219815298e-06 4.05969210324085e-06 -2.70508768347554e-06 -1.49537886099478e-05 2.0491105349359e-05 -3.09104219815298e-06 0.000504556436912707 2.48954628259091e-05 2.27095728426571e-05 -3.33444060683843e-06 2.58390597425485e-06 4.05969210324085e-06 2.48954628259091e-05 1.28705301872522e-05 1.33368655633949e-06 4.79085699284442e-06 -3.15265224814384e-05 -2.70508768347554e-06 2.27095728426571e-05 1.33368655633949e-06 7.37685369627127e-05 3310 3330 0 782 251 3310 3330 0 717 322 0 0 0 0 0 0 0 0 3044 0 0 0 0 0 3469 +559 563 0.998593885352121 -0.0470134626727517 0.024494621141636 0.599989790845378 0.0463640006688721 0.998574630841517 0.0264402360372201 0.0281685494037578 -0.0257027543141066 -0.0252673894030402 0.999350252640897 0.0498967703355405 4.39611459220788e-05 -5.46487475403691e-06 2.36511370812036e-06 -3.31186850783371e-06 5.15480571196627e-07 8.53802560279267e-06 -5.46487475403691e-06 3.42304241109507e-05 -1.69897756975043e-06 1.02950483497281e-05 -8.07358760693409e-07 -2.164453884887e-05 2.36511370812036e-06 -1.69897756975043e-06 1.15129640711427e-05 -9.99524661548194e-07 3.84168863274072e-06 1.80802591227777e-06 -3.31186850783371e-06 1.02950483497281e-05 -9.99524661548194e-07 0.000422460761625852 3.06675770645617e-06 6.69706245027798e-05 5.15480571196627e-07 -8.07358760693409e-07 3.84168863274072e-06 3.06675770645617e-06 1.04363374663118e-05 1.4457752635608e-06 8.53802560279267e-06 -2.164453884887e-05 1.80802591227777e-06 6.69706245027798e-05 1.4457752635608e-06 7.57193357872478e-05 3347 3350 0 703 1070 3347 3350 0 628 1172 0 0 0 0 0 0 0 0 3102 0 0 0 0 0 2616 +560 562 0.999413004636132 -0.0305155075841948 0.0155708047658809 0.303981789394485 0.0307453929756859 0.999418491877835 -0.0147444533097839 0.0183222204175405 -0.0151118157396414 0.0152145288955229 0.999770049129068 0.0213202810018688 4.19897939073429e-05 -4.27894661387835e-05 -3.67425674178109e-07 -2.94115389968594e-05 -2.04066756226053e-06 3.34971281476257e-05 -4.27894661387835e-05 0.000771339332538769 4.26158121558326e-06 -0.000126046205874952 -1.57756457369946e-06 -0.000724869225770209 -3.67425674178109e-07 4.26158121558326e-06 1.12203717104433e-05 -3.30176283107705e-06 4.3494462132074e-06 -6.52441932950991e-06 -2.94115389968594e-05 -0.000126046205874952 -3.30176283107705e-06 0.000604323068093553 8.25035629102719e-06 -6.04977147428648e-05 -2.04066756226053e-06 -1.57756457369946e-06 4.3494462132074e-06 8.25035629102719e-06 1.04197419364988e-05 4.83084297715484e-07 3.34971281476257e-05 -0.000724869225770209 -6.52441932950991e-06 -6.04977147428648e-05 4.83084297715484e-07 0.00113005214424338 3049 3060 0 263 451 3049 3060 0 202 531 0 0 0 0 0 0 0 0 3555 0 0 0 0 0 3252 +559 561 0.998779668906959 -0.0119390145694215 0.047923198027843 0.275871602454178 0.0123944343632474 0.999880703289899 -0.00921722221240581 0.000215996562788037 -0.0478074363976972 0.00979995508198155 0.998808495110785 0.0251273440262116 4.30137592837088e-05 1.87594876250651e-06 -5.54479950708056e-07 3.33021518805001e-06 -1.4605807739203e-06 -5.98767746894755e-06 1.87594876250651e-06 4.07163910452295e-05 2.85896506007174e-06 4.71258443437061e-06 -3.67799549630097e-07 -3.46565571190142e-05 -5.54479950708056e-07 2.85896506007174e-06 1.22716666839855e-05 3.88471967841858e-07 4.19038156630416e-06 -2.6283266175261e-06 3.33021518805001e-06 4.71258443437061e-06 3.88471967841858e-07 0.000503887655511187 1.28974188643708e-05 -5.54944566089466e-05 -1.4605807739203e-06 -3.67799549630097e-07 4.19038156630416e-06 1.28974188643708e-05 1.10148143590159e-05 -8.90426929491155e-07 -5.98767746894755e-06 -3.46565571190142e-05 -2.6283266175261e-06 -5.54944566089466e-05 -8.90426929491155e-07 0.000103441394176185 3347 3360 0 311 332 3347 3360 0 240 411 0 0 0 0 0 0 0 0 3514 0 0 0 0 0 3376 +561 565 0.996455164757721 -0.0695663931706426 -0.0473035048267002 0.571190510047862 0.0710119949812993 0.997036258331244 0.0295972319923561 0.0782520900651082 0.0451043367808241 -0.0328514309286672 0.998441977427582 0.0485323939965598 2.72990777437843e-05 -5.7015684090632e-06 -4.15153640216873e-06 -1.23056292809369e-05 -2.98741853025781e-06 7.01263452751093e-06 -5.7015684090632e-06 0.000121001252756785 -1.0014365281278e-06 3.21085299165913e-06 6.69725597622302e-07 -5.2994423006144e-05 -4.15153640216873e-06 -1.0014365281278e-06 1.18118400140875e-05 5.80544814424959e-06 4.48724266130152e-06 2.00318631489078e-06 -1.23056292809369e-05 3.21085299165913e-06 5.80544814424959e-06 0.000739763724348641 -2.4993843781294e-05 0.000368015423887088 -2.98741853025781e-06 6.69725597622302e-07 4.48724266130152e-06 -2.4993843781294e-05 1.12536890535901e-05 -2.20897297802661e-05 7.01263452751093e-06 -5.2994423006144e-05 2.00318631489078e-06 0.000368015423887088 -2.20897297802661e-05 0.000566691510803131 3210 3193 0 529 1111 3210 3193 0 456 1208 0 0 0 0 0 0 0 0 3262 0 0 0 0 0 2582 +560 563 0.998653173377091 -0.0518011832141696 0.00291148097653676 0.436746860882303 0.0517371948209944 0.998481865665438 0.0189004393948976 0.0343010555565285 -0.00388612608122526 -0.0187243519214352 0.999817131614178 0.0319030262000032 5.20644323272074e-05 -6.93106328452873e-07 -1.23171796789467e-07 -1.58906391277312e-05 -1.47960828255548e-06 4.70459620716865e-06 -6.93106328452873e-07 0.000100892712355977 2.82949436000664e-06 -2.37252671342027e-05 5.94795133744116e-07 -5.88921235794978e-05 -1.23171796789467e-07 2.82949436000664e-06 1.35187453923846e-05 1.59056343728077e-06 2.86926746009247e-06 -6.06036933035883e-06 -1.58906391277312e-05 -2.37252671342027e-05 1.59056343728077e-06 0.000683486366092929 8.21966429802616e-07 6.58772735304701e-07 -1.47960828255548e-06 5.94795133744116e-07 2.86926746009247e-06 8.21966429802616e-07 1.14248478691528e-05 -4.32268740972335e-06 4.70459620716865e-06 -5.88921235794978e-05 -6.06036933035883e-06 6.58772735304701e-07 -4.32268740972335e-06 0.000231997416301926 3171 3174 0 385 763 3171 3174 0 329 856 0 0 0 0 0 0 0 0 3417 0 0 0 0 0 2920 +561 563 0.999075032162747 -0.0337792032103504 -0.0266091251167775 0.277997570687937 0.0346037988281834 0.998915116751472 0.0311635465255821 0.0221573322976267 0.0255275775518374 -0.0320554980598861 0.999160041148798 0.0292201671577487 4.0002179711201e-05 -1.59692541501919e-05 -8.06398641725516e-06 -1.95258189126333e-05 1.78975300061364e-06 1.99664519230559e-06 -1.59692541501919e-05 3.74818068923627e-05 2.96522152108018e-06 5.24181307692279e-06 -2.30238865653962e-06 -9.44050131538494e-06 -8.06398641725516e-06 2.96522152108018e-06 1.41253906697193e-05 7.90120164609329e-06 3.29666479958616e-06 8.66965010927768e-08 -1.95258189126333e-05 5.24181307692279e-06 7.90120164609329e-06 0.000316592272666081 -6.3624844950857e-06 9.72651268808193e-05 1.78975300061364e-06 -2.30238865653962e-06 3.29666479958616e-06 -6.3624844950857e-06 1.15064352115395e-05 -4.36078535819403e-06 1.99664519230559e-06 -9.44050131538494e-06 8.66965010927768e-08 9.72651268808193e-05 -4.36078535819403e-06 0.000187353844754097 3290 3293 0 208 417 3290 3293 0 151 496 0 0 0 0 0 0 0 0 3594 0 0 0 0 0 3295 +563 608 0.767040721435475 -0.629688396209726 -0.123048995682898 2.9051620588527 0.625771865913166 0.776567144580123 -0.0731644844868663 0.52208030435375 0.141626634116966 -0.0208804606629677 0.989699905461853 0.497425588345055 9.56651410773595e-05 -1.84353383392675e-05 8.0254683659234e-06 -3.91924755756734e-06 -1.20152070220026e-05 -3.11438265142893e-05 -1.84353383392675e-05 4.75013725839984e-05 -1.17799338041908e-05 3.58712982944859e-06 4.51956431124292e-06 2.17362400443714e-05 8.0254683659234e-06 -1.17799338041908e-05 2.02695147137213e-05 2.72089991683971e-06 -3.29419659205362e-07 -2.50443107525387e-06 -3.91924755756734e-06 3.58712982944859e-06 2.72089991683971e-06 2.81033551071388e-05 -4.22116505641835e-06 -2.30333826603372e-05 -1.20152070220026e-05 4.51956431124292e-06 -3.29419659205362e-07 -4.22116505641835e-06 2.98639293767304e-05 4.75265272679776e-05 -3.11438265142893e-05 2.17362400443714e-05 -2.50443107525387e-06 -2.30333826603372e-05 4.75265272679776e-05 0.000469412467232723 1642 1621 0 1207 3574 1642 1621 0 1197 3574 0 0 0 0 0 0 0 0 257 0 0 0 0 0 0 +563 566 0.999411072296877 -0.0342872385592293 -0.0013761694624804 0.441130281743082 0.0343014709902275 0.999337417415446 0.0121710821759627 0.0643441166235316 0.000957944838469948 -0.0122111189253872 0.999924982644336 0.03341382526533 3.41251489832554e-05 -3.33990410351613e-06 -6.11402439212031e-06 -8.66375969396107e-06 -1.21734753484342e-06 8.94622059816013e-06 -3.33990410351613e-06 7.88019143955227e-05 8.32284720821728e-07 1.48065804272169e-05 -2.82771907700759e-07 -2.71317088607574e-05 -6.11402439212031e-06 8.32284720821728e-07 1.09515799953435e-05 4.90606502394935e-07 4.20747328218624e-06 2.57341192043733e-06 -8.66375969396107e-06 1.48065804272169e-05 4.90606502394935e-07 0.000188826605691232 1.35972263861915e-06 -0.000104289696193334 -1.21734753484342e-06 -2.82771907700759e-07 4.20747328218624e-06 1.35972263861915e-06 1.03770838966744e-05 -8.74091042640487e-06 8.94622059816013e-06 -2.71317088607574e-05 2.57341192043733e-06 -0.000104289696193334 -8.74091042640487e-06 0.000278743597236153 3296 3279 0 440 732 3296 3279 0 370 813 0 0 0 0 0 0 0 0 3356 0 0 0 0 0 2974 +563 565 0.999263373837927 -0.0381690556556346 -0.00397905722512335 0.266987677770768 0.0381680719617782 0.99927128149711 -0.000322889833574904 0.0445526359585082 0.0039884820125277 0.000170779041967483 0.999992031391128 0.0362541061301831 4.50197806124549e-05 -1.70423342802002e-05 2.32919820808185e-06 2.42039403768104e-06 5.27605108524026e-07 1.62491801035527e-05 -1.70423342802002e-05 0.000100484244355079 3.71207787346018e-06 -2.23327603230921e-05 -8.99561666720536e-07 8.27549506545649e-06 2.32919820808185e-06 3.71207787346018e-06 1.30373847732894e-05 -1.13763445318539e-06 4.57080137624459e-06 2.17650994021933e-06 2.42039403768104e-06 -2.23327603230921e-05 -1.13763445318539e-06 0.000211654347840371 -1.7615737503115e-07 -3.64272423976199e-05 5.27605108524026e-07 -8.99561666720536e-07 4.57080137624459e-06 -1.7615737503115e-07 1.10211387236102e-05 -1.75262744199877e-05 1.62491801035527e-05 8.27549506545649e-06 2.17650994021933e-06 -3.64272423976199e-05 -1.75262744199877e-05 0.000609077081265804 3281 3264 0 163 430 3281 3264 0 110 500 0 0 0 0 0 0 0 0 3630 0 0 0 0 0 3301 +564 568 0.997703497840428 0.0577365437328384 0.0354149956199415 0.561597062344625 -0.0562706271960438 0.997570074381039 -0.0410799612265074 0.0473699123351048 -0.0377007547926867 0.0389927969911563 0.998528024078878 0.0319085519847384 4.4131420091643e-05 8.99235966660932e-06 -2.47304429795123e-06 -1.25602595511443e-05 4.97224258472412e-07 -3.47367407167806e-06 8.99235966660932e-06 5.60245177092478e-05 3.37144424091837e-06 1.54591994200479e-05 3.16065101047354e-08 -4.87307897167905e-05 -2.47304429795123e-06 3.37144424091837e-06 1.28971155756464e-05 -2.04295942453192e-06 3.615324498534e-06 -5.92997574217285e-06 -1.25602595511443e-05 1.54591994200479e-05 -2.04295942453192e-06 0.00067648643556316 2.23187032797e-05 -0.000119915063511836 4.97224258472412e-07 3.16065101047354e-08 3.615324498534e-06 2.23187032797e-05 1.21744735215696e-05 -1.94299634642156e-06 -3.47367407167806e-06 -4.87307897167905e-05 -5.92997574217285e-06 -0.000119915063511836 -1.94299634642156e-06 0.000156422008191623 3338 3335 0 969 699 3338 3335 0 880 779 0 0 0 0 0 0 0 0 2858 0 0 0 0 0 3028 +564 608 0.779811931860675 -0.618196386664473 -0.0986234173141054 2.7793538271343 0.615280355080795 0.78591861934493 -0.0613352135286921 0.460485604722837 0.115427187349312 -0.0128511198714078 0.993232809133225 0.465519952439928 0.000106138990590694 -2.10850802957585e-05 -1.17451854153159e-06 -1.09122670261341e-06 -3.15804352780586e-07 1.71319071804299e-05 -2.10850802957585e-05 7.6736353940689e-05 -6.75809542634052e-06 -1.805523597789e-05 1.247916418183e-05 -2.49642636842745e-06 -1.17451854153159e-06 -6.75809542634052e-06 1.79808203688743e-05 4.4399768728399e-06 4.35062553009084e-06 3.95797829132607e-06 -1.09122670261341e-06 -1.805523597789e-05 4.4399768728399e-06 3.88715347150154e-05 -1.26205659937766e-05 -3.87074659515277e-05 -3.15804352780586e-07 1.247916418183e-05 4.35062553009084e-06 -1.26205659937766e-05 3.45096798196509e-05 4.84778637928616e-05 1.71319071804299e-05 -2.49642636842745e-06 3.95797829132607e-06 -3.87074659515277e-05 4.84778637928616e-05 0.00032098148464523 1674 1653 0 1209 3539 1674 1653 0 1192 3539 0 0 0 0 0 0 0 0 272 0 0 0 0 0 0 +564 605 0.940930298111736 -0.328591506555159 -0.0817177821234179 2.88953881956237 0.332358469322453 0.942410417020664 0.0374226370072329 0.263720359609406 0.0647149284554605 -0.0623716899783079 0.99595268478189 0.248672117988714 6.92170704650142e-05 -5.24364177499374e-06 8.31365467810731e-06 -2.39381654869564e-05 -9.85045203366121e-06 3.42218993818339e-05 -5.24364177499374e-06 8.38292578980119e-05 -5.54860048600175e-06 6.29324953787438e-06 6.93140209131899e-06 8.8199975256361e-06 8.31365467810731e-06 -5.54860048600175e-06 1.96922570383245e-05 -3.19437248555372e-06 -3.05381968238382e-09 1.03530022912825e-05 -2.39381654869564e-05 6.29324953787438e-06 -3.19437248555372e-06 0.000125442227054965 -1.85456187281407e-05 -4.81799379292178e-06 -9.85045203366121e-06 6.93140209131899e-06 -3.05381968238382e-09 -1.85456187281407e-05 3.10774816215001e-05 -3.08091419306755e-05 3.42218993818339e-05 8.8199975256361e-06 1.03530022912825e-05 -4.81799379292178e-06 -3.08091419306755e-05 0.000472779092880532 2801 2647 0 2822 3938 2801 2647 0 2822 3938 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +565 608 0.791078182861259 -0.601712145569973 -0.110171695432661 2.67359829496332 0.598237599455775 0.798595639293674 -0.0660059050276579 0.38004546032803 0.127699190280594 -0.0136930191962156 0.99171841670253 0.476876068749952 0.000139601337807333 4.28847162455757e-06 1.15128509450831e-05 2.14035912235559e-06 -7.15340240560382e-06 4.73166859676122e-05 4.28847162455757e-06 4.84868445731596e-05 -3.23959709277633e-06 1.10243280150708e-05 -7.14490335745046e-06 2.82223170231434e-05 1.15128509450831e-05 -3.23959709277633e-06 2.17076174938669e-05 2.50097318181732e-06 3.99957727241185e-06 2.2311251593868e-06 2.14035912235559e-06 1.10243280150708e-05 2.50097318181732e-06 3.46369186712817e-05 -3.17056629151146e-06 5.24076706087464e-05 -7.15340240560382e-06 -7.14490335745046e-06 3.99957727241185e-06 -3.17056629151146e-06 2.33944465070594e-05 -2.04956114665105e-05 4.73166859676122e-05 2.82223170231434e-05 2.2311251593868e-06 5.24076706087464e-05 -2.04956114665105e-05 0.000325708904445485 1704 1683 0 1183 3567 1704 1683 0 1165 3567 0 0 0 0 0 0 0 0 278 0 0 0 0 0 0 +565 569 0.994437758342333 0.105279040036651 -0.00314141879359447 0.580444795895912 -0.105283364060939 0.992746397873602 -0.0580517248753222 0.000165343650095395 -0.00299299767579237 0.0580595662914351 0.998308634004015 0.018064759319967 4.44601201532313e-05 1.28177218673294e-05 -9.90736801778078e-07 1.36264158875225e-05 5.10015412498934e-07 -8.90748282842765e-06 1.28177218673294e-05 0.000116793441021354 -1.58722046444466e-06 9.55561185475836e-06 -7.12197705103527e-07 -0.000118150380372429 -9.90736801778078e-07 -1.58722046444466e-06 1.61541987090913e-05 3.78258385956902e-06 3.13138550364024e-06 3.04312921633563e-06 1.36264158875225e-05 9.55561185475836e-06 3.78258385956902e-06 0.000262413294401914 9.77695818855738e-06 4.75749463691545e-05 5.10015412498934e-07 -7.12197705103527e-07 3.13138550364024e-06 9.77695818855738e-06 1.30771570955892e-05 4.21287825268926e-06 -8.90748282842765e-06 -0.000118150380372429 3.04312921633563e-06 4.75749463691545e-05 4.21287825268926e-06 0.000193540642448048 3268 3275 0 1223 533 3268 3275 0 1124 599 0 0 0 0 0 0 0 0 2589 0 0 0 0 0 3213 +565 596 0.612075380970516 0.790665439887446 0.014556447966086 2.82654292492617 -0.784605837376466 0.609477951291931 -0.113711507085979 -0.28839491817791 -0.0987795928548576 0.0581789399747243 0.99340716877766 0.0756619729272801 6.74084074453563e-05 1.34808391530288e-05 -1.05199089806649e-06 -9.44098596714174e-06 -1.09568690875229e-05 9.66429789965062e-06 1.34808391530288e-05 8.02763967921053e-05 -1.06419773755552e-06 1.69154206271893e-05 2.12750336563827e-05 -4.57200988414839e-05 -1.05199089806649e-06 -1.06419773755552e-06 1.50473043286404e-05 -3.3095606572964e-06 4.56548850558404e-06 -2.49978012241747e-07 -9.44098596714174e-06 1.69154206271893e-05 -3.3095606572964e-06 8.9866028160719e-05 8.70856262417283e-05 -3.44273982990146e-05 -1.09568690875229e-05 2.12750336563827e-05 4.56548850558404e-06 8.70856262417283e-05 0.000122528705124846 -3.52814596134134e-05 9.66429789965062e-06 -4.57200988414839e-05 -2.49978012241747e-07 -3.44273982990146e-05 -3.52814596134134e-05 0.00012861262608573 3205 3245 0 2604 2327 3205 3245 0 2604 2346 0 0 0 0 0 0 0 0 0 0 0 0 0 0 358 +565 568 0.996665256299016 0.0774619187798741 0.025651862025149 0.41936736775654 -0.0760438805757413 0.995732938685911 -0.0522804269579215 0.0184372826568979 -0.0295921461438588 0.050155418001053 0.99830292944163 0.00376089725826327 3.65683330057345e-05 9.61969761486484e-06 2.01876905697983e-06 -6.05315449825392e-06 -1.92372996388109e-06 -1.05306161078194e-05 9.61969761486484e-06 8.06029884520343e-05 8.0986665825564e-06 -2.28968297985997e-05 -5.60098727595717e-06 -2.95817731913197e-05 2.01876905697983e-06 8.0986665825564e-06 1.60142831293696e-05 -1.36516838157538e-05 1.87539938141122e-06 -8.68274624290951e-06 -6.05315449825392e-06 -2.28968297985997e-05 -1.36516838157538e-05 0.000257146476985876 1.10944583019153e-05 -3.7772804995939e-05 -1.92372996388109e-06 -5.60098727595717e-06 1.87539938141122e-06 1.10944583019153e-05 1.3524162404092e-05 7.43960058007317e-06 -1.05306161078194e-05 -2.95817731913197e-05 -8.68274624290951e-06 -3.7772804995939e-05 7.43960058007317e-06 0.000335145099812835 3356 3353 0 800 339 3356 3353 0 711 400 0 0 0 0 0 0 0 0 3023 0 0 0 0 0 3415 +566 570 0.992994913603074 0.117968845200335 -0.00666731734081053 0.540495558856566 -0.118133554886777 0.990088605224342 -0.0759540454138521 -0.024937791157 -0.0023589760992148 0.0762096146625603 0.997089028053537 0.0167688084919899 4.34846527516897e-05 9.57161602421236e-07 -5.57750781787549e-06 3.02446372617956e-06 2.15037890682522e-06 1.18643450066602e-06 9.57161602421236e-07 5.21039657435334e-05 5.03024293440503e-07 4.77494436078747e-06 1.05653422220046e-06 -4.33567790014207e-05 -5.57750781787549e-06 5.03024293440503e-07 1.31292528051162e-05 -4.76725609168228e-06 2.31397091146442e-06 2.27345359877766e-06 3.02446372617956e-06 4.77494436078747e-06 -4.76725609168228e-06 0.000342700487515958 2.76831196413947e-05 -1.51829948434448e-05 2.15037890682522e-06 1.05653422220046e-06 2.31397091146442e-06 2.76831196413947e-05 1.48241746664341e-05 -2.24137775830509e-06 1.18643450066602e-06 -4.33567790014207e-05 2.27345359877766e-06 -1.51829948434448e-05 -2.24137775830509e-06 9.13327905457352e-05 3287 3302 0 1207 393 3287 3302 0 1120 447 0 0 0 0 0 0 0 0 2602 0 0 0 0 0 3364 +566 569 0.994789653288632 0.101060564977 -0.0134278783288051 0.405784191190131 -0.101770171963145 0.9921880495502 -0.0721505816217793 -0.0100363869075352 0.00603140186653832 0.0731412095627256 0.99730335688557 0.000970746309541026 3.67134332460367e-05 1.04764518253246e-06 -2.59289247958406e-06 -2.77826613178988e-06 6.68288354830233e-07 -1.13953480474843e-05 1.04764518253246e-06 2.62754770053808e-05 2.32400703820048e-06 -8.16688954651587e-07 -7.90604450548414e-08 -1.35575250248089e-05 -2.59289247958406e-06 2.32400703820048e-06 1.35266266639898e-05 -3.58262421143646e-06 2.80177641469011e-06 -2.18846807210832e-06 -2.77826613178988e-06 -8.16688954651587e-07 -3.58262421143646e-06 0.000227472705483164 8.29488004097129e-06 -1.49395752635635e-05 6.68288354830233e-07 -7.90604450548414e-08 2.80177641469011e-06 8.29488004097129e-06 1.22816523060864e-05 8.77128823015332e-07 -1.13953480474843e-05 -1.35575250248089e-05 -2.18846807210832e-06 -1.49395752635635e-05 8.77128823015332e-07 9.80032289902376e-05 3388 3395 0 878 219 3388 3395 0 798 285 0 0 0 0 0 0 0 0 2947 0 0 0 0 0 3531 +566 568 0.99714598386967 0.074624367514212 0.0114494814595539 0.260053371913214 -0.0737585962145084 0.995272266583938 -0.0631884867150259 0.00641486975755198 -0.0161107522187499 0.0621636480748493 0.997935932072281 -0.00127988883921254 4.31262624670474e-05 5.91445259895691e-06 2.69802469765681e-06 -7.11996232418198e-06 -3.37290875842469e-07 -1.05224615617698e-05 5.91445259895691e-06 3.73363947912264e-05 1.91840995229495e-06 -6.4899992576572e-06 -1.2011987981224e-06 -2.71593882751099e-05 2.69802469765681e-06 1.91840995229495e-06 1.18340437125299e-05 -2.12032953792009e-06 4.49881221602106e-06 -2.3915780547244e-06 -7.11996232418198e-06 -6.4899992576572e-06 -2.12032953792009e-06 0.00031264415456999 6.32557028236901e-06 -1.50641166414744e-05 -3.37290875842469e-07 -1.2011987981224e-06 4.49881221602106e-06 6.32557028236901e-06 1.02509694848619e-05 4.63571244654385e-07 -1.05224615617698e-05 -2.71593882751099e-05 -2.3915780547244e-06 -1.50641166414744e-05 4.63571244654385e-07 5.661803984076e-05 3367 3364 0 537 94 3367 3364 0 461 147 0 0 0 0 0 0 0 0 3294 0 0 0 0 0 3671 +567 571 0.995893791887876 0.090497389259959 0.00240370886721843 0.546144712772373 -0.0902690068616179 0.994692234753007 -0.0493848612662468 -0.0276610612535058 -0.00686015155838973 0.048965096336071 0.998776930881663 0.0288806649598135 4.25016218188132e-05 1.42974790617586e-05 -5.46391462743701e-06 3.7673106083365e-07 -1.12672430293005e-07 -9.75318500781564e-06 1.42974790617586e-05 6.14821527436719e-05 5.67938074568095e-06 -1.74679001457596e-05 -1.80072385231477e-06 -4.68609591299554e-05 -5.46391462743701e-06 5.67938074568095e-06 1.21708970829962e-05 -7.05402922343708e-06 3.00907220172234e-06 -3.12536748900498e-06 3.7673106083365e-07 -1.74679001457596e-05 -7.05402922343708e-06 0.000219481908050292 1.30098441545971e-05 -2.10902110184553e-05 -1.12672430293005e-07 -1.80072385231477e-06 3.00907220172234e-06 1.30098441545971e-05 1.36262300379142e-05 -2.09502193187357e-06 -9.75318500781564e-06 -4.68609591299554e-05 -3.12536748900498e-06 -2.10902110184553e-05 -2.09502193187357e-06 0.00010197515634133 3319 3336 0 1129 476 3319 3336 0 1039 546 0 0 0 0 0 0 0 0 2662 0 0 0 0 0 3284 +568 608 0.738354845538242 -0.661157640436681 -0.133051480872626 2.22198016639669 0.663656564899156 0.747392939008754 -0.0310444614401626 0.555326987039068 0.119967020203264 -0.0653786602192037 0.99062280654722 0.475742378419658 7.01563745984767e-05 -2.32591497530566e-05 -5.01140418981962e-07 3.60081242543374e-06 -3.83532438140268e-06 1.41149681366952e-06 -2.32591497530566e-05 5.81172268074288e-05 -8.17864349388814e-06 -3.15202787077561e-06 -1.12882722174483e-07 -2.26227333425804e-05 -5.01140418981962e-07 -8.17864349388814e-06 1.70328962668624e-05 3.03884570443014e-06 1.30962657836332e-06 -2.41940630736576e-06 3.60081242543374e-06 -3.15202787077561e-06 3.03884570443014e-06 6.22976915520043e-05 -2.29273237958601e-05 4.57573595056046e-05 -3.83532438140268e-06 -1.12882722174483e-07 1.30962657836332e-06 -2.29273237958601e-05 3.72722273054764e-05 -1.12409784009568e-05 1.41149681366952e-06 -2.26227333425804e-05 -2.41940630736576e-06 4.57573595056046e-05 -1.12409784009568e-05 0.000290838214809376 1616 1600 0 866 3557 1616 1600 0 824 3557 0 0 0 0 0 0 0 0 488 0 0 0 0 0 0 +567 598 0.837140127447214 0.546749031882304 0.0161834221790644 2.53953861262003 -0.541926286034097 0.833045458010194 -0.111135797085713 -0.18524307199197 -0.0742449158054128 0.0842660134594592 0.993673453128691 0.126284385101549 7.3413385745255e-05 4.25945775074959e-05 -2.19338708302273e-06 1.56346899875189e-05 1.69266620126599e-05 3.29608749452972e-05 4.25945775074959e-05 0.000356432212661156 -2.61045683243078e-05 0.000104633516613217 9.06403966281745e-05 0.000158980614750385 -2.19338708302273e-06 -2.61045683243078e-05 1.62507775384764e-05 -1.346119871552e-05 -4.50212060904161e-06 -2.05524818800339e-05 1.56346899875189e-05 0.000104633516613217 -1.346119871552e-05 0.000100959303790267 6.92376207632029e-05 0.000212441113747324 1.69266620126599e-05 9.06403966281745e-05 -4.50212060904161e-06 6.92376207632029e-05 8.66857510817709e-05 0.000220339022270035 3.29608749452972e-05 0.000158980614750385 -2.05524818800339e-05 0.000212441113747324 0.000220339022270035 0.00086053285768964 3087 3255 0 3135 2988 3087 3255 0 3135 3012 0 0 0 0 0 0 0 0 0 0 0 0 0 0 478 +568 572 0.999054342136643 0.0395963143195987 0.0179597703277055 0.572223495107307 -0.0393408842960958 0.999122664558232 -0.0143595260667156 0.0032498444854707 -0.0185125978922891 0.0136393936215298 0.999735590374233 0.0364303730523206 4.95339705059179e-05 -1.2490706986509e-05 -8.7623560982733e-06 -2.9494612252084e-05 1.46768388806972e-07 1.09173795776023e-05 -1.2490706986509e-05 0.000119086989486638 5.46686990784297e-06 -7.41229450191871e-05 -1.61422149454044e-05 -0.000168376681615474 -8.7623560982733e-06 5.46686990784297e-06 1.3273991110525e-05 -4.52144998367167e-06 2.05049690426342e-06 -6.40003614490663e-06 -2.9494612252084e-05 -7.41229450191871e-05 -4.52144998367167e-06 0.000378814783368376 3.29528360971425e-05 0.000189721014598939 1.46768388806972e-07 -1.61422149454044e-05 2.05049690426342e-06 3.29528360971425e-05 1.63164326465648e-05 3.25681509551683e-05 1.09173795776023e-05 -0.000168376681615474 -6.40003614490663e-06 0.000189721014598939 3.25681509551683e-05 0.000408244690438741 3214 3230 0 956 714 3214 3230 0 865 798 0 0 0 0 0 0 0 0 2835 0 0 0 0 0 3025 +568 594 0.529760980540538 0.848142912383887 -0.00262748353111185 2.42888103463586 -0.847673542315209 0.529359229439311 -0.0350481364155814 -0.130176381466272 -0.0283349458357452 0.0207943833858294 0.99938217137594 0.14628359058372 5.05429310536908e-05 -2.84794277026448e-05 -6.50033088102783e-06 1.05927134994993e-05 1.10447388912648e-05 -1.99322553416294e-05 -2.84794277026448e-05 0.00021927856331482 -5.42525040034485e-06 -1.47472983064842e-05 -4.36234775821531e-05 -0.0001559855184332 -6.50033088102783e-06 -5.42525040034485e-06 1.5477783686605e-05 -4.23389672225284e-06 1.41237172408468e-06 -1.95284944003011e-06 1.05927134994993e-05 -1.47472983064842e-05 -4.23389672225284e-06 3.91021159490636e-05 4.8525339918675e-05 2.25622170512482e-05 1.10447388912648e-05 -4.36234775821531e-05 1.41237172408468e-06 4.8525339918675e-05 0.000127055530980351 9.41570683611205e-05 -1.99322553416294e-05 -0.0001559855184332 -1.95284944003011e-06 2.25622170512482e-05 9.41570683611205e-05 0.000472612065272997 2630 2695 0 2707 1943 2630 2695 0 2707 1973 0 0 0 0 0 0 0 0 0 0 0 0 0 0 502 +569 571 0.999420728002499 0.0163696486422822 0.0298369409002105 0.270433710125267 -0.0167202817448693 0.99979360596871 0.0115402618018944 0.00307566599005506 -0.0296418727027598 -0.0120324589096453 0.999488158666855 0.0221702137019303 5.48236608523863e-05 4.01684789563481e-06 -1.23223953025844e-06 -4.24208718829087e-05 -2.66009425540933e-06 1.02011517268368e-05 4.01684789563481e-06 0.000267622302960499 -1.5480656577438e-06 -1.3954094694256e-05 -2.88222959808153e-06 -0.000270303312044237 -1.23223953025844e-06 -1.5480656577438e-06 1.38949513209429e-05 -7.90624553663965e-07 3.75376035106771e-06 2.10096900430459e-06 -4.24208718829087e-05 -1.3954094694256e-05 -7.90624553663965e-07 0.000364970701531757 2.14740906367494e-05 -5.6938695376645e-05 -2.66009425540933e-06 -2.88222959808153e-06 3.75376035106771e-06 2.14740906367494e-05 1.27699713577364e-05 -3.41559878527147e-06 1.02011517268368e-05 -0.000270303312044237 2.10096900430459e-06 -5.6938695376645e-05 -3.41559878527147e-06 0.000364937443031925 3149 3166 0 372 259 3149 3166 0 321 317 0 0 0 0 0 0 0 0 3424 0 0 0 0 0 3504 +569 572 0.999209991362918 0.0131899562960505 0.0374889078718629 0.432458429931908 -0.0128748679900423 0.999879839743798 -0.00863387793264483 0.0204525075323276 -0.0375982836676853 0.00814439235456544 0.999259744980463 0.017258502942626 5.26470157673157e-05 -2.32665691369141e-05 -4.64545562607049e-07 -2.50689911179499e-05 -9.52054798710804e-07 1.65983339570894e-05 -2.32665691369141e-05 0.000147027378598649 -7.93360027304538e-06 -5.1115913447417e-05 -7.66013269734435e-06 -0.000128550272050636 -4.64545562607049e-07 -7.93360027304538e-06 1.23261821053056e-05 1.05036343333751e-06 5.34059021464572e-06 1.28940525280383e-05 -2.50689911179499e-05 -5.1115913447417e-05 1.05036343333751e-06 0.000340323552135588 2.50247702113411e-05 0.000185068951331759 -9.52054798710804e-07 -7.66013269734435e-06 5.34059021464572e-06 2.50247702113411e-05 1.32236057037243e-05 2.1865864472544e-05 1.65983339570894e-05 -0.000128550272050636 1.28940525280383e-05 0.000185068951331759 2.1865864472544e-05 0.000310042362238206 3210 3226 0 584 561 3210 3226 0 525 634 0 0 0 0 0 0 0 0 3213 0 0 0 0 0 3186 +570 573 0.998781297794895 -0.019214841425503 0.0454610717442804 0.450268449801502 0.0174514918618512 0.999091790802487 0.0388720848794601 0.048818347399425 -0.0461667045276309 -0.0380313478603241 0.998209523082697 0.0428554775288544 5.69798042176268e-05 -4.33391960563155e-05 2.34029924283675e-07 -2.66138226972097e-05 -4.36486599153505e-06 5.87222404263863e-05 -4.33391960563155e-05 0.000140730436218837 1.63315663398089e-06 5.16177906628988e-05 3.43901617893822e-06 -0.000135877889444692 2.34029924283675e-07 1.63315663398089e-06 1.37073647005454e-05 5.03306483047875e-06 4.0675608081629e-06 -1.516086755466e-06 -2.66138226972097e-05 5.16177906628988e-05 5.03306483047875e-06 0.000297696968951206 1.57695300182182e-05 -0.000122780192249415 -4.36486599153505e-06 3.43901617893822e-06 4.0675608081629e-06 1.57695300182182e-05 1.21418296158561e-05 -9.21023066970927e-06 5.87222404263863e-05 -0.000135877889444692 -1.516086755466e-06 -0.000122780192249415 -9.21023066970927e-06 0.000286317093182811 3204 3213 0 496 725 3204 3213 0 434 810 0 0 0 0 0 0 0 0 3293 0 0 0 0 0 3020 +570 605 0.900380927013137 -0.421315529816302 -0.10866190963982 1.98534024870257 0.430403491474882 0.899039337944399 0.0805053001654377 0.458287083021207 0.0637731981101365 -0.119253902091734 0.990813547565182 0.247809880209404 7.65110601609399e-05 -4.30506507901317e-05 2.73404182637037e-07 9.72117817367739e-06 -4.04142267474031e-06 4.06675159977512e-05 -4.30506507901317e-05 7.03288748660526e-05 -5.02934175686453e-06 -1.20727187218227e-05 4.13900254152675e-06 -3.3641271105835e-05 2.73404182637037e-07 -5.02934175686453e-06 1.39077056670628e-05 2.59271307104304e-06 1.90489836662372e-06 8.41736430930669e-06 9.72117817367739e-06 -1.20727187218227e-05 2.59271307104304e-06 0.000122057701644578 -3.11187797204728e-05 7.17398992615541e-05 -4.04142267474031e-06 4.13900254152675e-06 1.90489836662372e-06 -3.11187797204728e-05 2.96385435718948e-05 -3.83516707544061e-05 4.06675159977512e-05 -3.3641271105835e-05 8.41736430930669e-06 7.17398992615541e-05 -3.83516707544061e-05 0.000270905913724669 2930 2776 0 2191 3938 2930 2776 0 2104 3938 0 0 0 0 0 0 0 0 593 0 0 0 0 0 0 +571 573 0.998960291735242 -0.0172863714871791 0.0421843205118604 0.257326984597478 0.0163327536947877 0.999605552594526 0.022846889918257 0.0361555124824888 -0.0425626208425364 -0.0221341497012827 0.998848588487773 0.0275987661229799 4.55559868754065e-05 -2.01421440928352e-05 -6.45002967895785e-07 -9.75745318144817e-06 -2.79994595325321e-06 1.92409547232171e-05 -2.01421440928352e-05 5.17340836055563e-05 2.69706610415544e-07 4.27229270365756e-05 2.29835718759013e-06 -4.08341597934352e-05 -6.45002967895785e-07 2.69706610415544e-07 1.3329962646348e-05 -6.39710195336597e-06 2.49445111673402e-06 -1.24513462146907e-07 -9.75745318144817e-06 4.27229270365756e-05 -6.39710195336597e-06 0.000436086757771385 2.77019985194594e-05 -4.60919872812899e-05 -2.79994595325321e-06 2.29835718759013e-06 2.49445111673402e-06 2.77019985194594e-05 1.39277250548136e-05 -3.14470793969254e-06 1.92409547232171e-05 -4.08341597934352e-05 -1.24513462146907e-07 -4.60919872812899e-05 -3.14470793969254e-06 8.3950032023973e-05 3244 3253 0 208 373 3244 3253 0 160 445 0 0 0 0 0 0 0 0 3576 0 0 0 0 0 3393 +571 607 0.763034067704177 -0.631480464940103 -0.137881956476722 1.77772448253276 0.631164111896374 0.773928135333175 -0.0516440237953628 0.583971634395365 0.139322917629793 -0.0476199930569776 0.989101340047811 0.412035140185386 0.000126811594928857 -0.000131753097861923 7.51838208481282e-06 2.81038689115477e-05 -9.27104379775945e-06 6.2959227519947e-05 -0.000131753097861923 0.000622196477968086 -3.37178581744919e-05 -9.95963520617808e-05 1.37666367530799e-05 -0.000669108382009105 7.51838208481282e-06 -3.37178581744919e-05 2.04691785688514e-05 5.83694465623039e-06 1.36967336800446e-06 3.29839136944285e-05 2.81038689115477e-05 -9.95963520617808e-05 5.83694465623039e-06 8.41817299588971e-05 -2.19823989080991e-05 0.000111528583016421 -9.27104379775945e-06 1.37666367530799e-05 1.36967336800446e-06 -2.19823989080991e-05 3.55970602390826e-05 -2.58276514871644e-06 6.2959227519947e-05 -0.000669108382009105 3.29839136944285e-05 0.000111528583016421 -2.58276514871644e-06 0.00128634146109962 2015 1994 0 266 3636 2015 1994 0 184 3636 0 0 0 0 0 0 0 0 1243 0 0 0 0 0 0 +572 607 0.763136493624129 -0.62493015277711 -0.164575199374167 1.60254801771797 0.630547147408435 0.775834244405965 -0.022170252639758 0.563912596484936 0.141537934823689 -0.0868534936372896 0.986115350072618 0.417913464115747 0.000144912149548438 -1.63471550764167e-05 1.37809612519091e-05 8.47434021152321e-06 -1.41927372300571e-05 -0.000119487009671718 -1.63471550764167e-05 9.27879955536862e-05 2.69985804257575e-06 -6.53182441366937e-07 -9.4278908828347e-07 6.08336752939462e-05 1.37809612519091e-05 2.69985804257575e-06 2.31702525501188e-05 4.71757650732538e-06 -7.13017855075677e-07 -2.0977216552366e-05 8.47434021152321e-06 -6.53182441366937e-07 4.71757650732538e-06 9.3971757206453e-05 -4.08356491547185e-05 5.11771437411407e-07 -1.41927372300571e-05 -9.4278908828347e-07 -7.13017855075677e-07 -4.08356491547185e-05 5.17252579074217e-05 3.03761393443924e-05 -0.000119487009671718 6.08336752939462e-05 -2.0977216552366e-05 5.11771437411407e-07 3.03761393443924e-05 0.000700816527587502 1938 1910 0 0 3701 1938 1910 0 0 3701 0 0 0 0 0 0 0 0 1491 0 0 0 0 0 0 +572 576 0.994831366115424 -0.098976448373613 -0.0226763237819769 0.554290522729491 0.100472219616888 0.991815785677183 0.0787831223474118 0.122795052829993 0.014693062246361 -0.0806542618148407 0.996633836457968 0.0324173572764545 5.19244052595546e-05 -3.69744066225626e-05 -1.02985249604934e-05 -5.60974691096977e-06 -2.68986062760141e-06 4.28229752236639e-05 -3.69744066225626e-05 9.59439017165404e-05 5.75621545927886e-06 -1.61545545724862e-05 4.37487175719896e-06 -9.46324522054688e-05 -1.02985249604934e-05 5.75621545927886e-06 1.48021025535169e-05 -2.25044905065176e-06 4.05140899896833e-06 -4.90344078781724e-06 -5.60974691096977e-06 -1.61545545724862e-05 -2.25044905065176e-06 0.000272771388289441 -1.79034318399859e-06 2.1143793326801e-05 -2.68986062760141e-06 4.37487175719896e-06 4.05140899896833e-06 -1.79034318399859e-06 1.20671944131831e-05 -4.6633761361226e-06 4.28229752236639e-05 -9.46324522054688e-05 -4.90344078781724e-06 2.1143793326801e-05 -4.6633761361226e-06 0.000121236700260686 3241 3215 0 383 1192 3241 3215 0 315 1281 0 0 0 0 0 0 0 0 3392 0 0 0 0 0 2530 +573 575 0.996624655378906 -0.0636808941423372 -0.0518077215491108 0.282427187275717 0.065392482623551 0.997345098247245 0.0320402593391879 0.0617169265228275 0.049629824775092 -0.0353199479533349 0.998142966598156 0.038931086307017 6.2561527778322e-05 -4.13947158482313e-05 -2.94763726963986e-06 3.34589053067818e-05 -1.93188847473075e-06 5.33737035311536e-05 -4.13947158482313e-05 0.000461040029062055 1.56254882577529e-05 -0.000149951499649124 2.23903746181627e-05 -0.000509505293059625 -2.94763726963986e-06 1.56254882577529e-05 1.39355117702406e-05 -5.0630232222978e-06 5.63955721867414e-06 -1.67479437302215e-05 3.34589053067818e-05 -0.000149951499649124 -5.0630232222978e-06 0.000531103424681827 2.51391303310522e-06 -3.38489205452718e-05 -1.93188847473075e-06 2.23903746181627e-05 5.63955721867414e-06 2.51391303310522e-06 1.25823840943978e-05 -4.34605174400523e-05 5.33737035311536e-05 -0.000509505293059625 -1.67479437302215e-05 -3.38489205452718e-05 -4.34605174400523e-05 0.000936028682486993 3172 3154 0 87 539 3172 3154 0 32 607 0 0 0 0 0 0 0 0 3696 0 0 0 0 0 3222 +573 576 0.996004720363051 -0.0857357000317178 -0.0249797268718561 0.429542375810823 0.0867100202477119 0.995391477072338 0.0409533852128228 0.0972714079051542 0.0213534400779505 -0.0429557576096589 0.9988487540589 0.0238916002540194 4.79297238267558e-05 -4.64416887271957e-05 -5.7546718826674e-06 6.30500416336426e-06 -4.36059610557268e-06 7.67521401960539e-05 -4.64416887271957e-05 0.000568331575984408 2.89999254293704e-05 -0.000163384953154565 1.60958807176232e-05 -0.000309765521835665 -5.7546718826674e-06 2.89999254293704e-05 1.26507584304576e-05 -6.38097328314471e-06 5.37759601183043e-06 -2.24471953790137e-05 6.30500416336426e-06 -0.000163384953154565 -6.38097328314471e-06 0.000328576492066862 -8.28342136692665e-06 8.63726974237984e-05 -4.36059610557268e-06 1.60958807176232e-05 5.37759601183043e-06 -8.28342136692665e-06 1.18089611170491e-05 -3.02828934070487e-05 7.67521401960539e-05 -0.000309765521835665 -2.24471953790137e-05 8.63726974237984e-05 -3.02828934070487e-05 0.000854514821244185 3067 3041 0 225 877 3067 3041 0 160 953 0 0 0 0 0 0 0 0 3534 0 0 0 0 0 2861 +574 576 0.998403001671491 -0.0558926854248081 -0.00821303654936908 0.292748277407587 0.0560269038837662 0.998282154571674 0.0171384335613111 0.0604414987774832 0.00724101474636374 -0.0175712145209058 0.999819393753544 0.0311835655301014 5.03271941660214e-05 -5.92970028026841e-05 -5.374450560686e-06 1.3031987613027e-05 -1.7204343559027e-06 2.01074062274937e-05 -5.92970028026841e-05 0.000311086551906955 2.09877478059172e-05 -0.000158325323113274 1.95747889864979e-06 -8.58955128980702e-05 -5.374450560686e-06 2.09877478059172e-05 1.38748852106042e-05 -6.94131097749898e-06 4.32246432359602e-06 -1.04241751327545e-05 1.3031987613027e-05 -0.000158325323113274 -6.94131097749898e-06 0.000456868492978299 5.39416060434047e-06 -0.000161623441161993 -1.7204343559027e-06 1.95747889864979e-06 4.32246432359602e-06 5.39416060434047e-06 1.10209060338641e-05 -1.14478037027653e-05 2.01074062274937e-05 -8.58955128980702e-05 -1.04241751327545e-05 -0.000161623441161993 -1.14478037027653e-05 0.000317789285955772 3164 3138 0 153 520 3164 3138 0 90 585 0 0 0 0 0 0 0 0 3624 0 0 0 0 0 3232 +574 577 0.998887894552172 -0.0460721494019486 -0.0100165446444527 0.425591714400941 0.0463189057486446 0.998588709529362 0.0259836135041281 0.081147350415626 0.00880528746708263 -0.0264186723733094 0.999612185131141 0.0842007749003958 4.75250380859223e-05 -1.06726261141494e-05 -8.00431541431966e-06 6.45246891293254e-06 2.46550307012941e-06 -2.28599434962831e-05 -1.06726261141494e-05 3.77956880904768e-05 2.10238917609501e-07 3.91295896799966e-06 -5.27719411574513e-06 5.11494081120785e-05 -8.00431541431966e-06 2.10238917609501e-07 1.4766987252243e-05 3.20883334022116e-06 3.34742256528102e-06 1.58776005052331e-06 6.45246891293254e-06 3.91295896799966e-06 3.20883334022116e-06 0.000259248164453109 3.72129994923778e-07 8.5799542592347e-07 2.46550307012941e-06 -5.27719411574513e-06 3.34742256528102e-06 3.72129994923778e-07 1.43494288507233e-05 -3.85640215661638e-05 -2.28599434962831e-05 5.11494081120785e-05 1.58776005052331e-06 8.5799542592347e-07 -3.85640215661638e-05 0.000618901151971465 3297 3267 0 386 730 3297 3267 0 306 801 0 0 0 0 0 0 0 0 3399 0 0 0 0 0 2992 +574 601 0.989806541429571 0.142369388860275 -0.00373733311100846 1.5773043251123 -0.142271184426836 0.987249630259625 -0.0713938206991322 0.018463999782274 -0.00647461388933532 0.0711977855539518 0.997441203634178 0.169420078248774 7.00249642321878e-05 -9.77940964474189e-06 -3.27397501988897e-06 -2.86018353981811e-05 -2.59388953399871e-06 2.43667572947299e-05 -9.77940964474189e-06 6.54206475722728e-05 1.93743474434781e-08 -4.28624403391484e-05 -7.25965717236489e-06 1.34400539857604e-05 -3.27397501988897e-06 1.93743474434781e-08 1.35646339475207e-05 -5.87366427256572e-06 3.83358114893501e-06 -4.62263535284658e-06 -2.86018353981811e-05 -4.28624403391484e-05 -5.87366427256572e-06 0.000257821060280798 3.38536952689402e-05 -2.82530804602353e-05 -2.59388953399871e-06 -7.25965717236489e-06 3.83358114893501e-06 3.38536952689402e-05 1.90503325644325e-05 1.11362219515227e-05 2.43667572947299e-05 1.34400539857604e-05 -4.62263535284658e-06 -2.82530804602353e-05 1.11362219515227e-05 0.00037967658460972 3257 3310 0 3047 2916 3257 3310 0 2966 2987 0 0 0 0 0 0 0 0 174 0 0 0 0 0 846 +574 578 0.999823215776382 -0.0162779719611661 -0.0094108885556264 0.587201115776194 0.0162587244441668 0.99986557463459 -0.00211814543657737 0.0960705857820597 0.00944410260551975 0.00196476193808016 0.999953473235882 0.107868367783407 3.92864328627921e-05 -9.86508115086272e-06 -6.2471356176325e-06 -1.86656869087487e-05 -1.39901827650859e-07 1.2765558564368e-05 -9.86508115086272e-06 0.000161451457427227 -5.23301847777674e-07 4.0870949442287e-05 6.12423713651803e-06 -0.000121605443146894 -6.2471356176325e-06 -5.23301847777674e-07 1.34471058670041e-05 -4.49207209728844e-06 3.22516668230462e-06 1.13839688647865e-06 -1.86656869087487e-05 4.0870949442287e-05 -4.49207209728844e-06 0.00016225591435476 7.61292162827006e-07 -5.35091425370442e-05 -1.39901827650859e-07 6.12423713651803e-06 3.22516668230462e-06 7.61292162827006e-07 1.20890349088893e-05 -7.4321841308778e-06 1.2765558564368e-05 -0.000121605443146894 1.13839688647865e-06 -5.35091425370442e-05 -7.4321841308778e-06 0.000184270770753331 3271 3254 0 766 959 3271 3254 0 670 1033 0 0 0 0 0 0 0 0 3031 0 0 0 0 0 2766 +575 577 0.999734817528788 -0.0104177321697072 0.020536929593345 0.276252469858899 0.0100696551672792 0.999805121796407 0.0169800021933063 0.0407567533182089 -0.0207098205084894 -0.0167686995951638 0.999644893974052 0.058546231322394 5.05341270047284e-05 -3.31180924473978e-06 -4.44621950807519e-06 8.30083039807118e-06 2.40121350554439e-07 9.18097077632921e-06 -3.31180924473978e-06 4.75426327795356e-05 1.84136587849966e-06 1.04378483759837e-05 3.84411111148964e-06 -4.71068791850536e-05 -4.44621950807519e-06 1.84136587849966e-06 1.41700133712004e-05 -4.79199765046625e-06 4.46992554172473e-06 -2.19003022907965e-06 8.30083039807118e-06 1.04378483759837e-05 -4.79199765046625e-06 0.00030063444800273 -5.29057534515119e-07 8.43253368098483e-06 2.40121350554439e-07 3.84411111148964e-06 4.46992554172473e-06 -5.29057534515119e-07 1.15579304944632e-05 -4.80735066693445e-06 9.18097077632921e-06 -4.71068791850536e-05 -2.19003022907965e-06 8.43253368098483e-06 -4.80735066693445e-06 7.94480222444893e-05 3261 3231 0 293 358 3261 3231 0 205 408 0 0 0 0 0 0 0 0 3500 0 0 0 0 0 3401 +575 579 0.998433391127422 0.0546944754772472 -0.0118016030294692 0.579684440455791 -0.0551561294565872 0.997543615320397 -0.0431802838906731 0.0472640314809743 0.00941089077423385 0.0437635680192982 0.998997590211836 0.0620096072646009 3.96496449197993e-05 -3.94628548378046e-06 -4.22630634911337e-06 -9.37642045022005e-07 1.3729363874253e-07 -2.01700303933013e-06 -3.94628548378046e-06 0.000113017106702864 -1.89035116731245e-06 -3.66697954561416e-05 -2.53261316051381e-06 -0.000126293924736333 -4.22630634911337e-06 -1.89035116731245e-06 1.29395649542471e-05 1.75798481440665e-07 4.12568180444079e-06 1.19052289785658e-06 -9.37642045022005e-07 -3.66697954561416e-05 1.75798481440665e-07 0.000227475899989588 6.04613708489627e-06 1.85910493026759e-05 1.3729363874253e-07 -2.53261316051381e-06 4.12568180444079e-06 6.04613708489627e-06 1.16198540803998e-05 3.39260161143229e-06 -2.01700303933013e-06 -0.000126293924736333 1.19052289785658e-06 1.85910493026759e-05 3.39260161143229e-06 0.000242391003654706 3277 3264 0 1067 682 3277 3264 0 948 754 0 0 0 0 0 0 0 0 2739 0 0 0 0 0 3064 +575 578 0.999299408499928 0.0171773252778317 0.0332510401039221 0.439671305944791 -0.0168429712466547 0.99980499438268 -0.010309584231867 0.0510748529794194 -0.0334216470461501 0.00974231511239312 0.999393856697635 0.0688539140038505 4.25592303995523e-05 -1.31147699997919e-05 -1.09242198806448e-06 -2.7146743489238e-05 -1.0088179764131e-06 1.71238526770363e-05 -1.31147699997919e-05 7.87796148814087e-05 2.89043881246517e-06 1.159457235835e-05 1.14370831720997e-06 -7.29943911421395e-05 -1.09242198806448e-06 2.89043881246517e-06 1.32057495659714e-05 -6.03511811080226e-07 4.10287463418667e-06 -4.24142967858169e-06 -2.7146743489238e-05 1.159457235835e-05 -6.03511811080226e-07 0.000314438352914841 3.89383701825768e-06 -3.94718565992294e-05 -1.0088179764131e-06 1.14370831720997e-06 4.10287463418667e-06 3.89383701825768e-06 1.06674200561073e-05 -5.25480329391159e-07 1.71238526770363e-05 -7.29943911421395e-05 -4.24142967858169e-06 -3.94718565992294e-05 -5.25480329391159e-07 9.8363366412076e-05 3251 3234 0 655 543 3251 3234 0 551 605 0 0 0 0 0 0 0 0 3151 0 0 0 0 0 3213 +576 578 0.999169878400124 0.0396042918778329 0.0095422304906145 0.284733958261371 -0.0394166632770031 0.999040141306652 -0.0191081844792517 0.0202296425745937 -0.0102898374130959 0.018716199476421 0.999771885543483 0.0418645417187515 5.19708116443149e-05 2.85130293331461e-06 -1.27132971715993e-06 -2.47149924361923e-05 -1.92704824785245e-06 -2.16592682436728e-06 2.85130293331461e-06 2.19673843332446e-05 4.05679307177335e-07 8.29507634777543e-06 6.88579235699835e-07 -1.34270620575096e-05 -1.27132971715993e-06 4.05679307177335e-07 1.17731271271972e-05 -5.93355048735461e-07 4.57398988357292e-06 2.07729706310147e-06 -2.47149924361923e-05 8.29507634777543e-06 -5.93355048735461e-07 0.000222131007069439 1.10497470623406e-06 2.36469633702099e-05 -1.92704824785245e-06 6.88579235699835e-07 4.57398988357292e-06 1.10497470623406e-06 1.06505525265768e-05 -1.51621827092419e-06 -2.16592682436728e-06 -1.34270620575096e-05 2.07729706310147e-06 2.36469633702099e-05 -1.51621827092419e-06 8.06174808694497e-05 3386 3369 0 472 214 3386 3369 0 378 256 0 0 0 0 0 0 0 0 3324 0 0 0 0 0 3570 +577 579 0.997616034923048 0.0639160641010325 -0.0260189087828292 0.290267501992021 -0.0653583645526649 0.996117121522507 -0.058982746568102 0.00272750689609624 0.0221479355114067 0.0605426870856316 0.997919862510529 0.0275676491973653 5.45485612845938e-05 3.31423919936203e-06 5.1617037248038e-08 -1.27767592767604e-05 -1.2885681730892e-06 4.45199365677083e-06 3.31423919936203e-06 7.09899263528321e-05 7.01643588642998e-07 -8.04325468077286e-06 -7.114465822259e-07 3.57031884129107e-05 5.1617037248038e-08 7.01643588642998e-07 1.45223767865778e-05 -9.09105994553919e-07 2.92958675042011e-06 1.7876935114086e-07 -1.27767592767604e-05 -8.04325468077286e-06 -9.09105994553919e-07 0.000200374634649804 6.66516770688005e-06 -0.000172696546635936 -1.2885681730892e-06 -7.114465822259e-07 2.92958675042011e-06 6.66516770688005e-06 1.18674996983312e-05 -1.14528389989541e-05 4.45199365677083e-06 3.57031884129107e-05 1.7876935114086e-07 -0.000172696546635936 -1.14528389989541e-05 0.000794395451762926 3327 3314 0 585 147 3327 3314 0 501 185 0 0 0 0 0 0 0 0 3226 0 0 0 0 0 3643 +577 581 0.994622052944794 0.102420586035799 -0.0153946533564882 0.570518440154786 -0.103166666926308 0.992855405839944 -0.0599565003124393 -0.0292102488283043 0.0091438849073657 0.0612222725034184 0.998082272519815 0.0551164433533988 4.762282059406e-05 -4.22415362887617e-06 -4.39131358726952e-06 -1.38670027019296e-05 -2.13500915208488e-06 3.20997750083824e-06 -4.22415362887617e-06 6.00557765198719e-05 5.56679072444262e-06 1.58622043114463e-06 -1.7975688568926e-07 1.0959031375505e-05 -4.39131358726952e-06 5.56679072444262e-06 1.26373816715932e-05 -1.80468749265335e-06 4.30771129329537e-06 -2.80486387683179e-06 -1.38670027019296e-05 1.58622043114463e-06 -1.80468749265335e-06 0.000115549678457926 1.490395294564e-06 -4.81873468913909e-05 -2.13500915208488e-06 -1.7975688568926e-07 4.30771129329537e-06 1.490395294564e-06 1.16306331230762e-05 -2.59674625128134e-06 3.20997750083824e-06 1.0959031375505e-05 -2.80486387683179e-06 -4.81873468913909e-05 -2.59674625128134e-06 0.000408158455102686 3205 3210 0 1311 451 3205 3210 0 1195 505 0 0 0 0 0 0 0 0 2484 0 0 0 0 0 3327 +577 580 0.994875506099814 0.0859334119218132 -0.0532745349873238 0.443099275052413 -0.088473109312865 0.994954905952983 -0.0472995142533623 -0.0132862510289274 0.0489411513059659 0.0517704919386147 0.997459061753053 -0.00909817268832446 4.22881318161673e-05 -5.36127771437604e-06 -4.56559880374035e-06 1.92020129834297e-06 -1.22822509723588e-07 1.21061730989505e-05 -5.36127771437604e-06 0.000153644064396087 5.72311810568641e-06 -6.02514988849643e-05 -3.22474289753708e-06 -8.166199825601e-05 -4.56559880374035e-06 5.72311810568641e-06 1.53601587460965e-05 -6.84459851664127e-06 2.15220052466359e-06 -1.27075444473832e-06 1.92020129834297e-06 -6.02514988849643e-05 -6.84459851664127e-06 0.000176574311731869 9.20804868790495e-06 3.70003961494157e-05 -1.22822509723588e-07 -3.22474289753708e-06 2.15220052466359e-06 9.20804868790495e-06 1.27938471261169e-05 -7.51282023173916e-07 1.21061730989505e-05 -8.166199825601e-05 -1.27075444473832e-06 3.70003961494157e-05 -7.51282023173916e-07 0.000358220870249168 3242 3240 0 952 289 3242 3240 0 845 340 0 0 0 0 0 0 0 0 2851 0 0 0 0 0 3478 +577 607 0.820642772664648 -0.55741962709091 -0.125812555045633 0.934912938384742 0.548273169816563 0.830106223609968 -0.10158832995623 0.296941767628814 0.161065113952642 0.0143880804080616 0.986838898812564 0.398463945438173 7.91224359049407e-05 -5.70076610332639e-05 -1.02566122592608e-06 1.62465975953865e-05 -1.13020710459191e-05 8.44608334739736e-05 -5.70076610332639e-05 0.000914872072063719 -3.04959134535054e-05 -0.000171084476805378 8.70622991278534e-05 -0.000642387648412732 -1.02566122592608e-06 -3.04959134535054e-05 2.26163337221005e-05 5.32209785277578e-06 -1.85424638543928e-06 2.77388346864398e-05 1.62465975953865e-05 -0.000171084476805378 5.32209785277578e-06 9.14429769137185e-05 -3.17905796509359e-05 0.000114898537002179 -1.13020710459191e-05 8.70622991278534e-05 -1.85424638543928e-06 -3.17905796509359e-05 3.92944291251232e-05 -5.12144221561365e-05 8.44608334739736e-05 -0.000642387648412732 2.77388346864398e-05 0.000114898537002179 -5.12144221561365e-05 0.000680660266219315 1495 1472 0 0 2931 1495 1472 0 0 2988 0 0 0 0 0 0 0 0 955 0 0 0 0 0 674 +579 583 0.992517145603944 0.0700498705968822 0.100013655625413 0.539206532487891 -0.0703740653322131 0.99752063058397 -0.000287207200598456 -0.0213463947652485 -0.0997858036537061 -0.00675330946416138 0.994986023118147 0.0662357719540137 5.02652567550175e-05 -2.21960539568306e-05 -1.18659065804379e-06 -5.1025602127385e-06 1.91957680145777e-06 2.72726443355173e-05 -2.21960539568306e-05 0.000233316027313761 1.04693976151224e-05 4.21675635303597e-05 1.16489758720097e-06 -0.000218402737871382 -1.18659065804379e-06 1.04693976151224e-05 1.14215701341869e-05 -1.28291139412766e-06 4.01508636524603e-06 -8.31918368911694e-06 -5.1025602127385e-06 4.21675635303597e-05 -1.28291139412766e-06 8.67394182723123e-05 3.29538600970801e-06 -3.3361161439911e-05 1.91957680145777e-06 1.16489758720097e-06 4.01508636524603e-06 3.29538600970801e-06 1.15719780094481e-05 -1.34928152374786e-06 2.72726443355173e-05 -0.000218402737871382 -8.31918368911694e-06 -3.3361161439911e-05 -1.34928152374786e-06 0.000288423599586368 3032 3088 0 1011 534 3032 3088 0 917 603 0 0 0 0 0 0 0 0 2728 0 0 0 0 0 3213 +579 581 0.99905915412478 0.0392678484441491 -0.0184076787794353 0.288690242463505 -0.0392065815712661 0.999224358724276 0.00367762063781871 -0.012196705240238 0.0185378132738246 -0.0029524584040074 0.999823800711104 -0.000592150240297544 5.17265859675759e-05 -4.48702016603042e-05 -5.35466090815025e-06 2.06685454405125e-05 2.57049295962579e-06 4.74237739644956e-05 -4.48702016603042e-05 0.000807680765101021 5.7295526115288e-06 -6.11601504457208e-05 2.89197807569797e-06 -0.000949856989631175 -5.35466090815025e-06 5.7295526115288e-06 1.18536227822553e-05 -4.04803825437364e-06 5.12847176698724e-06 -6.83889614738602e-06 2.06685454405125e-05 -6.11601504457208e-05 -4.04803825437364e-06 0.000118514665846622 5.57289532490402e-06 4.52013418150628e-05 2.57049295962579e-06 2.89197807569797e-06 5.12847176698724e-06 5.57289532490402e-06 1.19127176210304e-05 -7.18227182805024e-06 4.74237739644956e-05 -0.000949856989631175 -6.83889614738602e-06 4.52013418150628e-05 -7.18227182805024e-06 0.00127883212002266 3115 3120 0 505 200 3115 3120 0 432 246 0 0 0 0 0 0 0 0 3301 0 0 0 0 0 3588 +579 582 0.996840073785472 0.0439880213268251 0.0661431876698291 0.424547967992958 -0.0439803775501927 0.999031157705633 -0.00157236251736471 -0.0126388916702077 -0.0661482704680776 -0.00134160839826499 0.997808902746908 0.0197029061207712 5.08913980976571e-05 -4.19936838205793e-05 7.46552805998519e-07 1.30120065729879e-05 2.22430958445777e-06 4.68427576877614e-05 -4.19936838205793e-05 0.000253163963778255 -4.53884169425265e-06 -4.60831621383589e-05 -7.55691627278884e-06 -0.000191355402076828 7.46552805998519e-07 -4.53884169425265e-06 1.23367154195598e-05 -2.57963790324777e-06 4.39910831546455e-06 3.50000225654841e-06 1.30120065729879e-05 -4.60831621383589e-05 -2.57963790324777e-06 0.000107764824368312 4.80860143175595e-06 6.57879070935427e-06 2.22430958445777e-06 -7.55691627278884e-06 4.39910831546455e-06 4.80860143175595e-06 1.11897942357068e-05 4.4833871358365e-06 4.68427576877614e-05 -0.000191355402076828 3.50000225654841e-06 6.57879070935427e-06 4.4833871358365e-06 0.000297428769643235 3065 3073 0 759 400 3065 3073 0 674 466 0 0 0 0 0 0 0 0 3039 0 0 0 0 0 3364 +580 611 0.55912027371469 -0.824438347643626 -0.087669438551058 0.512813091847345 0.82327323234737 0.564587280752887 -0.0588420539442061 0.544089980470972 0.0980086956423926 -0.0392761167467896 0.99441021828608 0.702066805113101 0.000256502672410021 -7.33646373634458e-05 2.72710671743795e-05 8.49152057107024e-05 -7.09114283247241e-05 -0.000200355163564013 -7.33646373634458e-05 0.000104674561275074 -1.49164576878746e-05 -4.88010578220155e-05 5.26906997981859e-05 5.11158946409593e-05 2.72710671743795e-05 -1.49164576878746e-05 3.05283864931443e-05 5.86426227767006e-06 -7.94495534982863e-06 -1.14801192437141e-05 8.49152057107024e-05 -4.88010578220155e-05 5.86426227767006e-06 0.000105703726086985 -7.34364263264553e-05 -0.000180847169282357 -7.09114283247241e-05 5.26906997981859e-05 -7.94495534982863e-06 -7.34364263264553e-05 0.000120991655222701 0.000193756005563472 -0.000200355163564013 5.11158946409593e-05 -1.14801192437141e-05 -0.000180847169282357 0.000193756005563472 0.000704919160532472 643 611 0 0 1725 643 611 0 0 1756 0 0 0 0 0 0 0 0 165 0 0 0 0 0 61 +580 609 0.66570524159179 -0.741228320371513 -0.0861226357959521 0.476497684821342 0.740260424084775 0.670531086025238 -0.0490159893059839 0.47320873185401 0.0940799439362383 -0.0311229778948095 0.995078049399098 0.492855519503932 0.000143033249969355 -4.2725397580136e-05 2.00849365603227e-05 3.54815976296071e-05 -3.53053275729509e-05 -0.000155175968897581 -4.2725397580136e-05 8.01083779152741e-05 -1.2696229096778e-05 -1.78383960256231e-05 1.83486712695913e-05 3.0340376024575e-05 2.00849365603227e-05 -1.2696229096778e-05 2.50787571026795e-05 7.26815748758882e-06 -6.48889825322605e-06 -1.90399750258017e-05 3.54815976296071e-05 -1.78383960256231e-05 7.26815748758882e-06 5.49804812796159e-05 -2.55800371757606e-05 -9.76894692000854e-05 -3.53053275729509e-05 1.83486712695913e-05 -6.48889825322605e-06 -2.55800371757606e-05 5.36006245901e-05 9.24416922626383e-05 -0.000155175968897581 3.0340376024575e-05 -1.90399750258017e-05 -9.76894692000854e-05 9.24416922626383e-05 0.000653568024488825 1207 1200 0 0 2165 1133 1126 0 0 2212 0 0 0 0 0 0 0 0 455 0 0 0 0 0 439 +580 584 0.991132499745865 0.093508849597452 0.094405841950987 0.500203153813722 -0.0929241850501502 0.995616973782396 -0.0105800448557433 -0.016111124570347 -0.0949813864937708 0.00171364037802746 0.995477573658179 0.045812653200304 6.58425799705276e-05 -9.260553870459e-05 -4.06173416255755e-06 -2.96370268045968e-05 -3.22951953797016e-06 0.000104726621828551 -9.260553870459e-05 0.000841625337896047 1.3326244703408e-05 0.000139242195502583 2.88453245607476e-05 -0.000431882227214436 -4.06173416255755e-06 1.3326244703408e-05 1.38384095384003e-05 1.77975690466202e-06 4.56159105796507e-06 -9.81385098584051e-06 -2.96370268045968e-05 0.000139242195502583 1.77975690466202e-06 9.05820881836893e-05 3.1204997049455e-06 -0.000188338458352003 -3.22951953797016e-06 2.88453245607476e-05 4.56159105796507e-06 3.1204997049455e-06 1.31367190794594e-05 -2.67255210241401e-05 0.000104726621828551 -0.000431882227214436 -9.81385098584051e-06 -0.000188338458352003 -2.67255210241401e-05 0.000927627623148316 3100 3138 0 702 441 3100 3138 0 615 512 0 0 0 0 0 0 0 0 2795 0 0 0 0 0 3325 +580 583 0.989171982491666 0.0471106327687111 0.138994162948084 0.3972787344314 -0.0462671041458233 0.998885853631889 -0.00929550902596264 -0.00376695221620761 -0.139277220418367 0.00276399967870011 0.990249572672622 0.0212678566266527 4.88441585714123e-05 -6.76894090463177e-06 -6.57479527161704e-06 -1.70236122073805e-05 2.38795356984951e-06 1.41069045803277e-05 -6.76894090463177e-06 6.02988733491722e-05 -2.06440900078573e-06 -1.49313241610314e-05 -8.35560942226114e-07 -3.93702497457365e-06 -6.57479527161704e-06 -2.06440900078573e-06 1.56736133682635e-05 1.03499664659489e-06 3.3681507684472e-06 1.46205945632239e-06 -1.70236122073805e-05 -1.49313241610314e-05 1.03499664659489e-06 0.000128029868829599 4.31383281120608e-06 -9.19400867643522e-05 2.38795356984951e-06 -8.35560942226114e-07 3.3681507684472e-06 4.31383281120608e-06 1.20426314344751e-05 -1.0968302302695e-05 1.41069045803277e-05 -3.93702497457365e-06 1.46205945632239e-06 -9.19400867643522e-05 -1.0968302302695e-05 0.000361209461200724 3062 3118 0 634 378 3062 3118 0 561 443 0 0 0 0 0 0 0 0 3117 0 0 0 0 0 3378 +581 584 0.991744011896787 0.0767239013519624 0.102748517401468 0.363785466708682 -0.0772283327430363 0.997012994643367 0.000934416393195581 -0.00805780343091725 -0.102369914958431 -0.00886179855330417 0.994706926203796 0.0526004469091661 6.92624483546297e-05 -3.08865432023719e-05 1.67285942349992e-06 -1.17701433708905e-05 -6.58634786455063e-07 3.1290303392438e-05 -3.08865432023719e-05 0.000204196835573574 6.17873805658112e-06 1.71040460617442e-05 4.56773287945238e-06 -0.000139718811014582 1.67285942349992e-06 6.17873805658112e-06 1.55357164394306e-05 3.29260643049688e-06 4.31679923324778e-06 -4.75870490937408e-06 -1.17701433708905e-05 1.71040460617442e-05 3.29260643049688e-06 9.64369126803173e-05 3.93700752692355e-06 -4.2314903042054e-05 -6.58634786455063e-07 4.56773287945238e-06 4.31679923324778e-06 3.93700752692355e-06 1.24715070572033e-05 -8.40540962704247e-06 3.1290303392438e-05 -0.000139718811014582 -4.75870490937408e-06 -4.2314903042054e-05 -8.40540962704247e-06 0.000195063126535779 3061 3107 0 407 247 3061 3107 0 343 324 0 0 0 0 0 0 0 0 3124 0 0 0 0 0 3476 +581 583 0.996941146833149 0.0315533998348866 0.0715033755137836 0.260236138972589 -0.0314615230726219 0.999502055630162 -0.00241109042354457 0.000961626288593356 -0.0715438489106943 0.0001541101534697 0.997437443618949 0.0592622640162453 8.21870651270089e-05 -0.000116926822435729 -9.09569864116878e-06 -2.43307917043797e-05 -2.75331938742441e-06 0.000110248190717931 -0.000116926822435729 0.000871168673503318 9.04578007416868e-06 1.57259966776528e-06 2.66048825975041e-06 -0.000564420966152466 -9.09569864116878e-06 9.04578007416868e-06 1.31258808236566e-05 -1.48201034013798e-06 4.43656624488208e-06 -1.09860584709245e-05 -2.43307917043797e-05 1.57259966776528e-06 -1.48201034013798e-06 0.000107730172876808 4.74933730912824e-06 -8.87918825928659e-05 -2.75331938742441e-06 2.66048825975041e-06 4.43656624488208e-06 4.74933730912824e-06 1.19546389279426e-05 -6.3785132347554e-06 0.000110248190717931 -0.000564420966152466 -1.09860584709245e-05 -8.87918825928659e-05 -6.3785132347554e-06 0.000910009319251289 3100 3156 0 347 200 3100 3156 0 285 267 0 0 0 0 0 0 0 0 3422 0 0 0 0 0 3547 +582 609 0.643439110368997 -0.751512079051648 -0.145656123410668 0.132383357535768 0.755755817787412 0.653904221352171 -0.035247881897951 0.480557260663417 0.121734362971325 -0.0874005968931646 0.988707176334168 0.44454472585564 0.000171930067744487 -9.80724309834065e-05 1.1073275133155e-05 7.4413793215936e-05 -4.7853716694952e-05 -0.000149835071154929 -9.80724309834065e-05 0.000218995358979597 -1.43608762489434e-05 -3.91056478173351e-06 -1.74032283755722e-05 -0.000101256523445097 1.1073275133155e-05 -1.43608762489434e-05 2.03019299439457e-05 6.70953907930611e-06 -2.86905610066851e-06 5.37952925701835e-06 7.4413793215936e-05 -3.91056478173351e-06 6.70953907930611e-06 0.000150337046422881 -0.00010420862319651 -0.000273550626413994 -4.7853716694952e-05 -1.74032283755722e-05 -2.86905610066851e-06 -0.00010420862319651 0.000121033702219632 0.000233517352016086 -0.000149835071154929 -0.000101256523445097 5.37952925701835e-06 -0.000273550626413994 0.000233517352016086 0.00101440938095176 691 688 0 0 1853 680 677 0 0 1895 0 0 0 0 0 375 375 0 356 0 0 0 0 0 740 +583 587 0.936046096094581 0.34539180445893 0.0672473597898 0.364596218087677 -0.345153819874702 0.938418197225803 -0.0154960556715665 -0.060617151551115 -0.0684583567725375 -0.00870566069170383 0.997615990679743 0.0723833059820698 6.07537623021601e-05 -9.45713209481967e-06 -1.49744346301062e-05 -1.17809438744974e-06 7.03280791915898e-06 1.45402812889773e-05 -9.45713209481967e-06 2.70916950301892e-05 9.30072898707191e-07 -4.12440681366146e-07 -1.66237096721469e-06 -3.79397115021608e-06 -1.49744346301062e-05 9.30072898707191e-07 1.81897754787332e-05 1.11983786642579e-06 9.74434819566072e-07 3.62755429298332e-07 -1.17809438744974e-06 -4.12440681366146e-07 1.11983786642579e-06 0.000129816490396542 4.95623579354691e-05 -5.64392002739668e-05 7.03280791915898e-06 -1.66237096721469e-06 9.74434819566072e-07 4.95623579354691e-05 4.40943248516998e-05 -2.62421513491466e-05 1.45402812889773e-05 -3.79397115021608e-06 3.62755429298332e-07 -5.64392002739668e-05 -2.62421513491466e-05 0.000164586623871641 3048 3074 0 1056 0 3138 3164 0 1070 0 0 0 0 0 0 0 0 0 2407 0 209 320 0 0 3390 +584 587 0.949823512474355 0.302712668714128 0.0787422081913478 0.248007375837778 -0.303002841158789 0.952951521866885 -0.00852497632189058 -0.0454676562965005 -0.0776181254642283 -0.0157618898472764 0.996858560392527 0.0331193821697106 6.80341270147797e-05 -1.90571928144432e-05 -1.76964514186345e-06 -3.57939477094672e-05 -1.65000054277114e-05 4.61206536377126e-05 -1.90571928144432e-05 4.18612610842703e-05 1.51266797853185e-06 -8.79460852043899e-06 -5.39130327440031e-06 1.05972021240514e-05 -1.76964514186345e-06 1.51266797853185e-06 1.50815281613419e-05 -6.69241923958976e-06 2.24447091897587e-06 2.21222935437977e-07 -3.57939477094672e-05 -8.79460852043899e-06 -6.69241923958976e-06 8.84496971637919e-05 2.67175221120515e-05 -0.00013498535785772 -1.65000054277114e-05 -5.39130327440031e-06 2.24447091897587e-06 2.67175221120515e-05 2.67949372279309e-05 -5.92639115465503e-05 4.61206536377126e-05 1.05972021240514e-05 2.21222935437977e-07 -0.00013498535785772 -5.92639115465503e-05 0.00034562893866702 3034 3057 0 1004 0 3117 3140 0 987 0 0 0 0 0 0 0 0 0 2485 0 279 390 0 0 3441 +585 588 0.928060962952078 0.366644947626206 0.0653783712296252 0.174983365879414 -0.364577059827968 0.930243734103489 -0.0415952233843113 -0.0608240221516145 -0.0760684986814918 0.0147674487090125 0.996993232658562 0.0512128057627387 6.40398639808767e-05 -3.97884530989522e-05 -1.94481511146971e-06 5.66588630374716e-06 3.88161496130099e-06 -2.37679395568052e-05 -3.97884530989522e-05 8.23511097142927e-05 -1.15667011243918e-06 -2.18905348635495e-05 -5.58825078187811e-06 0.000178955653424735 -1.94481511146971e-06 -1.15667011243918e-06 1.39994524118562e-05 -3.26010567743142e-06 2.26200590510545e-06 -6.41670141632555e-06 5.66588630374716e-06 -2.18905348635495e-05 -3.26010567743142e-06 5.25937805562805e-05 1.38539325447059e-05 -0.000145308293228952 3.88161496130099e-06 -5.58825078187811e-06 2.26200590510545e-06 1.38539325447059e-05 2.63075841146227e-05 -3.74997406619079e-05 -2.37679395568052e-05 0.000178955653424735 -6.41670141632555e-06 -0.000145308293228952 -3.74997406619079e-05 0.00111752259698512 2701 2730 0 1021 0 2794 2823 0 1003 0 0 0 0 0 0 0 0 0 2414 0 578 708 0 0 3151 +586 590 0.862723008340432 0.503766838378085 -0.043908808120725 0.114949544656936 -0.505383561178579 0.856009513545574 -0.108789562044924 -0.113928423722869 -0.0172182162401202 0.116046048058594 0.993094581477258 0.0151454000813846 4.77695897602992e-05 -1.94887270606327e-05 -4.91578839941526e-06 1.41699995854834e-06 3.91762444313468e-06 8.5822482674209e-06 -1.94887270606327e-05 4.27193421227425e-05 -3.31819924932815e-06 -3.45028100022971e-06 -2.69191141008768e-06 -1.03971266060146e-05 -4.91578839941526e-06 -3.31819924932815e-06 1.3081213341022e-05 -4.12690160185148e-06 -2.84600914346339e-07 1.75189656277131e-06 1.41699995854834e-06 -3.45028100022971e-06 -4.12690160185148e-06 3.13968543609551e-05 1.79281834924544e-05 1.05398740391659e-05 3.91762444313468e-06 -2.69191141008768e-06 -2.84600914346339e-07 1.79281834924544e-05 5.22785307056694e-05 2.2729039003295e-05 8.5822482674209e-06 -1.03971266060146e-05 1.75189656277131e-06 1.05398740391659e-05 2.2729039003295e-05 0.000160671285250682 2546 2593 0 904 0 2661 2708 0 906 0 0 0 0 0 0 0 0 0 1940 0 1181 1334 0 0 2669 +599 601 0.967741719298931 -0.248793493987223 -0.0397210533341981 -0.0796781292204489 0.249674393941524 0.968144641784424 0.0189380462044791 0.0746372139590094 0.0337440622670334 -0.02824446731202 0.99903132499836 -0.00259573895147746 0.00116417659324659 -0.00187657853862392 0.000108127240061919 -0.000534953296410692 -8.90714460674688e-05 0.000731496884984084 -0.00187657853862392 0.00339014690169015 -0.000194047682903635 0.0010838401038012 0.000194402527170087 -0.00124829523669676 0.000108127240061919 -0.000194047682903635 2.90075936268799e-05 -5.84568786580242e-05 -4.37384177529852e-06 8.09169062982589e-05 -0.000534953296410692 0.0010838401038012 -5.84568786580242e-05 0.000574279586478882 0.000105689520176931 -0.00028359892801642 -8.90714460674688e-05 0.000194402527170087 -4.37384177529852e-06 0.000105689520176931 3.45306268668113e-05 -3.6090704153073e-05 0.000731496884984084 -0.00124829523669676 8.09169062982589e-05 -0.00028359892801642 -3.6090704153073e-05 0.00102314880679855 2440 2516 0 0 490 2460 2536 0 0 599 0 0 0 0 0 712 689 0 2868 0 0 0 0 0 3208 +600 602 0.972031330092181 -0.23465487897759 -0.00960109843912066 -0.0592301415735497 0.234850844639202 0.971289807614407 0.0379630135345118 0.107092290062263 0.000417242709255028 -0.0391560646181506 0.999233020127008 0.0243539082600894 5.60104213754588e-05 -1.43592292513874e-05 -8.55225921706026e-06 2.26583758628076e-05 1.68103863434466e-06 2.83307556566664e-05 -1.43592292513874e-05 3.32517656686345e-05 3.24476542518591e-06 1.41819617603724e-05 1.81801141242861e-06 1.07371099444215e-05 -8.55225921706026e-06 3.24476542518591e-06 1.54697656566305e-05 -5.02691026879638e-07 4.22211563977584e-06 -3.69437598288055e-07 2.26583758628076e-05 1.41819617603724e-05 -5.02691026879638e-07 0.000204464758288273 1.1288004286528e-05 5.21115596764975e-05 1.68103863434466e-06 1.81801141242861e-06 4.22211563977584e-06 1.1288004286528e-05 1.40199464339732e-05 3.49024657755189e-06 2.83307556566664e-05 1.07371099444215e-05 -3.69437598288055e-07 5.21115596764975e-05 3.49024657755189e-06 0.000255164198024293 2791 2844 0 0 575 2798 2851 0 0 669 0 0 0 0 0 633 642 0 3197 0 0 0 0 0 3203 +601 604 0.926198572664027 -0.374569232562471 -0.0430591919650116 -0.0925109571555642 0.376944627353906 0.922430728683736 0.0838707260551438 0.1943695731836 0.00830372832788605 -0.0939118778299815 0.995545884074814 0.0949680332546439 7.19148469078663e-05 -5.79088917707956e-05 -1.04051003655723e-06 -1.15222355190055e-06 -8.56020791076263e-07 3.54428766514657e-05 -5.79088917707956e-05 0.000141714137542685 9.50686690086338e-06 2.17322641018673e-05 -2.9086601338541e-06 -5.48371585135521e-05 -1.04051003655723e-06 9.50686690086338e-06 1.5126945632245e-05 1.37264349544491e-06 4.32430025628479e-06 -5.70250276058623e-06 -1.15222355190055e-06 2.17322641018673e-05 1.37264349544491e-06 8.67250866870788e-05 -4.91884654191051e-06 9.44576080379021e-06 -8.56020791076263e-07 -2.9086601338541e-06 4.32430025628479e-06 -4.91884654191051e-06 1.3233542725545e-05 -8.30615441560906e-06 3.54428766514657e-05 -5.48371585135521e-05 -5.70250276058623e-06 9.44576080379021e-06 -8.30615441560906e-06 0.000159038208903991 2153 2157 0 0 1075 2134 2138 0 0 1139 0 0 0 0 0 997 891 0 2892 0 0 0 0 0 2774 +602 604 0.963637315521661 -0.263124890710828 -0.0465662541184319 -0.0611874488992316 0.265908779362058 0.961459494034594 0.0699153945059516 0.140055788963361 0.0263750865854109 -0.0797554588674487 0.996465464323001 0.0826535303284033 6.03035777062117e-05 -1.85444403555608e-05 4.48763650866785e-08 3.58396995291683e-06 -2.74062005626981e-06 2.82305376804675e-05 -1.85444403555608e-05 4.76161019984912e-05 2.46283886919457e-06 2.28498042397877e-07 3.6417445910418e-07 -2.26364728731855e-05 4.48763650866785e-08 2.46283886919457e-06 1.36528759970042e-05 -2.17095055908789e-06 4.2885192525709e-06 2.43703877982044e-07 3.58396995291683e-06 2.28498042397877e-07 -2.17095055908789e-06 0.000115585108197386 -9.16761364662056e-06 -3.31044207278015e-05 -2.74062005626981e-06 3.6417445910418e-07 4.2885192525709e-06 -9.16761364662056e-06 1.33238617574037e-05 -2.43107216087139e-06 2.82305376804675e-05 -2.26364728731855e-05 2.43703877982044e-07 -3.31044207278015e-05 -2.43107216087139e-06 0.000150615375226208 2440 2444 0 0 737 2467 2471 0 0 787 0 0 0 0 0 749 643 0 3137 0 0 0 0 0 3148 +606 608 0.980912646193858 -0.19381739691782 -0.0156587735459532 -0.0102389959403807 0.193097436082294 0.980409328520703 -0.0388706666784772 0.142872028137601 0.0228858190897284 0.0351050594869877 0.999121551205361 0.130541438624765 5.7549591537299e-05 -7.52447089094365e-06 3.39941635463469e-06 -3.10055441773415e-06 -8.93833323117516e-08 -1.31450785891932e-05 -7.52447089094365e-06 4.88557419550158e-05 -7.84876767609278e-06 -7.59118774928377e-07 5.19673562326727e-06 4.36524660375876e-05 3.39941635463469e-06 -7.84876767609278e-06 1.47765197503441e-05 3.66080352307453e-06 2.49839665394765e-06 -7.09774897710179e-06 -3.10055441773415e-06 -7.59118774928377e-07 3.66080352307453e-06 3.00396888244714e-05 -7.13094902447267e-06 -2.07980144825833e-05 -8.93833323117516e-08 5.19673562326727e-06 2.49839665394765e-06 -7.13094902447267e-06 2.483641600798e-05 2.98416145391914e-05 -1.31450785891932e-05 4.36524660375876e-05 -7.09774897710179e-06 -2.07980144825833e-05 2.98416145391914e-05 0.000261868163532043 1975 1933 0 0 415 1975 1933 0 0 379 0 0 0 0 0 0 0 0 1227 0 0 0 0 0 3379 +606 711 0.960658380887321 -0.276856898708931 -0.0220393481805443 0.577281742154045 0.2767711471597 0.960911008663919 -0.00691126098426477 0.0776627928268462 0.0230912825727338 0.000539505108452196 0.999733215214631 -0.0172824270122113 7.56001573017623e-05 4.30844741107214e-05 -1.99447916746872e-07 3.0453081660697e-05 -2.71182813066222e-05 -6.36618243214455e-06 4.30844741107214e-05 4.8622927380751e-05 -1.25968855954083e-06 2.23737901219165e-06 -2.86324563762008e-06 -1.83910942641892e-05 -1.99447916746872e-07 -1.25968855954083e-06 1.50078542338613e-05 6.54115165418133e-06 6.66231301101435e-06 1.90660551632678e-06 3.0453081660697e-05 2.23737901219165e-06 6.54115165418133e-06 0.000146867913124596 -0.000116443310391595 5.28721759399983e-05 -2.71182813066222e-05 -2.86324563762008e-06 6.66231301101435e-06 -0.000116443310391595 0.000132522168266568 -5.00241383962084e-05 -6.36618243214455e-06 -1.83910942641892e-05 1.90660551632678e-06 5.28721759399983e-05 -5.00241383962084e-05 0.000169896827612809 880 870 0 0 572 880 870 0 0 516 0 0 0 0 0 0 0 0 741 0 0 0 0 0 2898 +607 609 0.988058103010182 -0.152665011185179 0.0208465689203061 0.0331559971770369 0.153064712656928 0.98803069461162 -0.0191452407801777 0.110515792428898 -0.0176742415727503 0.0221074843686051 0.999599359903617 0.174940631319867 3.48472837835128e-05 6.46549915929475e-06 -2.8133361177345e-07 -1.68523509865621e-06 1.53188482776953e-06 -4.38973051164228e-06 6.46549915929475e-06 4.17839018859502e-05 -6.49462886795825e-06 -1.10631295275374e-05 1.10271773974909e-05 1.43000555595184e-05 -2.8133361177345e-07 -6.49462886795825e-06 1.66767349484291e-05 3.81081887673742e-06 1.90427611622134e-06 -2.36654197491016e-06 -1.68523509865621e-06 -1.10631295275374e-05 3.81081887673742e-06 3.87176966423062e-05 -1.71719948425346e-05 -1.73150950409513e-05 1.53188482776953e-06 1.10271773974909e-05 1.90427611622134e-06 -1.71719948425346e-05 3.97758338932654e-05 2.90351649361314e-05 -4.38973051164228e-06 1.43000555595184e-05 -2.36654197491016e-06 -1.73150950409513e-05 2.90351649361314e-05 0.000150192775327737 1750 1734 0 0 222 1750 1734 0 0 186 0 0 0 0 0 0 0 0 1211 0 0 0 0 0 3421 +608 611 0.978169383992677 -0.206470026181669 -0.0235538639702163 0.107382328569946 0.206319596052457 0.97844621139472 -0.00867385105184955 0.0704261878662397 0.024837079219136 0.00362487184042236 0.999684940268684 0.244766099542661 5.40896341211556e-05 3.64112537362434e-05 -1.72011412916263e-06 1.10334233080165e-05 -3.39783935687969e-06 4.45374367278082e-05 3.64112537362434e-05 6.12687365519512e-05 -5.31527825620804e-06 1.25243882292462e-05 -7.21760562928889e-06 6.92089638949726e-05 -1.72011412916263e-06 -5.31527825620804e-06 1.54738374855413e-05 4.9286997645725e-07 4.65935356982703e-06 -1.00698691904624e-05 1.10334233080165e-05 1.25243882292462e-05 4.9286997645725e-07 3.82872246317855e-05 -1.87237579257933e-05 6.14522187446575e-05 -3.39783935687969e-06 -7.21760562928889e-06 4.65935356982703e-06 -1.87237579257933e-05 4.19924458985323e-05 -3.94177858244712e-05 4.45374367278082e-05 6.92089638949726e-05 -1.00698691904624e-05 6.14522187446575e-05 -3.94177858244712e-05 0.000381105485253374 1258 1222 0 0 259 1258 1222 0 0 241 0 0 0 0 0 0 0 0 1090 0 0 0 0 0 2797 +608 610 0.989606806145147 -0.14231376762586 -0.0206194271339987 0.061008335694711 0.142486322550379 0.989770955772971 0.00714863583694264 0.0665685560528207 0.0193911608025685 -0.0100123250243105 0.999761839755017 0.167497932459157 4.1216185742669e-05 8.21570644690403e-06 4.24188809208252e-06 -5.22134848448867e-06 3.54954203196347e-06 -1.14577361059113e-05 8.21570644690403e-06 3.80423726172044e-05 -1.39959436278172e-06 -2.2713599082682e-06 4.56920656217064e-06 6.40750628402707e-06 4.24188809208252e-06 -1.39959436278172e-06 1.67196944642505e-05 3.91607868380761e-06 1.72776054565921e-06 -7.78342231242308e-07 -5.22134848448867e-06 -2.2713599082682e-06 3.91607868380761e-06 2.61591650776764e-05 -5.6261624903642e-06 1.20614073066634e-05 3.54954203196347e-06 4.56920656217064e-06 1.72776054565921e-06 -5.6261624903642e-06 2.84341034439407e-05 -3.45252211198554e-06 -1.14577361059113e-05 6.40750628402707e-06 -7.78342231242308e-07 1.20614073066634e-05 -3.45252211198554e-06 0.000156219236210795 1517 1488 0 0 196 1517 1488 0 0 176 0 0 0 0 0 0 0 0 1324 0 0 0 0 0 3330 +609 611 0.990475386365224 -0.135576381325562 -0.024032349683841 0.0709008384976552 0.135619420914103 0.990760993492671 0.000162617152303537 0.0322287104756138 0.0237882676036748 -0.00342032163408519 0.999711168150249 0.163164286665966 4.56919302286701e-05 1.88262178850367e-05 1.86774034711995e-06 6.00768038128204e-06 -1.39444485210482e-07 2.17667852175885e-05 1.88262178850367e-05 4.28898664050412e-05 -1.25964500046445e-06 5.59165460504151e-06 -5.23447798761456e-06 2.31546055321583e-05 1.86774034711995e-06 -1.25964500046445e-06 1.53163142731538e-05 3.35117617295264e-06 2.43500343965014e-06 -4.51031202787736e-06 6.00768038128204e-06 5.59165460504151e-06 3.35117617295264e-06 2.85497042224311e-05 -7.67764377552633e-06 3.43593591532519e-05 -1.39444485210482e-07 -5.23447798761456e-06 2.43500343965014e-06 -7.67764377552633e-06 3.30488499952374e-05 -1.64690522177762e-05 2.17667852175885e-05 2.31546055321583e-05 -4.51031202787736e-06 3.43593591532519e-05 -1.64690522177762e-05 0.000230759951060726 1256 1220 0 0 190 1256 1220 0 0 174 0 0 0 0 0 0 0 0 1354 0 0 0 0 0 2919 +611 613 0.993599368643402 -0.0994884343562166 0.0535008977567801 0.0351370897097341 0.0982978570024277 0.994856662068552 0.024448992751238 0.000195296242502272 -0.0556581165703882 -0.0190334801643997 0.998268451215738 0.105536312414006 7.28269756193422e-05 5.10281901963987e-05 1.02937627795133e-07 1.28221795135356e-06 9.52488203938097e-06 4.67811953476885e-05 5.10281901963987e-05 6.9167162543007e-05 -3.58163197266405e-06 -2.41285999730613e-06 1.11877719423215e-05 1.47262489162781e-05 1.02937627795133e-07 -3.58163197266405e-06 1.85151663935432e-05 2.60491837294872e-07 3.91785530540123e-06 -4.96019625629061e-06 1.28221795135356e-06 -2.41285999730613e-06 2.60491837294872e-07 2.70205372435311e-05 -9.72685540841022e-06 4.09952055038148e-06 9.52488203938097e-06 1.11877719423215e-05 3.91785530540123e-06 -9.72685540841022e-06 4.47374409188109e-05 -1.68164087635069e-05 4.67811953476885e-05 1.47262489162781e-05 -4.96019625629061e-06 4.09952055038148e-06 -1.68164087635069e-05 0.000194444900855506 929 928 0 0 208 929 928 0 0 179 0 0 0 0 0 0 0 0 1432 0 0 0 0 0 3084 +611 614 0.990340936362392 -0.122076924120302 0.0657423331057395 0.047752483434353 0.119717940509438 0.992052823256069 0.0387144751978101 0.0073685503427099 -0.0699460112160702 -0.0304699928944733 0.997085319843779 0.158278111849448 7.47481938869593e-05 4.34094874450242e-05 -6.83744711482816e-06 -3.5962841282649e-06 1.59828369952728e-05 5.05243514723376e-05 4.34094874450242e-05 8.21455238764238e-05 -1.04019504780394e-05 1.10079749676919e-06 1.11538368494177e-05 3.49055031847783e-05 -6.83744711482816e-06 -1.04019504780394e-05 2.34014650821015e-05 2.61920127675259e-06 9.29143726977005e-07 -5.66558169669225e-06 -3.5962841282649e-06 1.10079749676919e-06 2.61920127675259e-06 2.53059645218306e-05 -8.20456169339672e-06 3.83637601021606e-06 1.59828369952728e-05 1.11538368494177e-05 9.29143726977005e-07 -8.20456169339672e-06 4.97524021134501e-05 1.18903951747748e-05 5.05243514723376e-05 3.49055031847783e-05 -5.66558169669225e-06 3.83637601021606e-06 1.18903951747748e-05 0.000264535105619755 822 846 0 0 240 822 846 0 0 215 0 0 0 0 0 0 0 0 1443 0 0 0 0 0 2591 +612 614 0.996477519424493 -0.068236364811154 0.0487478389158731 0.0307391476515084 0.0659148690722815 0.996682477834708 0.0477416842230297 -0.00558857405170062 -0.0518438358611012 -0.0443603076480156 0.997669474219083 0.110556735301557 4.04395376194353e-05 1.32767758827841e-05 -1.68765265544048e-06 2.87909833412638e-06 -3.29089850217354e-06 -3.49596016226605e-06 1.32767758827841e-05 4.96092902467873e-05 -8.58757704869529e-06 -1.74246870946436e-06 6.24374229819966e-06 -7.61726790581842e-06 -1.68765265544048e-06 -8.58757704869529e-06 1.95538046817638e-05 -9.85157804748541e-08 5.62218696681339e-06 -2.55026490957201e-07 2.87909833412638e-06 -1.74246870946436e-06 -9.85157804748541e-08 2.38520330039972e-05 -4.68668216283457e-06 4.60144518642285e-06 -3.29089850217354e-06 6.24374229819966e-06 5.62218696681339e-06 -4.68668216283457e-06 3.87105501223258e-05 2.54040928360491e-06 -3.49596016226605e-06 -7.61726790581842e-06 -2.55026490957201e-07 4.60144518642285e-06 2.54040928360491e-06 0.000108915682667202 824 848 0 0 165 824 848 0 0 168 0 0 0 0 0 0 0 0 1566 0 0 0 0 0 2624 +612 615 0.995184934306767 -0.0854836732712566 0.0479529783526502 0.0384441638596941 0.0824552357078947 0.994668696340427 0.0619299493362466 -9.12562166959924e-05 -0.0529913260184365 -0.0576777784288506 0.996927877653304 0.124351808496013 4.66024864632031e-05 2.63259214517359e-05 -8.36425815449754e-06 -3.78038121183947e-06 1.33313500285282e-05 -3.97353871187425e-06 2.63259214517359e-05 5.26180369330723e-05 -4.71105193664068e-06 6.26770900042781e-06 -1.88484086995571e-06 -6.29027609985862e-06 -8.36425815449754e-06 -4.71105193664068e-06 1.77945966387153e-05 4.44917711513721e-06 -3.20370590541736e-06 -2.39484592888293e-06 -3.78038121183947e-06 6.26770900042781e-06 4.44917711513721e-06 3.43555905076419e-05 -2.31567164231701e-05 5.94320579903176e-06 1.33313500285282e-05 -1.88484086995571e-06 -3.20370590541736e-06 -2.31567164231701e-05 6.68527438951034e-05 4.11708464420268e-07 -3.97353871187425e-06 -6.29027609985862e-06 -2.39484592888293e-06 5.94320579903176e-06 4.11708464420268e-07 0.000111352591898995 712 748 0 0 187 712 748 0 0 188 0 0 0 0 0 0 0 0 1532 0 0 0 0 0 2515 +613 617 0.997927645974912 -0.061427321585805 0.0191597902328229 0.0479796184133 0.0610270800665542 0.997918975919915 0.0208185733780934 -0.0207235893455776 -0.0203987474498328 -0.0196061638711598 0.999599664586146 0.109032182046722 5.23897425035579e-05 2.96012240398174e-05 -3.38544305720999e-06 2.07187642003419e-06 1.32629448927843e-08 1.99842612068781e-05 2.96012240398174e-05 5.38507819272585e-05 -7.34293867053124e-06 5.10733867689837e-06 -3.92886179416835e-06 1.24355632886693e-05 -3.38544305720999e-06 -7.34293867053124e-06 2.03952259759529e-05 -5.39265541910438e-07 1.69771697355602e-06 -1.00744422185485e-06 2.07187642003419e-06 5.10733867689837e-06 -5.39265541910438e-07 2.39036342489614e-05 -1.49916305576525e-06 2.13261813064895e-06 1.32629448927843e-08 -3.92886179416835e-06 1.69771697355602e-06 -1.49916305576525e-06 3.49117463039244e-05 -2.35963605831864e-06 1.99842612068781e-05 1.24355632886693e-05 -1.00744422185485e-06 2.13261813064895e-06 -2.35963605831864e-06 0.000165880676449146 602 656 0 0 144 602 656 0 0 139 0 0 0 0 0 0 0 0 1510 0 0 0 0 0 2532 +613 616 0.998242039123596 -0.0557057991024197 0.0202409306289611 0.0336165012442989 0.0554208110828401 0.998359551450644 0.0143784465847179 -0.0106939188082437 -0.0210086892805263 -0.01323140104563 0.999691734986883 0.0886612574372081 5.71950428606774e-05 4.1385160993583e-05 -4.58829629428631e-06 -1.92539118519912e-06 1.20422280055982e-05 1.75670163627155e-05 4.1385160993583e-05 7.21602223481463e-05 -8.34072008335992e-06 7.69710543994233e-06 -5.07695028205318e-06 3.82005568832367e-05 -4.58829629428631e-06 -8.34072008335992e-06 1.85177922070827e-05 1.20202779695487e-06 -8.91514033440516e-07 -2.12543699127688e-06 -1.92539118519912e-06 7.69710543994233e-06 1.20202779695487e-06 2.48315779666196e-05 -4.97133075845461e-06 1.44387719214761e-05 1.20422280055982e-05 -5.07695028205318e-06 -8.91514033440516e-07 -4.97133075845461e-06 4.68987800898462e-05 -1.38579906793858e-05 1.75670163627155e-05 3.82005568832367e-05 -2.12543699127688e-06 1.44387719214761e-05 -1.38579906793858e-05 0.000134670264216062 643 692 0 0 137 643 692 0 0 132 0 0 0 0 0 0 0 0 1504 0 0 0 0 0 2589 +613 615 0.999178207953843 -0.0396978643608597 0.00818463898609225 0.0246133303308185 0.0395589641426031 0.999081220138576 0.0164864769547121 -0.00490863271590113 -0.0088315970305554 -0.0161491526589106 0.999830589531191 0.0708113432098299 4.11323295241174e-05 2.3963094675544e-05 -6.97131179149241e-06 2.50249333737732e-06 5.86166868350481e-06 1.30736380419134e-05 2.3963094675544e-05 7.29552752187659e-05 -1.31293841752745e-06 3.86419535511435e-06 6.26665580669437e-06 1.42129116127768e-05 -6.97131179149241e-06 -1.31293841752745e-06 1.64573223010984e-05 -2.14969029719456e-06 -2.65328117711276e-06 -6.99949761248779e-07 2.50249333737732e-06 3.86419535511435e-06 -2.14969029719456e-06 2.608753868582e-05 -6.66593440894857e-06 1.02577849080845e-05 5.86166868350481e-06 6.26665580669437e-06 -2.65328117711276e-06 -6.66593440894857e-06 5.24929776554023e-05 -9.47767305747873e-07 1.30736380419134e-05 1.42129116127768e-05 -6.99949761248779e-07 1.02577849080845e-05 -9.47767305747873e-07 9.90001044712135e-05 713 748 0 0 109 713 748 0 0 105 0 0 0 0 0 0 0 0 1598 0 1 0 0 0 2771 +614 616 0.999155285841108 -0.0328531400696742 0.0246857441317178 0.0222250290091631 0.0326003569345037 0.99941253366074 0.0105737547523503 -0.00156429127290014 -0.0250186231339222 -0.00976005888211046 0.999639339835673 0.0485501862908324 4.0842009726515e-05 2.43790253456448e-05 -7.33440567042297e-06 -2.34780874191161e-06 8.28895173506309e-06 9.17231077814771e-06 2.43790253456448e-05 4.55449116046188e-05 -8.86310313049664e-06 4.09665548715684e-07 2.13938854206879e-06 3.06645915670702e-06 -7.33440567042297e-06 -8.86310313049664e-06 1.83752724159881e-05 2.02757526381455e-06 1.0851704888807e-06 -3.22360815983197e-06 -2.34780874191161e-06 4.09665548715684e-07 2.02757526381455e-06 2.12259654899197e-05 7.54724647419973e-07 -3.02403737347617e-06 8.28895173506309e-06 2.13938854206879e-06 1.0851704888807e-06 7.54724647419973e-07 3.37132550964658e-05 1.07150133281434e-05 9.17231077814771e-06 3.06645915670702e-06 -3.22360815983197e-06 -3.02403737347617e-06 1.07150133281434e-05 7.06846444587339e-05 643 689 0 0 72 643 689 0 0 87 0 0 0 0 0 0 0 0 1557 0 0 3 0 0 3056 +614 617 0.999019958674587 -0.0384055197518724 0.0220031411942474 0.0392741163364921 0.0379671017883188 0.999078661525379 0.0200081799885097 -0.0218896230716388 -0.0227512934054503 -0.0191531756438899 0.999557669427399 0.0434250110364077 5.75447957067715e-05 4.29224626415068e-05 -5.91810968402989e-06 3.30920547907428e-06 9.44068940087643e-06 2.85311998192224e-05 4.29224626415068e-05 9.52845235675166e-05 -8.73129067542938e-06 1.37157315871406e-05 5.7803672355062e-06 3.86039360138995e-05 -5.91810968402989e-06 -8.73129067542938e-06 1.6654833709016e-05 1.67779896797018e-06 1.69966097851623e-06 -1.15226351437155e-06 3.30920547907428e-06 1.37157315871406e-05 1.67779896797018e-06 2.5282359823384e-05 -3.2327921541677e-06 9.20091184775349e-06 9.44068940087643e-06 5.7803672355062e-06 1.69966097851623e-06 -3.2327921541677e-06 3.9026457448867e-05 1.90593263757196e-06 2.85311998192224e-05 3.86039360138995e-05 -1.15226351437155e-06 9.20091184775349e-06 1.90593263757196e-06 0.000115757501604429 602 656 0 0 77 602 656 0 0 93 0 0 0 0 0 0 0 0 1544 0 0 0 0 0 3117 +614 618 0.999489041933559 -0.0312928676178356 0.00651241053592774 0.0386103018054604 0.0311339470630275 0.999245472668055 0.0232198771028524 -0.0204704147191566 -0.00723411328446351 -0.0230052556744667 0.999709170617305 0.0762112108977452 4.39648011292796e-05 2.24733180596997e-05 -1.02900746235326e-06 4.26729590141978e-06 3.78061155106367e-07 9.87302483960362e-06 2.24733180596997e-05 6.80664466370942e-05 -3.76707728172552e-06 4.66903224386315e-06 4.10506786879383e-06 -2.12853900389943e-06 -1.02900746235326e-06 -3.76707728172552e-06 1.81283645131542e-05 -2.44756629889359e-07 -6.68967288614179e-07 1.69804158022126e-06 4.26729590141978e-06 4.66903224386315e-06 -2.44756629889359e-07 2.00422284938262e-05 2.418345606647e-06 3.97757024884992e-06 3.78061155106367e-07 4.10506786879383e-06 -6.68967288614179e-07 2.418345606647e-06 3.30835355659087e-05 -8.13309879635491e-06 9.87302483960362e-06 -2.12853900389943e-06 1.69804158022126e-06 3.97757024884992e-06 -8.13309879635491e-06 6.53244243839465e-05 627 674 0 0 59 627 674 0 0 77 0 0 0 0 0 0 0 0 1522 0 0 4 0 0 3001 +615 619 0.999648615312849 0.0101949459632602 -0.0244685303994565 0.0242829733825258 -0.0103331093407689 0.999931338352466 -0.00552679219774786 -0.00847215627590219 0.0244105050020404 0.00577768616762602 0.999685323283329 0.0420995068726426 0.000156974787996156 6.378336948746e-05 2.58674841160004e-06 -2.77464738376475e-06 2.48749628834965e-05 0.000107133469384838 6.378336948746e-05 8.96743950495158e-05 1.44133823375738e-06 -1.65810749961743e-06 1.28898782702554e-05 1.9226000685118e-05 2.58674841160004e-06 1.44133823375738e-06 2.36688731536668e-05 -1.36835336443905e-06 1.77055847539873e-07 2.98656457136265e-08 -2.77464738376475e-06 -1.65810749961743e-06 -1.36835336443905e-06 2.72058308362259e-05 -6.2083019400408e-06 -2.81665625900875e-06 2.48749628834965e-05 1.28898782702554e-05 1.77055847539873e-07 -6.2083019400408e-06 4.51013191390571e-05 7.12027504614435e-06 0.000107133469384838 1.9226000685118e-05 2.98656457136265e-08 -2.81665625900875e-06 7.12027504614435e-06 0.000178756344937108 672 684 0 0 0 684 708 0 0 0 0 0 0 0 0 0 0 0 1468 0 0 17 0 0 2848 +615 617 0.999701452007908 -0.0204437459326035 0.0133813342206303 0.0150679764806464 0.0203736599234695 0.999778104321863 0.00535313925706735 0.000300712983147886 -0.0134878031793123 -0.00507891433535736 0.999896136503472 0.0311128480123305 0.000105705442338941 4.33667070267514e-05 -3.62894864495116e-06 -6.27689295961965e-07 1.46905529302401e-05 5.20104012457843e-05 4.33667070267514e-05 8.19432377466174e-05 -5.363662985949e-07 6.02075720193954e-07 1.08564366777566e-05 -2.29539305750528e-06 -3.62894864495116e-06 -5.363662985949e-07 1.82166134614768e-05 1.11381554610165e-06 2.88785951666927e-06 -8.41019854524597e-06 -6.27689295961965e-07 6.02075720193954e-07 1.11381554610165e-06 2.19009978526996e-05 8.83015040352248e-07 1.78214872683948e-06 1.46905529302401e-05 1.08564366777566e-05 2.88785951666927e-06 8.83015040352248e-07 3.68792222127356e-05 -1.85083341229702e-06 5.20104012457843e-05 -2.29539305750528e-06 -8.41019854524597e-06 1.78214872683948e-06 -1.85083341229702e-06 0.000117796045193493 608 659 0 0 24 608 659 0 0 52 0 0 0 0 0 0 0 0 1527 0 0 3 0 0 2849 +615 618 0.999829401197952 -0.0108615268899135 -0.0149397367367756 0.0301232847226586 0.0111951453614104 0.999685696308386 0.0224316142253483 -0.0284565368887003 0.0146913995412747 -0.0225950399432629 0.999636747498551 0.0261360104108916 3.90894595354798e-05 2.83904111224336e-05 -6.52410567555776e-06 -4.83369620290003e-06 1.06922348393109e-05 1.14106488916971e-05 2.83904111224336e-05 6.78314016793187e-05 -6.55008436517613e-06 -3.97582486332815e-06 4.72699652593669e-06 1.0497609044183e-05 -6.52410567555776e-06 -6.55008436517613e-06 1.83340402973513e-05 -3.99553039342506e-07 2.73713500287824e-06 -3.95605658555591e-07 -4.83369620290003e-06 -3.97582486332815e-06 -3.99553039342506e-07 3.19616924095848e-05 -1.95601927979668e-05 -1.04006617341944e-06 1.06922348393109e-05 4.72699652593669e-06 2.73713500287824e-06 -1.95601927979668e-05 6.35287123537637e-05 -7.83787404551316e-07 1.14106488916971e-05 1.0497609044183e-05 -3.95605658555591e-07 -1.04006617341944e-06 -7.83787404551316e-07 5.61248570706675e-05 637 683 0 0 1 637 683 0 0 32 0 0 0 0 0 0 0 0 1531 0 0 5 0 0 3105 +616 618 0.999715919549967 0.00140602270180345 -0.0237929253881564 0.0206424098938173 -0.00113363768540385 0.999933714991307 0.01145776982145 -0.025777046355523 0.0238074581583712 -0.0114275423361767 0.99965124729187 0.00695294466517058 0.000108752316213017 8.37460852351354e-05 3.81109118300595e-06 -1.83101077339119e-05 1.75306092848334e-05 3.84661989042478e-05 8.37460852351354e-05 0.000106941246603777 -3.40522714340612e-06 -1.40952408602669e-05 1.9161937561193e-05 2.41594623033575e-05 3.81109118300595e-06 -3.40522714340612e-06 2.21978329928012e-05 -2.10202710197222e-06 5.02520945991652e-07 4.36751144880579e-06 -1.83101077339119e-05 -1.40952408602669e-05 -2.10202710197222e-06 2.5181170551243e-05 4.08890811021379e-06 -8.35621425274205e-06 1.75306092848334e-05 1.9161937561193e-05 5.02520945991652e-07 4.08890811021379e-06 3.23612705778898e-05 9.27433003326377e-06 3.84661989042478e-05 2.41594623033575e-05 4.36751144880579e-06 -8.35621425274205e-06 9.27433003326377e-06 9.52133874332532e-05 625 626 0 0 0 636 676 0 0 0 0 0 0 0 0 0 0 0 1480 0 0 6 0 0 3082 +616 619 0.998811033539851 0.0253754779130309 -0.0416245648594707 0.0200461550109325 -0.025723986207123 0.999638195245578 -0.00785844385231559 -0.0196189629047281 0.0414100931255986 0.00891985015846875 0.999102417402981 0.0163472433415404 2.98712285321489e-05 1.67682293498637e-05 -8.40940934515208e-06 2.11019623752602e-07 7.71514033706267e-06 6.51277106709613e-06 1.67682293498637e-05 4.92537764341294e-05 -1.22745126165382e-05 -2.89997490219368e-06 6.37479027974846e-06 2.29291839588298e-06 -8.40940934515208e-06 -1.22745126165382e-05 2.15148470054607e-05 -1.48792526875417e-06 -6.01740344501461e-07 -3.43011349535685e-06 2.11019623752602e-07 -2.89997490219368e-06 -1.48792526875417e-06 2.17934167271306e-05 9.43524600858634e-07 2.89033046235533e-06 7.71514033706267e-06 6.37479027974846e-06 -6.01740344501461e-07 9.43524600858634e-07 3.07558750838575e-05 4.5480544815799e-06 6.51277106709613e-06 2.29291839588298e-06 -3.43011349535685e-06 2.89033046235533e-06 4.5480544815799e-06 4.97377410466159e-05 602 602 0 0 0 634 634 0 0 0 0 0 0 0 0 0 0 0 1436 0 44 92 0 0 3429 +616 620 0.99708948769974 0.0514783149755086 -0.0562364348616832 0.0192204406974752 -0.0529082048076723 0.998305145820297 -0.0242395893683394 -0.032517464214729 0.0548933090886259 0.0271444085586448 0.998123191645852 0.0238899071029749 4.34606553086728e-05 2.54440685836314e-05 -7.47466067260898e-06 8.10376749677372e-06 -6.90229095978168e-06 8.9519460215078e-06 2.54440685836314e-05 6.75081766992081e-05 -6.2868603981508e-06 6.74345893845492e-07 -5.07041937466554e-07 -3.87029017451675e-06 -7.47466067260898e-06 -6.2868603981508e-06 2.13260430821984e-05 -3.9299858171141e-06 9.6061095097091e-07 -9.60422342175439e-07 8.10376749677372e-06 6.74345893845492e-07 -3.9299858171141e-06 5.41662358707414e-05 -4.20371226504072e-05 1.97840937118305e-05 -6.90229095978168e-06 -5.07041937466554e-07 9.6061095097091e-07 -4.20371226504072e-05 8.44449586812669e-05 -2.35098355301157e-05 8.9519460215078e-06 -3.87029017451675e-06 -9.60422342175439e-07 1.97840937118305e-05 -2.35098355301157e-05 5.81008606034119e-05 600 600 0 0 0 645 645 0 0 0 0 0 0 0 0 0 0 0 1420 0 137 171 0 0 3152 +617 619 0.999017285976139 0.0292764910639886 -0.0332768597053501 0.00928414957560046 -0.0297462739082574 0.999463439744483 -0.0137110102728279 -0.00872650805571166 0.0328575943952731 0.0146873988543535 0.999352119528172 0.00716958299388449 4.0902056088827e-05 2.70880160693387e-05 -2.6279267850385e-06 -1.6126898316136e-06 1.18455727269681e-05 8.81592592286142e-06 2.70880160693387e-05 6.53239446483155e-05 -1.46069511454815e-06 -1.42692748464944e-06 -7.33049224895006e-07 -4.61089768536439e-07 -2.6279267850385e-06 -1.46069511454815e-06 2.2198758931856e-05 -2.19063565867453e-06 -2.20500564424956e-06 -2.01077595735034e-06 -1.6126898316136e-06 -1.42692748464944e-06 -2.19063565867453e-06 2.41889921305589e-05 -4.84971509967346e-06 -4.20747465814162e-06 1.18455727269681e-05 -7.33049224895006e-07 -2.20500564424956e-06 -4.84971509967346e-06 3.98461311855642e-05 1.94125319109395e-06 8.81592592286142e-06 -4.61089768536439e-07 -2.01077595735034e-06 -4.20747465814162e-06 1.94125319109395e-06 5.01513084210484e-05 598 598 0 0 0 630 630 0 0 0 0 0 0 0 0 0 0 0 1453 0 47 95 0 0 3306 +617 620 0.996820265260736 0.0578855793898144 -0.0547596426597248 0.00682083948147859 -0.0592265144066324 0.997975196933693 -0.0231889261587722 -0.0168938784642443 0.0533064607412294 0.0263584142895872 0.998230261632747 0.0110893933488793 0.000100353142576294 7.82436854744263e-05 -1.43514252046317e-06 -6.30991773694406e-06 1.69678470058313e-05 4.62428970788221e-05 7.82436854744263e-05 0.000107648599482499 3.91500172149793e-07 -1.09897316120412e-05 1.44172488222089e-05 2.99129367189003e-05 -1.43514252046317e-06 3.91500172149793e-07 2.53082267965677e-05 -8.40499876897502e-07 -4.151335718289e-07 4.75479568508794e-06 -6.30991773694406e-06 -1.09897316120412e-05 -8.40499876897502e-07 4.07380491976824e-05 -2.95598227343543e-05 -3.93663829195471e-06 1.69678470058313e-05 1.44172488222089e-05 -4.151335718289e-07 -2.95598227343543e-05 7.39354214990761e-05 1.12225065154214e-05 4.62428970788221e-05 2.99129367189003e-05 4.75479568508794e-06 -3.93663829195471e-06 1.12225065154214e-05 8.53050313385224e-05 595 595 0 0 0 634 634 0 0 0 0 0 0 0 0 0 0 0 1442 0 147 181 0 0 3000 +617 621 0.993752194139095 0.103001687500069 -0.0429794022279577 -0.00655159614617849 -0.104498690689974 0.993937910540993 -0.034168020625799 -0.0198640148997652 0.0391994934637628 0.038445836725737 0.998491520920755 0.000386953568039499 7.64889488345712e-05 4.42370448016249e-05 -5.33382915347459e-06 3.21318268283332e-07 1.56390171670518e-05 6.1981694759986e-05 4.42370448016249e-05 8.37820196065146e-05 -1.0048435412349e-06 -3.84241764472671e-06 1.2166855278437e-05 2.28000598616043e-05 -5.33382915347459e-06 -1.0048435412349e-06 2.62725058255808e-05 -4.75996105441027e-06 1.33137287690443e-06 -6.73872185058291e-07 3.21318268283332e-07 -3.84241764472671e-06 -4.75996105441027e-06 3.21008757775247e-05 -9.73021253250468e-06 8.15323952219288e-06 1.56390171670518e-05 1.2166855278437e-05 1.33137287690443e-06 -9.73021253250468e-06 4.66016805336938e-05 4.39443143050233e-06 6.1981694759986e-05 2.28000598616043e-05 -6.73872185058291e-07 8.15323952219288e-06 4.39443143050233e-06 0.000142265588419244 636 636 0 0 0 696 696 0 0 0 0 0 0 0 0 0 0 0 1359 0 254 273 0 0 2996 +618 620 0.998473846229808 0.0498239722226135 -0.0238233118397381 -0.00127889275209783 -0.0504631909146182 0.998360117319818 -0.0270285498662753 0.00357887992213677 0.0224375746855127 0.0281895004765812 0.999350742885156 0.00654827098408976 2.97406262603499e-05 1.8026990240341e-05 -7.33805031548378e-06 -1.08913296221988e-06 3.58085120760939e-06 8.58325427389275e-06 1.8026990240341e-05 4.84096812791562e-05 -1.06651588368537e-05 1.61168390843247e-06 3.38122914145872e-06 3.33196723752921e-06 -7.33805031548378e-06 -1.06651588368537e-05 1.95055182596998e-05 1.20279728385599e-06 2.58563151220203e-06 -2.2973283391894e-06 -1.08913296221988e-06 1.61168390843247e-06 1.20279728385599e-06 3.51863861548955e-05 -1.47986682156932e-05 6.11812422700862e-06 3.58085120760939e-06 3.38122914145872e-06 2.58563151220203e-06 -1.47986682156932e-05 5.96438289388358e-05 -2.61396565029706e-06 8.58325427389275e-06 3.33196723752921e-06 -2.2973283391894e-06 6.11812422700862e-06 -2.61396565029706e-06 5.17325328329596e-05 617 617 0 0 0 658 658 0 0 0 0 0 0 0 0 0 0 0 1392 0 118 152 0 0 3242 +618 621 0.995214833089135 0.0957252942056018 -0.0195985726168074 -0.0116940168874256 -0.0964578764314743 0.99450615247267 -0.0406619080754511 -0.00999050378590586 0.0155985279336137 0.0423577707541011 0.998980733139057 -0.00261766919282733 8.74192470844205e-05 4.53425869822205e-05 -1.16031671326003e-05 -1.59010397055366e-06 1.41839654606989e-05 5.06594508083588e-05 4.53425869822205e-05 0.000107807286920699 -8.89138941836465e-06 3.73551411263584e-06 1.24564730808246e-05 1.8836789864507e-05 -1.16031671326003e-05 -8.89138941836465e-06 2.07207495819005e-05 5.83262444465859e-07 -5.16983750191085e-07 -4.44427574279822e-06 -1.59010397055366e-06 3.73551411263584e-06 5.83262444465859e-07 3.12121311419536e-05 -9.75417453864997e-07 4.21765120998668e-06 1.41839654606989e-05 1.24564730808246e-05 -5.16983750191085e-07 -9.75417453864997e-07 4.65302788052558e-05 1.47849421125432e-05 5.06594508083588e-05 1.8836789864507e-05 -4.44427574279822e-06 4.21765120998668e-06 1.47849421125432e-05 0.000104146435087563 665 665 0 0 0 707 707 0 0 0 0 0 0 0 0 0 0 0 1377 0 256 275 0 0 2948 +618 622 0.991313066049815 0.130101681271 -0.0192862025648828 -0.0199652893027154 -0.130764399346857 0.990669264660009 -0.0384067692139496 -0.0268890727736826 0.0141094628661143 0.0405950808406268 0.999076054396848 -0.00468604329133128 9.62778869178999e-05 5.9973138075946e-05 -6.01883291836142e-06 1.94519523186502e-05 -2.49721360808046e-05 9.42344023395902e-05 5.9973138075946e-05 8.0364983945449e-05 -7.48123074952633e-06 3.26475344683844e-06 -1.01390013988182e-05 5.82773580899738e-05 -6.01883291836142e-06 -7.48123074952633e-06 2.17284203058337e-05 3.08506491462482e-06 -1.54801603516292e-06 -1.30969288894541e-06 1.94519523186502e-05 3.26475344683844e-06 3.08506491462482e-06 3.61158044033619e-05 -1.40230189884363e-05 3.13227027162536e-05 -2.49721360808046e-05 -1.01390013988182e-05 -1.54801603516292e-06 -1.40230189884363e-05 5.47443972535933e-05 -3.79292167929662e-05 9.42344023395902e-05 5.82773580899738e-05 -1.30969288894541e-06 3.13227027162536e-05 -3.79292167929662e-05 0.000184330322415521 680 680 0 0 0 727 727 0 0 0 0 0 0 0 0 0 0 0 1345 0 340 359 0 0 2883 +619 623 0.993771987475264 0.108617818687698 0.0248878760240778 -0.0304541563248029 -0.108264612100105 0.994006983671354 -0.0151291169401818 -0.0194200918357215 -0.0263820142573939 0.0123404163666479 0.999575761734757 0.0312531240359177 8.04012911859673e-05 4.15193675305891e-05 -3.88346155945603e-06 1.08152944299486e-06 -2.20184263407919e-06 7.24436810622928e-05 4.15193675305891e-05 8.19826186663397e-05 -7.30877476894893e-06 4.19292188578537e-06 -2.02029224787294e-06 3.03114297706291e-05 -3.88346155945603e-06 -7.30877476894893e-06 1.89225216507986e-05 1.10695777344264e-06 -1.58108854385258e-06 3.641827519636e-06 1.08152944299486e-06 4.19292188578537e-06 1.10695777344264e-06 3.27814726190025e-05 -9.13954766131494e-06 6.02568720488416e-06 -2.20184263407919e-06 -2.02029224787294e-06 -1.58108854385258e-06 -9.13954766131494e-06 5.1320556576803e-05 -1.12936435677211e-05 7.24436810622928e-05 3.03114297706291e-05 3.641827519636e-06 6.02568720488416e-06 -1.12936435677211e-05 0.000142064379629104 772 772 0 0 0 798 798 0 0 0 0 0 0 0 0 0 0 0 1318 0 280 298 0 0 3002 +619 622 0.994233955302041 0.10671207450135 0.0105534487290727 -0.0228206097529862 -0.106618341508649 0.9942585650925 -0.00907937190274853 -0.0252761416875252 -0.0114617354010566 0.0079018286378376 0.999903090167129 -0.00783316987835184 4.52704317112304e-05 1.68218111803133e-05 -6.71000632256091e-06 1.10867238159082e-05 -9.43560251476286e-06 2.73936511417605e-05 1.68218111803133e-05 8.89846445678128e-05 -4.86105070776351e-06 3.74788380967009e-06 -1.50647511955551e-06 1.60097587815521e-05 -6.71000632256091e-06 -4.86105070776351e-06 2.62328844439953e-05 -3.86911048220275e-06 -3.78314219893066e-06 2.03920871722648e-07 1.10867238159082e-05 3.74788380967009e-06 -3.86911048220275e-06 3.20726234580235e-05 -2.94527179410874e-07 2.00296993294748e-05 -9.43560251476286e-06 -1.50647511955551e-06 -3.78314219893066e-06 -2.94527179410874e-07 4.65784202790894e-05 -1.69194718510319e-05 2.73936511417605e-05 1.60097587815521e-05 2.03920871722648e-07 2.00296993294748e-05 -1.69194718510319e-05 9.30755038932889e-05 742 742 0 0 0 772 772 0 0 0 0 0 0 0 0 0 0 0 1387 0 280 299 0 0 2961 +619 621 0.997268971837109 0.0735602275360109 -0.00659475062494879 -0.0222902757581741 -0.0737034965096204 0.996965544409985 -0.0250499074161588 -0.00297725032922581 0.00473206225776151 0.0254675515931952 0.999664449404217 -0.00263243171764755 5.84548105501603e-05 4.21454739847335e-05 -1.05664660179673e-05 -2.58244417224776e-06 1.01382435974615e-05 3.70005181340176e-05 4.21454739847335e-05 0.000106552969627697 -6.3284625035901e-06 -2.57813259294136e-06 -5.9721353226277e-07 3.48300347066431e-05 -1.05664660179673e-05 -6.3284625035901e-06 2.65031468890095e-05 -2.81931521207741e-06 -3.79638806575747e-06 -2.89246037680065e-06 -2.58244417224776e-06 -2.57813259294136e-06 -2.81931521207741e-06 2.96877176417499e-05 -5.42004902797103e-06 2.03734584004172e-06 1.01382435974615e-05 -5.9721353226277e-07 -3.79638806575747e-06 -5.42004902797103e-06 4.04433884677502e-05 3.16490257527598e-06 3.70005181340176e-05 3.48300347066431e-05 -2.89246037680065e-06 2.03734584004172e-06 3.16490257527598e-06 9.93616495511131e-05 720 720 0 0 0 748 748 0 0 0 0 0 0 0 0 0 0 0 1404 0 203 222 0 0 3246 +620 623 0.995972508291276 0.0806831479900121 0.0391023318793819 -0.0320159612601499 -0.0807334350419096 0.996735685177823 -0.000293869749309391 -0.00531004100728673 -0.0389983998943196 -0.00286417937944067 0.999235168157209 0.0163093353461166 0.000102302049296303 3.25987740463134e-05 -6.52962790579837e-06 -7.81955033918712e-06 4.63464031587594e-06 8.92857784990089e-05 3.25987740463134e-05 0.000120840642952754 -8.34778750761478e-06 2.06410506487474e-05 -2.46904951920525e-05 2.42816114256024e-05 -6.52962790579837e-06 -8.34778750761478e-06 1.93553403208069e-05 2.7251348641776e-06 3.06947970092346e-08 -3.87579716880337e-06 -7.81955033918712e-06 2.06410506487474e-05 2.7251348641776e-06 4.51662841618529e-05 -2.56638365992134e-05 3.18009474562375e-06 4.63464031587594e-06 -2.46904951920525e-05 3.06947970092346e-08 -2.56638365992134e-05 6.55142685434773e-05 -2.22374007058654e-05 8.92857784990089e-05 2.42816114256024e-05 -3.87579716880337e-06 3.18009474562375e-06 -2.22374007058654e-05 0.000184789263519209 859 859 0 0 0 910 910 0 0 0 0 0 0 0 0 0 0 0 1322 0 187 205 0 0 3029 +620 624 0.997161664702612 0.0400499772168346 0.0637543235588553 -0.0182782408805201 -0.0427966896321707 0.998187247555697 0.0423162164389572 -0.0149062426011929 -0.0619439892487062 -0.0449245828262439 0.997068063902282 0.0147828050662323 7.36355174558273e-05 5.30832578968546e-05 -1.17082414405701e-07 3.27849649039046e-06 6.01339214419525e-07 6.16863942383549e-05 5.30832578968546e-05 6.74048403821036e-05 -5.22174050094085e-06 1.10849362131214e-06 -3.54952974915777e-07 4.84848807635033e-05 -1.17082414405701e-07 -5.22174050094085e-06 2.02159060874885e-05 7.97149004407159e-08 -4.07351805784883e-07 -5.28515959724871e-07 3.27849649039046e-06 1.10849362131214e-06 7.97149004407159e-08 2.30667350313304e-05 -1.79483327230202e-06 5.64280750104264e-06 6.01339214419525e-07 -3.54952974915777e-07 -4.07351805784883e-07 -1.79483327230202e-06 3.20359112531069e-05 -7.08793565936183e-06 6.16863942383549e-05 4.84848807635033e-05 -5.28515959724871e-07 5.64280750104264e-06 -7.08793565936183e-06 0.000133180523498506 845 845 0 0 0 891 891 0 0 0 0 0 0 0 0 0 0 0 1330 0 114 114 0 0 3182 +620 622 0.996536288988125 0.0787237236811451 0.0267955231251513 -0.0210883836729855 -0.0786597053181614 0.996895601936502 -0.00343650970006917 -0.0162260264382978 -0.026982873995107 0.00131687867070824 0.999635028568693 -0.00502742028604289 6.82773287958915e-05 4.96984897622621e-05 -1.05086031694526e-05 8.90023526117427e-06 -7.02630012075403e-06 5.67747381059194e-05 4.96984897622621e-05 8.80109296209827e-05 -1.86341007094696e-05 8.72229214283658e-06 -4.95416080147695e-06 5.35472316674214e-05 -1.05086031694526e-05 -1.86341007094696e-05 2.11786659441215e-05 1.59701230187175e-06 6.01785917148549e-06 -5.06794457511053e-06 8.90023526117427e-06 8.72229214283658e-06 1.59701230187175e-06 3.412419993703e-05 -1.03563509575728e-05 2.15744272849947e-05 -7.02630012075403e-06 -4.95416080147695e-06 6.01785917148549e-06 -1.03563509575728e-05 4.74006029221957e-05 -1.30208545851291e-05 5.67747381059194e-05 5.35472316674214e-05 -5.06794457511053e-06 2.15744272849947e-05 -1.30208545851291e-05 0.000136501883730889 831 831 0 0 0 893 893 0 0 0 0 0 0 0 0 0 0 0 1330 0 172 191 0 0 2973 +621 623 0.998802286459984 0.0342379552852284 0.0349536118333323 -0.00492466121128331 -0.0348393632977339 0.999252646951471 0.0167441430203769 -0.0173908446011107 -0.0343542039249505 -0.0179418499147949 0.999248657089074 0.023307995405605 0.000114286311491329 8.04724689222931e-05 -6.76842484841932e-06 2.88214739234555e-06 -7.09884989052054e-06 0.000109027348973675 8.04724689222931e-05 9.27298148797342e-05 -1.03757506788555e-05 6.91352530564414e-07 -1.65223013990315e-06 7.45596614866509e-05 -6.76842484841932e-06 -1.03757506788555e-05 1.92667898344419e-05 2.07078129707516e-07 3.62417244275474e-07 -3.27933888445296e-06 2.88214739234555e-06 6.91352530564414e-07 2.07078129707516e-07 1.90390045247982e-05 4.45588754696602e-06 8.79973549636496e-06 -7.09884989052054e-06 -1.65223013990315e-06 3.62417244275474e-07 4.45588754696602e-06 2.50575579717284e-05 -1.75966163557572e-05 0.000109027348973675 7.45596614866509e-05 -3.27933888445296e-06 8.79973549636496e-06 -1.75966163557572e-05 0.00019222906399334 1013 1012 0 0 6 999 999 0 0 1 0 0 0 0 0 0 0 0 1354 0 85 83 0 0 3118 +621 624 0.998733123273551 -0.00552417618974737 0.050016316874432 0.00879746684732637 0.00242746155031356 0.998087806354924 0.0617643767558407 -0.0270642166624642 -0.0502618732906038 -0.0615647162183041 0.996836761867398 0.0154938637324856 5.77400042319882e-05 4.11570515025501e-05 -3.59654183491181e-06 2.31400029999775e-06 -7.53374747371672e-07 3.77219470284487e-05 4.11570515025501e-05 5.90789292005791e-05 -1.05715401939594e-05 -1.31284617986614e-06 -2.0380431293577e-06 3.56733278985049e-05 -3.59654183491181e-06 -1.05715401939594e-05 2.2164761307982e-05 2.30017656089513e-06 2.6257247588565e-06 4.01471979070712e-06 2.31400029999775e-06 -1.31284617986614e-06 2.30017656089513e-06 2.49338388411219e-05 -3.59622191987192e-06 8.48899583053848e-06 -7.53374747371672e-07 -2.0380431293577e-06 2.6257247588565e-06 -3.59622191987192e-06 3.29715219107453e-05 -9.13629472642307e-06 3.77219470284487e-05 3.56733278985049e-05 4.01471979070712e-06 8.48899583053848e-06 -9.13629472642307e-06 0.000105976213932524 984 996 0 0 12 981 1002 0 0 23 0 0 0 0 0 0 0 0 1334 0 32 28 0 0 3350 +621 625 0.991271709312312 -0.0814466224596698 0.103666995745797 0.000960215823909649 0.0751507532219863 0.99516361835622 0.0632592838271555 0.013771924784913 -0.108317877597445 -0.05491648559466 0.992598316038626 0.0377202435240629 6.1983284701219e-05 3.4384772058289e-05 -5.4665473595566e-06 -7.3918376982411e-06 9.27447399190967e-06 4.03276645697317e-05 3.4384772058289e-05 6.25069799635745e-05 -6.03825600608743e-06 -4.52752706381935e-06 6.6947286579394e-06 1.97694534301264e-05 -5.4665473595566e-06 -6.03825600608743e-06 1.90933940676186e-05 1.06012372292119e-06 1.00141451863225e-06 -2.55540323637369e-06 -7.3918376982411e-06 -4.52752706381935e-06 1.06012372292119e-06 2.34142205493509e-05 -5.5348068345894e-07 -8.07894919735481e-06 9.27447399190967e-06 6.6947286579394e-06 1.00141451863225e-06 -5.5348068345894e-07 3.19662865191094e-05 7.24880162174251e-06 4.03276645697317e-05 1.97694534301264e-05 -2.55540323637369e-06 -8.07894919735481e-06 7.24880162174251e-06 9.96637083594224e-05 729 769 0 0 178 729 769 0 0 196 0 0 0 0 0 0 0 0 1366 0 0 0 0 0 2918 +622 626 0.975846586646427 -0.18609500412004 0.114420665843541 0.016078128542448 0.178463988025477 0.981178387856281 0.0737534825061945 0.0436043531016457 -0.125992239080666 -0.051552115817988 0.990690837267676 0.0507192030872362 7.99719225299362e-05 2.0391228558678e-05 -1.18168552709399e-05 -2.31058807137892e-06 -3.53798241870332e-06 5.47186548591069e-05 2.0391228558678e-05 5.98513307207298e-05 -1.06881725838905e-05 -1.22058225974549e-06 2.49861266038855e-06 6.04125147934481e-06 -1.18168552709399e-05 -1.06881725838905e-05 2.27110320898133e-05 2.63642230633461e-07 4.12023527378875e-06 -9.31502659058006e-06 -2.31058807137892e-06 -1.22058225974549e-06 2.63642230633461e-07 2.43859228706486e-05 1.86034084242798e-06 -3.95003035841056e-06 -3.53798241870332e-06 2.49861266038855e-06 4.12023527378875e-06 1.86034084242798e-06 4.37498060156873e-05 -7.71047315661101e-06 5.47186548591069e-05 6.04125147934481e-06 -9.31502659058006e-06 -3.95003035841056e-06 -7.71047315661101e-06 0.000120749361821988 463 516 0 0 331 463 516 0 0 335 0 0 0 0 0 0 0 0 1340 0 0 0 0 0 2625 +622 624 0.99796846444158 -0.0395294192273848 0.0499636767628388 -0.00207283995862676 0.0369285100937137 0.997966732636305 0.0519488757671978 0.0138634196206589 -0.0519155961380996 -0.0499982556372012 0.997399090289771 0.0244939685030956 5.60987520774325e-05 4.04306621191455e-05 -4.42121369199001e-06 -1.06512393557008e-05 2.1004868299752e-05 2.45281151890161e-05 4.04306621191455e-05 6.82388233616781e-05 -8.25269815142791e-06 -1.19955002631424e-05 1.79957363367407e-05 2.58432145575643e-05 -4.42121369199001e-06 -8.25269815142791e-06 2.01329528856541e-05 4.86765513640489e-08 4.39990013947707e-06 2.3868457476383e-06 -1.06512393557008e-05 -1.19955002631424e-05 4.86765513640489e-08 3.6236349821872e-05 -1.63747061111976e-05 -1.84775785587321e-05 2.1004868299752e-05 1.79957363367407e-05 4.39990013947707e-06 -1.63747061111976e-05 5.47234875542576e-05 2.3739465017323e-05 2.45281151890161e-05 2.58432145575643e-05 2.3868457476383e-06 -1.84775785587321e-05 2.3739465017323e-05 0.00010397105939568 1010 1021 0 0 84 1010 1021 0 0 106 0 0 0 0 0 0 0 0 1324 0 1 0 0 0 3226 +622 625 0.989163289204517 -0.114827340226924 0.0914913614857222 0.0165657260848753 0.110532974252122 0.992577726917243 0.0507140772446673 0.0109611564092526 -0.0966356502181299 -0.0400516911529142 0.994513656589346 0.0381641386532674 8.4544687137425e-05 6.5935261296171e-05 -6.6340574157565e-06 -1.6079653371392e-05 1.39374015441277e-05 5.33383566133738e-05 6.5935261296171e-05 8.75815588975285e-05 -1.01409277421075e-05 -9.61316489278804e-06 6.67401278984462e-06 4.59905267730604e-05 -6.6340574157565e-06 -1.01409277421075e-05 1.80697906595289e-05 2.36895210380081e-06 4.40931765872177e-07 3.05367502803468e-06 -1.6079653371392e-05 -9.61316489278804e-06 2.36895210380081e-06 2.36533342665633e-05 -2.57593960622182e-06 -1.43188144220156e-05 1.39374015441277e-05 6.67401278984462e-06 4.40931765872177e-07 -2.57593960622182e-06 3.28982682683979e-05 6.69578970677407e-06 5.33383566133738e-05 4.59905267730604e-05 3.05367502803468e-06 -1.43188144220156e-05 6.69578970677407e-06 0.000121800154537094 729 769 0 0 227 729 769 0 0 233 0 0 0 0 0 0 0 0 1355 0 0 0 0 0 2844 +622 677 0.956661306911598 -0.285618941442677 0.0567535386329218 0.0473711379270526 0.286827803430792 0.957875953886087 -0.0142642260878575 0.120062360612771 -0.050288716798708 0.0299245259942978 0.998286315496088 0.174774652019583 0.000131816495002641 0.000106597918367574 -1.68841660923561e-05 2.62143978019899e-06 6.68374509308469e-06 0.000118831071331052 0.000106597918367574 0.000138227340261087 -1.64433266610205e-05 3.69014324085199e-06 7.5357058088155e-07 0.000100574687151442 -1.68841660923561e-05 -1.64433266610205e-05 1.7298466605037e-05 2.26048693810043e-06 5.97786440799709e-06 -1.05434506958016e-05 2.62143978019899e-06 3.69014324085199e-06 2.26048693810043e-06 4.05231524386133e-05 -5.19563097334273e-05 7.27114908637712e-06 6.68374509308469e-06 7.5357058088155e-07 5.97786440799709e-06 -5.19563097334273e-05 0.000164939528630523 -8.89151115571381e-06 0.000118831071331052 0.000100574687151442 -1.05434506958016e-05 7.27114908637712e-06 -8.89151115571381e-06 0.000201861485947818 0 6 0 0 396 0 6 0 0 393 0 0 0 0 0 0 0 0 956 0 0 0 0 0 1933 +622 676 0.956934529335597 -0.285529561911233 0.0524325837627596 0.042918251806574 0.286559617757051 0.95797218092271 -0.0131486139619175 0.124745802463911 -0.0464746386343373 0.0276074238741339 0.99853790018749 0.177039324374652 0.000109876311504974 9.43062989229597e-05 -1.42669809276113e-05 -4.52205071495647e-06 2.21036583364348e-05 9.3396315947332e-05 9.43062989229597e-05 0.000132413369085421 -1.07384241444983e-05 -5.08670997068049e-06 1.31977084650505e-05 8.6745887382843e-05 -1.42669809276113e-05 -1.07384241444983e-05 1.90531278878197e-05 3.29247098160159e-06 7.50898899789258e-07 -1.51318578651003e-06 -4.52205071495647e-06 -5.08670997068049e-06 3.29247098160159e-06 2.26533494999899e-05 -1.97372349569522e-06 -8.4019982657206e-06 2.21036583364348e-05 1.31977084650505e-05 7.50898899789258e-07 -1.97372349569522e-06 6.56813357653068e-05 3.32760647196001e-05 9.3396315947332e-05 8.6745887382843e-05 -1.51318578651003e-06 -8.4019982657206e-06 3.32760647196001e-05 0.000191180526621946 0 5 0 0 394 0 5 0 0 393 0 0 0 0 0 0 0 0 917 0 0 0 0 0 1951 +623 625 0.990289102152551 -0.115229328323167 0.0777797920547831 0.0164554683438996 0.112360114890934 0.992849052954249 0.0403232269237846 0.0147042705024863 -0.0818700112348201 -0.0311923058147799 0.99615477779227 0.02927270343494 5.38705262832805e-05 4.0901985446328e-05 -3.94645989224757e-06 -9.02780169290508e-06 1.02093776952674e-05 2.23000187973575e-05 4.0901985446328e-05 7.1206333829795e-05 -8.55511985026892e-06 -7.45663354710441e-06 1.00031347372079e-05 1.49606200528267e-05 -3.94645989224757e-06 -8.55511985026892e-06 2.15382351314105e-05 1.47688867742508e-06 6.49426204334343e-06 5.85491170250649e-06 -9.02780169290508e-06 -7.45663354710441e-06 1.47688867742508e-06 3.24348511523668e-05 -1.24900065473462e-05 -6.09044224381176e-06 1.02093776952674e-05 1.00031347372079e-05 6.49426204334343e-06 -1.24900065473462e-05 4.91045476949299e-05 5.23739421206833e-06 2.23000187973575e-05 1.49606200528267e-05 5.85491170250649e-06 -6.09044224381176e-06 5.23739421206833e-06 7.69704668993248e-05 729 769 0 0 222 729 769 0 0 220 0 0 0 0 0 0 0 0 1332 0 0 0 0 0 3002 +623 626 0.977908953928708 -0.185809508317851 0.0957543964773293 0.0147880790524619 0.181196872589046 0.981914402549217 0.054879863614655 0.0447429595414945 -0.104219821483287 -0.0363171128408139 0.993890988048941 0.0377187290347465 8.46805498783352e-05 6.07563932216368e-05 -8.02971741141994e-06 -1.63343698001885e-06 -1.04752753752267e-06 6.2252539596193e-05 6.07563932216368e-05 7.21158200376388e-05 -1.2057373824777e-05 -4.31687854576098e-06 -6.19208099185602e-06 4.74959577320147e-05 -8.02971741141994e-06 -1.2057373824777e-05 1.95644306853816e-05 1.99194219822982e-06 4.72428878167581e-06 -4.41096907992125e-06 -1.63343698001885e-06 -4.31687854576098e-06 1.99194219822982e-06 3.24581728383379e-05 -1.86459634904952e-05 -2.90677114716135e-06 -1.04752753752267e-06 -6.19208099185602e-06 4.72428878167581e-06 -1.86459634904952e-05 7.30383452513909e-05 -1.49594242219711e-05 6.2252539596193e-05 4.74959577320147e-05 -4.41096907992125e-06 -2.90677114716135e-06 -1.49594242219711e-05 0.000142588590751929 462 515 0 0 350 462 515 0 0 345 0 0 0 0 0 0 0 0 1308 0 0 0 0 0 2770 +623 627 0.972376851337574 -0.225448398097367 0.0604671710778414 0.0304783524734545 0.222759100789325 0.973684987493954 0.0481240911023812 0.0721848715774514 -0.0697254759636464 -0.0333251395230417 0.997009424768599 0.074934687734657 6.90868606470257e-05 3.79251735692414e-05 -4.69308816900823e-06 -1.71755623428216e-06 7.24383482583122e-06 3.75009258029575e-05 3.79251735692414e-05 8.59084116530418e-05 -6.54268742981727e-07 -2.88893566861901e-06 6.55728898083725e-06 1.87832367009616e-05 -4.69308816900823e-06 -6.54268742981727e-07 1.86463389205855e-05 7.45599889765225e-07 8.12019331474558e-07 -3.41202366736116e-06 -1.71755623428216e-06 -2.88893566861901e-06 7.45599889765225e-07 2.19707928939669e-05 1.98102574790474e-06 -2.19598174971032e-06 7.24383482583122e-06 6.55728898083725e-06 8.12019331474558e-07 1.98102574790474e-06 4.24358798284916e-05 2.28828525423239e-06 3.75009258029575e-05 1.87832367009616e-05 -3.41202366736116e-06 -2.19598174971032e-06 2.28828525423239e-06 8.370330730445e-05 210 318 0 0 371 210 318 0 0 366 0 0 0 0 0 0 0 0 1246 0 0 0 0 0 2482 +623 676 0.957833326924247 -0.286173718503901 0.0256889211700056 0.0350177736319401 0.28683017230926 0.957598169628606 -0.0270960841632738 0.128616585184014 -0.0168454767302322 0.0333218901263597 0.999302697660793 0.174655142166179 0.000165708507729458 0.000128180848947909 -1.61673196119984e-05 1.02075403777574e-05 9.65242484754536e-06 0.000153459515317408 0.000128180848947909 0.000165497938669883 -1.08439723050082e-05 9.01857330870212e-06 1.04396994802245e-06 0.000113601080995803 -1.61673196119984e-05 -1.08439723050082e-05 1.98050398416272e-05 6.08412493381057e-07 2.31677636335019e-06 -8.75052032610695e-06 1.02075403777574e-05 9.01857330870212e-06 6.08412493381057e-07 3.93391497301266e-05 -3.82328218263043e-05 1.28418352355535e-05 9.65242484754536e-06 1.04396994802245e-06 2.31677636335019e-06 -3.82328218263043e-05 0.000140634777909647 9.15973469406014e-06 0.000153459515317408 0.000113601080995803 -8.75052032610695e-06 1.28418352355535e-05 9.15973469406014e-06 0.00021946402190656 0 5 0 0 399 0 5 0 0 394 0 0 0 0 0 0 0 0 906 0 0 0 0 0 1940 +623 675 0.957251946965491 -0.286451650212519 0.0401766365105527 0.0327040202394214 0.287823008434255 0.9570845956133 -0.033867280014497 0.133057062191667 -0.0287511016594427 0.0439832801215395 0.998618468296636 0.178726706763066 0.000130860666859839 0.000110895371642754 -4.77556613592597e-06 -1.89974501184451e-05 5.74323843907013e-05 0.00015037873798074 0.000110895371642754 0.000164712397663138 -2.85305764635214e-06 -1.78243140603108e-05 5.96695830192777e-05 0.00015190178641512 -4.77556613592597e-06 -2.85305764635214e-06 1.51269559737177e-05 1.78074717124947e-06 4.17564919233385e-06 3.89139285915667e-06 -1.89974501184451e-05 -1.78243140603108e-05 1.78074717124947e-06 3.75979373893092e-05 -3.06042955474609e-05 -3.048982846913e-05 5.74323843907013e-05 5.96695830192777e-05 4.17564919233385e-06 -3.06042955474609e-05 0.000121843064960433 8.98451654144633e-05 0.00015037873798074 0.00015190178641512 3.89139285915667e-06 -3.048982846913e-05 8.98451654144633e-05 0.000280614758824514 0 7 0 0 402 0 7 0 0 400 0 0 0 0 0 0 0 0 829 0 0 0 0 0 1978 +624 626 0.986636853848938 -0.14721446841028 0.0698256322402356 0.000443866803143479 0.14640660989642 0.989085579356481 0.0165777346972371 0.054469045343414 -0.0715040083191664 -0.0061332699054573 0.997421455451285 0.0302470105116152 8.20367160372802e-05 4.8864209151039e-05 -1.10561922604179e-05 -2.06947797556228e-06 1.04530307091451e-05 5.39685535952443e-05 4.8864209151039e-05 7.87325389691141e-05 -1.09086605375711e-05 4.431702238519e-06 -2.64575293911902e-06 2.4691108236584e-05 -1.10561922604179e-05 -1.09086605375711e-05 1.99920909738639e-05 -1.63062958136102e-07 2.09895350570583e-06 -3.35471006164942e-06 -2.06947797556228e-06 4.431702238519e-06 -1.63062958136102e-07 2.89432793652532e-05 -1.18247636676783e-05 -4.00096232927817e-06 1.04530307091451e-05 -2.64575293911902e-06 2.09895350570583e-06 -1.18247636676783e-05 6.17631562403348e-05 3.6389834568791e-06 5.39685535952443e-05 2.4691108236584e-05 -3.35471006164942e-06 -4.00096232927817e-06 3.6389834568791e-06 0.000110689624768765 444 497 0 0 302 444 497 0 0 303 0 0 0 0 0 0 0 0 1346 0 0 0 0 0 2758 +624 627 0.981348093280725 -0.187996560172052 0.0401648251304681 0.0224826846442986 0.187806813257686 0.982169377860563 0.00848021739033196 0.0704788774671508 -0.0410429130091637 -0.000778817353802903 0.9991570811115 0.0673882982790683 7.60056655736084e-05 4.72201343864446e-05 -3.21566306020074e-06 3.65330986314397e-06 2.47319696325518e-06 4.27859656141104e-05 4.72201343864446e-05 6.2323553367459e-05 -5.31210368071034e-06 9.76571389097485e-08 1.03623474166855e-05 2.24773311224573e-05 -3.21566306020074e-06 -5.31210368071034e-06 1.6747985765615e-05 -8.01923254950777e-07 3.24427667062455e-06 -2.50754543478878e-06 3.65330986314397e-06 9.76571389097485e-08 -8.01923254950777e-07 2.49703317697874e-05 -8.17626369805898e-06 -2.20484479113604e-06 2.47319696325518e-06 1.03623474166855e-05 3.24427667062455e-06 -8.17626369805898e-06 5.57368780585694e-05 1.09042805909288e-05 4.27859656141104e-05 2.24773311224573e-05 -2.50754543478878e-06 -2.20484479113604e-06 1.09042805909288e-05 9.6659377980981e-05 210 318 0 0 320 210 318 0 0 314 0 0 0 0 0 0 0 0 1312 0 0 0 0 0 2563 +625 627 0.993718999895294 -0.110360233570662 -0.0185247967148325 0.0197561407468717 0.110592574884672 0.993793115924151 0.0120218601782755 0.0514133943170577 0.0170830801518665 -0.0139950558411454 0.999756123654428 0.0414852443483675 7.12328642828856e-05 5.46501112312436e-05 3.06582859712768e-06 -7.91845443658866e-06 2.24062773106195e-05 1.31514741890545e-05 5.46501112312436e-05 8.39322099554228e-05 -1.91126218023411e-06 -9.46793417297623e-06 2.51521657575174e-05 7.5242223040472e-07 3.06582859712768e-06 -1.91126218023411e-06 2.01881302294751e-05 -2.16275228928737e-07 9.27671932201469e-06 8.84211266124686e-07 -7.91845443658866e-06 -9.46793417297623e-06 -2.16275228928737e-07 2.39473281445941e-05 -7.57502938298106e-06 -1.45610259831439e-06 2.24062773106195e-05 2.51521657575174e-05 9.27671932201469e-06 -7.57502938298106e-06 5.57938277750274e-05 3.66276598518483e-06 1.31514741890545e-05 7.5242223040472e-07 8.84211266124686e-07 -1.45610259831439e-06 3.66276598518483e-06 4.96182159336327e-05 210 318 0 0 223 210 318 0 0 232 0 0 0 0 0 0 0 0 1373 0 0 0 0 0 2758 +625 628 0.985185969047506 -0.154180562691376 -0.0750796941928876 0.0494987709318841 0.153896447367242 0.988040442633793 -0.00958995348063185 0.0478649961844125 0.0756603587069784 -0.00210661059276757 0.997131421785585 0.0759552083058256 0.000117910029910256 0.000103330580518273 1.42839195879681e-05 -1.19878609257226e-05 5.08369246738168e-05 5.0857671801099e-05 0.000103330580518273 0.000132189609046685 1.158033330225e-05 -8.54202791614339e-06 3.92366945672598e-05 4.14780732888219e-05 1.42839195879681e-05 1.158033330225e-05 2.11789052739356e-05 -1.21664179339942e-06 1.04570105444735e-05 5.03357483335977e-06 -1.19878609257226e-05 -8.54202791614339e-06 -1.21664179339942e-06 2.70738424414449e-05 -1.11738453077169e-05 -1.29556466640483e-05 5.08369246738168e-05 3.92366945672598e-05 1.04570105444735e-05 -1.11738453077169e-05 8.21174686043164e-05 4.11572019085739e-05 5.0857671801099e-05 4.14780732888219e-05 5.03357483335977e-06 -1.29556466640483e-05 4.11572019085739e-05 9.84349144537895e-05 2 126 0 0 280 2 126 0 0 287 0 0 0 0 0 0 0 0 1329 0 0 0 0 0 2587 +624 675 0.967915227207312 -0.251221340434437 0.00528687530993368 0.0277353189525468 0.251021330190751 0.965767660782182 -0.0654302466492143 0.120146819265009 0.0113315810672497 0.0646580505245569 0.997843139863616 0.164002054555064 0.000192177451934548 0.000113204802286353 -1.2372903093606e-05 -2.30550354092235e-05 8.03654901841634e-05 0.000188497381118744 0.000113204802286353 0.000135289837685663 -5.95550963037835e-06 3.04589018062895e-06 1.13874119244194e-05 0.000113010607177464 -1.2372903093606e-05 -5.95550963037835e-06 1.73764461052524e-05 3.60480173824741e-06 -5.22266034512281e-06 -2.53305037296662e-06 -2.30550354092235e-05 3.04589018062895e-06 3.60480173824741e-06 4.40059049996697e-05 -4.62228669926404e-05 -2.43391686685523e-05 8.03654901841634e-05 1.13874119244194e-05 -5.22266034512281e-06 -4.62228669926404e-05 0.000157567446382432 8.19658884468707e-05 0.000188497381118744 0.000113010607177464 -2.53305037296662e-06 -2.43391686685523e-05 8.19658884468707e-05 0.000255698225614352 0 7 0 0 356 0 7 0 0 352 0 0 0 0 0 0 0 0 882 0 0 0 0 0 1990 +625 629 0.977463373851797 -0.174560427347006 -0.118718195668116 0.0580156225450782 0.176830873764452 0.984202042689127 0.008785286008454 0.0627533719015951 0.115309127400926 -0.0295803375738086 0.992889122091211 0.0973433059496082 0.000102677453012315 7.40485996570881e-05 1.54050027666486e-06 2.70066061620981e-06 2.02531432648749e-05 5.62151742269934e-05 7.40485996570881e-05 7.85601964809519e-05 -1.3334304685018e-06 3.78389553521032e-06 9.50097889718402e-06 3.11348835043009e-05 1.54050027666486e-06 -1.3334304685018e-06 2.10118055077538e-05 -2.79958210903142e-07 2.13639572783483e-06 5.37553626286476e-06 2.70066061620981e-06 3.78389553521032e-06 -2.79958210903142e-07 3.29770810368326e-05 -2.59894343570388e-05 -1.19209566711415e-06 2.02531432648749e-05 9.50097889718402e-06 2.13639572783483e-06 -2.59894343570388e-05 0.0001129047865323 2.17678388668984e-05 5.62151742269934e-05 3.11348835043009e-05 5.37553626286476e-06 -1.19209566711415e-06 2.17678388668984e-05 9.64848638160975e-05 0 14 0 0 281 0 14 0 0 287 0 0 0 0 0 0 0 0 1291 0 0 0 0 0 2451 +626 628 0.990569996379531 -0.0813078236773778 -0.110272934492124 0.0419500431750211 0.0805355954047865 0.996686007874638 -0.0114463784540715 0.0218730334142861 0.110838170976665 0.00245754262745214 0.993835429202834 0.0602707254508827 0.000141192359341178 0.000162539000091045 2.34442580867406e-05 -1.54201849128712e-05 5.00429253986132e-05 3.5293274165011e-05 0.000162539000091045 0.000251785141808216 3.39281490932812e-05 -2.56259495183882e-05 8.07924601864262e-05 3.3794211192683e-05 2.34442580867406e-05 3.39281490932812e-05 2.79129914838249e-05 -3.55959357128737e-06 1.22161482999799e-05 5.30541587798689e-06 -1.54201849128712e-05 -2.56259495183882e-05 -3.55959357128737e-06 3.51037011741033e-05 -2.62966863057777e-05 -8.05926923715061e-06 5.00429253986132e-05 8.07924601864262e-05 1.22161482999799e-05 -2.62966863057777e-05 0.000127690080349171 2.90206609250565e-05 3.5293274165011e-05 3.3794211192683e-05 5.30541587798689e-06 -8.05926923715061e-06 2.90206609250565e-05 6.24261515723761e-05 2 126 0 0 143 2 126 0 0 183 0 0 0 0 0 0 0 0 1388 0 0 0 0 0 2744 +626 629 0.985165427065595 -0.104341129553696 -0.136242467674815 0.0377556146383743 0.106024010227195 0.994350312939569 0.00513462874267428 0.0612935035410901 0.134936987405262 -0.019503431504233 0.990662215686836 0.0826071639305986 9.09980615423488e-05 7.54713847579013e-05 9.12270847975287e-06 -1.07373987709685e-06 1.23273701599201e-05 3.45530301884207e-05 7.54713847579013e-05 0.000109636301681064 9.84240638972318e-06 -7.2198670806439e-06 2.56454948118153e-05 1.71975891059329e-05 9.12270847975287e-06 9.84240638972318e-06 2.57969983091201e-05 -2.9540944991929e-06 9.00878539530514e-06 3.41997990901404e-06 -1.07373987709685e-06 -7.2198670806439e-06 -2.9540944991929e-06 2.98507629667815e-05 -9.87309197387311e-06 1.58190458227653e-07 1.23273701599201e-05 2.56454948118153e-05 9.00878539530514e-06 -9.87309197387311e-06 7.12389382731524e-05 4.78273012426865e-06 3.45530301884207e-05 1.71975891059329e-05 3.41997990901404e-06 1.58190458227653e-07 4.78273012426865e-06 7.89646993433864e-05 0 14 0 0 162 0 14 0 0 199 0 0 0 0 0 0 0 0 1346 0 0 0 0 0 2602 +626 630 0.981761237309408 -0.115488492752635 -0.151020796443486 0.0648506971825494 0.12371668313531 0.991239564299483 0.0462418477287388 0.020952696565958 0.144357387170513 -0.0640822456620808 0.987448434380352 0.0895699696668105 4.74008517020434e-05 3.46736087735219e-05 -1.04780904043414e-05 -4.57190613395347e-06 2.5547027954961e-06 1.73478044303578e-05 3.46736087735219e-05 9.50880557627687e-05 -6.00801497056804e-06 -8.61113303889684e-06 1.33896467223442e-05 -3.29113558080608e-07 -1.04780904043414e-05 -6.00801497056804e-06 2.56585241369563e-05 -3.94907773850467e-07 -5.24291097334743e-06 1.94019692556387e-06 -4.57190613395347e-06 -8.61113303889684e-06 -3.94907773850467e-07 3.33280874008534e-05 -2.6667191483502e-05 5.28514797571198e-06 2.5547027954961e-06 1.33896467223442e-05 -5.24291097334743e-06 -2.6667191483502e-05 0.00012436740077068 -9.34351763126325e-06 1.73478044303578e-05 -3.29113558080608e-07 1.94019692556387e-06 5.28514797571198e-06 -9.34351763126325e-06 7.30480668834216e-05 0 0 0 0 126 0 0 0 0 163 0 0 0 0 0 0 0 0 1284 0 0 0 0 0 2232 +627 629 0.99342116395687 -0.0663147891890231 -0.0933634818191369 0.0322064972620275 0.0676726315479663 0.997641875615537 0.0114500199862938 0.0305379235282569 0.0923840134544397 -0.0176928446872951 0.995566249581072 0.0483171860717755 8.51592150074713e-05 4.83115801570215e-05 -3.11413034947437e-06 5.72841065856845e-06 7.18941928737755e-06 3.72795858363364e-05 4.83115801570215e-05 6.67375216235135e-05 -1.38496963136963e-06 6.46225555687449e-06 2.95913949528729e-06 6.9120315038781e-06 -3.11413034947437e-06 -1.38496963136963e-06 2.08371891773716e-05 -1.68626501010043e-06 -2.37119446915621e-06 -5.39761591339754e-06 5.72841065856845e-06 6.46225555687449e-06 -1.68626501010043e-06 2.5483124833593e-05 1.27703731545413e-05 4.5160490206867e-06 7.18941928737755e-06 2.95913949528729e-06 -2.37119446915621e-06 1.27703731545413e-05 3.88889382773619e-05 2.91867656311432e-06 3.72795858363364e-05 6.9120315038781e-06 -5.39761591339754e-06 4.5160490206867e-06 2.91867656311432e-06 7.63659192406283e-05 0 14 0 0 69 0 14 0 0 127 0 0 0 0 0 0 0 0 1380 0 0 0 0 0 2524 +627 630 0.990926346418505 -0.0782686932214851 -0.10926567455095 0.0341548397667078 0.0812623657831438 0.996422402051753 0.023212595648492 0.0297907583596564 0.107057946370176 -0.0318811598097515 0.993741509532628 0.0804876043400722 7.77903684920046e-05 8.02405799508492e-05 -6.83575479570417e-06 -5.5772547522265e-06 7.38184459349423e-06 1.03682846022305e-05 8.02405799508492e-05 0.000118582689813052 -6.97471859124158e-06 -1.72858101339352e-06 1.07027915501159e-05 1.29568349049181e-05 -6.83575479570417e-06 -6.97471859124158e-06 2.38088790098877e-05 -5.37873989484977e-06 -2.47629645511492e-06 2.39795076971571e-06 -5.5772547522265e-06 -1.72858101339352e-06 -5.37873989484977e-06 2.89947057407361e-05 4.57323483832307e-06 1.35750746864834e-07 7.38184459349423e-06 1.07027915501159e-05 -2.47629645511492e-06 4.57323483832307e-06 6.35601814267442e-05 -5.69406695594011e-06 1.03682846022305e-05 1.29568349049181e-05 2.39795076971571e-06 1.35750746864834e-07 -5.69406695594011e-06 6.36669341878036e-05 0 0 0 0 75 0 0 0 0 105 0 0 0 0 0 0 0 0 1310 0 0 0 0 0 2263 +626 673 0.991718809155533 -0.111174578412181 -0.0642963193503802 0.0202524320246012 0.105616430645134 0.990835544573092 -0.0842026910990744 0.0822645398514616 0.0730682772816901 0.0767146447910584 0.994372108483373 0.146955923075547 7.86174557799907e-05 5.54232928074146e-05 -7.80183365448183e-06 -3.11854203870371e-06 3.4973242135996e-05 4.12824767358291e-05 5.54232928074146e-05 0.00011233588843026 7.62781047356196e-07 -1.18272547419282e-05 3.53600982915854e-05 2.54791269186806e-05 -7.80183365448183e-06 7.62781047356196e-07 1.96695659009058e-05 6.2189133788287e-07 -6.40071834619302e-06 -1.93743667411752e-06 -3.11854203870371e-06 -1.18272547419282e-05 6.2189133788287e-07 5.2960803638409e-05 -5.82772270289691e-05 -4.70521117483941e-06 3.4973242135996e-05 3.53600982915854e-05 -6.40071834619302e-06 -5.82772270289691e-05 0.000207413147636834 2.33976925202398e-05 4.12824767358291e-05 2.54791269186806e-05 -1.93743667411752e-06 -4.70521117483941e-06 2.33976925202398e-05 7.66685651844566e-05 0 11 0 0 156 0 11 0 0 198 0 0 0 0 0 0 0 0 1044 0 0 0 0 0 2266 +627 631 0.988517120937991 -0.0921335086389687 -0.119771942450381 0.0344478410052214 0.0976687101060413 0.994366471075241 0.0411842720901286 0.0351943529118567 0.115302752259807 -0.0524093292004846 0.99194684209088 0.0772720220090147 0.000443099414260702 5.3102999890768e-05 4.97192848209458e-05 -2.83803359592141e-05 9.37124432635125e-05 0.000306401720468909 5.3102999890768e-05 0.000200097687883565 1.44643901309727e-05 3.43180932427857e-05 -2.42501675336843e-05 -5.37840012749437e-05 4.97192848209458e-05 1.44643901309727e-05 3.67033099302402e-05 -6.56789230999586e-06 -1.57086886561954e-06 2.51937687947116e-05 -2.83803359592141e-05 3.43180932427857e-05 -6.56789230999586e-06 4.22117247036803e-05 -9.12299160830287e-06 -3.62985541434424e-05 9.37124432635125e-05 -2.42501675336843e-05 -1.57086886561954e-06 -9.12299160830287e-06 9.25597293015627e-05 7.10490671751512e-05 0.000306401720468909 -5.37840012749437e-05 2.51937687947116e-05 -3.62985541434424e-05 7.10490671751512e-05 0.000319474854464168 0 0 0 0 64 0 0 0 0 97 0 0 0 0 0 0 0 0 1367 0 0 0 0 0 2011 +627 674 0.997141097956096 -0.0693329585849521 -0.0300428297729796 0.00669619258918321 0.0668606872016531 0.994811456885466 -0.0766799436380766 0.0643503489334918 0.0352033986119751 0.0744520389463795 0.996603037634791 0.110601189401207 9.74614795519963e-05 5.97596553336228e-05 -1.49941756423152e-05 1.65555058309013e-05 1.68920225461365e-05 6.81941015941639e-05 5.97596553336228e-05 0.000107557573540719 -4.90349889106903e-06 2.75738397608378e-06 3.02276083642037e-05 3.73462859670167e-05 -1.49941756423152e-05 -4.90349889106903e-06 1.88473063639152e-05 -2.43664393929692e-06 -2.84082069058557e-06 -7.74998775164519e-06 1.65555058309013e-05 2.75738397608378e-06 -2.43664393929692e-06 3.5375245908977e-05 -2.05983650854733e-05 1.45986898099703e-05 1.68920225461365e-05 3.02276083642037e-05 -2.84082069058557e-06 -2.05983650854733e-05 0.000108384226237511 7.40619899367968e-06 6.81941015941639e-05 3.73462859670167e-05 -7.74998775164519e-06 1.45986898099703e-05 7.40619899367968e-06 0.000102438586964344 0 3 0 0 71 0 3 0 0 108 0 0 0 0 0 0 0 0 1000 0 0 0 0 0 2282 +627 673 0.997307861950108 -0.0687086046027884 -0.0256155450076985 0.00783716991678109 0.0664547341052272 0.994548878310603 -0.0803510856561646 0.0642133366713213 0.0309967225284755 0.0784324952086725 0.996437427482446 0.113866524149561 7.11240021608025e-05 2.48155859823937e-05 -1.62211959903313e-05 1.030677305216e-05 9.15100173101248e-06 4.24549870602927e-05 2.48155859823937e-05 0.000107000846790229 -3.8007210300724e-06 -2.68204852667471e-06 2.05016614679064e-05 7.66168114853743e-06 -1.62211959903313e-05 -3.8007210300724e-06 2.02852476294692e-05 -5.26125109922914e-06 -4.11299569866466e-06 -5.71573729844834e-06 1.030677305216e-05 -2.68204852667471e-06 -5.26125109922914e-06 3.00871319574837e-05 -5.54967211184243e-06 3.35899088449313e-06 9.15100173101248e-06 2.05016614679064e-05 -4.11299569866466e-06 -5.54967211184243e-06 7.88117797790041e-05 8.10173668512339e-06 4.24549870602927e-05 7.66168114853743e-06 -5.71573729844834e-06 3.35899088449313e-06 8.10173668512339e-06 6.78128235006245e-05 0 11 0 0 70 0 11 0 0 123 0 0 0 0 0 0 0 0 1072 0 0 0 0 0 2252 +627 671 0.997324871749168 -0.0694791239620498 -0.0227101634510112 0.00116968822291812 0.0673032113624526 0.994057293223151 -0.0855591931364681 0.0752518932659877 0.0285197813947891 0.0838018443909711 0.9960742306404 0.121983673444277 7.28122629194464e-05 4.88872819862e-05 -1.49793555434308e-05 4.01714528739892e-06 2.60719327396158e-05 3.89458392086176e-05 4.88872819862e-05 8.98806457735832e-05 -1.030410279189e-05 -3.92174811260275e-06 2.91303316331146e-05 1.11124266902471e-05 -1.49793555434308e-05 -1.030410279189e-05 2.11870635983971e-05 -3.02845388327163e-06 -4.10310901240682e-06 -7.59149378667942e-06 4.01714528739892e-06 -3.92174811260275e-06 -3.02845388327163e-06 3.32491692239996e-05 -1.5227852189074e-05 5.61908206922658e-06 2.60719327396158e-05 2.91303316331146e-05 -4.10310901240682e-06 -1.5227852189074e-05 8.43821577073757e-05 1.02474847366949e-05 3.89458392086176e-05 1.11124266902471e-05 -7.59149378667942e-06 5.61908206922658e-06 1.02474847366949e-05 6.53814278444027e-05 0 8 0 0 73 0 8 0 0 125 0 0 0 0 0 0 0 0 1006 0 0 0 0 0 2248 +627 672 0.996964830369314 -0.0683928989118674 -0.0371959458155961 0.00224354871135775 0.0652207785051108 0.994603830497573 -0.0806812890994113 0.0747266301641121 0.0425132574366272 0.0780104591576451 0.996045677267936 0.116225856707867 8.26308173618117e-05 5.65856180679524e-05 -7.80664941948084e-06 9.2425336173207e-06 7.49879783104199e-06 4.28713570443167e-05 5.65856180679524e-05 0.000123077456350456 -1.18153249152752e-06 7.44212856574655e-08 1.54615763482581e-05 2.10033192144763e-05 -7.80664941948084e-06 -1.18153249152752e-06 2.02160179792736e-05 -2.38396062628218e-06 -1.38821271366437e-06 -4.44965819538186e-06 9.2425336173207e-06 7.44212856574655e-08 -2.38396062628218e-06 3.17167985092194e-05 -7.0322724134086e-06 3.68934216848965e-06 7.49879783104199e-06 1.54615763482581e-05 -1.38821271366437e-06 -7.0322724134086e-06 6.82384790205077e-05 -1.40710532250691e-06 4.28713570443167e-05 2.10033192144763e-05 -4.44965819538186e-06 3.68934216848965e-06 -1.40710532250691e-06 7.65000564749275e-05 0 8 0 0 74 0 8 0 0 120 0 0 0 0 0 0 0 0 1094 0 0 0 0 0 2208 +628 630 0.997672710540925 -0.037598762127392 -0.0568814181294035 0.00977844295126024 0.0400335389556477 0.99830307462338 0.0422881420281397 0.0264936016040893 0.0551949128145962 -0.0444668897494896 0.997484945909158 0.0463503388654877 5.4652040259463e-05 4.59007512348976e-05 -1.04365580278093e-05 -3.59142131796478e-06 5.56544218007173e-06 2.47166036332617e-05 4.59007512348976e-05 0.000104177663799961 -7.04475641076647e-06 -5.82018563313429e-06 1.62289930852119e-05 2.17778375806751e-05 -1.04365580278093e-05 -7.04475641076647e-06 2.83060024502071e-05 -7.03045983530302e-07 -5.00159310902748e-06 -1.71815981159103e-06 -3.59142131796478e-06 -5.82018563313429e-06 -7.03045983530302e-07 2.50681841298217e-05 -9.02059936156566e-06 3.71050656189187e-06 5.56544218007173e-06 1.62289930852119e-05 -5.00159310902748e-06 -9.02059936156566e-06 7.81419226179955e-05 3.71228233902309e-07 2.47166036332617e-05 2.17778375806751e-05 -1.71815981159103e-06 3.71050656189187e-06 3.71228233902309e-07 9.38127409870337e-05 0 0 0 0 0 0 0 0 0 70 0 0 0 0 0 0 0 0 1397 0 0 0 0 0 2311 +628 631 0.99690799675476 -0.0534707556174898 -0.0575788528898108 0.0113610428109514 0.0561311820839175 0.997380471848219 0.0456232920084263 0.0377328493278539 0.0549885115662707 -0.0487141937172187 0.997297944912255 0.0496609380604563 0.000123892654963795 0.000115393818979199 7.9636850910073e-06 1.21787335917104e-06 2.10075658584357e-05 5.27471092736069e-05 0.000115393818979199 0.00016716118838113 9.55796908376808e-06 1.00651870740324e-05 -2.04657829947613e-06 4.24986818076829e-05 7.9636850910073e-06 9.55796908376808e-06 2.64280041619178e-05 -4.15764388441889e-06 5.04265862531079e-08 -5.0737867987617e-06 1.21787335917104e-06 1.00651870740324e-05 -4.15764388441889e-06 2.62516127277727e-05 -8.06310124634853e-06 5.37814120655544e-07 2.10075658584357e-05 -2.04657829947613e-06 5.04265862531079e-08 -8.06310124634853e-06 7.6698904284823e-05 1.48402851820127e-07 5.27471092736069e-05 4.24986818076829e-05 -5.0737867987617e-06 5.37814120655544e-07 1.48402851820127e-07 0.000108659910420822 0 0 0 0 0 0 0 0 0 65 0 0 0 0 0 0 0 0 1403 0 0 0 0 0 2076 +628 632 0.995531056961483 -0.066070012008072 -0.0674734624753041 0.0191517825729086 0.0694060722896637 0.996415863081301 0.04835519547338 0.0417653752238241 0.064036800001835 -0.052822166873388 0.996548597376126 0.0519448836846306 6.00178290442103e-05 5.40093938392605e-05 -8.53343880294674e-06 3.00910680402384e-06 1.81271451853149e-06 1.72654333730106e-05 5.40093938392605e-05 9.52336617626464e-05 -5.68817426980002e-06 6.03993658287886e-06 5.90458294596213e-06 1.14297479132145e-05 -8.53343880294674e-06 -5.68817426980002e-06 2.32056015494932e-05 -5.56700819961126e-06 -4.49491796472475e-06 -5.61026734476837e-06 3.00910680402384e-06 6.03993658287886e-06 -5.56700819961126e-06 2.5783611461288e-05 6.63476930665157e-07 6.73481539581856e-06 1.81271451853149e-06 5.90458294596213e-06 -4.49491796472475e-06 6.63476930665157e-07 5.18073230386216e-05 -1.09065666266718e-05 1.72654333730106e-05 1.14297479132145e-05 -5.61026734476837e-06 6.73481539581856e-06 -1.09065666266718e-05 6.39695245137783e-05 0 0 0 0 0 0 0 0 0 28 0 0 0 0 0 0 0 0 1391 0 0 0 0 0 2025 +627 670 0.997338619257097 -0.0691107442379939 -0.0232246328112402 0.00333940751190773 0.0669089610952688 0.994131263765424 -0.0850071839864836 0.0739414859988812 0.0289632433180081 0.0832270114507944 0.996109630061607 0.12163509361637 8.42090099967042e-05 5.39252321032196e-05 -1.00931293512986e-05 -5.1002397053139e-06 3.75225088406502e-05 5.25875638390745e-05 5.39252321032196e-05 9.56074584128188e-05 -9.67151939725243e-06 -9.53093069375989e-06 4.50462127275015e-05 2.06916419640239e-05 -1.00931293512986e-05 -9.67151939725243e-06 2.09133265159802e-05 -8.90862272183113e-07 -6.90571485499884e-06 -6.33388351692792e-06 -5.1002397053139e-06 -9.53093069375989e-06 -8.90862272183113e-07 3.10922330966168e-05 -1.16501747675121e-05 -4.69469408337804e-06 3.75225088406502e-05 4.50462127275015e-05 -6.90571485499884e-06 -1.16501747675121e-05 0.000104861753273157 2.91591392689775e-05 5.25875638390745e-05 2.06916419640239e-05 -6.33388351692792e-06 -4.69469408337804e-06 2.91591392689775e-05 7.77282653439612e-05 0 4 0 0 78 0 4 0 0 125 0 0 0 0 0 0 0 0 1132 0 0 0 0 0 2168 +628 675 0.998969879170197 -0.0220809948930156 0.0396435388836057 0.00224744646075532 0.0248584607461146 0.997167012417554 -0.0709930015958167 0.0366058866610908 -0.0379636331245472 0.0719053475812778 0.996688709452054 0.0800886129896705 6.9849364369869e-05 4.42005687282453e-05 -1.36287113372857e-05 8.4689997858864e-07 1.30495787589216e-05 4.68340959562497e-05 4.42005687282453e-05 9.32186136395701e-05 -5.42193885772565e-06 5.54671959911713e-06 -5.07562964862587e-06 2.30683078564979e-05 -1.36287113372857e-05 -5.42193885772565e-06 2.42251813152858e-05 -5.11066494374858e-06 -6.44118684901235e-06 -5.31220121600701e-07 8.4689997858864e-07 5.54671959911713e-06 -5.11066494374858e-06 3.3708341910648e-05 -7.98990215289736e-06 8.31519350429963e-07 1.30495787589216e-05 -5.07562964862587e-06 -6.44118684901235e-06 -7.98990215289736e-06 7.56369167174738e-05 5.27485470962362e-06 4.68340959562497e-05 2.30683078564979e-05 -5.31220121600701e-07 8.31519350429963e-07 5.27485470962362e-06 7.8050861211041e-05 0 0 0 0 0 0 7 0 0 56 0 0 0 0 0 0 0 0 1029 0 0 0 0 0 2345 +628 673 0.999305468774076 -0.0216100359058727 0.030357641976448 -0.00390265724442289 0.0239147809129791 0.996687531596509 -0.0777306092472015 0.0453689953846685 -0.0285773219897792 0.0784026192687707 0.996512100257538 0.0911101979880825 9.03128498426932e-05 6.39507499420239e-05 -8.94211062853378e-06 -2.1257713449532e-06 4.02144050978635e-05 5.19347749244555e-05 6.39507499420239e-05 0.000135501094142511 -1.17842836194042e-05 -2.58540367101926e-06 3.62781491631656e-05 2.79547432984388e-05 -8.94211062853378e-06 -1.17842836194042e-05 2.48227277754423e-05 -6.5489083901466e-06 -3.62903983309783e-06 -6.61467001656236e-07 -2.1257713449532e-06 -2.58540367101926e-06 -6.5489083901466e-06 3.49508580679544e-05 -1.52078202466787e-05 -6.74872051830489e-06 4.02144050978635e-05 3.62781491631656e-05 -3.62903983309783e-06 -1.52078202466787e-05 9.31438273135486e-05 2.16591214013216e-05 5.19347749244555e-05 2.79547432984388e-05 -6.61467001656236e-07 -6.74872051830489e-06 2.16591214013216e-05 7.83470384269517e-05 0 0 0 0 0 0 11 0 0 56 0 0 0 0 0 0 0 0 1081 0 0 0 0 0 2268 +628 672 0.999326090130134 -0.0223013147872761 0.0291550500596029 -0.00677437252970642 0.0242920524197286 0.997264340287114 -0.0698121177228106 0.0537431610506812 -0.0275183897504249 0.0704733066519887 0.997134018713171 0.0833691954393759 0.000120874845243953 4.09096013748342e-05 -1.82214626233472e-05 9.70683668861193e-06 2.69568072676219e-05 9.28435439082046e-05 4.09096013748342e-05 0.000177791085349428 -3.95232945011455e-06 6.88768278560081e-06 1.54587070396334e-05 8.12152210825277e-06 -1.82214626233472e-05 -3.95232945011455e-06 2.50830371464365e-05 -4.378380423117e-06 -3.64113049010224e-06 -1.11262834239382e-05 9.70683668861193e-06 6.88768278560081e-06 -4.378380423117e-06 2.89450287588258e-05 -7.3949342340294e-06 3.93553043718508e-06 2.69568072676219e-05 1.54587070396334e-05 -3.64113049010224e-06 -7.3949342340294e-06 8.24625838512691e-05 2.03038619735663e-05 9.28435439082046e-05 8.12152210825277e-06 -1.11262834239382e-05 3.93553043718508e-06 2.03038619735663e-05 0.000120725515222996 0 0 0 0 0 0 8 0 0 61 0 0 0 0 0 0 0 0 1090 0 0 0 0 0 2267 +628 670 0.998621939776358 -0.0232534673335695 0.0470478230555984 -0.000512767169751763 0.0265627247035105 0.997123877394883 -0.0709816510467339 0.042873306040814 -0.0452619382442885 0.0721335524285433 0.996367456092585 0.0839917054741178 7.78375650658048e-05 4.82767064672862e-05 -1.45627294257768e-05 1.25259171114735e-06 3.09405445072381e-05 4.70324780191392e-05 4.82767064672862e-05 8.31761311998469e-05 -1.43178493218973e-05 -6.19618761523093e-07 3.39091249249746e-05 1.80655026237689e-05 -1.45627294257768e-05 -1.43178493218973e-05 2.41834786652475e-05 -2.3515959537336e-06 -9.08802191701162e-06 -1.35006006659877e-05 1.25259171114735e-06 -6.19618761523093e-07 -2.3515959537336e-06 2.80231889804369e-05 -1.68916468064339e-05 -6.13628243550605e-06 3.09405445072381e-05 3.39091249249746e-05 -9.08802191701162e-06 -1.68916468064339e-05 0.000103851511713396 2.57610819608418e-05 4.70324780191392e-05 1.80655026237689e-05 -1.35006006659877e-05 -6.13628243550605e-06 2.57610819608418e-05 7.65174136787065e-05 0 0 0 0 0 0 4 0 0 63 0 0 0 0 0 0 0 0 1143 0 0 0 0 0 2277 +628 674 0.999309026641899 -0.022090935324637 0.0298907987264095 -0.00242054988267795 0.0241366183788192 0.997261650825557 -0.069904387887451 0.0422910886811211 -0.0282646939706636 0.0705775486197039 0.997105770069343 0.0825271953894385 7.9557404701331e-05 7.292655128209e-05 -8.07811692635541e-06 1.63438885107428e-06 2.23999245694435e-05 3.81194957597057e-05 7.292655128209e-05 0.000153460621309995 8.40563571019885e-08 -3.83836677335525e-07 2.29157856552625e-05 3.70663492442824e-05 -8.07811692635541e-06 8.40563571019885e-08 2.1259460945063e-05 -4.48176052870181e-06 -5.67760044650844e-06 -3.87973965856719e-07 1.63438885107428e-06 -3.83836677335525e-07 -4.48176052870181e-06 3.11835815131873e-05 -1.37985497716793e-05 -4.31674610004716e-06 2.23999245694435e-05 2.29157856552625e-05 -5.67760044650844e-06 -1.37985497716793e-05 9.10054634607309e-05 9.89391618286481e-06 3.81194957597057e-05 3.70663492442824e-05 -3.87973965856719e-07 -4.31674610004716e-06 9.89391618286481e-06 6.96263248550263e-05 0 0 0 0 0 0 3 0 0 49 0 0 0 0 0 0 0 0 1018 0 0 0 0 0 2294 +628 671 0.998899577119116 -0.0223330354273471 0.0412416095691113 -0.00494146622331835 0.0252996830662791 0.997020372377573 -0.0728718265232224 0.0499216934837569 -0.0394912758466472 0.0738350363491862 0.996488247065322 0.0863253361369234 7.19932434151762e-05 5.64181107988508e-05 -1.841898076378e-05 1.19086952678785e-05 5.65909110337388e-06 3.41468490332366e-05 5.64181107988508e-05 0.000118500729105226 -1.93169474101706e-05 1.79265940671767e-05 1.14460603059994e-06 3.87730915793631e-06 -1.841898076378e-05 -1.93169474101706e-05 2.77665739091497e-05 -1.07564215777749e-05 2.94635105098131e-06 -5.28827611428652e-06 1.19086952678785e-05 1.79265940671767e-05 -1.07564215777749e-05 3.80630119911955e-05 -2.88172848713214e-05 1.98118706290836e-06 5.65909110337388e-06 1.14460603059994e-06 2.94635105098131e-06 -2.88172848713214e-05 0.000108297759891101 -2.47015533122786e-06 3.41468490332366e-05 3.87730915793631e-06 -5.28827611428652e-06 1.98118706290836e-06 -2.47015533122786e-06 6.80212862541039e-05 0 0 0 0 0 0 8 0 0 60 0 0 0 0 0 0 0 0 1021 0 0 0 0 0 2290 +628 665 0.999353926478052 -0.0232238476440154 -0.0274295922956944 -0.0160763358096083 0.0204772224018416 0.995123559290659 -0.0964872276904887 0.0479861720742699 0.0295366381906604 0.0958632079856409 0.994956196201167 0.115868127768633 0.00148536259561182 -0.00481440177253515 3.19154592164345e-05 -0.00010907609035115 -0.000277399133401512 0.00178012539618323 -0.00481440177253515 0.0264801581391627 -7.87407994564671e-05 0.000908555610523872 0.00233820892595802 -0.00542207920177108 3.19154592164345e-05 -7.87407994564671e-05 3.32348170573621e-05 8.8185046704793e-06 -4.72795260888661e-06 5.719678107417e-05 -0.00010907609035115 0.000908555610523872 8.8185046704793e-06 9.04405067000668e-05 8.16198408128613e-05 -0.000108650294605197 -0.000277399133401512 0.00233820892595802 -4.72795260888661e-06 8.16198408128613e-05 0.000319891151122588 -0.000269543651808459 0.00178012539618323 -0.00542207920177108 5.719678107417e-05 -0.000108650294605197 -0.000269543651808459 0.00235613329884254 0 0 0 0 0 0 5 0 0 60 0 0 0 0 0 0 0 0 1102 0 0 0 0 0 2175 +628 666 0.998371938479773 -0.024600394033955 0.0514615688598226 -0.0051178773556398 0.0280017597820912 0.997396498125424 -0.0664539462804638 0.0556230204412943 -0.0496927953052168 0.0677867696568797 0.996461529590701 0.0793049704610983 0.000105849034475207 5.35393287691864e-05 -1.17367837790123e-05 1.41604011908091e-06 1.50121557454122e-05 7.82089244501758e-05 5.35393287691864e-05 9.17696274755153e-05 -8.5963716994201e-06 1.11704031619826e-05 8.78441305673167e-06 9.88883356585393e-06 -1.17367837790123e-05 -8.5963716994201e-06 1.94787049939478e-05 -9.2430281995883e-07 -4.82980781892241e-07 -9.92018918333692e-06 1.41604011908091e-06 1.11704031619826e-05 -9.2430281995883e-07 3.92672208936455e-05 -3.45817674364997e-05 -4.33037665691106e-06 1.50121557454122e-05 8.78441305673167e-06 -4.82980781892241e-07 -3.45817674364997e-05 0.000148688055614619 1.71784818471791e-05 7.82089244501758e-05 9.88883356585393e-06 -9.92018918333692e-06 -4.33037665691106e-06 1.71784818471791e-05 0.000127532334438146 0 0 0 0 0 0 4 0 0 67 0 0 0 0 0 0 0 0 804 0 0 0 0 0 2205 +628 669 0.998732772452291 -0.0235824882265342 0.0444602685417702 -0.00296592590830713 0.0266442398523932 0.997220508221479 -0.0695797561448982 0.0500402798841318 -0.0426958278107954 0.0706761928200772 0.996585140394944 0.0828643636033346 9.27715327451295e-05 5.98974975768872e-05 -1.11325379250617e-05 -3.50611238226689e-06 3.56171755711042e-05 4.97683503696042e-05 5.98974975768872e-05 8.19370513379454e-05 -1.03403449172194e-05 4.60140863642938e-06 1.49963403032864e-05 1.53797089509744e-05 -1.11325379250617e-05 -1.03403449172194e-05 2.50572182048403e-05 -4.67361089200758e-06 -4.28960235515388e-06 -5.06465440315638e-06 -3.50611238226689e-06 4.60140863642938e-06 -4.67361089200758e-06 3.03157498994226e-05 -1.75726034252747e-05 -6.70753053680615e-06 3.56171755711042e-05 1.49963403032864e-05 -4.28960235515388e-06 -1.75726034252747e-05 9.51678807988332e-05 2.97467835328076e-05 4.97683503696042e-05 1.53797089509744e-05 -5.06465440315638e-06 -6.70753053680615e-06 2.97467835328076e-05 8.40800163534282e-05 0 0 0 0 0 0 1 0 0 53 0 0 0 0 0 0 0 0 1126 0 0 0 0 0 2380 +629 633 0.995635827354928 -0.0328110581488026 -0.0873655180859358 0.0136460963922591 0.033736746419335 0.999388961235757 0.00913980859490525 0.026522845935544 0.0870122475764508 -0.0120473492217132 0.996134393617861 0.0443518922105044 8.1042206072044e-05 4.41989747142744e-05 -1.2338096206359e-05 2.06261259947632e-06 9.49560278772445e-07 1.79638582346728e-05 4.41989747142744e-05 9.00652422894325e-05 -9.52380654141338e-06 8.86228052459707e-06 -6.112271175724e-06 -1.28103945883576e-05 -1.2338096206359e-05 -9.52380654141338e-06 2.89861252915373e-05 -7.76585309675023e-06 -5.58595264733642e-06 -8.08550011315809e-06 2.06261259947632e-06 8.86228052459707e-06 -7.76585309675023e-06 2.09158873968243e-05 1.17928231789764e-07 3.77325759206162e-06 9.49560278772445e-07 -6.112271175724e-06 -5.58595264733642e-06 1.17928231789764e-07 4.35486022433875e-05 -7.18214226850634e-06 1.79638582346728e-05 -1.28103945883576e-05 -8.08550011315809e-06 3.77325759206162e-06 -7.18214226850634e-06 7.1096316542903e-05 0 0 0 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 1461 0 0 0 0 0 1974 +628 667 0.998911972162307 -0.0231255233588117 0.0404979263690206 -0.0138605087094487 0.0263411770534004 0.996385513726474 -0.0807592126476738 0.0684334656762992 -0.0384839481115305 0.081738107424945 0.995910572055713 0.0958708354863104 0.000230838504958913 0.000118234878929462 -1.99707892500202e-05 1.46589022067795e-05 1.92382412041366e-05 0.000182823123014099 0.000118234878929462 0.000192504779704695 -1.40325282547928e-05 2.15161192255816e-05 9.97368571279592e-06 6.37982508510599e-05 -1.99707892500202e-05 -1.40325282547928e-05 2.415609344176e-05 -4.70938613061448e-06 -1.68382072472008e-06 -1.21258137728016e-05 1.46589022067795e-05 2.15161192255816e-05 -4.70938613061448e-06 3.47094100828812e-05 -9.76548404701292e-06 3.2802107019806e-06 1.92382412041366e-05 9.97368571279592e-06 -1.68382072472008e-06 -9.76548404701292e-06 8.35775752404985e-05 2.67376246938827e-05 0.000182823123014099 6.37982508510599e-05 -1.21258137728016e-05 3.2802107019806e-06 2.67376246938827e-05 0.00022127634677583 0 0 0 0 0 0 8 0 0 71 0 0 0 0 0 0 0 0 909 0 0 0 0 0 2117 +628 668 0.998330312721733 -0.0239292176559086 0.0525735603065243 0.00218020424899799 0.0274386644720807 0.997370335781423 -0.0670785583867153 0.0424585336865706 -0.0508301720724628 0.0684091064524859 0.996361624994387 0.0785731193378861 5.60827631975006e-05 4.24019198327996e-05 -7.01067694919091e-06 6.01627189516032e-07 1.14475822673149e-05 2.08396176304048e-05 4.24019198327996e-05 9.33685974435629e-05 -4.64388258219609e-06 2.83243552755557e-06 1.11108503814353e-05 -2.8899554127822e-06 -7.01067694919091e-06 -4.64388258219609e-06 2.14222950064575e-05 -3.29801423344918e-06 -3.29879517027628e-06 -4.69332271884015e-06 6.01627189516032e-07 2.83243552755557e-06 -3.29801423344918e-06 2.78845604943039e-05 -8.26030443605184e-06 4.42224777970795e-06 1.14475822673149e-05 1.11108503814353e-05 -3.29879517027628e-06 -8.26030443605184e-06 7.01126004175032e-05 1.12297015113871e-05 2.08396176304048e-05 -2.8899554127822e-06 -4.69332271884015e-06 4.42224777970795e-06 1.12297015113871e-05 6.0201520046149e-05 0 0 0 0 0 0 1 0 0 51 0 0 0 0 0 0 0 0 1079 0 0 0 0 0 2307 +629 676 0.996770023771865 0.00408920237991382 0.0802047263802516 -0.0100175227520661 0.00360561740060739 0.995417058486304 -0.0955608664550205 0.0306909124435128 -0.0802279205326635 0.0955413946850785 0.992187140951058 0.0613628444741962 6.75895194483629e-05 4.27600194317101e-05 -1.66363093711902e-05 5.84610277009526e-06 1.45955786612e-06 3.59366311587254e-05 4.27600194317101e-05 9.07952943035515e-05 -1.16111436739791e-05 6.52911694920877e-06 3.45705334686993e-06 8.19360333421949e-06 -1.66363093711902e-05 -1.16111436739791e-05 2.24870587058753e-05 -5.39731745917992e-06 -1.48779438808656e-06 -6.29429534115054e-06 5.84610277009526e-06 6.52911694920877e-06 -5.39731745917992e-06 3.16474014646809e-05 -2.02333669432439e-05 5.38849608608928e-06 1.45955786612e-06 3.45705334686993e-06 -1.48779438808656e-06 -2.02333669432439e-05 9.47527933667362e-05 2.05177001823433e-07 3.59366311587254e-05 8.19360333421949e-06 -6.29429534115054e-06 5.38849608608928e-06 2.05177001823433e-07 7.39651269690245e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1041 0 0 0 0 0 2301 +629 631 0.999373834622665 -0.0314993140456005 -0.0161161994975806 0.00487156871514241 0.0319027310939411 0.999167698886148 0.0254189939082362 0.008135697768364 0.015302105094949 -0.0259172281931518 0.999546968812595 0.0307518792447772 7.70074457931805e-05 5.45998051647354e-05 -7.94272936590856e-07 8.20362630064837e-06 -5.38799111079762e-06 3.00957126953027e-05 5.45998051647354e-05 0.000113156098659204 -8.33736277181067e-07 1.54108026993768e-05 -1.06843569862065e-05 -5.15868334683904e-06 -7.94272936590856e-07 -8.33736277181067e-07 2.25967045116229e-05 -2.36526211236762e-06 -3.98072282224529e-06 -7.06293637315943e-06 8.20362630064837e-06 1.54108026993768e-05 -2.36526211236762e-06 2.06072148933554e-05 -3.56723684201935e-06 5.28392252995033e-06 -5.38799111079762e-06 -1.06843569862065e-05 -3.98072282224529e-06 -3.56723684201935e-06 4.62996681189363e-05 -1.12944294826972e-05 3.00957126953027e-05 -5.15868334683904e-06 -7.06293637315943e-06 5.28392252995033e-06 -1.12944294826972e-05 9.01963865701927e-05 0 0 0 0 0 0 0 0 0 9 0 0 0 0 0 0 0 0 1408 0 0 0 0 0 2072 +629 632 0.998471655278469 -0.0414206528053063 -0.0365880188949418 0.0107966042340652 0.0425318764634382 0.998640579081082 0.030133590843131 0.01643566135595 0.0352901273725838 -0.0316436934283067 0.998876010111486 0.0268237347480031 4.82533854553647e-05 4.74474974079676e-05 -6.84876554128891e-06 2.28782097308803e-06 6.95594697758566e-06 2.05125412489334e-05 4.74474974079676e-05 7.39704661699674e-05 -1.11265302465878e-05 5.23256782624397e-06 8.31948202777479e-06 2.14365319088784e-05 -6.84876554128891e-06 -1.11265302465878e-05 1.854432005003e-05 -4.62196735723054e-06 -6.37195915221841e-06 -8.63735647767112e-06 2.28782097308803e-06 5.23256782624397e-06 -4.62196735723054e-06 1.83220594538055e-05 -4.66129412035926e-06 3.37758883024443e-06 6.95594697758566e-06 8.31948202777479e-06 -6.37195915221841e-06 -4.66129412035926e-06 5.61727015059943e-05 1.08088013712998e-05 2.05125412489334e-05 2.14365319088784e-05 -8.63735647767112e-06 3.37758883024443e-06 1.08088013712998e-05 7.72192020499872e-05 0 0 0 0 0 0 0 0 0 7 0 0 0 0 0 0 0 0 1416 0 0 0 0 0 2107 +629 675 0.997706633633513 0.00450592715031458 0.0675364333097319 -0.00988596242032686 0.00173056020429069 0.995757434800434 -0.0920007402200573 0.0237126263630959 -0.0676644542212758 0.0919066246805703 0.993466000412073 0.05431588903134 6.06665601708477e-05 5.51530970708527e-05 -1.10218885156585e-05 -2.6621614235271e-06 2.5345743112412e-05 3.45612052674932e-05 5.51530970708527e-05 0.000136373050905184 -6.68346432266241e-06 -2.03091599860071e-06 4.43146023868858e-05 2.02016794967446e-05 -1.10218885156585e-05 -6.68346432266241e-06 1.83915616508786e-05 -2.73486982268878e-06 -7.53792236007962e-07 -8.20414962365868e-07 -2.6621614235271e-06 -2.03091599860071e-06 -2.73486982268878e-06 3.34631317166523e-05 -2.70591928529407e-05 -4.59455486453305e-06 2.5345743112412e-05 4.43146023868858e-05 -7.53792236007962e-07 -2.70591928529407e-05 0.000121152798617081 1.31134644329088e-05 3.45612052674932e-05 2.02016794967446e-05 -8.20414962365868e-07 -4.59455486453305e-06 1.31134644329088e-05 8.21890002785676e-05 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 984 0 0 0 0 0 2367 +629 673 0.997792291891658 0.00516895277353731 0.0662104536219015 -0.0112800572124266 0.00131558454377183 0.995232479213019 -0.0975222105820766 0.0310989203401978 -0.0663988816088134 0.0973940154564522 0.993028496204599 0.0619907015517448 6.66101682777402e-05 5.25031572294778e-05 -1.28733622980226e-05 9.07675727316293e-06 1.17860699789847e-05 3.62364716365372e-05 5.25031572294778e-05 0.00018009724234635 -1.10814333460796e-05 2.99966304742095e-05 -5.41464285700283e-06 2.5147545737004e-05 -1.28733622980226e-05 -1.10814333460796e-05 2.24450786359713e-05 -4.23177086334203e-06 -2.28002491108196e-06 -3.64619439791702e-06 9.07675727316293e-06 2.99966304742095e-05 -4.23177086334203e-06 4.02247855632529e-05 -2.00029673687062e-05 3.32928136998752e-06 1.17860699789847e-05 -5.41464285700283e-06 -2.28002491108196e-06 -2.00029673687062e-05 9.81471565433742e-05 3.76065775414608e-06 3.62364716365372e-05 2.5147545737004e-05 -3.64619439791702e-06 3.32928136998752e-06 3.76065775414608e-06 7.44785607289871e-05 0 0 0 0 0 0 8 0 0 0 0 0 0 0 0 0 0 0 1052 0 0 0 0 0 2292 +629 671 0.996718297841945 0.00478431777807873 0.080806837894162 -0.00851174380700269 0.00274851151278635 0.995676074925595 -0.0928525686517385 0.0295898490878411 -0.0809016713765488 0.0927699527010771 0.992395412849294 0.0570432207049088 0.000127466057037138 9.26825589093727e-05 -1.73286779352162e-05 -5.20111024110482e-06 4.77010578529779e-05 9.7078373963658e-05 9.26825589093727e-05 0.00011326051755825 -1.80335338831521e-05 9.53831606467545e-07 3.29310618554691e-05 6.56922919914338e-05 -1.73286779352162e-05 -1.80335338831521e-05 1.95482108521727e-05 -3.15409584861169e-07 -7.10802711986611e-06 -1.00536645916044e-05 -5.20111024110482e-06 9.53831606467545e-07 -3.15409584861169e-07 2.56563101481557e-05 -1.39060049504792e-05 -8.2965853955711e-06 4.77010578529779e-05 3.29310618554691e-05 -7.10802711986611e-06 -1.39060049504792e-05 8.78221742296891e-05 3.74467420254797e-05 9.7078373963658e-05 6.56922919914338e-05 -1.00536645916044e-05 -8.2965853955711e-06 3.74467420254797e-05 0.00013619411599329 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 977 0 0 0 0 0 2326 +629 668 0.996366919575352 0.00397623074878949 0.085071447413077 -0.0089305780884679 0.00432393600239111 0.995259306954262 -0.0971607713965296 0.0327355636286279 -0.0850544834407379 0.0971756219941701 0.99162625688143 0.061353831502626 5.57954399305526e-05 4.07128905393999e-05 -8.78097600110416e-06 1.07736111187946e-05 -1.98724973910369e-07 2.70582293481652e-05 4.07128905393999e-05 7.93152673113358e-05 -7.67749245010927e-06 1.24740018743872e-05 -1.72441056079342e-06 1.08362874271498e-05 -8.78097600110416e-06 -7.67749245010927e-06 1.6029778618792e-05 -2.08927463944385e-07 -3.00099214384665e-07 -8.49181939371614e-06 1.07736111187946e-05 1.24740018743872e-05 -2.08927463944385e-07 2.93818658758683e-05 -1.83263014655002e-05 1.13933952017659e-05 -1.98724973910369e-07 -1.72441056079342e-06 -3.00099214384665e-07 -1.83263014655002e-05 8.1126964168279e-05 -2.84445611834744e-06 2.70582293481652e-05 1.08362874271498e-05 -8.49181939371614e-06 1.13933952017659e-05 -2.84445611834744e-06 7.17730239652285e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 993 0 0 0 0 0 2276 +629 667 0.997330983244668 0.00370225169582014 0.0729191551830142 -0.0131864823009264 0.00316233537404347 0.995586053217405 -0.0937998415455649 0.0300230872317647 -0.0729445645350343 0.0937800830207129 0.992917109598491 0.0579850018321456 0.000261146997771346 0.000154377470189999 -2.13611869220793e-05 2.26993571593679e-05 -2.44419757954089e-05 0.000268478401056416 0.000154377470189999 0.000180672391638438 -1.20814903042647e-05 1.54296556567747e-05 -5.47747481509188e-06 0.000125241241325302 -2.13611869220793e-05 -1.20814903042647e-05 1.91660451112962e-05 -2.99759900529593e-06 -5.74301936618002e-07 -2.02572215711633e-05 2.26993571593679e-05 1.54296556567747e-05 -2.99759900529593e-06 4.14303886510405e-05 -4.1493656877905e-05 2.9325367747544e-05 -2.44419757954089e-05 -5.47747481509188e-06 -5.74301936618002e-07 -4.1493656877905e-05 0.000143437087370803 -4.75590404522539e-05 0.000268478401056416 0.000125241241325302 -2.02572215711633e-05 2.9325367747544e-05 -4.75590404522539e-05 0.00039373821488077 0 0 0 0 0 0 7 0 0 0 0 0 0 0 0 0 0 0 901 0 0 0 0 0 2194 +629 674 0.997825865279895 0.00519961943203586 0.0657001258460839 -0.0090626374851148 0.000742196338719696 0.995933170197056 -0.0900920065590567 0.0238375067085417 -0.0659013787642114 0.0899448967924491 0.993764018174321 0.0519007837268034 4.89126724080358e-05 3.13776496087249e-05 -1.08565699906578e-05 4.64781782557131e-06 1.33357356123301e-05 2.38494674984506e-05 3.13776496087249e-05 0.000108327247820397 -3.56430499694801e-06 4.5523406485276e-06 2.34283708628362e-05 2.73547334444327e-05 -1.08565699906578e-05 -3.56430499694801e-06 1.98302064208185e-05 -4.60355393850649e-06 -1.33115539004325e-06 -4.40802466242577e-06 4.64781782557131e-06 4.5523406485276e-06 -4.60355393850649e-06 3.31537438151105e-05 -1.74569804948078e-05 3.98389527227964e-07 1.33357356123301e-05 2.34283708628362e-05 -1.33115539004325e-06 -1.74569804948078e-05 8.89967280452117e-05 5.8639717126506e-06 2.38494674984506e-05 2.73547334444327e-05 -4.40802466242577e-06 3.98389527227964e-07 5.8639717126506e-06 7.2898218761805e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 991 0 0 0 0 0 2346 +629 672 0.998391982551107 0.00507550989464854 0.0564596172230971 -0.017409040274775 0.000232397654286411 0.995608813601107 -0.0936110905348612 0.0421029824525484 -0.0566868165361189 0.0934736833504759 0.994006677719972 0.0594108008525154 0.000185183795679863 0.000114745462490059 -2.56966040226274e-05 2.30065731145968e-05 1.83111434344123e-05 0.000113809742258051 0.000114745462490059 0.000219882785325669 -1.41992262577548e-05 3.34623130266993e-05 6.81702423661897e-07 5.20114340873675e-05 -2.56966040226274e-05 -1.41992262577548e-05 2.06545361344586e-05 -4.92488278295183e-06 -1.61814898837876e-06 -1.64675494019114e-05 2.30065731145968e-05 3.34623130266993e-05 -4.92488278295183e-06 3.64506887311005e-05 -1.62248669956553e-05 1.62313182316469e-05 1.83111434344123e-05 6.81702423661897e-07 -1.61814898837876e-06 -1.62248669956553e-05 8.34503902765315e-05 9.4851130924491e-07 0.000113809742258051 5.20114340873675e-05 -1.64675494019114e-05 1.62313182316469e-05 9.4851130924491e-07 0.000135620641194145 0 0 0 0 0 0 6 0 0 1 0 0 0 0 0 0 0 0 1043 0 0 0 0 0 2277 +629 666 0.996327124306734 0.00289511785871071 0.0855796685157039 -0.0137918198494894 0.00479770138280471 0.995970904968142 -0.0895485260536566 0.040712631896674 -0.0854941134354583 0.0896302111429241 0.99229893772913 0.0525964831921147 6.51930844059509e-05 5.49822652456115e-05 -6.87704600117733e-06 1.75110258761235e-06 9.54852155335715e-06 4.1040151604218e-05 5.49822652456115e-05 8.37535085789272e-05 -1.10225650564948e-05 5.29705272485735e-06 2.08060612880372e-05 2.40988775473477e-05 -6.87704600117733e-06 -1.10225650564948e-05 1.57088207887654e-05 -4.30745846109117e-07 -1.23605119230176e-06 -6.52767395497083e-06 1.75110258761235e-06 5.29705272485735e-06 -4.30745846109117e-07 3.33243553039569e-05 -2.38421693663787e-05 2.81021277256802e-06 9.54852155335715e-06 2.08060612880372e-05 -1.23605119230176e-06 -2.38421693663787e-05 0.000112238182042702 4.10102444522809e-06 4.1040151604218e-05 2.40988775473477e-05 -6.52767395497083e-06 2.81021277256802e-06 4.10102444522809e-06 9.4535921905027e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 790 0 0 0 0 0 2249 +629 670 0.996008390137192 0.00360079540084391 0.0891870004473771 -0.00606199893827975 0.00480409541710324 0.995575199549977 -0.093845312659962 0.0260329119857965 -0.0891302835378782 0.0938991816444846 0.991583953199604 0.0573444005493637 9.71394815404445e-05 6.31716975613631e-05 -1.84032609821796e-05 2.04480263130331e-06 2.4617750636046e-05 6.98184162671679e-05 6.31716975613631e-05 9.52328851569513e-05 -1.81446922040588e-05 9.354919550722e-07 2.92239760075663e-05 3.65642354021026e-05 -1.84032609821796e-05 -1.81446922040588e-05 2.19308809098361e-05 -1.22229787919305e-06 -5.57222055967402e-06 -1.3866162125231e-05 2.04480263130331e-06 9.354919550722e-07 -1.22229787919305e-06 2.8380281945953e-05 -1.6751465974131e-05 -1.5560697782449e-06 2.4617750636046e-05 2.92239760075663e-05 -5.57222055967402e-06 -1.6751465974131e-05 8.88783669295934e-05 1.6394295087752e-05 6.98184162671679e-05 3.65642354021026e-05 -1.3866162125231e-05 -1.5560697782449e-06 1.6394295087752e-05 0.000113351441212145 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1079 0 0 0 0 0 2284 +629 669 0.996616245860971 0.00437062717054427 0.0820789626160173 -0.0100667249576365 0.00347225185347109 0.995455198498985 -0.0951677006573792 0.0331298921562076 -0.0821218725617696 0.0951306753864524 0.992071646932552 0.0625983714199735 0.000135669789590989 6.93745284167254e-05 -2.25380870441753e-05 -1.95858951931573e-06 4.799902885179e-05 0.000105276347759508 6.93745284167254e-05 9.35886484617278e-05 -1.34065993250417e-05 1.28627411305749e-05 5.20271949454938e-06 2.22892453672789e-05 -2.25380870441753e-05 -1.34065993250417e-05 1.94030424673226e-05 -1.18063162224422e-06 -6.96080992700716e-06 -2.1734911897167e-05 -1.95858951931573e-06 1.28627411305749e-05 -1.18063162224422e-06 3.50743552194609e-05 -2.55842280619289e-05 -8.72431856138466e-06 4.799902885179e-05 5.20271949454938e-06 -6.96080992700716e-06 -2.55842280619289e-05 9.59421744461587e-05 5.15226841493368e-05 0.000105276347759508 2.22892453672789e-05 -2.1734911897167e-05 -8.72431856138466e-06 5.15226841493368e-05 0.0001654203114011 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1062 0 0 0 0 0 2366 +630 632 0.999493691070508 -0.0272183843159892 -0.0164778962698121 0.00949671351117624 0.027242939560101 0.999628038639057 0.00126752150139353 0.0167807765762866 0.0164372672417364 -0.00171578607609516 0.999863426835768 0.00725032833504576 5.63020707485818e-05 5.34316396576678e-05 -4.29164596674396e-06 5.80161617795692e-06 -5.70170928979436e-06 8.83081326650338e-06 5.34316396576678e-05 8.48344096896126e-05 -4.56413019092783e-06 1.15374775477627e-05 -1.21943424217212e-05 1.21185036385273e-05 -4.29164596674396e-06 -4.56413019092783e-06 1.6638470917688e-05 -4.82938572680593e-06 -9.5192087212979e-07 -1.26369502864308e-06 5.80161617795692e-06 1.15374775477627e-05 -4.82938572680593e-06 1.97557826984838e-05 3.13961125242465e-07 8.13986472857445e-06 -5.70170928979436e-06 -1.21943424217212e-05 -9.5192087212979e-07 3.13961125242465e-07 3.51052173292757e-05 -2.05357093124125e-05 8.83081326650338e-06 1.21185036385273e-05 -1.26369502864308e-06 8.13986472857445e-06 -2.05357093124125e-05 6.1071111152429e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1483 0 0 0 0 0 2119 +629 665 0.996375151722393 0.0046658864663284 0.0849398995388041 -0.0115541805205239 0.00347591129658392 0.995427760474467 -0.095454134103476 0.040311068752033 -0.0849969121253066 0.0954033709062182 0.991803267663952 0.0626075688324308 0.000166796936760942 0.000122871155542854 -1.77200984421313e-05 5.2061348208146e-07 2.548016872426e-05 0.000117799422917653 0.000122871155542854 0.000146889180338355 -1.38239073759017e-05 2.29507451658344e-06 2.05825107727108e-05 7.72618791448615e-05 -1.77200984421313e-05 -1.38239073759017e-05 2.20810071351377e-05 -3.85947941489129e-06 -7.59633450546386e-07 -1.21635492908257e-05 5.2061348208146e-07 2.29507451658344e-06 -3.85947941489129e-06 2.6660147648351e-05 -1.01581336702458e-05 1.55002980252678e-06 2.548016872426e-05 2.05825107727108e-05 -7.59633450546386e-07 -1.01581336702458e-05 7.30419988468951e-05 1.11026845144196e-05 0.000117799422917653 7.72618791448615e-05 -1.21635492908257e-05 1.55002980252678e-06 1.11026845144196e-05 0.000162884636064898 0 0 0 0 0 0 5 0 0 1 0 0 0 0 0 0 0 0 1108 0 0 0 0 0 2265 +629 664 0.996295263411029 0.00428438034361698 0.0858917469249479 -0.00888425887996145 0.00464647259816312 0.994617651567284 -0.103509117874584 0.0357405568734439 -0.0858729200455102 0.103524737506798 0.99091294790562 0.0742566332266125 5.67906123536001e-05 4.42042748274513e-05 -3.04648357785458e-06 6.75043424269237e-06 -5.08988959764075e-06 2.27613556920604e-05 4.42042748274513e-05 6.97836390993367e-05 -8.71821575931e-06 4.81155709712684e-06 4.54414259149508e-06 1.46300598226832e-05 -3.04648357785458e-06 -8.71821575931e-06 2.21454410957102e-05 -1.29748573110051e-06 -7.01607234510979e-07 -7.18396324354089e-06 6.75043424269237e-06 4.81155709712684e-06 -1.29748573110051e-06 2.61740939595895e-05 -8.48346678676746e-06 3.94296880729123e-06 -5.08988959764075e-06 4.54414259149508e-06 -7.01607234510979e-07 -8.48346678676746e-06 7.90548452050218e-05 -2.91185473979096e-06 2.27613556920604e-05 1.46300598226832e-05 -7.18396324354089e-06 3.94296880729123e-06 -2.91185473979096e-06 6.09310102869322e-05 0 0 0 0 0 0 4 0 0 1 0 0 0 0 0 0 0 0 1138 0 0 0 0 0 2280 +630 633 0.997101651562062 -0.0154814062799142 -0.0744890764596062 0.0157926309744743 0.0138168013139679 0.999644321803203 -0.0228106529512939 0.0191521996338274 0.074815723305059 0.0217153389614409 0.996960907759241 0.0321374420484389 5.81136843681196e-05 3.94358437542774e-05 -4.62756538198923e-06 -8.80640510893144e-07 4.63056061782402e-06 3.5514661570127e-06 3.94358437542774e-05 8.68298130336038e-05 -4.97402338325072e-06 7.29679298069168e-06 3.92137119562695e-06 -2.6017608188196e-06 -4.62756538198923e-06 -4.97402338325072e-06 2.27566637966618e-05 -1.99210856477049e-06 -2.90310620745797e-06 -2.12037634778666e-06 -8.80640510893144e-07 7.29679298069168e-06 -1.99210856477049e-06 2.24396204236346e-05 2.92917873186323e-06 4.32096899063727e-06 4.63056061782402e-06 3.92137119562695e-06 -2.90310620745797e-06 2.92917873186323e-06 4.11202987175104e-05 -1.18870820842743e-05 3.5514661570127e-06 -2.6017608188196e-06 -2.12037634778666e-06 4.32096899063727e-06 -1.18870820842743e-05 5.68681505266138e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1500 0 0 0 0 0 2036 +630 676 0.995970575288894 0.0225661026543357 0.0867950699619739 -0.0130057982335207 -0.0112642564726694 0.991637530696469 -0.128561752634003 0.0282581904116417 -0.0889703865610794 0.127066040802422 0.987895992293708 0.0471019525756403 0.000192542832640675 0.000182701332082567 -3.68795812533349e-05 1.93245738775492e-05 3.37917833065707e-05 0.000159757558986612 0.000182701332082567 0.000258051250583668 -3.35970052688923e-05 1.58356060337012e-05 5.30113759952009e-05 0.000129014572745305 -3.68795812533349e-05 -3.35970052688923e-05 3.13267290494923e-05 -5.56274435616026e-06 -1.27592702739518e-05 -2.24225725903734e-05 1.93245738775492e-05 1.58356060337012e-05 -5.56274435616026e-06 3.38876229581638e-05 -2.31153005154022e-05 2.08440455865738e-05 3.37917833065707e-05 5.30113759952009e-05 -1.27592702739518e-05 -2.31153005154022e-05 0.000122058566953088 7.51494628194814e-06 0.000159757558986612 0.000129014572745305 -2.24225725903734e-05 2.08440455865738e-05 7.51494628194814e-06 0.000188277258760101 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1027 0 0 0 0 0 2143 +629 663 0.996422209915735 0.00354896795518316 0.084440419309102 -0.0112505743668589 0.00411332722255635 0.995897467863317 -0.0903953209109459 0.0372452703402806 -0.0844148098724629 0.0904192365035549 0.992319757711349 0.0560920072861128 0.000143152667024281 8.27389048144948e-05 -1.87205970139009e-05 -1.2404708886341e-05 5.61682226274228e-05 0.000134459862676036 8.27389048144948e-05 0.000121896371160646 -1.50099607533875e-05 -6.42458055614914e-06 5.37542333357834e-05 5.15606141664391e-05 -1.87205970139009e-05 -1.50099607533875e-05 2.00182642143764e-05 -7.45216356905199e-08 -5.07330714427616e-06 -1.66051872717534e-05 -1.2404708886341e-05 -6.42458055614914e-06 -7.45216356905199e-08 3.4688382337813e-05 -3.0253389078748e-05 -2.07390048887086e-05 5.61682226274228e-05 5.37542333357834e-05 -5.07330714427616e-06 -3.0253389078748e-05 0.000125182180098257 6.99980547064704e-05 0.000134459862676036 5.15606141664391e-05 -1.66051872717534e-05 -2.07390048887086e-05 6.99980547064704e-05 0.00021161753054822 0 0 0 0 0 0 3 0 0 1 0 0 0 0 0 0 0 0 1146 0 0 0 0 0 2307 +630 634 0.995874301678175 -0.00520551790423155 -0.0905940276196882 0.0157338463659812 0.00300821096845078 0.999698381487917 -0.0243740993107169 0.0179465745310386 0.0906935825942354 0.024001013182533 0.995589586849137 0.0313533872359874 8.91453355589863e-05 2.26739908088727e-05 -9.65274475743112e-06 1.22188608224439e-05 4.85484311174408e-06 4.40814049801521e-05 2.26739908088727e-05 0.000114152091818385 -9.17009491266611e-07 1.88355578989486e-05 1.21620160354313e-05 -2.97385591286647e-05 -9.65274475743112e-06 -9.17009491266611e-07 2.51955332033996e-05 -5.10906856028482e-06 -6.47490374913613e-07 -1.26299117501799e-05 1.22188608224439e-05 1.88355578989486e-05 -5.10906856028482e-06 2.80073220266692e-05 1.36078782506901e-06 4.91370925249774e-06 4.85484311174408e-06 1.21620160354313e-05 -6.47490374913613e-07 1.36078782506901e-06 5.02662573721092e-05 -1.07369898751214e-05 4.40814049801521e-05 -2.97385591286647e-05 -1.26299117501799e-05 4.91370925249774e-06 -1.07369898751214e-05 0.000105913122370752 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1540 0 0 0 0 0 2047 +630 674 0.997138287297487 0.0216582198428284 0.0724303632372083 -0.0110713985110685 -0.0124715867001696 0.99208345056568 -0.124959540007449 0.01701725738794 -0.0745633658750353 0.123698620149672 0.989514505119785 0.0385327443506144 0.00015760290743346 0.000135559702340767 -2.91414305263553e-05 -2.68164776480762e-07 7.34799900892972e-05 0.000130623177259369 0.000135559702340767 0.000237205766591998 -1.83737668901895e-05 2.87639949591602e-06 7.48148381487065e-05 0.000117565164129182 -2.91414305263553e-05 -1.83737668901895e-05 2.73838632356129e-05 -5.08281334361714e-06 -1.5539883533124e-05 -1.1999399761716e-05 -2.68164776480762e-07 2.87639949591602e-06 -5.08281334361714e-06 3.76656215324566e-05 -3.59279513451614e-05 -3.17860576299374e-06 7.34799900892972e-05 7.48148381487065e-05 -1.5539883533124e-05 -3.59279513451614e-05 0.000160970401493339 4.50200095036825e-05 0.000130623177259369 0.000117565164129182 -1.1999399761716e-05 -3.17860576299374e-06 4.50200095036825e-05 0.000175706810058551 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 953 0 0 0 0 0 2168 +630 672 0.997300624761556 0.0222841114780763 0.069963434920271 -0.0168672369168513 -0.0132736270623447 0.991851596141284 -0.126705256625751 0.0315798714459078 -0.0722168586607041 0.125434563050303 0.989470007487624 0.04410068839775 0.000148201840470472 8.88838056229312e-05 -3.17434834660511e-05 -6.64730868415721e-06 5.97451933905759e-05 0.000112511164620401 8.88838056229312e-05 0.000159497041207132 -2.1760377306183e-05 5.65275168021232e-06 4.35768254043824e-05 4.98218124692605e-05 -3.17434834660511e-05 -2.1760377306183e-05 2.70495799324685e-05 -3.31293530457461e-06 -9.03590905771168e-06 -1.88663928031664e-05 -6.64730868415721e-06 5.65275168021232e-06 -3.31293530457461e-06 3.5908229104984e-05 -2.17137483788247e-05 -7.56752687259625e-06 5.97451933905759e-05 4.35768254043824e-05 -9.03590905771168e-06 -2.17137483788247e-05 0.00011596823876594 4.46541362595142e-05 0.000112511164620401 4.98218124692605e-05 -1.88663928031664e-05 -7.56752687259625e-06 4.46541362595142e-05 0.000160608553147378 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1076 0 0 0 0 0 2157 +630 675 0.996468378326797 0.0217670750529692 0.0810984922079461 -0.0118449937077306 -0.0112175006512745 0.991667370599352 -0.128335473535988 0.0212550867552058 -0.0832162164118422 0.126972518807048 0.988409348799318 0.0435394852113932 0.0001500423306611 0.000138182333991924 -1.89744943495921e-05 -1.43697378916699e-06 6.0829549580751e-05 0.000122836769407506 0.000138182333991924 0.000186085827270052 -1.45858310861233e-05 -1.24340385673787e-06 6.28721432396935e-05 0.000112076595794315 -1.89744943495921e-05 -1.45858310861233e-05 2.86103151774226e-05 -5.95843334439701e-06 -4.66340003781596e-06 -5.07603928641611e-06 -1.43697378916699e-06 -1.24340385673787e-06 -5.95843334439701e-06 3.42597260006339e-05 -1.99272603213099e-05 -6.95781834948111e-06 6.0829549580751e-05 6.28721432396935e-05 -4.66340003781596e-06 -1.99272603213099e-05 9.92131002457893e-05 5.22793049892347e-05 0.000122836769407506 0.000112076595794315 -5.07603928641611e-06 -6.95781834948111e-06 5.22793049892347e-05 0.000153464365891668 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 961 0 0 0 0 0 2212 +630 669 0.995394822651359 0.0222859129092222 0.0932334978678398 -0.0167938360435681 -0.00935261872203504 0.990538007823131 -0.136919624527766 0.0401189478843082 -0.0954027020681813 0.135417108016626 0.986184836272848 0.057128154434482 9.21394634828545e-05 7.24347800714019e-05 -2.69662050194307e-05 1.19715598289686e-05 1.34947837238799e-05 7.19828844219557e-05 7.24347800714019e-05 0.000154890618428813 -2.53241744810025e-05 1.46535110021617e-05 1.69084095702298e-05 4.34778648318706e-05 -2.69662050194307e-05 -2.53241744810025e-05 2.71542893605571e-05 -8.43130721900889e-06 -4.51999149159564e-06 -1.56177438954342e-05 1.19715598289686e-05 1.46535110021617e-05 -8.43130721900889e-06 2.69607640909752e-05 -6.17255849765355e-06 9.62955922407141e-06 1.34947837238799e-05 1.69084095702298e-05 -4.51999149159564e-06 -6.17255849765355e-06 6.15568690124372e-05 3.55256172677489e-06 7.19828844219557e-05 4.34778648318706e-05 -1.56177438954342e-05 9.62955922407141e-06 3.55256172677489e-06 0.000119425495748992 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1092 0 0 0 0 0 2194 +630 673 0.99731400076035 0.0212586452018487 0.0700917533777375 -0.0138715922694204 -0.0126017412871206 0.992485465635451 -0.121711941151698 0.0222552185286812 -0.0721524774620812 0.120501744827882 0.990087546376339 0.0340400177999143 0.000153057850270645 9.62074339798743e-05 -3.59262526951038e-05 2.00593445361343e-05 2.3875731981036e-05 0.000135022674408277 9.62074339798743e-05 0.000126301042828833 -2.3538034768996e-05 2.00665894444677e-05 6.0993081751431e-06 9.26255582249164e-05 -3.59262526951038e-05 -2.3538034768996e-05 3.00708199504699e-05 -8.55543928151709e-06 -9.24938418961678e-06 -2.18932296474447e-05 2.00593445361343e-05 2.00665894444677e-05 -8.55543928151709e-06 3.35201226441621e-05 -6.51048329226394e-06 1.42146575437101e-05 2.3875731981036e-05 6.0993081751431e-06 -9.24938418961678e-06 -6.51048329226394e-06 7.00682049683599e-05 1.37250267651872e-05 0.000135022674408277 9.26255582249164e-05 -2.18932296474447e-05 1.42146575437101e-05 1.37250267651872e-05 0.000191574073183161 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1009 0 0 0 0 0 2190 +630 668 0.995527462751633 0.0214396605592736 0.0920076728452527 -0.0135426673791283 -0.00931511470340738 0.991439322261359 -0.130235551643936 0.0327275954296256 -0.0940122308285379 0.128796006261999 0.987204785860361 0.0477799745653329 0.000193966487744429 0.000162874128492948 -1.83040936976224e-05 7.28557627156601e-06 1.26818522221618e-05 0.000133128333825931 0.000162874128492948 0.000233826500345858 -1.36834880563201e-05 1.42297325724539e-05 1.01483532992544e-05 8.82045377391144e-05 -1.83040936976224e-05 -1.36834880563201e-05 2.46891570357306e-05 -2.49092091763035e-06 -1.00065514467902e-06 -8.38954897677366e-06 7.28557627156601e-06 1.42297325724539e-05 -2.49092091763035e-06 3.66238978376616e-05 -3.09036221774262e-05 -3.09204107398029e-06 1.26818522221618e-05 1.01483532992544e-05 -1.00065514467902e-06 -3.09036221774262e-05 0.000116984651141251 1.30837827899647e-05 0.000133128333825931 8.82045377391144e-05 -8.38954897677366e-06 -3.09204107398029e-06 1.30837827899647e-05 0.000152449633866596 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1036 0 0 0 0 0 2137 +630 671 0.995265124099146 0.0228247974308083 0.0944794230198019 -0.0154411531798351 -0.00961930814137517 0.99039489205252 -0.137932689044905 0.0365084379908086 -0.0967202236494177 0.136370768196559 0.985925053905563 0.0587545681977845 7.6040606311645e-05 5.07277105157531e-05 -2.1269309755155e-05 3.96995216208726e-07 2.95694082045417e-05 5.45637844683693e-05 5.07277105157531e-05 0.000112710411880052 -1.29585636094479e-05 -1.81914709678407e-07 2.52250408428979e-05 2.60976130584267e-05 -2.1269309755155e-05 -1.29585636094479e-05 2.47970573936301e-05 -4.04198388350294e-06 -5.56436307270756e-06 -1.2692638346072e-05 3.96995216208726e-07 -1.81914709678407e-07 -4.04198388350294e-06 2.28704069952548e-05 -9.93288697366099e-06 -2.85917882093004e-06 2.95694082045417e-05 2.52250408428979e-05 -5.56436307270756e-06 -9.93288697366099e-06 7.29401934801265e-05 1.99198333518077e-05 5.45637844683693e-05 2.60976130584267e-05 -1.2692638346072e-05 -2.85917882093004e-06 1.99198333518077e-05 8.92205840275641e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 988 0 0 0 0 0 2139 +630 670 0.994612006922408 0.0221457576011517 0.101274483983142 -0.0149045189654078 -0.00810622205676808 0.990539122522953 -0.136991006695422 0.0378081488966345 -0.103350108126441 0.135431946643803 0.985381623016445 0.0582301354853807 0.000139636429498648 8.5284611873525e-05 -2.78657475573517e-05 4.52203305407147e-06 2.51813784756309e-05 0.00010996784311778 8.5284611873525e-05 0.000131122744883247 -1.51404823172541e-05 1.67502762251667e-06 2.15987797069112e-05 5.0005689886221e-05 -2.78657475573517e-05 -1.51404823172541e-05 2.59852913615534e-05 -5.26724573628736e-06 -6.62114416907057e-06 -1.86817388752525e-05 4.52203305407147e-06 1.67502762251667e-06 -5.26724573628736e-06 2.25683669826019e-05 -1.68501933228673e-06 -1.03025561048097e-06 2.51813784756309e-05 2.15987797069112e-05 -6.62114416907057e-06 -1.68501933228673e-06 4.9437220403514e-05 1.52419772919043e-05 0.00010996784311778 5.0005689886221e-05 -1.86817388752525e-05 -1.03025561048097e-06 1.52419772919043e-05 0.000142317936195457 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1102 0 0 0 0 0 2131 +630 666 0.994945229993532 0.0202310976244545 0.0983600122103901 -0.0141035030887959 -0.00804122831775385 0.992401158343618 -0.122781430051079 0.0359983366738302 -0.100096593150117 0.121369862845585 0.987547481609155 0.0388551903240684 0.000483056527025301 0.000122856086971618 -5.03239327602615e-05 -6.93440296638438e-05 0.00013103241241481 0.000552311667620383 0.000122856086971618 0.000194923611486817 -1.37897028257757e-05 2.44270387806859e-06 1.51360092087146e-05 9.82420286986554e-05 -5.03239327602615e-05 -1.37897028257757e-05 2.38973576041699e-05 7.73992183201838e-06 -1.55135133935859e-05 -5.39700976438426e-05 -6.93440296638438e-05 2.44270387806859e-06 7.73992183201838e-06 3.92265127759659e-05 -2.78408391656697e-05 -8.80279533221589e-05 0.00013103241241481 1.51360092087146e-05 -1.55135133935859e-05 -2.78408391656697e-05 0.000101332688532291 0.000160007063797003 0.000552311667620383 9.82420286986554e-05 -5.39700976438426e-05 -8.80279533221589e-05 0.000160007063797003 0.000726885854418087 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 791 0 0 0 0 0 2128 +630 665 0.995156786764022 0.0226164097659028 0.0956633041809038 -0.0138043193180034 -0.00974876314850473 0.991082179229882 -0.132894979702104 0.0346836472363534 -0.0978158032967153 0.131318742082953 0.986502638923571 0.0512648791430841 0.000190525071574377 8.95986169938349e-05 -3.98791337534734e-05 6.00658282560035e-06 9.96785723292435e-06 0.000171128423666735 8.95986169938349e-05 0.000228872066150823 -1.67349912229077e-05 8.40676755729462e-06 3.22071793617796e-05 5.2270690061967e-05 -3.98791337534734e-05 -1.67349912229077e-05 3.07515707397519e-05 -3.26213607995041e-06 -6.33017144540253e-06 -2.56243160105643e-05 6.00658282560035e-06 8.40676755729462e-06 -3.26213607995041e-06 2.529905386731e-05 -4.45721004071186e-06 4.47171584121992e-06 9.96785723292435e-06 3.22071793617796e-05 -6.33017144540253e-06 -4.45721004071186e-06 7.47564270545124e-05 -4.61923931753358e-06 0.000171128423666735 5.2270690061967e-05 -2.56243160105643e-05 4.47171584121992e-06 -4.61923931753358e-06 0.000218699097727576 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1125 0 0 0 0 0 2134 +630 664 0.995177115134696 0.0225300512177373 0.0954720184363502 -0.0129817575317026 -0.00936774850148289 0.990646488590916 -0.136131480306731 0.0330235369053474 -0.0976460690463145 0.134580575993027 0.986079770487757 0.0560066878640359 0.000203324139436855 9.70351669352661e-05 -2.17022193342758e-05 -1.55225187974649e-05 4.77926974966022e-05 0.000182104311198554 9.70351669352661e-05 0.000138738623513639 -7.20302503313215e-06 7.00658897041115e-06 1.09158743856272e-05 7.14434208815918e-05 -2.17022193342758e-05 -7.20302503313215e-06 2.24875734223471e-05 1.25737407322543e-06 -6.34893586521058e-06 -1.69253116328955e-05 -1.55225187974649e-05 7.00658897041115e-06 1.25737407322543e-06 2.62273161666007e-05 -9.17276371538484e-06 -1.56409386257702e-05 4.77926974966022e-05 1.09158743856272e-05 -6.34893586521058e-06 -9.17276371538484e-06 6.30836599353501e-05 4.86567780917526e-05 0.000182104311198554 7.14434208815918e-05 -1.69253116328955e-05 -1.56409386257702e-05 4.86567780917526e-05 0.000227996283495926 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1182 0 0 0 0 0 2130 +630 667 0.996349508783922 0.0212674938473819 0.0826761758397659 -0.0214733656051602 -0.0105650433142083 0.991744573992714 -0.127793113334715 0.0442424183816667 -0.0847114880391392 0.126453128318212 0.988348911130443 0.0457916473544113 0.00010188795572575 6.77744713669199e-05 -2.26427228071528e-05 2.97628641940058e-06 1.67837353006326e-05 8.58445893435052e-05 6.77744713669199e-05 0.000157503273290727 -1.54428625537733e-05 3.00342200487415e-06 4.16788099304447e-05 3.7857068094991e-05 -2.26427228071528e-05 -1.54428625537733e-05 2.44206104030333e-05 -5.86624765128552e-06 -5.17186959939304e-06 -1.50253129469059e-05 2.97628641940058e-06 3.00342200487415e-06 -5.86624765128552e-06 3.41921167483662e-05 -2.43841096176216e-05 3.4056056862215e-06 1.67837353006326e-05 4.16788099304447e-05 -5.17186959939304e-06 -2.43841096176216e-05 0.000121969881890473 4.56633069240184e-06 8.58445893435052e-05 3.7857068094991e-05 -1.50253129469059e-05 3.4056056862215e-06 4.56633069240184e-06 0.000139294097373173 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 937 0 0 0 0 0 2060 +630 663 0.995514657083621 0.0217981616906815 0.0920619773771258 -0.0182817010428761 -0.00929008574878944 0.990915140355869 -0.134167354152519 0.0423105995995834 -0.094150208913521 0.132710303896925 0.986673052941614 0.0567301019464869 9.58525199047993e-05 6.89512133604096e-05 -2.76045784243223e-05 -4.66830353214193e-06 4.16379678305919e-05 6.77522323488482e-05 6.89512133604096e-05 0.000134243001751796 -2.12868337652371e-05 2.98305198198775e-06 3.92182933722708e-05 2.77819941015538e-05 -2.76045784243223e-05 -2.12868337652371e-05 2.3247654099508e-05 -2.07663999385874e-06 -9.05272722376499e-06 -8.61237584729234e-06 -4.66830353214193e-06 2.98305198198775e-06 -2.07663999385874e-06 3.05399121225499e-05 -1.64530840520015e-05 -1.24622000993425e-05 4.16379678305919e-05 3.92182933722708e-05 -9.05272722376499e-06 -1.64530840520015e-05 8.78889468418149e-05 4.27919849814441e-05 6.77522323488482e-05 2.77819941015538e-05 -8.61237584729234e-06 -1.24622000993425e-05 4.27919849814441e-05 0.000102655732648296 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1194 0 0 0 0 0 2154 +630 662 0.995575185186016 0.0229441645727519 0.0911241787556366 -0.0162456771391558 -0.0103406906921798 0.990593719361844 -0.136444689441826 0.0400917895210046 -0.0933976485669709 0.134898660011603 0.986447784106809 0.0577963962928836 0.000198676244426639 8.7040573785433e-05 -2.89732374992222e-05 -1.91528028819146e-06 5.05902107786424e-05 0.000185442766269155 8.7040573785433e-05 0.000198698164529046 -2.07773077836271e-05 1.93933497855457e-05 2.00147520333531e-05 3.9963018351956e-05 -2.89732374992222e-05 -2.07773077836271e-05 2.37733203596779e-05 -5.53700885241389e-06 -7.78109982482933e-06 -1.63696921774174e-05 -1.91528028819146e-06 1.93933497855457e-05 -5.53700885241389e-06 2.69364350343305e-05 -1.38289860446653e-06 -1.22037723002073e-05 5.05902107786424e-05 2.00147520333531e-05 -7.78109982482933e-06 -1.38289860446653e-06 5.77910261227715e-05 5.25708219300287e-05 0.000185442766269155 3.9963018351956e-05 -1.63696921774174e-05 -1.22037723002073e-05 5.25708219300287e-05 0.000235175893229121 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1188 0 0 0 0 0 2153 +631 675 0.995803457231419 0.0363319582453715 0.0839968057488477 -0.01619919748537 -0.025670167356841 0.991863133705971 -0.124693891200987 0.0195043400981227 -0.0878437082199109 0.122014395892568 0.988633385093355 0.0251441194773011 0.000245965421371231 0.00012350569519729 -3.62865460569612e-05 -1.47154347596665e-05 8.70791720713515e-05 0.000194104940775857 0.00012350569519729 0.00017992979335268 -2.43330280801864e-05 2.76119471533871e-06 6.41173381752322e-05 7.05984983141525e-05 -3.62865460569612e-05 -2.43330280801864e-05 2.39276517886576e-05 6.65999318651197e-07 -1.32130223873311e-05 -2.15739365270389e-05 -1.47154347596665e-05 2.76119471533871e-06 6.65999318651197e-07 3.20763832737964e-05 -2.29668568309968e-05 -1.58748972907706e-05 8.70791720713515e-05 6.41173381752322e-05 -1.32130223873311e-05 -2.29668568309968e-05 0.000122721608091515 6.76209317564723e-05 0.000194104940775857 7.05984983141525e-05 -2.15739365270389e-05 -1.58748972907706e-05 6.76209317564723e-05 0.000213650993020923 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 957 0 0 7 0 0 2126 +631 673 0.996703919865361 0.0364423288830382 0.0724793266428767 -0.017395960046253 -0.0274175041122294 0.992172585431213 -0.121827095454987 0.0202946111685513 -0.0763516639850123 0.119438341349514 0.989901462784249 0.0222474728751335 8.10642701899607e-05 7.171211654791e-05 -1.6189582880129e-05 -9.68137280244495e-07 3.94997988456072e-05 4.80297906052549e-05 7.171211654791e-05 0.000143045284643111 -4.84773818156799e-06 5.99539475663168e-06 2.29115389462516e-05 4.46052878027944e-05 -1.6189582880129e-05 -4.84773818156799e-06 2.28565537027374e-05 4.63425093266452e-07 -7.55562838822868e-06 -4.78120602271404e-06 -9.68137280244495e-07 5.99539475663168e-06 4.63425093266452e-07 3.46298661219812e-05 -2.46095322242991e-05 -5.21972655741176e-07 3.94997988456072e-05 2.29115389462516e-05 -7.55562838822868e-06 -2.46095322242991e-05 0.000118005589015037 2.24019335573704e-05 4.80297906052549e-05 4.46052878027944e-05 -4.78120602271404e-06 -5.21972655741176e-07 2.24019335573704e-05 7.82561886617447e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1009 0 0 11 0 0 2089 +631 633 0.997848971449679 -0.00201576721301326 -0.0655237884997628 0.0125311231319147 0.000849651036013042 0.999840853150726 -0.0178198334432372 0.0135914513699007 0.0655492812312668 0.0177258301179565 0.997691879628522 0.0224247337725723 6.16816224749181e-05 5.2074269228137e-05 -1.02427198479062e-05 8.46568112882867e-06 4.49389138331267e-06 2.97853343858161e-05 5.2074269228137e-05 0.000120003353510409 -1.62940832860732e-05 1.3872439750015e-05 1.05667000841822e-05 1.43929907534508e-05 -1.02427198479062e-05 -1.62940832860732e-05 2.13950791887572e-05 -3.63985370586654e-06 -3.26067778418679e-06 -8.37798586895198e-06 8.46568112882867e-06 1.3872439750015e-05 -3.63985370586654e-06 2.39374386905116e-05 1.41844431415429e-07 1.24364750964019e-05 4.49389138331267e-06 1.05667000841822e-05 -3.26067778418679e-06 1.41844431415429e-07 4.08544761985418e-05 -1.8152793593548e-05 2.97853343858161e-05 1.43929907534508e-05 -8.37798586895198e-06 1.24364750964019e-05 -1.8152793593548e-05 9.71710434814573e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1497 0 0 0 0 0 2081 +631 672 0.996708541260999 0.038079907317111 0.0715681803324123 -0.0192933126050489 -0.0282583140598821 0.990638746251376 -0.133552769016575 0.0259103824663084 -0.075983889502088 0.13109078947135 0.988454173673172 0.0396107338139643 6.93916899231909e-05 5.5636892677667e-05 -1.83201380677804e-05 5.27474803695657e-06 1.50033815146572e-05 3.70775723082378e-05 5.5636892677667e-05 9.9183179772308e-05 -1.3882243185671e-05 6.0047989043297e-06 1.36053756078337e-05 3.4356209929436e-05 -1.83201380677804e-05 -1.3882243185671e-05 2.24782192670588e-05 -4.16006311575578e-06 -2.3570477868824e-06 -8.55803323238143e-06 5.27474803695657e-06 6.0047989043297e-06 -4.16006311575578e-06 3.04544011192499e-05 -1.79114724403703e-05 7.9246631220169e-06 1.50033815146572e-05 1.36053756078337e-05 -2.3570477868824e-06 -1.79114724403703e-05 7.72669334537385e-05 -2.92432296689008e-07 3.70775723082378e-05 3.4356209929436e-05 -8.55803323238143e-06 7.9246631220169e-06 -2.92432296689008e-07 6.05193937653366e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1066 0 0 8 0 0 2092 +631 635 0.996975496730842 0.00862186775062217 -0.0772367937888462 0.00954668771376427 -0.0117750251957717 0.999111668074984 -0.0404626185269995 0.00749679076351744 0.076819318533354 0.0412497043978902 0.996191374278636 0.0311442632813408 9.00397137667456e-05 5.58617547772571e-05 -5.88706449279305e-06 1.9387973639764e-05 -2.13790704461139e-05 3.48127691575404e-05 5.58617547772571e-05 0.000112440409385921 -3.20131793541602e-06 1.82940041777263e-05 -4.70481859245917e-06 -1.79304632834035e-06 -5.88706449279305e-06 -3.20131793541602e-06 2.10600415420516e-05 -5.14145279071873e-06 -1.89584562577721e-06 -8.34329904657124e-06 1.9387973639764e-05 1.82940041777263e-05 -5.14145279071873e-06 2.66543151421174e-05 -4.58571213054171e-06 1.31833249888389e-05 -2.13790704461139e-05 -4.70481859245917e-06 -1.89584562577721e-06 -4.58571213054171e-06 5.03149693586601e-05 -2.79491990592631e-05 3.48127691575404e-05 -1.79304632834035e-06 -8.34329904657124e-06 1.31833249888389e-05 -2.79491990592631e-05 8.26857414650222e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1500 0 0 0 0 0 1995 +631 678 0.994547614203449 0.0377384988630584 0.0972154760611177 -0.00926413059241466 -0.0242837631770573 0.99040585532849 -0.136038746601851 0.0095672348410167 -0.101416674803443 0.132936253274286 0.985922213279125 0.0365712226540709 7.80672608169708e-05 7.49047725195525e-05 -2.01610127493121e-05 2.31184450537626e-06 2.25474537142621e-05 4.7263625485829e-05 7.49047725195525e-05 0.000137610031693867 -2.23638684213242e-05 6.23663977019636e-06 2.98205321184985e-05 4.62669273415825e-05 -2.01610127493121e-05 -2.23638684213242e-05 2.58773996652627e-05 -5.80374450855815e-06 -2.8364388591586e-06 -7.31391729833746e-06 2.31184450537626e-06 6.23663977019636e-06 -5.80374450855815e-06 2.96509117634204e-05 -1.56700176944375e-05 -3.62548775469344e-07 2.25474537142621e-05 2.98205321184985e-05 -2.8364388591586e-06 -1.56700176944375e-05 8.19020437784228e-05 1.83962153589459e-05 4.7263625485829e-05 4.62669273415825e-05 -7.31391729833746e-06 -3.62548775469344e-07 1.83962153589459e-05 6.84175062776123e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1073 0 0 2 0 0 2090 +631 634 0.996425014842132 0.00989774123331357 -0.083900086503747 0.0134791038728777 -0.0124066088629437 0.999489710196262 -0.0294345930549986 0.0101288095325553 0.0835659371597052 0.0303702803785182 0.996039346720977 0.0290740857807839 8.03961805477651e-05 4.21090299287801e-05 -7.23365306870156e-06 1.049967344188e-05 -1.25274714233712e-05 9.55479954585065e-06 4.21090299287801e-05 0.000103475551706377 -7.91229231533022e-06 8.42299662218972e-06 3.2263821294044e-06 -1.68302946456307e-05 -7.23365306870156e-06 -7.91229231533022e-06 2.10930106558721e-05 -5.20620068527884e-06 3.24734207970449e-07 -8.95085952688891e-06 1.049967344188e-05 8.42299662218972e-06 -5.20620068527884e-06 1.66475228984407e-05 2.75023960434787e-06 4.52179069333969e-06 -1.25274714233712e-05 3.2263821294044e-06 3.24734207970449e-07 2.75023960434787e-06 3.84291173406621e-05 -1.69624298924587e-05 9.55479954585065e-06 -1.68302946456307e-05 -8.95085952688891e-06 4.52179069333969e-06 -1.69624298924587e-05 5.69825495949902e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1528 0 0 0 0 0 2001 +631 669 0.995183153579056 0.0370657554943443 0.0907558295762809 -0.0178677787475034 -0.0246813792307837 0.990679146927709 -0.133961402507785 0.0303561563484489 -0.0948752884143795 0.131076151958394 0.986822031592358 0.0411557736430657 7.25846169107037e-05 6.324003596601e-05 -1.8735001229372e-05 2.92581562727394e-06 1.82609563411831e-05 3.82577008414828e-05 6.324003596601e-05 0.000128857967465301 -1.87903105339441e-05 8.09929386673465e-06 1.01776440372453e-05 1.9350423138628e-05 -1.8735001229372e-05 -1.87903105339441e-05 1.99988874960827e-05 -3.47294245741256e-06 -2.44741466880698e-06 -6.93460798237877e-06 2.92581562727394e-06 8.09929386673465e-06 -3.47294245741256e-06 2.67166922922788e-05 -1.88547518277674e-05 1.39885082972979e-06 1.82609563411831e-05 1.01776440372453e-05 -2.44741466880698e-06 -1.88547518277674e-05 7.86120971015749e-05 8.57189657753934e-06 3.82577008414828e-05 1.9350423138628e-05 -6.93460798237877e-06 1.39885082972979e-06 8.57189657753934e-06 6.94604896076377e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1058 0 0 1 0 0 2121 +631 674 0.996926300114573 0.0358511249222365 0.0696609573698099 -0.0166444814306384 -0.0273620211866498 0.992492365148322 -0.119206647964244 0.0131770109774489 -0.0734116607661863 0.116934177912619 0.990422700718966 0.0180378241621565 0.000122026548077538 9.2997838120318e-05 -2.03519688079298e-05 1.61154781145715e-05 1.62690464510266e-05 9.70589263830794e-05 9.2997838120318e-05 0.000176772212839046 -1.29962159965364e-05 2.91213839890269e-05 6.645963823604e-06 5.97921601025987e-05 -2.03519688079298e-05 -1.29962159965364e-05 2.50744943533658e-05 -8.36494768458877e-06 -7.09252613773521e-06 -7.03629214001329e-06 1.61154781145715e-05 2.91213839890269e-05 -8.36494768458877e-06 3.58220370579303e-05 -7.88119862896263e-06 3.07533059197887e-06 1.62690464510266e-05 6.645963823604e-06 -7.09252613773521e-06 -7.88119862896263e-06 6.65895218947424e-05 1.08163368799472e-05 9.70589263830794e-05 5.97921601025987e-05 -7.03629214001329e-06 3.07533059197887e-06 1.08163368799472e-05 0.000138060492212464 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 958 0 0 3 0 0 2093 +631 670 0.994436833367555 0.0378134415243406 0.0983134176091668 -0.0151358604610818 -0.0239994758673136 0.990131403343905 -0.13807182649014 0.0258140896759217 -0.102564173082044 0.134944239418785 0.98553064013641 0.0449683753181654 0.000107567891599011 9.80519942896457e-05 -2.11370269418701e-05 6.01767365110459e-06 7.37088561815039e-06 4.96914141079656e-05 9.80519942896457e-05 0.000130504404954717 -2.46157315165473e-05 3.14004200053786e-06 1.33444044881239e-05 4.35710286264976e-05 -2.11370269418701e-05 -2.46157315165473e-05 2.43196568990586e-05 -8.10472118768421e-07 -2.31445494756494e-06 -4.17191252302579e-06 6.01767365110459e-06 3.14004200053786e-06 -8.10472118768421e-07 2.83036720109389e-05 -2.2977843816486e-05 1.44185814544296e-06 7.37088561815039e-06 1.33444044881239e-05 -2.31445494756494e-06 -2.2977843816486e-05 9.6523395249335e-05 6.92414784959195e-06 4.96914141079656e-05 4.35710286264976e-05 -4.17191252302579e-06 1.44185814544296e-06 6.92414784959195e-06 7.40005412675155e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1070 0 0 4 0 0 2071 +631 668 0.994826537997754 0.0379080476614544 0.0942504069906385 -0.0146967890597159 -0.0246370588606831 0.990101127476021 -0.138176599688253 0.0249750451814895 -0.098555439353185 0.135139695475495 0.985912819716171 0.0427569084695708 7.15888180476571e-05 6.75244606156696e-05 -1.56361636284523e-05 -2.32946060710565e-06 1.45633471439776e-05 4.10393846614071e-05 6.75244606156696e-05 0.000100884712912313 -1.3295536275222e-05 6.44832950218387e-07 9.73447863781807e-06 3.71388797882915e-05 -1.56361636284523e-05 -1.3295536275222e-05 2.0776217416065e-05 -2.14256459247089e-06 2.63817700101632e-07 -5.56661781658261e-06 -2.32946060710565e-06 6.44832950218387e-07 -2.14256459247089e-06 3.5280326480157e-05 -3.10778027238608e-05 2.35377078049436e-06 1.45633471439776e-05 9.73447863781807e-06 2.63817700101632e-07 -3.10778027238608e-05 9.64288780315836e-05 6.06703859725103e-06 4.10393846614071e-05 3.71388797882915e-05 -5.56661781658261e-06 2.35377078049436e-06 6.06703859725103e-06 6.87865597197619e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1014 0 0 1 0 0 2017 +631 676 0.99563969177078 0.0352222576461803 0.0863770614045847 -0.0139983677926061 -0.0246279577196698 0.992373143534729 -0.120784964666794 0.0166176820679516 -0.0899725951006386 0.11813101437517 0.988913543022619 0.0244020084275531 7.64682369322279e-05 6.31221601355304e-05 -1.46250328699796e-05 -2.62202418543163e-06 2.59673694627237e-05 4.25060600794628e-05 6.31221601355304e-05 0.000145501567298892 -7.91144309902761e-06 2.6004646650179e-06 3.05311386477971e-05 1.32731080905064e-05 -1.46250328699796e-05 -7.91144309902761e-06 2.32002121566207e-05 -8.12496507934816e-07 6.29823924034896e-07 -6.23415719393128e-06 -2.62202418543163e-06 2.6004646650179e-06 -8.12496507934816e-07 3.14990109010711e-05 -2.14822833764717e-05 -1.59482225082474e-06 2.59673694627237e-05 3.05311386477971e-05 6.29823924034896e-07 -2.14822833764717e-05 9.8284028778524e-05 2.36980986958847e-05 4.25060600794628e-05 1.32731080905064e-05 -6.23415719393128e-06 -1.59482225082474e-06 2.36980986958847e-05 7.7670920628907e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1016 0 0 5 0 0 2074 +631 671 0.994446593387196 0.0380031914284883 0.0981413793557559 -0.0156461055341661 -0.0242518130247453 0.990178800355401 -0.137687301127417 0.0267329343166209 -0.102410070137724 0.13454256117671 0.985601581150516 0.0445776222994464 0.000102880629434959 6.93097374303931e-05 -3.09903497845089e-05 6.38845591847588e-07 3.00417175184123e-05 6.90983741696346e-05 6.93097374303931e-05 9.38841771066867e-05 -2.47626548534663e-05 -3.97499436147018e-07 3.11676265099531e-05 3.12395840234188e-05 -3.09903497845089e-05 -2.47626548534663e-05 2.32847138267513e-05 -1.35041202324073e-06 -7.00042225079197e-06 -1.90070830758732e-05 6.38845591847588e-07 -3.97499436147018e-07 -1.35041202324073e-06 2.92190647546481e-05 -2.41833115286261e-05 5.16569281014826e-07 3.00417175184123e-05 3.11676265099531e-05 -7.00042225079197e-06 -2.41833115286261e-05 0.000109253253941053 1.82629414247929e-05 6.90983741696346e-05 3.12395840234188e-05 -1.90070830758732e-05 5.16569281014826e-07 1.82629414247929e-05 9.9071066916371e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 952 0 0 8 0 0 2056 +631 666 0.994650764310004 0.0341738518064284 0.0974782278780064 -0.0164459565591703 -0.0233790995274767 0.993677967036061 -0.109806718976414 0.0299209880437287 -0.100614485849745 0.106940383764942 0.989161503273049 0.00871411829542759 0.000119924055225101 4.76894038575131e-05 -9.39289624498109e-06 9.57385512075674e-07 -8.12743902942576e-06 0.000102665723068485 4.76894038575131e-05 8.90517588022529e-05 -5.16129883697783e-06 5.42287212850049e-06 4.81431644438926e-06 4.27260376823988e-06 -9.39289624498109e-06 -5.16129883697783e-06 1.68829630002137e-05 1.12634391011105e-06 4.96090362188217e-06 -6.81276524971085e-06 9.57385512075674e-07 5.42287212850049e-06 1.12634391011105e-06 2.55781386387553e-05 -1.28673246025635e-05 6.54211388606586e-06 -8.12743902942576e-06 4.81431644438926e-06 4.96090362188217e-06 -1.28673246025635e-05 6.83025893462885e-05 -1.81399342019652e-05 0.000102665723068485 4.27260376823988e-06 -6.81276524971085e-06 6.54211388606586e-06 -1.81399342019652e-05 0.000173058171293785 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 780 0 0 4 0 0 2073 +631 665 0.994005944259383 0.0362821027609645 0.103129975255771 -0.0151615752624577 -0.0226837176308632 0.9912421398898 -0.130094077732749 0.0273052951765268 -0.106946864056205 0.126974915341315 0.986123592224935 0.0339309702604524 8.84202752997307e-05 6.66422178119433e-05 -2.44985344306099e-05 -9.03070914428438e-06 3.3165203134926e-05 6.29212572956269e-05 6.66422178119433e-05 8.76642073726332e-05 -2.14411981421495e-05 -4.73909991224158e-06 2.09281985846823e-05 4.68625174455191e-05 -2.44985344306099e-05 -2.14411981421495e-05 2.56311497043545e-05 -9.05474629800522e-07 -8.01544683134281e-06 -1.05138925105022e-05 -9.03070914428438e-06 -4.73909991224158e-06 -9.05474629800522e-07 2.82518410928348e-05 -1.48663583387922e-05 -1.13430831754419e-05 3.3165203134926e-05 2.09281985846823e-05 -8.01544683134281e-06 -1.48663583387922e-05 7.59732233913021e-05 2.65010918980976e-05 6.29212572956269e-05 4.68625174455191e-05 -1.05138925105022e-05 -1.13430831754419e-05 2.65010918980976e-05 8.37003409992254e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1110 0 0 5 0 0 2058 +631 667 0.995122551769951 0.0373648793910871 0.0912960719141348 -0.0195431755768047 -0.025107512249104 0.990945645025011 -0.131895191097423 0.0343914466119005 -0.0953976927788217 0.128959661887174 0.987050498109607 0.0365901958278459 6.54489607195964e-05 5.15854278710717e-05 -1.82420257720328e-05 -3.24588509486157e-06 1.85314878777845e-05 4.08857520945022e-05 5.15854278710717e-05 0.000134901007188389 -1.52259097991492e-05 1.57450771082657e-06 2.2994480505889e-05 1.55951378392665e-05 -1.82420257720328e-05 -1.52259097991492e-05 2.13661039963204e-05 7.73578168004539e-08 2.42290968587723e-07 -7.54884846753431e-06 -3.24588509486157e-06 1.57450771082657e-06 7.73578168004539e-08 3.6266441543181e-05 -3.66674834135297e-05 -4.66910543100971e-06 1.85314878777845e-05 2.2994480505889e-05 2.42290968587723e-07 -3.66674834135297e-05 0.0001281215012559 1.29209144039226e-05 4.08857520945022e-05 1.55951378392665e-05 -7.54884846753431e-06 -4.66910543100971e-06 1.29209144039226e-05 7.87266555367573e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 912 0 0 8 0 0 2003 +631 664 0.995066423134907 0.0370368174314756 0.0920385120699467 -0.0163587108173435 -0.0244814207794029 0.990681964629636 -0.133977255510726 0.0273851858889926 -0.0961429851113642 0.131063034880595 0.986701072920144 0.0415646723556355 9.91234024316573e-05 9.66849020652403e-05 -1.74466293052904e-05 -7.89254101673514e-06 3.8355001059244e-05 6.30260074178157e-05 9.66849020652403e-05 0.000139286213373357 -2.16118432201667e-05 -5.91049962456113e-06 4.33379962425494e-05 5.44773859793164e-05 -1.74466293052904e-05 -2.16118432201667e-05 2.01366704282233e-05 2.42068236860978e-06 -4.17276398039052e-06 -8.0659308266121e-06 -7.89254101673514e-06 -5.91049962456113e-06 2.42068236860978e-06 2.75108652477624e-05 -1.63388323614611e-05 -6.90058382975087e-06 3.8355001059244e-05 4.33379962425494e-05 -4.17276398039052e-06 -1.63388323614611e-05 8.24615477724554e-05 2.5699839264269e-05 6.30260074178157e-05 5.44773859793164e-05 -8.0659308266121e-06 -6.90058382975087e-06 2.5699839264269e-05 8.37715550160878e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1169 0 0 5 0 0 2051 +631 660 0.99494104216344 0.0371218539082717 0.093350364654567 -0.0165539781601592 -0.0246155264829031 0.990981350920707 -0.131719542905903 0.0304750123543322 -0.0973981441029406 0.128755310918748 0.986881792027556 0.0390087671995359 9.21376298359746e-05 9.17945488367416e-05 -2.32477538804037e-05 -2.73844301538822e-06 2.39203202453476e-05 5.57606517734372e-05 9.17945488367416e-05 0.000123821906064461 -2.18668386874622e-05 -4.35727229389103e-06 3.35960628515222e-05 5.33761290327276e-05 -2.32477538804037e-05 -2.18668386874622e-05 2.1928718020992e-05 4.84472409646047e-07 -3.38420372304083e-06 -6.50510039410862e-06 -2.73844301538822e-06 -4.35727229389103e-06 4.84472409646047e-07 2.69458505396716e-05 -1.8511352025603e-05 -3.07235740243924e-06 2.39203202453476e-05 3.35960628515222e-05 -3.38420372304083e-06 -1.8511352025603e-05 8.4120039261882e-05 1.72722123899939e-05 5.57606517734372e-05 5.33761290327276e-05 -6.50510039410862e-06 -3.07235740243924e-06 1.72722123899939e-05 7.63079140857596e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1188 0 0 7 0 0 2131 +631 662 0.99499603627635 0.0365854009439492 0.0929752452651901 -0.0170867012687865 -0.0239849201450931 0.990799499141896 -0.133195630956131 0.0308864154596927 -0.0969928420038576 0.130299121017521 0.986719072310897 0.0407077141626915 0.000117421134288687 8.65381114997429e-05 -2.43297244931558e-05 -5.53046214555572e-06 3.01434988530317e-05 9.07465449850461e-05 8.65381114997429e-05 0.000132978261358974 -2.6210542641466e-05 -2.08374488024145e-06 2.86064428550098e-05 4.50329315012572e-05 -2.43297244931558e-05 -2.6210542641466e-05 2.16798669882827e-05 1.16825189028986e-06 -3.3860651725115e-06 -1.27735627283024e-05 -5.53046214555572e-06 -2.08374488024145e-06 1.16825189028986e-06 2.32270980091735e-05 -7.24290897584433e-06 -7.49596560822583e-06 3.01434988530317e-05 2.86064428550098e-05 -3.3860651725115e-06 -7.24290897584433e-06 6.44817838645862e-05 2.62431575599875e-05 9.07465449850461e-05 4.50329315012572e-05 -1.27735627283024e-05 -7.49596560822583e-06 2.62431575599875e-05 0.000122087266199407 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1184 0 0 2 0 0 2061 +632 636 0.999111819846974 0.0200681176471347 -0.0370518838410215 0.000365510970658405 -0.0212395137174495 0.99927815522363 -0.0314968498409829 0.00647616448680775 0.0363930556440932 0.03225583895917 0.998816853258857 0.0225514755549456 6.36438367113032e-05 2.93098903673151e-05 -7.03350097659956e-06 3.45514963487786e-06 4.00853483605408e-06 1.14327980967128e-05 2.93098903673151e-05 7.49416457679499e-05 -4.43162887974082e-06 5.69051599274907e-06 1.4591690041534e-05 -2.06591389166516e-05 -7.03350097659956e-06 -4.43162887974082e-06 2.24831516467355e-05 -5.22124948416773e-06 -1.31364519173003e-06 -7.67241318016217e-06 3.45514963487786e-06 5.69051599274907e-06 -5.22124948416773e-06 1.80361357441988e-05 4.07586409489725e-06 5.08218385214894e-07 4.00853483605408e-06 1.4591690041534e-05 -1.31364519173003e-06 4.07586409489725e-06 4.34342029050586e-05 -8.07170863740226e-06 1.14327980967128e-05 -2.06591389166516e-05 -7.67241318016217e-06 5.08218385214894e-07 -8.07170863740226e-06 6.33922482614491e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1562 0 0 0 0 0 2085 +632 672 0.99320863183716 0.0483336294187287 0.105832291439663 -0.0220272326378561 -0.0356960875074731 0.992347206798547 -0.118206643196484 0.0183124573420242 -0.11073573488633 0.113626059626897 0.987333133037097 0.0193426846497238 0.000107222924247501 8.46770082343854e-05 -2.02198425336823e-05 6.0485749777854e-06 1.95542188921286e-05 6.73672753609706e-05 8.46770082343854e-05 0.000136347485552658 -1.89432183428553e-05 8.52100230637856e-06 2.27073327794999e-05 4.81019525516776e-05 -2.02198425336823e-05 -1.89432183428553e-05 2.05104005301254e-05 -5.4584369816079e-06 4.8235376843507e-07 -1.03496829567167e-05 6.0485749777854e-06 8.52100230637856e-06 -5.4584369816079e-06 3.32762506032513e-05 -1.61981540474155e-05 4.54370218458231e-06 1.95542188921286e-05 2.27073327794999e-05 4.8235376843507e-07 -1.61981540474155e-05 7.19197323063129e-05 2.96352030579734e-06 6.73672753609706e-05 4.81019525516776e-05 -1.03496829567167e-05 4.54370218458231e-06 2.96352030579734e-06 9.95516393626939e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1060 0 0 8 0 0 2083 +632 673 0.993972143012624 0.0482550249670985 0.0984420209073198 -0.0215362488352935 -0.0371268896332556 0.993025972560298 -0.111897327433829 0.0136750150121489 -0.103155091881364 0.107567980301288 0.988831712999158 0.00767719132636132 0.000173213860733723 0.000133185637116247 -3.82414224478715e-05 3.69599018141632e-06 7.44794161693432e-05 0.000132103381230602 0.000133185637116247 0.000259680659954829 -2.98435279617534e-05 3.12562650085352e-05 4.42631151826079e-05 9.40441881554218e-05 -3.82414224478715e-05 -2.98435279617534e-05 2.6329391132051e-05 5.54461963813891e-08 -1.69002385676853e-05 -2.36383814920242e-05 3.69599018141632e-06 3.12562650085352e-05 5.54461963813891e-08 3.97525540661932e-05 -2.75741589790361e-05 -2.09130728544207e-06 7.44794161693432e-05 4.42631151826079e-05 -1.69002385676853e-05 -2.75741589790361e-05 0.000147966031482187 6.09659301249342e-05 0.000132103381230602 9.40441881554218e-05 -2.36383814920242e-05 -2.09130728544207e-06 6.09659301249342e-05 0.000166304748826981 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1005 0 0 11 0 0 2094 +631 663 0.994894498997252 0.0381460696223759 0.0934334695779369 -0.0194466332427505 -0.0247879108199455 0.98981753926105 -0.140167037667143 0.0362830009352942 -0.0978289085198687 0.137135394204286 0.985709586193746 0.0492319329366459 6.41316376370029e-05 5.22448213995061e-05 -1.92147658163693e-05 4.63176050748345e-06 7.74260505185028e-06 2.90219231308441e-05 5.22448213995061e-05 9.54297681673721e-05 -1.92738231849528e-05 1.1797836355875e-05 6.67020437349861e-06 1.05221446501628e-05 -1.92147658163693e-05 -1.92738231849528e-05 2.04050341384511e-05 -1.72302057824706e-06 1.0302130059658e-06 -5.86920403633395e-06 4.63176050748345e-06 1.1797836355875e-05 -1.72302057824706e-06 2.64708957388669e-05 -1.60655829280076e-05 4.74906885188095e-06 7.74260505185028e-06 6.67020437349861e-06 1.0302130059658e-06 -1.60655829280076e-05 7.20965496923315e-05 3.65527859983897e-06 2.90219231308441e-05 1.05221446501628e-05 -5.86920403633395e-06 4.74906885188095e-06 3.65527859983897e-06 5.10347601412295e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1172 0 0 4 0 0 2098 +632 671 0.990926600753975 0.0509490146677598 0.124373107312461 -0.0194254641255371 -0.0345650524825891 0.990845113107954 -0.130503712502601 0.0209467444192387 -0.129883521145096 0.125020637234298 0.98361583517168 0.0332272105787185 9.76830529377128e-05 6.55097084419603e-05 -2.4985153147478e-05 -3.59681570932552e-06 3.45561172247839e-05 5.92393297091978e-05 6.55097084419603e-05 0.000106672715755596 -2.19332977672384e-05 1.06293294819688e-05 3.3211211857726e-06 2.46178331684317e-05 -2.4985153147478e-05 -2.19332977672384e-05 2.46088397340425e-05 -1.32258777921658e-06 -3.5374321774446e-06 -1.3564443153872e-05 -3.59681570932552e-06 1.06293294819688e-05 -1.32258777921658e-06 3.3910313214394e-05 -3.5604004865229e-05 -7.71262269202274e-06 3.45561172247839e-05 3.3211211857726e-06 -3.5374321774446e-06 -3.5604004865229e-05 0.000132600754944625 1.9405995765665e-05 5.92393297091978e-05 2.46178331684317e-05 -1.3564443153872e-05 -7.71262269202274e-06 1.9405995765665e-05 9.60186512910978e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 960 0 0 8 0 0 2046 +631 661 0.994758434279774 0.0375664101946002 0.0951021674534523 -0.0170894277806878 -0.0246394280260644 0.990726027044336 -0.133621996405886 0.0322093146072085 -0.0992398912524688 0.130578344919965 0.986458686323031 0.0414233198604475 0.000275117231628021 0.000117064307995315 -2.97015846772774e-05 -2.7889777568208e-05 7.42775311977546e-05 0.000248367857730595 0.000117064307995315 0.000134519281272752 -1.45457425642179e-05 -3.93284626488327e-06 3.02003121994481e-05 7.71695501874686e-05 -2.97015846772774e-05 -1.45457425642179e-05 2.06385752791458e-05 3.1815809818849e-06 -6.62476595046586e-06 -1.88727182518482e-05 -2.7889777568208e-05 -3.93284626488327e-06 3.1815809818849e-06 3.03384277423622e-05 -2.1273577457433e-05 -2.43538464798738e-05 7.42775311977546e-05 3.02003121994481e-05 -6.62476595046586e-06 -2.1273577457433e-05 0.000104339058133262 6.92785553806871e-05 0.000248367857730595 7.71695501874686e-05 -1.88727182518482e-05 -2.43538464798738e-05 6.92785553806871e-05 0.000285695506804554 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1038 0 0 2 0 0 2074 +632 676 0.991825899108764 0.0493704536753604 0.117660291351757 -0.0179113684645289 -0.0348097804263886 0.991828054523942 -0.122741148136719 0.011869812138118 -0.122758564034278 0.117642120701484 0.985439326591495 0.0234810016717106 0.000304488896669436 0.000145597867896236 -5.46801957152929e-05 2.62346820386835e-05 -3.48794653957461e-06 0.000283095543937808 0.000145597867896236 0.000139694431521024 -3.29665346609655e-05 2.05198914218281e-05 6.89346429002175e-06 0.000121663001696115 -5.46801957152929e-05 -3.29665346609655e-05 3.07116256460027e-05 -7.62656869059444e-06 -3.0125905522793e-08 -4.38068242007543e-05 2.62346820386835e-05 2.05198914218281e-05 -7.62656869059444e-06 3.16505470442349e-05 -1.83918328748471e-05 2.70020679693521e-05 -3.48794653957461e-06 6.89346429002175e-06 -3.0125905522793e-08 -1.83918328748471e-05 8.9806803536756e-05 -1.2924945315156e-05 0.000283095543937808 0.000121663001696115 -4.38068242007543e-05 2.70020679693521e-05 -1.2924945315156e-05 0.000318537180505175 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1013 0 0 5 0 0 2016 +632 674 0.994759636893481 0.0497183927955613 0.0893383804720948 -0.0198497741428606 -0.0384070101618421 0.991520313616136 -0.124146563613287 0.00548455661587428 -0.0947531866375936 0.120064770454892 0.988233921962627 0.0228811794230213 0.000196972960160901 8.75252161351426e-05 -3.49039406297608e-05 6.67765129736225e-06 4.79326289484888e-05 0.00014834401341397 8.75252161351426e-05 0.000166120808167781 -1.45828978082056e-05 2.20672634986756e-05 1.34908187791693e-05 5.56481789153934e-05 -3.49039406297608e-05 -1.45828978082056e-05 2.449091893639e-05 -3.1960537622133e-06 -8.51907890603517e-06 -2.32904507761774e-05 6.67765129736225e-06 2.20672634986756e-05 -3.1960537622133e-06 3.92321181150242e-05 -2.43073221672242e-05 3.76268691458675e-06 4.79326289484888e-05 1.34908187791693e-05 -8.51907890603517e-06 -2.43073221672242e-05 0.000108421310068284 4.0303121452546e-05 0.00014834401341397 5.56481789153934e-05 -2.32904507761774e-05 3.76268691458675e-06 4.0303121452546e-05 0.000164136800296246 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 953 0 0 3 0 0 2075 +632 634 0.998221206966921 0.0178646743491816 -0.0568794811149102 0.00970849468524851 -0.0187839887268314 0.999700776650706 -0.0156690437323326 0.00107097782324927 0.0565825390824237 0.016709595278557 0.998258085715619 0.0131708595718787 0.000141956423512155 4.70557649716339e-05 -1.31509694691619e-05 2.60743114647031e-05 -1.60924972302201e-05 5.69132619948821e-05 4.70557649716339e-05 0.000119748546837545 -1.49394744348662e-06 1.56759654420089e-05 1.05437420345827e-05 -2.95339888544493e-05 -1.31509694691619e-05 -1.49394744348662e-06 2.50880657863497e-05 -5.03873519228075e-06 5.739126990887e-06 -2.15229172138929e-05 2.60743114647031e-05 1.56759654420089e-05 -5.03873519228075e-06 2.61532552154621e-05 2.90860306665132e-08 1.41367285921541e-05 -1.60924972302201e-05 1.05437420345827e-05 5.739126990887e-06 2.90860306665132e-08 4.54129470743158e-05 -3.97314880629426e-05 5.69132619948821e-05 -2.95339888544493e-05 -2.15229172138929e-05 1.41367285921541e-05 -3.97314880629426e-05 0.000117832953455923 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1561 0 0 0 0 0 2012 +632 635 0.998611037051639 0.0194295285019519 -0.0489743820873858 0.00445443911279271 -0.0209708433852183 0.999294483542875 -0.0311570038433179 0.00223302062957979 0.0483344639606364 0.0321407620160401 0.998313954129995 0.0219474355892492 0.000160744717371479 8.52023342168428e-05 -1.28457677413919e-05 3.67318321858004e-05 -4.06249653496036e-05 8.36329737190958e-05 8.52023342168428e-05 0.000110533167156964 -5.83315686737609e-06 2.27922736751015e-05 -8.45181182148194e-06 1.37972126009167e-05 -1.28457677413919e-05 -5.83315686737609e-06 1.75454843321255e-05 -6.94569135373531e-06 1.68177308752913e-06 -1.31930642143444e-05 3.67318321858004e-05 2.27922736751015e-05 -6.94569135373531e-06 2.82571554427738e-05 -1.27912924267002e-05 2.76072036273053e-05 -4.06249653496036e-05 -8.45181182148194e-06 1.68177308752913e-06 -1.27912924267002e-05 6.82315882610763e-05 -4.86923850897678e-05 8.36329737190958e-05 1.37972126009167e-05 -1.31930642143444e-05 2.76072036273053e-05 -4.86923850897678e-05 0.000132849682082344 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1518 0 0 0 0 0 1943 +632 675 0.993529400486072 0.0488681946002434 0.102524289445476 -0.0197702598237714 -0.0366641364324767 0.992370569521204 -0.117713184681339 0.0116007115996877 -0.107494518322786 0.113192545269885 0.987741047150455 0.0177375487696447 0.000220761487452093 0.000110299283134167 -3.55246394870338e-05 2.44729002897162e-05 1.57099188734686e-05 0.000172712194715568 0.000110299283134167 0.000166584609751477 -2.58583612243939e-05 3.88744714679968e-05 -8.45799869481989e-06 5.8960070719838e-05 -3.55246394870338e-05 -2.58583612243939e-05 2.40538773537801e-05 -5.07000765779262e-06 -1.23628154004372e-06 -2.26421886682627e-05 2.44729002897162e-05 3.88744714679968e-05 -5.07000765779262e-06 4.07237736327418e-05 -2.39123125782476e-05 8.87445546667562e-06 1.57099188734686e-05 -8.45799869481989e-06 -1.23628154004372e-06 -2.39123125782476e-05 9.92996304127867e-05 2.51047935622549e-05 0.000172712194715568 5.8960070719838e-05 -2.26421886682627e-05 8.87445546667562e-06 2.51047935622549e-05 0.000199745779950706 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 955 0 0 7 0 0 2086 +632 678 0.991183852753818 0.0507577394991004 0.122385546209673 -0.0123331717170435 -0.034352918786138 0.99057317950105 -0.13260713790763 0.00026372247462065 -0.127962678195525 0.127233753124403 0.983583816995231 0.0303856092409675 0.000258843215032893 0.000167295202249948 -5.3033847774991e-05 -1.0214928436536e-05 0.000109646486416472 0.000243561727517987 0.000167295202249948 0.000200627811274034 -4.0397126313301e-05 9.26718799712012e-06 6.10465999780689e-05 0.000133181246715732 -5.3033847774991e-05 -4.0397126313301e-05 3.03261380875835e-05 -1.48052738120836e-06 -2.03395154386835e-05 -4.42595718991405e-05 -1.0214928436536e-05 9.26718799712012e-06 -1.48052738120836e-06 3.58953105638179e-05 -3.2973917588753e-05 -1.69677876098272e-05 0.000109646486416472 6.10465999780689e-05 -2.03395154386835e-05 -3.2973917588753e-05 0.000145318483310943 0.000109529646061065 0.000243561727517987 0.000133181246715732 -4.42595718991405e-05 -1.69677876098272e-05 0.000109529646061065 0.00028863954606445 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1045 0 0 2 0 0 2060 +632 667 0.99191916570986 0.0482403290647633 0.117342402179168 -0.0235098555463855 -0.034371751888712 0.992481985092832 -0.117465279714014 0.0259578802260656 -0.122126783997431 0.112482798320072 0.986120007256993 0.0175370034123929 0.000112783156800591 8.61300281771353e-05 -1.60063604950981e-05 -5.54490732556521e-07 3.41663969492881e-05 9.06089387529035e-05 8.61300281771353e-05 0.000173297957027289 -1.18687375832006e-05 1.99649425133643e-05 -5.48146807941887e-06 5.63656550942181e-05 -1.60063604950981e-05 -1.18687375832006e-05 1.87231166781964e-05 -1.02203665247161e-06 -5.88239397673215e-06 -8.80854766604603e-06 -5.54490732556521e-07 1.99649425133643e-05 -1.02203665247161e-06 3.7959189382822e-05 -3.89686052055553e-05 -1.1131837214002e-05 3.41663969492881e-05 -5.48146807941887e-06 -5.88239397673215e-06 -3.89686052055553e-05 0.000132299903713072 3.97002647556997e-05 9.06089387529035e-05 5.63656550942181e-05 -8.80854766604603e-06 -1.1131837214002e-05 3.97002647556997e-05 0.000133857957271126 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 905 0 0 8 0 0 1997 +632 670 0.99071532677359 0.0497927020525843 0.126506237467571 -0.0180655680403642 -0.0335162935519768 0.991249391798112 -0.12767654963387 0.0150334373902735 -0.131756591343419 0.122251094400725 0.98371483192813 0.0299477227714016 0.000159669880302035 0.000125697276736843 -3.33846222523813e-05 8.15877623365369e-06 1.65580375554356e-05 9.87732695276524e-05 0.000125697276736843 0.000154354097014823 -3.02052612524843e-05 7.46996753170182e-06 2.52565594026339e-05 6.59405960802301e-05 -3.33846222523813e-05 -3.02052612524843e-05 2.13279671077941e-05 -2.20967625610898e-06 -3.26063649625324e-06 -2.10301965535217e-05 8.15877623365369e-06 7.46996753170182e-06 -2.20967625610898e-06 2.78886836106589e-05 -2.47009477406323e-05 6.35878064522597e-06 1.65580375554356e-05 2.52565594026339e-05 -3.26063649625324e-06 -2.47009477406323e-05 0.00010343988034976 -2.48590930635979e-06 9.87732695276524e-05 6.59405960802301e-05 -2.10301965535217e-05 6.35878064522597e-06 -2.48590930635979e-06 0.000125887003214771 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1085 0 0 4 0 0 2052 +632 668 0.991092569660204 0.0495680958437338 0.123606319574531 -0.0170500053757637 -0.0332914145972794 0.99089832552967 -0.130430786920147 0.0132790806978406 -0.128946500838319 0.125153954539691 0.983722159750725 0.0302803576979993 0.000112648686375822 9.66404352928127e-05 -1.39206991881193e-05 1.00044663951535e-05 -9.1656281407166e-06 8.08686517003799e-05 9.66404352928127e-05 0.000126569019920035 -1.74479203476527e-05 1.75390474408117e-05 -1.78594494948864e-05 6.37792384580749e-05 -1.39206991881193e-05 -1.74479203476527e-05 1.93744444228561e-05 -2.32873557255926e-06 2.8290043529379e-06 -6.61858045474123e-06 1.00044663951535e-05 1.75390474408117e-05 -2.32873557255926e-06 3.17071044342416e-05 -2.51057898608964e-05 4.61012753530934e-06 -9.1656281407166e-06 -1.78594494948864e-05 2.8290043529379e-06 -2.51057898608964e-05 9.86467752848864e-05 -8.46668210716624e-06 8.08686517003799e-05 6.37792384580749e-05 -6.61858045474123e-06 4.61012753530934e-06 -8.46668210716624e-06 0.000110115466746807 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1035 0 0 1 0 0 2009 +632 665 0.990196028919789 0.0506045204974348 0.130196032261757 -0.0180925375890763 -0.0330892855802825 0.990518345471281 -0.133336065880998 0.0202631288457007 -0.135708966141763 0.127720749254223 0.982481799688256 0.0362748046368093 0.000299903416701863 0.000230451275317604 -4.22055348874298e-05 -3.69316255260389e-06 6.52029919588161e-05 0.000272488814232388 0.000230451275317604 0.000250179023157317 -3.58839504615748e-05 7.94068768709314e-06 3.69610046378402e-05 0.000195532182013062 -4.22055348874298e-05 -3.58839504615748e-05 2.34652653601826e-05 -2.68597866608118e-06 -5.52982450186104e-06 -3.28016526020838e-05 -3.69316255260389e-06 7.94068768709314e-06 -2.68597866608118e-06 3.68003928603156e-05 -3.25895575047339e-05 -8.64482882890078e-06 6.52029919588161e-05 3.69610046378402e-05 -5.52982450186104e-06 -3.25895575047339e-05 0.000119407250107897 5.68476333991289e-05 0.000272488814232388 0.000195532182013062 -3.28016526020838e-05 -8.64482882890078e-06 5.68476333991289e-05 0.000311417138218801 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1090 0 0 5 0 0 2028 +632 669 0.990972048682306 0.0499038654448851 0.124434733672127 -0.0211857530337653 -0.0337604781825713 0.991118939637284 -0.128621450797097 0.0230107789631518 -0.12974832886507 0.123259286489598 0.983855944460772 0.0299480263242526 9.32787740199659e-05 7.94156628436993e-05 -2.18392895722054e-05 1.44876044701272e-06 2.52212092295781e-05 5.72999905194349e-05 7.94156628436993e-05 0.000127154705888138 -2.10436526969648e-05 1.48103393041959e-05 -3.0174200960696e-06 4.09976614998099e-05 -2.18392895722054e-05 -2.10436526969648e-05 2.11461205256397e-05 -3.2032730739084e-06 -5.59327626982318e-06 -1.09996761381324e-05 1.44876044701272e-06 1.48103393041959e-05 -3.2032730739084e-06 3.08025719169465e-05 -2.09150982646795e-05 2.12125840025668e-06 2.52212092295781e-05 -3.0174200960696e-06 -5.59327626982318e-06 -2.09150982646795e-05 8.29623326874258e-05 7.02991070643969e-06 5.72999905194349e-05 4.09976614998099e-05 -1.09996761381324e-05 2.12125840025668e-06 7.02991070643969e-06 8.59259160723999e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1065 0 0 1 0 0 2088 +632 662 0.991361829645941 0.049182515156101 0.121584550515151 -0.018684589720324 -0.0339383713523491 0.991649999869576 -0.124412478106582 0.0211337209791183 -0.126688238092577 0.119211400300435 0.98475313270251 0.0260347739844147 0.000258850153646105 0.000136740050624852 -3.82928444654732e-05 -2.58567211115318e-05 0.000106512900094935 0.000279528475726095 0.000136740050624852 0.00016388224460734 -2.53071529904664e-05 3.2745295921113e-06 5.28300560063436e-05 0.000115015952770236 -3.82928444654732e-05 -2.53071529904664e-05 1.93766324282796e-05 4.7993866369395e-06 -1.03762222442606e-05 -3.81126664103965e-05 -2.58567211115318e-05 3.2745295921113e-06 4.7993866369395e-06 3.34394448147427e-05 -2.94509199442927e-05 -3.73299186311159e-05 0.000106512900094935 5.28300560063436e-05 -1.03762222442606e-05 -2.94509199442927e-05 0.000132212301168254 0.000129102771288477 0.000279528475726095 0.000115015952770236 -3.81126664103965e-05 -3.73299186311159e-05 0.000129102771288477 0.000367886590093409 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1173 0 0 2 0 0 2077 +632 666 0.990973297723788 0.0469876841543821 0.125555090443397 -0.0211705695523314 -0.0326742588502671 0.99297525450115 -0.113721311797583 0.0217324205373634 -0.130016598967314 0.10859236384841 0.985547250265956 0.0105405127965414 0.000203830260090424 8.78431753965629e-05 -2.74571081557035e-05 -7.44029100539136e-06 2.19975629833531e-05 0.000203618561651427 8.78431753965629e-05 9.94186607409791e-05 -1.34994188498669e-05 2.21860451514959e-06 1.12927539701908e-05 6.02553006430092e-05 -2.74571081557035e-05 -1.34994188498669e-05 2.18184289072207e-05 -1.41026071843155e-06 -1.27446853747474e-06 -2.50270408774568e-05 -7.44029100539136e-06 2.21860451514959e-06 -1.41026071843155e-06 4.1611368881524e-05 -4.33749704878475e-05 -5.1314884840305e-06 2.19975629833531e-05 1.12927539701908e-05 -1.27446853747474e-06 -4.33749704878475e-05 0.000152820128991127 1.10446850441057e-05 0.000203618561651427 6.02553006430092e-05 -2.50270408774568e-05 -5.1314884840305e-06 1.10446850441057e-05 0.000289626724886116 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 775 0 0 4 0 0 2088 +632 664 0.990762245058958 0.0501898824158194 0.125980750389967 -0.0176538792367118 -0.0341049381857846 0.991350434531166 -0.126732668030825 0.0174983025149706 -0.131251769348366 0.121265376995883 0.983904304993616 0.025855750548776 0.000187251074072019 0.000101085313774471 -2.0419590507947e-05 9.03965710750551e-06 -8.43615592285888e-07 0.000194075444096572 0.000101085313774471 0.000144091427223964 -2.0762551168132e-05 1.87339056838928e-05 -3.14267732724718e-06 7.37952154258836e-05 -2.0419590507947e-05 -2.0762551168132e-05 2.25927016468579e-05 -1.88702437134393e-06 3.13855955462811e-06 -1.69878283290743e-05 9.03965710750551e-06 1.87339056838928e-05 -1.88702437134393e-06 3.26218512549258e-05 -1.9086594978317e-05 1.22782100579696e-06 -8.43615592285888e-07 -3.14267732724718e-06 3.13855955462811e-06 -1.9086594978317e-05 7.74083797281291e-05 1.01178301969135e-06 0.000194075444096572 7.37952154258836e-05 -1.69878283290743e-05 1.22782100579696e-06 1.01178301969135e-06 0.000264880007532915 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1161 0 0 5 0 0 2047 +632 659 0.991602294539876 0.0497721777774198 0.119363393812953 -0.0188824057188365 -0.0351146003690449 0.99192108723364 -0.121899637169914 0.017514454023358 -0.124466277779065 0.116684562048831 0.985338956235516 0.0245329493837431 0.000225337640055003 0.000170662517918224 -3.81385239661398e-05 5.34468378260649e-06 3.26910251722675e-05 0.000187951800856511 0.000170662517918224 0.00019539609315109 -3.61585759431278e-05 6.81362358694291e-06 3.74544825110788e-05 0.000114958106979426 -3.81385239661398e-05 -3.61585759431278e-05 2.25814636541479e-05 -1.36541770528512e-06 -6.37156918543267e-06 -2.74824383888941e-05 5.34468378260649e-06 6.81362358694291e-06 -1.36541770528512e-06 2.79093581088724e-05 -1.92557241794504e-05 4.23123159018423e-06 3.26910251722675e-05 3.74544825110788e-05 -6.37156918543267e-06 -1.92557241794504e-05 8.80194157280666e-05 1.74203929163083e-05 0.000187951800856511 0.000114958106979426 -2.74824383888941e-05 4.23123159018423e-06 1.74203929163083e-05 0.000229296869523728 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1174 0 0 3 0 0 2085 +632 661 0.990622749828208 0.0508310779295009 0.126817857730387 -0.0179178885043465 -0.0339009028447041 0.990636042260131 -0.132253395273989 0.0220073225740986 -0.132352923311552 0.126713982226544 0.983069819697043 0.034343233333269 8.70045397359155e-05 8.30602858022342e-05 -1.91367598497568e-05 8.89698181224386e-06 -1.11230216928939e-06 5.00513896137311e-05 8.30602858022342e-05 0.000130059158769449 -2.16014406742491e-05 1.53842159285964e-05 -7.33827083203024e-06 4.05851843970758e-05 -1.91367598497568e-05 -2.16014406742491e-05 1.95913208257953e-05 -1.37222421282452e-06 3.54167812413876e-06 -6.46812041908482e-06 8.89698181224386e-06 1.53842159285964e-05 -1.37222421282452e-06 3.25966437760294e-05 -2.18628614827853e-05 3.27039265924538e-06 -1.11230216928939e-06 -7.33827083203024e-06 3.54167812413876e-06 -2.18628614827853e-05 8.41989563979484e-05 6.1247399859189e-06 5.00513896137311e-05 4.05851843970758e-05 -6.46812041908482e-06 3.27039265924538e-06 6.1247399859189e-06 7.39381104228839e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1055 0 0 2 0 0 2082 +632 663 0.990884033326688 0.0503256193239782 0.124964653153976 -0.021016172908643 -0.0339907412279744 0.990987999525534 -0.129566254507694 0.0264883349358187 -0.130358973642049 0.124137491661615 0.983664791051786 0.0320031067919525 0.000111691174445898 9.79427203295038e-05 -2.6996545180532e-05 4.37924271407551e-07 2.17369393309033e-05 8.3083721365875e-05 9.79427203295038e-05 0.000140161078482067 -2.94486750034175e-05 8.46930930953793e-06 1.88964695946102e-05 5.57618931574831e-05 -2.6996545180532e-05 -2.94486750034175e-05 2.26259490913495e-05 -7.29318753518902e-07 -5.75160268913386e-06 -1.01329745004397e-05 4.37924271407551e-07 8.46930930953793e-06 -7.29318753518902e-07 3.25860346594106e-05 -3.0496033667695e-05 -2.52696306070751e-06 2.17369393309033e-05 1.88964695946102e-05 -5.75160268913386e-06 -3.0496033667695e-05 0.00011862382153137 1.87509756453559e-05 8.3083721365875e-05 5.57618931574831e-05 -1.01329745004397e-05 -2.52696306070751e-06 1.87509756453559e-05 0.000114776547268644 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1190 0 0 4 0 0 2050 +633 635 0.999882496175268 0.00851754731471827 0.0127454003489736 -0.000804245501003836 -0.00835380779712894 0.999882596527863 -0.0128455072296658 0.00181185570904611 -0.0128533162103291 0.0127375252086229 0.999836260451659 -0.00173255756415844 5.55905632458605e-05 1.55720245422982e-05 -7.74341274362645e-06 4.30990983016739e-06 -5.09188735745394e-06 8.40906928117755e-06 1.55720245422982e-05 7.2440210121252e-05 -1.44883988488004e-06 5.66567410178566e-06 1.58310996684512e-05 -2.05470311459773e-05 -7.74341274362645e-06 -1.44883988488004e-06 2.17655163388928e-05 -8.02157003562867e-06 -1.05831995065172e-06 -5.11132673724265e-06 4.30990983016739e-06 5.66567410178566e-06 -8.02157003562867e-06 1.78842025424987e-05 4.73806900091625e-06 3.3796204065908e-06 -5.09188735745394e-06 1.58310996684512e-05 -1.05831995065172e-06 4.73806900091625e-06 3.76808576437694e-05 -1.83106134106547e-05 8.40906928117755e-06 -2.05470311459773e-05 -5.11132673724265e-06 3.3796204065908e-06 -1.83106134106547e-05 5.88775754031396e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1580 0 0 0 0 0 1985 +632 658 0.991095200481404 0.0500267954459738 0.123400256564289 -0.0189144006766446 -0.0338896860823443 0.990991749501091 -0.12956404438735 0.0202308680169832 -0.128770310087247 0.124228306589817 0.983862559040571 0.0335829414568504 0.00024140214654427 0.000174221854889683 -3.26906102012751e-05 -9.85635450233898e-06 7.00764611101634e-05 0.000228934641008631 0.000174221854889683 0.000184334303563999 -2.99603679289922e-05 -3.95920139145967e-06 6.26912541558868e-05 0.000138966346257303 -3.26906102012751e-05 -2.99603679289922e-05 2.27002582470342e-05 1.50967392043194e-06 -1.13689555345066e-05 -2.52699615245845e-05 -9.85635450233898e-06 -3.95920139145967e-06 1.50967392043194e-06 2.57059047114546e-05 -1.3411458411509e-05 -1.27649003163133e-05 7.00764611101634e-05 6.26912541558868e-05 -1.13689555345066e-05 -1.3411458411509e-05 9.45418912721021e-05 5.4256978065785e-05 0.000228934641008631 0.000138966346257303 -2.52699615245845e-05 -1.27649003163133e-05 5.4256978065785e-05 0.000283000860473421 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1126 0 0 0 0 0 1928 +632 660 0.991771371670408 0.0499173504048733 0.117888949709273 -0.0204557538549395 -0.0354040156719626 0.991880796528527 -0.122143526853592 0.0236399401891707 -0.123028866569183 0.11696471094519 0.985486252762671 0.0244390413056015 0.000131924671711716 0.000102640816278653 -2.40077383461199e-05 -4.41496479712347e-07 3.70207565382601e-05 7.91427890646281e-05 0.000102640816278653 0.000134927173658026 -2.15666334606255e-05 1.52920805466383e-06 3.34238444852081e-05 4.69327717102755e-05 -2.40077383461199e-05 -2.15666334606255e-05 2.11142149280216e-05 4.44094618898188e-07 -4.35886182006222e-06 -9.4954008723052e-06 -4.41496479712347e-07 1.52920805466383e-06 4.44094618898188e-07 2.29853150072305e-05 -1.1382135994376e-05 -5.75095240119335e-08 3.70207565382601e-05 3.34238444852081e-05 -4.35886182006222e-06 -1.1382135994376e-05 7.76081591700401e-05 1.81763936006557e-05 7.91427890646281e-05 4.69327717102755e-05 -9.4954008723052e-06 -5.75095240119335e-08 1.81763936006557e-05 0.000102957363736915 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1184 0 0 7 0 0 2123 +633 673 0.98878328963331 0.0449380527119537 0.142436573815812 -0.0292894470259103 -0.0306700205435701 0.994430890766252 -0.100829327726094 0.0084842420419665 -0.146174402621617 0.0953298217154354 0.984654898484701 -0.00552899621981738 0.000216909558589352 0.000155573997486351 -4.98610746924961e-05 2.46483453552023e-05 4.92524740311806e-05 0.000187439677629327 0.000155573997486351 0.000258997197938533 -3.90942129049929e-05 3.22844824917276e-05 4.81218429174449e-05 0.000117256667101493 -4.98610746924961e-05 -3.90942129049929e-05 2.71598800632909e-05 -8.66251879016501e-06 -1.26160473606709e-05 -3.88208322653455e-05 2.46483453552023e-05 3.22844824917276e-05 -8.66251879016501e-06 3.28928457388554e-05 -2.90030031645436e-06 1.82069461951421e-05 4.92524740311806e-05 4.81218429174449e-05 -1.26160473606709e-05 -2.90030031645436e-06 7.27103241015399e-05 3.22457133142675e-05 0.000187439677629327 0.000117256667101493 -3.88208322653455e-05 1.82069461951421e-05 3.22457133142675e-05 0.000220865617071343 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1006 0 0 0 0 0 2083 +633 637 0.999560647834004 0.0150531390506584 0.0255326126040343 -0.0084246486995236 -0.0148296622641786 0.999850250642791 -0.00891949587578997 0.00692112758337972 -0.025663055523389 0.00853693705431742 0.999634197237637 0.000123361078605956 0.000106515018968888 7.31304996348366e-05 -1.15613517540344e-05 1.42040933230745e-05 -1.79655887325565e-05 4.36050932360788e-05 7.31304996348366e-05 9.75006605320618e-05 -7.18272117463359e-06 9.19861744968608e-06 -2.00702855537949e-06 1.22320343141965e-05 -1.15613517540344e-05 -7.18272117463359e-06 1.97364182282465e-05 -4.00633518694309e-06 1.26466888605901e-06 -7.95747478401062e-06 1.42040933230745e-05 9.19861744968608e-06 -4.00633518694309e-06 2.17961630124044e-05 -8.59590524266821e-06 9.90458611701322e-06 -1.79655887325565e-05 -2.00702855537949e-06 1.26466888605901e-06 -8.59590524266821e-06 6.13341874220856e-05 -1.38031809101737e-05 4.36050932360788e-05 1.22320343141965e-05 -7.95747478401062e-06 9.90458611701322e-06 -1.38031809101737e-05 8.64976968287271e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1485 0 0 0 0 0 2032 +633 671 0.984482601601989 0.0460584253005378 0.169329940063223 -0.0262361291930762 -0.0276124512927029 0.993579034865853 -0.109718977431659 0.0180598086109506 -0.173296161747997 0.103340809624638 0.979433059167157 0.00939367002964647 9.03270392641394e-05 6.51977113289333e-05 -2.76939573175299e-05 8.42045457838303e-07 2.40500367273503e-05 5.59602708747666e-05 6.51977113289333e-05 0.000100112935190278 -2.12436747871017e-05 7.62042443039245e-07 2.2536075016535e-05 3.18188022012422e-05 -2.76939573175299e-05 -2.12436747871017e-05 2.30673385096379e-05 -3.27360411479191e-06 -7.82115370173754e-06 -1.60587141268408e-05 8.42045457838303e-07 7.62042443039245e-07 -3.27360411479191e-06 2.66942180432636e-05 -1.60086030671176e-05 7.75131178904176e-07 2.40500367273503e-05 2.2536075016535e-05 -7.82115370173754e-06 -1.60086030671176e-05 8.52211413647625e-05 -8.71462192844109e-07 5.59602708747666e-05 3.18188022012422e-05 -1.60587141268408e-05 7.75131178904176e-07 -8.71462192844109e-07 9.22215408159749e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 960 0 0 0 0 0 2097 +633 670 0.983201270997614 0.0462403196313002 0.176570364300102 -0.0238245673759076 -0.0266376639509221 0.993371684610541 -0.111817400583508 0.0115878915764845 -0.180570472580412 0.105235588345437 0.977916036977447 0.00638840345056117 8.34622901536321e-05 6.1325639398861e-05 -2.52040621670807e-05 5.9897421550588e-06 9.91763930449994e-06 5.90325905993903e-05 6.1325639398861e-05 9.45040440538236e-05 -2.16331915315475e-05 6.68152901198055e-06 1.34908577784964e-05 4.24991553836332e-05 -2.52040621670807e-05 -2.16331915315475e-05 2.26790018227614e-05 -4.26952232352705e-06 -2.8637537297814e-06 -1.48471802167734e-05 5.9897421550588e-06 6.68152901198055e-06 -4.26952232352705e-06 2.29618545255659e-05 -4.10252786050913e-06 -1.48837565555575e-06 9.91763930449994e-06 1.34908577784964e-05 -2.8637537297814e-06 -4.10252786050913e-06 5.16344729106899e-05 1.68888858093231e-06 5.90325905993903e-05 4.24991553836332e-05 -1.48471802167734e-05 -1.48837565555575e-06 1.68888858093231e-06 9.31016842776423e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1092 0 0 1 0 0 2100 +633 636 0.999915367276155 0.0129273049185771 0.00146392367793332 -0.0072180068891507 -0.0128944855363698 0.999705407978678 -0.0205628184093917 0.00492872280852489 -0.00172931424126151 0.0205422015793683 0.999787491133255 0.0100410361380583 0.000110701938364768 4.52854415067441e-05 -4.98466292490597e-06 2.1737896931348e-05 -1.42868483352364e-05 5.7011262495636e-05 4.52854415067441e-05 0.000140976593046973 -3.21832772279767e-06 1.35749085383757e-05 2.36406957594755e-05 -5.27210504953794e-06 -4.98466292490597e-06 -3.21832772279767e-06 2.20721029883499e-05 -5.53963262403252e-06 5.53586664103201e-06 -1.35743233151111e-05 2.1737896931348e-05 1.35749085383757e-05 -5.53963262403252e-06 2.78046569875794e-05 -6.60745721121263e-06 1.70666807166385e-05 -1.42868483352364e-05 2.36406957594755e-05 5.53586664103201e-06 -6.60745721121263e-06 7.35649321754436e-05 -2.77847877841489e-05 5.7011262495636e-05 -5.27210504953794e-06 -1.35743233151111e-05 1.70666807166385e-05 -2.77847877841489e-05 0.000106465927337359 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1521 0 0 0 0 0 2096 +633 669 0.983663400379813 0.0461398586565694 0.174004103964178 -0.0238864740469946 -0.0267677491418522 0.993338802974236 -0.11207814288072 0.013395268157175 -0.178016298015388 0.105589468929738 0.978346084824809 0.0104000474719967 0.000171693483692065 0.000114978483545502 -4.25762639143308e-05 -1.47834537912923e-05 7.55382062272399e-05 0.000164207868552922 0.000114978483545502 0.000131643280167517 -3.61829978127228e-05 -3.82372081844607e-06 5.65057093476024e-05 9.2247987815733e-05 -4.25762639143308e-05 -3.61829978127228e-05 2.70801699819005e-05 -5.02706605952593e-07 -1.60274468852784e-05 -3.79998979541856e-05 -1.47834537912923e-05 -3.82372081844607e-06 -5.02706605952593e-07 3.35127878694904e-05 -2.73912547818931e-05 -2.0279822547018e-05 7.55382062272399e-05 5.65057093476024e-05 -1.60274468852784e-05 -2.73912547818931e-05 0.000114182856806031 7.43828887535214e-05 0.000164207868552922 9.2247987815733e-05 -3.79998979541856e-05 -2.0279822547018e-05 7.43828887535214e-05 0.000220866044280185 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1083 0 0 0 0 0 2147 +633 675 0.98756351999311 0.0459430224143743 0.150358014985073 -0.0247289892346481 -0.0296671763939036 0.993625954677795 -0.108753486543896 0.00464508396399745 -0.154396090052929 0.102940278230014 0.982631745108154 0.00799681384638851 0.000109336784645206 6.99605431827828e-05 -2.08251438317515e-05 1.16202727377039e-06 2.19858402701226e-05 7.85631915198253e-05 6.99605431827828e-05 0.000117366401529064 -1.4143695821907e-05 9.4432037874029e-07 3.71013694766531e-05 4.85678603543659e-05 -2.08251438317515e-05 -1.4143695821907e-05 2.04038270675149e-05 -2.33476893690276e-06 -4.49372958370934e-06 -8.47230421850251e-06 1.16202727377039e-06 9.4432037874029e-07 -2.33476893690276e-06 3.17943110100334e-05 -1.46749571538432e-05 -7.62073861660538e-07 2.19858402701226e-05 3.71013694766531e-05 -4.49372958370934e-06 -1.46749571538432e-05 8.36572211670778e-05 1.04451217499436e-05 7.85631915198253e-05 4.85678603543659e-05 -8.47230421850251e-06 -7.62073861660538e-07 1.04451217499436e-05 0.000112728811190947 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 976 0 0 3 0 0 2129 +633 667 0.984586733652278 0.0464352740825285 0.168620073647293 -0.0297280919480002 -0.0271953861304435 0.993031451690183 -0.114668857704709 0.0243636879712531 -0.172769716354326 0.108315748046935 0.978988418642365 0.0182398219174033 0.00033895159019177 0.000175783657674196 -5.65710564161917e-05 -1.95869683722268e-05 3.5491229799311e-05 0.000410371670291083 0.000175783657674196 0.000226287761846911 -2.91633005882022e-05 8.42695101795291e-06 2.8793255843206e-05 0.000187278757003441 -5.65710564161917e-05 -2.91633005882022e-05 2.67552614248872e-05 2.4498785964602e-07 -6.22207652468853e-06 -6.43272115768526e-05 -1.95869683722268e-05 8.42695101795291e-06 2.4498785964602e-07 4.28763739765449e-05 -4.0377345903627e-05 -3.04358143540659e-05 3.5491229799311e-05 2.8793255843206e-05 -6.22207652468853e-06 -4.0377345903627e-05 0.000154423489904398 3.27686217691191e-05 0.000410371670291083 0.000187278757003441 -6.43272115768526e-05 -3.04358143540659e-05 3.27686217691191e-05 0.000584224896043796 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 902 0 0 0 0 0 1999 +633 676 0.986793969206689 0.0448429803311374 0.155649508358779 -0.0257376226373286 -0.0289073904191113 0.99424304025841 -0.10317528617295 0.0052137193154895 -0.159380127733872 0.0973133290599712 0.982409329592711 0.00217411874058122 0.000347427005742157 0.000169615305423823 -6.56316551229559e-05 2.2993708483647e-05 1.20949662047952e-06 0.00032311682906549 0.000169615305423823 0.000160642662717197 -3.67309186219485e-05 1.26973359823994e-05 3.40195317913003e-05 0.000137333436031377 -6.56316551229559e-05 -3.67309186219485e-05 3.12420349617872e-05 -7.82947889655476e-06 -1.93816904468786e-07 -5.76485544589306e-05 2.2993708483647e-05 1.26973359823994e-05 -7.82947889655476e-06 3.77670101339853e-05 -3.42251410116951e-05 2.29369321149276e-05 1.20949662047952e-06 3.40195317913003e-05 -1.93816904468786e-07 -3.42251410116951e-05 0.000142668622592213 -1.94239746082086e-05 0.00032311682906549 0.000137333436031377 -5.76485544589306e-05 2.29369321149276e-05 -1.94239746082086e-05 0.000353261542070764 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1021 0 0 1 0 0 2076 +633 672 0.986892829915028 0.043782984077138 0.155324153201 -0.0271911448968086 -0.0281736522934683 0.994455908011497 -0.101309882723628 0.00938995838193311 -0.158898670789763 0.0956059481744189 0.982654931852945 -0.00367939593105159 0.000119044495882478 0.000100028172555648 -2.42508141965804e-05 4.48915208897922e-06 3.95479381144133e-05 7.50332949958312e-05 0.000100028172555648 0.000153208577240795 -2.44430604626705e-05 1.35755568256022e-05 2.57214555024323e-05 6.35279931023776e-05 -2.42508141965804e-05 -2.44430604626705e-05 2.03003047856306e-05 -3.82741111067213e-06 -6.69805529508187e-06 -9.75278376274106e-06 4.48915208897922e-06 1.35755568256022e-05 -3.82741111067213e-06 3.24194446242773e-05 -1.9811465151708e-05 -1.49892049513163e-06 3.95479381144133e-05 2.57214555024323e-05 -6.69805529508187e-06 -1.9811465151708e-05 9.58153873451837e-05 2.13629111137972e-05 7.50332949958312e-05 6.35279931023776e-05 -9.75278376274106e-06 -1.49892049513163e-06 2.13629111137972e-05 0.000110605510488461 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1062 0 0 2 0 0 2128 +633 674 0.989530113054484 0.0463982829993615 0.136665118787093 -0.0243208957694905 -0.0315344935586402 0.993543143440802 -0.108984392633851 -0.00290979554023671 -0.140839380410378 0.103533673056067 0.98460400540986 0.00485138834051121 0.000125482226334601 5.08830765140456e-05 -2.20885861684522e-05 -9.45299244270477e-07 2.84662845283232e-05 0.000120783557509731 5.08830765140456e-05 0.000158547834888815 -1.44366163866876e-05 1.00745880186064e-05 4.44858004039049e-05 3.15864194705717e-05 -2.20885861684522e-05 -1.44366163866876e-05 2.32779821114656e-05 -3.40704232933784e-06 -1.22902468909039e-05 -1.28734310002142e-05 -9.45299244270477e-07 1.00745880186064e-05 -3.40704232933784e-06 3.38531599539517e-05 -1.73012465136402e-05 -5.71908234227428e-06 2.84662845283232e-05 4.44858004039049e-05 -1.22902468909039e-05 -1.73012465136402e-05 0.000106126814619491 1.29757846543148e-05 0.000120783557509731 3.15864194705717e-05 -1.28734310002142e-05 -5.71908234227428e-06 1.29757846543148e-05 0.000185811037381263 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 959 0 0 2 0 0 2086 +633 665 0.983950839398098 0.0460867976304298 0.172385477149177 -0.0262596853956668 -0.0270979099124888 0.993458977241445 -0.110927741420961 0.0173862965346803 -0.176370204190368 0.10447615815368 0.978763650454641 0.00914138531149418 0.000233605924443203 0.000167495772194677 -4.10527482092016e-05 -5.69673319905523e-06 6.1032928751768e-05 0.000234382473158047 0.000167495772194677 0.00017928372227942 -3.31075732382663e-05 1.40337573008861e-06 4.73109417905228e-05 0.000164741554799579 -4.10527482092016e-05 -3.31075732382663e-05 2.54211898217579e-05 -1.26016392534932e-06 -1.10845465146191e-05 -3.40155948531683e-05 -5.69673319905523e-06 1.40337573008861e-06 -1.26016392534932e-06 2.29063360569606e-05 -1.07106011277167e-05 -5.15178996233236e-06 6.1032928751768e-05 4.73109417905228e-05 -1.10845465146191e-05 -1.07106011277167e-05 8.35764775909502e-05 5.78831315528695e-05 0.000234382473158047 0.000164741554799579 -3.40155948531683e-05 -5.15178996233236e-06 5.78831315528695e-05 0.000303044018517353 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1111 0 0 1 0 0 2074 +633 666 0.985401064478018 0.044194614634081 0.164412828462179 -0.0287435921315138 -0.0267327812921347 0.993905727092835 -0.106942807408675 0.0165227314753297 -0.168137147977405 0.100986344073876 0.980577206435382 0.00619097926360501 0.00015936706953327 6.80523927197414e-05 -1.59136205508375e-05 -1.57875416741434e-05 1.62582332696757e-05 0.000175204529925933 6.80523927197414e-05 0.000140717346745825 -8.68591306226079e-06 1.55533611917229e-06 1.00485941573562e-05 4.28223532119355e-05 -1.59136205508375e-05 -8.68591306226079e-06 1.7785768499948e-05 -6.88903711660441e-07 -1.85654821864248e-07 -2.11771052549179e-05 -1.57875416741434e-05 1.55533611917229e-06 -6.88903711660441e-07 3.4945221644692e-05 -3.40916237936954e-05 -2.23568328156966e-05 1.62582332696757e-05 1.00485941573562e-05 -1.85654821864248e-07 -3.40916237936954e-05 0.000123909972817607 1.67609175926453e-05 0.000175204529925933 4.28223532119355e-05 -2.11771052549179e-05 -2.23568328156966e-05 1.67609175926453e-05 0.000265256927971914 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 783 0 0 0 0 0 2080 +633 668 0.983557351780659 0.0455132002462432 0.17476694298855 -0.0219334944549886 -0.0262993217232978 0.993503338399372 -0.110722456015925 0.00804618246050856 -0.178670874613386 0.10430563356142 0.978364478797262 0.00938366079917561 0.00017231247109585 0.000128741576489588 -3.47438847967306e-05 1.37651472344055e-05 6.28721888795764e-06 0.000146278746860109 0.000128741576489588 0.000181345136161495 -3.01216615653417e-05 3.03471087847084e-05 -1.92617117706e-05 0.000101236689329487 -3.47438847967306e-05 -3.01216615653417e-05 2.45162384587823e-05 -3.07973158736054e-06 -2.33670234390962e-06 -2.55078427362197e-05 1.37651472344055e-05 3.03471087847084e-05 -3.07973158736054e-06 3.71995930929565e-05 -3.1889342716986e-05 7.59559506185266e-06 6.28721888795764e-06 -1.92617117706e-05 -2.33670234390962e-06 -3.1889342716986e-05 0.000102977548928367 2.43482956933132e-06 0.000146278746860109 0.000101236689329487 -2.55078427362197e-05 7.59559506185266e-06 2.43482956933132e-06 0.000181677774105243 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1034 0 0 0 0 0 2068 +633 662 0.984006293231284 0.0446806577585125 0.172439130430119 -0.0239904399822882 -0.0271285823778854 0.99432854999427 -0.102833723478532 0.0111385115776547 -0.176055828927631 0.0965110019042369 0.979637673638599 0.000132564488414222 0.000208220183592882 8.16707454851864e-05 -3.2072251038624e-05 -2.08832400039514e-05 6.56843494838666e-05 0.000233334653956586 8.16707454851864e-05 9.33427781005377e-05 -1.97975951569164e-05 2.27607356949534e-06 1.98190153783375e-05 6.56791721295085e-05 -3.2072251038624e-05 -1.97975951569164e-05 2.07297141218103e-05 3.50803677161986e-06 -1.11431215464078e-05 -3.30985262723616e-05 -2.08832400039514e-05 2.27607356949534e-06 3.50803677161986e-06 3.09177137847013e-05 -1.81815881188621e-05 -3.12941179207519e-05 6.56843494838666e-05 1.98190153783375e-05 -1.11431215464078e-05 -1.81815881188621e-05 8.17710831649361e-05 7.93851076894425e-05 0.000233334653956586 6.56791721295085e-05 -3.30985262723616e-05 -3.12941179207519e-05 7.93851076894425e-05 0.000323561506732395 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1163 0 0 0 0 0 2095 +633 661 0.984924961245677 0.0468419783438356 0.166519217449632 -0.0244704660444055 -0.0281101657680325 0.993183857467189 -0.113117831693713 0.0143132036951215 -0.170682861751541 0.106731693191053 0.979528308101851 0.0143819516543911 8.25773267246091e-05 7.2093106190725e-05 -1.9581621386277e-05 1.83429530683754e-06 7.27085784229047e-06 4.52924734536481e-05 7.2093106190725e-05 0.000105524073399632 -1.63752802740748e-05 2.06605815439374e-07 2.13235637481757e-05 3.41462455455936e-05 -1.9581621386277e-05 -1.63752802740748e-05 1.88739114373343e-05 -1.01182101896252e-07 1.22643299534713e-06 -6.67505817328972e-06 1.83429530683754e-06 2.06605815439374e-07 -1.01182101896252e-07 1.90284776911384e-05 -5.72227911973839e-06 3.93632507976848e-06 7.27085784229047e-06 2.13235637481757e-05 1.22643299534713e-06 -5.72227911973839e-06 5.74554399934908e-05 1.35982745151815e-06 4.52924734536481e-05 3.41462455455936e-05 -6.67505817328972e-06 3.93632507976848e-06 1.35982745151815e-06 6.54121737717054e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1058 0 0 0 0 0 2142 +633 660 0.984619747096356 0.0468653632164934 0.168308025234966 -0.0226061164679192 -0.0279902209965618 0.993221491980916 -0.112816733669112 0.00952384777644519 -0.172454345136536 0.106370604951696 0.979257266118429 0.0117332704418128 0.000203165804867317 0.000154185328859628 -3.74012422540693e-05 -2.00024398644611e-05 8.65955340695186e-05 0.000191247790106845 0.000154185328859628 0.000194871567753531 -3.10997249669341e-05 -1.80692105906027e-06 5.82920549810807e-05 0.000131697934965999 -3.74012422540693e-05 -3.10997249669341e-05 2.14977447369261e-05 2.9124810182424e-06 -1.43094229844638e-05 -3.05731431937852e-05 -2.00024398644611e-05 -1.80692105906027e-06 2.9124810182424e-06 3.11141099132267e-05 -2.46215825379532e-05 -2.36674297936116e-05 8.65955340695186e-05 5.82920549810807e-05 -1.43094229844638e-05 -2.46215825379532e-05 9.79194278828747e-05 8.96075368836867e-05 0.000191247790106845 0.000131697934965999 -3.05731431937852e-05 -2.36674297936116e-05 8.96075368836867e-05 0.00024817297709744 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1182 0 0 0 0 0 2149 +633 678 0.984358532764641 0.0456477116426995 0.170160410775326 -0.018089396707047 -0.0272114542241286 0.993653303429279 -0.109145083916271 -0.00642578405635061 -0.174062677597614 0.102807582433722 0.979353248456185 0.00435663448027045 0.000286157526897025 0.000184832962884394 -6.94192382954114e-05 -1.06006980420629e-05 9.88983357799053e-05 0.00027077223812097 0.000184832962884394 0.000209124846305128 -4.58387468287916e-05 6.71594698862046e-06 6.07503488206885e-05 0.000156188160274337 -6.94192382954114e-05 -4.58387468287916e-05 3.3416477715103e-05 -1.93637891645827e-07 -2.97508985658853e-05 -6.14943717457161e-05 -1.06006980420629e-05 6.71594698862046e-06 -1.93637891645827e-07 3.22978019293039e-05 -2.4371704053209e-05 -2.09361978159525e-05 9.88983357799053e-05 6.07503488206885e-05 -2.97508985658853e-05 -2.4371704053209e-05 0.000134445669229593 0.000102803945958951 0.00027077223812097 0.000156188160274337 -6.14943717457161e-05 -2.09361978159525e-05 0.000102803945958951 0.000321949049048315 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1064 0 0 1 0 0 2081 +633 659 0.985443205355599 0.046744730544654 0.16345219235235 -0.0241058730166511 -0.0283615005985538 0.99318496120023 -0.113045380841037 0.00867023502609297 -0.167622535186293 0.1067640529954 0.980053122379453 0.0118912455353727 0.000263609080754963 0.000157796635768397 -4.89598383316119e-05 8.07435727486065e-06 1.80984969758109e-05 0.000251981908922507 0.000157796635768397 0.000161907330345917 -3.27638845096512e-05 1.26227416821413e-05 1.41066904931547e-05 0.00012848931529928 -4.89598383316119e-05 -3.27638845096512e-05 2.54009710447604e-05 -4.06693714831155e-06 3.26578539070578e-07 -4.66046178199477e-05 8.07435727486065e-06 1.26227416821413e-05 -4.06693714831155e-06 2.44179323579221e-05 -1.05054837969756e-05 4.55789013412835e-06 1.80984969758109e-05 1.41066904931547e-05 3.26578539070578e-07 -1.05054837969756e-05 6.28439677124355e-05 1.49369649588852e-05 0.000251981908922507 0.00012848931529928 -4.66046178199477e-05 4.55789013412835e-06 1.49369649588852e-05 0.000310394712135495 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1173 0 0 0 0 0 2129 +633 664 0.984361112834072 0.04666390494389 0.169869595618092 -0.0245785654033076 -0.0269827143947945 0.992838470878724 -0.116377419919357 0.0147418965733912 -0.174083694422986 0.109973863797654 0.978570700878306 0.01650053447701 0.000306293477797746 0.000132130442486855 -5.17681185564217e-05 -5.52443037584074e-06 4.07209811738167e-05 0.000315393200179638 0.000132130442486855 0.000161251278313873 -2.98341843229515e-05 1.1102057133971e-05 2.66043248668125e-05 0.000104175697935676 -5.17681185564217e-05 -2.98341843229515e-05 2.66838742679718e-05 -2.17019709697046e-06 -7.59921325835108e-06 -5.21755101479226e-05 -5.52443037584074e-06 1.1102057133971e-05 -2.17019709697046e-06 2.5133505985804e-05 -6.14656437449398e-06 -9.39166821822847e-06 4.07209811738167e-05 2.66043248668125e-05 -7.59921325835108e-06 -6.14656437449398e-06 6.18805456676317e-05 3.84417188128494e-05 0.000315393200179638 0.000104175697935676 -5.21755101479226e-05 -9.39166821822847e-06 3.84417188128494e-05 0.000392930291691413 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1160 0 0 1 0 0 2043 +633 663 0.985317143144123 0.0463188304051629 0.16433104811995 -0.0270180485434793 -0.0282620246270001 0.993467039060539 -0.110564462031288 0.0172360825788973 -0.168378696367107 0.104296731732988 0.980189168660586 0.011881219719262 0.000276220612782501 0.000168335722808661 -6.25251256283203e-05 -9.52867785753896e-06 8.80727593306192e-05 0.00023374945686956 0.000168335722808661 0.000169120551481651 -4.12003065705455e-05 8.92649395589697e-06 4.50305124218208e-05 0.000109260556937907 -6.25251256283203e-05 -4.12003065705455e-05 3.12339679691818e-05 2.21590482457436e-06 -1.81447934832761e-05 -4.70109490591541e-05 -9.52867785753896e-06 8.92649395589697e-06 2.21590482457436e-06 2.80795011841113e-05 -2.28809824648012e-05 -1.76007858345832e-05 8.80727593306192e-05 4.50305124218208e-05 -1.81447934832761e-05 -2.28809824648012e-05 0.000109437067728382 8.23614457589576e-05 0.00023374945686956 0.000109260556937907 -4.70109490591541e-05 -1.76007858345832e-05 8.23614457589576e-05 0.000273960131434286 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1192 0 0 0 0 0 2111 +634 637 0.998933480450937 0.00297068235012825 0.0460768562355643 -0.00775093025207788 -0.0027950704230718 0.999988584971419 -0.00387524298460952 0.00347366676001634 -0.0460878423828703 0.0037423219041569 0.99893038086308 -0.00062066598233849 0.000129552652384779 9.25299667880011e-05 -2.18643396689587e-05 2.48014764829872e-05 -1.09885871744771e-05 5.85761910839177e-05 9.25299667880011e-05 0.000122442417236218 -1.58687367183756e-05 1.79493079778443e-05 1.62011958726113e-05 3.3248458930824e-05 -2.18643396689587e-05 -1.58687367183756e-05 2.29903576183159e-05 -9.13365989432424e-06 5.90320854851351e-06 -1.33073589724353e-05 2.48014764829872e-05 1.79493079778443e-05 -9.13365989432424e-06 2.92471246999767e-05 -7.4618191072666e-06 2.33650407575378e-05 -1.09885871744771e-05 1.62011958726113e-05 5.90320854851351e-06 -7.4618191072666e-06 6.66134889505269e-05 -2.35967301090941e-05 5.85761910839177e-05 3.3248458930824e-05 -1.33073589724353e-05 2.33650407575378e-05 -2.35967301090941e-05 9.53732398816115e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1499 0 0 0 0 0 2044 +634 636 0.999804259610491 0.00106021002690623 0.0197564779102261 -0.00824948315375269 -0.000882040644560797 0.999958886566059 -0.009024809242824 -0.000469580068236378 -0.0197652338468267 0.00900561670663738 0.999764089372445 0.00089905127190555 0.000166553569132418 8.80412101322353e-05 -2.00806120528316e-05 3.35041308014548e-05 -1.9274342850924e-05 6.53525650344267e-05 8.80412101322353e-05 0.000116742452847283 -1.12274543351772e-05 2.37813469361267e-05 7.59788855381467e-06 8.71855214652668e-07 -2.00806120528316e-05 -1.12274543351772e-05 2.42574166460369e-05 -1.09109485067937e-05 5.75301873468211e-06 -2.351707977074e-05 3.35041308014548e-05 2.37813469361267e-05 -1.09109485067937e-05 2.87815920148622e-05 -3.57989154286623e-06 2.42885896586384e-05 -1.9274342850924e-05 7.59788855381467e-06 5.75301873468211e-06 -3.57989154286623e-06 5.90416508882511e-05 -2.89963701657877e-05 6.53525650344267e-05 8.71855214652668e-07 -2.351707977074e-05 2.42885896586384e-05 -2.89963701657877e-05 0.000117256443748401 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1522 0 0 0 0 0 2086 +634 671 0.981526852488292 0.0369895717968039 0.187714702201813 -0.0271878227203477 -0.0162969129138083 0.993731032614745 -0.110603098726535 0.0183187047635333 -0.190629086117271 0.105500741214083 0.975976508492583 0.0167802750473764 0.000121089630173807 7.5017312769598e-05 -2.65889830344066e-05 7.62683764466233e-06 1.07223839180554e-05 8.47619661457335e-05 7.5017312769598e-05 0.000103526938916824 -2.43307046243247e-05 9.04365423674329e-06 8.78767036753653e-06 4.76682623796286e-05 -2.65889830344066e-05 -2.43307046243247e-05 2.53963280707885e-05 -7.5306697285882e-06 -1.00990598550994e-07 -1.75380976491798e-05 7.62683764466233e-06 9.04365423674329e-06 -7.5306697285882e-06 2.86963250551795e-05 -1.06137693476463e-05 7.57748045240305e-07 1.07223839180554e-05 8.78767036753653e-06 -1.00990598550994e-07 -1.06137693476463e-05 6.84078151524703e-05 -6.7571031091569e-07 8.47619661457335e-05 4.76682623796286e-05 -1.75380976491798e-05 7.57748045240305e-07 -6.7571031091569e-07 0.000115524567882239 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 965 0 0 8 0 0 2095 +634 673 0.987611207364689 0.0355122231732891 0.152849550516029 -0.0256011597933926 -0.0205241641280731 0.994921302138861 -0.0985411651907859 -0.000441977214116405 -0.155572689680758 0.0941832498675021 0.98332428713517 0.000303323027943751 0.000139740328105084 0.00013320824413707 -3.4388274605447e-05 1.60251718175036e-05 2.86779993471426e-05 7.81427292140884e-05 0.00013320824413707 0.00023956309432684 -3.95330473110343e-05 2.12472165285848e-05 3.40782823119236e-05 6.28457430713558e-05 -3.4388274605447e-05 -3.95330473110343e-05 2.77645785636866e-05 -7.0929205478887e-06 -1.01896150434364e-05 -1.38106971216967e-05 1.60251718175036e-05 2.12472165285848e-05 -7.0929205478887e-06 3.42799714582051e-05 -1.32385844987113e-05 3.79279856713792e-06 2.86779993471426e-05 3.40782823119236e-05 -1.01896150434364e-05 -1.32385844987113e-05 9.27144583397865e-05 4.7321945683106e-06 7.81427292140884e-05 6.28457430713558e-05 -1.38106971216967e-05 3.79279856713792e-06 4.7321945683106e-06 0.000101977522388317 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1029 0 0 11 0 0 2132 +634 674 0.988903389233039 0.0360437853010711 0.144121241684145 -0.0274400152788406 -0.0222054669021161 0.995085336393522 -0.0964991737490523 -0.003251240289234 -0.146891129763062 0.0922280805165165 0.984843630817182 -0.00460257692469173 0.000149485473117366 0.000100797758419334 -3.55229822764693e-05 1.05950491539367e-05 3.12128165159818e-05 0.000121221099903442 0.000100797758419334 0.000166142855624894 -2.29550363590629e-05 1.42039628267002e-05 3.84362086983298e-05 8.3355040839467e-05 -3.55229822764693e-05 -2.29550363590629e-05 2.6642562207059e-05 -3.2150421417712e-06 -1.00451698843306e-05 -2.77159515397503e-05 1.05950491539367e-05 1.42039628267002e-05 -3.2150421417712e-06 3.24510217889964e-05 -2.11341652473692e-05 6.51301755055195e-06 3.12128165159818e-05 3.84362086983298e-05 -1.00451698843306e-05 -2.11341652473692e-05 0.00011816085741932 2.08114158858677e-05 0.000121221099903442 8.3355040839467e-05 -2.77159515397503e-05 6.51301755055195e-06 2.08114158858677e-05 0.000170883155601171 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 956 0 0 3 0 0 2141 +634 668 0.980851218626216 0.0369028269763206 0.191230406265906 -0.0226216498182319 -0.0150680691157273 0.993320464145623 -0.114400213298086 0.00592088950119182 -0.194174767188199 0.109328115645883 0.974855642091038 0.0169073184097775 0.000231914654357884 0.000169485664273581 -4.67014507771698e-05 -1.52337831819439e-06 6.55872241344179e-05 0.000198161036654584 0.000169485664273581 0.000206856255890841 -4.08728509759577e-05 1.56133838058238e-05 3.9968111487773e-05 0.000130431250449687 -4.67014507771698e-05 -4.08728509759577e-05 2.55359829151966e-05 -4.11808275427258e-06 -1.30283432543084e-05 -4.03401911773611e-05 -1.52337831819439e-06 1.56133838058238e-05 -4.11808275427258e-06 3.31797852627905e-05 -2.29946387771585e-05 -1.16575124307958e-05 6.55872241344179e-05 3.9968111487773e-05 -1.30283432543084e-05 -2.29946387771585e-05 0.000106022074695963 6.58585605068957e-05 0.000198161036654584 0.000130431250449687 -4.03401911773611e-05 -1.16575124307958e-05 6.58585605068957e-05 0.000233605377949793 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1026 0 0 1 0 0 2048 +634 672 0.985754243074049 0.0364358842087309 0.164198046892878 -0.0243556863297882 -0.0194075750489357 0.994373157629248 -0.104141103398987 -0.000722558880392253 -0.167068603550241 0.0994708486360028 0.980914691489227 0.00533980661421819 0.00014091982298128 7.03591625458361e-05 -4.10954833971022e-05 1.33339048549561e-05 3.31290552373236e-05 8.27775592562098e-05 7.03591625458361e-05 9.26972399823533e-05 -2.24454455841808e-05 9.3857926479576e-06 1.85149216129797e-05 4.18644932935518e-05 -4.10954833971022e-05 -2.24454455841808e-05 2.76006758734487e-05 -6.77839368228851e-06 -1.32657806495458e-05 -2.44024428861921e-05 1.33339048549561e-05 9.3857926479576e-06 -6.77839368228851e-06 3.40669644676712e-05 -2.10723378072404e-05 2.25938177088297e-06 3.31290552373236e-05 1.85149216129797e-05 -1.32657806495458e-05 -2.10723378072404e-05 0.000101669914432996 2.7885512372302e-05 8.27775592562098e-05 4.18644932935518e-05 -2.44024428861921e-05 2.25938177088297e-06 2.7885512372302e-05 9.82971558586982e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1076 0 0 8 0 0 2123 +634 638 0.998673790400801 0.00971599939145152 0.0505594671878835 -0.00754084791921236 -0.0104859280566072 0.99983272949041 0.0149852711869839 -0.00153794943675546 -0.0504054131943089 -0.0154955605120017 0.998608622997583 -0.000281161784178418 6.81806410078192e-05 4.68001497235685e-05 -8.52276162198026e-06 3.09478185654938e-06 -6.90554740377628e-06 4.30137003894769e-07 4.68001497235685e-05 8.9662302510233e-05 -6.62704477588494e-06 9.77221045024993e-06 3.11025608832241e-07 -8.29225466894806e-06 -8.52276162198026e-06 -6.62704477588494e-06 2.12848387040946e-05 -4.6740999685028e-06 -4.75573510289765e-06 -2.90593519870183e-06 3.09478185654938e-06 9.77221045024993e-06 -4.6740999685028e-06 2.22594225670244e-05 -1.6854363784625e-06 9.95752686345478e-07 -6.90554740377628e-06 3.11025608832241e-07 -4.75573510289765e-06 -1.6854363784625e-06 4.71979586420849e-05 -4.97221068448259e-06 4.30137003894769e-07 -8.29225466894806e-06 -2.90593519870183e-06 9.95752686345478e-07 -4.97221068448259e-06 5.19333158094764e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1564 0 0 0 0 0 2028 +634 669 0.982360448450361 0.0363961613497261 0.183421015043015 -0.0280265874883897 -0.0167706253107593 0.994070816288443 -0.107433506553196 0.0165373095898299 -0.186243645387142 0.102462342558787 0.977146239265277 0.0124004228984343 0.000227955021025111 0.000151728244962979 -5.04506423134726e-05 1.7808671870998e-06 6.71606242721698e-05 0.000184468870456197 0.000151728244962979 0.000168544945230668 -4.42545817917715e-05 1.24964444747604e-05 4.49841496815482e-05 0.00010375575193424 -5.04506423134726e-05 -4.42545817917715e-05 3.03818561837944e-05 -7.9565260849078e-06 -1.54983601746014e-05 -3.80305924002562e-05 1.7808671870998e-06 1.24964444747604e-05 -7.9565260849078e-06 3.40490581425754e-05 -2.16991639285793e-05 -6.93681454844011e-06 6.71606242721698e-05 4.49841496815482e-05 -1.54983601746014e-05 -2.16991639285793e-05 0.000110917905066135 5.38391540177863e-05 0.000184468870456197 0.00010375575193424 -3.80305924002562e-05 -6.93681454844011e-06 5.38391540177863e-05 0.000209524298392066 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1072 0 0 1 0 0 2168 +634 665 0.980218139167633 0.0354975607456782 0.194710869824595 -0.0258318268046518 -0.015296347210193 0.994429471812883 -0.104288289620532 0.0174870526655731 -0.197328207331767 0.0992469081183771 0.975300789408157 0.00755867457917182 7.70576861689222e-05 5.68143496254469e-05 -2.34613858555746e-05 9.21583817867282e-06 1.25881600931829e-05 5.10403802516044e-05 5.68143496254469e-05 0.000130554552184931 -1.78565799415314e-05 9.67433927503557e-06 2.51294895773587e-05 3.0954680321152e-05 -2.34613858555746e-05 -1.78565799415314e-05 3.07858256550507e-05 -5.65809677829514e-06 -3.38500728609476e-06 -1.48676319739752e-05 9.21583817867282e-06 9.67433927503557e-06 -5.65809677829514e-06 2.51231683855034e-05 -4.64486533006913e-06 2.09834654305945e-06 1.25881600931829e-05 2.51294895773587e-05 -3.38500728609476e-06 -4.64486533006913e-06 6.7660602474653e-05 4.99839230246743e-07 5.10403802516044e-05 3.0954680321152e-05 -1.48676319739752e-05 2.09834654305945e-06 4.99839230246743e-07 7.61504908312788e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1122 0 0 5 0 0 2120 +634 670 0.981153700049979 0.036516949570618 0.189747013869239 -0.0248905030392105 -0.0156120380961646 0.993751206945568 -0.11052059971205 0.0120141143959633 -0.192597199213073 0.10547535773006 0.975592777631628 0.0165865999859586 0.000118681102594552 8.74400879980866e-05 -2.72792536908098e-05 6.02675413796329e-06 2.83967644661153e-05 7.54795565742595e-05 8.74400879980866e-05 0.000149955929472524 -3.08909264396797e-05 1.02087118442141e-05 4.98539155783894e-05 3.93620702748147e-05 -2.72792536908098e-05 -3.08909264396797e-05 2.34700131201742e-05 -6.09994952487617e-06 -7.56150781734151e-06 -1.86775985431824e-05 6.02675413796329e-06 1.02087118442141e-05 -6.09994952487617e-06 3.11140889193047e-05 -1.60080020757816e-05 3.08213800190233e-06 2.83967644661153e-05 4.98539155783894e-05 -7.56150781734151e-06 -1.60080020757816e-05 0.000105633849479301 8.5180995582143e-06 7.54795565742595e-05 3.93620702748147e-05 -1.86775985431824e-05 3.08213800190233e-06 8.5180995582143e-06 0.00010366283874103 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1082 0 0 4 0 0 2103 +634 675 0.985742143943757 0.0346329014589684 0.164660219208219 -0.0264121976016113 -0.0193436549583418 0.995425144719628 -0.0935660423057488 0.00174157890761834 -0.167147386057987 0.0890468606770723 0.981902443187479 -0.00220163904025278 0.000128109071457615 0.0001250717885203 -3.62158223172899e-05 3.77345878404521e-06 4.2871412138333e-05 7.51993075034815e-05 0.0001250717885203 0.000218236322829562 -3.34408207819708e-05 8.50003150688863e-06 4.79618306466233e-05 6.62042291547427e-05 -3.62158223172899e-05 -3.34408207819708e-05 2.9999656670164e-05 -4.25346377789599e-06 -1.48951315508327e-05 -1.51954445019494e-05 3.77345878404521e-06 8.50003150688863e-06 -4.25346377789599e-06 3.09582684332018e-05 -2.0350820285438e-05 1.00428892960996e-06 4.2871412138333e-05 4.79618306466233e-05 -1.48951315508327e-05 -2.0350820285438e-05 0.00011414105745824 2.03429056870139e-05 7.51993075034815e-05 6.62042291547427e-05 -1.51954445019494e-05 1.00428892960996e-06 2.03429056870139e-05 9.47695210181201e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 969 0 0 7 0 0 2123 +634 662 0.981987070845517 0.035403729398675 0.185601639639599 -0.0258331079060953 -0.0164719216680935 0.994589507329286 -0.102568941239773 0.0184976003299557 -0.188228766369018 0.0976641584981579 0.977257204453385 0.00862144287693825 0.000106684081790629 6.25855088931582e-05 -1.86192988009604e-05 2.00529060972592e-06 1.60892046349618e-05 7.79998178256505e-05 6.25855088931582e-05 0.000101500919399087 -1.95054689130694e-05 -8.21959229797512e-07 3.18771133368855e-05 2.69376811788863e-05 -1.86192988009604e-05 -1.95054689130694e-05 2.27413394655751e-05 1.04785840746274e-06 -6.79532160425064e-06 -9.69699569071549e-06 2.00529060972592e-06 -8.21959229797512e-07 1.04785840746274e-06 2.01480779990417e-05 -3.54584477320096e-06 -2.08080412223012e-06 1.60892046349618e-05 3.18771133368855e-05 -6.79532160425064e-06 -3.54584477320096e-06 7.08722605715437e-05 6.53355191240862e-06 7.79998178256505e-05 2.69376811788863e-05 -9.69699569071549e-06 -2.08080412223012e-06 6.53355191240862e-06 0.000113162275296138 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1178 0 0 2 0 0 2112 +634 667 0.983164887859403 0.0367655244446257 0.178983517377213 -0.0327373964248278 -0.0169261533727287 0.993661204149393 -0.111134678207934 0.0231245797236973 -0.181934902128235 0.106234210971277 0.977555105253356 0.0196784510543381 8.70525646451631e-05 5.92589777179925e-05 -1.95805970468211e-05 2.19157660333257e-06 1.78966155683678e-05 7.23445122659191e-05 5.92589777179925e-05 0.000130278143612109 -1.60242750225681e-05 9.34735082676077e-06 2.30376916693999e-05 4.73174724316769e-05 -1.95805970468211e-05 -1.60242750225681e-05 2.44514537298409e-05 -5.53452481379436e-06 -9.60229170520577e-06 -1.48271890156975e-05 2.19157660333257e-06 9.34735082676077e-06 -5.53452481379436e-06 3.11056203476651e-05 -1.28448877095851e-05 -8.06448041374571e-07 1.78966155683678e-05 2.30376916693999e-05 -9.60229170520577e-06 -1.28448877095851e-05 9.89324450636636e-05 1.53508883315874e-05 7.23445122659191e-05 4.73174724316769e-05 -1.48271890156975e-05 -8.06448041374571e-07 1.53508883315874e-05 0.000115733837594043 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 924 0 0 8 0 0 1988 +634 676 0.9839404269244 0.0344229231862467 0.175146506168816 -0.0257121318598533 -0.0177084114259544 0.995212753382715 -0.0961144508862437 0.00835752210437299 -0.177616577009576 0.091469327447559 0.979839636730263 0.00451172791961495 0.000124426426109792 0.000103643051512254 -3.24986281683519e-05 2.33849650497308e-05 -1.69645502042519e-07 7.94970583075513e-05 0.000103643051512254 0.000143887057821681 -3.04170212376837e-05 3.3415080112143e-05 -2.30989001419989e-05 6.49573824670594e-05 -3.24986281683519e-05 -3.04170212376837e-05 2.99446425982026e-05 -1.06263816321457e-05 -3.26076773725014e-06 -1.64829594196842e-05 2.33849650497308e-05 3.3415080112143e-05 -1.06263816321457e-05 3.52941463956292e-05 -1.96806368885602e-05 1.67658395128124e-05 -1.69645502042519e-07 -2.30989001419989e-05 -3.26076773725014e-06 -1.96806368885602e-05 8.43990243983491e-05 -1.1871678079709e-05 7.94970583075513e-05 6.49573824670594e-05 -1.64829594196842e-05 1.67658395128124e-05 -1.1871678079709e-05 8.94270084306448e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1039 0 0 5 0 0 2123 +634 661 0.982018863449323 0.0360619679066303 0.185306465889353 -0.0274581508926902 -0.0168745680957844 0.994424044212045 -0.10409644203594 0.0194849057944597 -0.188027127780226 0.0990977031200128 0.9771516998169 0.0104275282239069 0.000243598430300602 0.000137809926452348 -5.33962737437904e-05 -1.56138608970782e-05 6.55289237047555e-05 0.000227897339369425 0.000137809926452348 0.000134131833972289 -3.59624428234713e-05 5.51440341596554e-06 2.42285546199201e-05 0.000104461604845377 -5.33962737437904e-05 -3.59624428234713e-05 2.63988201142418e-05 3.29613700341751e-06 -1.51874085691579e-05 -4.6167767752427e-05 -1.56138608970782e-05 5.51440341596554e-06 3.29613700341751e-06 3.36184944681394e-05 -2.7370350310873e-05 -2.01440282461199e-05 6.55289237047555e-05 2.42285546199201e-05 -1.51874085691579e-05 -2.7370350310873e-05 0.000113627756017225 6.35225889876358e-05 0.000227897339369425 0.000104461604845377 -4.6167767752427e-05 -2.01440282461199e-05 6.35225889876358e-05 0.000282643852708057 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1050 0 0 2 0 0 2164 +634 666 0.983201808916643 0.0328831865899696 0.179535230477837 -0.0332452924781348 -0.0165971678812962 0.995669342277356 -0.091471825538232 0.0222767106969986 -0.18176560995238 0.0869554879732495 0.979489666178247 -0.00482038116829923 0.000132481977507249 6.54323142274096e-05 -1.80866956708546e-05 -6.68047822144171e-06 1.13003468855847e-05 0.00012092111995315 6.54323142274096e-05 0.000136410574331583 -1.70078126433066e-05 4.4016115781089e-06 3.06579811218176e-05 3.44515517369244e-05 -1.80866956708546e-05 -1.70078126433066e-05 1.80200602598975e-05 -1.84830298020071e-07 -2.26665813937904e-06 -1.77610864956856e-05 -6.68047822144171e-06 4.4016115781089e-06 -1.84830298020071e-07 3.77327775874213e-05 -3.2335260606053e-05 -5.39017831598935e-06 1.13003468855847e-05 3.06579811218176e-05 -2.26665813937904e-06 -3.2335260606053e-05 0.000139310286161148 4.54810944808036e-06 0.00012092111995315 3.44515517369244e-05 -1.77610864956856e-05 -5.39017831598935e-06 4.54810944808036e-06 0.000188096807515057 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 779 0 0 4 0 0 2115 +634 664 0.981956208875815 0.035707669605605 0.185706667035875 -0.0260779375791316 -0.0165745439600523 0.994483181526174 -0.103578405829087 0.0167135004243056 -0.188380700558079 0.09863145539287 0.97713077306179 0.00745888597540401 8.58714747805622e-05 7.01947101249031e-05 -1.92341804094403e-05 9.99926258913606e-06 2.50752654157843e-05 5.09288258366652e-05 7.01947101249031e-05 0.000121341771729189 -2.22477672653736e-05 1.49796534900259e-05 2.19339027305384e-05 3.74765132555339e-05 -1.92341804094403e-05 -2.22477672653736e-05 2.06018108206608e-05 -4.22125110213017e-06 -5.57429927603892e-06 -1.21686892642328e-05 9.99926258913606e-06 1.49796534900259e-05 -4.22125110213017e-06 2.63326880673264e-05 -7.30297676925794e-06 1.92182010052198e-06 2.50752654157843e-05 2.19339027305384e-05 -5.57429927603892e-06 -7.30297676925794e-06 6.46637016328359e-05 1.03397831035103e-05 5.09288258366652e-05 3.74765132555339e-05 -1.21686892642328e-05 1.92182010052198e-06 1.03397831035103e-05 7.85613183369455e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1184 0 0 5 0 0 2099 +634 663 0.981829999405322 0.0368323019302238 0.186153790727632 -0.0296603811977171 -0.016399982368104 0.993781784617353 -0.110130854627915 0.026222915219742 -0.189052619252081 0.105076858048145 0.976328818102107 0.0187097306378988 0.000202929828648454 0.000155214382525124 -4.79399131464013e-05 -7.79829658085609e-06 7.34179912206118e-05 0.000176034580294644 0.000155214382525124 0.000179447747249045 -4.2589274186395e-05 5.66266726889564e-06 5.23009349749104e-05 0.000116972146716548 -4.79399131464013e-05 -4.2589274186395e-05 2.74724433581923e-05 -1.27325515892615e-06 -1.71541241752115e-05 -3.60681189074115e-05 -7.79829658085609e-06 5.66266726889564e-06 -1.27325515892615e-06 2.79525068545478e-05 -1.48954382931435e-05 -1.16008199594926e-05 7.34179912206118e-05 5.23009349749104e-05 -1.71541241752115e-05 -1.48954382931435e-05 9.52003451563206e-05 6.8764176274829e-05 0.000176034580294644 0.000116972146716548 -3.60681189074115e-05 -1.16008199594926e-05 6.8764176274829e-05 0.000205378252339277 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1183 0 0 4 0 0 2119 +634 660 0.983434717851057 0.0355201271438256 0.177748351027229 -0.0264588645860456 -0.0177327301130282 0.994761185346212 -0.100676384576215 0.0126228408788618 -0.180393198341709 0.0958566883231723 0.978912554468357 0.00341974535952301 0.000230578509085263 0.000152058260133869 -4.28363141207456e-05 -2.02244737648443e-05 9.48802965970784e-05 0.000190069248685146 0.000152058260133869 0.000194501623336178 -3.10353144803478e-05 4.06010442402498e-06 4.9924381915816e-05 0.000110242078868334 -4.28363141207456e-05 -3.10353144803478e-05 2.53255168718034e-05 2.43590833068494e-07 -1.69102255587393e-05 -3.15238737128532e-05 -2.02244737648443e-05 4.06010442402498e-06 2.43590833068494e-07 3.17296631647608e-05 -2.45330257025677e-05 -2.57505561277546e-05 9.48802965970784e-05 4.9924381915816e-05 -1.69102255587393e-05 -2.45330257025677e-05 0.000104697195890002 8.34670229751257e-05 0.000190069248685146 0.000110242078868334 -3.15238737128532e-05 -2.57505561277546e-05 8.34670229751257e-05 0.00022888777874673 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1188 0 0 7 0 0 2199 +634 678 0.982257666859551 0.0367636387342032 0.183897555075243 -0.018139882117768 -0.0173248723348338 0.994192270695776 -0.106214771512059 -0.00574758193396796 -0.186734369343763 0.101144271987089 0.977189905571066 0.00620936601365899 0.000111632609944545 0.000103157619242173 -2.36460468536989e-05 -3.17876020139486e-06 5.4565186810516e-05 7.6397468521538e-05 0.000103157619242173 0.000186542015234274 -2.68912420024675e-05 -2.70419168224374e-06 6.04772431136016e-05 6.67413084461036e-05 -2.36460468536989e-05 -2.68912420024675e-05 2.41726844279996e-05 -3.75693619182739e-06 -1.17070477592501e-05 -1.37956660509131e-05 -3.17876020139486e-06 -2.70419168224374e-06 -3.75693619182739e-06 2.63065467512471e-05 -1.54337989258426e-05 -8.47097012290999e-06 5.4565186810516e-05 6.04772431136016e-05 -1.17070477592501e-05 -1.54337989258426e-05 9.8471135811724e-05 3.75838221573234e-05 7.6397468521538e-05 6.67413084461036e-05 -1.37956660509131e-05 -8.47097012290999e-06 3.75838221573234e-05 0.000101427850813969 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1083 0 0 2 0 0 2117 +635 639 0.998967386083462 0.0110245029954423 0.0440751843476482 -0.00747754666779848 -0.012287298430878 0.999518742063006 0.0284834436481333 0.000750488100229743 -0.0437399570055371 -0.0289955961913069 0.998622086458468 4.89436389746992e-05 8.76551031767954e-05 6.58172501163618e-05 -1.00541688267807e-05 9.68781383607785e-06 1.16922042332562e-05 1.46444127689498e-05 6.58172501163618e-05 8.89672353282466e-05 -8.03880268332022e-06 1.08770036781687e-05 1.62780984371817e-05 7.87852298631315e-06 -1.00541688267807e-05 -8.03880268332022e-06 2.30126879116378e-05 -8.07323242912095e-06 -6.65862177778886e-06 -8.59895472864445e-06 9.68781383607785e-06 1.08770036781687e-05 -8.07323242912095e-06 2.29676851548776e-05 7.09017901890179e-07 9.7165852227473e-06 1.16922042332562e-05 1.62780984371817e-05 -6.65862177778886e-06 7.09017901890179e-07 5.30259524864463e-05 -9.07209627376568e-06 1.46444127689498e-05 7.87852298631315e-06 -8.59895472864445e-06 9.7165852227473e-06 -9.07209627376568e-06 7.31997983947587e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1549 0 0 0 0 0 2021 +635 673 0.990639922563322 0.0351280265237038 0.13190362230161 -0.0237976871073301 -0.0236880227983984 0.995898748484458 -0.0873187284778707 -4.14819978421527e-05 -0.134429986980727 0.0833768824053737 0.987409172572709 -0.000598354708535001 0.000215276230068207 0.000162137260131884 -4.14114711495276e-05 2.53946058949632e-05 2.08247902767459e-05 0.000132822688735898 0.000162137260131884 0.000176440252185642 -2.77393481214967e-05 1.79579733458914e-05 2.06018670328385e-05 0.000109200677823526 -4.14114711495276e-05 -2.77393481214967e-05 2.46780366444668e-05 -8.0825945607148e-06 -3.25664869371202e-06 -2.19033828669152e-05 2.53946058949632e-05 1.79579733458914e-05 -8.0825945607148e-06 3.31864696581626e-05 -1.81826104234019e-05 1.65977819371563e-05 2.08247902767459e-05 2.06018670328385e-05 -3.25664869371202e-06 -1.81826104234019e-05 9.83034082621874e-05 2.86302524315316e-07 0.000132822688735898 0.000109200677823526 -2.19033828669152e-05 1.65977819371563e-05 2.86302524315316e-07 0.000142578598524926 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1031 0 0 11 0 0 2238 +635 638 0.998960757547165 0.0106457449634135 0.0443178631588587 -0.000535208021758937 -0.0119819492759368 0.99947823543818 0.0299948291698802 -0.000772426586122259 -0.0439754223668432 -0.0304946716584286 0.998567092001385 -0.00188859176699241 5.89810823804665e-05 2.94806544023499e-05 -1.26928172684907e-05 -1.25931828094912e-06 -1.59835001888964e-06 -2.8164968149112e-06 2.94806544023499e-05 5.45304152496299e-05 -9.15099775305361e-06 6.94195563316381e-06 -8.0348749653712e-07 -9.77848948467636e-06 -1.26928172684907e-05 -9.15099775305361e-06 2.04915041558105e-05 -3.82494155467412e-06 -2.18895365039109e-06 8.01537232648632e-07 -1.25931828094912e-06 6.94195563316381e-06 -3.82494155467412e-06 2.23064704208226e-05 -2.75787410874451e-06 4.15869886677967e-06 -1.59835001888964e-06 -8.0348749653712e-07 -2.18895365039109e-06 -2.75787410874451e-06 4.72546565824808e-05 -6.48496614914448e-06 -2.8164968149112e-06 -9.77848948467636e-06 8.01537232648632e-07 4.15869886677967e-06 -6.48496614914448e-06 4.28649305662445e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1588 0 0 0 0 0 2017 +635 670 0.985227236600472 0.0339996013586955 0.16784313917479 -0.0226396662544209 -0.0187008631554041 0.995592422680465 -0.0919021524148671 0.00741877478923435 -0.170227994107435 0.0874056920840537 0.98152059327019 0.00277078071826517 9.16897902640054e-05 6.10359653115544e-05 -2.23589886022159e-05 -2.74482149997362e-06 3.74289638143711e-05 4.92675134272775e-05 6.10359653115544e-05 0.000114097112032495 -1.57217831708862e-05 -2.52917708185551e-06 5.07555446425826e-05 2.163577185235e-05 -2.23589886022159e-05 -1.57217831708862e-05 1.98070574369728e-05 -2.16506104838254e-06 -1.24529304612748e-05 -1.15332869001245e-05 -2.74482149997362e-06 -2.52917708185551e-06 -2.16506104838254e-06 3.71249776755385e-05 -4.07022936344894e-05 -8.59092356756833e-06 3.74289638143711e-05 5.07555446425826e-05 -1.24529304612748e-05 -4.07022936344894e-05 0.000166101627290715 2.53624984077906e-05 4.92675134272775e-05 2.163577185235e-05 -1.15332869001245e-05 -8.59092356756833e-06 2.53624984077906e-05 8.62211994021233e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1109 0 0 4 0 0 2179 +635 669 0.984489320452442 0.0347674590909561 0.171965117693814 -0.0258205097523832 -0.0182746994489546 0.995157744173801 -0.0965769101336433 0.0206497775545082 -0.17449015237296 0.0919363257873085 0.980357536170142 0.0121861214025129 0.000136444376189397 0.00010086736227477 -3.71628240656889e-05 4.85311003305435e-06 4.97186186278082e-05 8.90592309807594e-05 0.00010086736227477 0.000139616702370919 -3.07830800257492e-05 5.45152894349057e-06 4.63299129947812e-05 5.83940592299937e-05 -3.71628240656889e-05 -3.07830800257492e-05 2.54026820470892e-05 -5.87612627549525e-06 -1.82223968603929e-05 -2.37992939546474e-05 4.85311003305435e-06 5.45152894349057e-06 -5.87612627549525e-06 2.9134645249252e-05 -1.29842396397241e-05 5.35179327325834e-06 4.97186186278082e-05 4.63299129947812e-05 -1.82223968603929e-05 -1.29842396397241e-05 0.000106944356350964 3.05273282511123e-05 8.90592309807594e-05 5.83940592299937e-05 -2.37992939546474e-05 5.35179327325834e-06 3.05273282511123e-05 0.000118259279936159 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1103 0 0 1 0 0 2239 +635 637 0.999585036266836 0.00271039787250458 0.0286776745012656 -0.0040896746096785 -0.00286739366370953 0.999981120385074 0.00543478858744479 0.00429847165493347 -0.0286624026383891 -0.00551476352943844 0.999573936263951 -0.00315897805173673 0.000101310166037159 8.13814246517387e-05 -1.07312652777428e-05 1.6353696962213e-05 -3.07539081445355e-06 2.16369438562998e-05 8.13814246517387e-05 0.000111449827440288 -9.58191798720594e-06 1.62993787145307e-05 3.66172109064709e-06 1.0837434726051e-05 -1.07312652777428e-05 -9.58191798720594e-06 2.0593853710042e-05 -6.03671665700264e-06 -2.40112063385448e-07 -9.32672520484721e-06 1.6353696962213e-05 1.62993787145307e-05 -6.03671665700264e-06 2.54936761241156e-05 5.57683501286878e-07 4.9199780831803e-06 -3.07539081445355e-06 3.66172109064709e-06 -2.40112063385448e-07 5.57683501286878e-07 5.39960144483413e-05 2.06619176349885e-06 2.16369438562998e-05 1.0837434726051e-05 -9.32672520484721e-06 4.9199780831803e-06 2.06619176349885e-06 7.54454884363425e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1562 0 0 0 0 0 2134 +635 666 0.984382737103918 0.0331480458418607 0.17289255029834 -0.0252216329789769 -0.0181318141368604 0.995980131809099 -0.0877200909577533 0.0201351519138109 -0.175105294631272 0.0832152876483406 0.981026682457567 0.00111947622069938 0.000130180012462615 9.16168201126452e-05 -2.49271543309667e-05 4.8837804311481e-06 1.88266912427977e-06 9.32524143164042e-05 9.16168201126452e-05 0.000157090226405001 -2.06272644995472e-05 2.00535813847105e-05 -1.82593229179015e-05 4.26185375959215e-05 -2.49271543309667e-05 -2.06272644995472e-05 2.38257680777955e-05 -4.77569133976204e-06 -6.44345074396228e-07 -1.81865910729958e-05 4.8837804311481e-06 2.00535813847105e-05 -4.77569133976204e-06 3.64387492106544e-05 -3.15294748023757e-05 -7.90823275079132e-08 1.88266912427977e-06 -1.82593229179015e-05 -6.44345074396228e-07 -3.15294748023757e-05 0.000122180569172655 6.67224493380037e-06 9.32524143164042e-05 4.26185375959215e-05 -1.81865910729958e-05 -7.90823275079132e-08 6.67224493380037e-06 0.000126107108806248 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 796 0 0 4 0 0 2212 +635 674 0.990932868260101 0.035960424322148 0.129456164335192 -0.0236303659685757 -0.0240295511076704 0.995416070742115 -0.0925711984468821 -0.000118482612693722 -0.132191646012042 0.0886210696781484 0.987254614946787 0.00254648993759427 8.71208148340089e-05 5.95746109602322e-05 -2.16170770640304e-05 2.75154566393678e-06 2.78346092883206e-05 3.71180667617172e-05 5.95746109602322e-05 0.000182280457525416 -1.08284758379939e-05 1.63174263953517e-05 2.27609775376644e-05 5.1987843265062e-05 -2.16170770640304e-05 -1.08284758379939e-05 2.16480088568162e-05 -3.47588058995763e-06 -7.72480792192888e-06 -4.07754343083779e-06 2.75154566393678e-06 1.63174263953517e-05 -3.47588058995763e-06 3.15688714645558e-05 -1.42855595125084e-05 1.71681374780823e-06 2.78346092883206e-05 2.27609775376644e-05 -7.72480792192888e-06 -1.42855595125084e-05 8.30834880361906e-05 1.30173179056001e-05 3.71180667617172e-05 5.1987843265062e-05 -4.07754343083779e-06 1.71681374780823e-06 1.30173179056001e-05 7.96184645317479e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 985 0 0 3 0 0 2227 +635 672 0.988985751396657 0.0341032325046523 0.144028306478703 -0.0225421931482445 -0.0214288820081351 0.995832225332369 -0.0886508996314362 -0.00307161084245034 -0.146451311193417 0.0845881109986219 0.985594675780776 -0.000536422271994515 0.000135753656266495 6.98548610769322e-05 -2.918935584946e-05 6.81601595693603e-06 3.47234004616419e-05 9.88878646206485e-05 6.98548610769322e-05 0.000119258302026631 -1.80576532611114e-05 1.68115210707573e-05 1.53096056083691e-05 3.35453401679087e-05 -2.918935584946e-05 -1.80576532611114e-05 2.18120570543366e-05 -4.77281629867076e-06 -9.76613311267436e-06 -1.8145073296763e-05 6.81601595693603e-06 1.68115210707573e-05 -4.77281629867076e-06 3.27660239710917e-05 -2.04264685281069e-05 -7.576888649014e-07 3.47234004616419e-05 1.53096056083691e-05 -9.76613311267436e-06 -2.04264685281069e-05 0.000101632041778953 2.98192973670984e-05 9.88878646206485e-05 3.35453401679087e-05 -1.8145073296763e-05 -7.576888649014e-07 2.98192973670984e-05 0.000141473863069336 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1073 0 0 8 0 0 2211 +635 676 0.985210203095137 0.0347486470334186 0.167789711384774 -0.0193478506226388 -0.0188768364421385 0.995271691392605 -0.0952781473289603 0.00471466526767841 -0.170307136559734 0.0907016639420094 0.981207769738385 0.00780103942183153 0.000114610137754104 7.48559087611263e-05 -2.18259070938353e-05 -6.15929908183944e-08 1.9018453204787e-05 7.25931794693748e-05 7.48559087611263e-05 0.000120734975865061 -8.3200143049192e-06 -1.40289885193036e-06 2.18899421890145e-05 4.24579025886593e-05 -2.18259070938353e-05 -8.3200143049192e-06 2.52888976966776e-05 -4.93012942364506e-06 -3.58182264228962e-06 -1.0387362631247e-05 -6.15929908183944e-08 -1.40289885193036e-06 -4.93012942364506e-06 3.29796266125233e-05 -2.7274010251543e-05 -1.76296159394334e-06 1.9018453204787e-05 2.18899421890145e-05 -3.58182264228962e-06 -2.7274010251543e-05 0.000101388375089046 1.33321443929738e-05 7.25931794693748e-05 4.24579025886593e-05 -1.0387362631247e-05 -1.76296159394334e-06 1.33321443929738e-05 8.57649460836266e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1059 0 0 5 0 0 2241 +635 671 0.985795751523139 0.0348953654602195 0.164283443317724 -0.024213043185614 -0.0199795528563376 0.995596777264845 -0.09158534035268 0.0164937834978429 -0.166755970647503 0.0870021296822851 0.982152267056466 0.00665823873944834 9.36244684445685e-05 8.72274175663852e-05 -2.16211462950677e-05 6.08791186395181e-06 2.41519327717975e-05 5.00654908657926e-05 8.72274175663852e-05 0.000155505035026682 -2.29322326243929e-05 1.71252664249053e-05 1.52008525089114e-05 3.79602404528848e-05 -2.16211462950677e-05 -2.29322326243929e-05 2.07730846709351e-05 -3.55713846612133e-06 -8.67266537277666e-06 -1.15742145183532e-05 6.08791186395181e-06 1.71252664249053e-05 -3.55713846612133e-06 2.94269713664536e-05 -1.66132552436989e-05 6.55469623628222e-06 2.41519327717975e-05 1.52008525089114e-05 -8.67266537277666e-06 -1.66132552436989e-05 8.22860750761577e-05 4.81367750262971e-06 5.00654908657926e-05 3.79602404528848e-05 -1.15742145183532e-05 6.55469623628222e-06 4.81367750262971e-06 8.23519462689191e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1008 0 0 8 0 0 2193 +635 678 0.984691282699673 0.0359356644931388 0.17056290860767 -0.0156819768138066 -0.0184633928563298 0.994516126903612 -0.102940645290726 -0.00622199486047782 -0.17332680375379 0.0982155860649151 0.979954854957319 0.0124417016815923 0.00013380023876054 9.83271683636579e-05 -3.30149967389536e-05 1.90166089021173e-06 5.06313590691957e-05 9.13889168477994e-05 9.83271683636579e-05 0.000133788366287016 -2.79174643020905e-05 7.71572507813887e-06 3.78077781399183e-05 6.84045358396248e-05 -3.30149967389536e-05 -2.79174643020905e-05 2.36182825689932e-05 -5.92648164856503e-06 -1.41152842380545e-05 -1.97615187228584e-05 1.90166089021173e-06 7.71572507813887e-06 -5.92648164856503e-06 3.31099438893097e-05 -2.24984044801758e-05 -2.20468385993096e-06 5.06313590691957e-05 3.78077781399183e-05 -1.41152842380545e-05 -2.24984044801758e-05 0.000103496996718997 3.79582398665613e-05 9.13889168477994e-05 6.84045358396248e-05 -1.97615187228584e-05 -2.20468385993096e-06 3.79582398665613e-05 0.000100822339273143 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1077 0 0 2 0 0 2194 +635 664 0.986083175545518 0.0342515540023605 0.162686207019802 -0.0253320926730736 -0.0196741905335323 0.995712591128094 -0.0903845235415148 0.0151468897667047 -0.165084515121549 0.0859259385599003 0.98252930538976 0.00251348535003725 0.000188959505066049 0.00012316141612751 -2.86074486387826e-05 -4.04119034302653e-07 3.04609742009598e-05 0.000155772729022276 0.00012316141612751 0.000144561890416172 -2.46175527175381e-05 1.03562904451056e-05 1.91743167564806e-05 8.55053522836919e-05 -2.86074486387826e-05 -2.46175527175381e-05 2.05479509612333e-05 -3.64127650342805e-06 -3.45208081981209e-06 -2.31023973043888e-05 -4.04119034302653e-07 1.03562904451056e-05 -3.64127650342805e-06 2.87442980270811e-05 -1.37554947023327e-05 -7.63100781410606e-06 3.04609742009598e-05 1.91743167564806e-05 -3.45208081981209e-06 -1.37554947023327e-05 7.73916136001303e-05 2.929854418804e-05 0.000155772729022276 8.55053522836919e-05 -2.31023973043888e-05 -7.63100781410606e-06 2.929854418804e-05 0.000190435251062217 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1193 0 0 5 0 0 2204 +635 665 0.985236832623304 0.0348852879184234 0.167604893512238 -0.0255758301972898 -0.0189340371707979 0.995216288701731 -0.0958438362085351 0.0173454561744809 -0.170146659910839 0.0912554403287956 0.981184263393774 0.0118141989403908 0.000154946566857116 0.000111390337250719 -2.79267439915371e-05 -2.65264830741494e-06 5.74373982948649e-05 0.000117826890552613 0.000111390337250719 0.0001903979493504 -1.83714013043353e-05 6.87084853372377e-06 4.74793825146423e-05 7.11958597226468e-05 -2.79267439915371e-05 -1.83714013043353e-05 2.41401320777194e-05 -4.38042540046135e-06 -9.54912185335195e-06 -1.81342678265469e-05 -2.65264830741494e-06 6.87084853372377e-06 -4.38042540046135e-06 2.81332262030292e-05 -8.47892903294617e-06 -3.70892466619922e-06 5.74373982948649e-05 4.74793825146423e-05 -9.54912185335195e-06 -8.47892903294617e-06 8.55617097346517e-05 4.01954426075821e-05 0.000117826890552613 7.11958597226468e-05 -1.81342678265469e-05 -3.70892466619922e-06 4.01954426075821e-05 0.000141082571844257 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1129 0 0 5 0 0 2186 +635 668 0.985133995357194 0.0337886371948404 0.168432001674527 -0.0216368470102628 -0.0184622480221395 0.995611494116907 -0.0917436547139272 0.00833597086550072 -0.170792729908335 0.0872701597272214 0.981434543223156 0.00512261718396987 0.00011229209802498 0.000109128361390905 -1.87538052206485e-05 1.84696493492258e-05 2.97910761757277e-06 7.50272479853287e-05 0.000109128361390905 0.000204977041144083 -1.35295637656828e-05 3.1263105319295e-05 -1.2858659715183e-06 7.16164215736769e-05 -1.87538052206485e-05 -1.35295637656828e-05 1.8312776612041e-05 -4.76003917333262e-06 -4.34079868384864e-07 -1.037040755389e-05 1.84696493492258e-05 3.1263105319295e-05 -4.76003917333262e-06 3.28638680268768e-05 -2.28933217338896e-05 9.66269142564978e-06 2.97910761757277e-06 -1.2858659715183e-06 -4.34079868384864e-07 -2.28933217338896e-05 9.76364884757909e-05 5.52601018114296e-06 7.50272479853287e-05 7.16164215736769e-05 -1.037040755389e-05 9.66269142564978e-06 5.52601018114296e-06 9.74777312298583e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1044 0 0 1 0 0 2202 +635 667 0.987597352846773 0.0341211716332752 0.153255389126838 -0.0335101604917347 -0.0200677458151277 0.995526459146094 -0.0923274320987035 0.0246282068768412 -0.155720115039597 0.0881068373420239 0.983864030740854 0.00939593293349276 0.000306470994361325 0.000156669160875967 -4.48952394674404e-05 -1.13894134483231e-05 1.05470189887614e-05 0.000325950196679114 0.000156669160875967 0.000204178756268711 -2.58006961412951e-05 1.51433514946685e-05 4.19570071913213e-06 0.000138425222497539 -4.48952394674404e-05 -2.58006961412951e-05 2.41354546376107e-05 -7.14812676581155e-06 -1.1962933425904e-06 -4.25944625808892e-05 -1.13894134483231e-05 1.51433514946685e-05 -7.14812676581155e-06 3.8349217388081e-05 -1.70422117701831e-05 -2.02040119345716e-05 1.05470189887614e-05 4.19570071913213e-06 -1.1962933425904e-06 -1.70422117701831e-05 8.52705240577356e-05 1.50084870737919e-05 0.000325950196679114 0.000138425222497539 -4.25944625808892e-05 -2.02040119345716e-05 1.50084870737919e-05 0.000421746995553897 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 912 0 0 8 0 0 2103 +635 675 0.987639635595827 0.0352702848267639 0.152721829508361 -0.0207527602352555 -0.0213865398110477 0.995564788977477 -0.0916153200242268 0.00303661607126965 -0.155275774398495 0.0872167297969259 0.984013554748347 0.00405496733769949 0.000128036777951521 0.000103782900757754 -2.01222707022761e-05 6.87841572490703e-06 1.22694848063336e-05 7.07819349011698e-05 0.000103782900757754 0.00015994270034964 -1.51066395698649e-05 4.58171542769597e-06 2.25057226672594e-05 6.9432310228066e-05 -2.01222707022761e-05 -1.51066395698649e-05 1.9979401787102e-05 -2.7405662122921e-06 -5.34510211093312e-06 -7.84534444781358e-06 6.87841572490703e-06 4.58171542769597e-06 -2.7405662122921e-06 2.89892118411061e-05 -1.59633664247552e-05 5.79768565383516e-06 1.22694848063336e-05 2.25057226672594e-05 -5.34510211093312e-06 -1.59633664247552e-05 8.57796018522724e-05 5.31355250048195e-06 7.07819349011698e-05 6.9432310228066e-05 -7.84534444781358e-06 5.79768565383516e-06 5.31355250048195e-06 8.61906445079939e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1002 0 0 7 0 0 2220 +635 662 0.98603277760589 0.0356374691103067 0.162693983546492 -0.0248060261166314 -0.0196441908654205 0.994906097108863 -0.098873473191006 0.015965033702451 -0.165388836540007 0.0942964937366263 0.981710091634451 0.0154582137145211 0.000241020351372787 5.8892098208406e-05 -3.59980882344305e-05 -5.27196995845888e-05 0.00012528003666583 0.00024322320079184 5.8892098208406e-05 0.000203324583600203 -1.89488682779802e-05 1.22103745094502e-05 5.11713882173453e-05 4.71986500355044e-07 -3.59980882344305e-05 -1.89488682779802e-05 2.2766485689284e-05 1.2555665282753e-06 -1.59674240412437e-05 -2.76571278858428e-05 -5.27196995845888e-05 1.22103745094502e-05 1.2555665282753e-06 5.1671669064223e-05 -4.90854713627796e-05 -7.41994466817153e-05 0.00012528003666583 5.11713882173453e-05 -1.59674240412437e-05 -4.90854713627796e-05 0.000159373259349295 0.00014561500772877 0.00024322320079184 4.71986500355044e-07 -2.76571278858428e-05 -7.41994466817153e-05 0.00014561500772877 0.000326964876914141 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1200 0 0 2 0 0 2202 +635 663 0.985556387793387 0.0346319110292576 0.165768625554153 -0.0261390436163017 -0.019475268591568 0.995550059090069 -0.0921997492352659 0.0206319446277917 -0.168224018478153 0.0876396633050425 0.981845185873435 0.00762830889319777 0.000198169422535726 0.000118297659844422 -4.25222480413283e-05 -1.44361136056578e-05 5.97720209934095e-05 0.000151107335594333 0.000118297659844422 0.000126320781778734 -2.73395990686281e-05 -8.2549728443212e-07 3.38635012672996e-05 7.47557229282066e-05 -4.25222480413283e-05 -2.73395990686281e-05 2.38187865921881e-05 2.41542727939443e-07 -1.50193708737589e-05 -2.76415404513619e-05 -1.44361136056578e-05 -8.2549728443212e-07 2.41542727939443e-07 2.44216298293969e-05 -1.14438011508565e-05 -1.07701356201559e-05 5.97720209934095e-05 3.38635012672996e-05 -1.50193708737589e-05 -1.14438011508565e-05 7.26772589208472e-05 4.68786487488031e-05 0.000151107335594333 7.47557229282066e-05 -2.76415404513619e-05 -1.07701356201559e-05 4.68786487488031e-05 0.0001750622073011 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1211 0 0 4 0 0 2225 +635 661 0.984404993005624 0.034904441155533 0.172419516683051 -0.0225813837904292 -0.0193550233943337 0.995657738298816 -0.0910552098184986 0.0185980630228569 -0.174849057232236 0.0862980194054646 0.980806025181173 0.00497419159348563 8.74348510808012e-05 6.26034568765971e-05 -2.08131263071086e-05 4.11746280063145e-06 9.66998096337372e-06 5.45428865476562e-05 6.26034568765971e-05 0.000112982959870121 -1.80500901105662e-05 5.3534385558128e-06 2.74262610757762e-05 2.69062553458241e-05 -2.08131263071086e-05 -1.80500901105662e-05 2.04170871988821e-05 -4.55786791921755e-06 -4.26792573434859e-06 -9.60874098937839e-06 4.11746280063145e-06 5.3534385558128e-06 -4.55786791921755e-06 2.33389947729409e-05 -5.37220220302509e-06 5.25971766570836e-06 9.66998096337372e-06 2.74262610757762e-05 -4.26792573434859e-06 -5.37220220302509e-06 6.17000989321605e-05 -3.95932201005345e-06 5.45428865476562e-05 2.69062553458241e-05 -9.60874098937839e-06 5.25971766570836e-06 -3.95932201005345e-06 7.80002492891749e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1115 0 0 2 0 0 2270 +636 640 0.999178372504833 0.00892301322089274 0.0395342857992139 -0.00322570332581292 -0.0101479049025729 0.999471228822585 0.0308914677857933 0.00192157905864574 -0.0392377362328982 -0.031267276679176 0.998740585669965 0.00118360614154728 9.98710799079423e-05 5.18122691377705e-05 -1.42491909914986e-05 1.13122246812208e-05 -4.39577782755567e-06 1.624004989424e-05 5.18122691377705e-05 6.85586397411962e-05 -1.30602844719185e-05 9.69217154096263e-06 1.07243594375605e-05 -4.28616751048843e-07 -1.42491909914986e-05 -1.30602844719185e-05 2.03656794606742e-05 -4.37606211695351e-06 -9.86021925910871e-07 -7.10369355505088e-06 1.13122246812208e-05 9.69217154096263e-06 -4.37606211695351e-06 2.16511154000467e-05 -5.82724422852787e-06 6.45619401767867e-06 -4.39577782755567e-06 1.07243594375605e-05 -9.86021925910871e-07 -5.82724422852787e-06 5.78693056239996e-05 -1.89167803247512e-05 1.624004989424e-05 -4.28616751048843e-07 -7.10369355505088e-06 6.45619401767867e-06 -1.89167803247512e-05 5.71490675762662e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1502 0 0 0 0 0 1939 +636 672 0.989700815605278 0.032091999934224 0.139507702763934 -0.0221047923565764 -0.0207588560992264 0.996420570682735 -0.0819458126675447 0.00926355697552189 -0.141638149817414 0.0782058173060961 0.98682444469915 -0.00103336410316591 0.000117467665140878 6.75285572771529e-05 -2.48586373687044e-05 1.41652592330789e-05 7.18072934685922e-06 4.81538019722364e-05 6.75285572771529e-05 0.000114324317125544 -1.30579804435086e-05 1.26609870227829e-05 7.78318027606942e-06 1.46805101891564e-05 -2.48586373687044e-05 -1.30579804435086e-05 2.48425768402818e-05 -5.02572571854922e-06 -5.16173851695856e-06 -9.65937051222927e-06 1.41652592330789e-05 1.26609870227829e-05 -5.02572571854922e-06 2.82339143233454e-05 -6.29221536247262e-06 6.0592160651089e-06 7.18072934685922e-06 7.78318027606942e-06 -5.16173851695856e-06 -6.29221536247262e-06 6.37415254896891e-05 -5.89275521205864e-06 4.81538019722364e-05 1.46805101891564e-05 -9.65937051222927e-06 6.0592160651089e-06 -5.89275521205864e-06 8.43601987192159e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1096 0 0 8 0 0 2156 +636 639 0.999416671237802 0.0124865307534173 0.0317868495088103 -0.00349362292619911 -0.0133502616094231 0.999543387443947 0.0271069572626539 0.00240595992019493 -0.0314338633787155 -0.0275155077515088 0.999127023489138 -0.000188234290415677 9.32619030003354e-05 6.21603480304376e-05 -5.96764234783775e-06 1.0400198305926e-05 -7.19667762460524e-06 5.97118069637777e-06 6.21603480304376e-05 9.94139248068925e-05 -4.81701541443072e-06 9.10832689087594e-06 1.41068177903883e-05 -7.21603474938559e-06 -5.96764234783775e-06 -4.81701541443072e-06 1.8091590351634e-05 -4.36560881781335e-06 -5.3642282557049e-07 -4.58805290628606e-06 1.0400198305926e-05 9.10832689087594e-06 -4.36560881781335e-06 2.09406419072537e-05 -6.22393574996358e-06 6.74262026414048e-06 -7.19667762460524e-06 1.41068177903883e-05 -5.3642282557049e-07 -6.22393574996358e-06 6.41068545417294e-05 -1.62729877383224e-05 5.97118069637777e-06 -7.21603474938559e-06 -4.58805290628606e-06 6.74262026414048e-06 -1.62729877383224e-05 6.01953886549736e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1508 0 0 0 0 0 2046 +636 669 0.985918580717785 0.0340017682115636 0.163732806590234 -0.0191803615749724 -0.0189024579674435 0.995495127146469 -0.0929093585728785 0.0127986279817171 -0.166154293589473 0.0885061104451087 0.982119859862156 0.00632543843329308 0.000103422797424812 7.17553104025805e-05 -2.27844136904423e-05 6.86532314344544e-06 1.22301859017425e-05 5.80992698219948e-05 7.17553104025805e-05 0.000102298601294668 -2.01720067991692e-05 7.75429112694736e-06 1.4353888112506e-05 3.91364330921561e-05 -2.27844136904423e-05 -2.01720067991692e-05 2.23330139390253e-05 -3.48228783155535e-06 -4.75808810488796e-06 -1.20978144036952e-05 6.86532314344544e-06 7.75429112694736e-06 -3.48228783155535e-06 2.05751046631446e-05 -4.40379693502837e-06 4.32053580864726e-06 1.22301859017425e-05 1.4353888112506e-05 -4.75808810488796e-06 -4.40379693502837e-06 5.17786234847786e-05 8.5588567535512e-06 5.80992698219948e-05 3.91364330921561e-05 -1.20978144036952e-05 4.32053580864726e-06 8.5588567535512e-06 7.57109637384336e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1126 0 0 1 0 0 2230 +636 674 0.992101026172198 0.0349076598143903 0.120486551757261 -0.0207630612867933 -0.0236110016142556 0.995297452244677 -0.0939441438197521 -0.00346914675562051 -0.123199328207763 0.0903572733184078 0.988259828530746 0.00615123647599716 0.000226846353119979 9.35711762475817e-05 -3.82530463452218e-05 -4.52479800161241e-06 5.75484376297513e-05 0.000185955665549482 9.35711762475817e-05 0.000348424253192578 -2.71023372971896e-05 5.33438148248706e-05 1.73280392865266e-05 3.09871404911135e-05 -3.82530463452218e-05 -2.71023372971896e-05 2.49997264806237e-05 -5.47495249312061e-06 -1.06380634549446e-05 -2.36387730848407e-05 -4.52479800161241e-06 5.33438148248706e-05 -5.47495249312061e-06 3.99447760705284e-05 -1.81944379292638e-05 -1.4606457258898e-05 5.75484376297513e-05 1.73280392865266e-05 -1.06380634549446e-05 -1.81944379292638e-05 9.66159932653748e-05 4.51725649671507e-05 0.000185955665549482 3.09871404911135e-05 -2.36387730848407e-05 -1.4606457258898e-05 4.51725649671507e-05 0.000228200281982457 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 992 0 0 3 0 0 2180 +636 638 0.999748508666401 0.0127971603238279 0.0184160828341227 -0.00195248606900946 -0.0132813435455541 0.99956286524469 0.0264137149498183 -0.00240129315410619 -0.0180700119792985 -0.0266516624523037 0.999481447329362 0.00277601310637048 0.000170891015125536 8.5179584303359e-05 -2.8446965488068e-05 1.98674713039859e-05 -9.73541235361199e-06 7.83759206714119e-05 8.5179584303359e-05 9.33694237935603e-05 -2.07963148586996e-05 1.58116749755025e-05 2.08826533722055e-07 1.52077455255962e-05 -2.8446965488068e-05 -2.07963148586996e-05 2.15924960720747e-05 -4.06996336249769e-06 6.55737353327215e-07 -1.12228483577158e-05 1.98674713039859e-05 1.58116749755025e-05 -4.06996336249769e-06 2.61816139725426e-05 -4.83797339311192e-06 1.63636549026818e-05 -9.73541235361199e-06 2.08826533722055e-07 6.55737353327215e-07 -4.83797339311192e-06 4.99844302091681e-05 -1.40558110244594e-05 7.83759206714119e-05 1.52077455255962e-05 -1.12228483577158e-05 1.63636549026818e-05 -1.40558110244594e-05 0.000139298181720637 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1503 0 0 0 0 0 2027 +636 666 0.987345938976289 0.0298167788775647 0.155752869907414 -0.0259368126606208 -0.0189582846722494 0.997314447879687 -0.0707423175526527 0.0182969653888205 -0.157443895497144 0.0668943327031581 0.98525964497836 -0.0188345763910104 0.000217612328997786 0.000115966643787334 -2.60114155175887e-05 -8.87361274979425e-06 4.27460336730103e-05 0.000184208695234103 0.000115966643787334 0.000155459704435383 -1.82565204409136e-05 1.27378188217446e-05 2.67242487077459e-05 5.05840388965235e-05 -2.60114155175887e-05 -1.82565204409136e-05 1.83838714013824e-05 1.59848925721245e-06 -6.32730587648383e-06 -2.50705330397424e-05 -8.87361274979425e-06 1.27378188217446e-05 1.59848925721245e-06 2.68045191472563e-05 -6.00796383583541e-06 -1.36185777208278e-05 4.27460336730103e-05 2.67242487077459e-05 -6.32730587648383e-06 -6.00796383583541e-06 6.24123382682736e-05 3.70388462616544e-05 0.000184208695234103 5.05840388965235e-05 -2.50705330397424e-05 -1.36185777208278e-05 3.70388462616544e-05 0.00026746926206417 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 770 0 0 4 0 0 2237 +636 670 0.985121477294567 0.0336769064277662 0.168527567318896 -0.0172010010035186 -0.0183252416017305 0.995605819543376 -0.0918326609197424 0.00991474846557209 -0.170879666704988 0.087378018201477 0.981409813198327 0.00485564540396367 9.22013208130029e-05 6.63299524024797e-05 -2.05748298909205e-05 3.92903462154395e-06 2.51088420235835e-05 4.65177158906446e-05 6.63299524024797e-05 0.000117687920124379 -1.58233589221389e-05 6.09820365664378e-06 3.27066471048991e-05 2.05701970465644e-05 -2.05748298909205e-05 -1.58233589221389e-05 2.10412816795111e-05 -3.49738103241589e-06 -4.87507302364886e-06 -1.08593368012179e-05 3.92903462154395e-06 6.09820365664378e-06 -3.49738103241589e-06 2.22951230481501e-05 -6.00359389808872e-06 3.44037204717677e-07 2.51088420235835e-05 3.27066471048991e-05 -4.87507302364886e-06 -6.00359389808872e-06 6.18967065529718e-05 9.54829921075626e-06 4.65177158906446e-05 2.05701970465644e-05 -1.08593368012179e-05 3.44037204717677e-07 9.54829921075626e-06 7.581038372061e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1148 0 0 4 0 0 2129 +636 667 0.987419091211346 0.0336302082180169 0.154507434793838 -0.0258906336573053 -0.0199469188500546 0.995807493644645 -0.0892723699111839 0.0214769372102814 -0.156861909779744 0.0850672951044215 0.983950149430279 0.00356429623270426 0.000313903839318978 9.54421243508654e-05 -5.58904069398305e-05 -6.17591934961978e-06 1.41710953335156e-05 0.000322422981640274 9.54421243508654e-05 0.000243142388086023 -1.68533238946204e-05 5.09921529086688e-05 -4.67292552534561e-05 4.97638849385925e-05 -5.58904069398305e-05 -1.68533238946204e-05 2.82431495956907e-05 1.50264031258226e-06 -5.51882989297418e-06 -5.32477631339987e-05 -6.17591934961978e-06 5.09921529086688e-05 1.50264031258226e-06 4.69014203373489e-05 -4.63383428663904e-05 -1.37504488098862e-05 1.41710953335156e-05 -4.67292552534561e-05 -5.51882989297418e-06 -4.63383428663904e-05 0.000127282737572088 1.11181777684228e-05 0.000322422981640274 4.97638849385925e-05 -5.32477631339987e-05 -1.37504488098862e-05 1.11181777684228e-05 0.000426584333741215 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 930 0 0 8 0 0 2070 +636 675 0.989740896672783 0.0337230464439907 0.138837003683786 -0.0228287124656071 -0.0212363862307749 0.995674006347704 -0.0904560057893831 0.00896640625072301 -0.14128684777152 0.0865796120460701 0.986175439475522 0.00526682907590849 0.000398680730198368 0.000179714103234657 -6.54166964603686e-05 -2.59639787381471e-05 0.000128741523801108 0.000331924546532851 0.000179714103234657 0.000168086633201286 -2.98582607490176e-05 -2.176817119251e-06 6.12290677911011e-05 0.0001442080816478 -6.54166964603686e-05 -2.98582607490176e-05 2.48079859207106e-05 1.89411250550407e-06 -1.91293745343219e-05 -5.1230148442664e-05 -2.59639787381471e-05 -2.176817119251e-06 1.89411250550407e-06 3.07325493423347e-05 -2.57637864081113e-05 -2.7875304597626e-05 0.000128741523801108 6.12290677911011e-05 -1.91293745343219e-05 -2.57637864081113e-05 0.000114665897144404 0.000112097127271711 0.000331924546532851 0.0001442080816478 -5.1230148442664e-05 -2.7875304597626e-05 0.000112097127271711 0.000323629920871261 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1013 0 0 7 0 0 2201 +636 673 0.992055594775678 0.0335482365915675 0.121244433669638 -0.0229691934484645 -0.0237268349880037 0.996385999706581 -0.0815596523421251 0.00235866997647482 -0.12354243876388 0.078034962743071 0.989266299038818 -0.00616165976614 0.000372751090366022 0.000211291339256834 -6.65228608057196e-05 2.36520456805496e-05 4.7085152028698e-05 0.000215994466594224 0.000211291339256834 0.000214007192308552 -3.79922574284849e-05 2.56314363083901e-05 2.76247098278186e-05 0.000118199453459134 -6.65228608057196e-05 -3.79922574284849e-05 2.92039617208493e-05 -5.82135232973782e-06 -9.79798986063689e-06 -3.50080161969703e-05 2.36520456805496e-05 2.56314363083901e-05 -5.82135232973782e-06 3.2757993336042e-05 -7.31999001214119e-06 7.48098364147766e-06 4.7085152028698e-05 2.76247098278186e-05 -9.79798986063689e-06 -7.31999001214119e-06 7.36470068236333e-05 2.46735762321778e-05 0.000215994466594224 0.000118199453459134 -3.50080161969703e-05 7.48098364147766e-06 2.46735762321778e-05 0.000215617152392509 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1047 0 0 11 0 0 2222 +636 668 0.986416064835561 0.0330435891375915 0.160908260357364 -0.0182292699914267 -0.0183379021725513 0.995587031165814 -0.0920336064617229 0.00924877625930088 -0.163239297898015 0.0878327079814085 0.982668991588936 0.00648173059311397 0.000121094928279049 0.000122394881087186 -2.06157420471738e-05 2.51593218951347e-05 -2.09559824713575e-05 8.29089044420595e-05 0.000122394881087186 0.000169655226351633 -2.15196816200488e-05 3.73831616658261e-05 -3.93837136677532e-05 8.63413222635389e-05 -2.06157420471738e-05 -2.15196816200488e-05 1.97974566281849e-05 -4.27806734877522e-06 -2.14450012947136e-06 -9.1729583594228e-06 2.51593218951347e-05 3.73831616658261e-05 -4.27806734877522e-06 3.58471908046775e-05 -3.26184902904463e-05 1.91902425528105e-05 -2.09559824713575e-05 -3.93837136677532e-05 -2.14450012947136e-06 -3.26184902904463e-05 9.93266284164037e-05 -2.53501570876806e-05 8.29089044420595e-05 8.63413222635389e-05 -9.1729583594228e-06 1.91902425528105e-05 -2.53501570876806e-05 0.000110751288897782 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1089 0 0 1 0 0 2162 +636 678 0.98623281116057 0.0351714268937559 0.16157912278688 -0.0138968922122853 -0.0193625406836296 0.994959304742723 -0.0983924485118255 -0.00180877330961221 -0.164225254478704 0.0939092787542032 0.981942520290913 0.00848864826704518 0.000295824783216585 0.000119456657151112 -5.83639591625765e-05 -2.16635538752996e-05 8.5348831777091e-05 0.000258971640701652 0.000119456657151112 0.000137653878639978 -2.7245326927802e-05 7.19831087639774e-06 3.06803487369228e-05 8.5290451475557e-05 -5.83639591625765e-05 -2.7245326927802e-05 2.88943025334334e-05 -1.48000460490885e-06 -1.7307016198223e-05 -4.58525922958117e-05 -2.16635538752996e-05 7.19831087639774e-06 -1.48000460490885e-06 3.17984531118397e-05 -2.30862428058995e-05 -2.9867346861151e-05 8.5348831777091e-05 3.06803487369228e-05 -1.7307016198223e-05 -2.30862428058995e-05 0.000100578075830334 7.70749370212059e-05 0.000258971640701652 8.5290451475557e-05 -4.58525922958117e-05 -2.9867346861151e-05 7.70749370212059e-05 0.00028678424394504 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1098 0 0 2 0 0 2184 +636 663 0.986262697270874 0.0335254258482555 0.161746523281564 -0.0215480442539652 -0.0187751561556925 0.995593530958953 -0.0918749945524544 0.0194475486478529 -0.164113940551404 0.0875760637067988 0.982546206334497 0.00792653538460474 6.42481581214496e-05 5.41832762202617e-05 -1.69287713314468e-05 4.81673333226184e-06 6.74765637480227e-06 3.38420453863882e-05 5.41832762202617e-05 9.24951203115534e-05 -1.62187955813975e-05 1.1526564219543e-05 5.24907279757312e-06 1.56684462975903e-05 -1.69287713314468e-05 -1.62187955813975e-05 1.95719316228363e-05 -1.69358764865234e-06 -3.33211551440447e-06 -3.72767427873429e-06 4.81673333226184e-06 1.1526564219543e-05 -1.69358764865234e-06 2.09173740979063e-05 -6.30609765275288e-06 2.58316327286157e-06 6.74765637480227e-06 5.24907279757312e-06 -3.33211551440447e-06 -6.30609765275288e-06 5.32238678811243e-05 5.40828010717984e-08 3.38420453863882e-05 1.56684462975903e-05 -3.72767427873429e-06 2.58316327286157e-06 5.40828010717984e-08 5.93865227600361e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1255 0 0 4 0 0 2197 +636 662 0.987625951129043 0.0324676852680887 0.153430212376133 -0.0206710529243496 -0.0195479539837536 0.996191186417748 -0.0849764532011563 0.0139266619261488 -0.155604814037041 0.0809257036851184 0.984498944809778 0.00132134334207156 7.69868784353854e-05 4.73160046342251e-05 -1.57701931708985e-05 5.85215928544112e-06 5.01867612087808e-06 3.5569033089569e-05 4.73160046342251e-05 9.12270903570027e-05 -1.15560134297619e-05 6.58540586602378e-06 1.03516270900935e-05 5.99763047827675e-06 -1.57701931708985e-05 -1.15560134297619e-05 1.97072104191604e-05 -1.29345899364734e-06 2.07125842707226e-06 -5.01078060783408e-06 5.85215928544112e-06 6.58540586602378e-06 -1.29345899364734e-06 2.15319239742999e-05 -6.08473086205457e-06 -1.61159139823418e-06 5.01867612087808e-06 1.03516270900935e-05 2.07125842707226e-06 -6.08473086205457e-06 5.14215777580612e-05 3.54468573369753e-06 3.5569033089569e-05 5.99763047827675e-06 -5.01078060783408e-06 -1.61159139823418e-06 3.54468573369753e-06 6.96355556498519e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1211 0 0 2 0 0 2224 +636 665 0.985494366892279 0.0340252283338498 0.166262252662519 -0.0198928988726635 -0.0180333163300047 0.995143934043658 -0.0967644048100987 0.0172303111558035 -0.168747303165793 0.092362516060034 0.981322328952792 0.0132864707449654 0.000249072839467656 0.000155777288492354 -4.80157568778141e-05 7.0298250255412e-06 4.00913316701359e-05 0.000199507490513116 0.000155777288492354 0.000213644074801415 -3.84256904588764e-05 3.12566693343422e-05 1.88864884572936e-05 7.9129914127105e-05 -4.80157568778141e-05 -3.84256904588764e-05 2.82901998190029e-05 -7.47249135603215e-06 -7.48774221369887e-06 -3.07679041084584e-05 7.0298250255412e-06 3.12566693343422e-05 -7.47249135603215e-06 3.44928324067492e-05 -1.1905917791861e-05 -7.56471244686014e-06 4.00913316701359e-05 1.88864884572936e-05 -7.48774221369887e-06 -1.1905917791861e-05 7.62518550752482e-05 3.0647529476716e-05 0.000199507490513116 7.9129914127105e-05 -3.07679041084584e-05 -7.56471244686014e-06 3.0647529476716e-05 0.000234530359373943 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1129 0 0 5 0 0 2151 +636 676 0.987444114811909 0.0340356047500654 0.154258541846544 -0.0190275968410659 -0.019418537461036 0.995259974770985 -0.0952916734123792 0.00720046607084238 -0.156770662198637 0.0910997268281004 0.983424526461307 0.012085666018743 0.000409609112174186 0.000203804985986187 -7.74647713293897e-05 2.65634470071516e-05 1.24715037274264e-06 0.0003692116762251 0.000203804985986187 0.000183998387525439 -4.07266343292813e-05 2.53372027505623e-05 1.92238943532801e-07 0.000168889802266604 -7.74647713293897e-05 -4.07266343292813e-05 3.13961105689555e-05 -8.86282298104873e-06 -2.31029351454333e-06 -6.34247276787978e-05 2.65634470071516e-05 2.53372027505623e-05 -8.86282298104873e-06 3.25634417564336e-05 -1.65108063128383e-05 1.88857755185792e-05 1.24715037274264e-06 1.92238943532801e-07 -2.31029351454333e-06 -1.65108063128383e-05 8.06240710678919e-05 2.33383092284913e-07 0.0003692116762251 0.000168889802266604 -6.34247276787978e-05 1.88857755185792e-05 2.33383092284913e-07 0.000397108333305859 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1048 0 0 5 0 0 2205 +637 640 0.999925714657704 0.00796710998400111 0.00922444170579442 -0.00994903695072122 -0.00811462763046004 0.999837995218948 0.0160666155419747 0.00320756244933875 -0.00909494280904197 -0.0161402749374811 0.999828372042043 0.0113365095089518 8.43205019854163e-05 5.73974926055625e-05 -1.46687205764748e-05 4.31175398676257e-06 1.29014208589903e-05 1.98096271434964e-05 5.73974926055625e-05 8.87564499963255e-05 -1.23888891724561e-05 8.46719296737548e-06 1.68387882090465e-05 6.87623407288044e-07 -1.46687205764748e-05 -1.23888891724561e-05 2.17869752509431e-05 -7.47840646706191e-06 -4.31125754704908e-06 -8.43780630892149e-06 4.31175398676257e-06 8.46719296737548e-06 -7.47840646706191e-06 2.4068744842078e-05 9.12483350094171e-07 5.3649412779477e-06 1.29014208589903e-05 1.68387882090465e-05 -4.31125754704908e-06 9.12483350094171e-07 4.55030082398934e-05 -2.40431131714335e-06 1.98096271434964e-05 6.87623407288044e-07 -8.43780630892149e-06 5.3649412779477e-06 -2.40431131714335e-06 8.25591481019363e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1515 0 0 0 0 0 1961 +636 664 0.985612903685787 0.0348075533474052 0.165395399930103 -0.0182829866921527 -0.0185251236040442 0.994916271153621 -0.0989870354603563 0.0141999463950461 -0.168000071081908 0.0944989292200843 0.981247129164071 0.0133260073162157 0.000272728973378916 0.000203567712750638 -4.33153799816808e-05 -1.30896024098037e-05 7.36113097149986e-05 0.000240534100389475 0.000203567712750638 0.000238597045546141 -4.06740998637981e-05 5.39607038332179e-06 5.84438106449943e-05 0.000161436547606439 -4.33153799816808e-05 -4.06740998637981e-05 2.25506199913875e-05 -1.2014946161747e-07 -9.43172953436839e-06 -3.91198404674531e-05 -1.30896024098037e-05 5.39607038332179e-06 -1.2014946161747e-07 2.75644562201e-05 -1.45146329044494e-05 -1.61881271083966e-05 7.36113097149986e-05 5.84438106449943e-05 -9.43172953436839e-06 -1.45146329044494e-05 7.85208160771634e-05 6.24032222181396e-05 0.000240534100389475 0.000161436547606439 -3.91198404674531e-05 -1.61881271083966e-05 6.24032222181396e-05 0.000265041784666725 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1201 0 0 5 0 0 2179 +637 670 0.988200492093017 0.028845692202497 0.150425109168907 -0.0177700719685675 -0.0138774206341221 0.994928525646525 -0.0996225177927947 0.0103014168682144 -0.152535912570327 0.0963595085925144 0.983589162445453 0.00664992627349014 0.000104551808488083 8.73360338142642e-05 -2.02293360863469e-05 1.11719930578543e-05 1.46526258022341e-05 2.94315212067009e-05 8.73360338142642e-05 0.000152361794074404 -2.04657682537401e-05 4.36173157008488e-06 4.11436843499618e-05 1.20445321827468e-05 -2.02293360863469e-05 -2.04657682537401e-05 2.11048806315532e-05 -5.32213745395861e-06 -4.54794098558585e-06 -6.26612283679056e-06 1.11719930578543e-05 4.36173157008488e-06 -5.32213745395861e-06 2.42829500757134e-05 -9.13460606732547e-06 3.28172317123724e-06 1.46526258022341e-05 4.11436843499618e-05 -4.54794098558585e-06 -9.13460606732547e-06 8.31744741835955e-05 -1.5630669688007e-06 2.94315212067009e-05 1.20445321827468e-05 -6.26612283679056e-06 3.28172317123724e-06 -1.5630669688007e-06 5.56329220449804e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1144 0 0 3 0 0 2136 +637 672 0.99190120691305 0.0284672328891252 0.123780500791 -0.0200537260362711 -0.0175341736604484 0.995918742015752 -0.0885348070298165 0.00493388934285223 -0.125795661604364 0.0856473931500423 0.988352151597862 -0.00203133253145292 0.000175086334201185 0.000109550154146677 -3.63629038721536e-05 5.88775833246255e-06 4.89261708078579e-05 8.02093840850707e-05 0.000109550154146677 0.000135530391782141 -2.51283286156256e-05 1.01257568295151e-05 3.28603012743259e-05 4.86479784242856e-05 -3.63629038721536e-05 -2.51283286156256e-05 2.50870283623199e-05 -2.52720683354552e-06 -1.05792015126714e-05 -1.51045164528234e-05 5.88775833246255e-06 1.01257568295151e-05 -2.52720683354552e-06 2.71734231275812e-05 -1.02442271461018e-05 3.1053511059428e-06 4.89261708078579e-05 3.28603012743259e-05 -1.05792015126714e-05 -1.02442271461018e-05 9.13576220843508e-05 2.02306641300617e-05 8.02093840850707e-05 4.86479784242856e-05 -1.51045164528234e-05 3.1053511059428e-06 2.02306641300617e-05 8.83546358566906e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1126 0 0 6 0 0 2204 +637 673 0.994724086053419 0.0275679676179281 0.0988129535364989 -0.0247837938076952 -0.0192870435661879 0.996295890369274 -0.0838004104033546 -0.00132308947089007 -0.100757146524033 0.0814524769096162 0.991571223578833 -0.00520107751241117 0.000239931633666526 0.000134327772252933 -3.75608207142236e-05 2.83828612547826e-05 9.59221049929782e-07 0.000122328487624464 0.000134327772252933 0.000163989972123845 -2.13973194112189e-05 3.17282996976375e-05 -9.00102579337917e-06 5.31851487821373e-05 -3.75608207142236e-05 -2.13973194112189e-05 2.25615051826772e-05 -8.24187290129573e-06 -3.76794292080287e-06 -1.75458114827609e-05 2.83828612547826e-05 3.17282996976375e-05 -8.24187290129573e-06 3.95606131615545e-05 -1.47722599720591e-05 1.14489714131967e-05 9.59221049929782e-07 -9.00102579337917e-06 -3.76794292080287e-06 -1.47722599720591e-05 8.6235229624088e-05 -5.40081127222525e-06 0.000122328487624464 5.31851487821373e-05 -1.75458114827609e-05 1.14489714131967e-05 -5.40081127222525e-06 0.000136370720043003 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1038 0 0 11 0 0 2231 +637 669 0.988932784709978 0.0282330265260737 0.145653161788357 -0.0190805985539208 -0.0146357175861576 0.995502831937172 -0.0935943768386196 0.0128128168768309 -0.147640587564889 0.0904268091787458 0.984898598377135 0.00458236248616812 9.96685864211252e-05 8.00529275727397e-05 -2.36029890292521e-05 5.51648170075488e-06 1.80124903121325e-05 3.26006830653873e-05 8.00529275727397e-05 0.000106842540043033 -2.27384812778661e-05 4.55965932048451e-06 2.65163480057735e-05 2.39132986787102e-05 -2.36029890292521e-05 -2.27384812778661e-05 1.95082020795783e-05 -3.8206955828885e-06 -3.3904337444923e-06 -7.07910401633661e-06 5.51648170075488e-06 4.55965932048451e-06 -3.8206955828885e-06 2.38116631992301e-05 -1.05143088696805e-05 -2.95780580288378e-06 1.80124903121325e-05 2.65163480057735e-05 -3.3904337444923e-06 -1.05143088696805e-05 7.09790591116189e-05 1.95002784151538e-05 3.26006830653873e-05 2.39132986787102e-05 -7.07910401633661e-06 -2.95780580288378e-06 1.95002784151538e-05 6.05715507539267e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1139 0 0 1 0 0 2204 +637 667 0.988951815023679 0.0274833849238734 0.145667330292337 -0.0245970786268993 -0.014304853693423 0.995770325089311 -0.0907569877879248 0.0233838168914042 -0.147545514069999 0.0876705379512067 0.985162016144129 0.00175625606467739 0.00022809780409761 0.000135801364216531 -4.12121747838701e-05 -6.62473059124644e-07 3.74798527926993e-05 0.00017189500539889 0.000135801364216531 0.000165994042927345 -2.64905820834115e-05 7.43465905574375e-06 2.58871227622521e-05 8.62748733368948e-05 -4.12121747838701e-05 -2.64905820834115e-05 2.28363163309632e-05 1.29983164278547e-07 -5.87211122132262e-06 -2.65302595007628e-05 -6.62473059124644e-07 7.43465905574375e-06 1.29983164278547e-07 2.76220232788454e-05 -1.28568935808495e-05 1.87117655712207e-06 3.74798527926993e-05 2.58871227622521e-05 -5.87211122132262e-06 -1.28568935808495e-05 7.29819352515346e-05 1.57783248140644e-05 0.00017189500539889 8.62748733368948e-05 -2.65302595007628e-05 1.87117655712207e-06 1.57783248140644e-05 0.00019991250610646 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 945 0 0 8 0 0 2077 +637 641 0.999580831663774 0.00778926684450495 0.0278834770497436 -0.00463057630058695 -0.00853026771929717 0.999610948094532 0.0265553569395905 -0.00827962811653574 -0.0276657821685127 -0.0267820792989834 0.999258387368066 0.00683369189600217 6.5992173733659e-05 2.87772735600727e-05 -6.98756425766599e-06 1.5684007235382e-06 4.40368815233975e-07 1.91862985007886e-06 2.87772735600727e-05 6.91539257564297e-05 -3.44033858919823e-06 7.01303443671631e-06 1.59512878159718e-05 -2.29215006559497e-05 -6.98756425766599e-06 -3.44033858919823e-06 2.0741988563777e-05 -5.47493905787761e-06 -2.26569485857683e-06 -4.80097411474786e-06 1.5684007235382e-06 7.01303443671631e-06 -5.47493905787761e-06 2.22735426846205e-05 -5.20535506112322e-07 -1.65778467693493e-06 4.40368815233975e-07 1.59512878159718e-05 -2.26569485857683e-06 -5.20535506112322e-07 6.35207537951484e-05 -1.60540948923328e-05 1.91862985007886e-06 -2.29215006559497e-05 -4.80097411474786e-06 -1.65778467693493e-06 -1.60540948923328e-05 6.28922922424925e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1546 0 0 0 0 0 1992 +637 671 0.989480521698929 0.0296949451926178 0.141585689278339 -0.0194166221432728 -0.0156031087284397 0.994903309176493 -0.0996190161950656 0.00976882607096831 -0.143822252021109 0.0963618992116266 0.984900778862473 0.00860146116705177 0.000159190208475448 0.000119692889897094 -3.19351420027173e-05 -5.59099965711702e-06 5.80601843554688e-05 6.97132250893943e-05 0.000119692889897094 0.000179525797941789 -2.25413212228884e-05 -1.07132627383861e-05 7.87090445530838e-05 3.99556121634008e-05 -3.19351420027173e-05 -2.25413212228884e-05 2.42823928620091e-05 -1.85015870752644e-06 -1.33003856975779e-05 -1.24236942985267e-05 -5.59099965711702e-06 -1.07132627383861e-05 -1.85015870752644e-06 2.98126559566733e-05 -2.19532409887841e-05 2.17946314466226e-07 5.80601843554688e-05 7.87090445530838e-05 -1.33003856975779e-05 -2.19532409887841e-05 0.000119285068041583 1.68373725729354e-05 6.97132250893943e-05 3.99556121634008e-05 -1.24236942985267e-05 2.17946314466226e-07 1.68373725729354e-05 7.51170009420709e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1020 0 0 8 0 0 2142 +637 675 0.992965222453648 0.0294932402524415 0.11467439024032 -0.0176532050982228 -0.0184819395097973 0.995216877990298 -0.0959259280653592 -0.0056318717664344 -0.116955055083283 0.0931317053567475 0.988760840925555 0.00428477976372716 0.000146114532003613 0.000113809430567544 -3.56379540100743e-05 5.9815987342432e-06 6.28159655343932e-05 6.81739762863606e-05 0.000113809430567544 0.000168008548988378 -2.93553810809516e-05 1.36308973255044e-05 5.07362340596833e-05 4.55564650237163e-05 -3.56379540100743e-05 -2.93553810809516e-05 2.44471629781294e-05 -7.14575078459585e-06 -1.47717114022144e-05 -1.43697629897576e-05 5.9815987342432e-06 1.36308973255044e-05 -7.14575078459585e-06 3.8798980187639e-05 -1.75525041509167e-05 4.19773905533381e-06 6.28159655343932e-05 5.07362340596833e-05 -1.47717114022144e-05 -1.75525041509167e-05 0.000103855698106135 3.01340374058008e-05 6.81739762863606e-05 4.55564650237163e-05 -1.43697629897576e-05 4.19773905533381e-06 3.01340374058008e-05 8.15041847138989e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1021 0 0 7 0 0 2240 +637 663 0.990654709533159 0.0276541500954375 0.133560826825355 -0.024629276834317 -0.0156452064747627 0.995806207364229 -0.0901400293389839 0.0199120091764849 -0.135493446314334 0.0872080578694988 0.986932763995853 0.00418042477635764 0.00010185111457898 8.62377186481761e-05 -2.48889801487905e-05 8.5696527914291e-06 8.14543120610213e-06 3.89019896385204e-05 8.62377186481761e-05 0.00011257876992999 -2.28021841367611e-05 1.28544582989597e-05 2.98181452217127e-06 2.21695186239663e-05 -2.48889801487905e-05 -2.28021841367611e-05 1.96691671780415e-05 -1.99483398880335e-06 -3.44362319963646e-06 -6.93800008358062e-06 8.5696527914291e-06 1.28544582989597e-05 -1.99483398880335e-06 3.00605174852328e-05 -2.08393307431359e-05 4.24512244982037e-06 8.14543120610213e-06 2.98181452217127e-06 -3.44362319963646e-06 -2.08393307431359e-05 8.27158563366824e-05 7.43869445924468e-06 3.89019896385204e-05 2.21695186239663e-05 -6.93800008358062e-06 4.24512244982037e-06 7.43869445924468e-06 6.06869809820392e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1245 0 0 4 0 0 2246 +637 674 0.993759149973713 0.0297132298361714 0.107516862938919 -0.01683502915368 -0.0194062949009857 0.995223921752959 -0.0956699602219827 -0.0122850468427926 -0.10984601750514 0.0929863943991949 0.989589502215387 0.00340981986562241 0.000196024955541932 0.000109353532337242 -3.34420868180816e-05 -7.92500691401493e-06 7.43728228630548e-05 0.000115680838573406 0.000109353532337242 0.000133308234617584 -1.73260305134189e-05 3.60926908919595e-06 4.26597811723272e-05 6.64936563863834e-05 -3.34420868180816e-05 -1.73260305134189e-05 2.18655500171699e-05 -2.10580881540512e-06 -1.29133866917304e-05 -1.7464176236114e-05 -7.92500691401493e-06 3.60926908919595e-06 -2.10580881540512e-06 3.06193083748786e-05 -1.92717688450896e-05 -1.16241065666849e-05 7.43728228630548e-05 4.26597811723272e-05 -1.29133866917304e-05 -1.92717688450896e-05 0.000116289332166035 5.73262627798719e-05 0.000115680838573406 6.64936563863834e-05 -1.7464176236114e-05 -1.16241065666849e-05 5.73262627798719e-05 0.000137405521862623 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1009 0 0 3 0 0 2206 +637 676 0.991622514036022 0.0278875949609451 0.126123240143019 -0.0186508489892161 -0.016183999391334 0.99554531335096 -0.0928849138915427 -0.00251494499498622 -0.12815173748561 0.0900655933874433 0.987656479281732 0.00556040510229911 0.000318079407499592 0.000265529864640389 -4.61806434302995e-05 1.87676526719785e-05 4.0594297715115e-05 0.000231327873849696 0.000265529864640389 0.000298078646449343 -4.19746334978276e-05 2.36575122816462e-05 3.9887601810669e-05 0.000172690019085916 -4.61806434302995e-05 -4.19746334978276e-05 2.35844891989623e-05 -6.10663732335942e-06 -8.7260796244289e-06 -3.12688792545424e-05 1.87676526719785e-05 2.36575122816462e-05 -6.10663732335942e-06 2.8727407265163e-05 -8.41015930873765e-06 8.42180934055517e-06 4.0594297715115e-05 3.9887601810669e-05 -8.7260796244289e-06 -8.41015930873765e-06 7.94738298618933e-05 3.21152050850553e-05 0.000231327873849696 0.000172690019085916 -3.12688792545424e-05 8.42180934055517e-06 3.21152050850553e-05 0.00022282225312796 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1053 0 0 5 0 0 2264 +637 678 0.989411493046044 0.0281408012979013 0.142383260008715 -0.0112098446108913 -0.0151702548456077 0.995701040604019 -0.0913745101655434 -0.0101999364819553 -0.144342512089532 0.0882470001891606 0.985584956338771 -0.000765895684573447 0.000206102089601138 0.000213334984371379 -3.53428505543436e-05 1.56137508740589e-05 4.96271333437859e-05 9.21173178388208e-05 0.000213334984371379 0.000329110102263526 -2.90746995543266e-05 2.4092207740742e-05 5.51832836964828e-05 8.17671604837544e-05 -3.53428505543436e-05 -2.90746995543266e-05 2.46567345518838e-05 -6.04435344315477e-06 -7.51114466677608e-06 -1.37661914328297e-05 1.56137508740589e-05 2.4092207740742e-05 -6.04435344315477e-06 3.1424685203014e-05 -1.51906788652378e-05 3.75887289274857e-06 4.96271333437859e-05 5.51832836964828e-05 -7.51114466677608e-06 -1.51906788652378e-05 9.34239905402611e-05 2.74971337546175e-05 9.21173178388208e-05 8.17671604837544e-05 -1.37661914328297e-05 3.75887289274857e-06 2.74971337546175e-05 9.19949246302669e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1120 0 0 2 0 0 2201 +637 668 0.988617322421205 0.0287090142624323 0.14768744804081 -0.016618482618056 -0.0141323550804502 0.995005199690256 -0.0988176559590139 0.00791958965770473 -0.149786736223897 0.0956056749855019 0.984085102296523 0.00658153157269313 9.96744957641778e-05 7.93263052232303e-05 -1.57312014348009e-05 2.85234560653941e-06 1.93132034805008e-05 5.51503408222199e-05 7.93263052232303e-05 0.000127711312668799 -1.32114507600521e-05 1.05755870523874e-05 7.76791244454833e-06 4.36832186571503e-05 -1.57312014348009e-05 -1.32114507600521e-05 1.70632702847304e-05 -1.1646326789934e-06 -5.80420415089961e-06 -6.07187664439994e-06 2.85234560653941e-06 1.05755870523874e-05 -1.1646326789934e-06 2.54850719121951e-05 -1.31840456061292e-05 1.62044979513097e-06 1.93132034805008e-05 7.76791244454833e-06 -5.80420415089961e-06 -1.31840456061292e-05 7.14615898680101e-05 6.94726033879904e-06 5.51503408222199e-05 4.36832186571503e-05 -6.07187664439994e-06 1.62044979513097e-06 6.94726033879904e-06 6.6754979199808e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1099 0 0 1 0 0 2221 +637 666 0.990143831563561 0.0270637066544409 0.137414513784943 -0.023177732584022 -0.0147392902908261 0.995839410894208 -0.0899256416802168 0.0132384157586761 -0.139276509643057 0.0870139270002127 0.986423149753517 -0.00153676405079616 0.000142800225589536 9.45234421011778e-05 -1.81401892835581e-05 -4.26773805815634e-06 2.5547776430587e-05 0.000101447994743837 9.45234421011778e-05 0.00011050450317516 -1.6724325607151e-05 3.03139760144142e-06 2.00724607450789e-05 5.68658271259076e-05 -1.81401892835581e-05 -1.6724325607151e-05 1.73561339379349e-05 -1.03252693027202e-06 -5.75432144089881e-06 -1.1743742054802e-05 -4.26773805815634e-06 3.03139760144142e-06 -1.03252693027202e-06 4.1392926590773e-05 -3.9103030595174e-05 -5.14547803018565e-06 2.5547776430587e-05 2.00724607450789e-05 -5.75432144089881e-06 -3.9103030595174e-05 0.00013949637926398 3.64996920553441e-05 0.000101447994743837 5.68658271259076e-05 -1.1743742054802e-05 -5.14547803018565e-06 3.64996920553441e-05 0.000154688873755484 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 792 0 0 4 0 0 2225 +638 671 0.990049105589397 0.0179146116329511 0.139577344908389 -0.0206857365348645 -0.00239045508611137 0.993861550911066 -0.110605168708938 0.0202938277878873 -0.140702005124718 0.109170894979806 0.984014563633685 0.0035624264839491 0.000104261911830923 6.18094761599459e-05 -2.20444723560324e-05 -7.89739145020595e-06 4.77849154377999e-05 4.61464801827321e-05 6.18094761599459e-05 0.000119263625695838 -1.38664828158234e-05 -2.7522649534514e-06 4.17662898367615e-05 2.04664570862357e-05 -2.20444723560324e-05 -1.38664828158234e-05 2.08814081572922e-05 -9.63122357807032e-07 -6.44676910261237e-06 -8.26056485983313e-06 -7.89739145020595e-06 -2.7522649534514e-06 -9.63122357807032e-07 2.87917460819735e-05 -2.03348542683891e-05 -7.44262635211739e-06 4.77849154377999e-05 4.17662898367615e-05 -6.44676910261237e-06 -2.03348542683891e-05 9.92278351904101e-05 2.3418290263026e-05 4.61464801827321e-05 2.04664570862357e-05 -8.26056485983313e-06 -7.44262635211739e-06 2.3418290263026e-05 6.80523532895042e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1017 0 0 0 0 0 2222 +638 642 0.999185202854375 0.000206955865655679 0.0403594792599078 -0.00631922901152463 -0.000974279928434883 0.999819132566013 0.0189934971389072 0.000116188745694592 -0.0403482487288148 -0.019017342722218 0.999004684423603 0.00664121278623295 0.000101765518136586 6.76049030930556e-05 -5.59787698084693e-06 9.37668137117294e-06 -8.60831525396376e-06 2.43138006230364e-05 6.76049030930556e-05 0.000106349591026743 -4.00808740583498e-06 1.58412453413583e-05 2.5247958450351e-06 4.22489201323723e-06 -5.59787698084693e-06 -4.00808740583498e-06 2.15069848070185e-05 -4.89210928859725e-06 7.8853490156144e-07 -1.26113067909558e-05 9.37668137117294e-06 1.58412453413583e-05 -4.89210928859725e-06 2.27336755063898e-05 -1.44865609138704e-06 4.02164635927521e-06 -8.60831525396376e-06 2.5247958450351e-06 7.8853490156144e-07 -1.44865609138704e-06 5.36501563591746e-05 -1.74677793262127e-05 2.43138006230364e-05 4.22489201323723e-06 -1.26113067909558e-05 4.02164635927521e-06 -1.74677793262127e-05 8.79666228921521e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1510 0 0 0 0 0 1981 +637 664 0.988471289504174 0.0292438557602909 0.148557418953841 -0.0188321460611097 -0.0145799483052697 0.994995040552754 -0.0988549158253648 0.0133669883571247 -0.150704793995982 0.0955492866310136 0.98395040469067 0.00406002090305514 0.000233661304706436 0.000145941377609952 -2.71782734510527e-05 8.9334957642545e-06 1.86338027006373e-05 0.000185131324167774 0.000145941377609952 0.000140537647567564 -1.89595788918835e-05 1.45321131071013e-05 6.80102216752292e-06 0.000115707116592767 -2.71782734510527e-05 -1.89595788918835e-05 1.91845332523618e-05 -4.19668157188549e-06 -1.78433025029579e-06 -2.2043237590251e-05 8.9334957642545e-06 1.45321131071013e-05 -4.19668157188549e-06 2.62536285002596e-05 -9.05228868670483e-06 6.6794440344631e-06 1.86338027006373e-05 6.80102216752292e-06 -1.78433025029579e-06 -9.05228868670483e-06 5.54707554279579e-05 1.64581187621605e-05 0.000185131324167774 0.000115707116592767 -2.2043237590251e-05 6.6794440344631e-06 1.64581187621605e-05 0.000199359186911625 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1226 0 0 4 0 0 2205 +638 672 0.993177877033378 0.0186693154860215 0.11510500089377 -0.0244525700935298 -0.00532482080630063 0.993331838378261 -0.11516729200361 0.0192889984323922 -0.116487556652426 0.113768693072161 0.986654617189724 0.0064895375503674 0.000134095991523543 7.71285647520262e-05 -2.89190139087844e-05 5.83183793164089e-06 3.65884799324637e-05 7.1408553287143e-05 7.71285647520262e-05 0.000145171481179712 -1.69225043120834e-05 1.11752249563377e-05 2.69849721728242e-05 2.57421965409186e-05 -2.89190139087844e-05 -1.69225043120834e-05 2.75462920156895e-05 -4.51270902632251e-06 -1.04543652109384e-05 -1.10931426717871e-05 5.83183793164089e-06 1.11752249563377e-05 -4.51270902632251e-06 2.65729321943319e-05 9.20685809759149e-07 -2.93979771527895e-06 3.65884799324637e-05 2.69849721728242e-05 -1.04543652109384e-05 9.20685809759149e-07 6.09751471434322e-05 1.69120094344355e-05 7.1408553287143e-05 2.57421965409186e-05 -1.10931426717871e-05 -2.93979771527895e-06 1.69120094344355e-05 0.000108739446961909 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1103 0 0 0 0 0 2211 +638 641 0.999697263788785 -0.00310772560258557 0.0244074335970667 -0.00432761342856648 0.0026425090621936 0.999814666138167 0.019069622987402 0.002040325563041 -0.0244621732287303 -0.0189993530575243 0.999520198227291 0.00248838845987258 0.000127390035322577 5.93760476487804e-05 -6.91176920777071e-06 8.81725127258577e-06 -1.75644092888148e-05 5.63675420744185e-06 5.93760476487804e-05 0.000100736088554735 -1.12740875176967e-06 7.15281024465658e-06 1.33708466833834e-05 -2.04832408975002e-05 -6.91176920777071e-06 -1.12740875176967e-06 1.9205984078991e-05 -4.70839811364298e-06 6.44079972628757e-07 -5.18043853623014e-06 8.81725127258577e-06 7.15281024465658e-06 -4.70839811364298e-06 2.19176740228737e-05 3.98102093567701e-06 3.96674493770238e-06 -1.75644092888148e-05 1.33708466833834e-05 6.44079972628757e-07 3.98102093567701e-06 4.35498962797664e-05 -2.22374001309809e-05 5.63675420744185e-06 -2.04832408975002e-05 -5.18043853623014e-06 3.96674493770238e-06 -2.22374001309809e-05 6.40709037444226e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1499 0 0 0 0 0 1995 +638 640 0.999934906466878 -0.00314063790202118 0.0109690119265197 -0.00472992674179098 0.00310436045884862 0.999989661157931 0.00332272830477308 0.00415171419093004 -0.0109793340060899 -0.00328846024975079 0.99993431796992 0.00506925643202814 6.69707755537324e-05 4.50242376556632e-05 -1.31921479024657e-05 3.89281863661148e-06 9.2102339866691e-06 1.55658477491465e-05 4.50242376556632e-05 7.55811987975745e-05 -1.5207470322779e-05 1.14788359758118e-05 2.47259361816893e-06 7.51758274034258e-07 -1.31921479024657e-05 -1.5207470322779e-05 2.15286603222883e-05 -6.67409128746508e-06 -4.37473707418544e-06 -7.08991613095089e-06 3.89281863661148e-06 1.14788359758118e-05 -6.67409128746508e-06 2.119082142684e-05 6.32634097134903e-06 4.83614199194298e-06 9.2102339866691e-06 2.47259361816893e-06 -4.37473707418544e-06 6.32634097134903e-06 3.45344100650864e-05 -3.05186136455096e-06 1.55658477491465e-05 7.51758274034258e-07 -7.08991613095089e-06 4.83614199194298e-06 -3.05186136455096e-06 6.85010235391775e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1581 0 0 0 0 0 1999 +638 670 0.989626607900453 0.0178615387311456 0.142548736822181 -0.0195864315847616 -0.00176334110042034 0.993676494287462 -0.112267160508951 0.0194456287764836 -0.143652593306237 0.110851207186637 0.983400194377476 0.00409749909238271 9.57935106017171e-05 8.70993134916727e-05 -2.47902234572646e-05 7.90070333823672e-06 2.54321189687447e-05 4.86668962648283e-05 8.70993134916727e-05 0.000172630244671215 -2.19608357425138e-05 1.3068759639625e-05 3.3092236148176e-05 3.92027439534013e-05 -2.47902234572646e-05 -2.19608357425138e-05 2.48645635727934e-05 -5.88710894453417e-06 -6.32077731302862e-06 -1.34578278194842e-05 7.90070333823672e-06 1.3068759639625e-05 -5.88710894453417e-06 2.40743597673059e-05 -2.11704551096275e-06 2.06071474718142e-06 2.54321189687447e-05 3.3092236148176e-05 -6.32077731302862e-06 -2.11704551096275e-06 5.94307755745597e-05 1.02513939490062e-05 4.86668962648283e-05 3.92027439534013e-05 -1.34578278194842e-05 2.06071474718142e-06 1.02513939490062e-05 7.67034683509582e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1143 0 0 0 0 0 2194 +638 669 0.988938226634681 0.0179964273047167 0.147232172112341 -0.0206393343111072 -0.00134020161979387 0.993656001211299 -0.112454235653397 0.0253334594313758 -0.148321905867846 0.111012971589078 0.982688522563835 0.00442238304592538 0.000138749831186788 8.41663327906852e-05 -2.93382368469801e-05 -2.24046206348556e-06 3.3034368870537e-05 7.45717704832322e-05 8.41663327906852e-05 0.000190949169083976 -1.55007100220939e-05 1.11192471848856e-05 3.35228970526964e-05 2.44361498136223e-05 -2.93382368469801e-05 -1.55007100220939e-05 2.2609785855749e-05 -2.6652813553944e-06 -5.63692813406567e-06 -1.44733327126194e-05 -2.24046206348556e-06 1.11192471848856e-05 -2.6652813553944e-06 2.90476460002699e-05 -1.85407437136346e-05 -3.1245770761234e-06 3.3034368870537e-05 3.35228970526964e-05 -5.63692813406567e-06 -1.85407437136346e-05 9.47359196613638e-05 2.11896366150595e-05 7.45717704832322e-05 2.44361498136223e-05 -1.44733327126194e-05 -3.1245770761234e-06 2.11896366150595e-05 0.000100872708520189 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1127 0 0 0 0 0 2255 +638 673 0.995070793500438 0.0171784775717375 0.0976678853601587 -0.0255237993939402 -0.00728746241504511 0.994886071463356 -0.100740248658413 0.0126650804818051 -0.0988989828762516 0.0995319281262393 0.990107260083228 -0.00885046450817267 0.000269471716862687 0.000139679379386256 -5.50679414625562e-05 2.56283435022011e-05 3.29580126166721e-05 0.000207901480881768 0.000139679379386256 0.00020415031657253 -2.58193711093184e-05 3.0592019960945e-05 1.83118369942378e-05 8.65707953047245e-05 -5.50679414625562e-05 -2.58193711093184e-05 2.84509157672633e-05 -8.64486728392835e-06 -8.35046815226824e-06 -3.72949130004434e-05 2.56283435022011e-05 3.0592019960945e-05 -8.64486728392835e-06 3.22899516539336e-05 -5.97105402930305e-06 8.41353937616455e-06 3.29580126166721e-05 1.83118369942378e-05 -8.35046815226824e-06 -5.97105402930305e-06 6.88033198218525e-05 2.42102024709563e-05 0.000207901480881768 8.65707953047245e-05 -3.72949130004434e-05 8.41353937616455e-06 2.42102024709563e-05 0.000232504964942192 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1031 0 0 1 0 0 2237 +638 668 0.989250667889448 0.0177709137418401 0.145145825654965 -0.0183564401063095 -0.00126504710669208 0.993590975489349 -0.113028195959861 0.0189663467395548 -0.146224196821522 0.111629602036839 0.982933017154779 0.0050944009565182 0.000111402186790572 6.6093635829203e-05 -2.59231277775714e-05 -1.09878844456727e-06 2.42956805093881e-05 7.83619725708169e-05 6.6093635829203e-05 9.68203875628836e-05 -1.35434649731222e-05 7.05664998760045e-06 7.67892856438651e-06 3.52996870950012e-05 -2.59231277775714e-05 -1.35434649731222e-05 2.418180316771e-05 -1.43530089599115e-06 -5.59828901452756e-06 -1.57495651887899e-05 -1.09878844456727e-06 7.05664998760045e-06 -1.43530089599115e-06 2.79566740343603e-05 -1.8553383984181e-05 -5.03551193208954e-06 2.42956805093881e-05 7.67892856438651e-06 -5.59828901452756e-06 -1.8553383984181e-05 8.46229783270133e-05 2.02747325787032e-05 7.83619725708169e-05 3.52996870950012e-05 -1.57495651887899e-05 -5.03551193208954e-06 2.02747325787032e-05 0.000102221813229393 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1089 0 0 0 0 0 2151 +638 674 0.994688812310384 0.0187575978987725 0.101204343709275 -0.0202382050769018 -0.00772298304704878 0.994083707058649 -0.108341768923109 0.00474698418473281 -0.102637820502055 0.106984746022979 0.988948806521847 -0.00258095597182922 0.000106922502257637 6.98419771978814e-05 -2.92503322686231e-05 2.01203028983428e-05 9.14911319027314e-06 5.17779901265471e-05 6.98419771978814e-05 0.000156402667955154 -1.69505728065065e-05 3.15661232773203e-05 -4.16367360457385e-06 4.50764981588483e-05 -2.92503322686231e-05 -1.69505728065065e-05 2.57572800899974e-05 -7.94279483888231e-06 -4.92124427770886e-06 -1.35264629561853e-05 2.01203028983428e-05 3.15661232773203e-05 -7.94279483888231e-06 3.2959471028286e-05 -5.8295510789566e-06 1.35479741691028e-05 9.14911319027314e-06 -4.16367360457385e-06 -4.92124427770886e-06 -5.8295510789566e-06 5.99364406942044e-05 -2.8669734667942e-06 5.17779901265471e-05 4.50764981588483e-05 -1.35264629561853e-05 1.35479741691028e-05 -2.8669734667942e-06 7.38361835665598e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 999 0 0 0 0 0 2220 +638 676 0.991740950381112 0.0182408214243357 0.126953376366814 -0.0173194549806631 -0.00377016976866056 0.993553329380335 -0.113302989798004 0.00551986412793562 -0.128201689369072 0.111888579001686 0.985416294127461 0.00626400929684867 8.64586215769666e-05 5.5690369965242e-05 -2.16483323246508e-05 1.66476764442215e-06 2.94186442874034e-05 4.52655243595834e-05 5.5690369965242e-05 0.000114173955359759 -1.13903857850447e-05 8.6419953974695e-06 2.56081092775906e-05 1.03148118504698e-05 -2.16483323246508e-05 -1.13903857850447e-05 2.56354447721447e-05 -3.91588170992355e-06 -8.92040888004462e-06 -7.2515242315543e-06 1.66476764442215e-06 8.6419953974695e-06 -3.91588170992355e-06 3.05167722625007e-05 -1.40337053094373e-05 -4.24233392105797e-06 2.94186442874034e-05 2.56081092775906e-05 -8.92040888004462e-06 -1.40337053094373e-05 9.72668669608475e-05 1.73176667116308e-05 4.52655243595834e-05 1.03148118504698e-05 -7.2515242315543e-06 -4.24233392105797e-06 1.73176667116308e-05 7.87848092726293e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1079 0 0 0 0 0 2192 +638 664 0.990052365053216 0.0195830283389182 0.139329894328567 -0.0214810176272843 -0.00208638974002138 0.992201109242544 -0.124629875213445 0.0213441696899823 -0.140683906081632 0.123099406249353 0.98237191264341 0.0166845937022856 7.69792124659206e-05 4.52853244217217e-05 -1.16542758508514e-05 3.45926618636061e-06 2.31989756993603e-06 3.78345933176313e-05 4.52853244217217e-05 0.000121167072480687 -1.22696564574197e-05 9.84577513050774e-06 1.65895119957525e-05 8.52134405518957e-06 -1.16542758508514e-05 -1.22696564574197e-05 2.05292324816964e-05 -2.28426859416487e-06 -2.96940547233774e-06 -4.75041870064027e-06 3.45926618636061e-06 9.84577513050774e-06 -2.28426859416487e-06 2.29192668923306e-05 -1.76677333098037e-06 6.81363734454508e-07 2.31989756993603e-06 1.65895119957525e-05 -2.96940547233774e-06 -1.76677333098037e-06 5.1098117219561e-05 -6.7969539212137e-06 3.78345933176313e-05 8.52134405518957e-06 -4.75041870064027e-06 6.81363734454508e-07 -6.7969539212137e-06 7.19652743412226e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1213 0 0 0 0 0 2184 +639 642 0.999486233768175 -0.000298716112101716 0.0320496376983236 -0.00238148338246219 -0.00038821206860043 0.999770385209079 0.0214248955721831 -0.00044492001994911 -0.0320486785889719 -0.0214263302404665 0.99925662098038 -0.00123174385463707 0.000104106151672253 4.02453652886972e-05 -5.13129133039185e-06 5.71839924432822e-06 -1.83980314594965e-06 3.01064443537912e-05 4.02453652886972e-05 8.91101952411598e-05 -1.53238417998044e-06 1.02647083739695e-05 1.66447331947575e-05 -8.59251485631071e-06 -5.13129133039185e-06 -1.53238417998044e-06 1.73734368762165e-05 -3.6135449785702e-06 9.84865157698274e-07 -8.6359791286331e-06 5.71839924432822e-06 1.02647083739695e-05 -3.6135449785702e-06 1.72305928496098e-05 6.63504851994732e-06 7.9148615400429e-07 -1.83980314594965e-06 1.66447331947575e-05 9.84865157698274e-07 6.63504851994732e-06 3.35502381593153e-05 -2.24928767407631e-05 3.01064443537912e-05 -8.59251485631071e-06 -8.6359791286331e-06 7.9148615400429e-07 -2.24928767407631e-05 7.32707849134194e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1517 0 0 0 0 0 1958 +638 667 0.990649992560361 0.0175686167958335 0.135292039470314 -0.0231831252190823 -0.00221971153326882 0.99361808966515 -0.112774841036853 0.0233660564639573 -0.136409915771783 0.111420086133782 0.984366750395946 0.00697218860319341 0.000167197174527482 0.000121601543710053 -2.805155794401e-05 2.62889807767018e-06 1.93638863071293e-05 0.000122124118902303 0.000121601543710053 0.000207449011952419 -2.15503138640569e-05 1.93575255705209e-05 1.32081086862961e-05 7.38633576257131e-05 -2.805155794401e-05 -2.15503138640569e-05 2.54652061527097e-05 -2.69787703830551e-06 -8.3171783590055e-06 -1.81180706541769e-05 2.62889807767018e-06 1.93575255705209e-05 -2.69787703830551e-06 3.07300625960263e-05 -9.6170169201754e-06 1.92739021095615e-06 1.93638863071293e-05 1.32081086862961e-05 -8.3171783590055e-06 -9.6170169201754e-06 7.73839150761986e-05 7.82763241251946e-06 0.000122124118902303 7.38633576257131e-05 -1.81180706541769e-05 1.92739021095615e-06 7.82763241251946e-06 0.000154520132440029 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 944 0 0 0 0 0 2103 +638 666 0.990477225314958 0.0176654744038228 0.136538628770287 -0.0227590703927855 -0.00227877541693932 0.993701623451443 -0.112035220946656 0.0234228710662947 -0.137657812400828 0.110657193910088 0.984279082435954 0.00346930602504598 7.93765344285815e-05 3.98123813442557e-05 -8.68928081805094e-06 -6.54387782727036e-06 1.94857558847022e-05 5.25363811240472e-05 3.98123813442557e-05 9.18674673441915e-05 -4.09068054251348e-06 2.07561577527282e-07 1.4796301507439e-05 4.09733808911357e-06 -8.68928081805094e-06 -4.09068054251348e-06 1.91938048937373e-05 -2.55688033394374e-06 -3.97535700637186e-06 -4.53366346581994e-06 -6.54387782727036e-06 2.07561577527282e-07 -2.55688033394374e-06 3.50263552169803e-05 -3.16385633709335e-05 -1.29946146038778e-05 1.94857558847022e-05 1.4796301507439e-05 -3.97535700637186e-06 -3.16385633709335e-05 0.000118032494977128 2.58483155338343e-05 5.25363811240472e-05 4.09733808911357e-06 -4.53366346581994e-06 -1.29946146038778e-05 2.58483155338343e-05 9.20597702959622e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 810 0 0 0 0 0 2188 +638 675 0.993268084818044 0.0188205872279561 0.114299156507345 -0.0187645922551559 -0.00636356651658574 0.994088354382402 -0.108387493293635 0.00642870325664894 -0.115663376671635 0.106930487596774 0.987516001956035 -0.00242870645804718 9.3015371801268e-05 5.2247185204942e-05 -2.28070474590359e-05 4.91112188636869e-06 1.96343349138769e-05 4.72836703692213e-05 5.2247185204942e-05 0.000108555367741718 -1.14452422723079e-05 8.20385302534978e-06 1.9648797682718e-05 1.36261646989054e-05 -2.28070474590359e-05 -1.14452422723079e-05 2.48653111732528e-05 -2.25438297856877e-06 -5.75819699403975e-06 -8.11283193757089e-06 4.91112188636869e-06 8.20385302534978e-06 -2.25438297856877e-06 3.02756311944038e-05 -6.95548940800385e-06 -3.1430398525993e-06 1.96343349138769e-05 1.9648797682718e-05 -5.75819699403975e-06 -6.95548940800385e-06 5.90584343653887e-05 7.60949479026255e-06 4.72836703692213e-05 1.36261646989054e-05 -8.11283193757089e-06 -3.1430398525993e-06 7.60949479026255e-06 7.93839476703095e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1019 0 0 0 0 0 2259 +639 641 0.999949698533565 -3.09960591393297e-05 0.0100299273116548 -0.000398636440139575 -6.09104521079431e-05 0.999958018877477 0.00916279283560347 -0.00287803969414488 -0.010029790254516 -0.00916294286109436 0.99990771763477 0.00505441407267014 0.000103931706254861 5.16322345409609e-05 -1.08549057287563e-05 1.64617372139463e-05 -1.75714847796288e-05 3.73870843973427e-05 5.16322345409609e-05 0.000109406034965792 3.85041596398252e-06 1.61143364999446e-05 6.87135626858062e-06 -1.7181125258026e-05 -1.08549057287563e-05 3.85041596398252e-06 2.43973870090369e-05 -5.5884272525272e-06 5.52007112327548e-06 -1.74869752710767e-05 1.64617372139463e-05 1.61143364999446e-05 -5.5884272525272e-06 2.46524290943468e-05 -7.95899919291563e-06 6.33782915399435e-06 -1.75714847796288e-05 6.87135626858062e-06 5.52007112327548e-06 -7.95899919291563e-06 6.21180076939642e-05 -3.79371255177367e-05 3.73870843973427e-05 -1.7181125258026e-05 -1.74869752710767e-05 6.33782915399435e-06 -3.79371255177367e-05 0.000105401718532247 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1492 0 0 0 0 0 2024 +639 672 0.994664156616549 0.0178718968467559 0.101606155548707 -0.0193081040776377 -0.00612932148143654 0.993378186845048 -0.114726672219768 0.00945588213726429 -0.102983721822754 0.113491731873048 0.988187219020763 0.00352696088801849 0.000105791195762665 5.96481289334292e-05 -2.86392272931975e-05 6.6604507268018e-06 3.96847289075198e-05 4.43734338542387e-05 5.96481289334292e-05 0.000107288085582616 -2.27472884181844e-05 1.2282724718082e-05 3.27439775928003e-05 1.25550774072837e-05 -2.86392272931975e-05 -2.27472884181844e-05 2.66998807785495e-05 -7.03438228003715e-06 -1.07301483797469e-05 -7.4832326127346e-06 6.6604507268018e-06 1.2282724718082e-05 -7.03438228003715e-06 3.11398398453139e-05 -1.46688776949413e-05 -3.55924972409619e-06 3.96847289075198e-05 3.27439775928003e-05 -1.07301483797469e-05 -1.46688776949413e-05 0.000101509949372232 2.00837038416975e-05 4.43734338542387e-05 1.25550774072837e-05 -7.4832326127346e-06 -3.55924972409619e-06 2.00837038416975e-05 7.14250514237488e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1092 0 0 1 0 0 2163 +638 665 0.989272414160989 0.0178269194444142 0.144990660124062 -0.0219605896551496 -0.000808322953210237 0.993178825042073 -0.116598319464947 0.0226204745392245 -0.146080242312547 0.115230301705623 0.982538823851118 0.00910587585747912 0.0001510317661445 9.17292681012958e-05 -3.31105269865848e-05 3.02583377773144e-06 3.369319282669e-05 0.000108037936823217 9.17292681012958e-05 0.000128566210586489 -1.84989432003372e-05 6.67934654911517e-06 2.41465208083485e-05 7.11565240926877e-05 -3.31105269865848e-05 -1.84989432003372e-05 2.88303648291671e-05 -6.37403048932003e-06 -1.04734987761807e-05 -2.05744550032684e-05 3.02583377773144e-06 6.67934654911517e-06 -6.37403048932003e-06 2.44588143076953e-05 6.64635989974727e-07 2.61454647291446e-06 3.369319282669e-05 2.41465208083485e-05 -1.04734987761807e-05 6.64635989974727e-07 6.46907480507131e-05 1.28080647756092e-05 0.000108037936823217 7.11565240926877e-05 -2.05744550032684e-05 2.61454647291446e-06 1.28080647756092e-05 0.000125637192215194 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1155 0 0 0 0 0 2186 +639 669 0.990649434360567 0.0176399005976838 0.13528685120141 -0.018332427979157 -0.00171854601885841 0.993140986580326 -0.116910339037391 0.0196534577621104 -0.136421203632975 0.115584664558757 0.983884871577041 0.00363458454387006 0.00016737963846861 0.000129670969929271 -3.68779334579213e-05 2.14392550989136e-06 4.6361151703306e-05 0.000104168854108372 0.000129670969929271 0.00019968420133155 -3.0311926276521e-05 1.06544905474193e-05 4.24142975924883e-05 6.18368335327619e-05 -3.68779334579213e-05 -3.0311926276521e-05 2.3680200504911e-05 -2.88856484475163e-06 -1.19867112152098e-05 -1.97547380438233e-05 2.14392550989136e-06 1.06544905474193e-05 -2.88856484475163e-06 2.31228330197117e-05 -5.53209377898783e-06 -2.46992813064182e-06 4.6361151703306e-05 4.24142975924883e-05 -1.19867112152098e-05 -5.53209377898783e-06 6.82358694368833e-05 3.29782546909013e-05 0.000104168854108372 6.18368335327619e-05 -1.97547380438233e-05 -2.46992813064182e-06 3.29782546909013e-05 0.000122803422971482 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1093 0 0 0 0 0 2202 +639 673 0.995779825194891 0.0168021479762519 0.0902232096426269 -0.0206556340751013 -0.00714340662965291 0.994305503973682 -0.106327496487814 0.00683239857991351 -0.0914959642637679 0.105234274792136 0.990229385512476 -0.0078018252513429 0.000141532298359122 0.000132146008312046 -2.96160666932434e-05 1.99847690738843e-05 3.0914022920992e-05 5.6576227100089e-05 0.000132146008312046 0.000258997117012581 -2.22078934137238e-05 3.19080720091005e-05 2.22474641096011e-05 3.8196826615964e-05 -2.96160666932434e-05 -2.22078934137238e-05 2.40529875863411e-05 -6.85129087057008e-06 -8.10090534026277e-06 -7.30044669264507e-06 1.99847690738843e-05 3.19080720091005e-05 -6.85129087057008e-06 2.89547694484605e-05 7.42007324065141e-06 4.93743106074558e-06 3.0914022920992e-05 2.22474641096011e-05 -8.10090534026277e-06 7.42007324065141e-06 5.148891084192e-05 8.05415654173747e-07 5.6576227100089e-05 3.8196826615964e-05 -7.30044669264507e-06 4.93743106074558e-06 8.05415654173747e-07 9.40950646474227e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1034 0 0 2 0 0 2200 +639 668 0.990973563402713 0.0173679727514762 0.132927612479252 -0.0154402755896459 -0.00224354388318174 0.993581850340734 -0.113093205739016 0.0138778854877621 -0.134038662884164 0.111774148155945 0.984652312573448 -0.00137449699922312 0.000188782556574278 0.000138614194274613 -3.01190886807445e-05 1.25827723790074e-05 2.44282766110271e-05 0.000143526221123418 0.000138614194274613 0.000228582475791855 -2.10336622902452e-05 2.64130432500803e-05 1.17462223301935e-05 7.73748282240415e-05 -3.01190886807445e-05 -2.10336622902452e-05 2.05223412893339e-05 -3.02604723527013e-06 -5.21910437030846e-06 -1.80733094648253e-05 1.25827723790074e-05 2.64130432500803e-05 -3.02604723527013e-06 3.0559032318782e-05 -1.94695770754632e-05 6.71732946988856e-06 2.44282766110271e-05 1.17462223301935e-05 -5.21910437030846e-06 -1.94695770754632e-05 8.88009210964873e-05 4.52482688789108e-06 0.000143526221123418 7.73748282240415e-05 -1.80733094648253e-05 6.71732946988856e-06 4.52482688789108e-06 0.000189201603651305 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1044 0 0 0 0 0 2143 +639 671 0.991862608195437 0.0174596837989109 0.126109975439639 -0.0187455211081147 -0.00306585742639857 0.993540054828492 -0.113440556987519 0.0138250636822366 -0.127275948167693 0.112130811524039 0.985508759030063 0.00123779254679314 0.000264928238640446 0.000170852813840199 -4.20914619274951e-05 -1.89271562663952e-06 7.11651962517905e-05 0.000203088197857906 0.000170852813840199 0.000202374788891103 -2.81017021634522e-05 2.58745509038398e-06 6.22836139282973e-05 0.000100647045797844 -4.20914619274951e-05 -2.81017021634522e-05 2.49525451680529e-05 -4.61027087813413e-06 -7.8287443064868e-06 -2.35565074480328e-05 -1.89271562663952e-06 2.58745509038398e-06 -4.61027087813413e-06 2.54724315396179e-05 -1.0053780838608e-05 -6.54880818830198e-06 7.11651962517905e-05 6.22836139282973e-05 -7.8287443064868e-06 -1.0053780838608e-05 8.35436255347474e-05 5.14125153868914e-05 0.000203088197857906 0.000100647045797844 -2.35565074480328e-05 -6.54880818830198e-06 5.14125153868914e-05 0.000239891587605871 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1001 0 0 0 0 0 2153 +639 667 0.991729367008114 0.0158122822722324 0.127368890797669 -0.022915354258326 -0.00153687561037997 0.993773780505091 -0.111406064439853 0.0194813082256199 -0.128337448264501 0.110288915626013 0.985578943800543 -0.00457931498706928 9.62651589541707e-05 7.00795693616557e-05 -1.52012780332789e-05 2.32220271737342e-06 1.59281166524395e-05 7.42946331767056e-05 7.00795693616557e-05 0.000144530219187391 -1.04720775691791e-05 8.4672809015232e-06 1.60463156511567e-05 4.61109968531841e-05 -1.52012780332789e-05 -1.04720775691791e-05 2.36097874575972e-05 -6.35092499481464e-06 -3.24910217391942e-06 -3.24955027472612e-06 2.32220271737342e-06 8.4672809015232e-06 -6.35092499481464e-06 3.50115092009649e-05 -2.96279364043989e-05 -7.28598179875643e-06 1.59281166524395e-05 1.60463156511567e-05 -3.24910217391942e-06 -2.96279364043989e-05 0.000113365795577483 1.61480133211596e-05 7.42946331767056e-05 4.61109968531841e-05 -3.24955027472612e-06 -7.28598179875643e-06 1.61480133211596e-05 0.000136925428682494 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 935 0 0 0 0 0 2062 +639 674 0.995465653394265 0.0164598707262282 0.093686741687422 -0.0193024687258015 -0.00677233958929517 0.994679360480019 -0.102796426258635 0.00140135670118804 -0.094880284194437 0.101695833202426 0.990280611332186 -0.0158069784919003 0.000208267051623118 0.000139367205073679 -3.45877021725314e-05 2.75306887794897e-06 6.3234676660064e-05 0.000130558966319604 0.000139367205073679 0.000276855843476484 -2.89034681868394e-05 2.35634375203138e-05 6.25452772229661e-05 7.36068903126139e-05 -3.45877021725314e-05 -2.89034681868394e-05 2.33766116928946e-05 -2.73006878215893e-06 -1.08300819997972e-05 -2.09327918316111e-05 2.75306887794897e-06 2.35634375203138e-05 -2.73006878215893e-06 3.20312077024249e-05 -1.34774875923216e-05 7.3262122142157e-07 6.3234676660064e-05 6.25452772229661e-05 -1.08300819997972e-05 -1.34774875923216e-05 0.000108532976629308 3.57103466620618e-05 0.000130558966319604 7.36068903126139e-05 -2.09327918316111e-05 7.3262122142157e-07 3.57103466620618e-05 0.000154719486791345 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 989 0 0 1 0 0 2189 +639 675 0.993999717942938 0.0171058744979897 0.108036798300477 -0.0181811299953492 -0.00542295999825656 0.994188210236741 -0.107519273300758 0.0076564815940814 -0.109248122337257 0.10628824809886 0.988315565030653 -0.0068738253283776 0.000254640450577079 0.000150464100517655 -4.46936882394333e-05 -4.97740562666614e-06 7.47146351268997e-05 0.000179345715517972 0.000150464100517655 0.000187484947271171 -2.64353027528443e-05 2.16856393374656e-07 7.1130701419334e-05 8.54852116920776e-05 -4.46936882394333e-05 -2.64353027528443e-05 2.45997256634219e-05 -3.48953323488102e-06 -9.97405133209688e-06 -2.85566908387395e-05 -4.97740562666614e-06 2.16856393374656e-07 -3.48953323488102e-06 3.02405410700686e-05 -1.14600905414938e-05 -6.53463756164449e-06 7.47146351268997e-05 7.1130701419334e-05 -9.97405133209688e-06 -1.14600905414938e-05 9.5159639330255e-05 4.88033471127549e-05 0.000179345715517972 8.54852116920776e-05 -2.85566908387395e-05 -6.53463756164449e-06 4.88033471127549e-05 0.000197873112441429 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 988 0 0 1 0 0 2215 +639 643 0.998798279212164 0.010001893578097 0.0479787407887419 -0.007263828030855 -0.0113558986459158 0.999542524127681 0.0280318751853635 -0.00318981330234266 -0.0476764198400483 -0.0285430304157868 0.99845493358785 0.00142393375215687 0.000223637867359772 9.39842766913484e-05 -1.79752244309312e-05 2.77166422752035e-05 -4.84478371470201e-05 0.00011379379477126 9.39842766913484e-05 0.000147108620715937 -3.21238369777522e-06 2.84180470479224e-05 -2.24121503126591e-06 1.47377271701334e-05 -1.79752244309312e-05 -3.21238369777522e-06 1.93378900447012e-05 -5.27365875438004e-06 1.78598705587102e-06 -1.71063067125066e-05 2.77166422752035e-05 2.84180470479224e-05 -5.27365875438004e-06 2.42421764654626e-05 -6.09012956249637e-06 1.88917659555189e-05 -4.84478371470201e-05 -2.24121503126591e-06 1.78598705587102e-06 -6.09012956249637e-06 5.83566835002644e-05 -4.7914047812858e-05 0.00011379379477126 1.47377271701334e-05 -1.71063067125066e-05 1.88917659555189e-05 -4.7914047812858e-05 0.000162945617363574 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1496 0 0 0 0 0 1915 +639 670 0.991485512944115 0.0177330124884337 0.129003945249865 -0.0163054629245667 -0.00274039604546324 0.993306140955773 -0.115479004884279 0.0122213205622507 -0.130188201659979 0.114142238490553 0.984897244153372 0.00307846580654828 0.000164778901370058 0.000126923745623699 -3.6793341249322e-05 1.18322491637502e-05 3.6229046904796e-05 9.5557739762428e-05 0.000126923745623699 0.000237353409375248 -2.85041370270093e-05 2.40832147943005e-05 4.10107838836417e-05 4.74842509959116e-05 -3.6793341249322e-05 -2.85041370270093e-05 2.44629827742284e-05 -7.046254878786e-06 -7.3647351795306e-06 -1.98685285784657e-05 1.18322491637502e-05 2.40832147943005e-05 -7.046254878786e-06 2.87839302791147e-05 -1.01444396295789e-05 8.21517872537433e-07 3.6229046904796e-05 4.10107838836417e-05 -7.3647351795306e-06 -1.01444396295789e-05 8.29932510275925e-05 2.27198989819386e-05 9.5557739762428e-05 4.74842509959116e-05 -1.98685285784657e-05 8.21517872537433e-07 2.27198989819386e-05 0.000114099415905642 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1107 0 0 0 0 0 2140 +639 676 0.993108073597552 0.0172562791542513 0.115924867845987 -0.0171004805236677 -0.00421321221300546 0.993718583703932 -0.111828552902643 0.0082197525913629 -0.117126440218284 0.110569422677345 0.986942652726384 0.00112468659823107 0.000254673699678337 0.000211822021364346 -4.21294857568892e-05 6.14507715626188e-06 6.10920114113475e-05 0.000189551377620923 0.000211822021364346 0.000266103804051906 -3.53157135750855e-05 1.96117029523123e-05 4.76048357098061e-05 0.000148933095543164 -4.21294857568892e-05 -3.53157135750855e-05 2.66716818394648e-05 -4.23654844877227e-06 -9.43536667967079e-06 -2.65552464730323e-05 6.14507715626188e-06 1.96117029523123e-05 -4.23654844877227e-06 3.00205366011703e-05 -1.19991353612826e-05 4.06847008949465e-06 6.10920114113475e-05 4.76048357098061e-05 -9.43536667967079e-06 -1.19991353612826e-05 8.20164290688807e-05 4.68020777965588e-05 0.000189551377620923 0.000148933095543164 -2.65552464730323e-05 4.06847008949465e-06 4.68020777965588e-05 0.000197496594264347 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1063 0 0 0 0 0 2162 +639 666 0.991625654436055 0.0159511973280183 0.128156625923391 -0.0216123443612554 -0.00196292756015646 0.99408987670133 -0.108542452318562 0.0209879033229904 -0.129130586538043 0.107381918141447 0.985796335597067 -0.00433727513547908 0.000404814550107101 0.000152015633193155 -4.56704953881438e-05 -4.40963008199023e-05 8.84733593737732e-05 0.000427394268282184 0.000152015633193155 0.000171490493489364 -1.79870925731845e-05 -9.544657688399e-07 3.78004030813099e-05 0.000123042998893839 -4.56704953881438e-05 -1.79870925731845e-05 2.17450729852479e-05 3.81028157308763e-06 -1.13953411676094e-05 -4.67717488399017e-05 -4.40963008199023e-05 -9.544657688399e-07 3.81028157308763e-06 3.63292778439261e-05 -2.93883083386626e-05 -5.34815658970642e-05 8.84733593737732e-05 3.78004030813099e-05 -1.13953411676094e-05 -2.93883083386626e-05 0.000110797292038611 9.31640781626482e-05 0.000427394268282184 0.000123042998893839 -4.67717488399017e-05 -5.34815658970642e-05 9.31640781626482e-05 0.000541681985555026 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 800 0 0 2 0 0 2159 +639 665 0.990530476376155 0.0178171507596614 0.136132011330307 -0.0184282387796796 -0.00190428458572418 0.993231092492786 -0.116139444659437 0.0199347984165129 -0.137279820331481 0.114780425353774 0.983859596124042 0.00381672816371062 9.1983466989466e-05 6.07777414164749e-05 -2.10564842775779e-05 3.57662984773309e-06 1.33526572229866e-05 5.36656184909387e-05 6.07777414164749e-05 0.000157251350092043 -1.28606594152203e-05 1.38906164640873e-05 1.08334326921334e-05 1.9467327612582e-05 -2.10564842775779e-05 -1.28606594152203e-05 2.43299346484275e-05 -5.78626838289124e-06 -5.03717631737464e-06 -8.19775785156079e-06 3.57662984773309e-06 1.38906164640873e-05 -5.78626838289124e-06 2.64456705875872e-05 -3.12779394414224e-06 -3.5522966082166e-06 1.33526572229866e-05 1.08334326921334e-05 -5.03717631737464e-06 -3.12779394414224e-06 5.08245574054832e-05 3.72121547395537e-06 5.36656184909387e-05 1.9467327612582e-05 -8.19775785156079e-06 -3.5522966082166e-06 3.72121547395537e-06 8.32884424591169e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1142 0 0 0 0 0 2145 +640 642 0.999690873385455 0.00358364833130616 0.0246031529374363 -0.00239210686093247 -0.00387806447999013 0.999921322679559 0.0119293363876876 -0.00230957867096957 -0.0245584666808495 -0.0120210613258187 0.99962611800557 0.00420303369811401 8.77514276651867e-05 3.79948556433494e-05 -7.14509393245347e-07 5.31593661997809e-06 9.05890121098056e-06 2.44867306971248e-05 3.79948556433494e-05 9.81966297736836e-05 -2.4595983222204e-06 1.65169272922262e-05 1.29985435456783e-05 -1.09397260638999e-05 -7.14509393245347e-07 -2.4595983222204e-06 1.91051591888919e-05 -3.89751760506493e-06 2.77353620236044e-06 -1.08022302731742e-05 5.31593661997809e-06 1.65169272922262e-05 -3.89751760506493e-06 2.16507745296646e-05 -1.22486909820875e-06 1.12610572643332e-06 9.05890121098056e-06 1.29985435456783e-05 2.77353620236044e-06 -1.22486909820875e-06 5.3782606304099e-05 -1.52472390403704e-05 2.44867306971248e-05 -1.09397260638999e-05 -1.08022302731742e-05 1.12610572643332e-06 -1.52472390403704e-05 8.31904772579352e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1499 0 0 0 0 0 1946 +640 669 0.991640083543206 0.0203076004338446 0.127426630164354 -0.0178843324939875 -0.00460791456198621 0.992481279357956 -0.122309759411845 0.0205300296317793 -0.128952362653087 0.120700089016592 0.98427779446535 0.00712197783651686 9.48426286806737e-05 4.9672696219212e-05 -1.96222131090643e-05 -2.04999372127747e-07 2.1365413258909e-05 5.96322704355183e-05 4.9672696219212e-05 0.000168331141437617 -9.02912311642974e-06 1.40276413089667e-05 2.56616300749875e-05 4.28376757827031e-06 -1.96222131090643e-05 -9.02912311642974e-06 2.19556564046227e-05 -2.42882931369246e-06 -3.32176478978767e-06 -1.13624776750427e-05 -2.04999372127747e-07 1.40276413089667e-05 -2.42882931369246e-06 2.50930456350691e-05 -5.78728388128212e-06 -1.37190623685244e-06 2.1365413258909e-05 2.56616300749875e-05 -3.32176478978767e-06 -5.78728388128212e-06 6.24406923853261e-05 9.85453600809945e-06 5.96322704355183e-05 4.28376757827031e-06 -1.13624776750427e-05 -1.37190623685244e-06 9.85453600809945e-06 9.56861730003377e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1106 0 0 1 0 0 2202 +640 668 0.991336616784016 0.0198297172224266 0.129840265473004 -0.0142521598624459 -0.00372906955153295 0.99238852245001 -0.123089863716578 0.0129164880652242 -0.131292826397719 0.12153930567666 0.983865026775591 0.0078339530862254 0.000112809576409476 8.56651634824962e-05 -2.17798506835161e-05 6.2607835159696e-06 1.81508028255042e-05 6.79394780769248e-05 8.56651634824962e-05 0.000165855567832318 -1.15527273924271e-05 1.99900449632596e-05 5.80833993827881e-06 4.32600362061673e-05 -2.17798506835161e-05 -1.15527273924271e-05 2.15395171572912e-05 -2.19744254976493e-06 -4.98317924991821e-06 -1.06047393484203e-05 6.2607835159696e-06 1.99900449632596e-05 -2.19744254976493e-06 2.67406634039252e-05 -1.27748580527127e-05 1.42903753474702e-06 1.81508028255042e-05 5.80833993827881e-06 -4.98317924991821e-06 -1.27748580527127e-05 7.37156634972894e-05 7.98864711122619e-06 6.79394780769248e-05 4.32600362061673e-05 -1.06047393484203e-05 1.42903753474702e-06 7.98864711122619e-06 9.3040788040949e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1059 0 0 1 0 0 2109 +640 672 0.994578760745566 0.0203939246173029 0.101966546045839 -0.0189756579274757 -0.00817668862575251 0.992881297120527 -0.118827065904102 0.0100541714755084 -0.103664026725436 0.117349127252674 0.987665404829036 0.00226538299401776 0.000118782859267069 7.38267557443354e-05 -2.64461254665555e-05 1.12173837206662e-05 2.3782069336894e-05 5.77425930687918e-05 7.38267557443354e-05 0.0001152574058834 -1.86160257466582e-05 1.09975730331933e-05 2.26327325025484e-05 2.36997336120769e-05 -2.64461254665555e-05 -1.86160257466582e-05 2.25564518209501e-05 -5.82275983888282e-06 -6.91355457674196e-06 -1.15071700185171e-05 1.12173837206662e-05 1.09975730331933e-05 -5.82275983888282e-06 3.39787739299159e-05 -2.66234346541703e-05 1.985189242634e-06 2.3782069336894e-05 2.26327325025484e-05 -6.91355457674196e-06 -2.66234346541703e-05 0.000118065849281691 3.55170484360651e-07 5.77425930687918e-05 2.36997336120769e-05 -1.15071700185171e-05 1.985189242634e-06 3.55170484360651e-07 7.82087357897122e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1107 0 0 6 0 0 2170 +639 678 0.992404765717268 0.0171503326303925 0.12181398553664 -0.0129400254423992 -0.00322854680586218 0.993523975217824 -0.113576789675067 -0.000566881308688725 -0.122972994869509 0.112320865194491 0.986033298512167 -0.0023051919539555 0.000139226205513646 7.40335373663819e-05 -2.96525538947887e-05 2.78146069759775e-06 2.00825639144344e-05 0.000101941257033118 7.40335373663819e-05 0.000152481704605386 -1.3201855542431e-05 7.57588195579984e-06 3.17067840005094e-05 4.08217707324465e-05 -2.96525538947887e-05 -1.3201855542431e-05 2.78661162248637e-05 -3.5492554421618e-06 -7.54888061509183e-06 -1.67186590175149e-05 2.78146069759775e-06 7.57588195579984e-06 -3.5492554421618e-06 2.59175210226612e-05 -1.08188872810251e-05 2.76963806269916e-06 2.00825639144344e-05 3.17067840005094e-05 -7.54888061509183e-06 -1.08188872810251e-05 8.15197371326545e-05 1.18529633421628e-05 0.000101941257033118 4.08217707324465e-05 -1.67186590175149e-05 2.76963806269916e-06 1.18529633421628e-05 0.000125004056179031 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1097 0 0 0 0 0 2177 +640 643 0.999021057429197 0.0111569166404793 0.0428071258568727 -0.0073358311149005 -0.0127075281945965 0.999266526871545 0.0361237733530716 -0.00396935634341697 -0.0423726980523105 -0.0366323830122741 0.998430079161585 -0.0109014233916402 0.000226311686765438 0.000137911843024491 -1.01014604461949e-05 1.92042457267517e-05 -9.02987666064815e-06 0.000102400151658071 0.000137911843024491 0.000146479710199159 -6.97082631671738e-06 2.20283518082215e-05 -1.06593538221429e-06 3.5533730461747e-05 -1.01014604461949e-05 -6.97082631671738e-06 2.33263064676975e-05 -4.36255684862773e-06 -4.01593195720439e-06 -9.34141677613806e-06 1.92042457267517e-05 2.20283518082215e-05 -4.36255684862773e-06 2.46558992978548e-05 -5.19364536730712e-06 2.74139755448314e-06 -9.02987666064815e-06 -1.06593538221429e-06 -4.01593195720439e-06 -5.19364536730712e-06 4.96248848481702e-05 -1.4990138301632e-05 0.000102400151658071 3.5533730461747e-05 -9.34141677613806e-06 2.74139755448314e-06 -1.4990138301632e-05 0.000151975889351835 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1471 0 0 2 0 0 1860 +640 670 0.991871204893615 0.020130932847388 0.125643378041114 -0.0158222524041879 -0.00467291935964915 0.992502868246131 -0.122131979218639 0.0118816402396319 -0.127160043754107 0.120552072009974 0.984529086013489 0.00454543208719517 0.000107391078857791 8.43041711255893e-05 -3.20320215917719e-05 1.33337606096787e-05 1.65329755821836e-05 5.58277049108669e-05 8.43041711255893e-05 0.000134740120767614 -2.56240040034455e-05 1.15864845000034e-05 2.86151342991394e-05 3.15970890650444e-05 -3.20320215917719e-05 -2.56240040034455e-05 2.76431025476562e-05 -8.85953201337312e-06 -2.05159771641517e-06 -1.5618587911936e-05 1.33337606096787e-05 1.15864845000034e-05 -8.85953201337312e-06 2.71106450120039e-05 -1.81364223004582e-05 6.50378282327694e-06 1.65329755821836e-05 2.86151342991394e-05 -2.05159771641517e-06 -1.81364223004582e-05 0.000100116941258936 -8.9143888201207e-06 5.58277049108669e-05 3.15970890650444e-05 -1.5618587911936e-05 6.50378282327694e-06 -8.9143888201207e-06 8.16186240418621e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1115 0 0 3 0 0 2163 +640 675 0.993646322183704 0.0186378037044951 0.110993777680875 -0.0150770728936978 -0.00656585709954628 0.994112938869487 -0.108149684663527 0.0019545934385686 -0.112356023120023 0.10673376712805 0.987919038698672 -0.0110397051563298 0.00018765490179189 0.000130380610349326 -2.74793701550847e-05 3.70200512871152e-06 4.78559483692116e-05 0.000136890545447394 0.000130380610349326 0.000145451397952662 -1.95780302337283e-05 4.69216931276166e-06 4.23697030574883e-05 9.5419155076345e-05 -2.74793701550847e-05 -1.95780302337283e-05 2.24828267811626e-05 -5.05908024900086e-06 -5.28329216779474e-06 -1.4428931060403e-05 3.70200512871152e-06 4.69216931276166e-06 -5.05908024900086e-06 2.83477396587213e-05 -1.19725421714192e-05 6.21133175045967e-07 4.78559483692116e-05 4.23697030574883e-05 -5.28329216779474e-06 -1.19725421714192e-05 8.0862670422165e-05 2.94833788836553e-05 0.000136890545447394 9.5419155076345e-05 -1.4428931060403e-05 6.21133175045967e-07 2.94833788836553e-05 0.000156600722607722 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 991 0 0 5 0 0 2211 +640 671 0.993092027416742 0.0203282093711568 0.115563787516104 -0.0198097151309034 -0.00630110522003011 0.992696759670656 -0.120471736985844 0.0167600326540783 -0.11716877209526 0.118911341944924 0.985967327857544 0.00749197370291839 8.21291173140421e-05 5.7139217576534e-05 -2.08643057343863e-05 4.59672517960617e-06 2.82930022860873e-05 5.92116252860954e-05 5.7139217576534e-05 0.000116170588412653 -1.46891372054572e-05 -1.98594258813331e-06 4.97101540777309e-05 2.75309348463238e-05 -2.08643057343863e-05 -1.46891372054572e-05 2.49558259165383e-05 -6.16156015330025e-06 -6.79785148235237e-06 -1.3781843995851e-05 4.59672517960617e-06 -1.98594258813331e-06 -6.16156015330025e-06 2.55354487829795e-05 -1.252748571448e-05 2.13447254870914e-06 2.82930022860873e-05 4.97101540777309e-05 -6.79785148235237e-06 -1.252748571448e-05 8.78384935646951e-05 7.14788033515676e-06 5.92116252860954e-05 2.75309348463238e-05 -1.3781843995851e-05 2.13447254870914e-06 7.14788033515676e-06 0.000111489593829162 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1012 0 0 8 0 0 2166 +640 667 0.99350437696788 0.0197786070930762 0.11206185634337 -0.0236442476543612 -0.00598823778500332 0.992501705509933 -0.122084010288423 0.021735453834026 -0.113636235215246 0.120619945536927 0.986173227574534 0.00535755355337852 7.61367855632289e-05 4.70615177621695e-05 -2.23270697264318e-05 5.93562153456354e-06 7.56825739525152e-06 3.98370552425619e-05 4.70615177621695e-05 0.000140910948987181 -7.80763448012966e-06 2.684937066495e-05 -3.05052213326489e-05 2.10116766866945e-05 -2.23270697264318e-05 -7.80763448012966e-06 2.86956657528923e-05 -5.21964266930757e-06 -1.59292587422181e-06 -7.53693048757935e-06 5.93562153456354e-06 2.684937066495e-05 -5.21964266930757e-06 3.79991865718853e-05 -3.31239125287528e-05 5.64137538049895e-06 7.56825739525152e-06 -3.05052213326489e-05 -1.59292587422181e-06 -3.31239125287528e-05 0.000108836003614028 -8.3437307708941e-06 3.98370552425619e-05 2.10116766866945e-05 -7.53693048757935e-06 5.64137538049895e-06 -8.3437307708941e-06 8.59897667789446e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 946 0 0 8 0 0 2029 +640 674 0.995686785522427 0.0188903730053894 0.090834899370964 -0.0181554511585884 -0.00883325370735895 0.993906614153569 -0.109870905933876 0.0012997775397615 -0.0923569096763059 0.108594641440112 0.989786545213429 -0.00756412626766723 0.000183288287461815 0.000114089225936787 -3.84873045205758e-05 1.87486677355112e-05 3.29148898253828e-05 0.000117486193737184 0.000114089225936787 0.000204132135869939 -2.70993226275546e-05 2.77297353424405e-05 2.98516092669967e-05 5.44156701877274e-05 -3.84873045205758e-05 -2.70993226275546e-05 2.48641829324683e-05 -8.66816327431378e-06 -8.96868868031522e-06 -1.63818253033302e-05 1.87486677355112e-05 2.77297353424405e-05 -8.66816327431378e-06 3.23189345611852e-05 -6.10659274699495e-06 1.15334407816658e-05 3.29148898253828e-05 2.98516092669967e-05 -8.96868868031522e-06 -6.10659274699495e-06 7.35365623321103e-05 3.18960160894047e-07 0.000117486193737184 5.44156701877274e-05 -1.63818253033302e-05 1.15334407816658e-05 3.18960160894047e-07 0.000154078371629276 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 991 0 0 2 0 0 2188 +640 644 0.998837344935148 0.0152084823862093 0.0457456055420813 -0.00987584012526358 -0.0158446239250014 0.999782299847318 0.0135757432460117 -0.00135110768214362 -0.0455291802647337 -0.0142847812554034 0.998860870576532 0.00488790052544695 0.000131262032815766 9.27558319201473e-05 -1.37817379454248e-05 1.55153115600361e-05 -8.98007701758396e-06 3.88493456107541e-05 9.27558319201473e-05 0.000139009981158638 -1.38764156701065e-05 1.85223491073306e-05 -4.67058880578376e-06 7.36225225845352e-06 -1.37817379454248e-05 -1.38764156701065e-05 2.55869950359056e-05 -7.28328809921442e-06 1.20624594410007e-06 -9.16266763014642e-06 1.55153115600361e-05 1.85223491073306e-05 -7.28328809921442e-06 2.45833166134917e-05 -9.89184621262532e-06 4.88593897701391e-06 -8.98007701758396e-06 -4.67058880578376e-06 1.20624594410007e-06 -9.89184621262532e-06 6.25697591764464e-05 -1.63172450943067e-05 3.88493456107541e-05 7.36225225845352e-06 -9.16266763014642e-06 4.88593897701391e-06 -1.63172450943067e-05 9.76342981494603e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1525 0 0 3 0 0 1787 +640 673 0.995998502896205 0.0194080728372345 0.0872370846444505 -0.0210913907622001 -0.0095403776185064 0.99364687369277 -0.112137734931117 0.00702922883657634 -0.0888592337543754 0.110856741379718 0.989855958949208 -0.00468115420976113 9.06119301423353e-05 6.7794969148276e-05 -2.24240475773112e-05 1.38204587504098e-05 6.10290127548051e-06 5.42011337045851e-05 6.7794969148276e-05 0.000140354267328352 -1.66764425246158e-05 2.57338287086829e-06 5.21526001461738e-05 2.9641964429003e-05 -2.24240475773112e-05 -1.66764425246158e-05 2.29568798795279e-05 -6.97595395630219e-06 -7.73313029036383e-06 -1.04207140699296e-05 1.38204587504098e-05 2.57338287086829e-06 -6.97595395630219e-06 2.85673697749991e-05 -1.55952135135085e-05 1.17720258346172e-05 6.10290127548051e-06 5.21526001461738e-05 -7.73313029036383e-06 -1.55952135135085e-05 0.000122705845515248 -2.43338727681383e-05 5.42011337045851e-05 2.9641964429003e-05 -1.04207140699296e-05 1.17720258346172e-05 -2.43338727681383e-05 9.52181405386723e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1043 0 0 11 0 0 2177 +640 678 0.992433884824866 0.0203564612545161 0.121080959430534 -0.0109464699622204 -0.00563281437898949 0.992670447606371 -0.120721389368824 -0.00212346144729765 -0.122650950479795 0.119125970863455 0.985274452836489 0.00391778959529976 9.98733709476976e-05 4.9605276379157e-05 -2.75653103752506e-05 3.4964631292328e-06 2.44672347611379e-05 6.57689668180441e-05 4.9605276379157e-05 0.000190737000673778 -7.18599905867681e-06 1.13442946680892e-05 3.27461210381241e-05 4.00925270328387e-07 -2.75653103752506e-05 -7.18599905867681e-06 2.97712573286455e-05 -2.87799949282095e-06 -7.62119068887521e-06 -1.28357001917347e-05 3.4964631292328e-06 1.13442946680892e-05 -2.87799949282095e-06 2.37303323519657e-05 -3.8597131005085e-06 -4.28725095475875e-06 2.44672347611379e-05 3.27461210381241e-05 -7.62119068887521e-06 -3.8597131005085e-06 6.0907501032913e-05 1.08128032194658e-05 6.57689668180441e-05 4.00925270328387e-07 -1.28357001917347e-05 -4.28725095475875e-06 1.08128032194658e-05 9.63320279748898e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1102 0 0 2 0 0 2150 +641 671 0.992581195426525 0.0173144298200507 0.120344426566655 -0.0170821021942574 -0.00178038048656654 0.991771814076173 -0.128005855527707 0.0162303946326185 -0.121570558652058 0.126841946232561 0.984444879079049 0.00084623938512669 0.00015016829824234 0.000116209014130492 -3.12580884397083e-05 1.13608230684335e-05 1.42048473951744e-05 9.40784797117328e-05 0.000116209014130492 0.000122945572060635 -2.72882237763038e-05 5.47324285228198e-06 2.0842480728307e-05 6.92579644097427e-05 -3.12580884397083e-05 -2.72882237763038e-05 2.31173063773631e-05 -5.17327949458643e-06 -3.30097014713429e-06 -1.54444201733203e-05 1.13608230684335e-05 5.47324285228198e-06 -5.17327949458643e-06 2.69088265717762e-05 -1.52133399726728e-05 3.34929429101592e-06 1.42048473951744e-05 2.0842480728307e-05 -3.30097014713429e-06 -1.52133399726728e-05 7.55535955898295e-05 6.56103615413586e-06 9.40784797117328e-05 6.92579644097427e-05 -1.54444201733203e-05 3.34929429101592e-06 6.56103615413586e-06 0.000113746510367015 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 953 0 0 0 0 0 2095 +640 666 0.992671156081062 0.0171679668540293 0.119621222192326 -0.0197293402082609 -0.00445958111741264 0.994387398419521 -0.105706262826352 0.013332448667082 -0.120764597548057 0.104398097581113 0.987176250322353 -0.0135732856201523 0.00014226580345832 0.000100243484498233 -2.09924231366309e-05 1.66052301958356e-05 -3.83235127955353e-07 0.000110872129465735 0.000100243484498233 0.000165989222985983 -1.37391256146499e-05 1.40062883947871e-05 3.14223506442447e-05 4.69977738663468e-05 -2.09924231366309e-05 -1.37391256146499e-05 1.78136424088315e-05 -2.81795438952168e-06 -1.6293654382032e-06 -1.3459281459847e-05 1.66052301958356e-05 1.40062883947871e-05 -2.81795438952168e-06 3.34637640937737e-05 -2.33496964831845e-05 1.37058535455826e-05 -3.83235127955353e-07 3.14223506442447e-05 -1.6293654382032e-06 -2.33496964831845e-05 0.000118625718624141 -1.17683239344729e-05 0.000110872129465735 4.69977738663468e-05 -1.3459281459847e-05 1.37058535455826e-05 -1.17683239344729e-05 0.000172181306763969 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 786 0 0 4 0 0 2161 +640 676 0.993642816852247 0.0197851112547007 0.110826449417866 -0.0159604522862113 -0.00677645956985577 0.993162110022357 -0.116546569283006 0.00608155648736083 -0.112374517189752 0.11505465044308 0.986982469600038 0.00168567974446528 0.000250038091097614 0.000176755279579 -3.64006579745187e-05 -2.49666206526941e-06 5.63158287793052e-05 0.000215033635030522 0.000176755279579 0.000193657635922212 -2.96943407256494e-05 9.02591223869977e-06 4.56199333240386e-05 0.000144570360074677 -3.64006579745187e-05 -2.96943407256494e-05 2.67056632019193e-05 -6.07665759450782e-06 -6.29979120340515e-06 -2.23191463665836e-05 -2.49666206526941e-06 9.02591223869977e-06 -6.07665759450782e-06 3.26057941995557e-05 -1.94576659831914e-05 -9.50054264207542e-06 5.63158287793052e-05 4.56199333240386e-05 -6.29979120340515e-06 -1.94576659831914e-05 9.37861043607634e-05 5.16342534287393e-05 0.000215033635030522 0.000144570360074677 -2.23191463665836e-05 -9.50054264207542e-06 5.16342534287393e-05 0.000246420534299816 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1074 0 0 4 0 0 2148 +641 643 0.999411926064762 0.0106787705866843 0.0325847494739496 -0.00691347130342462 -0.0112368500414805 0.999792477186383 0.0169922265363253 -0.0010776792386248 -0.0323965313061193 -0.0173483837942756 0.999324521033612 -0.00268428068922069 7.82792137866785e-05 6.00810010586928e-05 -8.16593083444907e-06 8.0757360194303e-06 -1.92641065823738e-06 4.71390457052992e-06 6.00810010586928e-05 7.38862443105004e-05 -9.40524785030466e-06 1.1100581601907e-05 -3.1631450682796e-06 -3.98581670240402e-06 -8.16593083444907e-06 -9.40524785030466e-06 1.9820665750209e-05 -7.58036931062012e-06 -2.65053443924259e-06 -5.31135324169201e-06 8.0757360194303e-06 1.1100581601907e-05 -7.58036931062012e-06 1.90374857245978e-05 3.38969248775578e-08 1.27798120857427e-06 -1.92641065823738e-06 -3.1631450682796e-06 -2.65053443924259e-06 3.38969248775578e-08 3.65846074978999e-05 -5.76911557648529e-06 4.71390457052992e-06 -3.98581670240402e-06 -5.31135324169201e-06 1.27798120857427e-06 -5.76911557648529e-06 6.06767915973949e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1561 0 0 0 0 0 1867 +641 644 0.999218527947704 0.0137087626803615 0.0370729447413636 -0.00866570461926851 -0.0139479184899519 0.999883500881396 0.00620001894847685 0.00196846928491322 -0.0369836311875988 -0.00671226421837995 0.999293328574369 0.00473946887691767 0.000216044456156673 0.000123830255452653 -1.79326411097435e-05 3.01745297327625e-05 -5.07138508884356e-05 9.33963298815543e-05 0.000123830255452653 0.000116523661021988 -1.05920029791726e-05 1.6900542798539e-05 -5.80744396279372e-06 3.39231015026885e-05 -1.79326411097435e-05 -1.05920029791726e-05 2.24127055008619e-05 -3.49284762845475e-06 6.53855463578806e-06 -1.92122696453061e-05 3.01745297327625e-05 1.6900542798539e-05 -3.49284762845475e-06 2.29104244749595e-05 -1.38430583871596e-05 1.23826661903967e-05 -5.07138508884356e-05 -5.80744396279372e-06 6.53855463578806e-06 -1.38430583871596e-05 8.19704728045559e-05 -4.30040260888397e-05 9.33963298815543e-05 3.39231015026885e-05 -1.92122696453061e-05 1.23826661903967e-05 -4.30040260888397e-05 0.000136016753543735 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1461 0 0 0 0 0 1771 +641 672 0.994364672430764 0.0151718255517867 0.104922418629607 -0.0189141359496 -0.00327778692268492 0.993633209337516 -0.112615724543764 0.0119558793927359 -0.105962985681557 0.111637184714833 0.988083490730615 -0.019959231964341 0.000117073174299012 8.03871485601697e-05 -1.85860988011365e-05 7.77525124145513e-06 2.6350863570357e-05 8.4934204758598e-05 8.03871485601697e-05 0.000100342279955864 -1.9510534252379e-05 1.18111817148179e-05 1.87547102349455e-05 5.70954049409798e-05 -1.85860988011365e-05 -1.9510534252379e-05 2.02714621754282e-05 -7.19218520707766e-06 -5.75398655019995e-06 -6.95581350034638e-06 7.77525124145513e-06 1.18111817148179e-05 -7.19218520707766e-06 2.68102474449046e-05 -7.01588614992303e-06 5.97400364999105e-06 2.6350863570357e-05 1.87547102349455e-05 -5.75398655019995e-06 -7.01588614992303e-06 6.24394024946008e-05 6.86076956352061e-06 8.4934204758598e-05 5.70954049409798e-05 -6.95581350034638e-06 5.97400364999105e-06 6.86076956352061e-06 0.000128413920233604 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1058 0 0 0 0 0 2140 +641 669 0.992615805312866 0.0168775585471574 0.120120818597682 -0.0154477663357937 -0.00137616846419955 0.991776126358493 -0.12797742514092 0.0136026731413728 -0.121292906649351 0.126867108435673 0.984475884719236 0.000610367087513675 0.000152370886990981 0.000108194951192383 -3.02893621795032e-05 -5.92078574258089e-06 5.62402348887622e-05 0.000120564170219877 0.000108194951192383 0.000138207676690493 -3.01075232546509e-05 5.50880591413622e-06 4.08767915033069e-05 6.28904868991222e-05 -3.02893621795032e-05 -3.01075232546509e-05 2.29117002840141e-05 -3.18650137603782e-06 -8.35130951762602e-06 -1.93874260773258e-05 -5.92078574258089e-06 5.50880591413622e-06 -3.18650137603782e-06 3.27908517703485e-05 -2.90700612510659e-05 -1.0124523138624e-05 5.62402348887622e-05 4.08767915033069e-05 -8.35130951762602e-06 -2.90700612510659e-05 0.000106401251173799 4.23083697913899e-05 0.000120564170219877 6.28904868991222e-05 -1.93874260773258e-05 -1.0124523138624e-05 4.23083697913899e-05 0.00016899485384692 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1070 0 0 0 0 0 2155 +641 668 0.992470620267792 0.0160755339917814 0.121423412537051 -0.0155240661508014 -0.000539821577125978 0.991914144892472 -0.126909565261654 0.0135671366341468 -0.122481739446861 0.125888467975094 0.98445432455394 -0.000487839935415812 0.000134410419358095 0.000104884763223399 -1.83430275760482e-05 5.63320135171289e-06 2.64452793684692e-05 0.000113881121663593 0.000104884763223399 0.000143345274915259 -1.65758489567443e-05 2.34206091087155e-05 -9.03993441352165e-06 8.03942138483605e-05 -1.83430275760482e-05 -1.65758489567443e-05 2.17426554632044e-05 -1.06281780047408e-06 -6.97997968094175e-06 -1.10165986354453e-05 5.63320135171289e-06 2.34206091087155e-05 -1.06281780047408e-06 3.12870869532438e-05 -2.50022823374243e-05 9.04421086003608e-07 2.64452793684692e-05 -9.03993441352165e-06 -6.97997968094175e-06 -2.50022823374243e-05 9.36273127149272e-05 2.68229801442755e-05 0.000113881121663593 8.03942138483605e-05 -1.10165986354453e-05 9.04421086003608e-07 2.68229801442755e-05 0.000151908996350581 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1028 0 0 0 0 0 2163 +641 675 0.99502328458775 0.0172373949278877 0.0981403858984908 -0.017327534907801 -0.00473372927950432 0.991988582608584 -0.12623883626413 0.00913507192373456 -0.0995301709800251 0.12514601148384 0.987133334901812 -0.00145421064714594 9.02819021917842e-05 7.53982953818706e-05 -1.54093513627236e-05 1.23867731243437e-05 -1.56763741445293e-06 5.1337452100401e-05 7.53982953818706e-05 0.000116093048894527 -1.21188918869478e-05 1.09510369856235e-05 7.79431273999765e-06 5.1420719917805e-05 -1.54093513627236e-05 -1.21188918869478e-05 1.63337769159955e-05 -3.54986722452902e-06 2.73114510084215e-06 -4.91257221911234e-06 1.23867731243437e-05 1.09510369856235e-05 -3.54986722452902e-06 2.69843718798021e-05 -1.66529062284505e-05 4.81445625058239e-06 -1.56763741445293e-06 7.79431273999765e-06 2.73114510084215e-06 -1.66529062284505e-05 7.66984726144225e-05 4.03563959545508e-06 5.1337452100401e-05 5.1420719917805e-05 -4.91257221911234e-06 4.81445625058239e-06 4.03563959545508e-06 7.78498554714879e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 967 0 0 0 0 0 2183 +641 670 0.992864275453044 0.0162785931704124 0.118133559725824 -0.0171458444459656 -0.00138782836007746 0.992149186368921 -0.125052252758319 0.0123537115673685 -0.119241789912537 0.123995965224195 0.98509207495877 -0.00536533688496245 9.93024444382933e-05 9.04178097845177e-05 -1.66409982918685e-05 2.43493290450908e-06 2.25864255261498e-05 5.11299436913184e-05 9.04178097845177e-05 0.000129237491127883 -1.59731478251e-05 3.63666457613305e-06 2.85165354568672e-05 4.224840550429e-05 -1.66409982918685e-05 -1.59731478251e-05 1.59569287227072e-05 -2.71911421868866e-06 -4.09657694269073e-06 -4.99407970364364e-06 2.43493290450908e-06 3.63666457613305e-06 -2.71911421868866e-06 2.13265625411726e-05 -7.62968406450754e-06 -5.19065349269947e-07 2.25864255261498e-05 2.85165354568672e-05 -4.09657694269073e-06 -7.62968406450754e-06 6.64707210095763e-05 6.3662644029773e-06 5.11299436913184e-05 4.224840550429e-05 -4.99407970364364e-06 -5.19065349269947e-07 6.3662644029773e-06 7.97401951119365e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1081 0 0 0 0 0 2101 +641 645 0.999042208546162 0.0135790330949991 0.0415965792272829 -0.00888750445282387 -0.0133885258712738 0.999898582787219 -0.00485505047403186 -0.000406607256587726 -0.0416582875092212 0.00429348347103892 0.99912269170582 0.00418519243202066 0.000134454953635026 0.000116969617100039 -1.62798276142103e-05 2.02009635687692e-05 -9.07885066880329e-06 4.01973055540905e-05 0.000116969617100039 0.000165178257809376 -1.54179954454869e-05 2.25456676342044e-05 1.20938577127758e-06 1.24516595613792e-05 -1.62798276142103e-05 -1.54179954454869e-05 2.27855337385922e-05 -7.2996321288169e-06 -1.98772386817485e-06 -1.04281413301572e-05 2.02009635687692e-05 2.25456676342044e-05 -7.2996321288169e-06 2.1553218937137e-05 -2.88664771616923e-06 9.44517912847638e-06 -9.07885066880329e-06 1.20938577127758e-06 -1.98772386817485e-06 -2.88664771616923e-06 4.56169337514196e-05 -1.77767945901808e-05 4.01973055540905e-05 1.24516595613792e-05 -1.04281413301572e-05 9.44517912847638e-06 -1.77767945901808e-05 0.000111096217998433 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1493 0 0 0 0 0 1839 +641 674 0.996384313740594 0.0171158154716935 0.0832186769446944 -0.0189060251841198 -0.00651377425994559 0.992003999406433 -0.126038231924019 0.00625283406144482 -0.0847105074744388 0.125040449544863 0.98852871273476 -0.00264519950980734 0.000108089889977358 8.59096640808254e-05 -1.65524962198445e-05 1.42726929322565e-05 8.84397147650305e-06 6.11030872033002e-05 8.59096640808254e-05 0.000137861760504924 -1.05234811065284e-05 1.89115033307409e-05 1.15994684477526e-05 7.08375895447105e-05 -1.65524962198445e-05 -1.05234811065284e-05 1.87010487998801e-05 -2.71634750243545e-06 -6.42583086813094e-06 -3.56753691795829e-06 1.42726929322565e-05 1.89115033307409e-05 -2.71634750243545e-06 2.63560342635595e-05 -1.09721130352239e-05 8.40827561710947e-06 8.84397147650305e-06 1.15994684477526e-05 -6.42583086813094e-06 -1.09721130352239e-05 7.90099852421999e-05 6.69819996475261e-06 6.11030872033002e-05 7.08375895447105e-05 -3.56753691795829e-06 8.40827561710947e-06 6.69819996475261e-06 0.000100264653308688 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 963 0 0 0 0 0 2110 +641 673 0.995933054961377 0.01560083000569 0.0887353601358165 -0.0185482555190286 -0.0056277586248561 0.993742994381576 -0.111549045044771 0.00333965625361183 -0.0899204001779343 0.110596000021129 0.989789293946528 -0.0233890327484404 0.000337134612349839 0.000113130132938082 -4.5671774266915e-05 4.12066839922596e-05 -1.61058041398859e-05 0.000305901699187726 0.000113130132938082 0.000164970225858726 -2.49713665745557e-05 2.98129555467428e-05 2.50502786212956e-05 6.97541648886318e-05 -4.5671774266915e-05 -2.49713665745557e-05 2.65536220340257e-05 -1.1647097855661e-05 -2.80658253514909e-06 -3.69055254741442e-05 4.12066839922596e-05 2.98129555467428e-05 -1.1647097855661e-05 4.40106029333543e-05 -2.52107385541203e-05 3.33050783455531e-05 -1.61058041398859e-05 2.50502786212956e-05 -2.80658253514909e-06 -2.52107385541203e-05 0.000111709194225783 -3.04158889408887e-05 0.000305901699187726 6.97541648886318e-05 -3.69055254741442e-05 3.33050783455531e-05 -3.04158889408887e-05 0.000362850340226156 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1018 0 0 1 0 0 2174 +641 667 0.99371243620467 0.0172831261617276 0.11062046683258 -0.0231905188807667 -0.00251458151625371 0.991209735039339 -0.132275991937472 0.0265848338500406 -0.111934226275873 0.131166134018358 0.985020900425316 0.00578685334554273 0.000356110681400997 0.000138516509277421 -4.8686454956517e-05 -3.35116847939861e-06 2.11771626250781e-05 0.000355616863216229 0.000138516509277421 0.000199846704261962 -1.91633202756942e-05 1.01723930051171e-05 1.19852298493132e-05 0.000101661242362452 -4.8686454956517e-05 -1.91633202756942e-05 2.32516092140055e-05 -1.04045609390544e-06 -5.89296131497989e-06 -4.25493009396009e-05 -3.35116847939861e-06 1.01723930051171e-05 -1.04045609390544e-06 2.73045634827568e-05 -1.35703871717633e-05 -9.06044018283422e-06 2.11771626250781e-05 1.19852298493132e-05 -5.89296131497989e-06 -1.35703871717633e-05 7.41243407432516e-05 6.31104094206516e-06 0.000355616863216229 0.000101661242362452 -4.25493009396009e-05 -9.06044018283422e-06 6.31104094206516e-06 0.000456205833598185 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 897 0 0 0 0 0 1970 +641 676 0.993855247763043 0.0170831359887968 0.109361386963811 -0.0142422196446544 -0.00235899707645114 0.99106297490163 -0.133373966394958 0.00276709494889807 -0.110662467109014 0.132296433224477 0.985013437537493 0.00638787715010744 0.000170892681184414 0.000138837217872557 -3.1896997455835e-05 1.42845313519225e-05 1.15749765812599e-05 0.000170665250914425 0.000138837217872557 0.000204224687197345 -2.70251135531671e-05 1.80774707099371e-05 2.05954180007641e-05 0.000122811620486177 -3.1896997455835e-05 -2.70251135531671e-05 3.00292663432269e-05 -6.93321030583027e-06 -4.53267176556789e-06 -2.56497550788745e-05 1.42845313519225e-05 1.80774707099371e-05 -6.93321030583027e-06 3.28877421272124e-05 -2.53720370906341e-05 1.50288937090801e-05 1.15749765812599e-05 2.05954180007641e-05 -4.53267176556789e-06 -2.53720370906341e-05 0.000115256516144538 8.54415326323168e-06 0.000170665250914425 0.000122811620486177 -2.56497550788745e-05 1.50288937090801e-05 8.54415326323168e-06 0.000241840940077008 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1021 0 0 0 0 0 2158 +642 672 0.99623091463522 0.0114311651203046 0.0859842612869637 -0.0140819868026593 -0.000633987010841728 0.992211385474018 -0.12456389764374 0.0109186960631538 -0.0867384735024925 0.124039892775359 0.988478903272465 -0.0147779067036052 0.000117805765812411 9.77345138320878e-05 -2.43671532720564e-05 2.97488665415222e-05 -9.38587238965188e-06 6.47691140174672e-05 9.77345138320878e-05 0.000157607040495217 -2.12577621101858e-05 3.45148399218189e-05 -1.11246183343256e-05 5.41134320217162e-05 -2.43671532720564e-05 -2.12577621101858e-05 2.0089869604583e-05 -6.69270517405648e-06 3.77909550338447e-07 -9.82901427883286e-06 2.97488665415222e-05 3.45148399218189e-05 -6.69270517405648e-06 4.11616403966179e-05 -3.28953785064876e-05 1.24722678638303e-05 -9.38587238965188e-06 -1.11246183343256e-05 3.77909550338447e-07 -3.28953785064876e-05 0.000104391759986863 -1.10353978287417e-05 6.47691140174672e-05 5.41134320217162e-05 -9.82901427883286e-06 1.24722678638303e-05 -1.10353978287417e-05 9.85387606852353e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1068 0 0 0 0 0 2179 +642 671 0.994864255310681 0.0127859845039029 0.100407330934498 -0.0129814007920492 0.00055085443842698 0.99129077854864 -0.131690124625272 0.0146045663905961 -0.101216649146825 0.131069107590987 0.986192718980824 -0.00252313858713292 0.000185586253640432 0.000118701380727703 -3.60910044580021e-05 4.48874693626389e-06 4.40066464139289e-05 0.000127487613629604 0.000118701380727703 0.000137399649780565 -2.70180451421924e-05 1.27431268887339e-05 1.90403675897259e-05 5.94426902332469e-05 -3.60910044580021e-05 -2.70180451421924e-05 2.40581902140447e-05 -6.08900287548485e-06 -6.02531162208813e-06 -2.17390095162226e-05 4.48874693626389e-06 1.27431268887339e-05 -6.08900287548485e-06 3.59224479080414e-05 -2.93132605102058e-05 -8.38304693979351e-07 4.40066464139289e-05 1.90403675897259e-05 -6.02531162208813e-06 -2.93132605102058e-05 0.000105574549088697 2.91481037239885e-05 0.000127487613629604 5.94426902332469e-05 -2.17390095162226e-05 -8.38304693979351e-07 2.91481037239885e-05 0.000149585118627232 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 965 0 0 0 0 0 2130 +642 670 0.994063719781387 0.0117442114000281 0.108163739362983 -0.0120800202316807 0.00258515585728937 0.991326739863286 -0.131394869767517 0.0131388602144985 -0.108768736241557 0.130894493125649 0.985411585930363 -0.00515504182822218 9.45984159307449e-05 6.52032953101189e-05 -1.93694498653783e-05 5.91842483546568e-06 1.14204500062488e-05 6.21966178426854e-05 6.52032953101189e-05 8.93022947941157e-05 -2.06156998149759e-05 1.18926733633083e-05 5.50303299629948e-06 2.74788698492883e-05 -1.93694498653783e-05 -2.06156998149759e-05 2.26961667153551e-05 -4.09501086497096e-06 -4.00055232517575e-06 -9.7247700595735e-06 5.91842483546568e-06 1.18926733633083e-05 -4.09501086497096e-06 2.56134332264715e-05 -1.05679378102901e-05 -9.72715954577752e-07 1.14204500062488e-05 5.50303299629948e-06 -4.00055232517575e-06 -1.05679378102901e-05 6.81601804177587e-05 5.52085825371999e-06 6.21966178426854e-05 2.74788698492883e-05 -9.7247700595735e-06 -9.72715954577752e-07 5.52085825371999e-06 0.000106185123315724 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1086 0 0 0 0 0 2142 +642 645 0.999603803936672 0.0106430060772765 0.0260568911609744 -0.00538623622390532 -0.0104916347242535 0.999927323677598 -0.00593910462693239 0.000406072141012755 -0.0261182073685896 0.00566337219294894 0.999642818940473 -0.00211189363689234 0.000134797859673828 9.9699204758968e-05 -1.29338844007748e-05 1.9816929998071e-05 -7.73794434179421e-06 3.92448931474772e-05 9.9699204758968e-05 0.000143346993019396 -7.27245382021593e-06 2.06366372644662e-05 1.01843198698443e-05 5.36682299113956e-06 -1.29338844007748e-05 -7.27245382021593e-06 2.11746277437464e-05 -5.98976873517655e-06 -2.28164019904631e-06 -5.9432890038452e-06 1.9816929998071e-05 2.06366372644662e-05 -5.98976873517655e-06 2.60292899119576e-05 -1.10175731310038e-05 1.46318803410069e-05 -7.73794434179421e-06 1.01843198698443e-05 -2.28164019904631e-06 -1.10175731310038e-05 6.36911785742672e-05 -2.2536682042369e-05 3.92448931474772e-05 5.36682299113956e-06 -5.9432890038452e-06 1.46318803410069e-05 -2.2536682042369e-05 9.8887600212988e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1496 0 0 0 0 0 1784 +642 669 0.994253617705748 0.0117599173104518 0.1064022933206 -0.0123544796962157 0.00202063398441064 0.991708980321774 -0.128488191626498 0.0145392790064416 -0.107031120321767 0.127964849447018 0.985986478907632 -0.00962396996557557 8.75903750181646e-05 5.99949488361516e-05 -1.7803807591488e-05 1.44004998599562e-06 1.61134388635276e-05 6.08132021900261e-05 5.99949488361516e-05 0.000105194876525124 -2.31573093580397e-05 9.10518588555545e-06 1.38201873434421e-05 2.11706346899221e-05 -1.7803807591488e-05 -2.31573093580397e-05 2.18233690863373e-05 -4.53472690266806e-06 -1.47421456529503e-06 -6.55789790859754e-06 1.44004998599562e-06 9.10518588555545e-06 -4.53472690266806e-06 3.06385691817352e-05 -2.13171180426207e-05 1.06344224508147e-06 1.61134388635276e-05 1.38201873434421e-05 -1.47421456529503e-06 -2.13171180426207e-05 8.4394180876312e-05 2.25838158467974e-06 6.08132021900261e-05 2.11706346899221e-05 -6.55789790859754e-06 1.06344224508147e-06 2.25838158467974e-06 0.00010334541066376 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1067 0 0 0 0 0 2184 +642 674 0.99702071215868 0.0119555021671538 0.0762021357609393 -0.0121843567741088 -0.00254881921845542 0.992482021897013 -0.122363964188028 0.00296318267366551 -0.0770921724119192 0.121805181249192 0.989555604690137 -0.0143876240707209 0.000224822602067656 9.99416792924447e-05 -3.76295428143489e-05 2.59186429061544e-05 8.2500300619348e-06 0.000166705284736953 9.99416792924447e-05 0.000201943373580894 -2.11298326766267e-05 2.20246915644575e-05 4.10219677635441e-05 3.35914202031293e-05 -3.76295428143489e-05 -2.11298326766267e-05 2.14713995515285e-05 -7.59509021632394e-06 -3.06135430422987e-06 -2.32698537276164e-05 2.59186429061544e-05 2.20246915644575e-05 -7.59509021632394e-06 3.2866998688012e-05 -1.48760815278782e-05 2.31443468420445e-05 8.2500300619348e-06 4.10219677635441e-05 -3.06135430422987e-06 -1.48760815278782e-05 9.64936224827466e-05 -2.68048473010927e-05 0.000166705284736953 3.35914202031293e-05 -2.32698537276164e-05 2.31443468420445e-05 -2.68048473010927e-05 0.000210169182996977 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 972 0 0 0 0 0 2148 +642 644 0.999704904890088 0.0115469752335588 0.0213721899125057 -0.00739103095293774 -0.0115063802296939 0.999931756180747 -0.00202143397047781 0.0043402757190005 -0.0213940728406336 0.0017749209117236 0.999769545096792 0.00724614453896719 0.000142995252105785 8.63116752592346e-05 -8.78021982567182e-06 1.18478262792474e-05 -9.24634371298091e-06 4.47384601311615e-05 8.63116752592346e-05 0.000112374460375365 -7.91478467776336e-06 1.53747783964671e-05 6.65099853061309e-06 1.34511441494444e-06 -8.78021982567182e-06 -7.91478467776336e-06 2.05462958589643e-05 -3.43113798012673e-06 2.38063846800865e-06 -1.26414407771547e-05 1.18478262792474e-05 1.53747783964671e-05 -3.43113798012673e-06 1.96094031513912e-05 -2.08220101279948e-06 4.42748326107384e-06 -9.24634371298091e-06 6.65099853061309e-06 2.38063846800865e-06 -2.08220101279948e-06 4.70951294875583e-05 -1.90018574941116e-05 4.47384601311615e-05 1.34511441494444e-06 -1.26414407771547e-05 4.42748326107384e-06 -1.90018574941116e-05 0.000113405957361003 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1457 0 0 0 0 0 1787 +642 676 0.995680511341366 0.0103241644023427 0.0922698811334925 -0.0129210274686767 0.000638333977615004 0.993013689569208 -0.117997478184413 0.00634630370282265 -0.0928434804643194 0.117546688415886 0.988717787934318 -0.0148905855427826 0.000292378497747957 0.000199562038047766 -3.22979111346461e-05 1.75978441211217e-05 2.71920126318835e-05 0.000246352424934696 0.000199562038047766 0.000209364729681018 -2.56448774296502e-05 1.73840854743692e-05 3.80730508437899e-05 0.000152685004367914 -3.22979111346461e-05 -2.56448774296502e-05 2.06277325351358e-05 -3.12421542609508e-06 -6.51597912729926e-06 -2.55241984773617e-05 1.75978441211217e-05 1.73840854743692e-05 -3.12421542609508e-06 3.10165136359704e-05 -2.21838531311812e-05 2.12323969031922e-05 2.71920126318835e-05 3.80730508437899e-05 -6.51597912729926e-06 -2.21838531311812e-05 0.000101363262619097 3.55297080545759e-06 0.000246352424934696 0.000152685004367914 -2.55241984773617e-05 2.12323969031922e-05 3.55297080545759e-06 0.000269241597406514 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1024 0 0 0 0 0 2154 +642 675 0.99638968580755 0.0126269933805262 0.0839532789979074 -0.0106353041038926 -0.00129260143194391 0.991019232400137 -0.13371316387918 0.00332561772603361 -0.0848877093451724 0.133121899217261 0.987457663270137 -0.00319693341331307 0.000241435161700304 0.000116424692072411 -3.12900382926693e-05 -1.19499251528731e-06 5.67664544766462e-05 0.000189742257923481 0.000116424692072411 0.000148249199057332 -2.30550462191232e-05 1.78586346422671e-05 2.63221459413444e-05 7.5631716688946e-05 -3.12900382926693e-05 -2.30550462191232e-05 2.34664092254524e-05 -3.77016658811402e-06 -6.83273279225523e-06 -1.83502608875926e-05 -1.19499251528731e-06 1.78586346422671e-05 -3.77016658811402e-06 3.82945434603395e-05 -3.50747721497649e-05 -8.5784614357856e-06 5.67664544766462e-05 2.63221459413444e-05 -6.83273279225523e-06 -3.50747721497649e-05 0.000144560731183082 3.64630525663272e-05 0.000189742257923481 7.5631716688946e-05 -1.83502608875926e-05 -8.5784614357856e-06 3.64630525663272e-05 0.000222877694404171 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 980 0 0 0 0 0 2127 +642 673 0.997219791013436 0.0108296592438663 0.0737252120497462 -0.0130199631599621 -0.00196211610123145 0.992855966782365 -0.119302889005507 0.00148514192245907 -0.0744905263206241 0.118826544615741 0.990116868749927 -0.0200412566974537 0.000151031800752676 0.000116671928323621 -2.26815484078215e-05 2.23704984933649e-05 8.82376089315466e-06 9.93177055962476e-05 0.000116671928323621 0.000157883082355377 -1.72624510728288e-05 2.08119964702653e-05 1.10798287754118e-05 8.17193288556047e-05 -2.26815484078215e-05 -1.72624510728288e-05 1.80613988367373e-05 -5.45494343803008e-06 1.42529657186056e-06 -1.00638990916182e-05 2.23704984933649e-05 2.08119964702653e-05 -5.45494343803008e-06 3.53576891579985e-05 -2.38677608802279e-05 9.89717265869072e-06 8.82376089315466e-06 1.10798287754118e-05 1.42529657186056e-06 -2.38677608802279e-05 9.20949365728289e-05 9.82035491875e-06 9.93177055962476e-05 8.17193288556047e-05 -1.00638990916182e-05 9.89717265869072e-06 9.82035491875e-06 0.000133701720822348 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1027 0 0 1 0 0 2154 +642 678 0.993812859906052 0.0119772382044472 0.11041985894914 -0.00574838753887129 0.00276362054571288 0.991194087852153 -0.13238822684974 -0.00101136845428567 -0.1110331567003 0.131874280934278 0.985028330628736 -0.00542291357101978 0.000225660288116326 0.000117441295210704 -4.02688531946134e-05 -6.80768208763148e-06 6.89609784580435e-05 0.000193345575969812 0.000117441295210704 0.000144307212406354 -2.77026660098696e-05 1.38991963655029e-05 2.93236309652495e-05 7.20421789787331e-05 -4.02688531946134e-05 -2.77026660098696e-05 2.54757694282584e-05 -5.01760667159713e-06 -1.4152963645574e-05 -2.52761072934635e-05 -6.80768208763148e-06 1.38991963655029e-05 -5.01760667159713e-06 3.35871369649471e-05 -2.13345001219978e-05 -2.25863862141696e-05 6.89609784580435e-05 2.93236309652495e-05 -1.4152963645574e-05 -2.13345001219978e-05 9.57360534640917e-05 7.39960380407416e-05 0.000193345575969812 7.20421789787331e-05 -2.52761072934635e-05 -2.25863862141696e-05 7.39960380407416e-05 0.000230008641053414 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1067 0 0 0 0 0 2109 +642 668 0.994998183653055 0.0109222058876906 0.0992941083129732 -0.0104099383362021 0.00186552590201367 0.991799443737637 -0.127790387802929 0.00799233577118921 -0.0998755943172829 0.127336439483209 0.986818269409068 -0.00998267827167191 0.000205481426543738 0.00011634923273438 -2.55731799817765e-05 1.10238930257382e-05 2.10904043244971e-05 0.000170615626872216 0.00011634923273438 0.000146370614925101 -1.81400175944649e-05 2.82723399430253e-05 -1.25705926584877e-05 7.75732265905157e-05 -2.55731799817765e-05 -1.81400175944649e-05 2.00109817457094e-05 -3.0300652499142e-06 -2.02945935439173e-06 -1.74428246103029e-05 1.10238930257382e-05 2.82723399430253e-05 -3.0300652499142e-06 4.28672951826789e-05 -4.37272743750465e-05 4.56145249181085e-06 2.10904043244971e-05 -1.25705926584877e-05 -2.02945935439173e-06 -4.37272743750465e-05 0.000121977885626748 7.32598282262898e-06 0.000170615626872216 7.75732265905157e-05 -1.74428246103029e-05 4.56145249181085e-06 7.32598282262898e-06 0.000199415830617165 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1028 0 0 0 0 0 2126 +642 646 0.999368442984145 0.0109864758854354 0.0337936756666656 -0.00806683677217839 -0.0104900866974431 0.999834982933928 -0.0148312164906143 0.00975182403195522 -0.0339510419357811 0.0144673511442174 0.999318779220297 0.00645221618797441 0.000213296537933748 0.000123703358881495 -1.1251716414454e-05 3.59941435103983e-05 -5.39537163713505e-05 9.36980403027649e-05 0.000123703358881495 0.000156988685553695 -1.00022995630637e-05 3.3087213428711e-05 -2.06207880172229e-05 1.57163125419761e-05 -1.1251716414454e-05 -1.00022995630637e-05 1.80102252304591e-05 -5.63334928167066e-06 3.31677980973538e-07 -9.74480953257399e-06 3.59941435103983e-05 3.3087213428711e-05 -5.63334928167066e-06 2.78263714170491e-05 -1.39971794633048e-05 1.90863592547193e-05 -5.39537163713505e-05 -2.06207880172229e-05 3.31677980973538e-07 -1.39971794633048e-05 6.49669309786608e-05 -4.21428699422931e-05 9.36980403027649e-05 1.57163125419761e-05 -9.74480953257399e-06 1.90863592547193e-05 -4.21428699422931e-05 0.000131765865674606 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1467 0 0 0 0 0 1875 +643 670 0.996280832476419 0.000248078979823229 0.0861651977129585 -0.00940116260743869 0.0118900779566699 0.990033554652073 -0.140328852019694 0.0168846669118769 -0.0853412496175077 0.1408314564286 0.986348504329946 -0.00379479606382291 0.000151019757007074 0.000111172784658651 -3.66773419675461e-05 6.28711905868393e-06 3.49798052180707e-05 0.000104419812722893 0.000111172784658651 0.000123817455911159 -3.09215187777536e-05 8.87780840468526e-06 2.76495561437426e-05 6.49524114729255e-05 -3.66773419675461e-05 -3.09215187777536e-05 2.61392934529041e-05 -3.74422890319801e-06 -8.3512958102471e-06 -2.25410555375432e-05 6.28711905868393e-06 8.87780840468526e-06 -3.74422890319801e-06 2.51914990959663e-05 -9.22330847784102e-06 -3.23400932589668e-06 3.49798052180707e-05 2.76495561437426e-05 -8.3512958102471e-06 -9.22330847784102e-06 6.84424509612557e-05 3.00513781448862e-05 0.000104419812722893 6.49524114729255e-05 -2.25410555375432e-05 -3.23400932589668e-06 3.00513781448862e-05 0.000129737168277321 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1075 0 0 0 0 0 2051 +643 669 0.996365289786108 -1.1130431469214e-05 0.0851833856192535 -0.0119513833723163 0.0121237467502048 0.989838465649135 -0.141678603487273 0.0217225675293954 -0.0843162147761737 0.14219638461466 0.986240824610469 -0.00247309966050797 0.000110203510052715 0.000101683621255141 -2.83751501361644e-05 9.4166788517595e-06 2.45121983216447e-05 5.28907359955666e-05 0.000101683621255141 0.000143652805299413 -2.86211605444177e-05 1.09914565775681e-05 3.49160465986327e-05 3.60738359741902e-05 -2.83751501361644e-05 -2.86211605444177e-05 2.3343313557016e-05 -4.8071716189677e-06 -4.10388336465241e-06 -9.16830832399514e-06 9.4166788517595e-06 1.09914565775681e-05 -4.8071716189677e-06 2.38806071121288e-05 -6.03299845552616e-06 5.74139427564368e-06 2.45121983216447e-05 3.49160465986327e-05 -4.10388336465241e-06 -6.03299845552616e-06 6.49078953842877e-05 9.06790441895576e-06 5.28907359955666e-05 3.60738359741902e-05 -9.16830832399514e-06 5.74139427564368e-06 9.06790441895576e-06 7.54178651465624e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1066 0 0 0 0 0 2132 +643 671 0.996634476551553 0.00069241195940014 0.0819709748294498 -0.0106547915271861 0.011118242170599 0.989582222065532 -0.143538881362785 0.0153630434341378 -0.0812164074546992 0.143967171040909 0.986244061489158 0.000497630497820088 0.000209011005584369 0.000115210418065736 -3.87415962692655e-05 -9.95673700407229e-06 6.73789647381476e-05 0.000168153530545984 0.000115210418065736 0.000134175664441409 -2.91822078610813e-05 2.02980680795479e-06 3.79017807064072e-05 6.96004607569938e-05 -3.87415962692655e-05 -2.91822078610813e-05 2.3168543569013e-05 -2.17268740722915e-06 -1.19688790103745e-05 -2.49033721253015e-05 -9.95673700407229e-06 2.02980680795479e-06 -2.17268740722915e-06 2.66157545412702e-05 -1.39475719871249e-05 -1.63060538226898e-05 6.73789647381476e-05 3.79017807064072e-05 -1.19688790103745e-05 -1.39475719871249e-05 8.97271745957895e-05 6.37642955644656e-05 0.000168153530545984 6.96004607569938e-05 -2.49033721253015e-05 -1.63060538226898e-05 6.37642955644656e-05 0.000204500113880873 0 0 0 0 0 0 8 0 0 0 0 0 0 0 0 0 0 0 971 0 0 0 0 0 2097 +643 647 0.999784269000198 0.000634543724122407 0.0207608481040864 -0.00453325204744825 0.000114124441518862 0.999350323712488 -0.0360404976568935 0.00493884580626552 -0.020770229544967 0.0360350919244959 0.999134660451054 -0.00386121086458895 0.000154569230997024 0.000122332362930737 -1.46492905104455e-05 1.55320544920562e-05 -4.23731423972921e-06 7.03367178134014e-05 0.000122332362930737 0.000147795891312447 -1.77125944477658e-05 1.41151679706819e-05 8.63891363505917e-06 4.15031263637858e-05 -1.46492905104455e-05 -1.77125944477658e-05 1.90878081749886e-05 -2.97112817176923e-06 -5.55361323913071e-06 -3.83246161808167e-06 1.55320544920562e-05 1.41151679706819e-05 -2.97112817176923e-06 2.24944697592856e-05 -8.66093058464168e-06 1.33584761511592e-05 -4.23731423972921e-06 8.63891363505917e-06 -5.55361323913071e-06 -8.66093058464168e-06 5.41996374294194e-05 -1.443723083737e-05 7.03367178134014e-05 4.15031263637858e-05 -3.83246161808167e-06 1.33584761511592e-05 -1.443723083737e-05 0.000100297481954507 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1424 0 0 0 0 0 1862 +643 674 0.998377389538183 -0.000126723807083744 0.0569435861181972 -0.00902705659019372 0.00786724470338335 0.990714677873942 -0.135729633853147 0.000548080926370644 -0.0563976464021408 0.135957386655558 0.989108130840147 -0.0116771326707114 0.000191829377324926 0.000106050074081767 -1.28575321490173e-05 1.22510359072402e-06 3.84806188452534e-05 0.000142129986469971 0.000106050074081767 0.000140547441132147 -9.38221511256872e-06 8.86549389393597e-06 2.78387245123854e-05 6.4523009463732e-05 -1.28575321490173e-05 -9.38221511256872e-06 1.99946296817846e-05 -6.58695998468748e-06 5.72405125492015e-07 -2.95089522807811e-07 1.22510359072402e-06 8.86549389393597e-06 -6.58695998468748e-06 3.14614351308617e-05 -9.31093119484399e-06 -6.3203893585436e-06 3.84806188452534e-05 2.78387245123854e-05 5.72405125492015e-07 -9.31093119484399e-06 7.18502757899117e-05 2.67158216492649e-05 0.000142129986469971 6.4523009463732e-05 -2.95089522807811e-07 -6.3203893585436e-06 2.67158216492649e-05 0.000174521757122466 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 965 0 0 0 0 0 2118 +643 672 0.997495669920931 -0.00041106966095724 0.0707263706882174 -0.0110005717527498 0.00966734654604642 0.991390351333354 -0.130582210480172 0.013441366216225 -0.0700637631001358 0.130938925858063 0.988911556609278 -0.0169946733058949 0.000102628134355598 6.80804078610788e-05 -2.1994923178913e-05 1.20291760722633e-05 2.55604277342217e-05 4.96296399235947e-05 6.80804078610788e-05 9.41818744445274e-05 -1.48106164139377e-05 8.92526105838024e-06 2.66781669119944e-05 2.32078030051864e-05 -2.1994923178913e-05 -1.48106164139377e-05 2.40451859862751e-05 -6.10862952542246e-06 -2.55550646828968e-06 -5.6068471108295e-06 1.20291760722633e-05 8.92526105838024e-06 -6.10862952542246e-06 3.42895464144796e-05 -2.17732245356792e-05 3.56544346073371e-06 2.55604277342217e-05 2.66781669119944e-05 -2.55550646828968e-06 -2.17732245356792e-05 0.000102041763802963 6.86586260829708e-06 4.96296399235947e-05 2.32078030051864e-05 -5.6068471108295e-06 3.56544346073371e-06 6.86586260829708e-06 7.28449069449638e-05 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 1069 0 0 0 0 0 2116 +643 646 0.999975669472076 0.00178599872638754 0.00674319452647915 -0.00662911962287596 -0.00164020768394229 0.999766114916588 -0.0215644425697646 0.0121096792498327 -0.00678013146082972 0.0215528576560158 0.999744719488047 0.0139524665698129 0.000270225043132757 0.000104075069078825 -8.20776191535314e-06 2.04030587772736e-05 -4.43181207028368e-05 0.000146758550144745 0.000104075069078825 0.00027463325933546 6.05312412319235e-06 6.69943257235937e-05 -5.46639334024827e-05 -0.000224350654002118 -8.20776191535314e-06 6.05312412319235e-06 1.89614618691219e-05 -9.88755845152637e-07 -5.78972540179268e-06 -3.31617788250087e-05 2.04030587772736e-05 6.69943257235937e-05 -9.88755845152637e-07 3.77417560248575e-05 -2.64030304605167e-05 -6.43280324165739e-05 -4.43181207028368e-05 -5.46639334024827e-05 -5.78972540179268e-06 -2.64030304605167e-05 8.32992523335104e-05 5.44418024743585e-05 0.000146758550144745 -0.000224350654002118 -3.31617788250087e-05 -6.43280324165739e-05 5.44418024743585e-05 0.00162289300752536 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1463 0 0 0 0 0 1924 +643 645 0.999963433924672 0.00117185102419017 0.00847098452094884 -0.000646890716121925 -0.00105334462370919 0.99990171133329 -0.0139806343869729 -0.00158232447125981 -0.00848653513989975 0.0139712003040401 0.999866383214969 -0.00542877125408905 0.000134871961103267 0.000105537017834886 -6.5561773190252e-06 1.38371113656908e-05 1.47725739094545e-05 1.35615933424807e-05 0.000105537017834886 0.000147482075449834 -9.95253511008507e-06 1.83884243017049e-05 1.4485415449216e-05 -7.6209728913634e-06 -6.5561773190252e-06 -9.95253511008507e-06 1.74366929991703e-05 -3.94634063382683e-06 -4.59454857758996e-06 -3.06329787755983e-06 1.38371113656908e-05 1.83884243017049e-05 -3.94634063382683e-06 2.33376930251473e-05 -2.52981929712275e-06 1.26014721869265e-06 1.47725739094545e-05 1.4485415449216e-05 -4.59454857758996e-06 -2.52981929712275e-06 5.33015128078235e-05 -1.41614940544772e-05 1.35615933424807e-05 -7.6209728913634e-06 -3.06329787755983e-06 1.26014721869265e-06 -1.41614940544772e-05 8.78756346597745e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1494 0 0 0 0 0 1767 +643 673 0.998287819365971 -0.000871290161576181 0.0584864989462422 -0.00839962451960549 0.00819990947051178 0.992099895610074 -0.12518210181634 0.00110315509156705 -0.0579153795654476 0.12544735144249 0.990408385882235 -0.0235770823901675 0.000171067974766581 0.000128030457018196 -2.69481207757357e-05 2.63385255903345e-05 1.01094615034735e-05 0.000103130284497403 0.000128030457018196 0.000167920149413683 -2.02398963529467e-05 2.25277465129565e-05 1.91241272186996e-05 8.37905656719881e-05 -2.69481207757357e-05 -2.02398963529467e-05 2.2030883820227e-05 -7.41028366043462e-06 -7.78501664417705e-06 -1.03457153176989e-05 2.63385255903345e-05 2.25277465129565e-05 -7.41028366043462e-06 3.58197076594873e-05 -1.84552884019793e-05 1.742931110824e-05 1.01094615034735e-05 1.91241272186996e-05 -7.78501664417705e-06 -1.84552884019793e-05 0.000102490571807076 -1.03301219974078e-05 0.000103130284497403 8.37905656719881e-05 -1.03457153176989e-05 1.742931110824e-05 -1.03301219974078e-05 0.000132564775335371 0 0 0 0 0 0 10 0 0 0 0 0 0 0 0 0 0 0 1016 0 0 0 0 0 2167 +643 675 0.997127044367343 -0.000329165767415025 0.075746610756809 -0.00764370067409708 0.0104664761572968 0.990997043711286 -0.133474013322221 0.00529070753891929 -0.075020732255122 0.133883348499316 0.988153398378266 -0.0146270413647425 0.000213265996746011 8.03634278662826e-05 -2.75362985591167e-05 6.02781312132926e-06 1.92882774127746e-05 0.000174108939151091 8.03634278662826e-05 0.000122487456008321 -1.22486899787581e-05 1.38745181671308e-06 4.81950025435895e-05 4.28574391109295e-05 -2.75362985591167e-05 -1.22486899787581e-05 2.21660861902408e-05 -5.24839033135232e-06 -1.00247997562247e-06 -1.62171195133065e-05 6.02781312132926e-06 1.38745181671308e-06 -5.24839033135232e-06 2.47634135300287e-05 -1.02313876111234e-05 4.23897373135993e-06 1.92882774127746e-05 4.81950025435895e-05 -1.00247997562247e-06 -1.02313876111234e-05 8.20402944051385e-05 1.73864512195153e-06 0.000174108939151091 4.28574391109295e-05 -1.62171195133065e-05 4.23897373135993e-06 1.73864512195153e-06 0.000199169080366864 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 971 0 0 0 0 0 2100 +644 646 0.999845768092328 -0.00110107567898962 0.0175279108912302 0.00170957211976038 0.00135959188754968 0.999890380598122 -0.0147437545164746 0.00168363484059328 -0.017509755502607 0.0147653113645427 0.999737662610821 0.00259164023320814 0.000108965317483079 7.1242809133947e-05 -5.61103524955368e-06 4.73555081502332e-06 -2.32645668328437e-06 1.07604598529518e-05 7.1242809133947e-05 9.421481251529e-05 -3.0781118468316e-06 4.46551447639598e-06 1.14117568643485e-05 -1.76494606915493e-05 -5.61103524955368e-06 -3.0781118468316e-06 1.92948366733934e-05 -4.84978216871483e-06 -1.57829312806785e-06 -3.69896426399777e-06 4.73555081502332e-06 4.46551447639598e-06 -4.84978216871483e-06 1.97467544227092e-05 -2.09377398125023e-06 2.64798820262902e-06 -2.32645668328437e-06 1.14117568643485e-05 -1.57829312806785e-06 -2.09377398125023e-06 5.06591194663418e-05 -1.61800357796206e-05 1.07604598529518e-05 -1.76494606915493e-05 -3.69896426399777e-06 2.64798820262902e-06 -1.61800357796206e-05 7.66269063926894e-05 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 1555 0 0 0 0 0 1940 +644 673 0.998976048230275 -0.00161421156630459 0.0452133761539936 -0.0107117566455722 0.00769017592348601 0.990878905671801 -0.134535703398467 0.0118350884626743 -0.0445838115966899 0.1347456441436 0.989876707033678 0.0013658033303712 0.000118217261958155 8.69115785228761e-05 -3.00187614952376e-05 2.15104812864149e-05 8.49973694497731e-06 5.26782371107379e-05 8.69115785228761e-05 0.000211711048056146 -2.43834520612296e-05 2.73502197025938e-05 1.36685161024776e-05 1.66249639778484e-05 -3.00187614952376e-05 -2.43834520612296e-05 2.685325089895e-05 -1.12887456323436e-05 -3.42909057002985e-06 -1.15870200477152e-05 2.15104812864149e-05 2.73502197025938e-05 -1.12887456323436e-05 3.55099431629507e-05 -8.70694549275857e-06 9.57852928167079e-06 8.49973694497731e-06 1.36685161024776e-05 -3.42909057002985e-06 -8.70694549275857e-06 6.38501214730823e-05 -5.66440521537416e-06 5.26782371107379e-05 1.66249639778484e-05 -1.15870200477152e-05 9.57852928167079e-06 -5.66440521537416e-06 9.16714935425349e-05 0 0 0 0 0 0 10 0 0 0 0 0 0 0 0 0 0 0 1051 0 0 0 0 0 2067 +644 671 0.996759681583757 -0.00142896376154514 0.0804244691099338 -0.0127623796850571 0.0127325341616867 0.990039510312549 -0.140212875991864 0.0261482160637946 -0.0794230428960511 0.140782548927971 0.986849661384385 0.00847898143572535 7.63611703329707e-05 5.81820850216094e-05 -2.15140700926845e-05 7.58268319771883e-06 2.34211734879833e-05 3.89279835921025e-05 5.81820850216094e-05 0.000148794469805331 -1.62408896772463e-05 8.15256612373107e-06 3.66108825028068e-05 5.82913117067647e-06 -2.15140700926845e-05 -1.62408896772463e-05 2.2905965786421e-05 -5.94836098208621e-06 -8.1188149136368e-06 -6.15609255286355e-06 7.58268319771883e-06 8.15256612373107e-06 -5.94836098208621e-06 2.31697679130554e-05 -3.49129517657668e-06 -3.54186464220608e-07 2.34211734879833e-05 3.66108825028068e-05 -8.1188149136368e-06 -3.49129517657668e-06 7.09811949523907e-05 2.67757155713417e-06 3.89279835921025e-05 5.82913117067647e-06 -6.15609255286355e-06 -3.54186464220608e-07 2.67757155713417e-06 8.20955247648881e-05 0 0 0 0 0 0 8 0 0 0 0 0 0 0 0 0 0 0 1030 0 0 0 0 0 2052 +644 674 0.998779234876124 -0.00181300013153363 0.0493634785118237 -0.0110887489970046 0.00829609246727244 0.991288275875755 -0.131448579151877 0.00943213725943302 -0.0486951212139234 0.131697635293106 0.990093186537593 -0.00219815713109683 0.000254973062200334 0.000107871978965304 -3.11224516437287e-05 3.92144613439214e-06 6.41875392350814e-05 0.000151099432773344 0.000107871978965304 0.000140249325070054 -1.18838805221283e-05 8.75108882436441e-06 4.18210327065502e-05 4.69424439593195e-05 -3.11224516437287e-05 -1.18838805221283e-05 2.7287129581861e-05 -9.78979037110368e-06 -8.53574827873915e-06 -6.88754620781903e-06 3.92144613439214e-06 8.75108882436441e-06 -9.78979037110368e-06 3.06033725935061e-05 -3.49073772923016e-06 -5.46606790459402e-06 6.41875392350814e-05 4.18210327065502e-05 -8.53574827873915e-06 -3.49073772923016e-06 7.7332988714084e-05 2.4131454713739e-05 0.000151099432773344 4.69424439593195e-05 -6.88754620781903e-06 -5.46606790459402e-06 2.4131454713739e-05 0.000175714930016988 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 982 0 0 0 0 0 2023 +644 647 0.999805114996535 -0.0012251028648496 0.019703582154927 -0.00333935908779579 0.0017735157242737 0.99961082404647 -0.02783981126216 0.0133111452947988 -0.0196618073620197 0.027869330313222 0.999418187626757 -0.00234446542974018 9.92161099383097e-05 9.48532771670316e-05 -6.38156886651598e-06 7.02869101717203e-06 2.85441506658237e-06 1.3326626616837e-05 9.48532771670316e-05 0.000143394232261816 -4.21092287376256e-06 1.3021848347578e-05 5.29439586558555e-06 -6.30379550765644e-06 -6.38156886651598e-06 -4.21092287376256e-06 1.82440621011712e-05 -3.76721476663284e-06 -4.40247407851241e-06 -8.33893302479062e-07 7.02869101717203e-06 1.3021848347578e-05 -3.76721476663284e-06 2.22553521197596e-05 6.21176642580483e-07 1.53721776928955e-06 2.85441506658237e-06 5.29439586558555e-06 -4.40247407851241e-06 6.21176642580483e-07 4.18245680810592e-05 -9.18107698450658e-06 1.3326626616837e-05 -6.30379550765644e-06 -8.33893302479062e-07 1.53721776928955e-06 -9.18107698450658e-06 8.13343476003354e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1496 0 0 0 0 0 1865 +644 670 0.996887281060641 -0.00191245172721914 0.0788168217318682 -0.0113510308569425 0.0128134208026579 0.990344338143186 -0.138035894444408 0.0226176434289065 -0.0777918061678481 0.138616140604638 0.987286179614107 0.00516396757502593 9.79556658831861e-05 4.44482610563914e-05 -2.28020351506219e-05 1.02493203960365e-06 2.27989130151061e-05 6.63382471746602e-05 4.44482610563914e-05 0.000100337369115379 -1.37205414944356e-05 5.96540769024573e-06 1.80541449831403e-05 4.68272518978829e-06 -2.28020351506219e-05 -1.37205414944356e-05 2.27435499793772e-05 -5.78491764539942e-06 -4.09055132113428e-06 -1.42382556484653e-05 1.02493203960365e-06 5.96540769024573e-06 -5.78491764539942e-06 2.61944332959141e-05 -8.61897056530923e-06 -2.98363870354442e-06 2.27989130151061e-05 1.80541449831403e-05 -4.09055132113428e-06 -8.61897056530923e-06 6.97492094883335e-05 7.0067243824881e-06 6.63382471746602e-05 4.68272518978829e-06 -1.42382556484653e-05 -2.98363870354442e-06 7.0067243824881e-06 9.95049661489285e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1127 0 0 0 0 0 2006 +644 675 0.998300512111818 -0.00115872034999114 0.0582644392784465 -0.00936012673509895 0.00924453284048735 0.990291117733671 -0.138701264415138 0.00805470283661052 -0.0575380407195311 0.139004170818531 0.988618841801637 0.00403793188836843 0.000219066340680028 0.000132607987183953 -3.74276072069674e-05 1.43474246129333e-05 3.33840608420374e-05 0.000156923076420904 0.000132607987183953 0.000191981317702902 -2.38400556110438e-05 1.59833710430789e-05 2.97931087836218e-05 7.11543267230534e-05 -3.74276072069674e-05 -2.38400556110438e-05 2.75401940448419e-05 -1.07181143365016e-05 -4.86608018914236e-06 -1.74105344594834e-05 1.43474246129333e-05 1.59833710430789e-05 -1.07181143365016e-05 3.74179407705e-05 -1.63377632656767e-05 4.77087630877417e-06 3.33840608420374e-05 2.97931087836218e-05 -4.86608018914236e-06 -1.63377632656767e-05 8.55451080985583e-05 1.7316105970722e-05 0.000156923076420904 7.11543267230534e-05 -1.74105344594834e-05 4.77087630877417e-06 1.7316105970722e-05 0.000166703117146116 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1022 0 0 0 0 0 2079 +644 672 0.998217673367949 -0.000825886865026412 0.0596723930035012 -0.00811015590040309 0.00912561656155429 0.990257274873664 -0.138950540416927 0.0132573828172535 -0.0589762638546188 0.139247432546064 0.988499849686928 0.00316499832644497 6.19522530059592e-05 3.50764966954894e-05 -2.0348188502848e-05 1.41856404625472e-05 9.4940147083339e-06 1.37320817992121e-05 3.50764966954894e-05 0.000132894422875323 -1.54999789676156e-05 1.36711087730466e-05 2.2110109315596e-05 -1.20514934172569e-05 -2.0348188502848e-05 -1.54999789676156e-05 2.30051477290167e-05 -1.07191611881038e-05 -5.36538821879063e-06 -5.33687929799224e-06 1.41856404625472e-05 1.36711087730466e-05 -1.07191611881038e-05 3.09947163674622e-05 -1.02496841463203e-05 2.53357961464923e-06 9.4940147083339e-06 2.2110109315596e-05 -5.36538821879063e-06 -1.02496841463203e-05 7.64157385350421e-05 -6.13049741145221e-06 1.37320817992121e-05 -1.20514934172569e-05 -5.33687929799224e-06 2.53357961464923e-06 -6.13049741145221e-06 4.95857949527315e-05 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 1116 0 0 0 0 0 2037 +644 648 0.999564938813921 -0.000387762488341176 0.0294920791768895 -0.00671701114378443 0.00185485075846798 0.998760771893999 -0.0497340934809103 0.0173632704089849 -0.0294362467476255 0.0497671595126419 0.998326969089514 -0.00139076874885347 7.50028094253597e-05 5.38060910074689e-05 -7.4937405830092e-06 1.52063765712872e-06 2.81446844675629e-06 2.09753189149967e-05 5.38060910074689e-05 0.000108138056285794 -9.88632995878766e-06 3.04541849471349e-06 1.57028040227691e-05 -8.18330408090596e-07 -7.4937405830092e-06 -9.88632995878766e-06 2.22364396500883e-05 -4.11126971886459e-06 4.04376142236765e-07 -5.21947078847083e-06 1.52063765712872e-06 3.04541849471349e-06 -4.11126971886459e-06 2.2189202143688e-05 -1.11170645420861e-05 4.3095355415932e-06 2.81446844675629e-06 1.57028040227691e-05 4.04376142236765e-07 -1.11170645420861e-05 6.94180020792154e-05 -9.95432993831962e-06 2.09753189149967e-05 -8.18330408090596e-07 -5.21947078847083e-06 4.3095355415932e-06 -9.95432993831962e-06 7.6583072397426e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1428 0 0 0 0 0 1999 +645 671 0.996760899803785 -0.00231080326399572 0.0803888599908194 -0.00897631678409248 0.0125790146836499 0.991763726170834 -0.127461679893732 0.0162352536253699 -0.0794322164611877 0.128060031391604 0.988580371718984 -0.0017267902229281 9.20204239508612e-05 6.29900327086653e-05 -1.39130663575322e-05 -1.78536216878094e-07 2.45464534104942e-05 6.04538334711141e-05 6.29900327086653e-05 8.29107452625823e-05 -1.25364343416754e-05 -8.4525740862259e-07 2.91501286845653e-05 2.80403833012288e-05 -1.39130663575322e-05 -1.25364343416754e-05 2.05876816497677e-05 -4.30282711071995e-06 -6.46871223147922e-07 -5.49694394963757e-06 -1.78536216878094e-07 -8.4525740862259e-07 -4.30282711071995e-06 2.46408472509523e-05 -9.76292006088506e-06 -7.74191774502922e-07 2.45464534104942e-05 2.91501286845653e-05 -6.46871223147922e-07 -9.76292006088506e-06 6.54002267106779e-05 9.16679885219369e-06 6.04538334711141e-05 2.80403833012288e-05 -5.49694394963757e-06 -7.74191774502922e-07 9.16679885219369e-06 8.64276819492822e-05 0 0 0 0 0 0 8 0 0 0 0 0 0 0 0 0 0 0 996 0 0 0 0 0 2085 +645 672 0.998166370086667 -0.00203866433604373 0.0604957971741149 -0.00706034317884206 0.00965028299404731 0.992009014016984 -0.125797409143378 0.00962714827399215 -0.0597559174152778 0.126150544813634 0.990209710302359 -0.00319145731714724 0.000156440190018491 0.000101756000589243 -3.18199371954393e-05 2.46627162604068e-06 6.36551175849484e-05 6.73215831717877e-05 0.000101756000589243 0.000135200577772778 -2.45055266892242e-05 1.05131210334055e-05 4.11275692295267e-05 2.84880093808391e-05 -3.18199371954393e-05 -2.45055266892242e-05 2.37459774947668e-05 -6.11486532488801e-06 -1.40913890280564e-05 -9.46626980874445e-06 2.46627162604068e-06 1.05131210334055e-05 -6.11486532488801e-06 2.41911162529203e-05 3.11241893645665e-07 -5.29961372269753e-06 6.36551175849484e-05 4.11275692295267e-05 -1.40913890280564e-05 3.11241893645665e-07 7.0282532671638e-05 2.73576922540542e-05 6.73215831717877e-05 2.84880093808391e-05 -9.46626980874445e-06 -5.29961372269753e-06 2.73576922540542e-05 8.72294609648101e-05 0 0 0 0 0 0 8 0 0 0 0 0 0 0 0 0 0 0 1078 0 0 0 0 0 2078 +645 647 0.999865688787287 -0.000690727297795719 0.0163745925666737 -0.00294819132585702 0.00119327489378959 0.999527906446883 -0.0307008196786029 0.00785653355680207 -0.0163456563328713 0.0307162356044864 0.999394482869171 0.00177700228536705 0.000110850066057884 7.6652450707644e-05 -1.16076103734464e-05 5.33129597463696e-06 3.09053399704482e-06 1.1979019010373e-05 7.6652450707644e-05 0.000100654244754192 -1.11713321005642e-05 6.6884853295829e-06 7.98614562976537e-06 -5.27063894683751e-06 -1.16076103734464e-05 -1.11713321005642e-05 1.90962136037852e-05 -2.72889838027271e-06 -3.3565520982549e-06 -4.10636070696085e-06 5.33129597463696e-06 6.6884853295829e-06 -2.72889838027271e-06 1.6902356833785e-05 5.96580143910987e-07 5.72678506642834e-06 3.09053399704482e-06 7.98614562976537e-06 -3.3565520982549e-06 5.96580143910987e-07 3.99592109084175e-05 -1.60620811277562e-05 1.1979019010373e-05 -5.27063894683751e-06 -4.10636070696085e-06 5.72678506642834e-06 -1.60620811277562e-05 7.50485949106547e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1531 0 0 0 0 0 1886 +645 675 0.997718320591746 -0.00212471833163809 0.0674806515054238 -0.0046338309975303 0.0107496197529752 0.991753407567135 -0.12770913927414 0.00238429665670099 -0.0666528201260209 0.128143139305179 0.989513384153171 -0.00667838944361518 0.000108662607879393 7.66999038530543e-05 -1.78141996185431e-05 -9.61610619962272e-07 3.77970585788919e-05 7.2565405503936e-05 7.66999038530543e-05 0.000107732629092325 -1.67494969911669e-05 5.79406190772455e-06 2.73639576500197e-05 3.69825333698262e-05 -1.78141996185431e-05 -1.67494969911669e-05 2.16210510852557e-05 -3.32635801686295e-06 -4.91294432437586e-06 -4.06913744071531e-06 -9.61610619962272e-07 5.79406190772455e-06 -3.32635801686295e-06 2.50397335365506e-05 -5.37956228720086e-06 -2.41702682546363e-06 3.77970585788919e-05 2.73639576500197e-05 -4.91294432437586e-06 -5.37956228720086e-06 6.85964781640187e-05 3.00573955402081e-05 7.2565405503936e-05 3.69825333698262e-05 -4.06913744071531e-06 -2.41702682546363e-06 3.00573955402081e-05 0.000107766942060325 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 1009 0 0 0 0 0 2079 +645 674 0.998433406923655 -0.00258038485284006 0.0558934124278868 -0.00619005021286699 0.00954040390654616 0.992158969469594 -0.124617655227232 0.00242968265936367 -0.0551335889646463 0.12495567580164 0.99062927801112 -0.00662992223531666 8.33729964643034e-05 7.28094973136076e-05 -2.43696811885992e-05 9.76661297143489e-06 3.01236592176586e-05 4.94057473925339e-05 7.28094973136076e-05 0.000133526536732961 -1.96215079792016e-05 1.28234477636832e-05 4.08146382356996e-05 4.29218931631406e-05 -2.43696811885992e-05 -1.96215079792016e-05 2.25467420676703e-05 -6.48310753076444e-06 -1.08093274022932e-05 -9.83470237957327e-06 9.76661297143489e-06 1.28234477636832e-05 -6.48310753076444e-06 2.50628388418826e-05 1.69997486500015e-06 4.23732476188535e-06 3.01236592176586e-05 4.08146382356996e-05 -1.08093274022932e-05 1.69997486500015e-06 6.35883530146224e-05 1.78031295010422e-05 4.94057473925339e-05 4.29218931631406e-05 -9.83470237957327e-06 4.23732476188535e-06 1.78031295010422e-05 7.65842033901241e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 998 0 0 0 0 0 2077 +645 649 0.999544402335924 -0.000568843107326461 0.0301772128673292 -0.00466314125896411 0.00213793008610494 0.998645368371444 -0.0519890131201841 0.0141806668272045 -0.0301067602685473 0.0520298438185528 0.998191604021167 0.00202038273295475 0.000198265547750514 0.000155568085833244 -1.03152489063418e-05 1.55627155322606e-05 3.50900019284247e-06 5.39458766761656e-05 0.000155568085833244 0.000189743341974016 -7.97244903515989e-06 2.07293375083434e-05 1.69071414512042e-06 2.00541760102564e-05 -1.03152489063418e-05 -7.97244903515989e-06 1.83803958646969e-05 1.39177283427444e-07 -2.13589111058941e-06 -4.68006595512283e-06 1.55627155322606e-05 2.07293375083434e-05 1.39177283427444e-07 2.53273595504421e-05 -8.32885901926032e-06 2.04301425558062e-06 3.50900019284247e-06 1.69071414512042e-06 -2.13589111058941e-06 -8.32885901926032e-06 6.51414150805461e-05 6.16985034351454e-06 5.39458766761656e-05 2.00541760102564e-05 -4.68006595512283e-06 2.04301425558062e-06 6.16985034351454e-06 7.8254536974749e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1403 0 0 0 0 0 1976 +645 648 0.999696738985948 0.00061715504511565 0.0246180661407799 -0.00467283654692127 0.000517387731862991 0.99893887274657 -0.0460528047544086 0.011498280225807 -0.0246203649606671 0.0460515758195422 0.998635614222595 0.00361673650861366 9.58119446643172e-05 7.06418345885769e-05 -7.7692139509364e-06 2.48857565229575e-07 4.38990736837025e-06 -3.15085619881515e-05 7.06418345885769e-05 9.59597801868019e-05 -3.72961387338751e-06 2.17520906136482e-06 1.14203366915685e-05 -4.19774213848263e-05 -7.7692139509364e-06 -3.72961387338751e-06 2.93593654674621e-05 -6.43577931551451e-06 -8.52215173836154e-07 -8.97746249486771e-06 2.48857565229575e-07 2.17520906136482e-06 -6.43577931551451e-06 2.07577861706963e-05 -2.17781343769901e-06 9.27924088661649e-07 4.38990736837025e-06 1.14203366915685e-05 -8.52215173836154e-07 -2.17781343769901e-06 5.06881709623439e-05 -1.86747125122442e-06 -3.15085619881515e-05 -4.19774213848263e-05 -8.97746249486771e-06 9.27924088661649e-07 -1.86747125122442e-06 6.81076968861045e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1507 0 0 0 0 0 1932 +646 648 0.999817182623423 -0.00103876029095639 0.0190924673109245 -0.00320313125540149 0.00159547808275583 0.999573280188375 -0.0291669673284717 0.00527220944909612 -0.0190540226894017 0.0291920967131623 0.999392198142872 -0.00891949523119231 0.00018256689408268 0.000142426631933927 -8.73969627235791e-06 7.12939157002708e-06 1.66274483920679e-05 7.41588805814803e-05 0.000142426631933927 0.000170507159041345 -2.93046297843704e-06 1.12277875092857e-05 1.5707779191589e-05 1.9627624334387e-05 -8.73969627235791e-06 -2.93046297843704e-06 2.26124198472419e-05 -2.67231868353327e-06 -2.57472421639762e-06 -6.42092727485895e-06 7.12939157002708e-06 1.12277875092857e-05 -2.67231868353327e-06 2.34820527495609e-05 -2.52346574102532e-06 -8.41870309006624e-08 1.66274483920679e-05 1.5707779191589e-05 -2.57472421639762e-06 -2.52346574102532e-06 5.08233455133913e-05 9.15376290003356e-07 7.41588805814803e-05 1.9627624334387e-05 -6.42092727485895e-06 -8.41870309006624e-08 9.15376290003356e-07 0.000130521886167658 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1447 0 0 0 0 0 2028 +646 650 0.999652420890241 -0.000290071912520689 0.0263619662879461 -0.00595090288222808 0.00144664645256655 0.999036447626059 -0.0438643765343254 0.0132546047762678 -0.0263238413291548 0.0438872666383925 0.99868962305848 -0.00779630852923576 0.000131077582974676 8.04234311385406e-05 -9.07079938115348e-06 1.46285877658257e-05 -8.53005716457863e-07 6.36385540268036e-05 8.04234311385406e-05 9.26574043988851e-05 -8.24590207271014e-06 7.08755265720045e-06 8.47590602617368e-06 2.90392907967522e-05 -9.07079938115348e-06 -8.24590207271014e-06 1.79359860395373e-05 -6.98675794200765e-07 -1.03589497628818e-06 -3.00664328980064e-06 1.46285877658257e-05 7.08755265720045e-06 -6.98675794200765e-07 2.59385771309697e-05 -1.42985631168868e-05 7.01530965702601e-06 -8.53005716457863e-07 8.47590602617368e-06 -1.03589497628818e-06 -1.42985631168868e-05 7.09588823761458e-05 -2.657864725787e-06 6.36385540268036e-05 2.90392907967522e-05 -3.00664328980064e-06 7.01530965702601e-06 -2.657864725787e-06 0.000100366092328846 0 0 0 0 0 0 9 0 0 0 0 0 0 0 0 0 0 0 1471 0 0 0 0 0 2002 +646 649 0.99970675692552 -0.000458534033023455 0.0242113589870541 -4.97188699268206e-05 0.00143778723686494 0.99918076719002 -0.0404441249803297 0.00225284794609252 -0.0241729792396583 0.0404670758037146 0.998888423624268 -0.00466454576073045 8.80064869169091e-05 5.22199235510455e-05 -1.04279843796255e-05 2.92169216869897e-06 6.18267021743642e-06 4.28561795436982e-05 5.22199235510455e-05 9.25256925055401e-05 -7.04415230408639e-06 3.12259216503134e-06 1.41141455302171e-05 3.33698472485719e-06 -1.04279843796255e-05 -7.04415230408639e-06 2.03480735693838e-05 -2.74034321899798e-06 2.71814201692432e-07 -2.78996610214295e-06 2.92169216869897e-06 3.12259216503134e-06 -2.74034321899798e-06 2.28443393338711e-05 1.49434610964133e-06 -5.39944687553514e-06 6.18267021743642e-06 1.41141455302171e-05 2.71814201692432e-07 1.49434610964133e-06 4.18436697205867e-05 -4.64039296241611e-06 4.28561795436982e-05 3.33698472485719e-06 -2.78996610214295e-06 -5.39944687553514e-06 -4.64039296241611e-06 8.96200204633547e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1497 0 0 0 0 0 2088 +645 673 0.998873973010072 -0.00131077712424738 0.0474243387555808 -0.0101897509239642 0.00756804464550368 0.991220147488278 -0.132005090483511 0.01167697990407 -0.0468349308029509 0.132215358701804 0.990113926869043 0.00215788795321482 8.41361831631037e-05 6.43878057407856e-05 -1.72530410001718e-05 1.17251564379369e-05 9.14794983593012e-06 3.80709287458889e-05 6.43878057407856e-05 9.41524574650535e-05 -1.41004421181618e-05 1.07794635212009e-05 8.43041680284761e-06 2.71604662219392e-05 -1.72530410001718e-05 -1.41004421181618e-05 2.05602502231494e-05 -4.63238852705883e-06 -4.23567439682106e-06 -5.53751842692019e-06 1.17251564379369e-05 1.07794635212009e-05 -4.63238852705883e-06 2.49770320338368e-05 -2.28618222283967e-06 4.16542065523569e-06 9.14794983593012e-06 8.43041680284761e-06 -4.23567439682106e-06 -2.28618222283967e-06 5.30421816759384e-05 -4.58368778751678e-06 3.80709287458889e-05 2.71604662219392e-05 -5.53751842692019e-06 4.16542065523569e-06 -4.58368778751678e-06 7.34207835207691e-05 0 0 0 0 0 0 10 0 0 0 0 0 0 0 0 0 0 0 1056 0 0 0 0 0 2087 +646 673 0.999128763016358 -0.00215095795863217 0.0416783912029064 -0.00846385986796413 0.0070243012437624 0.993090915351532 -0.117137069445556 0.00674654458334874 -0.0411384747582987 0.117327776873665 0.992240806794623 -0.00543534723855999 0.000185956946650796 0.000140247295038408 -2.98542545985302e-05 2.12698388945293e-05 5.93718881978497e-05 0.000108218442738065 0.000140247295038408 0.000219485411082169 -2.03160360460434e-05 2.95824397464469e-05 3.08852091833815e-05 4.4128408396541e-05 -2.98542545985302e-05 -2.03160360460434e-05 2.31221784593856e-05 -7.36278854852103e-06 -7.53936968688839e-06 -9.25529204050134e-06 2.12698388945293e-05 2.95824397464469e-05 -7.36278854852103e-06 4.22019731536557e-05 -1.56297620503118e-05 -1.84854516149118e-06 5.93718881978497e-05 3.08852091833815e-05 -7.53936968688839e-06 -1.56297620503118e-05 0.000102627370365076 3.37589263520273e-05 0.000108218442738065 4.4128408396541e-05 -9.25529204050134e-06 -1.84854516149118e-06 3.37589263520273e-05 0.00014992849172417 0 0 0 0 0 0 10 0 0 0 0 0 0 0 0 0 0 0 1070 0 0 0 0 0 2133 +646 672 0.998857232014327 -0.00216702383271815 0.0477444662802459 -0.00962055439026662 0.00773869944590371 0.993122392762136 -0.116824764178217 0.0113530387866631 -0.047162936545163 0.117060740652528 0.992004254231966 -0.00117016709111628 8.90126080974416e-05 4.61503994187345e-05 -1.82524509490756e-05 9.22432700960702e-06 1.60802735024895e-05 3.85491292261061e-05 4.61503994187345e-05 0.000122746421196029 -8.16589395190421e-06 1.06633261902614e-05 7.50327267766937e-06 -4.48884080149798e-06 -1.82524509490756e-05 -8.16589395190421e-06 1.99855992711959e-05 -2.74099525582207e-06 -6.58630713565626e-06 -6.50310394797113e-06 9.22432700960702e-06 1.06633261902614e-05 -2.74099525582207e-06 2.98722064533783e-05 -1.90409004569262e-05 4.61618186237428e-06 1.60802735024895e-05 7.50327267766937e-06 -6.58630713565626e-06 -1.90409004569262e-05 0.000101349354489069 -6.27682407209512e-06 3.85491292261061e-05 -4.48884080149798e-06 -6.50310394797113e-06 4.61618186237428e-06 -6.27682407209512e-06 8.82881098412975e-05 0 0 0 0 0 0 8 0 0 0 0 0 0 0 0 0 0 0 1146 0 0 0 0 0 2137 +646 675 0.998602222832669 -0.00266852408398702 0.0527871152163717 -0.0074035805983409 0.00899451763077126 0.9927369257244 -0.119968724907189 0.00404116437443846 -0.0520835790460205 0.120275830001212 0.991373302803377 -0.00270811105857814 0.000178374959266716 0.000124217661142908 -2.07665060441789e-05 7.04521125377372e-06 3.80657671909277e-05 9.95497457805601e-05 0.000124217661142908 0.000149121568818671 -1.56116704634627e-05 2.36486108636511e-05 -4.60829093216835e-07 5.71735954203697e-05 -2.07665060441789e-05 -1.56116704634627e-05 1.77549586539799e-05 -5.4574046431345e-06 -4.67683810376968e-06 -7.55484501549401e-06 7.04521125377372e-06 2.36486108636511e-05 -5.4574046431345e-06 3.95064383687649e-05 -3.24832326998873e-05 -3.81939340306476e-06 3.80657671909277e-05 -4.60829093216835e-07 -4.67683810376968e-06 -3.24832326998873e-05 0.000108710600944797 2.91080190597197e-05 9.95497457805601e-05 5.71735954203697e-05 -7.55484501549401e-06 -3.81939340306476e-06 2.91080190597197e-05 0.000128810683266804 0 0 0 0 0 0 7 0 0 0 0 0 0 0 0 0 0 0 1036 0 0 0 0 0 2154 +646 674 0.999056068471583 -0.00300682954188139 0.0433351015483848 -0.00669796995634874 0.00775285751425787 0.993926580765532 -0.109771787122654 -0.00061425872061689 -0.0427418442567278 0.110004140939529 0.993011693650025 -0.0131362491879348 0.000157533248701846 0.000110337853131351 -2.11586998990267e-05 8.35178761427819e-06 5.18419349921292e-05 0.000100291057986585 0.000110337853131351 0.000167649094236208 -1.8895616882867e-05 1.31292024102756e-05 5.33599683101072e-05 5.41180727313029e-05 -2.11586998990267e-05 -1.8895616882867e-05 2.06378394849488e-05 -6.64474126652245e-06 -8.59576368067646e-06 -1.00962350526722e-05 8.35178761427819e-06 1.31292024102756e-05 -6.64474126652245e-06 3.01465027870039e-05 -1.21692580786687e-05 8.12527380357683e-06 5.18419349921292e-05 5.33599683101072e-05 -8.59576368067646e-06 -1.21692580786687e-05 0.00010804311125639 6.82412163260952e-06 0.000100291057986585 5.41180727313029e-05 -1.00962350526722e-05 8.12527380357683e-06 6.82412163260952e-06 0.000148999780521412 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 991 0 0 0 0 0 2172 +647 650 0.999950911917224 -8.61286575328217e-05 0.00990789270063049 -0.00264936293454047 0.000358516930623272 0.999621916350709 -0.02749355955394 0.00400830276540887 -0.00990177870502628 0.0274957620950928 0.999572877705916 0.00331715440998133 9.81471234196335e-05 5.20821852330675e-05 -1.1816523982973e-05 4.19092599591543e-06 1.82162758555219e-05 3.23843845977111e-05 5.20821852330675e-05 8.80355883122409e-05 -6.47953027576733e-06 6.38780423935749e-06 1.62094255483368e-05 -1.54616096845235e-05 -1.1816523982973e-05 -6.47953027576733e-06 2.41068620697401e-05 -6.87835870861194e-06 -1.72352410104967e-06 -5.78292164317487e-06 4.19092599591543e-06 6.38780423935749e-06 -6.87835870861194e-06 2.26184591717167e-05 2.46098968042434e-06 -1.31949683225581e-06 1.82162758555219e-05 1.62094255483368e-05 -1.72352410104967e-06 2.46098968042434e-06 4.59693719790592e-05 4.95255125621782e-06 3.23843845977111e-05 -1.54616096845235e-05 -5.78292164317487e-06 -1.31949683225581e-06 4.95255125621782e-06 9.24282423647191e-05 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 1534 0 0 0 0 0 2038 +647 673 0.99952900704661 -0.00178076949596853 0.0306364640978832 -0.00394126680079861 0.00502915176942616 0.99432324723261 -0.106282583922666 -0.0043695568822807 -0.0302732836821302 0.106386601002198 0.993863883749832 0.00545020120524949 5.50972548235511e-05 2.13706561970177e-05 -1.7633500879616e-05 6.67599055832494e-07 1.76123410611484e-05 2.85688116289387e-05 2.13706561970177e-05 0.000104763797171843 -5.28743323422501e-06 1.41740337923344e-05 -2.28302438192977e-06 1.08199725931235e-06 -1.7633500879616e-05 -5.28743323422501e-06 2.14652577254764e-05 -3.63857801956529e-06 -2.48523363211457e-06 -6.7600166973438e-06 6.67599055832494e-07 1.41740337923344e-05 -3.63857801956529e-06 2.76435623435679e-05 -1.29166367292069e-05 9.7827347846407e-08 1.76123410611484e-05 -2.28302438192977e-06 -2.48523363211457e-06 -1.29166367292069e-05 7.52763328543135e-05 -4.79550029710711e-07 2.85688116289387e-05 1.08199725931235e-06 -6.7600166973438e-06 9.7827347846407e-08 -4.79550029710711e-07 7.11152023880958e-05 0 0 0 0 0 0 7 0 0 0 0 0 0 0 0 0 0 0 1122 0 0 0 0 0 2187 +647 649 0.999986521265758 -0.000408003569224038 0.00517598492023295 -0.00419111184974688 0.000505472298107346 0.999822315022688 -0.0188436429712564 0.00673037542977049 -0.00516737695188038 0.0188460052997932 0.999809044917917 -0.00206357466576794 0.00017757854416274 0.00011686922354608 -5.85685613201671e-06 1.08106444446822e-05 7.53945448212273e-06 4.61198790914349e-05 0.00011686922354608 0.000127322974522785 -8.14473770763434e-06 9.15445549187186e-06 1.4845677698785e-05 6.5955076606528e-06 -5.85685613201671e-06 -8.14473770763434e-06 1.75053659438506e-05 -1.37897692738316e-06 9.70074933659293e-07 -5.57748837733514e-06 1.08106444446822e-05 9.15445549187186e-06 -1.37897692738316e-06 2.19755280017097e-05 -2.37049963331897e-06 4.70244767171106e-06 7.53945448212273e-06 1.4845677698785e-05 9.70074933659293e-07 -2.37049963331897e-06 4.96650596009305e-05 -4.27074760896532e-06 4.61198790914349e-05 6.5955076606528e-06 -5.57748837733514e-06 4.70244767171106e-06 -4.27074760896532e-06 8.27334218195121e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1464 0 0 0 0 0 2134 +647 651 0.999726431366885 -0.0010612887224353 0.0233652753607052 -0.00268125879000211 0.00203628829955751 0.999126246833545 -0.041744417809754 0.00290669286608471 -0.0233005569975276 0.0417805762832665 0.998855078321697 0.00033088505676425 0.000111786485156714 8.35089170018148e-05 -7.9240730808061e-06 8.09597644882078e-06 1.59115703991407e-05 4.52379903567294e-05 8.35089170018148e-05 9.91543480097433e-05 -9.66311492426942e-06 4.94001956465431e-06 1.80557347073328e-05 1.70436886443415e-05 -7.9240730808061e-06 -9.66311492426942e-06 1.87693960599758e-05 -2.56890201209331e-09 -4.22722697026955e-06 -2.78633303416119e-06 8.09597644882078e-06 4.94001956465431e-06 -2.56890201209331e-09 2.05463203534099e-05 2.62369637459824e-06 7.6270128797215e-06 1.59115703991407e-05 1.80557347073328e-05 -4.22722697026955e-06 2.62369637459824e-06 4.01985203562587e-05 4.89755066217463e-07 4.52379903567294e-05 1.70436886443415e-05 -2.78633303416119e-06 7.6270128797215e-06 4.89755066217463e-07 7.42900771949247e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1459 0 0 0 0 0 2156 +647 674 0.99953672573445 -0.00388157418115866 0.0301872040760931 -0.00456785181782608 0.00682433977311739 0.995162906411609 -0.0980011126929747 -0.00276972958842687 -0.0296607871560513 0.0981617190368844 0.994728362228105 0.000767967873932012 5.75676148537229e-05 5.07630200362499e-05 -1.18497135747815e-05 7.82020732006017e-06 8.42502003796561e-06 1.73135774930015e-05 5.07630200362499e-05 0.000126797575188338 -6.18557456371527e-06 8.28814466588935e-06 2.17522370962016e-05 1.20958697040752e-05 -1.18497135747815e-05 -6.18557456371527e-06 1.95550633434686e-05 -4.82305542421904e-06 -9.78179628731701e-08 -3.28031170610727e-06 7.82020732006017e-06 8.28814466588935e-06 -4.82305542421904e-06 2.87850101087834e-05 -9.97606436676029e-06 2.33281074950398e-06 8.42502003796561e-06 2.17522370962016e-05 -9.78179628731701e-08 -9.97606436676029e-06 7.08313929679153e-05 -9.43812912224093e-06 1.73135774930015e-05 1.20958697040752e-05 -3.28031170610727e-06 2.33281074950398e-06 -9.43812912224093e-06 5.90046900384049e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1062 0 0 0 0 0 2205 +648 651 0.999936770922195 -0.00139583981444537 0.0111582162062549 -0.00347478662858057 0.00171723646178352 0.999582389699098 -0.0288460968308533 0.00245077356611625 -0.0111132918897796 0.0288634342144702 0.999521584013432 0.004298071901806 8.98371557013523e-05 7.4358948355313e-05 -7.17300354822473e-06 -3.37354582495981e-06 3.57907121771418e-05 1.14741453609792e-05 7.4358948355313e-05 9.92479853731538e-05 -7.67951391011354e-06 -7.74209653534603e-08 3.58472673578034e-05 -2.19945304928661e-06 -7.17300354822473e-06 -7.67951391011354e-06 1.70090777891557e-05 -2.07579480860345e-07 -1.94767616855303e-06 -3.07218537846583e-06 -3.37354582495981e-06 -7.74209653534603e-08 -2.07579480860345e-07 2.13160546419762e-05 -7.56598642902096e-07 -1.33357324418825e-06 3.57907121771418e-05 3.58472673578034e-05 -1.94767616855303e-06 -7.56598642902096e-07 6.02337740085283e-05 5.39296772189455e-06 1.14741453609792e-05 -2.19945304928661e-06 -3.07218537846583e-06 -1.33357324418825e-06 5.39296772189455e-06 4.02244211987635e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1431 0 0 0 0 0 2147 +647 675 0.998770535891924 -0.00370791819050191 0.049433470208464 -0.00102938563551873 0.00847545394880617 0.995288548914697 -0.096586081189985 -0.00528122826005874 -0.0488424335442064 0.0968863031701037 0.994096303656497 -0.00304437947984178 6.17113699659617e-05 5.14590147423148e-05 -1.46003524775471e-05 1.87120154183716e-06 1.91941455365977e-05 1.39442645656543e-05 5.14590147423148e-05 0.000107641129942327 -8.37420808580959e-06 4.26292773099225e-06 2.47082428030723e-05 -1.20659572850663e-06 -1.46003524775471e-05 -8.37420808580959e-06 1.89792863639081e-05 -3.12615322184812e-06 -3.51037868313807e-06 -2.9025568969843e-06 1.87120154183716e-06 4.26292773099225e-06 -3.12615322184812e-06 2.75833074819828e-05 -1.7141360833802e-05 -7.49689001215002e-06 1.91941455365977e-05 2.47082428030723e-05 -3.51037868313807e-06 -1.7141360833802e-05 8.19107752957906e-05 1.66982885431139e-05 1.39442645656543e-05 -1.20659572850663e-06 -2.9025568969843e-06 -7.49689001215002e-06 1.66982885431139e-05 5.64645689502169e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1061 0 0 0 0 0 2220 +648 652 0.999841490054215 -0.0024171544167402 0.0176395048312674 -0.00342887428562072 0.00298465373217939 0.999476441662634 -0.032216989361184 0.00800658292671111 -0.0175523960833176 0.0322645304618754 0.999325229075004 0.0018075434695853 6.74357868711641e-05 3.4939209846436e-05 -1.35182243706649e-05 6.17871006669544e-06 1.3052070729475e-05 1.00088049559183e-05 3.4939209846436e-05 0.000120974563889809 -5.06184415516201e-06 9.07999171311745e-06 1.76296339892199e-05 -2.94092111202031e-05 -1.35182243706649e-05 -5.06184415516201e-06 2.56261243551944e-05 -4.46704341809556e-06 -4.97184563487337e-06 -8.08473038733974e-06 6.17871006669544e-06 9.07999171311745e-06 -4.46704341809556e-06 2.03677527900316e-05 8.95669415410731e-06 1.07686533795275e-06 1.3052070729475e-05 1.76296339892199e-05 -4.97184563487337e-06 8.95669415410731e-06 3.41094522201544e-05 -1.60476267059776e-06 1.00088049559183e-05 -2.94092111202031e-05 -8.08473038733974e-06 1.07686533795275e-06 -1.60476267059776e-06 4.09401835129145e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1437 0 0 0 0 0 2204 +648 674 0.999838915006004 -0.00428943469269206 0.0174282755783104 -0.00044917586616341 0.00569459424133548 0.996665796335845 -0.0813932553143213 -0.0216860412679774 -0.0170210351049209 0.0814793910400224 0.996529675022126 -0.00059480615608942 8.78332121055531e-05 5.48846356132767e-05 -1.09340992533019e-05 2.65069720285473e-06 1.11700416758882e-05 3.53437359354383e-05 5.48846356132767e-05 0.000135241403346295 -7.41642840053545e-06 8.29857225636389e-06 2.35147900073085e-05 1.44347760022129e-06 -1.09340992533019e-05 -7.41642840053545e-06 1.85009127113903e-05 -4.69974515752353e-06 -1.7534916588803e-06 -1.48299985954449e-06 2.65069720285473e-06 8.29857225636389e-06 -4.69974515752353e-06 2.90263331001699e-05 -7.60913731535012e-06 -6.7104078595744e-07 1.11700416758882e-05 2.35147900073085e-05 -1.7534916588803e-06 -7.60913731535012e-06 7.5597440856164e-05 -4.01367742147142e-06 3.53437359354383e-05 1.44347760022129e-06 -1.48299985954449e-06 -6.7104078595744e-07 -4.01367742147142e-06 7.47303125715389e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1044 0 0 0 0 0 2291 +648 650 0.999898000892816 -0.000943749921180075 0.0142512156195898 0.00351535879941746 0.00119319305471969 0.999846064796986 -0.017504942168311 -0.00473573844548784 -0.0142325015680286 0.0175201611313371 0.999745207466907 -0.0035559793272523 5.37677566813883e-05 2.93191139659851e-05 -6.37985703965338e-06 5.8896671701825e-07 1.29074409515372e-05 2.39747224747195e-06 2.93191139659851e-05 6.98524703438116e-05 -4.46037679189185e-06 5.22459527376718e-06 3.87896780468109e-06 -2.0231255848074e-05 -6.37985703965338e-06 -4.46037679189185e-06 1.85145691613596e-05 -2.71948652985474e-06 -2.58063335568947e-06 -7.27943126212471e-06 5.8896671701825e-07 5.22459527376718e-06 -2.71948652985474e-06 2.08818383781289e-05 3.12820807141361e-06 2.87367375910503e-08 1.29074409515372e-05 3.87896780468109e-06 -2.58063335568947e-06 3.12820807141361e-06 3.36321844305896e-05 1.59321237333582e-06 2.39747224747195e-06 -2.0231255848074e-05 -7.27943126212471e-06 2.87367375910503e-08 1.59321237333582e-06 4.50421449940052e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1538 0 0 0 0 0 2129 +648 678 0.998604238382563 -0.00356796137453944 0.0526957753146433 0.00830161151346436 0.0083145314861758 0.995895059313539 -0.0901326766552995 -0.0216071413558728 -0.0521578723736596 0.0904450136077892 0.994534693141944 -0.000974780197258003 6.60996685838501e-05 6.41549320511155e-05 -1.83099856479477e-05 1.98251285018035e-06 3.1511465980064e-05 1.53003914389231e-05 6.41549320511155e-05 0.000120433176733175 -1.6580966676987e-05 1.3464190031426e-06 4.01372020438331e-05 7.42338809917258e-06 -1.83099856479477e-05 -1.6580966676987e-05 2.21817859995884e-05 -2.14213733819964e-06 -5.10403379099103e-06 -3.97672071882382e-06 1.98251285018035e-06 1.3464190031426e-06 -2.14213733819964e-06 2.43521036025268e-05 -8.27595456411245e-06 -2.28019115475129e-06 3.1511465980064e-05 4.01372020438331e-05 -5.10403379099103e-06 -8.27595456411245e-06 7.54918770051119e-05 9.14908628416766e-06 1.53003914389231e-05 7.42338809917258e-06 -3.97672071882382e-06 -2.28019115475129e-06 9.14908628416766e-06 4.56618060015384e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1146 0 0 0 0 0 2275 +648 675 0.999551294178261 -0.00456985694773362 0.0296028159816103 0.00104870732336149 0.00692713199492763 0.996768875612345 -0.0800238930121871 -0.0212706199939791 -0.0291414678574824 0.0801930484392405 0.996353275617204 -0.00503311704403081 6.514192323603e-05 4.70359808285677e-05 -1.37270823003266e-05 3.1222074020105e-06 1.42170129303226e-05 2.73390458202601e-05 4.70359808285677e-05 8.10601693261397e-05 -1.08227351511465e-05 4.01404042945827e-06 1.60909972334189e-05 1.02604165094186e-05 -1.37270823003266e-05 -1.08227351511465e-05 2.18335446554186e-05 -1.28491464185716e-06 -5.10779029241521e-06 5.08836073960326e-07 3.1222074020105e-06 4.01404042945827e-06 -1.28491464185716e-06 2.70797019823206e-05 -6.67626242099354e-06 2.77581824621457e-06 1.42170129303226e-05 1.60909972334189e-05 -5.10779029241521e-06 -6.67626242099354e-06 6.90596137474382e-05 1.33460632166571e-06 2.73390458202601e-05 1.02604165094186e-05 5.08836073960326e-07 2.77581824621457e-06 1.33460632166571e-06 5.32693502542045e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1040 0 0 0 0 0 2343 +650 653 0.999763855041765 -0.00244201137338038 0.0215933029544041 -0.00777196169421836 0.00330502684079896 0.999193337046279 -0.0400218940069337 0.0161410203177465 -0.0214781505165132 0.0400838094842907 0.998965453490569 0.00500105139050613 8.841114085382e-05 4.6968537455635e-05 -1.93479853022239e-05 6.50953717605733e-06 7.28531279482369e-06 1.17644205332534e-05 4.6968537455635e-05 6.75171864691022e-05 -1.21788859928547e-05 5.54378921804165e-06 4.99930141773436e-06 -9.27282943328408e-06 -1.93479853022239e-05 -1.21788859928547e-05 1.98481917017618e-05 -1.35657625845752e-06 -3.56968699409167e-06 -6.66940812048735e-06 6.50953717605733e-06 5.54378921804165e-06 -1.35657625845752e-06 2.06953974743853e-05 9.45706468486541e-07 1.30835281423314e-06 7.28531279482369e-06 4.99930141773436e-06 -3.56968699409167e-06 9.45706468486541e-07 5.01325282993348e-05 1.2312299082969e-05 1.17644205332534e-05 -9.27282943328408e-06 -6.66940812048735e-06 1.30835281423314e-06 1.2312299082969e-05 4.50091013799777e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1323 0 0 0 0 0 2109 +649 652 0.999907432168769 -0.00197214086020398 0.0134624572083167 -0.00177649349052119 0.00227690412237252 0.999740628453772 -0.022660351419936 -0.00128069783036205 -0.0134142760250327 0.022688906524665 0.999652575007657 -0.00368258353452289 0.000116456540433497 8.56339694203976e-05 -1.56055372483315e-06 8.42645077418674e-06 2.39965839562136e-05 3.81785826845474e-05 8.56339694203976e-05 0.000100896667251916 -8.57341510471859e-06 1.18801045008812e-05 1.89729357078227e-05 1.51551952310679e-05 -1.56055372483315e-06 -8.57341510471859e-06 1.71449276747897e-05 3.74115407411656e-07 4.93305844674379e-07 -2.31404105208097e-06 8.42645077418674e-06 1.18801045008812e-05 3.74115407411656e-07 2.06663349383723e-05 4.28221252691085e-06 -3.16071907578009e-07 2.39965839562136e-05 1.89729357078227e-05 4.93305844674379e-07 4.28221252691085e-06 4.6022440904422e-05 1.27000765229833e-05 3.81785826845474e-05 1.51551952310679e-05 -2.31404105208097e-06 -3.16071907578009e-07 1.27000765229833e-05 6.57987336094929e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1329 0 0 0 0 0 2245 +649 651 0.999915890788935 -0.00113840772483951 0.0129195733529843 -0.000996296434680831 0.00135893958854231 0.999853310746617 -0.0170736719022051 0.00484169986733675 -0.0128982413904303 0.0170897927688279 0.999770760900794 6.75382744131049e-05 6.56843939595657e-05 4.85369615615107e-05 -1.18933806348644e-05 -5.54484416936889e-07 2.36997378992371e-05 -3.93941167878525e-06 4.85369615615107e-05 0.000107957677193849 -7.57823456049803e-06 2.58480611943348e-06 2.36365285005008e-05 -2.80167249873178e-05 -1.18933806348644e-05 -7.57823456049803e-06 2.03307937058518e-05 -1.07784126039924e-06 -2.29069732288686e-06 -3.13843123226976e-06 -5.54484416936889e-07 2.58480611943348e-06 -1.07784126039924e-06 2.11841707409098e-05 1.86451131804851e-06 8.27574384270575e-08 2.36997378992371e-05 2.36365285005008e-05 -2.29069732288686e-06 1.86451131804851e-06 4.08971805965481e-05 -4.20999741277951e-07 -3.93941167878525e-06 -2.80167249873178e-05 -3.13843123226976e-06 8.27574384270575e-08 -4.20999741277951e-07 5.12194337901387e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1491 0 0 0 0 0 2229 +649 653 0.999542003830099 -0.00233989447239791 0.0301713021457271 -0.00134783266352153 0.0037288783415431 0.998931584096372 -0.0460628457764681 0.00360635260963977 -0.0300312844484662 0.0461542542846351 0.998482802438682 -0.00269328103443854 0.000144786309391433 0.000107341781618986 -1.48607660232714e-05 -4.76248526030398e-07 3.42547843326596e-05 2.98595814016268e-05 0.000107341781618986 0.00012600764233267 -1.46202606852287e-05 7.76588113682955e-06 2.03588232229412e-05 1.62607085302855e-06 -1.48607660232714e-05 -1.46202606852287e-05 1.97169382229662e-05 1.85341399076014e-06 -1.59651759969347e-06 -2.13434928499666e-06 -4.76248526030398e-07 7.76588113682955e-06 1.85341399076014e-06 2.42889198034079e-05 -9.1420685529346e-06 -5.61623779026975e-06 3.42547843326596e-05 2.03588232229412e-05 -1.59651759969347e-06 -9.1420685529346e-06 6.81666893636386e-05 1.80970257490002e-05 2.98595814016268e-05 1.62607085302855e-06 -2.13434928499666e-06 -5.61623779026975e-06 1.80970257490002e-05 6.11378290556018e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1301 0 0 0 0 0 2198 +649 675 0.999238758284369 -0.00389159222074921 0.0388169995272597 0.00270349297387629 0.00683217416043554 0.997091064342191 -0.0759126524710953 -0.0148977921275205 -0.0384086622853928 0.0761200690944459 0.996358625065545 -0.00596787739533726 0.000218836048309643 0.000130256152303748 -2.34514884331948e-05 9.25582430064536e-06 5.30299136304286e-05 7.69822729200751e-05 0.000130256152303748 0.000180273250628122 -1.13943665243753e-05 1.37696535554485e-05 4.15149945293151e-05 2.40188176098829e-05 -2.34514884331948e-05 -1.13943665243753e-05 1.99653542252708e-05 -5.3697009662773e-06 -7.47483788827243e-06 -1.15324416458142e-05 9.25582430064536e-06 1.37696535554485e-05 -5.3697009662773e-06 3.68045849603661e-05 -2.15212774339844e-05 3.85502961272001e-06 5.30299136304286e-05 4.15149945293151e-05 -7.47483788827243e-06 -2.15212774339844e-05 0.000111853831078919 1.87570705670494e-05 7.69822729200751e-05 2.40188176098829e-05 -1.15324416458142e-05 3.85502961272001e-06 1.87570705670494e-05 9.75961604281673e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1034 0 0 0 0 0 2378 +651 653 0.999908667763783 -0.00160962196047676 0.0134188392941021 -0.00135193318962932 0.0019672263403736 0.999642117342507 -0.0266789665376017 0.00096835731303539 -0.0133710938738133 0.0267029277820444 0.999553984283232 -0.000605166280751328 8.26197011162858e-05 7.61172064899354e-05 -2.59780775026045e-06 9.51949440769016e-06 1.51766022504359e-05 -4.62291715173984e-06 7.61172064899354e-05 0.00011498488467386 -7.96422363790553e-06 1.24499852072564e-05 1.27306285765733e-05 -1.9210888773867e-05 -2.59780775026045e-06 -7.96422363790553e-06 1.73055713566465e-05 1.36582006063825e-06 2.02973561233748e-06 -1.95705376052102e-06 9.51949440769016e-06 1.24499852072564e-05 1.36582006063825e-06 2.3419784780093e-05 -4.07621614902859e-06 -2.33202710423294e-06 1.51766022504359e-05 1.27306285765733e-05 2.02973561233748e-06 -4.07621614902859e-06 5.23837125169643e-05 4.57588296300644e-06 -4.62291715173984e-06 -1.9210888773867e-05 -1.95705376052102e-06 -2.33202710423294e-06 4.57588296300644e-06 4.41764772120802e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1283 0 0 0 0 0 2198 +650 652 0.999993763099005 -0.00125231053315075 0.00330234483669413 -0.00351849364305657 0.00128945971750218 0.999935645424133 -0.0112713044435757 0.00938814924112933 -0.00328801714241576 0.011275492386206 0.999931023728497 5.48369810139792e-05 7.12000357016596e-05 3.99367128425478e-05 -1.04029619846909e-05 7.45102776182919e-06 1.04032145068844e-05 1.55877768227043e-05 3.99367128425478e-05 8.95353804149851e-05 -9.52627343561763e-06 8.85036670623799e-06 1.73026298602517e-05 -1.62031149628901e-05 -1.04029619846909e-05 -9.52627343561763e-06 2.11386263073451e-05 -4.25843660306577e-06 -1.29902433025725e-06 -3.89712057546266e-06 7.45102776182919e-06 8.85036670623799e-06 -4.25843660306577e-06 2.2379029285827e-05 5.75298092943339e-06 -9.75197773328319e-07 1.04032145068844e-05 1.73026298602517e-05 -1.29902433025725e-06 5.75298092943339e-06 4.35599338573333e-05 3.13967168653675e-07 1.55877768227043e-05 -1.62031149628901e-05 -3.89712057546266e-06 -9.75197773328319e-07 3.13967168653675e-07 4.87982538571773e-05 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 1395 0 0 0 0 0 2315 +650 654 0.999338045638162 -0.00256733511357702 0.0362888320356663 -0.0106661015260322 0.00508620847095513 0.997569614407591 -0.0694909698743676 0.0185155713231402 -0.0360222295740865 0.0696295425886518 0.9969223268517 0.0082598898540441 0.000273024038105558 0.000201410284068518 -1.73605761666036e-05 6.71252508905309e-06 5.13304087611057e-05 0.00010854746079594 0.000201410284068518 0.000196778190907031 -1.7907974535576e-05 8.37521271145646e-06 4.10176226927878e-05 5.96608040011239e-05 -1.73605761666036e-05 -1.7907974535576e-05 1.92129314663376e-05 -7.80504083341951e-07 -2.71927173422581e-06 -4.05245903807701e-06 6.71252508905309e-06 8.37521271145646e-06 -7.80504083341951e-07 2.60175636933142e-05 -4.25136739090505e-06 -1.37206009039841e-06 5.13304087611057e-05 4.10176226927878e-05 -2.71927173422581e-06 -4.25136739090505e-06 6.11947896525221e-05 2.43086609530486e-05 0.00010854746079594 5.96608040011239e-05 -4.05245903807701e-06 -1.37206009039841e-06 2.43086609530486e-05 0.000103216450385078 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1276 0 0 0 0 0 2334 +651 655 0.999278083998689 -0.00296020234229439 0.0378754279448079 -0.00597873944304544 0.00525903207649207 0.998139789331169 -0.0607396372688286 0.0127397954795644 -0.0376251700531451 0.060894976443243 0.997434784044776 -0.00409857978955418 9.34220777416865e-05 5.16418118953835e-05 -9.06645564969741e-06 4.83239673374364e-06 -1.42422939273412e-06 5.15982800180567e-05 5.16418118953835e-05 0.000108958380062551 -8.0179186118342e-06 7.2244629057048e-06 1.1417524561959e-05 -3.84720205541907e-06 -9.06645564969741e-06 -8.0179186118342e-06 2.04859719494803e-05 -1.85153121143224e-06 1.80345449254986e-06 -1.90999690555269e-06 4.83239673374364e-06 7.2244629057048e-06 -1.85153121143224e-06 2.85494583839282e-05 -7.44232758611065e-06 -3.67047070820051e-06 -1.42422939273412e-06 1.1417524561959e-05 1.80345449254986e-06 -7.44232758611065e-06 6.662872786856e-05 -1.50252118521793e-06 5.15982800180567e-05 -3.84720205541907e-06 -1.90999690555269e-06 -3.67047070820051e-06 -1.50252118521793e-06 8.72009225075584e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1216 0 0 0 0 0 2281 +651 654 0.999652776641931 -0.00199765205430286 0.026274237160154 0.00165184768671436 0.00324658748301166 0.998862239890459 -0.0475782028951392 -0.00662038443727 -0.026149298686451 0.0476469842412489 0.99852189714143 -0.00513833872243806 0.000158952597379855 0.000112500845015929 -7.05439753320485e-06 -2.68015671864048e-06 4.14391635184885e-05 5.40270271562504e-05 0.000112500845015929 0.000121287769137882 -1.08946264321827e-05 7.31959085431159e-06 1.66341375047528e-05 2.06958559753458e-05 -7.05439753320485e-06 -1.08946264321827e-05 1.59940210641376e-05 6.16759689310337e-07 4.34346018967122e-06 -4.01568171191194e-06 -2.68015671864048e-06 7.31959085431159e-06 6.16759689310337e-07 2.91116290026288e-05 -1.75720219127502e-05 -1.4016338325701e-06 4.14391635184885e-05 1.66341375047528e-05 4.34346018967122e-06 -1.75720219127502e-05 7.73347814981133e-05 2.17946807257245e-05 5.40270271562504e-05 2.06958559753458e-05 -4.01568171191194e-06 -1.4016338325701e-06 2.17946807257245e-05 7.38186360779575e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1258 0 0 0 0 0 2298 +652 655 0.999592768528973 -0.00252550877689129 0.0284239144032153 -0.00176309320849212 0.00404967900385823 0.998549241289521 -0.0536936944164465 0.00230034378713102 -0.0282470742652964 0.0537869363836505 0.998152828112966 0.00284361560852212 0.000104683193294178 7.77564455571057e-05 -1.16994951525972e-05 4.29356745936078e-06 2.13834283186995e-05 4.75248395140937e-05 7.77564455571057e-05 0.000102692433827143 -1.23839734036873e-05 7.48705312837452e-06 1.29409321879212e-05 1.52092855071691e-05 -1.16994951525972e-05 -1.23839734036873e-05 1.97065331262579e-05 -3.25549478929194e-07 -1.53600049014388e-06 -1.24009950251074e-06 4.29356745936078e-06 7.48705312837452e-06 -3.25549478929194e-07 2.2718053678705e-05 -1.53549161042621e-07 6.11453987483139e-07 2.13834283186995e-05 1.29409321879212e-05 -1.53600049014388e-06 -1.53549161042621e-07 4.52616566722382e-05 9.48810907949645e-06 4.75248395140937e-05 1.52092855071691e-05 -1.24009950251074e-06 6.11453987483139e-07 9.48810907949645e-06 6.8498797445757e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1195 0 0 0 0 0 2396 +653 656 0.999754482576573 -0.00224723875466616 0.0220436949268509 0.00190761342901203 0.00309369374044864 0.999256107963049 -0.0384403402375621 -0.00587020231823807 -0.0219409121754055 0.0384990989052829 0.999017725446547 -0.000613908422842086 9.02269754313459e-05 6.36562441167753e-05 -7.54400216393524e-06 -5.99834234797079e-06 4.05940356775114e-05 2.36714544375773e-06 6.36562441167753e-05 8.22880213397905e-05 -8.76821916177516e-06 -2.6577371467796e-06 3.15168496940268e-05 -1.68393678642418e-05 -7.54400216393524e-06 -8.76821916177516e-06 1.60552456800445e-05 1.41332613701358e-06 -3.35451114427086e-06 -1.5080737425667e-06 -5.99834234797079e-06 -2.6577371467796e-06 1.41332613701358e-06 2.66329907481825e-05 -2.04022428432841e-05 -4.40774585451815e-07 4.05940356775114e-05 3.15168496940268e-05 -3.35451114427086e-06 -2.04022428432841e-05 9.95238506824828e-05 6.34876249166137e-06 2.36714544375773e-06 -1.68393678642418e-05 -1.5080737425667e-06 -4.40774585451815e-07 6.34876249166137e-06 5.09174599763347e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1249 0 0 0 0 0 2356 +653 657 0.999766809604506 -0.00198452523548316 0.0215032107560242 0.00425380849626663 0.00281279555612229 0.999252445974612 -0.0385569370530842 -0.0098874001947139 -0.02141061872968 0.0386084300813407 0.999025011965299 7.01729077866224e-05 0.000117387402171366 8.38389582237351e-05 -3.51098995049758e-06 3.00918564584588e-06 1.7428276023969e-05 3.84180609966137e-05 8.38389582237351e-05 0.00010805553036007 -4.05814981665143e-06 -6.02031778877218e-07 2.33810552450282e-05 1.39256427688028e-05 -3.51098995049758e-06 -4.05814981665143e-06 1.62482926475671e-05 1.78555927402838e-07 -2.59345428181899e-06 -1.10518075191233e-06 3.00918564584588e-06 -6.02031778877218e-07 1.78555927402838e-07 2.565634312538e-05 -1.65998739195886e-05 -3.99733171025681e-06 1.7428276023969e-05 2.33810552450282e-05 -2.59345428181899e-06 -1.65998739195886e-05 8.61938564176628e-05 1.39081540935915e-05 3.84180609966137e-05 1.39256427688028e-05 -1.10518075191233e-06 -3.99733171025681e-06 1.39081540935915e-05 6.26663278369329e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1116 0 0 0 0 0 2334 +653 655 0.999780598852896 -0.00273815964077571 0.0207667195080657 0.00282274773798195 0.00351699056408042 0.999288166387139 -0.0375605018071018 -0.0110102745418395 -0.0206490904089555 0.0376252973464763 0.999078551498766 -0.00159476360697255 0.000249144182035647 0.000209381017765219 -1.14711911731529e-05 -3.2674378615367e-07 7.96116958643961e-05 5.86323575236837e-05 0.000209381017765219 0.000222277811802031 -1.27840831552005e-05 6.00824978980222e-06 6.38228880074809e-05 3.61331058639807e-05 -1.14711911731529e-05 -1.27840831552005e-05 2.03683845501694e-05 -2.40726117803598e-06 -4.33330252044726e-06 -2.55674813043073e-07 -3.2674378615367e-07 6.00824978980222e-06 -2.40726117803598e-06 3.0184359939709e-05 -1.3278100435839e-05 -4.24259184013318e-06 7.96116958643961e-05 6.38228880074809e-05 -4.33330252044726e-06 -1.3278100435839e-05 0.000103461859607819 2.51631087242754e-05 5.86323575236837e-05 3.61331058639807e-05 -2.55674813043073e-07 -4.24259184013318e-06 2.51631087242754e-05 6.29376350261631e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1190 0 0 0 0 0 2313 +654 656 0.999997181506524 -0.00190540595310603 0.00141647702463309 0.00296368756116119 0.00190779970127184 0.999996751241587 -0.0016905048276614 -0.00728609970706387 -0.00141325132487906 0.00169320241742902 0.999997567890176 -0.00350589805145251 8.07067847913376e-05 6.78048753473407e-05 -5.58771473028988e-06 2.44478592387788e-06 2.70716660456598e-05 1.31160267159943e-05 6.78048753473407e-05 8.22179022196805e-05 -7.19843940146589e-06 3.34815576992407e-06 2.1331926237136e-05 4.12513914770911e-06 -5.58771473028988e-06 -7.19843940146589e-06 1.69000863252122e-05 1.3455026473932e-06 -1.7240147437329e-06 -1.86198663042096e-06 2.44478592387788e-06 3.34815576992407e-06 1.3455026473932e-06 1.93653089835302e-05 -2.1798412426912e-06 -4.49213417832557e-07 2.70716660456598e-05 2.1331926237136e-05 -1.7240147437329e-06 -2.1798412426912e-06 6.60861029605091e-05 1.19483167255481e-05 1.31160267159943e-05 4.12513914770911e-06 -1.86198663042096e-06 -4.49213417832557e-07 1.19483167255481e-05 4.45500016268375e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1242 0 0 0 0 0 2531 +652 656 0.999583648086223 -0.00245700673433774 0.0287488016540613 -0.00152931287756396 0.00411214193119534 0.998328060022264 -0.0576556576661822 -0.00337166142269244 -0.0285590750441054 0.0577498717755261 0.997922507784315 0.00211436852066649 7.8250698525657e-05 4.8921902847787e-05 -9.29520767214699e-06 4.52086141322142e-06 2.7372397666797e-05 3.05806779455294e-05 4.8921902847787e-05 7.42367866442621e-05 -9.09138046315586e-06 7.36494663010812e-06 2.56470988249851e-05 1.81041179799327e-06 -9.29520767214699e-06 -9.09138046315586e-06 1.85898544181812e-05 -2.66479336955735e-06 3.06093023271155e-07 -4.16952453527955e-06 4.52086141322142e-06 7.36494663010812e-06 -2.66479336955735e-06 2.44344547240342e-05 -3.50485233171308e-07 2.26202459159402e-06 2.7372397666797e-05 2.56470988249851e-05 3.06093023271155e-07 -3.50485233171308e-07 5.99868563926817e-05 1.28454066636778e-05 3.05806779455294e-05 1.81041179799327e-06 -4.16952453527955e-06 2.26202459159402e-06 1.28454066636778e-05 6.31461652882811e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1257 0 0 0 0 0 2479 +654 657 0.999970691603921 -0.00197659162950295 0.00739655451582381 0.00409640987562877 0.00201458125248844 0.999984800860438 -0.00513220327803096 -0.00652845517198976 -0.00738629782451918 0.00514695382144512 0.999959474914263 -0.00321898266562748 6.77437994788481e-05 4.91830958867062e-05 -3.61527018559245e-06 8.33516309448663e-07 1.61847366443782e-05 9.87630958835321e-06 4.91830958867062e-05 7.34853685519567e-05 -3.71870905558843e-06 5.08923127956066e-06 4.60176864125459e-06 -8.88191784390202e-06 -3.61527018559245e-06 -3.71870905558843e-06 1.59991463590055e-05 6.11433928371357e-07 -2.99593015024944e-07 -1.17957708739341e-06 8.33516309448663e-07 5.08923127956066e-06 6.11433928371357e-07 1.98806987562372e-05 1.32273047363807e-06 -5.43739163176841e-06 1.61847366443782e-05 4.60176864125459e-06 -2.99593015024944e-07 1.32273047363807e-06 3.89716645568551e-05 6.53249813916413e-06 9.87630958835321e-06 -8.88191784390202e-06 -1.17957708739341e-06 -5.43739163176841e-06 6.53249813916413e-06 4.78675080811835e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1116 0 0 0 0 0 2386 +652 654 0.999643318647069 -0.00140229189192622 0.0266696280762346 -0.00613195968733294 0.00279535566313994 0.998629140404383 -0.0522687853495773 0.0105907955948554 -0.0265597716667782 0.0523246931443795 0.998276867916088 0.00623437047137609 6.80046907509502e-05 4.51890010283685e-05 -1.08379790412215e-05 9.06424178409105e-06 1.25572946425641e-06 1.99594022996404e-05 4.51890010283685e-05 0.000102708461358291 -1.51161288679349e-05 1.16777140907799e-05 8.37019272862328e-06 -1.2882596657216e-05 -1.08379790412215e-05 -1.51161288679349e-05 2.46187511529552e-05 -4.36781909713858e-06 -4.06056439436627e-06 -7.98030545616558e-06 9.06424178409105e-06 1.16777140907799e-05 -4.36781909713858e-06 2.55715879400927e-05 4.41581683489379e-06 2.29926280797151e-06 1.25572946425641e-06 8.37019272862328e-06 -4.06056439436627e-06 4.41581683489379e-06 4.42006933479911e-05 -2.44187787887019e-07 1.99594022996404e-05 -1.2882596657216e-05 -7.98030545616558e-06 2.29926280797151e-06 -2.44187787887019e-07 6.31307597957321e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1321 0 0 0 0 0 2406 +654 658 0.999991217467715 -0.00183104338801576 0.00376991611964903 0.00284122401651375 0.00188619444370365 0.999890492619534 -0.0146780461774263 -0.00996270175460615 -0.00374262714660803 0.01468502806185 0.999885164752865 0.00559949600717482 8.6208660343308e-05 6.47596246273044e-05 -9.87007164379898e-06 6.09708882340833e-06 2.34342378314589e-05 2.72519568574565e-05 6.47596246273044e-05 7.37340638888077e-05 -9.52347032962137e-06 2.8256479087687e-06 1.72494052821303e-05 9.64412883963488e-06 -9.87007164379898e-06 -9.52347032962137e-06 1.60495696126147e-05 -7.83413568938652e-07 -3.10455975274912e-06 -1.6720254687567e-06 6.09708882340833e-06 2.8256479087687e-06 -7.83413568938652e-07 2.21935475008064e-05 -3.42492199405514e-06 3.00722303943848e-06 2.34342378314589e-05 1.72494052821303e-05 -3.10455975274912e-06 -3.42492199405514e-06 6.20012957715712e-05 7.81119442143943e-06 2.72519568574565e-05 9.64412883963488e-06 -1.6720254687567e-06 3.00722303943848e-06 7.81119442143943e-06 5.09968957947295e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1196 0 0 0 0 0 2374 +655 657 0.999982751484046 0.000691774582203243 -0.00583251080788583 -0.000324091706447025 -0.000680804039105319 0.999997995961104 0.00188270540351808 -0.00348323736452156 0.00583380152705123 -0.00187870213272776 0.999981218442646 -0.00438530164996734 5.1795070571703e-05 2.03494085954746e-05 -5.12658010036838e-06 -4.20363078904028e-06 1.57847173899007e-05 1.16659193966879e-05 2.03494085954746e-05 9.23696920230856e-05 -2.57566996601937e-06 2.39524813776079e-06 1.28129069398559e-05 -2.78150062259327e-05 -5.12658010036838e-06 -2.57566996601937e-06 2.15892877546609e-05 -1.48733187714776e-06 1.01238576974621e-06 -8.29659882770477e-06 -4.20363078904028e-06 2.39524813776079e-06 -1.48733187714776e-06 2.3662257905114e-05 6.99304335296379e-06 -3.05565262549024e-06 1.57847173899007e-05 1.28129069398559e-05 1.01238576974621e-06 6.99304335296379e-06 4.26242354993001e-05 9.23220836637142e-06 1.16659193966879e-05 -2.78150062259327e-05 -8.29659882770477e-06 -3.05565262549024e-06 9.23220836637142e-06 6.10764434331657e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1176 0 0 0 0 0 2501 +656 658 0.999995530622834 2.91366543620267e-05 0.00298962964472469 0.00186165869018561 -2.92656449801291e-05 0.999999998642858 4.31022814705143e-05 -0.00369132658668765 -0.00298962838481106 -4.31895822699663e-05 0.9999955301184 -0.00188175799584241 8.41521341898854e-05 4.26474018887456e-05 -1.18606718293549e-05 1.18967784720964e-06 2.24982474437401e-05 4.99384971666188e-05 4.26474018887456e-05 8.9370389527509e-05 -1.48673452714214e-05 1.24082840509998e-05 6.61937550073807e-06 -4.28533684558487e-06 -1.18606718293549e-05 -1.48673452714214e-05 2.39426488299682e-05 -6.42422958018044e-06 3.13683585358063e-07 9.93136516828926e-07 1.18967784720964e-06 1.24082840509998e-05 -6.42422958018044e-06 3.24523461256691e-05 4.77099915874809e-06 -6.95958328978917e-06 2.24982474437401e-05 6.61937550073807e-06 3.13683585358063e-07 4.77099915874809e-06 5.3197866033806e-05 2.17784076634414e-05 4.99384971666188e-05 -4.28533684558487e-06 9.93136516828926e-07 -6.95958328978917e-06 2.17784076634414e-05 0.000100241292443893 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1250 0 0 0 0 0 2495 +655 659 0.999991213256335 0.000692734425244804 -0.00413443214227487 0.000670080074443462 -0.000705243946876386 0.9999951759845 -0.00302500226512923 -0.00313113809090076 0.00413231667450463 0.00302789146845185 0.999986877829983 0.00598379224439038 3.58741704254767e-05 1.00897245502149e-05 -1.20462026577099e-05 2.97633313331126e-06 7.25403414767619e-06 1.36454054486205e-05 1.00897245502149e-05 5.10713226994071e-05 -9.61710472111106e-06 9.65946326514737e-07 4.55892759651544e-06 -1.62654356447469e-05 -1.20462026577099e-05 -9.61710472111106e-06 2.03242320882917e-05 -3.18920475104217e-07 -2.07204456834738e-06 -1.58132923403392e-06 2.97633313331126e-06 9.65946326514737e-07 -3.18920475104217e-07 2.22143910454604e-05 1.23402937309952e-05 6.08936950035318e-06 7.25403414767619e-06 4.55892759651544e-06 -2.07204456834738e-06 1.23402937309952e-05 3.61618418150738e-05 9.55514910023622e-06 1.36454054486205e-05 -1.62654356447469e-05 -1.58132923403392e-06 6.08936950035318e-06 9.55514910023622e-06 5.55645497026892e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1316 0 0 0 0 0 2698 +656 659 0.999997590491959 0.000156336022838557 0.00218965050281324 0.000593119003633343 -0.000159904754570372 0.999998659191789 0.00162973773762584 -0.00026298350561374 -0.00218939278019569 -0.0016300839462859 0.999996274685852 -0.00763033316693841 2.78029129241552e-05 3.49634427575348e-06 -1.11320228798052e-05 2.86762139470829e-06 5.94897802192692e-06 1.42260181095186e-05 3.49634427575348e-06 5.12857836740095e-05 -7.818228177888e-06 1.26253698091368e-06 7.02246049771104e-06 -2.24737896588604e-05 -1.11320228798052e-05 -7.818228177888e-06 2.28403454719624e-05 -3.99385903229666e-06 -6.08086099143714e-06 -3.71375344445147e-06 2.86762139470829e-06 1.26253698091368e-06 -3.99385903229666e-06 2.56237925713546e-05 3.63952064417086e-06 3.3768739189802e-06 5.94897802192692e-06 7.02246049771104e-06 -6.08086099143714e-06 3.63952064417086e-06 5.70833785979044e-05 6.78257963426557e-06 1.42260181095186e-05 -2.24737896588604e-05 -3.71375344445147e-06 3.3768739189802e-06 6.78257963426557e-06 5.92127037957679e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1322 0 0 0 0 0 2728 +655 658 0.999970035876784 5.40466922449911e-05 0.00774108697399296 0.0034837483363865 -7.93515024374781e-05 0.999994654878057 0.00326862641712444 -0.0031400278350721 -0.00774086893849308 -0.00326914274248161 0.999964695203689 -0.00482440878795242 2.68516184126856e-05 5.82670681316148e-06 -9.24817615674131e-06 -2.42588012119456e-07 4.36091327431939e-06 -8.49071636600261e-07 5.82670681316148e-06 5.27128184486605e-05 -6.64506004497029e-06 1.64876497353098e-06 8.46660586444345e-06 -2.71720100873583e-05 -9.24817615674131e-06 -6.64506004497029e-06 2.1240307179297e-05 -4.30562492591997e-07 4.43313956880699e-07 -2.79604029027436e-06 -2.42588012119456e-07 1.64876497353098e-06 -4.30562492591997e-07 2.10859277298335e-05 7.9652268074081e-06 1.06743020994194e-06 4.36091327431939e-06 8.46660586444345e-06 4.43313956880699e-07 7.9652268074081e-06 3.71232916419507e-05 -2.08796080558569e-06 -8.49071636600261e-07 -2.71720100873583e-05 -2.79604029027436e-06 1.06743020994194e-06 -2.08796080558569e-06 3.64632740133993e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1259 0 0 0 0 0 2514 +656 660 0.99997289054252 0.000312231866133312 0.0073566766477405 0.00390744196197419 -0.000342476754113217 0.999991493973347 0.0041103151492684 -0.00184689314733184 -0.00735533070028341 -0.00411272321159401 0.999964491678617 -0.00818711972396528 2.32027587511128e-05 8.07627845083211e-06 -1.19745854314194e-05 -9.71882022787531e-07 6.07858777157418e-06 6.65473874214613e-06 8.07627845083211e-06 4.72663800682536e-05 -5.15951067298158e-06 -2.93820886013071e-07 6.57134907051678e-06 -1.6572760031293e-05 -1.19745854314194e-05 -5.15951067298158e-06 2.04381261018417e-05 -2.88587987153053e-06 -2.90620790607885e-06 -2.75362110672885e-06 -9.71882022787531e-07 -2.93820886013071e-07 -2.88587987153053e-06 2.30621688511418e-05 6.90922681753244e-06 2.11535805084104e-07 6.07858777157418e-06 6.57134907051678e-06 -2.90620790607885e-06 6.90922681753244e-06 4.09080109658927e-05 1.33361154451301e-05 6.65473874214613e-06 -1.6572760031293e-05 -2.75362110672885e-06 2.11535805084104e-07 1.33361154451301e-05 5.49817850786629e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1327 0 0 0 0 0 2714 +657 661 0.999998482896608 -0.000164889722106987 0.00173407492954133 0.000889329285901263 0.000164099669049234 0.999999882687388 0.000455737325307991 0.000528329280606978 -0.00173414987251339 -0.000455452072785304 0.999998392642523 -0.00164824062054509 3.22009234943751e-05 1.56965808838081e-05 -1.36013376951156e-05 1.63803437769135e-06 6.39010429202947e-06 -2.99239035134461e-06 1.56965808838081e-05 5.30338775725775e-05 -6.93336941682e-06 1.45412177918554e-06 5.58977067530031e-06 -3.02457601615534e-05 -1.36013376951156e-05 -6.93336941682e-06 2.17524196686653e-05 -2.63382895944714e-06 -3.67171819169771e-06 -3.64630152946506e-06 1.63803437769135e-06 1.45412177918554e-06 -2.63382895944714e-06 2.36421907616206e-05 1.05327846132592e-05 4.41121449780164e-06 6.39010429202947e-06 5.58977067530031e-06 -3.67171819169771e-06 1.05327846132592e-05 3.54216477371313e-05 -1.6232181479813e-06 -2.99239035134461e-06 -3.02457601615534e-05 -3.64630152946506e-06 4.41121449780164e-06 -1.6232181479813e-06 5.38431028740849e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1201 0 0 0 0 0 2714 +657 660 0.999903668272316 -0.0010598225922659 0.0138394707861299 -0.000117958723821869 0.000990460133538235 0.999986920137054 0.00501782258891567 0.00645521786598811 -0.0138446077694925 -0.00500363176931354 0.999891639381401 -0.00798260954509881 3.07473623530536e-05 9.52840021400482e-06 -1.55779027610787e-05 3.38659821733641e-06 8.42160078682233e-06 1.62911660168923e-05 9.52840021400482e-06 4.61898342306248e-05 -4.82026276448244e-06 -1.19784626643236e-06 5.10226022435122e-06 -1.63712160773256e-05 -1.55779027610787e-05 -4.82026276448244e-06 2.19125425513335e-05 -5.94773930086076e-06 -3.46741137837218e-06 -6.38555896587287e-06 3.38659821733641e-06 -1.19784626643236e-06 -5.94773930086076e-06 2.52559173267365e-05 8.56162667000038e-06 6.78240825466216e-06 8.42160078682233e-06 5.10226022435122e-06 -3.46741137837218e-06 8.56162667000038e-06 3.77226832629042e-05 1.06355962683614e-05 1.62911660168923e-05 -1.63712160773256e-05 -6.38555896587287e-06 6.78240825466216e-06 1.06355962683614e-05 6.92223716103644e-05 0 0 0 0 0 0 7 0 0 0 0 0 0 0 0 0 0 0 1283 0 0 0 0 0 2647 +658 660 0.999986419989853 -0.000559400175209293 -0.00518140013143335 -0.00624622361773008 0.000534697846550213 0.999988491693823 -0.00476765960669713 0.00755983035819273 0.00518400753191354 0.0047648243783389 0.999975210950028 0.0124970904489229 3.1893986499311e-05 1.23932183716044e-05 -1.0645511264735e-05 1.59710397278332e-06 5.10604522308699e-06 8.84421361824928e-06 1.23932183716044e-05 5.56452753845471e-05 -8.83342034438756e-06 -7.33569844013569e-07 1.01760053548318e-05 -1.96464255302918e-05 -1.0645511264735e-05 -8.83342034438756e-06 2.33866264040495e-05 -6.31416652935739e-06 -2.41413367393396e-06 -2.72034918322477e-06 1.59710397278332e-06 -7.33569844013569e-07 -6.31416652935739e-06 2.67134884281602e-05 9.52561629536785e-06 9.04522341239789e-06 5.10604522308699e-06 1.01760053548318e-05 -2.41413367393396e-06 9.52561629536785e-06 4.21179088182234e-05 2.61969398441385e-06 8.84421361824928e-06 -1.96464255302918e-05 -2.72034918322477e-06 9.04522341239789e-06 2.61969398441385e-06 6.62203152283336e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1322 0 0 0 0 0 2658 +656 630 0.996120249312734 -0.0119588397441888 -0.0871862091222494 0.0298245050402848 0.0229567759220734 0.99173207975686 0.126255567878794 -0.0648429437809394 0.0849554903958509 -0.12776724201886 0.988158942943135 -0.0479219584618157 0.000126028925683117 8.46192505186366e-05 -3.99287423759339e-06 2.71009007861949e-06 3.0807851375699e-05 4.41578987480957e-05 8.46192505186366e-05 0.000161184955146849 -4.57355643460401e-06 1.81306894595305e-05 2.63697222560943e-05 5.834854369423e-06 -3.99287423759339e-06 -4.57355643460401e-06 2.90740422331156e-05 -8.93243892276857e-06 -4.45918835774065e-06 4.55425359471545e-06 2.71009007861949e-06 1.81306894595305e-05 -8.93243892276857e-06 3.80181370350025e-05 -1.03644166773564e-05 -3.82103162099707e-06 3.0807851375699e-05 2.63697222560943e-05 -4.45918835774065e-06 -1.03644166773564e-05 8.25882667799521e-05 1.23527706524042e-05 4.41578987480957e-05 5.834854369423e-06 4.55425359471545e-06 -3.82103162099707e-06 1.23527706524042e-05 0.000128983219456593 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1270 0 0 0 0 0 2397 +658 662 0.99999537831302 -0.000296111160170762 0.00302583389840762 -0.00175550049491283 0.000308613774130417 0.999991414285723 -0.00413232529908197 0.00185416978947369 -0.0030245842918238 0.00413324001478722 0.999986884022406 0.00421223254884621 2.99586116697671e-05 1.84197176392214e-05 -8.50295962490809e-06 3.42535278868278e-06 4.5518250886217e-06 -4.29463514069617e-06 1.84197176392214e-05 5.10950535767367e-05 -6.79082989197022e-06 -1.73488416022936e-06 1.21495437346101e-05 -2.4905853443884e-05 -8.50295962490809e-06 -6.79082989197022e-06 1.98717899901801e-05 -1.40936808992866e-06 -2.4302812351854e-06 -1.70196851892298e-06 3.42535278868278e-06 -1.73488416022936e-06 -1.40936808992866e-06 2.28065845591246e-05 6.08393601293862e-06 6.15086406450545e-06 4.5518250886217e-06 1.21495437346101e-05 -2.4302812351854e-06 6.08393601293862e-06 5.42447439897837e-05 -8.32950246369003e-07 -4.29463514069617e-06 -2.4905853443884e-05 -1.70196851892298e-06 6.15086406450545e-06 -8.32950246369003e-07 4.71625967890492e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1327 0 0 0 0 0 2667 +657 630 0.996275428409341 -0.0122422173948135 -0.0853545479810043 0.0262743178822307 0.0228091682909859 0.992026404302676 0.123949001642523 -0.0555300030233301 0.083156554700498 -0.125434210961614 0.98861076573684 -0.0489501879312187 0.000174700497510274 0.000121321819060947 -4.7109380040752e-06 7.16599298842285e-06 4.61567166673864e-05 7.58170031078799e-05 0.000121321819060947 0.000166539494842841 1.53078239028835e-06 9.55147156935102e-06 5.19017038414852e-05 5.40248322172045e-05 -4.7109380040752e-06 1.53078239028835e-06 3.09695347159808e-05 -1.1108019982193e-05 -6.20428140731778e-06 -1.23364544532747e-07 7.16599298842285e-06 9.55147156935102e-06 -1.1108019982193e-05 4.00626318139607e-05 -1.28368192521018e-05 4.2798291062318e-06 4.61567166673864e-05 5.19017038414852e-05 -6.20428140731778e-06 -1.28368192521018e-05 0.00011931678473481 2.56801185830605e-05 7.58170031078799e-05 5.40248322172045e-05 -1.23364544532747e-07 4.2798291062318e-06 2.56801185830605e-05 0.000161216370237391 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1192 0 0 0 0 0 2367 +658 631 0.99555203506255 -0.0266594194363708 -0.0903627181869338 0.0230866047653219 0.0377424655030033 0.991657152933289 0.123254198038031 -0.0416691642556017 0.0863229504857785 -0.126116479460692 0.988252488905477 -0.0325555452173249 0.000280031942901286 8.3183225258085e-05 2.0883714317986e-05 -1.00981502735492e-05 4.23693217341826e-05 0.00012148444957185 8.3183225258085e-05 9.35959908216426e-05 -3.27624757962543e-06 5.39583895372031e-06 1.18025042855806e-05 1.94746105225288e-05 2.0883714317986e-05 -3.27624757962543e-06 2.20968190607831e-05 -5.10697483236098e-06 1.78677981411065e-06 6.92866977174472e-06 -1.00981502735492e-05 5.39583895372031e-06 -5.10697483236098e-06 3.07356331019079e-05 -1.15556834523862e-05 -1.2016327699248e-05 4.23693217341826e-05 1.18025042855806e-05 1.78677981411065e-06 -1.15556834523862e-05 0.000107968642018236 2.83622470828499e-05 0.00012148444957185 1.94746105225288e-05 6.92866977174472e-06 -1.2016327699248e-05 2.83622470828499e-05 0.000175849057874919 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1287 0 0 0 0 0 2141 +657 631 0.99600473521802 -0.0268488515926242 -0.0851686949027603 0.0266885209041534 0.0376563977678221 0.991066043369909 0.127945665758029 -0.0462604825788607 0.0809726072844007 -0.130641635198244 0.988117503145398 -0.0384813348124711 0.000261367303339312 0.00020481324787635 2.51837502206243e-05 1.79764460415512e-05 2.65474166054431e-05 9.48195844412128e-05 0.00020481324787635 0.000280690496768013 2.7584340591591e-05 3.20049650894285e-05 1.70464179403291e-05 2.24815908757782e-05 2.51837502206243e-05 2.7584340591591e-05 2.42168285237592e-05 -3.2010282109822e-06 -1.50012731240803e-06 -1.93573530995728e-06 1.79764460415512e-05 3.20049650894285e-05 -3.2010282109822e-06 2.9406131470411e-05 4.70569974906199e-06 3.31945738097443e-06 2.65474166054431e-05 1.70464179403291e-05 -1.50012731240803e-06 4.70569974906199e-06 5.14332114466884e-05 7.66660852266951e-07 9.48195844412128e-05 2.24815908757782e-05 -1.93573530995728e-06 3.31945738097443e-06 7.66660852266951e-07 0.000161757355254351 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1239 0 0 0 0 0 2119 +657 659 0.999998236640797 -0.000451415850168719 0.00182289303775451 -0.0028096230804596 0.000458508612174164 0.999992319484196 -0.00389239546681031 0.00545667335310016 -0.00182112194798688 0.00389322441527582 0.999990763116592 0.00510338503405201 5.86303149987389e-05 2.10106918731337e-05 -8.82643301602907e-06 5.28756417538019e-06 1.6827294719364e-05 3.75061594800142e-05 2.10106918731337e-05 9.91955234192839e-05 -9.66641003887613e-06 1.3516635278972e-05 8.63635919902122e-06 -2.3822739209424e-05 -8.82643301602907e-06 -9.66641003887613e-06 2.19964848073006e-05 -7.1051133546219e-06 -1.27184918119671e-06 -4.24838943841955e-06 5.28756417538019e-06 1.3516635278972e-05 -7.1051133546219e-06 2.95466119907697e-05 4.80691593107136e-06 2.92777496129227e-06 1.6827294719364e-05 8.63635919902122e-06 -1.27184918119671e-06 4.80691593107136e-06 5.0048088674504e-05 1.21276754075141e-05 3.75061594800142e-05 -2.3822739209424e-05 -4.24838943841955e-06 2.92777496129227e-06 1.21276754075141e-05 9.72260714153917e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1310 0 0 0 0 0 2678 +658 661 0.999998763076086 0.000528199330944595 -0.00148150321096208 0.00117437247351204 -0.000526572856898588 0.999999258526217 0.00109802916292966 -0.00392939684234574 0.0014820820907355 -0.00109724768537283 0.999998299738651 -0.00788327298519899 3.82763253425044e-05 2.92123596354337e-06 -1.38081293153088e-05 1.47766023796732e-07 9.63866194151471e-06 1.52387393400525e-05 2.92123596354337e-06 8.49887599906565e-05 -7.54832853761377e-06 8.87365310430402e-06 7.68168398489636e-06 -3.29376794939807e-05 -1.38081293153088e-05 -7.54832853761377e-06 2.08765089687252e-05 -4.33780110564042e-06 -1.639676569475e-06 -1.62816597760323e-06 1.47766023796732e-07 8.87365310430402e-06 -4.33780110564042e-06 2.92877714986062e-05 3.31006082470153e-06 -9.66569977699721e-06 9.63866194151471e-06 7.68168398489636e-06 -1.639676569475e-06 3.31006082470153e-06 4.73273668243715e-05 1.25062121590691e-05 1.52387393400525e-05 -3.29376794939807e-05 -1.62816597760323e-06 -9.66569977699721e-06 1.25062121590691e-05 7.39856953200465e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1190 0 0 0 0 0 2734 +659 662 0.999985177082747 -0.000930060183861499 0.00536475561797286 0.00378349596417258 0.000920812117570809 0.99999808639447 0.00172606849288343 -0.00108776150935309 -0.00536635069952669 -0.00172110297553215 0.99998411991627 -0.00384187931161468 2.68134621779963e-05 1.20771896875977e-05 -1.00901096953163e-05 2.12725322126156e-07 8.98651354360909e-06 -4.93592007069931e-07 1.20771896875977e-05 5.12807785404751e-05 -6.0233288756814e-06 2.20404672275219e-06 -4.46972307038004e-06 -2.56150912066238e-05 -1.00901096953163e-05 -6.0233288756814e-06 2.67418050213741e-05 -6.11721134400758e-06 -5.54670203148202e-06 -8.05741036250019e-06 2.12725322126156e-07 2.20404672275219e-06 -6.11721134400758e-06 2.83380946321825e-05 9.14078835997754e-06 2.21612702034772e-06 8.98651354360909e-06 -4.46972307038004e-06 -5.54670203148202e-06 9.14078835997754e-06 4.50031695399668e-05 1.33413611774502e-05 -4.93592007069931e-07 -2.56150912066238e-05 -8.05741036250019e-06 2.21612702034772e-06 1.33413611774502e-05 4.8544762275201e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1338 0 0 0 0 0 2624 +659 630 0.996075311783684 -0.0118705819296299 -0.0877101051173003 0.0280013241012352 0.0230686865219914 0.991533525501747 0.12778538065141 -0.067282772952014 0.0854506229186541 -0.129307219793512 0.987915904291497 -0.0438263468036579 0.000106535904418519 7.2767527984102e-05 -5.56117409181245e-07 1.81328678205992e-06 2.6895913046314e-05 2.28608428535689e-05 7.2767527984102e-05 0.000113265116534568 -4.06537643283802e-06 1.41366916888327e-05 1.84914467115128e-05 2.12076672144841e-05 -5.56117409181245e-07 -4.06537643283802e-06 2.90898387865576e-05 -1.10296718116537e-05 -4.46626585804762e-06 -3.11847149159038e-07 1.81328678205992e-06 1.41366916888327e-05 -1.10296718116537e-05 4.15606674171979e-05 -1.7179152989821e-05 7.42065028334555e-06 2.6895913046314e-05 1.84914467115128e-05 -4.46626585804762e-06 -1.7179152989821e-05 9.99388849808542e-05 5.39234894431218e-07 2.28608428535689e-05 2.12076672144841e-05 -3.11847149159038e-07 7.42065028334555e-06 5.39234894431218e-07 0.00010240447403857 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1247 0 0 0 0 0 2378 +659 631 0.995321139231051 -0.0269434150004397 -0.0927894508439235 0.0231319780368921 0.0386206648410134 0.991221080860534 0.126448460271027 -0.0451130403074793 0.0885679064167204 -0.129440415812796 0.987623868032344 -0.0354361602136195 0.000100284205247767 6.14068784355929e-05 2.48142840174046e-06 -9.5092435424703e-06 3.59345253407781e-05 1.05045932668423e-05 6.14068784355929e-05 0.000110919736596827 1.25554710201736e-06 4.13419949421365e-06 3.26341072125084e-05 -8.25462820932906e-06 2.48142840174046e-06 1.25554710201736e-06 2.30699399530246e-05 -5.41664061344266e-06 2.55536624508201e-08 -5.18440078044489e-06 -9.5092435424703e-06 4.13419949421365e-06 -5.41664061344266e-06 3.06967397759045e-05 -1.68765784828047e-06 -7.78566412628313e-06 3.59345253407781e-05 3.26341072125084e-05 2.55536624508201e-08 -1.68765784828047e-06 7.38799083881834e-05 4.66536149700808e-06 1.05045932668423e-05 -8.25462820932906e-06 -5.18440078044489e-06 -7.78566412628313e-06 4.66536149700808e-06 7.90400383194014e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1295 0 0 0 0 0 2126 +660 662 0.999982235234272 -0.000295008703415933 0.00595333400160867 0.00123018605470486 0.000277258460746873 0.999995514889422 0.00298216847050875 0.00123901650592001 -0.00595418706590122 -0.00298046488076291 0.999977831997029 -0.0038254356717301 2.4127331253997e-05 8.04154402597843e-06 -8.12120519412825e-06 1.99398555608578e-06 8.02343440728624e-07 -3.58984213231966e-07 8.04154402597843e-06 5.59144559272211e-05 -6.31623187879567e-06 2.57996217787083e-06 1.13236527410516e-05 -2.99955611825575e-05 -8.12120519412825e-06 -6.31623187879567e-06 2.11446871810563e-05 -4.48982995696965e-06 -6.33858060471677e-06 -2.88623665185828e-06 1.99398555608578e-06 2.57996217787083e-06 -4.48982995696965e-06 2.4882296499935e-05 5.11689345503676e-06 7.98826079619251e-07 8.02343440728624e-07 1.13236527410516e-05 -6.33858060471677e-06 5.11689345503676e-06 5.79112214407553e-05 1.10022865777858e-06 -3.58984213231966e-07 -2.99955611825575e-05 -2.88623665185828e-06 7.98826079619251e-07 1.10022865777858e-06 4.75038835413271e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1337 0 0 0 0 0 2653 +658 630 0.996126759443689 -0.0129614031910435 -0.0869682766733652 0.0230788839190702 0.0232053694775033 0.992762026172752 0.117834927830357 -0.0526549130795205 0.0848114965534057 -0.119396655801961 0.989217594180208 -0.0418649393301523 0.000132506154648227 8.47445478052441e-05 1.43438605297246e-06 3.19947968405753e-06 3.56829249757331e-05 2.62087536521518e-05 8.47445478052441e-05 0.00012534189213335 -8.05334775569952e-07 1.00172864132153e-05 2.46689056053128e-05 1.44520034630658e-06 1.43438605297246e-06 -8.05334775569952e-07 2.80217184283565e-05 -4.11075672817484e-06 -4.40741181812501e-06 -1.93673011343476e-06 3.19947968405753e-06 1.00172864132153e-05 -4.11075672817484e-06 3.48182702343766e-05 -1.34008998462815e-05 -9.16251878869981e-08 3.56829249757331e-05 2.46689056053128e-05 -4.40741181812501e-06 -1.34008998462815e-05 0.000103960054848787 2.04458704751959e-05 2.62087536521518e-05 1.44520034630658e-06 -1.93673011343476e-06 -9.16251878869981e-08 2.04458704751959e-05 0.000133085864823692 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1226 0 0 0 0 0 2387 +660 664 0.999994712831826 0.000187937603047339 -0.00324638073117544 -0.000180522083126866 -0.00018811298156091 0.999999980863967 -5.37175209632567e-05 0.000552957778212067 0.00324637057351046 5.43279233083128e-05 0.999994729049397 0.00239510283661972 3.37233994163654e-05 7.48194977243864e-07 -1.41654261842825e-05 7.31502486278265e-06 3.81757082866577e-06 7.85719014401739e-06 7.48194977243864e-07 8.17628287480849e-05 5.65940683491588e-06 4.69467892150346e-07 9.61152726848076e-06 -3.9369961952485e-05 -1.41654261842825e-05 5.65940683491588e-06 2.64657711456647e-05 -7.1492777104466e-06 -5.17714841445676e-06 -1.03798565311714e-05 7.31502486278265e-06 4.69467892150346e-07 -7.1492777104466e-06 2.58437457715579e-05 8.73719828183045e-06 8.05436352591019e-06 3.81757082866577e-06 9.61152726848076e-06 -5.17714841445676e-06 8.73719828183045e-06 4.43589901059883e-05 -2.81956305983999e-06 7.85719014401739e-06 -3.9369961952485e-05 -1.03798565311714e-05 8.05436352591019e-06 -2.81956305983999e-06 5.57669387245032e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1321 0 0 0 0 0 2618 +660 630 0.995740425913032 -0.0113612599443044 -0.0914982293545109 0.0252487166279188 0.0233582964092509 0.991089070452417 0.131136739392978 -0.056728976333018 0.0891930164945121 -0.132715395498195 0.987132832807403 -0.0439102999148782 9.7936009896542e-05 5.68353492667197e-05 -6.73117102495776e-06 4.42697891102448e-07 3.15392669638235e-05 2.18420124057039e-05 5.68353492667197e-05 0.00011158303518323 -5.3585841879093e-06 9.16895977500516e-06 3.49609871142029e-05 -4.23863517180839e-06 -6.73117102495776e-06 -5.3585841879093e-06 3.09147427745665e-05 -1.1037242939774e-05 -9.78977824069526e-06 -1.00086504408127e-06 4.42697891102448e-07 9.16895977500516e-06 -1.1037242939774e-05 2.89633300049668e-05 -3.46077614967527e-07 -2.18038366117058e-07 3.15392669638235e-05 3.49609871142029e-05 -9.78977824069526e-06 -3.46077614967527e-07 8.59630983344617e-05 6.92667467908927e-06 2.18420124057039e-05 -4.23863517180839e-06 -1.00086504408127e-06 -2.18038366117058e-07 6.92667467908927e-06 8.73362956327843e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1268 0 0 0 0 0 2360 +659 661 0.999995987258229 0.000267598562885536 -0.00282025857835916 -0.00043545637401458 -0.000272575233879347 0.999998406334304 -0.00176437852919488 -0.00351829833742498 0.00281978193865101 0.00176514018184105 0.999994466539669 0.00440127935791925 5.94009088896492e-05 1.82877007393866e-05 -1.6284320554743e-05 7.20352370474221e-08 2.46195840704896e-05 4.86289227899735e-05 1.82877007393866e-05 6.70254708562432e-05 -6.60067700829675e-06 3.21120757330372e-06 -1.54903818408396e-06 -3.08267094970644e-05 -1.6284320554743e-05 -6.60067700829675e-06 2.32192707892701e-05 -3.81721911863111e-06 -6.07040258819599e-06 -8.65025238395281e-06 7.20352370474221e-08 3.21120757330372e-06 -3.81721911863111e-06 2.8237439875704e-05 5.7081439111316e-06 -1.63792035846677e-06 2.46195840704896e-05 -1.54903818408396e-06 -6.07040258819599e-06 5.7081439111316e-06 5.34051969274542e-05 4.05481680384647e-05 4.86289227899735e-05 -3.08267094970644e-05 -8.65025238395281e-06 -1.63792035846677e-06 4.05481680384647e-05 0.000144082776989457 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1165 0 0 0 0 0 2733 +661 663 0.999960846279208 -0.00147449024201469 0.00872535312162603 0.001326489676301 0.00143049970830724 0.999986246762854 0.00504578593736541 -0.00178855856811162 -0.0087326730819033 -0.00503310676097628 0.999949202838413 -0.00973959166149534 2.37085481830628e-05 7.96117109021171e-07 -1.09343974154724e-05 4.62997549954854e-07 3.79606570643828e-06 1.06530444923774e-05 7.96117109021171e-07 5.80170926287944e-05 -8.04640355541742e-06 3.78287106125861e-06 6.8753464840311e-06 -2.8825793257249e-05 -1.09343974154724e-05 -8.04640355541742e-06 2.58626339607331e-05 -8.2526654759449e-06 -6.19766197361276e-07 -5.51763698199664e-06 4.62997549954854e-07 3.78287106125861e-06 -8.2526654759449e-06 3.00965017884167e-05 4.51858703148055e-06 3.51203422634302e-06 3.79606570643828e-06 6.8753464840311e-06 -6.19766197361276e-07 4.51858703148055e-06 4.50956124251064e-05 9.87625508559608e-06 1.06530444923774e-05 -2.8825793257249e-05 -5.51763698199664e-06 3.51203422634302e-06 9.87625508559608e-06 5.67932739311536e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1310 0 0 0 0 0 2701 +661 664 0.999985172058814 -0.000308186802819513 -0.00543697373531565 -0.00227536444025019 0.000284602768191815 0.999990550533105 -0.00433795409873275 0.000790052180148597 0.0054382592590168 0.00433634239802885 0.999975810442852 0.00777210395190171 4.94496396087156e-05 -5.18019622740503e-06 -1.30854725643707e-05 1.65079412600219e-06 1.25830349650428e-05 4.6932145160469e-05 -5.18019622740503e-06 0.000100045662624652 4.67577594778693e-06 3.781440923052e-06 6.45257116280956e-06 -6.09572695928988e-05 -1.30854725643707e-05 4.67577594778693e-06 2.58190317732082e-05 -5.10767808039467e-06 -5.18529275674315e-06 -1.55408487915537e-05 1.65079412600219e-06 3.781440923052e-06 -5.10767808039467e-06 2.76748706761094e-05 1.07109331665888e-05 -7.66436262806076e-07 1.25830349650428e-05 6.45257116280956e-06 -5.18529275674315e-06 1.07109331665888e-05 4.21221088571692e-05 1.64681460741626e-05 4.6932145160469e-05 -6.09572695928988e-05 -1.55408487915537e-05 -7.66436262806076e-07 1.64681460741626e-05 0.000135294149615576 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1279 0 0 0 0 0 2663 +659 663 0.999996262464751 -0.000989423068920278 -0.00254874449869461 -0.00245869569731852 0.000984548415833572 0.999997685324018 -0.001913115527978 0.00231215139884593 0.00255063147981382 0.00191059901528272 0.999994921932335 0.00521145948210734 2.68618518777951e-05 1.10619442679293e-05 -1.25012138028231e-05 3.23065435299208e-06 3.85850606981522e-06 5.24289813739125e-06 1.10619442679293e-05 4.96772557174569e-05 -8.47048473190376e-06 -3.29197828461595e-07 1.07897106244483e-05 -1.37505595493688e-05 -1.25012138028231e-05 -8.47048473190376e-06 1.94833426503821e-05 -6.06909360486369e-06 -5.10304278259253e-06 -3.61112922500407e-06 3.23065435299208e-06 -3.29197828461595e-07 -6.06909360486369e-06 2.47425660847941e-05 7.08922678526215e-06 7.25830025859997e-06 3.85850606981522e-06 1.07897106244483e-05 -5.10304278259253e-06 7.08922678526215e-06 4.78175934090791e-05 5.87082626392525e-06 5.24289813739125e-06 -1.37505595493688e-05 -3.61112922500407e-06 7.25830025859997e-06 5.87082626392525e-06 3.98574612695692e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1320 0 0 0 0 0 2657 +661 665 0.999998210360795 -0.000316535616124124 -0.00186522931887652 -0.00118719849291299 0.000314677360844577 0.999999454012404 -0.000996470297329212 0.00132267253699763 0.00186554371882396 0.000995881568567467 0.999997763980767 0.000927874876539203 4.75384392685179e-05 9.18774996177389e-06 -1.28224837704839e-05 1.91675440280434e-06 1.66204840013377e-05 3.95669179373565e-05 9.18774996177389e-06 9.23226337496429e-05 7.5237052044674e-07 2.81775351177516e-06 1.17992362447102e-05 -2.16156920232148e-05 -1.28224837704839e-05 7.5237052044674e-07 2.52247218872543e-05 -8.97122919561862e-06 -6.28440712267675e-06 -9.94141274473171e-06 1.91675440280434e-06 2.81775351177516e-06 -8.97122919561862e-06 3.03234572647822e-05 1.15607532109198e-05 7.10786902694185e-08 1.66204840013377e-05 1.17992362447102e-05 -6.28440712267675e-06 1.15607532109198e-05 4.4005285707537e-05 2.53757244280727e-05 3.95669179373565e-05 -2.16156920232148e-05 -9.94141274473171e-06 7.10786902694185e-08 2.53757244280727e-05 0.000110371877241306 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1201 0 0 0 0 0 2658 +662 664 0.999963977559426 -0.000935136502365242 0.00843617823737513 0.00313397269708568 0.000916188485260393 0.999997049882199 0.00224962787097025 -0.00326801412297313 -0.00843825705879443 -0.00224181770452327 0.999961884309192 -0.00436125146231143 2.96435806233036e-05 -6.26810940992875e-06 -1.09958325956247e-05 5.52370109430298e-06 -1.88975548328655e-06 9.10150997376507e-06 -6.26810940992875e-06 9.02942962145221e-05 6.54109258564819e-06 -9.09181157458327e-07 1.72830256779595e-05 -4.5676569307636e-05 -1.09958325956247e-05 6.54109258564819e-06 2.6261621981995e-05 -8.37097874716977e-06 3.02146571467184e-06 -1.28246878119103e-05 5.52370109430298e-06 -9.09181157458327e-07 -8.37097874716977e-06 2.81087817718628e-05 1.18938457714981e-06 5.9494247678905e-06 -1.88975548328655e-06 1.72830256779595e-05 3.02146571467184e-06 1.18938457714981e-06 5.51136191967639e-05 -7.70955164332168e-06 9.10150997376507e-06 -4.5676569307636e-05 -1.28246878119103e-05 5.9494247678905e-06 -7.70955164332168e-06 5.14220228931036e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1319 0 0 0 0 0 2665 +662 666 0.999989391309 -0.00046996569861192 -0.0045821830711494 -0.00990127039811456 0.000452694619311674 0.999992792979173 -0.00376949032301955 0.0141965380939912 0.00458392157841364 0.00376737600404047 0.999982397115573 0.00686075254763974 3.6028375269868e-05 1.62275881103273e-05 -6.47504799146353e-06 2.05086180169955e-06 9.05615789812998e-06 1.75790950090661e-05 1.62275881103273e-05 5.6033789118622e-05 -4.94593512811044e-06 8.52082300770924e-06 -5.80477297604517e-06 -1.63346715952992e-05 -6.47504799146353e-06 -4.94593512811044e-06 2.36518405259204e-05 -5.92063227430877e-06 -7.24462250523009e-06 -3.18409518272319e-06 2.05086180169955e-06 8.52082300770924e-06 -5.92063227430877e-06 3.95687790564596e-05 -2.62183162439462e-06 -4.19020482826816e-08 9.05615789812998e-06 -5.80477297604517e-06 -7.24462250523009e-06 -2.62183162439462e-06 8.55265216271157e-05 4.7610328624305e-06 1.75790950090661e-05 -1.63346715952992e-05 -3.18409518272319e-06 -4.19020482826816e-08 4.7610328624305e-06 8.2260146229233e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2622 +663 665 0.999993191946111 -0.000818579724461871 0.0035980534545809 0.00342947480608962 0.000811320618127578 0.999997633693194 0.00201850609772398 -0.00776029210452417 -0.00359969724864782 -0.00201557318067286 0.999991489786024 -0.0081389082198705 3.60445242813817e-05 -9.53843478208108e-06 -1.40654623503337e-05 4.89265216663861e-06 1.747522489162e-06 2.14178858437321e-05 -9.53843478208108e-06 0.000104439935072572 -1.11294759992455e-06 9.84041396945403e-06 1.32633133294396e-05 -3.42128641768465e-05 -1.40654623503337e-05 -1.11294759992455e-06 2.45459184845224e-05 -1.07269143150607e-05 -6.06849392838831e-06 -7.97917217544043e-06 4.89265216663861e-06 9.84041396945403e-06 -1.07269143150607e-05 3.42836788744616e-05 5.93019783606054e-06 4.77101851209838e-06 1.747522489162e-06 1.32633133294396e-05 -6.06849392838831e-06 5.93019783606054e-06 6.49048335768539e-05 4.96996174387518e-06 2.14178858437321e-05 -3.42128641768465e-05 -7.97917217544043e-06 4.77101851209838e-06 4.96996174387518e-06 6.69376638618443e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1220 0 0 0 0 0 2692 +660 663 0.999997974871847 -0.000220091177369302 -0.0020004529685437 -0.00175930009188572 0.000220480283399007 0.99999995681982 0.000194290512480997 0.00525144610428789 0.00200041012053614 -0.000194731179455241 0.999997980217519 0.00317667000394476 2.97018616680709e-05 1.19235070356611e-05 -1.29659872061801e-05 5.41853130235259e-06 5.16003364934528e-06 8.0838668575423e-07 1.19235070356611e-05 6.40470737786675e-05 -9.99229696119094e-06 2.33795382022839e-06 2.2002465185993e-05 -2.964943430587e-05 -1.29659872061801e-05 -9.99229696119094e-06 2.31667196541148e-05 -7.17602158072255e-06 -5.1918367646795e-06 -4.43812323158706e-06 5.41853130235259e-06 2.33795382022839e-06 -7.17602158072255e-06 2.43133849700635e-05 5.28926403001113e-06 5.38801478264627e-06 5.16003364934528e-06 2.2002465185993e-05 -5.1918367646795e-06 5.28926403001113e-06 5.21176592148854e-05 1.8266149470159e-06 8.0838668575423e-07 -2.964943430587e-05 -4.43812323158706e-06 5.38801478264627e-06 1.8266149470159e-06 5.262471578598e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1325 0 0 0 0 0 2622 +664 666 0.999970827796041 -0.00112442142653439 -0.00755507997015457 -0.0104797657720814 0.00109007189595255 0.999989058527956 -0.00454912822785246 0.0119612592396291 0.00756011244370974 0.00454075993940882 0.999961112343381 0.00661137644353213 5.18116924542351e-05 3.13363194890182e-05 -6.76990887543433e-06 3.78560219625357e-06 -4.40351770704552e-07 2.22819808795655e-05 3.13363194890182e-05 8.01887943608649e-05 -5.84053664032132e-06 1.5534993409222e-05 -2.56343729685483e-05 -5.95379260818346e-06 -6.76990887543433e-06 -5.84053664032132e-06 2.20427263932135e-05 -4.19829838861389e-06 -3.58008036273357e-06 6.57685020874577e-07 3.78560219625357e-06 1.5534993409222e-05 -4.19829838861389e-06 3.73992170150974e-05 -4.02027953652348e-06 3.38344539043282e-06 -4.40351770704552e-07 -2.56343729685483e-05 -3.58008036273357e-06 -4.02027953652348e-06 7.29850097864473e-05 -2.87823615221577e-06 2.22819808795655e-05 -5.95379260818346e-06 6.57685020874577e-07 3.38344539043282e-06 -2.87823615221577e-06 7.89565309997801e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 804 0 0 0 0 0 2626 +661 630 0.996226133064669 -0.0126533628992791 -0.0858684121569471 0.0266597891222167 0.023362939164671 0.991895711596318 0.124888231592981 -0.0591203845071537 0.0835922536638658 -0.12642305851455 0.988448048914672 -0.0469213578510056 0.000125164188239049 7.47551431589172e-05 -1.32173494015858e-05 -2.72052089570806e-06 2.28869314730007e-05 5.02623590308078e-05 7.47551431589172e-05 0.000132728283881641 -1.33415957358635e-05 1.38872671951856e-05 1.94423916130439e-05 1.74028198066186e-05 -1.32173494015858e-05 -1.33415957358635e-05 2.82771374844628e-05 -1.05186778260304e-05 -6.50084977155271e-06 -3.83205234568973e-06 -2.72052089570806e-06 1.38872671951856e-05 -1.05186778260304e-05 3.98983926661387e-05 -1.07359935810999e-05 -2.35188610814962e-07 2.28869314730007e-05 1.94423916130439e-05 -6.50084977155271e-06 -1.07359935810999e-05 9.28798920018967e-05 4.00621393706148e-06 5.02623590308078e-05 1.74028198066186e-05 -3.83205234568973e-06 -2.35188610814962e-07 4.00621393706148e-06 0.000120638869946493 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1180 0 0 0 0 0 2402 +663 667 0.99997376247421 0.000983562439535183 -0.00717683552127728 0.000796719758985612 -0.000979053626686621 0.999999321184418 0.000631731509296825 -0.00725959857285535 0.00717745199691392 -0.000624688427379817 0.999974046636812 -0.00611621553112165 3.3217552629152e-05 8.57732262596111e-06 -1.43952644205377e-05 5.68548487278959e-06 3.78634214053748e-06 1.68529480057071e-05 8.57732262596111e-06 6.02000772477047e-05 -6.25348874590423e-06 4.13682694506934e-06 8.85618668129973e-06 -2.61030263352781e-05 -1.43952644205377e-05 -6.25348874590423e-06 2.34487715227491e-05 -7.8405632150173e-06 -5.86228591158628e-06 -1.03497600667601e-05 5.68548487278959e-06 4.13682694506934e-06 -7.8405632150173e-06 3.53617833399051e-05 -7.81643600260217e-06 6.99150668059926e-06 3.78634214053748e-06 8.85618668129973e-06 -5.86228591158628e-06 -7.81643600260217e-06 8.69359273750908e-05 1.37312953016907e-06 1.68529480057071e-05 -2.61030263352781e-05 -1.03497600667601e-05 6.99150668059926e-06 1.37312953016907e-06 8.11953817394786e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 991 0 0 0 0 0 2528 +664 667 0.99997891566138 -0.000561856203689351 -0.00646935470486772 -0.00432261544485667 0.000549675090874521 0.999998073221467 -0.00188451867833609 -0.00222695926755654 0.00647040106836434 0.00188092290137084 0.999977297761831 0.00351840358125958 3.08004224735697e-05 4.50889189217484e-06 -1.52216941407702e-05 2.42173651303733e-06 9.72809908252767e-06 6.91323993057509e-06 4.50889189217484e-06 6.79352378061207e-05 -1.05312189538771e-05 9.72751842378776e-06 -8.49969359124889e-06 -2.41320775944558e-05 -1.52216941407702e-05 -1.05312189538771e-05 2.49306544438594e-05 -9.28165219823412e-06 -4.78635671620732e-06 -4.36335817665105e-06 2.42173651303733e-06 9.72751842378776e-06 -9.28165219823412e-06 4.21181844312796e-05 -1.4696885818032e-05 -2.33659056992624e-06 9.72809908252767e-06 -8.49969359124889e-06 -4.78635671620732e-06 -1.4696885818032e-05 9.4986973169161e-05 1.33733158299206e-05 6.91323993057509e-06 -2.41320775944558e-05 -4.36335817665105e-06 -2.33659056992624e-06 1.33733158299206e-05 5.30414335698347e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 994 0 0 0 0 0 2530 +662 665 0.999999097313106 -0.00126509695415054 0.00045266176175031 0.000499662479392608 0.00126477326990708 0.999998944817259 0.000714641828788067 -0.00301501471458492 -0.00045356537531034 -0.000714068669193683 0.999999642192129 0.000944817262034806 3.47681382509609e-05 -9.45680087563378e-06 -1.8718749008669e-05 8.46665774223003e-06 5.47415008219443e-06 1.69633353283045e-05 -9.45680087563378e-06 8.52493998415073e-05 7.7123789916981e-06 -8.71819683886834e-06 9.44949994837517e-06 -2.90274937412319e-05 -1.8718749008669e-05 7.7123789916981e-06 2.92762515453748e-05 -1.22779482156062e-05 -8.25081143342092e-06 -1.12704427879193e-05 8.46665774223003e-06 -8.71819683886834e-06 -1.22779482156062e-05 2.8701004428947e-05 1.02053094736704e-05 8.15193755674248e-06 5.47415008219443e-06 9.44949994837517e-06 -8.25081143342092e-06 1.02053094736704e-05 5.11478335788505e-05 3.53876464081589e-06 1.69633353283045e-05 -2.90274937412319e-05 -1.12704427879193e-05 8.15193755674248e-06 3.53876464081589e-06 5.75294289003044e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1226 0 0 0 0 0 2672 +665 669 0.999977292322172 0.000717732634511279 -0.00670072383269365 -0.000159809506126625 -0.000739960298767227 0.99999423055984 -0.0033153138296753 -0.00168194287119292 0.00669830566433927 0.00332019681620615 0.999972054106678 0.00635298647889664 2.49034415414519e-05 1.72833968227405e-06 -1.08961640785077e-05 -9.7975626101512e-08 3.64825059126024e-06 5.27541639322353e-06 1.72833968227405e-06 5.47489581097811e-05 -5.00610475796961e-06 -1.56350088145434e-06 1.03285978573814e-05 -2.90605969087943e-05 -1.08961640785077e-05 -5.00610475796961e-06 2.43557779441746e-05 -6.84127256187418e-06 -9.71106598561227e-06 -7.21158749870218e-06 -9.7975626101512e-08 -1.56350088145434e-06 -6.84127256187418e-06 3.05376599322215e-05 2.92608669366268e-06 5.30400209228273e-06 3.64825059126024e-06 1.03285978573814e-05 -9.71106598561227e-06 2.92608669366268e-06 6.70118942815195e-05 1.34251053070451e-05 5.27541639322353e-06 -2.90605969087943e-05 -7.21158749870218e-06 5.30400209228273e-06 1.34251053070451e-05 4.79533887743998e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1208 0 0 0 0 0 2721 +666 668 0.999954815481196 -0.00085639528302718 0.00946750141731731 0.00968142877752447 0.000820953913263159 0.999992644000227 0.00374672925458052 -0.0202481850686715 -0.00947064045563944 -0.00373878757808469 0.999948162874859 -0.0148069923190358 2.53694760513649e-05 6.20900120494121e-06 -8.72011625186637e-06 -7.58041719538758e-08 1.20665068796513e-05 5.40645407867761e-06 6.20900120494121e-06 4.80638688282509e-05 -3.84166840313463e-06 -5.72368469933069e-07 1.03178674820277e-05 -2.96430201314597e-05 -8.72011625186637e-06 -3.84166840313463e-06 2.20604663596297e-05 -3.3221277225933e-06 -3.4958045573008e-06 -5.66070991800651e-06 -7.58041719538758e-08 -5.72368469933069e-07 -3.3221277225933e-06 3.29390955941963e-05 -1.46410849648164e-05 -3.4566108030939e-06 1.20665068796513e-05 1.03178674820277e-05 -3.4958045573008e-06 -1.46410849648164e-05 0.000111301486104991 1.68493905950427e-05 5.40645407867761e-06 -2.96430201314597e-05 -5.66070991800651e-06 -3.4566108030939e-06 1.68493905950427e-05 5.47292727611288e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1025 0 0 0 0 0 2631 +665 668 0.999993385050685 -0.000666468197851209 0.00357570622585959 -0.000145309529366056 0.000664401542824708 0.999999611590672 0.000579127874541265 0.00132186566030255 -0.0035760908073328 -0.000576748338906579 0.999993439446425 0.00244116912451304 3.22235176948457e-05 4.35192980875582e-06 -1.03819340555715e-05 -1.25643549475438e-06 1.36501673279702e-05 3.51832315180987e-06 4.35192980875582e-06 7.03259459196131e-05 -6.47349938508433e-06 1.19724044309949e-05 -1.98629389433801e-06 -3.32380563544889e-05 -1.03819340555715e-05 -6.47349938508433e-06 2.58056609978075e-05 -9.49148979719043e-06 -3.12802546902187e-06 -3.16558687081664e-06 -1.25643549475438e-06 1.19724044309949e-05 -9.49148979719043e-06 3.73484678204363e-05 -2.70687737350073e-06 -3.74924031608195e-06 1.36501673279702e-05 -1.98629389433801e-06 -3.12802546902187e-06 -2.70687737350073e-06 6.21995603725871e-05 1.27557074666888e-05 3.51832315180987e-06 -3.32380563544889e-05 -3.16558687081664e-06 -3.74924031608195e-06 1.27557074666888e-05 5.11509624142608e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1126 0 0 0 0 0 2524 +663 666 0.999991973528081 -0.00112539787296177 0.0038453035043913 -0.00775931585568145 0.00112768452178895 0.999999188609421 -0.000592543770255442 0.0148909054794507 -0.00384463353684958 0.000596875303462992 0.999992431237777 -0.00118833052060343 3.24301534321502e-05 1.63533986622237e-05 -7.71266902362172e-06 2.17298172166794e-06 8.15166388413595e-06 8.70735745964467e-06 1.63533986622237e-05 5.0549955609571e-05 -8.2545217830069e-06 3.38000451837424e-06 3.76011495528994e-06 -1.9343453673691e-05 -7.71266902362172e-06 -8.2545217830069e-06 2.10144982804325e-05 -3.10754798384586e-06 -6.48728597351795e-06 -2.22485423595773e-06 2.17298172166794e-06 3.38000451837424e-06 -3.10754798384586e-06 2.78016689268917e-05 -1.03370718774122e-06 4.26944400508645e-06 8.15166388413595e-06 3.76011495528994e-06 -6.48728597351795e-06 -1.03370718774122e-06 7.26154067561373e-05 4.75426984730918e-06 8.70735745964467e-06 -1.9343453673691e-05 -2.22485423595773e-06 4.26944400508645e-06 4.75426984730918e-06 6.50404002786846e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 823 0 0 0 0 0 2619 +664 668 0.999852473628646 0.00106349914798939 -0.0171435103826671 -0.00230036876250554 -0.001165518107785 0.999981667012205 -0.00594198679159151 -0.00106715344555438 0.0171368767930103 0.00596109126362351 0.999835382872965 0.0123562746757573 2.71270270089425e-05 4.63626730496111e-06 -8.32774356073263e-06 3.42572972279433e-06 3.71517760232235e-06 9.76730052155429e-06 4.63626730496111e-06 5.16037888102055e-05 -6.67586821505309e-06 6.12700383241793e-06 -5.30313989562721e-06 -1.57010073569587e-05 -8.32774356073263e-06 -6.67586821505309e-06 2.34703839181992e-05 -7.04592383882276e-06 -7.68798226710197e-06 -5.67555673350453e-06 3.42572972279433e-06 6.12700383241793e-06 -7.04592383882276e-06 3.19351854710726e-05 -3.17314678218131e-06 6.41545952255731e-06 3.71517760232235e-06 -5.30313989562721e-06 -7.68798226710197e-06 -3.17314678218131e-06 6.28044893809981e-05 1.9816354557087e-06 9.76730052155429e-06 -1.57010073569587e-05 -5.67555673350453e-06 6.41545952255731e-06 1.9816354557087e-06 5.66296528929765e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1147 0 0 0 0 0 2582 +666 670 0.999914660210989 -0.000330065380405415 0.0130599905048508 0.0050174797139117 0.000279363961940241 0.999992418889107 0.00388382802006267 -0.0082152129990584 -0.0130611734127874 -0.00387984808430855 0.999907171955439 -0.0129398557507953 3.35409260557576e-05 5.63886017638898e-06 -1.10180681542876e-05 2.39677849808066e-06 1.0091669582086e-05 8.06225553775703e-06 5.63886017638898e-06 7.87609291578453e-05 -2.2354591783055e-06 1.05255541419912e-06 7.25240805583165e-06 -4.04166238460521e-05 -1.10180681542876e-05 -2.2354591783055e-06 2.79213889638383e-05 -6.16971303771531e-06 -4.30364232975161e-06 -6.52997271824822e-06 2.39677849808066e-06 1.05255541419912e-06 -6.16971303771531e-06 2.64844264503433e-05 1.16971525323199e-05 2.98170629967596e-06 1.0091669582086e-05 7.25240805583165e-06 -4.30364232975161e-06 1.16971525323199e-05 3.8994437316042e-05 8.39505021242007e-06 8.06225553775703e-06 -4.04166238460521e-05 -6.52997271824822e-06 2.98170629967596e-06 8.39505021242007e-06 5.95756308350261e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1067 0 0 0 0 0 2613 +667 669 0.99993883659283 -0.000867214460176066 0.0110259245624805 0.00861480696454033 0.000853319125342227 0.999998835956596 0.0012648841541265 -0.0126608552288329 -0.0110270086536547 -0.00125539815719821 0.999938412631308 -0.00395483746966508 2.50315693859241e-05 8.66637334263938e-06 -9.74124759542764e-06 4.51663441831904e-06 2.74836383187541e-06 4.82183915327761e-06 8.66637334263938e-06 3.64697114026942e-05 -5.55780599859389e-06 -5.41534401497478e-06 1.35344106304583e-05 -2.5375152515657e-05 -9.74124759542764e-06 -5.55780599859389e-06 2.13479300531269e-05 -5.73884097375066e-06 -4.73734092227331e-06 -7.28695115242933e-06 4.51663441831904e-06 -5.41534401497478e-06 -5.73884097375066e-06 2.98874931578779e-05 -5.0029183993324e-06 1.20876710740424e-05 2.74836383187541e-06 1.35344106304583e-05 -4.73734092227331e-06 -5.0029183993324e-06 7.1374249279343e-05 -3.33841184987258e-06 4.82183915327761e-06 -2.5375152515657e-05 -7.28695115242933e-06 1.20876710740424e-05 -3.33841184987258e-06 5.6688752264177e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1150 0 0 0 0 0 2718 +667 670 0.999982809999824 0.000326593363025075 0.0058543182037546 0.00280854309827678 -0.000325886696584405 0.999999939498095 -0.000121662104575007 -0.000794137639709998 -0.00585435758359308 0.000119752168783233 0.999982855931391 -0.000785722942912105 2.50902823295189e-05 6.14493727074811e-06 -6.93636452759483e-06 1.01068391690476e-06 6.77145230678874e-06 3.47566941369307e-07 6.14493727074811e-06 5.99434959739657e-05 -5.19956876617998e-06 6.9975658641667e-07 1.34826139821823e-05 -3.0547279023904e-05 -6.93636452759483e-06 -5.19956876617998e-06 2.39009090424126e-05 -6.58044478239188e-06 -2.17726906511088e-06 -6.11248544617853e-06 1.01068391690476e-06 6.9975658641667e-07 -6.58044478239188e-06 2.72246509483996e-05 2.12063198157057e-06 2.63790127292913e-06 6.77145230678874e-06 1.34826139821823e-05 -2.17726906511088e-06 2.12063198157057e-06 5.1593632993751e-05 1.16815605296258e-06 3.47566941369307e-07 -3.0547279023904e-05 -6.11248544617853e-06 2.63790127292913e-06 1.16815605296258e-06 4.59910520167273e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1159 0 0 0 0 0 2594 +665 667 0.99999447983745 -0.0010218402599721 0.00316166682488869 -0.000691123761503885 0.00101755259922932 0.999998560955911 0.0013574508520504 -0.00815222267817041 -0.00316304937304229 -0.00135422619640548 0.999994080577516 -0.00199621122173496 2.66298396297859e-05 3.87632469276569e-06 -1.14373476426315e-05 4.23431881459323e-06 2.64358238856358e-06 6.17413561501924e-06 3.87632469276569e-06 5.57326747174678e-05 -4.06823502620345e-06 -1.21000622332581e-06 -1.58232763229823e-06 -2.18597106980709e-05 -1.14373476426315e-05 -4.06823502620345e-06 2.79012444579327e-05 -7.97914833861974e-06 -1.11240727134913e-05 -5.60763491329638e-06 4.23431881459323e-06 -1.21000622332581e-06 -7.97914833861974e-06 3.86358171305498e-05 -6.09612971233681e-06 9.33882681414687e-06 2.64358238856358e-06 -1.58232763229823e-06 -1.11240727134913e-05 -6.09612971233681e-06 0.000104315720967931 -3.81847022526908e-06 6.17413561501924e-06 -2.18597106980709e-05 -5.60763491329638e-06 9.33882681414687e-06 -3.81847022526908e-06 5.25997042713007e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 970 0 0 0 0 0 2539 +668 671 0.999971410431093 0.000194300013704839 -0.00755913804318381 -0.000227044843415212 -0.000217582643680364 0.999995235077181 -0.0030793636884432 -0.00726635903566533 0.00755850370406759 0.00308092038800222 0.999966687920812 0.00408446063753506 2.68060145470567e-05 1.5868296154542e-05 -8.65692604614851e-06 -1.47164614527731e-06 1.25526090293748e-05 1.54081739166469e-06 1.5868296154542e-05 5.68650054132457e-05 -4.88233771568544e-06 2.88597859710409e-06 1.66525553673239e-06 -1.88113335722014e-05 -8.65692604614851e-06 -4.88233771568544e-06 2.37325988198092e-05 -6.44169076479846e-06 -6.58697576770775e-06 -4.35367000615658e-06 -1.47164614527731e-06 2.88597859710409e-06 -6.44169076479846e-06 2.79193496476065e-05 -1.29762276919981e-06 1.21190873832028e-07 1.25526090293748e-05 1.66525553673239e-06 -6.58697576770775e-06 -1.29762276919981e-06 5.3872457456758e-05 1.05619864178558e-05 1.54081739166469e-06 -1.88113335722014e-05 -4.35367000615658e-06 1.21190873832028e-07 1.05619864178558e-05 4.23654610651665e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1141 0 0 0 0 0 2652 +667 671 0.999999881788946 -0.00022063502336903 -0.00043329237257061 0.00411982853108517 0.000220149137403785 0.999999347324251 -0.00112110901767231 -0.0117997818995683 0.0004335394456855 0.00112101349620277 0.999999277685884 0.00360034073903726 3.63759896852977e-05 1.29766103268486e-05 -1.15763157985836e-05 3.22857177500315e-06 8.38090742685079e-06 5.28401980902561e-06 1.29766103268486e-05 7.10493446324836e-05 -4.16380834437494e-06 2.85095354477865e-06 8.32755106459964e-06 -3.60918773546072e-05 -1.15763157985836e-05 -4.16380834437494e-06 2.03344037756596e-05 -4.1013873362494e-06 -5.46155114942627e-06 -5.48937618438806e-06 3.22857177500315e-06 2.85095354477865e-06 -4.1013873362494e-06 2.50359357139183e-05 7.9252594343209e-06 4.75182180429444e-06 8.38090742685079e-06 8.32755106459964e-06 -5.46155114942627e-06 7.9252594343209e-06 5.02598728581561e-05 5.53343163308958e-06 5.28401980902561e-06 -3.60918773546072e-05 -5.48937618438806e-06 4.75182180429444e-06 5.53343163308958e-06 6.07828199899186e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1037 0 0 0 0 0 2665 +668 672 0.999903562403871 0.000390871389697954 -0.0138821148102468 -0.00339131244399521 -0.000397338462606008 0.999999813829585 -0.000463101436519902 0.000146848995387694 0.0138819312127057 0.000468572674287024 0.999903531559647 -5.166137937851e-05 3.92254496497688e-05 2.27515148893901e-05 -1.00085136986876e-05 3.73176811728941e-06 9.77990416334792e-06 5.80384938877364e-06 2.27515148893901e-05 6.22214230483224e-05 -1.12637399235636e-05 7.23153383651211e-06 6.11286971485674e-06 -2.00652262128251e-05 -1.00085136986876e-05 -1.12637399235636e-05 2.48271896202935e-05 -6.75058008053526e-06 -8.39913421836677e-06 -5.73737736907538e-06 3.73176811728941e-06 7.23153383651211e-06 -6.75058008053526e-06 3.04790985348518e-05 2.65711409355692e-06 1.10880483438133e-06 9.77990416334792e-06 6.11286971485674e-06 -8.39913421836677e-06 2.65711409355692e-06 6.24980202790515e-05 2.3813770680604e-06 5.80384938877364e-06 -2.00652262128251e-05 -5.73737736907538e-06 1.10880483438133e-06 2.3813770680604e-06 5.23652960145329e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1247 0 0 0 0 0 2590 +666 669 0.999973351427739 0.00111779693178341 -0.00721435821085271 0.000402897348643815 -0.00112865660049382 0.999998235979999 -0.00150138974569881 -0.0056113239052214 0.00721266723572938 0.00150949226881868 0.999972849063632 0.000209575037225788 3.19864285145163e-05 1.39842109842937e-05 -1.23825365602125e-05 8.57834565903775e-06 2.04581537798754e-06 1.02439227731423e-05 1.39842109842937e-05 7.0123734662534e-05 -6.17777342901996e-06 4.04075441822865e-06 8.27844829487563e-06 -2.28553136262492e-05 -1.23825365602125e-05 -6.17777342901996e-06 2.33278894827895e-05 -6.93571462375087e-06 -7.69278664999785e-06 -6.60715161208862e-06 8.57834565903775e-06 4.04075441822865e-06 -6.93571462375087e-06 3.1156944900383e-05 3.11066573983872e-06 1.2931919357326e-05 2.04581537798754e-06 8.27844829487563e-06 -7.69278664999785e-06 3.11066573983872e-06 5.50917888696787e-05 -1.22850428513349e-07 1.02439227731423e-05 -2.28553136262492e-05 -6.60715161208862e-06 1.2931919357326e-05 -1.22850428513349e-07 5.24620643631844e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1063 0 0 0 0 0 2715 +669 672 0.999996520584284 0.000179518608281841 0.00263184201540342 -0.000301372951761757 -0.000184613244661247 0.999998109580548 0.0019356531922639 0.00181023738729092 -0.00263148955435089 -0.00193613233021566 0.999994663312923 -0.00948756151373293 3.44168193560458e-05 1.33828472035496e-05 -1.38722597626314e-05 5.95247281061863e-06 1.18367493289163e-05 9.38758309007334e-06 1.33828472035496e-05 5.74022215577992e-05 -7.34681016524084e-06 2.99254931058048e-06 1.43869336675491e-06 -1.9132197174394e-05 -1.38722597626314e-05 -7.34681016524084e-06 2.57928595042249e-05 -8.2616540874124e-06 -8.95349222816367e-06 -9.94490952782184e-06 5.95247281061863e-06 2.99254931058048e-06 -8.2616540874124e-06 3.01054796880324e-05 8.72264099807425e-06 1.00494610085925e-05 1.18367493289163e-05 1.43869336675491e-06 -8.95349222816367e-06 8.72264099807425e-06 5.28277715272469e-05 7.21560053699718e-06 9.38758309007334e-06 -1.9132197174394e-05 -9.94490952782184e-06 1.00494610085925e-05 7.21560053699718e-06 5.04424217846579e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1262 0 0 0 0 0 2599 +670 672 0.999975615412678 -0.000713803854437666 0.00694687441182269 0.0029655173348741 0.000697620565037007 0.999997038192449 0.00233172294190771 -0.00514740419832226 -0.00694851822934102 -0.00232681980135361 0.999973151641597 -0.00809519066861275 3.02957200932257e-05 4.30739118316714e-06 -1.257845607881e-05 2.74389479558317e-06 3.91626027825474e-06 1.21913543025607e-05 4.30739118316714e-06 6.14494624434167e-05 -6.25909349674635e-06 1.94441698690823e-07 1.62846365872385e-05 -2.69243410621638e-05 -1.257845607881e-05 -6.25909349674635e-06 2.83280159989409e-05 -9.5781123885378e-06 -1.89414386890425e-06 -9.98385844365007e-06 2.74389479558317e-06 1.94441698690823e-07 -9.5781123885378e-06 3.12605007619976e-05 -2.74499695516906e-06 6.75328414711941e-06 3.91626027825474e-06 1.62846365872385e-05 -1.89414386890425e-06 -2.74499695516906e-06 6.45133235823193e-05 4.10621493790531e-06 1.21913543025607e-05 -2.69243410621638e-05 -9.98385844365007e-06 6.75328414711941e-06 4.10621493790531e-06 5.63227237039575e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1265 0 0 0 0 0 2670 +668 670 0.999990594550974 0.00017020933629998 0.00433380183791388 0.00127180185882835 -0.000177245884656853 0.99999866672175 0.00162331100480861 -0.00273064203938894 -0.00433351975706141 -0.00162406388538039 0.999989291454169 -0.00170814134797355 2.83990763769171e-05 8.40386537611171e-06 -8.51013642164344e-06 1.17049792733166e-06 4.94148103951986e-06 -1.37125985586927e-06 8.40386537611171e-06 6.41443922836532e-05 -2.3456410836677e-09 1.45495461895722e-06 1.36891238742192e-06 -3.00308090892626e-05 -8.51013642164344e-06 -2.3456410836677e-09 2.21776078393573e-05 -3.6539513877317e-06 -3.89845545666697e-06 -7.5255205199551e-06 1.17049792733166e-06 1.45495461895722e-06 -3.6539513877317e-06 2.37751945141623e-05 3.14356163964962e-06 7.60203324062224e-07 4.94148103951986e-06 1.36891238742192e-06 -3.89845545666697e-06 3.14356163964962e-06 4.25246004677498e-05 5.30912006950834e-06 -1.37125985586927e-06 -3.00308090892626e-05 -7.5255205199551e-06 7.60203324062224e-07 5.30912006950834e-06 3.93263300793896e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1294 0 0 0 0 0 2602 +670 673 0.999960269792068 4.21533265425584e-05 -0.00891386899565365 -0.00281088029786976 -4.36964969103685e-05 0.999999984093699 -0.000172925467959768 -0.00124968287431726 0.00891386156448325 0.000173308102443997 0.999960255728352 -0.00111721702150282 7.57023141844229e-05 2.2716425127032e-05 -1.34790530213481e-05 6.7726721537612e-06 1.92644275169654e-05 3.45142013908461e-05 2.2716425127032e-05 6.45882098470288e-05 -4.17593337327705e-06 2.2811902301975e-06 7.96185189730531e-06 -1.68475393651358e-05 -1.34790530213481e-05 -4.17593337327705e-06 2.91924394770265e-05 -1.00740944052091e-05 -1.28121098778757e-05 -1.04014828779131e-05 6.7726721537612e-06 2.2811902301975e-06 -1.00740944052091e-05 2.96380702827723e-05 1.20621749502842e-05 9.53493065741644e-06 1.92644275169654e-05 7.96185189730531e-06 -1.28121098778757e-05 1.20621749502842e-05 5.22407667442827e-05 8.78581270129136e-06 3.45142013908461e-05 -1.68475393651358e-05 -1.04014828779131e-05 9.53493065741644e-06 8.78581270129136e-06 9.36445268697143e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1159 0 0 0 0 0 2633 +669 671 0.999976599063251 -0.000533763891475895 0.00682029486182463 0.00344828427368717 0.000525598997923222 0.999999143212225 0.00119888302556675 -0.00741568177301644 -0.00682092893874853 -0.00119527023043598 0.999976022841292 -0.00484539267723432 2.99892163309079e-05 7.65950026168734e-06 -1.11828609093138e-05 2.64870468601995e-06 5.60407663145385e-06 6.70388777904862e-06 7.65950026168734e-06 6.10845333842412e-05 -6.62139809555797e-06 3.2942771095067e-07 4.54302880757918e-06 -2.90376239884845e-05 -1.11828609093138e-05 -6.62139809555797e-06 2.45030890698872e-05 -5.3720017823189e-06 -3.95554630057073e-06 -4.20844255146188e-06 2.64870468601995e-06 3.2942771095067e-07 -5.3720017823189e-06 2.69841570701438e-05 4.12236636231445e-06 1.32707778600589e-07 5.60407663145385e-06 4.54302880757918e-06 -3.95554630057073e-06 4.12236636231445e-06 4.96648110129798e-05 7.88231789020325e-06 6.70388777904862e-06 -2.90376239884845e-05 -4.20844255146188e-06 1.32707778600589e-07 7.88231789020325e-06 4.9370183916079e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1167 0 0 0 0 0 2674 +671 673 0.99990614182331 0.000807215336891782 -0.0136768398185682 -0.000238463150250914 -0.000854366164282214 0.999993711319451 -0.00344200232538387 -0.00456774019446186 0.013673975372225 0.00345336429449674 0.999900543390476 0.00392181116009299 4.76007006222566e-05 1.37859552586978e-05 -8.08172515877793e-06 1.44548169151999e-06 1.42173946253298e-05 1.39011981271365e-05 1.37859552586978e-05 0.000158152277732654 -3.37759739947692e-06 1.52021896818985e-05 1.44639885999028e-05 -5.32233505175029e-05 -8.08172515877793e-06 -3.37759739947692e-06 2.34860893644788e-05 -5.2965907443388e-06 -7.99054158756742e-06 -4.20885534233031e-06 1.44548169151999e-06 1.52021896818985e-05 -5.2965907443388e-06 3.58632112942271e-05 -2.0757736753409e-06 -3.17494456293182e-06 1.42173946253298e-05 1.44639885999028e-05 -7.99054158756742e-06 -2.0757736753409e-06 6.98813751423416e-05 3.46197193105179e-06 1.39011981271365e-05 -5.32233505175029e-05 -4.20885534233031e-06 -3.17494456293182e-06 3.46197193105179e-06 7.92950134232601e-05 0 0 0 0 0 0 10 0 0 0 0 0 0 0 0 0 0 0 1175 0 0 0 0 0 2650 +671 674 0.999986845184523 0.000941713571054098 -0.00504208622054429 0.00062275475017621 -0.000950002487822067 0.999998200986974 -0.00164180330391613 -7.1512406801924e-05 0.00504053104131321 0.00164657170074995 0.999985940825398 -0.000296263670800933 3.25143354028368e-05 -1.44100515627851e-06 -1.32559086190107e-05 8.26417776273754e-06 2.67461352731264e-06 9.72228263054093e-06 -1.44100515627851e-06 7.20184393123163e-05 3.65993582065384e-06 -9.58911197393043e-06 1.24555937901069e-05 -2.50704313318078e-05 -1.32559086190107e-05 3.65993582065384e-06 3.32234842040244e-05 -1.37978787235183e-05 -6.25273896489973e-06 -1.2131233682637e-05 8.26417776273754e-06 -9.58911197393043e-06 -1.37978787235183e-05 3.43606245025717e-05 7.50580169682184e-07 1.37708746887917e-05 2.67461352731264e-06 1.24555937901069e-05 -6.25273896489973e-06 7.50580169682184e-07 5.30131191977183e-05 -3.97804755408907e-06 9.72228263054093e-06 -2.50704313318078e-05 -1.2131233682637e-05 1.37708746887917e-05 -3.97804755408907e-06 5.86704127893196e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1143 0 0 0 0 0 2658 +669 673 0.999864685915519 0.000734814177184832 -0.0164338037954246 -0.00442640879096681 -0.000792405278661786 0.999993567351822 -0.00349819222614895 0.00236432754293938 0.0164311275613043 0.00351074110434652 0.999858836408401 0.00550962781811073 4.88536612109333e-05 -5.17496443616162e-06 -1.63215878513532e-05 1.03664447577074e-05 1.35253329392633e-05 3.30123262372803e-05 -5.17496443616162e-06 8.91597259645528e-05 -1.9762469468341e-07 3.06321213840999e-06 -3.37364109445044e-06 -5.75695623929286e-05 -1.63215878513532e-05 -1.9762469468341e-07 2.85092433172564e-05 -1.25410758291631e-05 -1.11742093172281e-05 -1.28647501526131e-05 1.03664447577074e-05 3.06321213840999e-06 -1.25410758291631e-05 3.86645905789575e-05 1.67050085404478e-05 9.62911246797789e-06 1.35253329392633e-05 -3.37364109445044e-06 -1.11742093172281e-05 1.67050085404478e-05 5.63172965246569e-05 1.31664048399984e-05 3.30123262372803e-05 -5.75695623929286e-05 -1.28647501526131e-05 9.62911246797789e-06 1.31664048399984e-05 0.000101003031441052 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 1161 0 0 0 0 0 2636 +673 675 0.999996037742773 0.000535809338989966 0.00276358591454467 0.00711595870740691 -0.000541892179739743 0.999997431436694 0.00220078914926062 -0.0189801812163608 -0.00276239961271998 -0.00220227799476304 0.999993759540535 -0.00685962119767319 3.77697390674568e-05 1.92217255767367e-05 -1.23507168428118e-05 5.94740327013949e-06 8.3765057800687e-07 5.15151198220485e-06 1.92217255767367e-05 6.65884588735833e-05 -6.32109893033192e-06 -9.78107274356096e-07 8.78999718984081e-06 -2.6923812562766e-05 -1.23507168428118e-05 -6.32109893033192e-06 2.77277697536649e-05 -8.76421556335941e-06 -2.67995832215666e-06 -6.50521062954707e-06 5.94740327013949e-06 -9.78107274356096e-07 -8.76421556335941e-06 3.48204614742475e-05 -6.98285817435597e-06 6.25423950690854e-06 8.3765057800687e-07 8.78999718984081e-06 -2.67995832215666e-06 -6.98285817435597e-06 7.4960938776882e-05 6.71132624660207e-06 5.15151198220485e-06 -2.6923812562766e-05 -6.50521062954707e-06 6.25423950690854e-06 6.71132624660207e-06 5.62028904305189e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1163 0 0 0 0 0 2628 +672 676 0.999996202013432 0.0004442989150494 0.00272002889425158 0.00241024151859435 -0.000453590740297842 0.999994061172377 0.003416412653267 -0.00544486186730095 -0.00271849483203364 -0.0034176334576974 0.999990464738238 -0.00325859314952398 2.38948595122928e-05 6.4613044426713e-06 -1.13428287360107e-05 2.13666221845175e-06 4.51231263903391e-06 5.59291014655005e-06 6.4613044426713e-06 5.74961937434036e-05 -5.21702872957547e-06 -5.19064616405757e-07 7.65738397649859e-06 -2.45990750701845e-05 -1.13428287360107e-05 -5.21702872957547e-06 2.64615285784571e-05 -5.32355108754009e-06 -3.90469402192704e-06 -8.75677093505172e-06 2.13666221845175e-06 -5.19064616405757e-07 -5.32355108754009e-06 2.70183150813171e-05 -7.57215582167376e-08 5.39692356128018e-06 4.51231263903391e-06 7.65738397649859e-06 -3.90469402192704e-06 -7.57215582167376e-08 6.20292827054555e-05 1.33214346840159e-05 5.59291014655005e-06 -2.45990750701845e-05 -8.75677093505172e-06 5.39692356128018e-06 1.33214346840159e-05 4.77911572373102e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1196 0 0 0 0 0 2612 +673 676 0.999970532393164 -0.00132220102671211 0.00756215113426075 0.00421622031610789 0.0013087523289619 0.999997553867875 0.00178309439093148 -0.00816245483514403 -0.00756449024547434 -0.00177314486449809 0.999969816766794 -0.00508520227947851 2.94787473075173e-05 1.25846279791494e-05 -1.28693838038323e-05 4.26738346601681e-06 1.82763557722799e-06 -3.56978290734139e-07 1.25846279791494e-05 6.07896783644134e-05 -9.83746456404795e-06 8.37702317295227e-07 1.70932986845499e-05 -3.05251723407038e-05 -1.28693838038323e-05 -9.83746456404795e-06 2.70667320005651e-05 -9.47957738064376e-06 1.3973239457329e-06 -1.67166313869334e-06 4.26738346601681e-06 8.37702317295227e-07 -9.47957738064376e-06 3.32723905730357e-05 -6.07106654393038e-06 3.94880825702181e-06 1.82763557722799e-06 1.70932986845499e-05 1.3973239457329e-06 -6.07106654393038e-06 5.87392935473335e-05 -3.20567753370895e-06 -3.56978290734139e-07 -3.05251723407038e-05 -1.67166313869334e-06 3.94880825702181e-06 -3.20567753370895e-06 4.50362334640519e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1195 0 0 0 0 0 2616 +674 676 0.999811101265917 0.00122790703858249 -0.0193972686154344 0.00392558939224415 -0.00134576600047511 0.999980707159486 -0.00606417535094686 -0.0167634125284311 0.0193894481434279 0.00608913402050454 0.99979346454534 0.0183040686273959 3.82095161868978e-05 1.40752117967876e-05 -1.16551322490076e-05 7.60531801565335e-06 7.95256898590072e-06 3.65892002223435e-06 1.40752117967876e-05 5.00632056448819e-05 -6.1835499963688e-06 -1.75842471404567e-06 1.38203386948961e-05 -2.22949622602903e-05 -1.16551322490076e-05 -6.1835499963688e-06 2.331030965405e-05 -8.71436615836003e-06 -6.70511979148043e-06 -5.34872968882049e-06 7.60531801565335e-06 -1.75842471404567e-06 -8.71436615836003e-06 3.30672962300719e-05 -2.99744849645102e-06 5.50234116924699e-06 7.95256898590072e-06 1.38203386948961e-05 -6.70511979148043e-06 -2.99744849645102e-06 7.56142165276845e-05 3.09389446707809e-06 3.65892002223435e-06 -2.22949622602903e-05 -5.34872968882049e-06 5.50234116924699e-06 3.09389446707809e-06 4.98973330088018e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1221 0 0 1 0 0 2651 +670 674 0.999976724923057 0.000707974669986719 -0.00678589596324408 0.000210749001406164 -0.000717737473370104 0.999998710856128 -0.00143636311586113 -0.00253161322821333 0.00678487030654495 0.0014412001762223 0.999975943949141 0.00209735561928742 6.00066193843161e-05 4.8854674361244e-05 -1.24782107217358e-05 6.22231775055317e-06 2.20164291675207e-05 5.0257406308981e-06 4.8854674361244e-05 0.000142838923412354 -7.50291359952847e-06 1.73906548835071e-05 1.18526048576097e-05 -3.57569659941183e-05 -1.24782107217358e-05 -7.50291359952847e-06 2.42461479020545e-05 -8.94799984920539e-06 -7.39774742665757e-06 -3.17008430348436e-06 6.22231775055317e-06 1.73906548835071e-05 -8.94799984920539e-06 3.09744161065497e-05 6.50093771892757e-06 -5.41080913339135e-06 2.20164291675207e-05 1.18526048576097e-05 -7.39774742665757e-06 6.50093771892757e-06 4.87957378580741e-05 1.03597749545629e-05 5.0257406308981e-06 -3.57569659941183e-05 -3.17008430348436e-06 -5.41080913339135e-06 1.03597749545629e-05 6.03601025563926e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1139 0 0 0 0 0 2646 +674 677 0.999994607942067 3.41402288180794e-05 -0.00328373586575803 0.000783012866428742 -4.32013971985987e-05 0.99999619197867 -0.00275937706722665 -0.00438849404093221 0.00328362915545734 0.00275950405048307 0.999990801416175 0.00407159790277937 4.47202141934923e-05 2.50430248326196e-05 -1.31535957486084e-05 5.00068732398561e-06 1.16820448278284e-05 1.08443246996982e-05 2.50430248326196e-05 7.03766132837393e-05 -8.43061221051892e-06 -6.00786962767944e-07 9.33091838695298e-06 -2.9559558859055e-05 -1.31535957486084e-05 -8.43061221051892e-06 2.6132717953302e-05 -8.20026840375446e-06 -9.90698328985889e-06 -7.69071771658803e-06 5.00068732398561e-06 -6.00786962767944e-07 -8.20026840375446e-06 2.82398641953838e-05 7.94143162299256e-06 8.57145024695969e-06 1.16820448278284e-05 9.33091838695298e-06 -9.90698328985889e-06 7.94143162299256e-06 6.11059400515073e-05 1.23019198991179e-05 1.08443246996982e-05 -2.9559558859055e-05 -7.69071771658803e-06 8.57145024695969e-06 1.23019198991179e-05 6.6664317570939e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1269 0 0 0 0 0 2621 +674 678 0.999944833496623 -0.000265102376058223 -0.0105004611394836 -0.000680893491532601 0.000247820917776526 0.999998612908119 -0.00164704785286135 -0.00488729269631694 0.0105008832106785 0.00164435475707375 0.999943512179177 0.00683290237000802 5.27988230157451e-05 -2.19822699934219e-05 -1.76469750223407e-05 4.48123230392347e-06 1.69800281657317e-05 4.03236501235283e-05 -2.19822699934219e-05 0.000151109209722484 5.22234976733477e-06 1.00836115253069e-05 -8.829746184442e-06 -0.000104693262673642 -1.76469750223407e-05 5.22234976733477e-06 3.09019619273935e-05 -1.28609834735101e-05 -8.57642275058128e-06 -1.79628009309984e-05 4.48123230392347e-06 1.00836115253069e-05 -1.28609834735101e-05 3.5993406400939e-05 1.12211810724231e-05 4.47565838399876e-06 1.69800281657317e-05 -8.829746184442e-06 -8.57642275058128e-06 1.12211810724231e-05 4.8534143665326e-05 2.10617397745656e-05 4.03236501235283e-05 -0.000104693262673642 -1.79628009309984e-05 4.47565838399876e-06 2.10617397745656e-05 0.000129547688337627 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1259 0 0 0 0 0 2631 +671 675 0.999992332621872 -4.49252514643651e-05 -0.00391569651381064 0.0012450932662567 3.83565394701519e-05 0.999998592105213 -0.0016775924321788 -0.000572485981759586 0.0039157663671838 0.0016774293768754 0.999990926461057 0.000277413994864333 3.90669932997095e-05 4.90261448104719e-06 -1.83592342643594e-05 8.98299790718001e-06 1.20086851249239e-05 7.80609453022289e-06 4.90261448104719e-06 7.32946450489868e-05 -5.78279654996771e-06 2.4401635747975e-06 -1.86587335120833e-06 -2.95843653637018e-05 -1.83592342643594e-05 -5.78279654996771e-06 3.37931037011206e-05 -1.30004110799948e-05 -1.5744334223235e-05 -1.16867203605577e-05 8.98299790718001e-06 2.4401635747975e-06 -1.30004110799948e-05 3.42493673481113e-05 7.60476101082816e-06 9.79846458233142e-06 1.20086851249239e-05 -1.86587335120833e-06 -1.5744334223235e-05 7.60476101082816e-06 6.30318661038283e-05 6.80926483756511e-06 7.80609453022289e-06 -2.95843653637018e-05 -1.16867203605577e-05 9.79846458233142e-06 6.80926483756511e-06 5.5086051511303e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1139 0 0 0 0 0 2598 +675 677 0.999980821935377 0.000309658300387355 -0.00618545658660878 0.00319860500736865 -0.000316255983580721 0.999999382138109 -0.00106569486818637 -0.0124854485710881 0.00618512276358926 0.00106763061787801 0.999980302016626 0.00410037940308069 5.40241761518761e-05 2.15388817230842e-05 -1.7839382902244e-05 6.8382994673813e-06 1.82800003780842e-05 8.46173740581793e-06 2.15388817230842e-05 0.000117949509746279 2.14726954812217e-06 3.68574979871566e-07 2.04549638605822e-05 -6.11621889045006e-05 -1.7839382902244e-05 2.14726954812217e-06 2.99130049133444e-05 -1.07676795037637e-05 -1.3358082243021e-06 -1.46289884919831e-05 6.8382994673813e-06 3.68574979871566e-07 -1.07676795037637e-05 3.81395785157035e-05 -1.81359013974625e-05 2.66445073783141e-06 1.82800003780842e-05 2.04549638605822e-05 -1.3358082243021e-06 -1.81359013974625e-05 0.000104855584120493 1.96918041870554e-05 8.46173740581793e-06 -6.11621889045006e-05 -1.46289884919831e-05 2.66445073783141e-06 1.96918041870554e-05 8.62829202384477e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1274 0 0 0 0 0 2590 +672 674 0.999967118871597 -0.00037567957317061 0.00810061976002407 0.00259812144494225 0.000367088196095499 0.999999368654783 0.00106204345106743 -0.00726933738092003 -0.00810101363376691 -0.00105903488798539 0.999966625454676 -0.00551323753513766 4.47476637242547e-05 1.04732544242719e-05 -9.86016775085478e-06 5.27523476874497e-06 6.32172443362557e-07 1.95421854898254e-05 1.04732544242719e-05 6.98362095792163e-05 1.46553816384073e-07 -5.01267452743114e-06 1.79540972395069e-05 -3.27479341693864e-05 -9.86016775085478e-06 1.46553816384073e-07 2.52793750633459e-05 -1.02609403279199e-05 -3.99551295360543e-06 -3.99729996513423e-06 5.27523476874497e-06 -5.01267452743114e-06 -1.02609403279199e-05 3.27697649707214e-05 2.15957956221266e-07 8.85036958514396e-06 6.32172443362557e-07 1.79540972395069e-05 -3.99551295360543e-06 2.15957956221266e-07 6.3224776517712e-05 -5.22384186776475e-06 1.95421854898254e-05 -3.27479341693864e-05 -3.99729996513423e-06 8.85036958514396e-06 -5.22384186776475e-06 7.88566531675302e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1120 0 0 0 0 0 2710 +672 675 0.999980114472207 -0.000947168114213994 0.0062348642899886 0.00255120233894081 0.000933774521539669 0.999997251192464 0.0021507377012529 -0.00795321979073013 -0.00623688426171931 -0.00214487297527932 0.999978250160785 -0.00366347101834737 4.66231544127642e-05 2.25243431215469e-05 -1.40799563772717e-05 6.92536696407477e-06 1.07496342526027e-05 1.28354382165189e-05 2.25243431215469e-05 0.000107130453275296 -5.02742743858027e-07 -1.75174161663099e-06 2.09611905519571e-05 -6.32867682870037e-05 -1.40799563772717e-05 -5.02742743858027e-07 2.78375031259086e-05 -1.18177543241322e-05 -3.44304038447222e-06 -1.43152249992793e-05 6.92536696407477e-06 -1.75174161663099e-06 -1.18177543241322e-05 3.581890649217e-05 2.01760177159504e-06 7.62079864172449e-06 1.07496342526027e-05 2.09611905519571e-05 -3.44304038447222e-06 2.01760177159504e-06 5.81424335430758e-05 7.73058971916541e-06 1.28354382165189e-05 -6.32867682870037e-05 -1.43152249992793e-05 7.62079864172449e-06 7.73058971916541e-06 0.000106452890351321 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1120 0 0 0 0 0 2634 +675 678 0.999957059706526 -0.000863623023919367 -0.0092267490672894 -0.00218871001922476 0.0008498392387228 0.999998517317472 -0.00149771029463734 -0.00338866270748517 0.00922802884404337 0.00148980472911452 0.999956311028398 -1.43524450065798e-05 4.32230296142758e-05 5.26347956318448e-06 -1.70975986502309e-05 4.81332261230088e-06 1.64104904512112e-05 2.30683178945999e-05 5.26347956318448e-06 6.50068337786176e-05 -2.41892128057612e-06 -1.09739729916826e-06 1.24831919617462e-05 -3.27440548126683e-05 -1.70975986502309e-05 -2.41892128057612e-06 3.10741940949921e-05 -1.39208932415221e-05 -3.06680428750604e-06 -9.00971927909239e-06 4.81332261230088e-06 -1.09739729916826e-06 -1.39208932415221e-05 3.66665169418391e-05 -2.6659832022601e-06 2.35829481369981e-06 1.64104904512112e-05 1.24831919617462e-05 -3.06680428750604e-06 -2.6659832022601e-06 6.71258325673061e-05 1.36201041694793e-05 2.30683178945999e-05 -3.27440548126683e-05 -9.00971927909239e-06 2.35829481369981e-06 1.36201041694793e-05 7.86748775945267e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1274 0 0 0 0 0 2621 +673 677 0.999999767165812 -9.40586175777073e-06 -0.000682334120643481 0.000491827170677883 7.69998879206756e-06 0.999996874928602 -0.00250001474779767 -0.00299487617056795 0.000682355503093747 0.00250000891174369 0.999996642167567 0.00371636798289496 2.43489767075632e-05 5.68744369199896e-06 -1.24915314989136e-05 4.78884677749428e-06 5.0711766736546e-06 6.08136575029599e-06 5.68744369199896e-06 5.34349273214846e-05 -4.57495049230077e-06 2.84219261509474e-06 1.35289615907109e-06 -2.39538652014453e-05 -1.24915314989136e-05 -4.57495049230077e-06 2.31663110596033e-05 -7.6061870917338e-06 -5.84149932967992e-06 -8.00220616907568e-06 4.78884677749428e-06 2.84219261509474e-06 -7.6061870917338e-06 2.92407276164758e-05 3.47655267538086e-06 4.07876864825241e-06 5.0711766736546e-06 1.35289615907109e-06 -5.84149932967992e-06 3.47655267538086e-06 5.38553200523838e-05 1.34533531741197e-05 6.08136575029599e-06 -2.39538652014453e-05 -8.00220616907568e-06 4.07876864825241e-06 1.34533531741197e-05 4.53107761545356e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1273 0 0 0 0 0 2605 +675 679 0.999848314375937 0.00165107938290906 -0.0173384594606638 0.000900289608628844 -0.00174186570981165 0.999984846479752 -0.00522232847650889 -0.00933624849925619 0.017329574243089 0.00525173759235036 0.999836039112821 0.0115678849788942 3.27479300229513e-05 4.37347044851019e-06 -1.10764009719029e-05 4.29487342087431e-06 3.20808751102539e-06 9.29732965672723e-06 4.37347044851019e-06 5.65327325301454e-05 -4.27222521030188e-06 9.67709807717548e-07 1.18606208592948e-06 -2.50737775268422e-05 -1.10764009719029e-05 -4.27222521030188e-06 2.95557940921235e-05 -7.68827541801608e-06 -5.46030242912107e-06 -5.57073185521027e-06 4.29487342087431e-06 9.67709807717548e-07 -7.68827541801608e-06 2.69955505577891e-05 2.99636662724155e-06 1.64946631201851e-06 3.20808751102539e-06 1.18606208592948e-06 -5.46030242912107e-06 2.99636662724155e-06 5.08321016317856e-05 5.82158837369449e-06 9.29732965672723e-06 -2.50737775268422e-05 -5.57073185521027e-06 1.64946631201851e-06 5.82158837369449e-06 5.4055952366566e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1224 0 0 0 0 0 2671 +676 679 0.999999958811786 0.000144081835983622 0.000248227416253391 0.00402234099772065 -0.00014443450906913 0.999998979473019 0.00142133444095571 -0.0109161141927357 -0.000248022374454815 -0.00142137023501849 0.999998959095237 -0.00631930109053851 3.11189323717547e-05 1.43544581815232e-05 -1.03151042192438e-05 2.74108330844328e-06 3.60707199805057e-06 3.33108279133464e-06 1.43544581815232e-05 3.89465724731437e-05 -9.35064553984014e-06 -1.60096959601246e-07 1.03376779617493e-05 -1.27757611348436e-05 -1.03151042192438e-05 -9.35064553984014e-06 2.35346077000164e-05 -3.66324558955558e-06 -8.92876813485515e-06 -1.36564226569489e-06 2.74108330844328e-06 -1.60096959601246e-07 -3.66324558955558e-06 2.50390000022131e-05 1.27179631718446e-06 2.06993076185942e-06 3.60707199805057e-06 1.03376779617493e-05 -8.92876813485515e-06 1.27179631718446e-06 6.58037278427571e-05 1.07258722486057e-06 3.33108279133464e-06 -1.27757611348436e-05 -1.36564226569489e-06 2.06993076185942e-06 1.07258722486057e-06 4.56468921787772e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1223 0 0 0 0 0 2636 +676 680 0.999936311125447 0.00108666679145793 -0.0112335590138456 -0.00209045788833401 -0.00114667344968208 0.999985102426566 -0.00533667170903608 -0.00220365140815898 0.0112275924771522 0.00534921304628769 0.999922660552781 0.00616460827110824 3.33072733403987e-05 1.48692035561241e-05 -1.14628796475593e-05 4.78443607290377e-06 1.95318512597317e-06 -1.1974022543555e-06 1.48692035561241e-05 7.63282241196408e-05 4.30283965802477e-06 -5.95684355845138e-07 6.76828295458178e-06 -3.52790349333997e-05 -1.14628796475593e-05 4.30283965802477e-06 2.9462633108707e-05 -9.71848805245225e-06 -1.64730680566077e-06 -1.24729461706555e-05 4.78443607290377e-06 -5.95684355845138e-07 -9.71848805245225e-06 2.86415215886011e-05 2.63457403345541e-06 7.61070020331115e-06 1.95318512597317e-06 6.76828295458178e-06 -1.64730680566077e-06 2.63457403345541e-06 4.81562169428133e-05 2.31500985041751e-06 -1.1974022543555e-06 -3.52790349333997e-05 -1.24729461706555e-05 7.61070020331115e-06 2.31500985041751e-06 4.82018478046535e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1295 0 0 0 0 0 2570 +677 679 0.999997336925022 -0.000605718296911254 0.00222693695675497 0.00747054126782231 0.00059931600417336 0.999995689093791 0.00287447632819813 -0.0201631287589622 -0.00222866847954464 -0.00287313403429368 0.999993389046962 -0.00689046087633854 3.92485535127496e-05 2.07628866588379e-05 -9.91764268623749e-06 3.98314613382314e-06 3.1019530892214e-06 -4.85064243779194e-07 2.07628866588379e-05 7.57959498605435e-05 8.38847664290966e-07 -1.33741999155645e-06 8.44980050451263e-06 -3.21816277728595e-05 -9.91764268623749e-06 8.38847664290966e-07 2.8198048004896e-05 -7.88923946701218e-06 -4.09160258237048e-06 -7.02800853624148e-06 3.98314613382314e-06 -1.33741999155645e-06 -7.88923946701218e-06 4.13302268359436e-05 -2.9574635990646e-05 1.48321626462586e-06 3.1019530892214e-06 8.44980050451263e-06 -4.09160258237048e-06 -2.9574635990646e-05 0.000131014094171936 1.34429003687837e-05 -4.85064243779194e-07 -3.21816277728595e-05 -7.02800853624148e-06 1.48321626462586e-06 1.34429003687837e-05 5.35403895120505e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1203 0 0 0 0 0 2678 +677 680 0.999968040571916 0.000756328352002523 -0.00795900761321626 0.000381836446580423 -0.00076354341951514 0.99999930031814 -0.000903529012699788 -0.00407785943922652 0.00795831867983385 0.000909577184318227 0.999967918401954 0.00223412530937648 2.77458769780338e-05 -2.86596876180594e-06 -1.10102459149615e-05 2.6193709676796e-06 7.4707907634924e-07 7.58043237786777e-06 -2.86596876180594e-06 7.51462018110394e-05 -2.99911322382889e-06 -2.14838306059154e-06 1.41127055459015e-05 -3.7035311706164e-05 -1.10102459149615e-05 -2.99911322382889e-06 2.7843395634569e-05 -7.63885847854942e-06 -3.80539530115707e-06 -6.33636756467014e-06 2.6193709676796e-06 -2.14838306059154e-06 -7.63885847854942e-06 2.69697170367323e-05 -2.60184343110592e-06 2.11611639685605e-06 7.4707907634924e-07 1.41127055459015e-05 -3.80539530115707e-06 -2.60184343110592e-06 5.97501196854223e-05 -3.92362767642559e-06 7.58043237786777e-06 -3.7035311706164e-05 -6.33636756467014e-06 2.11611639685605e-06 -3.92362767642559e-06 4.72997092877614e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1307 0 0 0 0 0 2615 +678 682 0.999996907386774 0.000598348584383583 -0.00241395854527689 -0.000659444818855604 -0.000606850885148496 0.999993610268854 -0.00352294670223939 0.0025977264502036 0.00241183517055865 0.00352440072000774 0.999990880783757 0.00501289423979544 3.63884469508352e-05 2.96592448079674e-05 -9.46528353353708e-06 1.42460263340034e-06 9.7871814965116e-06 -9.82702445262721e-06 2.96592448079674e-05 9.13206595779796e-05 -3.11830859610606e-06 5.98223445692416e-06 3.56243234131635e-06 -4.67824140810603e-05 -9.46528353353708e-06 -3.11830859610606e-06 2.22886557090236e-05 -4.84445040013771e-06 -4.1298130748977e-06 -6.22538738032048e-06 1.42460263340034e-06 5.98223445692416e-06 -4.84445040013771e-06 2.39214892923507e-05 -3.74534442764521e-07 7.85528815953039e-07 9.7871814965116e-06 3.56243234131635e-06 -4.1298130748977e-06 -3.74534442764521e-07 5.42945454080062e-05 8.84781836062206e-06 -9.82702445262721e-06 -4.67824140810603e-05 -6.22538738032048e-06 7.85528815953039e-07 8.84781836062206e-06 5.47050407696971e-05 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 1307 0 0 2 0 0 2580 +678 680 0.999999210725109 0.000822800485462159 -0.000949499089021436 0.00963194608133492 -0.000822636634357795 0.999999646679698 0.000172943482080272 -0.0248072260850634 0.000949641051525144 -0.000172162252845405 0.999999534270908 -0.00231035511960332 3.52534678566698e-05 1.47177321750808e-05 -1.07977469102566e-05 4.5937568884208e-06 1.27355848479573e-06 -3.88271555152543e-06 1.47177321750808e-05 7.47473832436784e-05 -7.0887846949195e-06 -5.5946992770034e-07 1.74241839568052e-05 -3.67693722863342e-05 -1.07977469102566e-05 -7.0887846949195e-06 2.67510577826613e-05 -7.60878848444125e-06 -1.18434769320808e-05 -6.40309825172312e-06 4.5937568884208e-06 -5.5946992770034e-07 -7.60878848444125e-06 2.95806648154013e-05 -7.29824498499752e-06 5.2934594474701e-06 1.27355848479573e-06 1.74241839568052e-05 -1.18434769320808e-05 -7.29824498499752e-06 9.44516954144108e-05 -1.14646690586659e-08 -3.88271555152543e-06 -3.67693722863342e-05 -6.40309825172312e-06 5.2934594474701e-06 -1.14646690586659e-08 5.21718615640753e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1300 0 0 0 0 0 2632 +679 681 0.999995988656169 -0.000143535989160016 0.00282879285062301 0.00388548986914609 0.000149330662683837 0.999997890965048 -0.00204835685593958 -0.00694163413616981 -0.00282849287167254 0.00204877106478692 0.999993901064001 0.000240482963258304 3.11360730534043e-05 9.85716469101957e-06 -1.15550282815527e-05 4.65582978746707e-06 1.10977595030161e-06 8.94647857303418e-06 9.85716469101957e-06 6.41359031445499e-05 -5.93457112467106e-06 2.76642287058026e-06 1.33119262040315e-05 -2.12800754478871e-05 -1.15550282815527e-05 -5.93457112467106e-06 2.75362177950609e-05 -7.37643409264808e-06 -8.0815014509148e-06 -1.10064832588037e-05 4.65582978746707e-06 2.76642287058026e-06 -7.37643409264808e-06 3.07135218988808e-05 -4.57200236658588e-06 9.02004885877126e-07 1.10977595030161e-06 1.33119262040315e-05 -8.0815014509148e-06 -4.57200236658588e-06 7.97068068406429e-05 1.68438907781354e-05 8.94647857303418e-06 -2.12800754478871e-05 -1.10064832588037e-05 9.02004885877126e-07 1.68438907781354e-05 5.44675449610073e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1273 0 0 0 0 0 2565 +678 681 0.999997537624466 -0.000287268012113576 0.00220050496341228 0.00356831833408347 0.000286339124219562 0.999999869782112 0.000422428295545718 -0.00670098465790309 -0.00220062602700389 -0.000421797164704554 0.99999748966297 -0.00366282871868462 1.98511591596244e-05 9.98019926136935e-06 -8.97264588590506e-06 2.035951969222e-07 3.04526041880941e-06 -1.10676475197179e-06 9.98019926136935e-06 4.91694300369081e-05 -9.8247654852716e-06 5.45408048553247e-06 -5.46879840388693e-06 -2.04486388474947e-05 -8.97264588590506e-06 -9.8247654852716e-06 2.62108533809918e-05 -7.88457519270348e-06 -3.84865407166486e-06 -2.78136470804687e-06 2.035951969222e-07 5.45408048553247e-06 -7.88457519270348e-06 3.40608659522508e-05 -1.29986183036784e-05 -3.33827786317682e-07 3.04526041880941e-06 -5.46879840388693e-06 -3.84865407166486e-06 -1.29986183036784e-05 8.39102157712907e-05 1.40762225000623e-05 -1.10676475197179e-06 -2.04486388474947e-05 -2.78136470804687e-06 -3.33827786317682e-07 1.40762225000623e-05 3.94278928030461e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1298 0 0 0 0 0 2615 +676 678 0.999942042227592 0.00259740565219227 -0.0104482376308769 -0.000197182023569483 -0.00264431336586596 0.99998647645282 -0.00447822713766272 -0.000420477740708371 0.0104364645611632 0.00450559600401055 0.999935387818689 0.00395922711970462 3.24246111296505e-05 1.00543468996327e-05 -1.26268865007491e-05 5.51221471960114e-06 8.09498974888604e-06 1.29634105870672e-05 1.00543468996327e-05 4.74005253734182e-05 -1.06958252929124e-06 -1.57888561868505e-06 4.32432188494016e-06 -1.24705121005957e-05 -1.26268865007491e-05 -1.06958252929124e-06 2.83080830498937e-05 -9.31860766820332e-06 -6.74622750127855e-06 -1.13845557375107e-05 5.51221471960114e-06 -1.57888561868505e-06 -9.31860766820332e-06 3.68882323520167e-05 -1.4323622185902e-05 1.63976100337329e-06 8.09498974888604e-06 4.32432188494016e-06 -6.74622750127855e-06 -1.4323622185902e-05 9.37325300049603e-05 1.66735719954696e-05 1.29634105870672e-05 -1.24705121005957e-05 -1.13845557375107e-05 1.63976100337329e-06 1.66735719954696e-05 5.98853112251014e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1296 0 0 0 0 0 2656 +679 683 0.999993305735977 -0.00120105850581217 0.00345629016419531 -0.000130005269048467 0.00119712778989981 0.999998634657362 0.00113910862758421 -0.00139256848216916 -0.00345765358128118 -0.00113496338108479 0.999993378222994 -0.0071365388056772 4.03698109905417e-05 8.77856660832382e-06 -1.35289821671245e-05 4.42212486940638e-06 1.23528415483464e-05 1.4213008766067e-05 8.77856660832382e-06 8.59529644919486e-05 -3.19885482589616e-06 -2.96085763788704e-06 2.40832778669635e-05 -3.44534810567618e-05 -1.35289821671245e-05 -3.19885482589616e-06 2.98171680898205e-05 -9.13395399380035e-06 -5.78184584776297e-06 -7.08269015141417e-06 4.42212486940638e-06 -2.96085763788704e-06 -9.13395399380035e-06 2.83388088794524e-05 3.73005748188959e-06 5.7348425317465e-08 1.23528415483464e-05 2.40832778669635e-05 -5.78184584776297e-06 3.73005748188959e-06 5.91788146376936e-05 7.39984379324375e-06 1.4213008766067e-05 -3.44534810567618e-05 -7.08269015141417e-06 5.7348425317465e-08 7.39984379324375e-06 6.08149980157634e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1145 0 0 0 0 0 2526 +680 682 0.999957636568782 0.000548110956406579 -0.0091882883148103 0.00536375498639639 -0.00058874299494358 0.999990058291254 -0.00442003397495225 -0.0133673951816494 0.00918577429847465 0.00442525626752783 0.999948017977687 0.00837813145880891 3.21231252775878e-05 1.05979594505427e-05 -1.04749276572555e-05 1.8840983478243e-06 3.01188773423919e-06 3.45331029796058e-07 1.05979594505427e-05 6.51051286669373e-05 -2.87314163492703e-06 4.9470666174412e-06 -7.64538211661671e-06 -3.89382116005031e-05 -1.04749276572555e-05 -2.87314163492703e-06 2.47139191792138e-05 -1.79912163026838e-06 -1.27096609978943e-05 -1.06055418954291e-05 1.8840983478243e-06 4.9470666174412e-06 -1.79912163026838e-06 3.14721889247714e-05 -1.90077479132919e-05 -1.64532096966417e-06 3.01188773423919e-06 -7.64538211661671e-06 -1.27096609978943e-05 -1.90077479132919e-05 0.000119238339093239 2.2538624170269e-05 3.45331029796058e-07 -3.89382116005031e-05 -1.06055418954291e-05 -1.64532096966417e-06 2.2538624170269e-05 5.90984733742553e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1294 0 0 0 0 0 2605 +680 684 0.999998231328659 -0.000123541515706151 -0.00187671975719891 0.000870772653115526 0.000122846488823761 0.999999923836993 -0.000370452085610633 0.00169677471073352 0.00187676538047444 0.000370220881969968 0.999998170342429 0.0010178472711381 3.66400231087018e-05 1.0844844084755e-05 -1.69255098855961e-05 4.28602275288111e-06 5.95991925563501e-06 -5.74368402025173e-06 1.0844844084755e-05 8.16532500454102e-05 -6.44125583094691e-06 4.8684756495732e-06 3.37257928379157e-06 -3.98810283342433e-05 -1.69255098855961e-05 -6.44125583094691e-06 2.83271859381628e-05 -7.08854532493643e-06 -2.29621249940715e-06 -2.4330019377692e-06 4.28602275288111e-06 4.8684756495732e-06 -7.08854532493643e-06 2.65200415037264e-05 3.23890789221936e-06 -1.50402597683631e-06 5.95991925563501e-06 3.37257928379157e-06 -2.29621249940715e-06 3.23890789221936e-06 4.78529189732192e-05 7.69552777712369e-06 -5.74368402025173e-06 -3.98810283342433e-05 -2.4330019377692e-06 -1.50402597683631e-06 7.69552777712369e-06 4.69966079620646e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1268 0 0 0 0 0 2563 +677 681 0.999996853047867 0.000356540457679852 0.00248329886737608 -0.000874891701612035 -0.000356695142382187 0.999999934471736 6.18473939207488e-05 0.00564867409148327 -0.00248327665355168 -6.27329799330369e-05 0.999996914696058 -0.00538549121239351 2.64808908253134e-05 1.0167054746518e-05 -1.23127295198162e-05 1.28133099594772e-06 5.54451157563613e-06 5.86834376693592e-07 1.0167054746518e-05 5.95366522975062e-05 -5.49781194334964e-06 1.2639921446076e-06 1.89836516070767e-06 -2.67309003561945e-05 -1.23127295198162e-05 -5.49781194334964e-06 2.6509662016106e-05 -5.06635595797845e-06 -4.05025874438127e-06 -5.53346306197387e-06 1.28133099594772e-06 1.2639921446076e-06 -5.06635595797845e-06 2.58112647057162e-05 -2.82566691449355e-06 1.72479057726836e-06 5.54451157563613e-06 1.89836516070767e-06 -4.05025874438127e-06 -2.82566691449355e-06 6.2064809748176e-05 5.78172936169293e-06 5.86834376693592e-07 -2.67309003561945e-05 -5.53346306197387e-06 1.72479057726836e-06 5.78172936169293e-06 4.47078428431657e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1306 0 0 0 0 0 2572 +681 685 0.99997286221552 0.000406503721797831 -0.00735592191530582 0.000577959295463433 -0.000418543052251551 0.999998575437489 -0.00163522007860179 -0.00321245334718702 0.00735524671328732 0.00163825447236228 0.999971607830978 0.00461099344000809 2.63084768456115e-05 1.11864139767155e-05 -9.15461470692697e-06 1.85299505437149e-06 4.46060771237017e-06 -2.44279384064123e-06 1.11864139767155e-05 4.78533609623627e-05 -4.83582099050853e-06 -6.53926359792375e-07 5.95906962923934e-06 -2.0466377388584e-05 -9.15461470692697e-06 -4.83582099050853e-06 2.85593453949567e-05 -8.84241031122157e-06 -1.65067703260332e-08 -5.27167367386375e-06 1.85299505437149e-06 -6.53926359792375e-07 -8.84241031122157e-06 2.48040505648454e-05 2.81487431562539e-06 3.67297980575562e-06 4.46060771237017e-06 5.95906962923934e-06 -1.65067703260332e-08 2.81487431562539e-06 4.35132803713042e-05 5.46961218238609e-06 -2.44279384064123e-06 -2.0466377388584e-05 -5.27167367386375e-06 3.67297980575562e-06 5.46961218238609e-06 3.69822491184658e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1275 0 0 0 0 0 2637 +679 682 0.999981675395521 -0.000977381189507585 -0.0059744120360363 -0.00120524099279798 0.000979853106950677 0.999999435549977 0.000410837700930417 -0.00335037338889202 0.00597400711873845 -0.000416684218687756 0.999982068645837 0.00110400591278508 7.41461589354972e-05 2.2050961694701e-05 -1.50268869057887e-05 3.220972111461e-06 2.28948300589904e-05 2.4038248132722e-05 2.2050961694701e-05 0.000133782954090041 -7.56656041790081e-07 -4.77341787212421e-07 3.49276870181392e-05 -6.33412751567513e-05 -1.50268869057887e-05 -7.56656041790081e-07 2.94101842402036e-05 -9.0375128235638e-06 -5.70740040081402e-06 -1.09518407803624e-05 3.220972111461e-06 -4.77341787212421e-07 -9.0375128235638e-06 3.24325141034749e-05 2.98169173035648e-06 4.637160569331e-06 2.28948300589904e-05 3.49276870181392e-05 -5.70740040081402e-06 2.98169173035648e-06 7.51673281031788e-05 4.96506286668899e-06 2.4038248132722e-05 -6.33412751567513e-05 -1.09518407803624e-05 4.637160569331e-06 4.96506286668899e-06 8.43611483752424e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1272 0 0 0 0 0 2576 +680 683 0.999999994770178 -9.89389850723013e-05 -2.58982699585322e-05 0.00118852287213671 9.89452647856671e-05 0.999999965680617 0.000242587301571979 -0.00300998843283205 2.58742677283106e-05 -0.000242589862814469 0.99999997024034 -0.00110715828408151 0.000100798106360668 4.77430327301634e-05 -9.63116711663711e-06 -4.02831078828226e-06 3.12274709437962e-05 2.99841120495894e-05 4.77430327301634e-05 0.000162026502881474 2.36308459763015e-06 2.2949828144734e-06 3.03672868913538e-05 -6.98109948682252e-05 -9.63116711663711e-06 2.36308459763015e-06 2.38454461127504e-05 -5.72633649536796e-06 -8.80670466105532e-06 -1.27725049083796e-05 -4.02831078828226e-06 2.2949828144734e-06 -5.72633649536796e-06 2.95481878697114e-05 2.5255040826834e-06 -6.26254946227119e-06 3.12274709437962e-05 3.03672868913538e-05 -8.80670466105532e-06 2.5255040826834e-06 7.68351913625469e-05 1.92529394048225e-05 2.99841120495894e-05 -6.98109948682252e-05 -1.27725049083796e-05 -6.26254946227119e-06 1.92529394048225e-05 0.000111295885086861 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1133 0 0 0 0 0 2504 +681 684 0.999998886794891 9.69617086782653e-05 -0.00148896185511916 0.00075128390512025 -9.82239448547204e-05 0.999999635895868 -0.000847679296066049 -0.000987551772835973 0.00148887912054904 0.000847824604132274 0.999998532215125 0.00118462519311861 3.04194497923082e-05 1.64314951398787e-05 -1.52533293718623e-05 6.56699781804016e-06 5.36985596915307e-06 -4.2808787249282e-06 1.64314951398787e-05 6.78409634842196e-05 -5.62346691593796e-06 1.59122455383127e-06 8.91165272397808e-06 -3.39516202090119e-05 -1.52533293718623e-05 -5.62346691593796e-06 2.85339202224795e-05 -8.89633326574317e-06 -1.72512461363482e-06 -5.11296828152756e-06 6.56699781804016e-06 1.59122455383127e-06 -8.89633326574317e-06 2.70291460254837e-05 -5.92426668280788e-07 3.68431521568223e-06 5.36985596915307e-06 8.91165272397808e-06 -1.72512461363482e-06 -5.92426668280788e-07 4.4090779922226e-05 1.40447371173528e-06 -4.2808787249282e-06 -3.39516202090119e-05 -5.11296828152756e-06 3.68431521568223e-06 1.40447371173528e-06 4.26591096693634e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1287 0 0 0 0 0 2557 +682 684 0.999996469272553 1.08736359103344e-05 0.00265731522269144 0.0066978953873238 -1.74843087598856e-05 0.999996905477691 0.00248771568742818 -0.0174560206247919 -0.00265727994905556 -0.00248775336530195 0.999993374951287 -0.00557588415390557 2.66170694158945e-05 1.23672870598465e-05 -1.209576506594e-05 4.37074053903062e-06 2.79948168988919e-06 2.81809247237049e-06 1.23672870598465e-05 3.55168654230945e-05 -9.18016308446142e-06 -2.2600539193071e-07 8.34688201210053e-06 -1.22263755862672e-05 -1.209576506594e-05 -9.18016308446142e-06 2.13541418308844e-05 -5.75029417190419e-06 -1.59110678239684e-07 -4.22692628933496e-06 4.37074053903062e-06 -2.2600539193071e-07 -5.75029417190419e-06 3.55883931171033e-05 -1.79067369377151e-05 6.87497016743052e-06 2.79948168988919e-06 8.34688201210053e-06 -1.59110678239684e-07 -1.79067369377151e-05 8.70214561201816e-05 4.75401856071626e-06 2.81809247237049e-06 -1.22263755862672e-05 -4.22692628933496e-06 6.87497016743052e-06 4.75401856071626e-06 3.68046241504505e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1261 0 0 0 0 0 2561 +681 683 0.999997536875153 0.000695177290527225 -0.00210783589514671 0.00379677417047661 -0.000705704175553401 0.999987263190238 -0.00499754328780576 -0.0124701941321039 0.00210433486943979 0.00499901848682531 0.999985290686281 0.0065332342324521 5.51549622246741e-05 2.43789619531156e-05 -1.12216468227783e-05 2.7871098362122e-06 1.79629089423259e-05 1.81796305236995e-05 2.43789619531156e-05 0.000104296108914477 -1.88825940626527e-06 -2.40320213483383e-06 3.23267390141575e-05 -3.26272329626379e-05 -1.12216468227783e-05 -1.88825940626527e-06 2.56391244760209e-05 -9.99569635592867e-06 -2.09209954023509e-06 -1.254551113875e-05 2.7871098362122e-06 -2.40320213483383e-06 -9.99569635592867e-06 3.4957186749822e-05 -1.16117213515539e-05 5.69254310983908e-06 1.79629089423259e-05 3.23267390141575e-05 -2.09209954023509e-06 -1.16117213515539e-05 8.32153522024768e-05 1.15756864976226e-05 1.81796305236995e-05 -3.26272329626379e-05 -1.254551113875e-05 5.69254310983908e-06 1.15756864976226e-05 6.62618786136865e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1133 0 0 0 0 0 2568 +682 686 0.999933299636611 -0.000458457468132198 -0.0115406279980378 -0.00372743477005582 0.000398979463708738 0.999986630379991 -0.00515556753988181 -0.0034847143093118 0.0115428373126679 0.0051506191880839 0.999920113823476 0.010926344148577 3.59994465447851e-05 1.34827456884151e-05 -1.39877764157633e-05 4.26895190367958e-06 8.53534453348314e-06 1.19942531942651e-05 1.34827456884151e-05 7.61568304021183e-05 -8.15852958778386e-06 -5.05193778289751e-07 1.81396316802667e-05 -3.02823248997391e-05 -1.39877764157633e-05 -8.15852958778386e-06 3.06823495708498e-05 -1.23593737782424e-05 -3.24964529118883e-06 -4.37990880643925e-06 4.26895190367958e-06 -5.05193778289751e-07 -1.23593737782424e-05 3.34618700257244e-05 5.9698945873222e-06 5.97626954782582e-06 8.53534453348314e-06 1.81396316802667e-05 -3.24964529118883e-06 5.9698945873222e-06 5.34958022323722e-05 3.58223476489247e-06 1.19942531942651e-05 -3.02823248997391e-05 -4.37990880643925e-06 5.97626954782582e-06 3.58223476489247e-06 6.61374250935062e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1182 0 0 0 0 0 2592 +682 685 0.999956456152602 -0.000171501962007846 0.00933040115999382 0.00444949266994464 0.000148007479760769 0.999996817144033 0.00251868926031918 -0.0081860205672464 -0.00933080342282064 -0.00251719861773754 0.999953298818802 -0.0090151180963895 2.64384527863187e-05 9.84736371570137e-06 -1.01797195029019e-05 2.48491357379162e-06 7.9099961988518e-06 2.32361107351702e-06 9.84736371570137e-06 5.7966135020731e-05 -6.93372943099559e-06 3.81698133094204e-06 3.37287873380214e-06 -2.53975510364118e-05 -1.01797195029019e-05 -6.93372943099559e-06 2.89958978552666e-05 -9.81332146920266e-06 -3.99339305919752e-06 -7.41655977223581e-06 2.48491357379162e-06 3.81698133094204e-06 -9.81332146920266e-06 3.16965375321921e-05 -3.79625859948749e-06 1.09022565225503e-06 7.9099961988518e-06 3.37287873380214e-06 -3.99339305919752e-06 -3.79625859948749e-06 5.55239042392106e-05 1.15675943591471e-05 2.32361107351702e-06 -2.53975510364118e-05 -7.41655977223581e-06 1.09022565225503e-06 1.15675943591471e-05 4.21787936494623e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1267 0 0 0 0 0 2587 +683 686 0.999997931509879 0.000289410839680893 -0.00201326037314269 0.00426573455042943 -0.000291157830577226 0.999999581332575 -0.000867503195029453 -0.0105284837394552 0.00201300846542805 0.000868087577130295 0.999997597107551 0.000219240445651013 3.21738339542826e-05 7.76513659204946e-06 -1.2777406160936e-05 2.91317644972017e-06 -4.53584740553299e-06 3.86389900585181e-06 7.76513659204946e-06 7.3894528267642e-05 -1.07182842826514e-05 -3.16416677893352e-06 2.32374379930473e-05 -3.3549963085325e-05 -1.2777406160936e-05 -1.07182842826514e-05 2.88575188858904e-05 -8.33691958779184e-06 -3.21673085774553e-06 -9.41197731676918e-06 2.91317644972017e-06 -3.16416677893352e-06 -8.33691958779184e-06 2.78390390938076e-05 -1.22229544426347e-06 6.82856751654067e-06 -4.53584740553299e-06 2.32374379930473e-05 -3.21673085774553e-06 -1.22229544426347e-06 6.15847848089639e-05 -2.09693227228499e-06 3.86389900585181e-06 -3.3549963085325e-05 -9.41197731676918e-06 6.82856751654067e-06 -2.09693227228499e-06 5.87035318994958e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1224 0 0 0 0 0 2600 +683 685 0.999980492444094 -0.000385200803819849 0.00623428838017748 0.00510216322470947 0.000377363880742328 0.9999991372702 0.00125819527778809 -0.0136687810305106 -0.00623476765950348 -0.00125581813821656 0.999979775091995 -0.0037125577227576 3.65120542220693e-05 3.16048008629637e-06 -1.3504549482081e-05 6.16523246559451e-06 9.00939233930507e-06 2.10995878695612e-05 3.16048008629637e-06 6.04079533117531e-05 -7.46912166933812e-06 7.23265309289832e-06 5.00617803926902e-06 -4.13259186848696e-05 -1.3504549482081e-05 -7.46912166933812e-06 2.88831394978364e-05 -1.03996578008735e-05 -7.96268230004504e-06 -1.39045066773412e-05 6.16523246559451e-06 7.23265309289832e-06 -1.03996578008735e-05 3.10411352086937e-05 -7.51944940841941e-07 4.85502262870651e-06 9.00939233930507e-06 5.00617803926902e-06 -7.96268230004504e-06 -7.51944940841941e-07 5.63633523368418e-05 1.03609177290569e-05 2.10995878695612e-05 -4.13259186848696e-05 -1.39045066773412e-05 4.85502262870651e-06 1.03609177290569e-05 8.7327964570424e-05 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1233 0 0 0 0 0 2638 +683 687 0.999998143817391 -3.70805615114192e-05 0.00192639217297562 0.000897570724734934 3.33915529749865e-05 0.999998165866597 0.00191498001201795 -0.00120636299975566 -0.00192645964824952 -0.00191491213223907 0.99999631092557 -0.0023390879945695 3.21084387594119e-05 1.20059972185746e-05 -1.038364511865e-05 1.38796458593539e-06 4.75922279114288e-06 5.15624802914656e-07 1.20059972185746e-05 7.81562450162036e-05 -3.82293864439633e-06 1.57759380799478e-06 1.21813492416787e-05 -4.44677764428621e-05 -1.038364511865e-05 -3.82293864439633e-06 2.60654937213029e-05 -6.76921058227582e-06 -1.76176689062559e-06 -6.61276673677647e-06 1.38796458593539e-06 1.57759380799478e-06 -6.76921058227582e-06 2.57117873136795e-05 1.59424046574449e-06 9.27812113278011e-07 4.75922279114288e-06 1.21813492416787e-05 -1.76176689062559e-06 1.59424046574449e-06 4.43840944202926e-05 -3.23687108408133e-06 5.15624802914656e-07 -4.44677764428621e-05 -6.61276673677647e-06 9.27812113278011e-07 -3.23687108408133e-06 6.51406124546723e-05 0 0 0 0 0 0 7 0 0 0 0 0 0 0 0 0 0 0 1140 0 0 0 0 0 2687 +684 688 0.999999516418436 -0.000454092713951858 0.000872331760820644 -0.000256404894225358 0.000453670610944254 0.999999779955751 0.000484015936161318 -0.00267065425942875 -0.000872551356979104 -0.000483619950817257 0.999999502382812 -0.00201780875426199 4.35081097366476e-05 1.6412364944032e-05 -1.7703428016429e-05 7.27963845356186e-06 1.25149655289446e-05 1.36287876797297e-05 1.6412364944032e-05 6.68160002043651e-05 -8.92522225089764e-06 -1.16037519479195e-06 1.16434802154971e-05 -3.1715253571136e-05 -1.7703428016429e-05 -8.92522225089764e-06 2.92690499304656e-05 -9.86039237236692e-06 -8.65285167726095e-06 -1.3709392510514e-05 7.27963845356186e-06 -1.16037519479195e-06 -9.86039237236692e-06 2.90270603960711e-05 1.22279217971333e-05 1.21780535514304e-05 1.25149655289446e-05 1.16434802154971e-05 -8.65285167726095e-06 1.22279217971333e-05 4.27502600246724e-05 1.1054237267193e-05 1.36287876797297e-05 -3.1715253571136e-05 -1.3709392510514e-05 1.21780535514304e-05 1.1054237267193e-05 6.99192470036681e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1130 0 0 0 0 0 2610 +684 687 0.999999011695343 -0.000368522683652869 -0.00135676061568031 0.00118978870623216 0.000372026616415447 0.999996594262339 0.00258322664884068 -0.00749889345764096 0.00135580401729247 -0.00258372884688689 0.999995743061295 -0.00132447648007044 6.71987038850615e-05 1.88982404777033e-05 -1.3548412876237e-05 -6.95894553681963e-07 2.27548536194142e-05 2.20642118513465e-05 1.88982404777033e-05 0.000197312154366488 -8.01875518577628e-06 2.48281355514474e-05 1.20586109077936e-05 -8.4001806517344e-05 -1.3548412876237e-05 -8.01875518577628e-06 2.56271525008979e-05 -9.61133768937095e-06 -5.58687474786036e-06 -7.82496950733359e-06 -6.95894553681963e-07 2.48281355514474e-05 -9.61133768937095e-06 3.9333134843605e-05 -1.17038326139801e-05 -9.65956694146194e-06 2.27548536194142e-05 1.20586109077936e-05 -5.58687474786036e-06 -1.17038326139801e-05 8.80457865548729e-05 1.83136151560588e-05 2.20642118513465e-05 -8.4001806517344e-05 -7.82496950733359e-06 -9.65956694146194e-06 1.83136151560588e-05 0.00010127895786727 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1107 0 0 0 0 0 2602 +684 686 0.999986559011693 -0.000237144504954807 0.00517933957533928 0.00834577941903849 0.000222724353137964 0.999996098281492 0.00278456740890967 -0.0201429663893913 -0.0051799797118739 -0.00278337641651509 0.999982710163485 -0.00541860658748085 4.33764784550301e-05 1.57706169177257e-05 -1.0554045897356e-05 4.26695766400009e-06 1.05716354467414e-06 7.78719829975126e-06 1.57706169177257e-05 5.58292159651806e-05 -1.80620466014393e-06 3.44891659522156e-06 3.40075921441276e-06 -2.05767930164059e-05 -1.0554045897356e-05 -1.80620466014393e-06 2.49136162588619e-05 -5.93165590824395e-06 -2.12434174183811e-06 -6.27040167732181e-06 4.26695766400009e-06 3.44891659522156e-06 -5.93165590824395e-06 3.80119223892164e-05 -3.42511266642714e-05 -2.21314759084925e-07 1.05716354467414e-06 3.40075921441276e-06 -2.12434174183811e-06 -3.42511266642714e-05 0.000130858657447328 1.06356900943285e-05 7.78719829975126e-06 -2.05767930164059e-05 -6.27040167732181e-06 -2.21314759084925e-07 1.06356900943285e-05 4.97502713740651e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1190 0 0 0 0 0 2616 +684 632 0.99289047490322 -0.0374019407971356 -0.113002653380642 -0.00835864963203717 0.0505909212939812 0.99193656758648 0.116199847535955 0.0580311628472794 0.107745364304382 -0.121090630146848 0.98677656830792 -0.0225043558852078 0.000168372806747301 0.000128093230626901 1.67799960805625e-05 -1.43542087209959e-05 7.47704846468341e-05 9.07015154830707e-05 0.000128093230626901 0.000241963468684659 1.8992118431482e-05 -3.96418770800678e-06 0.000119231918060541 4.40634918808906e-05 1.67799960805625e-05 1.8992118431482e-05 2.31253933359039e-05 -6.64982158696355e-06 7.06346361562091e-06 1.1957795780596e-05 -1.43542087209959e-05 -3.96418770800678e-06 -6.64982158696355e-06 5.50488205100325e-05 -7.95526643464345e-05 -3.49140901474723e-05 7.47704846468341e-05 0.000119231918060541 7.06346361562091e-06 -7.95526643464345e-05 0.000335419438254751 0.000110395816125649 9.07015154830707e-05 4.40634918808906e-05 1.1957795780596e-05 -3.49140901474723e-05 0.000110395816125649 0.000191551211248623 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1196 0 0 0 0 0 2037 +685 687 0.999947729241696 0.000199387932527381 -0.0102224766485064 0.00672977776175392 -0.000217316636819518 0.99999844028323 -0.00175277054587928 -0.023193844312688 0.0102221112230428 0.00175490044147894 0.999946212936768 0.000586943915531911 5.10546620513396e-05 7.0604517096096e-06 -1.61073685168255e-05 -1.07531113534497e-06 2.99783418605569e-05 2.75253029267604e-05 7.0604517096096e-06 0.000100030252666328 -9.70934622819657e-06 7.58976937401633e-06 1.2751896994675e-05 -6.23796394943933e-05 -1.61073685168255e-05 -9.70934622819657e-06 2.80429992550209e-05 -7.51383220619209e-06 -1.24236864511084e-05 -8.46431274103573e-06 -1.07531113534497e-06 7.58976937401633e-06 -7.51383220619209e-06 4.55258781774289e-05 -3.55417353994151e-05 -3.61343186997091e-06 2.99783418605569e-05 1.2751896994675e-05 -1.24236864511084e-05 -3.55417353994151e-05 0.000159411078651798 1.84750275046091e-05 2.75253029267604e-05 -6.23796394943933e-05 -8.46431274103573e-06 -3.61343186997091e-06 1.84750275046091e-05 0.000109909874866016 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 1090 0 0 0 0 0 2700 +685 689 0.999996755015012 0.000906211673610469 -0.00238091155833902 0.00285855283320047 -0.000907279234700778 0.99999948836484 -0.000447341535571815 -0.00421795412076675 0.00238050495405933 0.000449500235571788 0.999997065568546 -0.000199913182398741 2.74970528386524e-05 1.10809202334641e-05 -1.34148615547717e-05 6.26847973892198e-06 4.65402198244355e-06 1.8649873938135e-06 1.10809202334641e-05 4.0948407339273e-05 -8.3564306156131e-06 -3.68240217187542e-06 1.52763403853326e-05 -1.15724571183883e-05 -1.34148615547717e-05 -8.3564306156131e-06 2.75645371004682e-05 -8.25413866483439e-06 -2.27613662324116e-06 -5.79291190903742e-06 6.26847973892198e-06 -3.68240217187542e-06 -8.25413866483439e-06 2.83773231981348e-05 4.99566812785181e-07 3.66364604873843e-06 4.65402198244355e-06 1.52763403853326e-05 -2.27613662324116e-06 4.99566812785181e-07 5.58914538065504e-05 -1.01405959106773e-06 1.8649873938135e-06 -1.15724571183883e-05 -5.79291190903742e-06 3.66364604873843e-06 -1.01405959106773e-06 3.1042276558783e-05 0 0 0 0 0 0 7 0 0 0 0 0 0 0 0 0 0 0 1294 0 0 0 0 0 2607 +685 632 0.991808042972457 -0.0357320662991659 -0.122637781018479 0.00135524997904769 0.0514918756049816 0.990456179433187 0.127848126186092 0.0379548244427716 0.116899070320621 -0.133115649194998 0.984182316086592 -0.037985165929379 0.00020797399704615 0.000152499883575071 1.30605216640445e-05 -1.9003849321753e-06 8.60679056043964e-05 0.000153150278351505 0.000152499883575071 0.000182023098862773 1.34290190163199e-05 2.04371371035077e-05 4.06148612902154e-05 9.90478788701334e-05 1.30605216640445e-05 1.34290190163199e-05 2.04407019032672e-05 -3.30653591534666e-06 -1.13800058587748e-07 8.81233439521568e-06 -1.9003849321753e-06 2.04371371035077e-05 -3.30653591534666e-06 5.12460752590278e-05 -6.12013749710501e-05 -2.77370760720946e-05 8.60679056043964e-05 4.06148612902154e-05 -1.13800058587748e-07 -6.12013749710501e-05 0.000286076371840528 0.000142274173220321 0.000153150278351505 9.90478788701334e-05 8.81233439521568e-06 -2.77370760720946e-05 0.000142274173220321 0.000275289246640844 0 0 0 0 0 0 0 0 0 11 0 0 0 0 0 0 0 0 1165 0 0 0 0 0 2040 +685 688 0.999999914623422 -0.000310419210685842 -0.000272750917961821 -0.000345308391625767 0.000310114624487649 0.99999932912732 -0.00111605278994324 -0.00383558706149512 0.00027309717920682 0.00111596811060997 0.999999340016336 0.00211445749713911 3.87099897965313e-05 1.81553156412712e-05 -1.29636636101292e-05 9.57632259009115e-06 1.37354995227077e-05 1.78961763951168e-05 1.81553156412712e-05 7.31756538632059e-05 -1.17763929896053e-05 9.72875301609591e-06 6.97641196912768e-06 -2.75253363212672e-05 -1.29636636101292e-05 -1.17763929896053e-05 2.50613179384983e-05 -9.95286720914285e-06 -4.77708817215806e-06 -4.85078714080475e-06 9.57632259009115e-06 9.72875301609591e-06 -9.95286720914285e-06 3.3029996065708e-05 -4.80310161573376e-07 8.2187350865333e-07 1.37354995227077e-05 6.97641196912768e-06 -4.77708817215806e-06 -4.80310161573376e-07 5.45596008175218e-05 1.8865104843658e-05 1.78961763951168e-05 -2.75253363212672e-05 -4.85078714080475e-06 8.2187350865333e-07 1.8865104843658e-05 7.33387099959891e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1125 0 0 0 0 0 2677 +686 690 0.99999927232636 -0.000682841729624852 -0.000994521957175442 -0.00238365841737982 0.000680297487078441 0.999996501123236 -0.0025563522087722 0.00705152648287219 0.000996264061429443 0.00255567377779377 0.999996237987654 0.0049394882669965 3.24058902221081e-05 2.19254593269475e-05 -1.14593030834503e-05 1.53198085732472e-06 8.27948343296219e-06 1.18957051140135e-06 2.19254593269475e-05 6.34379486667023e-05 -9.78533778651048e-06 -2.85003298898224e-06 2.09854486717904e-05 -1.13955305227169e-05 -1.14593030834503e-05 -9.78533778651048e-06 2.75044442944328e-05 -7.67097779947904e-06 -3.06604024218557e-06 -4.57116089274787e-06 1.53198085732472e-06 -2.85003298898224e-06 -7.67097779947904e-06 2.57459678377126e-05 1.49788298996603e-06 5.80306966701093e-06 8.27948343296219e-06 2.09854486717904e-05 -3.06604024218557e-06 1.49788298996603e-06 5.24807740281969e-05 1.06812671448294e-05 1.18957051140135e-06 -1.13955305227169e-05 -4.57116089274787e-06 5.80306966701093e-06 1.06812671448294e-05 4.71745404513352e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1202 0 0 0 0 0 2477 +686 631 0.996010264403776 -0.0275189347110638 -0.0848897015820479 -0.00325758287708856 0.0378499058242917 0.991734226084915 0.122599385972556 0.0285446871957283 0.0808142180028564 -0.125323314048599 0.988819057828308 -0.0210426550791347 0.000220593394777002 0.000138035370277025 7.41261466618193e-06 -9.68787267136243e-06 8.19518637959862e-05 8.11125868178734e-05 0.000138035370277025 0.000129448220621537 -3.24308878488141e-06 3.43929120469695e-06 4.23729942858754e-05 5.38397079520142e-05 7.41261466618193e-06 -3.24308878488141e-06 2.67359488686782e-05 -8.90583126733355e-06 -6.73176486215223e-07 6.31179566722339e-06 -9.68787267136243e-06 3.43929120469695e-06 -8.90583126733355e-06 4.82669663474012e-05 -4.70814941245931e-05 -1.88744338857592e-05 8.19518637959862e-05 4.23729942858754e-05 -6.73176486215223e-07 -4.70814941245931e-05 0.000192772739129506 7.52247871213304e-05 8.11125868178734e-05 5.38397079520142e-05 6.31179566722339e-06 -1.88744338857592e-05 7.52247871213304e-05 0.00015225950984284 0 0 0 0 0 0 0 0 0 17 0 0 0 0 0 0 0 0 1229 0 0 0 0 0 2045 +686 688 0.999985775275218 -0.000540184424139461 -0.00530635920462268 0.00725544344469647 0.000537991347163244 0.999999769290053 -0.000414710924060401 -0.0252720167999424 0.00530658200077453 0.000411850249574615 0.999985835183099 -4.30389074585281e-05 2.56580010114567e-05 1.10958232399382e-05 -1.08566654271241e-05 1.40927191652887e-06 8.90223348054146e-06 3.24549738520642e-06 1.10958232399382e-05 4.55676530251954e-05 -7.38424849489639e-06 2.72316651401512e-06 4.48502317896571e-06 -1.95089652085488e-05 -1.08566654271241e-05 -7.38424849489639e-06 2.24487951501988e-05 -7.64429294130963e-06 2.20074876219895e-07 -7.37941516173888e-06 1.40927191652887e-06 2.72316651401512e-06 -7.64429294130963e-06 4.98755832117744e-05 -5.35225951009928e-05 2.08613940901999e-06 8.90223348054146e-06 4.48502317896571e-06 2.20074876219895e-07 -5.35225951009928e-05 0.000176352923162645 1.60751559615939e-05 3.24549738520642e-06 -1.95089652085488e-05 -7.37941516173888e-06 2.08613940901999e-06 1.60751559615939e-05 4.70167097168267e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1150 0 0 0 0 0 2671 +686 632 0.993085168813862 -0.0374806486129051 -0.111252184075182 -0.00414078144873845 0.0513739547677711 0.990854884488049 0.124769045270429 0.054440901999951 0.10555834525731 -0.129621753057622 0.98592881937836 -0.0355689044469468 0.000196293530927312 0.000139927971872021 1.58863072808013e-05 -3.1160897077603e-06 4.03424564250551e-05 9.64081068113662e-05 0.000139927971872021 0.00016410276575266 1.04614835167343e-05 7.42931158994096e-06 2.47253569794698e-05 5.42026211009155e-05 1.58863072808013e-05 1.04614835167343e-05 2.38624530143677e-05 -3.78414035667102e-06 -7.21692925640928e-07 7.35384747428532e-06 -3.1160897077603e-06 7.42931158994096e-06 -3.78414035667102e-06 3.92148903238064e-05 -3.78355205442025e-05 -1.50312724580438e-05 4.03424564250551e-05 2.47253569794698e-05 -7.21692925640928e-07 -3.78355205442025e-05 0.00018066694143368 7.62954573930977e-05 9.64081068113662e-05 5.42026211009155e-05 7.35384747428532e-06 -1.50312724580438e-05 7.62954573930977e-05 0.000179781727618519 0 0 0 0 0 0 0 0 0 14 0 0 0 0 0 0 0 0 1166 0 0 0 0 0 1997 +686 689 0.99999980961018 -0.000605793786754789 0.000117445693085161 0.00253988182324772 0.000605681028433035 0.999999357923873 0.000957759016720904 -0.00758894728771075 -0.000118025822137623 -0.000957687699745165 0.999999534451979 -0.0013342092868294 3.37119738028182e-05 1.27757192648025e-05 -1.49976309332047e-05 4.67641435214824e-06 7.89491719417125e-06 2.22836831609243e-06 1.27757192648025e-05 4.53370196740144e-05 -9.2939378170632e-06 3.87405140453325e-06 6.7035463280447e-06 -1.87705344689143e-05 -1.49976309332047e-05 -9.2939378170632e-06 2.92018406481234e-05 -8.87018369249934e-06 -6.25416282247943e-06 -9.04535088235112e-06 4.67641435214824e-06 3.87405140453325e-06 -8.87018369249934e-06 2.99672256620203e-05 -3.31800723921582e-06 1.81210226814455e-06 7.89491719417125e-06 6.7035463280447e-06 -6.25416282247943e-06 -3.31800723921582e-06 6.94127903262225e-05 1.34532988873682e-05 2.22836831609243e-06 -1.87705344689143e-05 -9.04535088235112e-06 1.81210226814455e-06 1.34532988873682e-05 4.37781060379095e-05 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 1267 0 0 0 0 0 2588 +687 632 0.993728795049033 -0.037975326256964 -0.105171081985844 0.00180040210606132 0.0515563618723585 0.990226752803061 0.129587497790456 0.0420290357847096 0.0992220914962108 -0.134197066394099 0.985974707551028 -0.0409736746509504 0.000178188769216209 0.000136660150318048 1.47642877103691e-05 -1.50445125017537e-05 5.64475956041205e-05 0.000101481975522255 0.000136660150318048 0.000152634057267029 8.371350297978e-06 -5.5310399864485e-06 5.61503785928265e-05 7.38478877928134e-05 1.47642877103691e-05 8.371350297978e-06 1.91632762919885e-05 -5.842538150231e-06 1.02671335486262e-06 1.2798683430372e-05 -1.50445125017537e-05 -5.5310399864485e-06 -5.842538150231e-06 4.30293179984449e-05 -4.09943090635001e-05 -1.78505675472206e-05 5.64475956041205e-05 5.61503785928265e-05 1.02671335486262e-06 -4.09943090635001e-05 0.000197098244853572 7.65190387214888e-05 0.000101481975522255 7.38478877928134e-05 1.2798683430372e-05 -1.78505675472206e-05 7.65190387214888e-05 0.000189189541101656 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1133 0 0 0 0 0 2036 +687 689 0.999994647388647 -3.98612169828765e-05 -0.00327163646191472 0.00976186179166528 4.03331203182931e-05 0.999999988793417 0.000144174910659508 -0.0279828957618309 0.00327163067826346 -0.0001443060942543 0.999994637789851 0.000696114999422774 4.68061819379106e-05 -1.08638923926321e-05 -1.81907843071687e-05 8.47763490663322e-06 1.80180521082036e-06 3.20575312916485e-05 -1.08638923926321e-05 0.000147661437888192 1.69190999574341e-06 2.29891048367931e-06 2.87646061387122e-05 -8.32297623263682e-05 -1.81907843071687e-05 1.69190999574341e-06 3.30287152599924e-05 -1.3423378707023e-05 -9.07369445237976e-06 -2.28941621203013e-05 8.47763490663322e-06 2.29891048367931e-06 -1.3423378707023e-05 4.57267162854218e-05 -2.23230598991002e-05 9.26983551069809e-06 1.80180521082036e-06 2.87646061387122e-05 -9.07369445237976e-06 -2.23230598991002e-05 0.00012572431255124 2.80805482342324e-06 3.20575312916485e-05 -8.32297623263682e-05 -2.28941621203013e-05 9.26983551069809e-06 2.80805482342324e-06 0.000110952780625035 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1252 0 0 0 0 0 2666 +687 691 0.999988538464958 0.000435153047846259 -0.00476797446948753 -0.0037180910404204 -0.000447688195032807 0.999996445858599 -0.00262827803887604 0.0058969316126984 0.00476681382023287 0.00263038248065941 0.999985179177176 0.00664356482927909 3.1164885395286e-05 -1.6861352924691e-06 -1.25336499280694e-05 7.98045087762249e-07 1.03578141437841e-05 1.82158509043912e-05 -1.6861352924691e-06 6.52377569813731e-05 -1.90607615806217e-06 1.38125269915238e-07 5.78859186762945e-06 -4.02496331138275e-05 -1.25336499280694e-05 -1.90607615806217e-06 2.9573140560847e-05 -1.08520886307188e-05 -7.53677591294407e-06 -1.30613133490083e-05 7.98045087762249e-07 1.38125269915238e-07 -1.08520886307188e-05 3.3208032788067e-05 1.92714477159507e-06 3.52107576738539e-06 1.03578141437841e-05 5.78859186762945e-06 -7.53677591294407e-06 1.92714477159507e-06 5.51315782795656e-05 1.79570817898499e-05 1.82158509043912e-05 -4.02496331138275e-05 -1.30613133490083e-05 3.52107576738539e-06 1.79570817898499e-05 7.36592532847284e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1222 0 0 0 0 0 2602 +687 690 0.999987322291508 0.000738065094304983 -0.0049810155766992 -0.00552929089277493 -0.000764026680186233 0.999986124425223 -0.00521221836216973 0.0118751694114316 0.00497709950580809 0.00521595791197976 0.999974010794065 0.00861590464447949 2.92408100681971e-05 1.08380179104961e-05 -1.30868567989625e-05 4.83534285670272e-06 3.85257484695597e-06 3.38400577357524e-06 1.08380179104961e-05 6.52962215744491e-05 1.479135090369e-06 -6.97300082789596e-06 1.59832812837572e-05 -2.42984735371906e-05 -1.30868567989625e-05 1.479135090369e-06 2.77604930245493e-05 -1.02604040743045e-05 -2.76073547097356e-06 -1.00196173034397e-05 4.83534285670272e-06 -6.97300082789596e-06 -1.02604040743045e-05 2.85235502302365e-05 9.02589183621897e-08 1.09552145526311e-05 3.85257484695597e-06 1.59832812837572e-05 -2.76073547097356e-06 9.02589183621897e-08 5.42521589762524e-05 6.50021330078974e-06 3.38400577357524e-06 -2.42984735371906e-05 -1.00196173034397e-05 1.09552145526311e-05 6.50021330078974e-06 4.58762038297193e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1203 0 0 0 0 0 2545 +688 692 0.999958091484809 -0.000691501652089237 0.00912891557212916 4.90129791461584e-05 0.000670054658149802 0.999997009093826 0.00235219687913984 0.0058054452765418 -0.00913051481642717 -0.00234598142965824 0.999955564047882 -0.00696422999170483 5.32226779245771e-05 2.17780132556554e-05 -1.83163862819052e-05 7.36836990667903e-06 2.01502277629062e-05 2.07629452074047e-05 2.17780132556554e-05 7.12080494839291e-05 -4.86198305562772e-06 -1.00659531948301e-06 2.26616729575965e-05 -1.77642741494586e-05 -1.83163862819052e-05 -4.86198305562772e-06 3.44197025104898e-05 -9.70506070092342e-06 -6.06978141800183e-06 -1.48011881248658e-05 7.36836990667903e-06 -1.00659531948301e-06 -9.70506070092342e-06 3.04675076236344e-05 8.67947871748632e-06 7.22864199000654e-06 2.01502277629062e-05 2.26616729575965e-05 -6.06978141800183e-06 8.67947871748632e-06 6.54807002228567e-05 1.79739830451196e-05 2.07629452074047e-05 -1.77642741494586e-05 -1.48011881248658e-05 7.22864199000654e-06 1.79739830451196e-05 7.22274174091213e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1265 0 0 0 0 0 2560 +687 645 0.997863032507443 0.0107312649964086 -0.0644531481514042 -0.0261845337700994 -0.00214269406621922 0.991264759075348 0.13186958056137 0.0790801764146452 0.0653052617879187 -0.13144967617636 0.989169452326517 -0.00867633375282919 0.000166247009514031 0.000123884328227849 5.15135244376786e-06 -3.22821846029355e-05 0.000114189394908553 1.54591899475747e-05 0.000123884328227849 0.000189191278655395 9.89730204274889e-06 -0.000407809127833382 0.0010707193993325 0.000117606218744173 5.15135244376786e-06 9.89730204274889e-06 2.11316682043925e-05 -7.2765952659996e-05 0.000172522451424452 2.29287748372289e-05 -3.22821846029355e-05 -0.000407809127833382 -7.2765952659996e-05 0.00404643719687689 -0.00997392660805298 -0.00149389865376989 0.000114189394908553 0.0010707193993325 0.000172522451424452 -0.00997392660805298 0.0247949520733273 0.00368360790258492 1.54591899475747e-05 0.000117606218744173 2.29287748372289e-05 -0.00149389865376989 0.00368360790258492 0.000654047427002175 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1220 0 0 0 0 0 1654 +688 691 0.99999743039737 0.000273514218441854 -0.00225041965616755 0.00337791995317714 -0.000278840403033812 0.99999716029983 -0.00236677846583018 -0.00476461153163136 0.00224976591808816 0.00236739989207393 0.999994666971312 0.00475247590266483 3.2208120994905e-05 9.52321930384225e-06 -7.84364941634997e-06 7.707398864028e-07 6.61543489143196e-06 1.10901410688604e-05 9.52321930384225e-06 5.79501301976898e-05 -8.26219858918018e-06 3.19282188550692e-06 9.37192822583751e-06 -2.0266464347761e-05 -7.84364941634997e-06 -8.26219858918018e-06 2.56311258221153e-05 -6.74000308362664e-06 2.04889871263754e-06 -3.50763986482864e-06 7.707398864028e-07 3.19282188550692e-06 -6.74000308362664e-06 3.69348959290835e-05 -1.71555274346376e-05 -3.83535950812289e-06 6.61543489143196e-06 9.37192822583751e-06 2.04889871263754e-06 -1.71555274346376e-05 7.25714865454534e-05 9.49026091195406e-06 1.10901410688604e-05 -2.0266464347761e-05 -3.50763986482864e-06 -3.83535950812289e-06 9.49026091195406e-06 6.34758873368756e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1219 0 0 0 0 0 2597 +688 690 0.999968412491975 -0.00010859794643162 -0.00794746656270003 0.00351434171472254 7.7273711042163e-05 0.99999222883024 -0.00394161234818774 -0.0113344460790209 0.00794783285259485 0.00394087371224138 0.999960649959453 0.0081639873408128 1.99835651140037e-05 8.92508835467763e-06 -9.61484368021043e-06 1.14449384879044e-06 4.87907405056051e-06 1.98289746893671e-06 8.92508835467763e-06 4.31686264829273e-05 -6.4308722031719e-06 5.1080907370161e-06 -1.12273452984115e-05 -2.01794167614504e-05 -9.61484368021043e-06 -6.4308722031719e-06 2.31843714651727e-05 -6.68252398020499e-06 -1.9734438716783e-06 -1.69886497884251e-06 1.14449384879044e-06 5.1080907370161e-06 -6.68252398020499e-06 3.82791640876079e-05 -2.71791691198579e-05 2.8116599848201e-06 4.87907405056051e-06 -1.12273452984115e-05 -1.9734438716783e-06 -2.71791691198579e-05 9.98259389635212e-05 1.72269635117742e-05 1.98289746893671e-06 -2.01794167614504e-05 -1.69886497884251e-06 2.8116599848201e-06 1.72269635117742e-05 4.95244689414396e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1194 0 0 0 0 0 2566 +689 691 0.999971044927579 -0.000796065579924134 0.00756806355933608 0.00696759267926012 0.000765694311932266 0.999991646171112 0.00401513389683392 -0.0166724000044364 -0.00757119664692215 -0.00400922281512143 0.999963300883464 -0.00706167805651522 2.65973974869969e-05 1.1346736188946e-05 -1.11670855244829e-05 5.65683716501236e-06 -2.38134049622861e-06 5.62585268129014e-06 1.1346736188946e-05 4.87732963898939e-05 -8.74696711834836e-06 -3.68918955371066e-06 2.2688510601955e-05 -1.24255890142364e-05 -1.11670855244829e-05 -8.74696711834836e-06 2.676466963842e-05 -8.30967164189397e-06 -4.08072850200973e-06 -8.65809653646578e-06 5.65683716501236e-06 -3.68918955371066e-06 -8.30967164189397e-06 3.69386514926059e-05 -2.28220141330633e-05 8.12544978329813e-06 -2.38134049622861e-06 2.2688510601955e-05 -4.08072850200973e-06 -2.28220141330633e-05 0.000123563216730079 8.00944050919313e-06 5.62585268129014e-06 -1.24255890142364e-05 -8.65809653646578e-06 8.12544978329813e-06 8.00944050919313e-06 4.76103298584347e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1223 0 0 0 0 0 2671 +689 693 0.999985896065947 -0.000657003138983498 0.00527029563309082 -0.00263418451870048 0.000644987141637462 0.999997189773997 0.00228132323343507 0.0120854809456012 -0.00527177965889439 -0.00227789178488666 0.999983509638156 -0.00681503341932709 2.55691104009731e-05 1.40190592262928e-05 -1.31255194664013e-05 4.49123799725088e-06 4.89419618573593e-06 2.45623944501142e-06 1.40190592262928e-05 4.59488967994939e-05 -9.51100076726082e-06 1.59644628679316e-06 1.25129876405887e-05 -7.93567324213585e-06 -1.31255194664013e-05 -9.51100076726082e-06 2.93354975550447e-05 -1.08634523008815e-05 -4.88323712081399e-06 -6.13295266702292e-06 4.49123799725088e-06 1.59644628679316e-06 -1.08634523008815e-05 3.00664305539359e-05 2.39133800698534e-06 6.25734938016776e-06 4.89419618573593e-06 1.25129876405887e-05 -4.88323712081399e-06 2.39133800698534e-06 4.78442141634703e-05 9.73553367894793e-06 2.45623944501142e-06 -7.93567324213585e-06 -6.13295266702292e-06 6.25734938016776e-06 9.73553367894793e-06 3.63790918154587e-05 0 0 0 0 0 0 5 0 0 0 0 0 0 0 0 0 0 0 1119 0 0 0 0 0 2594 +689 632 0.992785387190907 -0.0373044998230994 -0.113954154260162 -0.00445159549551965 0.0507610917650697 0.991766482569953 0.117569365115414 0.0456574122442178 0.108630044384685 -0.122505584949307 0.986504888539945 -0.0225583426247319 0.000210598026207566 0.000147968026620581 1.56881130669935e-05 -3.69112206177232e-05 0.000141665827925108 0.00017029959560787 0.000147968026620581 0.00015493942107235 1.16917864901472e-05 -1.02132561194903e-05 8.54424216398697e-05 0.000101563312149934 1.56881130669935e-05 1.16917864901472e-05 2.02094121499354e-05 -7.72537241501019e-06 5.19072966398141e-06 1.40780088483716e-05 -3.69112206177232e-05 -1.02132561194903e-05 -7.72537241501019e-06 5.76616667151666e-05 -8.50299656165876e-05 -5.58086623276548e-05 0.000141665827925108 8.54424216398697e-05 5.19072966398141e-06 -8.50299656165876e-05 0.000349069728501488 0.000210845148419408 0.00017029959560787 0.000101563312149934 1.40780088483716e-05 -5.58086623276548e-05 0.000210845148419408 0.000276848278432455 0 0 0 0 0 0 0 0 0 12 0 0 0 0 0 0 0 0 1196 0 0 0 0 0 2040 +689 692 0.999999187863631 0.000255714067733765 0.00124855211950051 0.00469228690971199 -0.000256255295772895 0.999999873273176 0.000433343808612847 -0.00870946816215785 -0.00124844114916744 -0.00043366340477125 0.999999126664993 -2.68495497637322e-05 3.6803574316144e-05 -3.36046845226491e-06 -1.46299918005978e-05 -9.95242510886723e-07 5.36595227901413e-06 7.00913589716254e-06 -3.36046845226491e-06 0.000104226772745691 -1.82626983137628e-06 2.73090784093886e-06 8.78949793486341e-07 -5.00675954980856e-05 -1.46299918005978e-05 -1.82626983137628e-06 2.39451221603026e-05 -4.57138097998827e-06 -3.41054332554856e-06 -8.5084641793851e-06 -9.95242510886723e-07 2.73090784093886e-06 -4.57138097998827e-06 3.47247851097801e-05 -2.02684052273111e-05 1.88130226367343e-06 5.36595227901413e-06 8.78949793486341e-07 -3.41054332554856e-06 -2.02684052273111e-05 8.46842764433015e-05 1.05380234211556e-05 7.00913589716254e-06 -5.00675954980856e-05 -8.5084641793851e-06 1.88130226367343e-06 1.05380234211556e-05 5.75114967719435e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1293 0 0 0 0 0 2627 +690 693 0.999999319370637 -0.0011283946772945 0.000296620488018824 0.00146322910191634 0.00112799685584029 0.999998468764376 0.00133794319639799 -0.00127487027310889 -0.000298129761804303 -0.0013376076987767 0.999999060961704 -0.00357987602396986 3.67405883417411e-05 4.63311328179514e-06 -1.41542677201545e-05 -2.01771544569875e-06 1.78137492305389e-05 8.29328522273869e-06 4.63311328179514e-06 8.145993887005e-05 -7.07658112012429e-06 7.31186749608225e-06 6.53714401101006e-06 -3.51044459096444e-05 -1.41542677201545e-05 -7.07658112012429e-06 3.15504040534589e-05 -6.9637025054967e-06 -5.68315560366304e-06 -9.98807552992749e-06 -2.01771544569875e-06 7.31186749608225e-06 -6.9637025054967e-06 3.17446371292299e-05 -1.09467796781923e-05 -6.47846511925635e-07 1.78137492305389e-05 6.53714401101006e-06 -5.68315560366304e-06 -1.09467796781923e-05 8.44572164586088e-05 1.09770020419764e-05 8.29328522273869e-06 -3.51044459096444e-05 -9.98807552992749e-06 -6.47846511925635e-07 1.09770020419764e-05 6.02033885175289e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1140 0 0 0 0 0 2593 +690 694 0.999993893385613 0.000273113635815333 0.00348404942918026 -0.00583079425599977 -0.000284760072633047 0.99999437251973 0.00334272950946476 0.0124519696247387 -0.00348311687775096 -0.00334370121487316 0.999988343711566 -0.00873573170023052 3.7807893315516e-05 1.76973782813271e-05 -1.214707650345e-05 3.54368930055648e-06 5.77757727633056e-06 1.79391272958867e-05 1.76973782813271e-05 7.71936476298803e-05 -2.82130493631375e-06 -1.54193473023812e-06 1.03390344660078e-05 -2.69722888168587e-06 -1.214707650345e-05 -2.82130493631375e-06 3.19870490456891e-05 -7.14159684530296e-06 -1.15873155306104e-05 -4.74633958225739e-06 3.54368930055648e-06 -1.54193473023812e-06 -7.14159684530296e-06 3.22699030960399e-05 -6.13860728229979e-06 3.14275053953014e-06 5.77757727633056e-06 1.03390344660078e-05 -1.15873155306104e-05 -6.13860728229979e-06 8.8431234048097e-05 1.09764485724528e-05 1.79391272958867e-05 -2.69722888168587e-06 -4.74633958225739e-06 3.14275053953014e-06 1.09764485724528e-05 6.9558566348188e-05 0 0 0 0 0 0 9 0 0 0 0 0 0 0 0 0 0 0 996 0 0 0 0 0 2464 +690 692 0.999998607136657 0.000449749494507073 -0.00160731146292502 0.00914661196220463 -0.000453735002044171 0.999996821590895 -0.00248010738807255 -0.0227622830896068 0.00160619092718752 0.0024808332270918 0.999995632799066 0.00418803967548095 2.82921544599623e-05 1.39129162436649e-05 -1.15382476451602e-05 3.43498273479708e-06 8.8360945036982e-06 -3.31853927291062e-06 1.39129162436649e-05 7.82635967864059e-05 -3.18354843009882e-06 3.78481464932768e-06 1.19076065327595e-06 -4.04595817672844e-05 -1.15382476451602e-05 -3.18354843009882e-06 2.73017398636532e-05 -8.94239742814299e-06 -5.29944064062328e-06 -9.38335338694084e-06 3.43498273479708e-06 3.78481464932768e-06 -8.94239742814299e-06 3.67759343323337e-05 -2.09217826944546e-05 7.25900534389422e-06 8.8360945036982e-06 1.19076065327595e-06 -5.29944064062328e-06 -2.09217826944546e-05 9.73816120161842e-05 9.6755723678582e-06 -3.31853927291062e-06 -4.04595817672844e-05 -9.38335338694084e-06 7.25900534389422e-06 9.6755723678582e-06 5.56373838163712e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1284 0 0 0 0 0 2676 +691 694 0.999991908133008 -0.00050668397649276 0.00399085703256301 -0.000607585457155718 0.000491819942710534 0.999992942623636 0.00372462294263659 -0.000624699409386404 -0.00399271607434643 -0.00372263002040602 0.999985100011035 -0.00957310451188302 2.95820492922358e-05 1.50799042682022e-05 -9.66583141329155e-06 -4.90053761006805e-07 3.06797586403293e-07 4.0933404131496e-06 1.50799042682022e-05 5.44691379341375e-05 -5.66530220441704e-06 -7.91848104967137e-06 1.39352861621864e-05 -1.11925353026333e-05 -9.66583141329155e-06 -5.66530220441704e-06 2.87328921404051e-05 -5.24769195611021e-06 7.90038762316833e-07 -1.43583364712218e-06 -4.90053761006805e-07 -7.91848104967137e-06 -5.24769195611021e-06 3.90571677002784e-05 -2.41049832242135e-05 3.05044460683029e-06 3.06797586403293e-07 1.39352861621864e-05 7.90038762316833e-07 -2.41049832242135e-05 0.000109692120790008 7.08882595256261e-06 4.0933404131496e-06 -1.11925353026333e-05 -1.43583364712218e-06 3.05044460683029e-06 7.08882595256261e-06 4.86010567217835e-05 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 0 0 0 994 0 0 0 0 0 2407 +691 695 0.999999754127704 -1.49055371760887e-05 -0.000701086554255104 -0.00389777065161272 1.45941307456599e-05 0.999999901245615 -0.000444179887410576 0.0124943753862913 0.000701093105759557 0.000444169546450211 0.999999655590876 -5.5934656572457e-06 4.29503091498662e-05 2.2023394948832e-06 -1.99074216967911e-05 4.2023430888892e-06 1.96248970286836e-05 3.13753689099826e-05 2.2023394948832e-06 8.39291503115787e-05 -8.50710797245731e-06 8.99337101888173e-06 -1.08245205959016e-06 -3.53674848457523e-05 -1.99074216967911e-05 -8.50710797245731e-06 3.1962412308987e-05 -1.09993919924763e-05 -1.12537784746775e-05 -1.63094095994988e-05 4.2023430888892e-06 8.99337101888173e-06 -1.09993919924763e-05 3.77914688462986e-05 1.28294518399489e-05 9.52132868069698e-06 1.96248970286836e-05 -1.08245205959016e-06 -1.12537784746775e-05 1.28294518399489e-05 5.27989273586039e-05 3.31384539234783e-05 3.13753689099826e-05 -3.53674848457523e-05 -1.63094095994988e-05 9.52132868069698e-06 3.31384539234783e-05 9.78060303650834e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1162 0 0 0 0 0 2501 +691 693 0.999999549441288 -0.000331111291059813 0.000889653041637884 0.0109981535055814 0.000330121396397314 0.999999326579767 0.00111259151399705 -0.0220742450940428 -0.000890020834140147 -0.00111229731920484 0.999998985328279 -0.00383367601868907 2.87933161446941e-05 1.02753772551279e-05 -1.47346917478448e-05 2.03361933989277e-06 7.10755726084294e-07 1.81099104651922e-06 1.02753772551279e-05 6.47576517165755e-05 -7.21492853101197e-06 -1.38870806924063e-06 7.22425867445212e-06 -2.237036887091e-05 -1.47346917478448e-05 -7.21492853101197e-06 3.20880205510884e-05 -1.03210073548457e-05 4.39483927459076e-06 -3.85385152760295e-06 2.03361933989277e-06 -1.38870806924063e-06 -1.03210073548457e-05 4.33379774190599e-05 -2.69582267371472e-05 4.4339138857905e-06 7.10755726084294e-07 7.22425867445212e-06 4.39483927459076e-06 -2.69582267371472e-05 9.46394486180222e-05 1.61574703740893e-06 1.81099104651922e-06 -2.237036887091e-05 -3.85385152760295e-06 4.4339138857905e-06 1.61574703740893e-06 4.53723588396658e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1139 0 0 0 0 0 2687 +692 694 0.999988325828328 -3.90224302335458e-05 -0.00483184067494565 0.0079844496205849 3.59203974947182e-05 0.999999793219385 -0.00064208325964044 -0.0256174967667668 0.00483186473146387 0.000641902202212563 0.999988120451828 0.00126848593704609 6.2484943351768e-05 2.00280254223392e-05 -1.65076716281519e-05 -1.17086347952039e-05 4.92009972572301e-05 4.43108988378423e-05 2.00280254223392e-05 8.59798621278246e-05 -3.82808249292491e-06 5.00707550408115e-06 -4.62574967502445e-06 -2.13673085940813e-05 -1.65076716281519e-05 -3.82808249292491e-06 3.03528407228594e-05 -8.22014398736892e-06 -7.84349045013999e-06 -8.20175946556889e-06 -1.17086347952039e-05 5.00707550408115e-06 -8.22014398736892e-06 7.20110123434551e-05 -8.95500188471599e-05 -2.57843465405637e-05 4.92009972572301e-05 -4.62574967502445e-06 -7.84349045013999e-06 -8.95500188471599e-05 0.000255951334154111 8.66927014040855e-05 4.43108988378423e-05 -2.13673085940813e-05 -8.20175946556889e-06 -2.57843465405637e-05 8.66927014040855e-05 0.000126155018372432 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 956 0 0 0 0 0 2465 +692 695 0.999993631203548 -0.000362357916151868 0.00355052800068759 -0.00341284461666313 0.000366020757360808 0.999999401495218 -0.00103103734697366 0.014329431779915 -0.00355015227113508 0.00103233034745451 0.999993165333096 0.00229742555551697 4.36065772837671e-05 1.897531527437e-05 -1.42567715520979e-05 3.95403244691276e-06 9.02075736666107e-06 5.24043933488898e-06 1.897531527437e-05 7.08214892038087e-05 -1.38460726376144e-05 1.59119618709782e-06 1.52833772244947e-05 -2.44803331238342e-05 -1.42567715520979e-05 -1.38460726376144e-05 2.64609647539733e-05 -8.09115770519472e-06 -3.04608578809769e-06 -3.1361515652288e-06 3.95403244691276e-06 1.59119618709782e-06 -8.09115770519472e-06 2.56947380975659e-05 4.8559387279592e-06 6.52566543672741e-06 9.02075736666107e-06 1.52833772244947e-05 -3.04608578809769e-06 4.8559387279592e-06 4.72633011003603e-05 4.35778351042925e-06 5.24043933488898e-06 -2.44803331238342e-05 -3.1361515652288e-06 6.52566543672741e-06 4.35778351042925e-06 5.44296114280449e-05 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 0 0 0 1207 0 0 0 0 0 2468 +693 696 0.999956606038693 -0.00172196482376921 0.00915537419904256 -0.00125209589394827 0.00171713510497824 0.99999838241555 0.00053536278858642 0.00182499940530356 -0.00915628126534152 -0.000519618542637898 0.999957945370684 -0.00374169772166534 4.87101008935666e-05 7.67007152727589e-06 -1.62366968818906e-05 6.3128633362433e-07 1.56131701323395e-05 3.64245861404865e-05 7.67007152727589e-06 6.67725710192388e-05 -6.70301018442783e-06 5.12728359343716e-06 -5.5385219763707e-08 -3.14557507528886e-05 -1.62366968818906e-05 -6.70301018442783e-06 2.61783671184573e-05 -4.94462450539978e-06 -5.57152632940327e-06 -8.26339166285033e-06 6.3128633362433e-07 5.12728359343716e-06 -4.94462450539978e-06 3.49644683003735e-05 -1.275860025135e-05 -3.69822024221015e-06 1.56131701323395e-05 -5.5385219763707e-08 -5.57152632940327e-06 -1.275860025135e-05 9.93050914959025e-05 3.54724469007356e-05 3.64245861404865e-05 -3.14557507528886e-05 -8.26339166285033e-06 -3.69822024221015e-06 3.54724469007356e-05 9.29407237762261e-05 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 0 0 0 1200 0 0 0 0 0 2377 +693 695 0.999999161250933 -0.00019546396878927 0.00128034810393163 0.0133107682282693 0.000192495701619403 0.999997294811173 0.002318041358751 -0.0338733726383308 -0.00128079773391205 -0.00231779295298939 0.999996493690349 -0.00383993376914593 3.68101824370391e-05 1.19918556189106e-05 -1.32105149850239e-05 8.62582256175466e-06 -2.55234019925534e-06 1.3309493237051e-05 1.19918556189106e-05 7.27056315594487e-05 -1.05033432309992e-05 1.59300990737796e-06 1.46351521509909e-05 -3.27016861837608e-05 -1.32105149850239e-05 -1.05033432309992e-05 2.49327964897527e-05 -6.38657692610936e-06 -8.00361214917122e-06 -5.76175258783988e-06 8.62582256175466e-06 1.59300990737796e-06 -6.38657692610936e-06 4.34038594474848e-05 -3.13840939144185e-05 1.40268897304895e-05 -2.55234019925534e-06 1.46351521509909e-05 -8.00361214917122e-06 -3.13840939144185e-05 0.00013383780005262 -1.33580713773104e-05 1.3309493237051e-05 -3.27016861837608e-05 -5.76175258783988e-06 1.40268897304895e-05 -1.33580713773104e-05 6.70242757025117e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1181 0 0 0 0 0 2532 +694 696 0.999973081191293 -0.000303985258369367 0.00733106307121217 0.0124856073357676 0.000266828234878733 0.999987117538445 0.00506888151820225 -0.0255837505071947 -0.00733250949433195 -0.00506678893533123 0.999960280188368 -0.0108238937358932 3.22576395357839e-05 1.93907477617304e-05 -1.141005159043e-05 3.166784825184e-08 8.76187851245996e-06 4.36756732670326e-06 1.93907477617304e-05 4.66295920079876e-05 -1.03369547039164e-05 1.02760939176753e-06 7.72230510050792e-06 -1.65352155547193e-05 -1.141005159043e-05 -1.03369547039164e-05 2.4792331452309e-05 -3.30366205231276e-06 -7.37793196058644e-06 -2.26538009093932e-06 3.166784825184e-08 1.02760939176753e-06 -3.30366205231276e-06 4.75718223073614e-05 -6.39565332387617e-05 -3.57690987176477e-06 8.76187851245996e-06 7.72230510050792e-06 -7.37793196058644e-06 -6.39565332387617e-05 0.000220284504938259 2.03949536649215e-05 4.36756732670326e-06 -1.65352155547193e-05 -2.26538009093932e-06 -3.57690987176477e-06 2.03949536649215e-05 4.76422352631796e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1184 0 0 0 0 0 2515 +694 697 0.999996235446316 -0.000293642539681219 0.00272816188213455 0.00128964987316636 0.000290967279951991 0.999999476533484 0.00098095402500198 0.000770360891994764 -0.00272844850386437 -0.000980156526305778 0.999995797422142 -0.000851091942867593 3.06325957479978e-05 3.45392259703301e-07 -1.49952111034097e-05 3.4620924184779e-06 6.92826414204159e-07 4.27965785612741e-06 3.45392259703301e-07 8.72016631184306e-05 -4.08792996646651e-06 4.07496290693938e-06 5.5507091287482e-06 -4.34427287879907e-05 -1.49952111034097e-05 -4.08792996646651e-06 3.0326162386728e-05 -3.4162471564868e-06 -1.2301752501945e-05 -5.80604942035084e-06 3.4620924184779e-06 4.07496290693938e-06 -3.4162471564868e-06 3.5365534924806e-05 -1.65542852538849e-05 6.29708615918062e-07 6.92826414204159e-07 5.5507091287482e-06 -1.2301752501945e-05 -1.65542852538849e-05 0.000105384340208384 8.87543188835787e-06 4.27965785612741e-06 -4.34427287879907e-05 -5.80604942035084e-06 6.29708615918062e-07 8.87543188835787e-06 5.47013320227423e-05 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 1086 0 0 0 0 0 2453 +695 697 0.999995134170735 -0.000492662854345244 -0.00308040876580957 0.0080742021225847 0.000485259162589275 0.999996993219753 -0.00240376267508726 -0.0235632897106448 0.00308158374827802 0.00240225618221036 0.999992366474283 0.00458260342523583 2.37753785890066e-05 4.09373871368126e-06 -8.93958504183333e-06 9.22625853803728e-07 -4.30444586055146e-06 8.67342160924685e-06 4.09373871368126e-06 4.73614426011193e-05 -8.81217555577371e-06 3.00390687601021e-09 9.72664533429234e-06 -1.89581714149315e-05 -8.93958504183333e-06 -8.81217555577371e-06 2.39880552515862e-05 -4.37419497119504e-06 -5.21716961361554e-06 -1.5684491068016e-06 9.22625853803728e-07 3.00390687601021e-09 -4.37419497119504e-06 4.6701841074088e-05 -5.23571973258013e-05 -1.21555170064148e-06 -4.30444586055146e-06 9.72664533429234e-06 -5.21716961361554e-06 -5.23571973258013e-05 0.000167259809896983 5.79574862875658e-07 8.67342160924685e-06 -1.89581714149315e-05 -1.5684491068016e-06 -1.21555170064148e-06 5.79574862875658e-07 4.66675473326691e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1156 0 0 0 0 0 2479 +695 698 0.999862004130597 0.0157252385051125 -0.00535626454762807 -0.000909310875902519 -0.0157606763156009 0.999853748586632 -0.00663946679605409 -0.00205776694717068 0.00525107398745288 0.00672296892885709 0.999963613293384 -5.71717123860803e-05 4.06486913546405e-05 2.92944055666033e-05 -7.31849776133537e-06 1.05217967272599e-06 4.85356637391764e-06 8.07609150891393e-06 2.92944055666033e-05 5.78483597053651e-05 -1.00620486474342e-05 4.73380604723544e-06 4.63551150728956e-06 -3.62343304228575e-06 -7.31849776133537e-06 -1.00620486474342e-05 2.16727938444131e-05 1.5804643987203e-07 -3.74914026514123e-06 -3.62604747925098e-07 1.05217967272599e-06 4.73380604723544e-06 1.5804643987203e-07 3.61727922053332e-05 -3.08372796535748e-05 -4.10347205493295e-07 4.85356637391764e-06 4.63551150728956e-06 -3.74914026514123e-06 -3.08372796535748e-05 0.000111279911330701 1.68160567740988e-05 8.07609150891393e-06 -3.62343304228575e-06 -3.62604747925098e-07 -4.10347205493295e-07 1.68160567740988e-05 5.03677631737872e-05 0 0 0 0 0 0 8 0 0 0 0 0 0 0 0 0 0 0 1246 0 0 0 0 0 2392 +696 698 0.999837505800722 0.0164875152740181 -0.00728860990042236 0.0117870113071948 -0.0165286195052817 0.99984762263584 -0.00561571426513626 -0.0298008833340134 0.00719491010653639 0.00573527240390988 0.999957669063552 -0.00513202473896435 3.52522649804801e-05 2.01383807095747e-05 -9.82104411862064e-06 -2.78923473249924e-06 8.56099877958355e-06 8.09692894243465e-06 2.01383807095747e-05 5.34101596779887e-05 -9.50578823836611e-06 1.86885391668608e-06 4.69278170707493e-06 -9.75804806728706e-06 -9.82104411862064e-06 -9.50578823836611e-06 2.47147084339852e-05 2.30338391697566e-06 -2.09556696094582e-06 1.65351980481552e-07 -2.78923473249924e-06 1.86885391668608e-06 2.30338391697566e-06 3.18536388325829e-05 -3.01204304107028e-05 -1.264553846424e-06 8.56099877958355e-06 4.69278170707493e-06 -2.09556696094582e-06 -3.01204304107028e-05 0.000112173448223732 2.22493760278279e-06 8.09692894243465e-06 -9.75804806728706e-06 1.65351980481552e-07 -1.264553846424e-06 2.22493760278279e-06 5.39911044919707e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1311 0 0 7 0 0 2514 +696 699 0.997264029495046 0.066048016245448 -0.0331981177982391 -0.00364410060026152 -0.066705414851139 0.997589888169591 -0.0190998076252191 -0.00891194608220804 0.0318566022174709 0.0212620453349147 0.999266271983266 -0.0112778926103023 0.000107165254227867 9.31455648474611e-05 -1.6680094664357e-05 1.48766620338347e-05 6.01958661106693e-06 9.92490728641768e-06 9.31455648474611e-05 0.000105724314183676 -1.14879975734838e-05 6.19703112668383e-06 1.94948208287773e-05 2.85403924378319e-06 -1.6680094664357e-05 -1.14879975734838e-05 1.93429690364849e-05 3.59784151322853e-07 -1.08333990519081e-06 -1.63787543499571e-06 1.48766620338347e-05 6.19703112668383e-06 3.59784151322853e-07 5.51802520932292e-05 -7.09655142164145e-05 2.50953057808867e-06 6.01958661106693e-06 1.94948208287773e-05 -1.08333990519081e-06 -7.09655142164145e-05 0.000197125212938594 4.39050757834181e-06 9.92490728641768e-06 2.85403924378319e-06 -1.63787543499571e-06 2.50953057808867e-06 4.39050757834181e-06 4.63318352370779e-05 0 0 0 0 0 4 4 0 0 0 0 0 0 0 0 0 0 0 1286 0 1 112 0 0 2347 +697 699 0.997144394982864 0.0658892660805611 -0.036900679798923 0.00402216812405084 -0.0665101639552071 0.997659722823202 -0.0158579805455606 -0.0352138965356697 0.0357694512805145 0.0182669666802381 0.99919310660322 -0.0103075966348383 8.09515732090856e-05 5.88729950099945e-05 -1.42320706497311e-05 1.76761765640328e-05 -1.1282604258569e-05 2.62449094677696e-05 5.88729950099945e-05 7.43208723865942e-05 -1.3000498223218e-05 1.04413556694243e-05 2.42752697139481e-06 7.53985165315816e-06 -1.42320706497311e-05 -1.3000498223218e-05 2.19794005502022e-05 -1.939950586661e-06 -3.4081707798405e-06 9.01820291195282e-07 1.76761765640328e-05 1.04413556694243e-05 -1.939950586661e-06 4.64190799824186e-05 -5.10051163812787e-05 7.23273528420971e-06 -1.1282604258569e-05 2.42752697139481e-06 -3.4081707798405e-06 -5.10051163812787e-05 0.000140847191278157 6.49191939504107e-07 2.62449094677696e-05 7.53985165315816e-06 9.01820291195282e-07 7.23273528420971e-06 6.49191939504107e-07 6.01556119767392e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1288 0 18 144 0 0 2437 +698 700 0.994404238126971 0.0991606545180639 -0.0364331688255029 -0.00293039944680942 -0.0976770953046395 0.994395085963661 0.0404672468074037 -0.0539270035135229 0.0402417227261307 -0.0366821156269938 0.99851641255673 -0.0525729818804797 7.83414001576596e-05 6.01057414477156e-05 -1.40656367065851e-05 -1.91887721629763e-06 2.08420654843766e-05 1.07111847162453e-05 6.01057414477156e-05 8.79516111207551e-05 -9.44087934245299e-06 1.13465092100739e-05 -3.5858959641036e-06 -4.87941388167723e-06 -1.40656367065851e-05 -9.44087934245299e-06 2.02694804430387e-05 3.62260856717112e-06 -6.35558103330007e-06 -2.56865989652078e-07 -1.91887721629763e-06 1.13465092100739e-05 3.62260856717112e-06 6.57734364055744e-05 -8.35032822984106e-05 -8.64038972921653e-06 2.08420654843766e-05 -3.5858959641036e-06 -6.35558103330007e-06 -8.35032822984106e-05 0.000197166563679463 2.62405540169326e-05 1.07111847162453e-05 -4.87941388167723e-06 -2.56865989652078e-07 -8.64038972921653e-06 2.62405540169326e-05 5.82304351886528e-05 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 1437 0 168 220 0 0 2560 +699 701 0.995814419895428 0.0697399006159738 -0.0590761152277836 -0.0180970783361243 -0.0657107617768482 0.995546221195345 0.0676004234482003 -0.0535896416742881 0.0635274500907959 -0.0634355399263204 0.995961944734445 -0.0974967136644392 5.27326080422462e-05 3.55198431646735e-05 -1.36441524162839e-05 -2.54984593627878e-07 9.92038061670207e-06 5.68416509997229e-06 3.55198431646735e-05 5.48638030509059e-05 -1.55110126728337e-05 -2.22887820056941e-06 2.05198809875792e-05 2.28573062313124e-06 -1.36441524162839e-05 -1.55110126728337e-05 2.31677482319109e-05 -3.75914139766601e-06 -1.09785813677135e-06 -2.72169632828563e-06 -2.54984593627878e-07 -2.22887820056941e-06 -3.75914139766601e-06 8.60515034439184e-05 -0.000110444617175889 -5.03613054350761e-06 9.92038061670207e-06 2.05198809875792e-05 -1.09785813677135e-06 -0.000110444617175889 0.000234772767074538 2.92473536007549e-05 5.68416509997229e-06 2.28573062313124e-06 -2.72169632828563e-06 -5.03613054350761e-06 2.92473536007549e-05 5.73756414842941e-05 22 22 0 0 0 175 175 0 0 0 0 0 0 0 0 0 0 0 1420 0 121 156 0 0 2617 +700 702 0.993956001967609 0.0289416109060859 -0.105895464070598 -0.0362145339293183 -0.026536100549472 0.999358388106316 0.0240550927907945 -0.00660949175186666 0.106523713417224 -0.0210996511749875 0.994086265472016 -0.135039473371029 9.09417678777182e-05 5.93539253333495e-05 -1.09696739736323e-05 -2.31826238346734e-06 1.31463881035598e-05 3.00506978509267e-05 5.93539253333495e-05 9.31046220202699e-05 -1.74221155759609e-05 1.20454572232205e-05 5.29364763961214e-06 2.09022704703901e-05 -1.09696739736323e-05 -1.74221155759609e-05 2.44286120295757e-05 3.63265277594127e-07 -5.6784833385297e-06 -1.18836854533436e-06 -2.31826238346734e-06 1.20454572232205e-05 3.63265277594127e-07 5.57917203141819e-05 -4.89067603412163e-05 -1.52383903648171e-05 1.31463881035598e-05 5.29364763961214e-06 -5.6784833385297e-06 -4.89067603412163e-05 0.000153615551497335 5.09483843363905e-05 3.00506978509267e-05 2.09022704703901e-05 -1.18836854533436e-06 -1.52383903648171e-05 5.09483843363905e-05 0.00011664647857654 295 295 0 0 4 409 420 0 0 1 0 0 0 0 0 0 0 0 1479 0 38 72 0 0 3049 +701 703 0.994492955222245 0.034367886379446 -0.0990081329948999 -0.027416449701518 -0.0308432766740898 0.998842393821866 0.0369129325333215 -0.0130008604270918 0.100162140039697 -0.0336559161220355 0.994401742261474 -0.137290241023567 6.04143177469257e-05 3.90574408514599e-05 -8.05738422194835e-06 1.15127776497061e-05 -1.81823662921008e-05 2.91682932846973e-05 3.90574408514599e-05 7.84100604657819e-05 -1.3120772896759e-05 1.14751996091546e-05 -9.1395120484406e-06 1.59137452792235e-05 -8.05738422194835e-06 -1.3120772896759e-05 2.60372516221286e-05 -6.68749991433384e-06 -3.1948172074204e-06 -5.97358773058051e-06 1.15127776497061e-05 1.14751996091546e-05 -6.68749991433384e-06 5.77619671479429e-05 -4.84929714181156e-05 1.28984221498939e-05 -1.81823662921008e-05 -9.1395120484406e-06 -3.1948172074204e-06 -4.84929714181156e-05 0.000112333843423532 -4.30804560450129e-07 2.91682932846973e-05 1.59137452792235e-05 -5.97358773058051e-06 1.28984221498939e-05 -4.30804560450129e-07 0.000126720839051493 505 505 0 0 0 593 607 0 0 5 0 0 0 0 0 0 0 0 1481 0 52 80 0 0 3172 +702 704 0.995949364945839 0.0680954688590677 -0.0587185625236436 -0.0102938766923459 -0.0646247271932413 0.996157445591882 0.05910996723951 -0.029850575122088 0.0625180541857986 -0.0550758632498896 0.996523026421417 -0.156880691692069 8.46579598007493e-05 6.41424172228025e-05 -6.53428859881757e-06 1.79705503286294e-05 -1.007991152659e-05 6.22662881197105e-05 6.41424172228025e-05 0.000112101848317743 -4.3352605564955e-06 -3.12599223710106e-06 2.2137750389203e-05 3.38593663254441e-05 -6.53428859881757e-06 -4.3352605564955e-06 1.98239065949473e-05 -2.93789662288028e-06 -1.64705523746255e-06 -1.3207362729429e-05 1.79705503286294e-05 -3.12599223710106e-06 -2.93789662288028e-06 6.72196020976629e-05 -6.94789870353095e-05 1.1498868850057e-05 -1.007991152659e-05 2.2137750389203e-05 -1.64705523746255e-06 -6.94789870353095e-05 0.000136913157786442 2.09903262529579e-05 6.22662881197105e-05 3.38593663254441e-05 -1.3207362729429e-05 1.1498868850057e-05 2.09903262529579e-05 0.00023295257672651 564 564 0 0 0 661 661 0 0 0 0 0 0 0 0 0 0 0 1429 0 157 194 0 0 3284 +704 707 0.981488180208516 0.133015636342813 0.137796199509607 -0.0293765576288929 -0.132420111792864 0.991101449011789 -0.013521529480726 -0.02006258187598 -0.138368587850496 -0.00497576678002044 0.990368303027318 -0.281644202952817 3.89276901465372e-05 6.82957014009639e-06 9.4413554702966e-06 -1.31212819783822e-05 1.30424109277415e-05 2.14709454408825e-05 6.82957014009639e-06 6.17792970999908e-05 -9.79403723737402e-07 3.88254246880675e-06 -1.6393023426287e-06 9.61027797972797e-06 9.4413554702966e-06 -9.79403723737402e-07 2.35021180556365e-05 7.11401421223192e-06 -9.13401229817886e-06 -1.00881993883217e-05 -1.31212819783822e-05 3.88254246880675e-06 7.11401421223192e-06 6.95459290397938e-05 -4.99670226276904e-05 -4.20288596662818e-05 1.30424109277415e-05 -1.6393023426287e-06 -9.13401229817886e-06 -4.99670226276904e-05 8.21552744344655e-05 4.75800035114747e-05 2.14709454408825e-05 9.61027797972797e-06 -1.00881993883217e-05 -4.20288596662818e-05 4.75800035114747e-05 0.000148168346117013 587 587 0 0 0 610 610 0 0 0 0 0 0 0 0 0 0 0 1158 0 263 258 0 0 2781 +705 707 0.990426991165998 0.0829415003846975 0.110340757129012 0.00864435732613516 -0.0819403880292499 0.996544645853756 -0.0135846100358968 -0.0428758140583366 -0.111086218674884 0.00441319998942427 0.993800973880771 -0.20308016821102 3.18479892889609e-05 -5.03743483919809e-06 8.49304526439983e-06 -6.06190787989618e-06 4.73055384186279e-06 -6.87899540485801e-07 -5.03743483919809e-06 6.99029859011456e-05 -2.89563572494158e-06 1.0916181622467e-05 -8.54516117260686e-06 3.96840644212155e-06 8.49304526439983e-06 -2.89563572494158e-06 2.55510929068941e-05 3.6357995535081e-06 -2.94447838758963e-06 -4.96153421514318e-06 -6.06190787989618e-06 1.0916181622467e-05 3.6357995535081e-06 9.61266224745725e-05 -7.901281560737e-05 -3.03380274975526e-06 4.73055384186279e-06 -8.54516117260686e-06 -2.94447838758963e-06 -7.901281560737e-05 0.000110051353541187 5.27491071716772e-06 -6.87899540485801e-07 3.96840644212155e-06 -4.96153421514318e-06 -3.03380274975526e-06 5.27491071716772e-06 9.28004551798847e-05 837 836 0 0 4 813 813 0 0 0 0 0 0 0 0 0 0 0 1229 0 162 157 0 0 3052 +705 709 0.978072709075785 0.162771821134746 0.129919629023611 0.0479641634771807 -0.161215150188972 0.986663187065599 -0.0224817846067126 -0.0967745774061451 -0.13184631625761 0.00104380746960864 0.991269619909369 -0.378698099723736 4.95541214500228e-05 2.46783790115365e-05 1.05610551911043e-05 -4.91727990398565e-06 7.87809079673986e-06 4.72335319206297e-05 2.46783790115365e-05 9.68490582025665e-05 -1.50438345864087e-05 1.64858422981369e-05 -4.75460568766851e-06 4.18257081764777e-05 1.05610551911043e-05 -1.50438345864087e-05 2.47737474679036e-05 -1.5402832982913e-07 3.44032152172595e-06 -5.5981186147683e-06 -4.91727990398565e-06 1.64858422981369e-05 -1.5402832982913e-07 6.5890335139857e-05 -3.71839498751032e-05 -3.52394257802865e-05 7.87809079673986e-06 -4.75460568766851e-06 3.44032152172595e-06 -3.71839498751032e-05 5.72939945037064e-05 3.77046022594195e-05 4.72335319206297e-05 4.18257081764777e-05 -5.5981186147683e-06 -3.52394257802865e-05 3.77046022594195e-05 0.000335755202369956 517 517 0 0 0 468 468 0 0 0 0 0 0 0 0 0 0 0 824 0 232 227 0 0 2797 +706 709 0.988877261480776 0.121002638399089 0.0864877056392443 0.030237852669402 -0.11911520702676 0.992521924126286 -0.0266795349215094 -0.0355350359182666 -0.0890692381310939 0.0160807844682749 0.995895616613323 -0.247651349776661 2.5995853662202e-05 8.33770129392746e-06 5.90470689763261e-06 3.01567307181979e-06 -5.90313774121776e-06 -1.2384970154836e-05 8.33770129392746e-06 6.00677727205219e-05 -1.03821112429048e-05 8.313436267289e-06 -7.23659271910092e-06 1.21956258887948e-06 5.90470689763261e-06 -1.03821112429048e-05 1.8594324690442e-05 2.57582212282265e-06 2.93187799793148e-06 -3.52700429415279e-06 3.01567307181979e-06 8.313436267289e-06 2.57582212282265e-06 6.1108585708485e-05 -4.00146220915811e-05 -7.77540429015545e-07 -5.90313774121776e-06 -7.23659271910092e-06 2.93187799793148e-06 -4.00146220915811e-05 6.08306850779503e-05 3.61016356251409e-06 -1.2384970154836e-05 1.21956258887948e-06 -3.52700429415279e-06 -7.77540429015545e-07 3.61016356251409e-06 7.36814004283243e-05 740 740 0 0 0 721 721 0 0 0 0 0 0 0 0 0 0 0 1032 0 178 171 0 0 2779 +706 710 0.985873827520131 0.134764512048085 0.0994551280892448 0.0945537237393595 -0.131291649065417 0.990507762404682 -0.0407047356182769 -0.101270960965245 -0.103996630216992 0.0270721057273365 0.994209133932594 -0.302684837882725 3.87291258483145e-05 3.47041061041708e-06 5.32689222200099e-06 1.67071344622232e-05 -1.55984704942281e-05 -1.62380044263961e-06 3.47041061041708e-06 5.68286118255283e-05 -1.05205925075349e-05 -3.14386922605465e-06 8.4671749853149e-06 -1.31564496832277e-05 5.32689222200099e-06 -1.05205925075349e-05 1.85541646701839e-05 -5.23433140549739e-07 7.74863413189123e-06 -9.95192973582809e-07 1.67071344622232e-05 -3.14386922605465e-06 -5.23433140549739e-07 8.69816981977246e-05 -6.20558441195649e-05 2.54890477118048e-05 -1.55984704942281e-05 8.4671749853149e-06 7.74863413189123e-06 -6.20558441195649e-05 7.84638731986405e-05 -2.35909133773522e-05 -1.62380044263961e-06 -1.31564496832277e-05 -9.95192973582809e-07 2.54890477118048e-05 -2.35909133773522e-05 0.000117766439709583 697 697 0 0 0 678 678 0 0 0 0 0 0 0 0 0 0 0 872 0 193 185 0 0 2676 +706 703 0.990049029763602 -0.136600954342157 -0.0338097313943967 0.0189868759175394 0.135815361678332 0.99043009593586 -0.02454409494495 0.0185234674373811 0.0368389223014626 0.0197079764890962 0.999126863549555 0.278758129586304 4.41984698458743e-05 2.13839074720959e-05 -4.07928090917638e-06 7.5185711623818e-06 -1.11097709011377e-05 2.58855296556031e-05 2.13839074720959e-05 7.1018269256856e-05 -8.8978044108459e-06 2.82329883735751e-06 -8.91861556456384e-06 3.49592736619354e-05 -4.07928090917638e-06 -8.8978044108459e-06 2.56806717734761e-05 -6.28755474170498e-06 4.26563443208676e-06 -2.80820659790238e-07 7.5185711623818e-06 2.82329883735751e-06 -6.28755474170498e-06 4.70482161226591e-05 -3.08617566195043e-05 1.67387464038629e-05 -1.11097709011377e-05 -8.91861556456384e-06 4.26563443208676e-06 -3.08617566195043e-05 7.42146852285161e-05 -7.99321438244322e-06 2.58855296556031e-05 3.49592736619354e-05 -2.80820659790238e-07 1.67387464038629e-05 -7.99321438244322e-06 0.00013974815976902 667 709 0 0 179 667 709 0 0 166 0 0 0 0 0 0 0 0 1054 0 0 0 0 0 2481 +707 703 0.978759365704064 -0.179017974496516 -0.0999133066900677 -0.0182485419447491 0.178476351215637 0.983838726904979 -0.014406647727441 0.0428124022383271 0.100877629350274 -0.00373152102430012 0.994891843190763 0.363962948828123 4.14108189519989e-05 3.21339572653239e-05 -9.77831520132262e-06 -3.87834083635067e-06 1.0613828255023e-05 1.51969219611272e-05 3.21339572653239e-05 5.62630293955855e-05 -1.16099931256508e-05 -3.97312043355796e-06 8.43102481946804e-06 2.68985295764187e-05 -9.77831520132262e-06 -1.16099931256508e-05 2.29679876629644e-05 -7.98874892796061e-07 -9.31835462468407e-07 -3.77476723207484e-06 -3.87834083635067e-06 -3.97312043355796e-06 -7.98874892796061e-07 5.83718931753036e-05 -5.55639012650203e-05 2.0024956897987e-05 1.0613828255023e-05 8.43102481946804e-06 -9.31835462468407e-07 -5.55639012650203e-05 0.000122122648252926 -6.03047934408113e-06 1.51969219611272e-05 2.68985295764187e-05 -3.77476723207484e-06 2.0024956897987e-05 -6.03047934408113e-06 0.000178381029826845 488 518 0 0 197 488 518 0 0 188 0 0 0 0 0 0 0 0 1024 0 0 0 0 0 2118 +708 711 0.999350698201922 0.0328924990633278 0.0147059684720176 0.148379304127824 -0.0328118333176476 0.999445330909265 -0.00569333979353376 -0.111321217356591 -0.0148850796996829 0.00520711331149033 0.999875652455492 -0.151048596130144 4.917373980605e-05 2.87093619752622e-05 -2.26476332574986e-06 6.17248111221684e-06 -4.54274610125769e-06 -1.97920233451061e-05 2.87093619752622e-05 5.71113211403703e-05 -9.94716849514168e-06 -7.85251348764964e-07 2.81520796180403e-06 -6.17935630300245e-06 -2.26476332574986e-06 -9.94716849514168e-06 1.85325358999833e-05 2.55789214321221e-08 5.03609131919363e-06 5.0202232779524e-06 6.17248111221684e-06 -7.85251348764964e-07 2.55789214321221e-08 0.000175521315918497 -0.000151268403422899 1.93568325371384e-05 -4.54274610125769e-06 2.81520796180403e-06 5.03609131919363e-06 -0.000151268403422899 0.000165176952804336 -2.25478665411599e-05 -1.97920233451061e-05 -6.17935630300245e-06 5.0202232779524e-06 1.93568325371384e-05 -2.25478665411599e-05 0.000187750466287769 1002 1001 0 0 18 995 994 0 0 13 0 0 0 0 0 0 0 0 862 0 25 18 0 0 3034 +708 712 0.99948337496433 0.0264351512552809 0.0182802064545984 0.163726152224481 -0.026237127767798 0.999595345656008 -0.0109889976495181 -0.113510404221539 -0.0185633051046564 0.0105037003458444 0.999772512115949 -0.166119019100478 5.86035016979348e-05 2.28119992190963e-05 1.03222892710828e-06 1.94203471203104e-06 6.87269787572355e-07 2.82585471466149e-05 2.28119992190963e-05 7.14195658615568e-05 -1.20615586575643e-05 -1.39449447549612e-05 1.60488879193424e-05 9.30972954542768e-06 1.03222892710828e-06 -1.20615586575643e-05 2.07674960636606e-05 2.8836135058302e-06 1.19329028813536e-06 2.37400453610985e-06 1.94203471203104e-06 -1.39449447549612e-05 2.8836135058302e-06 3.7839108850865e-05 -1.32295572574946e-05 -1.4136706944514e-05 6.87269787572355e-07 1.60488879193424e-05 1.19329028813536e-06 -1.32295572574946e-05 3.37884804881881e-05 1.66638721524314e-05 2.82585471466149e-05 9.30972954542768e-06 2.37400453610985e-06 -1.4136706944514e-05 1.66638721524314e-05 0.000326096549435057 995 993 0 0 14 992 990 0 0 11 0 0 0 0 0 0 0 0 794 0 22 20 0 0 2879 +708 704 0.971249986189564 -0.176822242720296 -0.159396859461336 -0.0678349169100132 0.178372009939988 0.983952146130136 -0.00464760108740064 0.0689111051972475 0.157660681200929 -0.0239179557082879 0.987203647176202 0.359203852569801 4.15898843877758e-05 3.34338464331692e-05 1.23808958529649e-06 -1.78137480818391e-06 9.38061188848167e-06 2.16203933441369e-05 3.34338464331692e-05 5.65466198015729e-05 3.0130653231589e-06 -1.72565834340328e-05 2.85517340832095e-05 4.03108946830747e-05 1.23808958529649e-06 3.0130653231589e-06 1.81075228427023e-05 7.36460209376954e-07 -6.79295465747597e-07 -1.50600394581975e-06 -1.78137480818391e-06 -1.72565834340328e-05 7.36460209376954e-07 6.95207959100917e-05 -6.64656700474592e-05 -1.89622214103688e-05 9.38061188848167e-06 2.85517340832095e-05 -6.79295465747597e-07 -6.64656700474592e-05 0.000129580168448106 6.88837611608515e-05 2.16203933441369e-05 4.03108946830747e-05 -1.50600394581975e-06 -1.89622214103688e-05 6.88837611608515e-05 0.000251450446216576 383 390 0 0 130 383 390 0 0 128 0 0 0 0 0 0 0 0 1042 0 0 0 0 0 2417 +709 712 0.999901594157425 -0.008734264729436 0.0109779151516467 0.144225780921312 0.00885693584106301 0.999898322276944 -0.0111758576968778 -0.0941677530987331 -0.0108791860425272 0.0112719886173514 0.999877285262378 -0.107281408833718 2.44197468138019e-05 8.18575707058851e-06 5.79319580676583e-06 1.92865031528579e-06 -3.21259619194268e-06 -1.3437139128945e-05 8.18575707058851e-06 3.94156711456905e-05 -1.033284878416e-05 -8.76167767135611e-06 9.96395037072759e-06 2.35574005649752e-05 5.79319580676583e-06 -1.033284878416e-05 2.12507570872913e-05 1.59490101938062e-06 1.36539733564268e-06 -1.52238582573537e-06 1.92865031528579e-06 -8.76167767135611e-06 1.59490101938062e-06 0.000125202974769471 -0.000104037836019742 -2.39775378562937e-05 -3.21259619194268e-06 9.96395037072759e-06 1.36539733564268e-06 -0.000104037836019742 0.000120541139387307 2.55323719588336e-05 -1.3437139128945e-05 2.35574005649752e-05 -1.52238582573537e-06 -2.39775378562937e-05 2.55323719588336e-05 0.000129838020741763 1055 1045 0 0 39 1048 1043 0 0 26 0 0 0 0 0 0 0 0 824 0 14 7 0 0 3291 +710 713 0.99995763108106 -0.0077056206504493 -0.00503581702857127 0.164450810957879 0.00774674369239396 0.999936386113578 0.00819827349400281 -0.12020730659218 0.00497232389514535 -0.00823693732581983 0.999953713358059 -0.0448588795198 4.5773042723344e-05 8.28314195906866e-06 7.48529215327065e-06 3.04872358743565e-05 -2.60890017595852e-05 -8.62214369139854e-06 8.28314195906866e-06 5.80238001003379e-05 -1.1869160603937e-05 1.6243940412883e-05 -1.0808498560355e-05 1.15091346447867e-07 7.48529215327065e-06 -1.1869160603937e-05 2.12847052886616e-05 5.9340920256535e-06 -5.91106013824583e-07 -2.93056142460217e-07 3.04872358743565e-05 1.6243940412883e-05 5.9340920256535e-06 0.000257281402682727 -0.000222993362214587 8.39581860724236e-05 -2.60890017595852e-05 -1.0808498560355e-05 -5.91106013824583e-07 -0.000222993362214587 0.000229781712772938 -7.92714891833051e-05 -8.62214369139854e-06 1.15091346447867e-07 -2.93056142460217e-07 8.39581860724236e-05 -7.92714891833051e-05 0.000142765391030087 1094 1076 0 0 48 1086 1075 0 0 31 0 0 0 0 0 0 0 0 773 0 21 7 0 0 3366 +711 714 0.999678144337301 0.0143138037244442 0.0209457097580724 0.187162376283881 -0.014475805703699 0.999866311526539 0.00760329688636158 -0.165240469335381 -0.0208340774588193 -0.00790405574698744 0.999751702733828 -0.0278092884861618 2.84119335887477e-05 1.59066743333595e-05 3.75695373258224e-06 4.00552655443811e-06 -2.85610977901489e-06 -1.07088271764351e-05 1.59066743333595e-05 4.07374330593131e-05 -9.14771197418119e-06 1.17402148617629e-05 -1.08774118834126e-05 6.96172403111339e-06 3.75695373258224e-06 -9.14771197418119e-06 1.88238124916425e-05 9.5784908102485e-07 3.18260458273788e-06 7.68359698250349e-07 4.00552655443811e-06 1.17402148617629e-05 9.5784908102485e-07 4.62484838602896e-05 -2.34150719165706e-05 1.47124349672576e-05 -2.85610977901489e-06 -1.08774118834126e-05 3.18260458273788e-06 -2.34150719165706e-05 4.41985706015741e-05 -1.64861220537986e-05 -1.07088271764351e-05 6.96172403111339e-06 7.68359698250349e-07 1.47124349672576e-05 -1.64861220537986e-05 0.000116096279055305 1180 1173 0 0 30 1167 1167 0 0 15 0 0 0 0 0 0 0 0 728 0 42 32 0 0 3422 +712 714 0.999632462991427 0.0201478656867486 0.0181384244619747 0.146186206148121 -0.0204344721907372 0.999667021176577 0.015756875268735 -0.141302964550045 -0.0178149173441813 -0.0161217331641863 0.999711317551123 -0.0452721418906935 2.05601478047252e-05 1.03458416872058e-05 6.73566553001455e-07 2.89478934364793e-06 -1.83029929788704e-06 -9.47738942778103e-06 1.03458416872058e-05 2.44054866851749e-05 -8.88275965316194e-06 -3.08680677902973e-06 4.55106655797946e-06 -2.38272932186072e-06 6.73566553001455e-07 -8.88275965316194e-06 1.7073396245137e-05 3.38415632047285e-06 7.49058143410727e-09 -5.18548961764297e-07 2.89478934364793e-06 -3.08680677902973e-06 3.38415632047285e-06 6.47442493878975e-05 -4.54053826552135e-05 -7.35580738143013e-06 -1.83029929788704e-06 4.55106655797946e-06 7.49058143410727e-09 -4.54053826552135e-05 6.06168092721796e-05 9.47052042871159e-06 -9.47738942778103e-06 -2.38272932186072e-06 -5.18548961764297e-07 -7.35580738143013e-06 9.47052042871159e-06 7.11885699709742e-05 1206 1204 0 0 25 1193 1193 0 0 9 0 0 0 0 0 0 0 0 759 0 63 49 0 0 3556 +712 715 0.999384070659422 0.0100887367395659 0.0336109610574229 0.227483906854206 -0.0103564551867415 0.999915943248713 0.00780065849794117 -0.222634618525892 -0.0335294370392478 -0.00814394425547097 0.999404549231088 -0.0178494989371586 4.08542941856092e-05 1.75902210754302e-05 4.91428580325874e-06 3.44917719366635e-06 -2.53746131392811e-06 1.27358927048745e-05 1.75902210754302e-05 5.30149913367524e-05 -7.64678211339649e-06 -2.40102202509558e-05 2.43358192250207e-05 9.84487520233493e-06 4.91428580325874e-06 -7.64678211339649e-06 1.85662735435555e-05 6.10909915771836e-06 2.19740227854363e-06 -5.80801374063788e-07 3.44917719366635e-06 -2.40102202509558e-05 6.10909915771836e-06 0.00011278914385464 -9.00639405849904e-05 -4.10002435152661e-05 -2.53746131392811e-06 2.43358192250207e-05 2.19740227854363e-06 -9.00639405849904e-05 0.000110612070994077 3.83124836668947e-05 1.27358927048745e-05 9.84487520233493e-06 -5.80801374063788e-07 -4.10002435152661e-05 3.83124836668947e-05 0.00023858765014531 1222 1211 0 0 34 1209 1206 0 0 22 0 0 0 0 0 0 0 0 704 0 51 36 0 0 3266 +713 609 0.999913041815386 0.00620839413474636 0.0116346314840455 -0.645160276784222 -0.0056727034429027 0.99894716758751 -0.0455233654790561 0.37160930888036 -0.0119050091621458 0.0454534070357601 0.998895519334075 0.309825714474607 2.81127069055814e-05 2.16795176901946e-05 1.7081429441249e-06 -6.98630864573592e-06 8.20991158018456e-06 4.92060762725208e-07 2.16795176901946e-05 3.44429164244221e-05 2.38866602291901e-07 -1.18195959979213e-05 1.23425533538423e-05 6.00248821856354e-06 1.7081429441249e-06 2.38866602291901e-07 1.17713531327461e-05 4.72647842901828e-06 6.15403879599977e-06 -9.52215526779977e-07 -6.98630864573592e-06 -1.18195959979213e-05 4.72647842901828e-06 7.92093078860464e-05 -5.22657917593956e-05 -4.27637008301161e-05 8.20991158018456e-06 1.23425533538423e-05 6.15403879599977e-06 -5.22657917593956e-05 6.99717435250797e-05 4.52786575040469e-05 4.92060762725208e-07 6.00248821856354e-06 -9.52215526779977e-07 -4.27637008301161e-05 4.52786575040469e-05 0.000192880496819199 625 625 0 0 0 621 621 0 0 0 0 0 0 0 0 0 0 0 1216 0 54 40 0 0 2257 +713 611 0.991378597353995 -0.130016443543562 -0.0162542645698986 -0.561125910448839 0.12913395159269 0.990516189694955 -0.046926543642633 0.380416681536831 0.0222013345202766 0.0444229936009605 0.998766087923017 0.467204121061386 3.03522734845781e-05 2.7206225158015e-05 1.56278615095062e-06 -6.16119048131768e-07 -5.16461840943834e-08 -7.41488793481942e-06 2.7206225158015e-05 4.50250584931239e-05 -1.19517392924533e-07 2.54568712607799e-06 -3.99537155156272e-06 7.21994166928648e-06 1.56278615095062e-06 -1.19517392924533e-07 1.32410423191122e-05 5.75778539464967e-06 6.32530684270541e-06 -5.31908584307212e-07 -6.16119048131768e-07 2.54568712607799e-06 5.75778539464967e-06 1.85988478514592e-05 2.82449572825586e-06 1.22809752607227e-05 -5.16461840943834e-08 -3.99537155156272e-06 6.32530684270541e-06 2.82449572825586e-06 1.93050034749644e-05 -9.82689979413131e-06 -7.41488793481942e-06 7.21994166928648e-06 -5.31908584307212e-07 1.22809752607227e-05 -9.82689979413131e-06 0.000109563726525246 401 366 0 0 129 401 366 0 0 128 0 0 0 0 0 0 0 0 784 0 0 0 0 0 1876 +713 716 0.999338729526863 -0.0265856350979196 0.0248053960677066 0.244339644422463 0.0266154247609186 0.999645366947108 -0.000871496401569015 -0.242061061428037 -0.0247734299690496 0.00153112625943604 0.999691918953007 -0.00249029373818209 3.11910409877845e-05 1.1991127057647e-05 4.27605310168778e-06 6.07922395720404e-07 -1.19234262346519e-06 7.17646433977367e-06 1.1991127057647e-05 3.31609047576499e-05 -6.89949615651204e-06 -7.26579641373628e-06 7.65292270564919e-06 7.38697830611737e-06 4.27605310168778e-06 -6.89949615651204e-06 1.94165994763337e-05 3.59315225493351e-06 2.95346330267098e-06 5.25259180507011e-06 6.07922395720404e-07 -7.26579641373628e-06 3.59315225493351e-06 6.33763965355829e-05 -4.61115518422837e-05 -1.20324401439435e-05 -1.19234262346519e-06 7.65292270564919e-06 2.95346330267098e-06 -4.61115518422837e-05 7.11808287112369e-05 8.84783070422522e-06 7.17646433977367e-06 7.38697830611737e-06 5.25259180507011e-06 -1.20324401439435e-05 8.84783070422522e-06 0.000157493318561635 1272 1256 0 0 63 1272 1256 0 0 51 0 0 0 0 0 0 0 0 704 0 12 1 0 0 3234 +713 608 0.996857953588117 0.0775984561836139 0.015896539435714 -0.663843350910969 -0.0770537612537319 0.996500025911769 -0.0324101254933804 0.323288008421734 -0.0183558776625999 0.0310834032204252 0.999348229497342 0.222175265663785 3.05931224620844e-05 2.39730134685357e-05 4.200685993409e-06 5.12725576048123e-06 -4.70403296496146e-06 -1.08700316916581e-05 2.39730134685357e-05 3.92234945202036e-05 -4.23389278336276e-06 -3.52973342772611e-07 2.15959741317841e-06 1.3818460091123e-07 4.200685993409e-06 -4.23389278336276e-06 1.615056467272e-05 6.6314501030898e-06 2.35867048098164e-06 -9.15540403415824e-07 5.12725576048123e-06 -3.52973342772611e-07 6.6314501030898e-06 8.08548319672585e-05 -4.2880081711404e-05 3.76628295291239e-05 -4.70403296496146e-06 2.15959741317841e-06 2.35867048098164e-06 -4.2880081711404e-05 5.81202866627413e-05 -2.51055363111842e-05 -1.08700316916581e-05 1.3818460091123e-07 -9.15540403415824e-07 3.76628295291239e-05 -2.51055363111842e-05 0.000149511673251453 740 740 0 0 0 723 723 0 0 0 0 0 0 0 0 0 0 0 1495 0 178 149 0 0 2247 +713 612 0.982847573451968 -0.184230938441417 0.0083431816816681 -0.511950357952203 0.184378194944577 0.980659556884983 -0.0656621254539355 0.354945899761294 0.00391517414148106 0.0660741614486598 0.997807033749662 0.523295358631139 3.22004507337618e-05 1.79284957760384e-05 -1.58751777106883e-06 -1.92386206130412e-06 5.55907596478905e-06 -1.0388857370537e-05 1.79284957760384e-05 4.68333163369022e-05 -6.27072541631228e-06 1.9591845128247e-06 6.39719530844766e-06 6.83343411479354e-06 -1.58751777106883e-06 -6.27072541631228e-06 1.75306310504832e-05 2.11616147515147e-06 3.71483562118476e-06 6.57092490720982e-06 -1.92386206130412e-06 1.9591845128247e-06 2.11616147515147e-06 2.71381517651801e-05 -8.07764496487458e-06 -1.13364380646241e-05 5.55907596478905e-06 6.39719530844766e-06 3.71483562118476e-06 -8.07764496487458e-06 4.57460495304043e-05 2.13338230304997e-05 -1.0388857370537e-05 6.83343411479354e-06 6.57092490720982e-06 -1.13364380646241e-05 2.13338230304997e-05 0.000163925193189862 233 221 0 0 197 233 221 0 0 177 0 0 0 0 0 0 0 0 702 0 0 0 0 0 2036 +714 612 0.981045144703738 -0.19222839332923 -0.0244677103809289 -0.612582967059163 0.19001212083988 0.979050008152413 -0.073187946211721 0.431453142843725 0.0380239133592645 0.0671515177402709 0.99701798162221 0.512037485494611 5.64884050175224e-05 1.54831770043827e-05 3.04391055810587e-06 -5.55900839667614e-06 7.28541676218274e-06 2.48364853361031e-05 1.54831770043827e-05 5.96676990678191e-05 -4.8546565282584e-06 2.29549664702075e-06 1.57117775349012e-06 2.29575199620432e-05 3.04391055810587e-06 -4.8546565282584e-06 1.77724796862963e-05 4.55134299286097e-06 2.60913960397964e-06 -4.20519135404811e-06 -5.55900839667614e-06 2.29549664702075e-06 4.55134299286097e-06 2.56087189735816e-05 -3.64997323389934e-06 3.22416737928524e-06 7.28541676218274e-06 1.57117775349012e-06 2.60913960397964e-06 -3.64997323389934e-06 4.11962539784151e-05 2.66786672614287e-05 2.48364853361031e-05 2.29575199620432e-05 -4.20519135404811e-06 3.22416737928524e-06 2.66786672614287e-05 0.000247888531822113 156 142 0 0 199 156 142 0 0 182 0 0 0 0 0 0 0 0 693 0 0 0 0 0 2065 +714 610 0.996280760981139 -0.0750859367729621 -0.0422699349156127 -0.65215099751311 0.0738007751135833 0.99678524887763 -0.0311867473872412 0.412041962731077 0.0444757337373729 0.0279512024587143 0.998619366620553 0.365602223506286 3.21794511447253e-05 1.66201184322143e-05 2.35443576483231e-06 -5.04347407573296e-07 8.96415348971732e-07 -5.85158620144052e-06 1.66201184322143e-05 4.52771841429522e-05 -1.29858908060478e-06 2.09343353957905e-06 1.0138131909193e-06 -3.35644890250415e-06 2.35443576483231e-06 -1.29858908060478e-06 1.42831757061759e-05 4.85793121323193e-06 6.04100634624821e-06 8.01071541273934e-07 -5.04347407573296e-07 2.09343353957905e-06 4.85793121323193e-06 8.90519305303007e-05 -7.11232258909288e-05 -2.46521321991313e-05 8.96415348971732e-07 1.0138131909193e-06 6.04100634624821e-06 -7.11232258909288e-05 9.96609062127416e-05 2.99266062588172e-05 -5.85158620144052e-06 -3.35644890250415e-06 8.01071541273934e-07 -2.46521321991313e-05 2.99266062588172e-05 0.000102362780095349 467 454 0 0 49 467 454 0 0 40 0 0 0 0 0 0 0 0 1091 0 1 0 0 0 2117 +714 607 0.987673815949162 0.151903513713349 -0.037759181796737 -0.753229656559287 -0.153146039127157 0.987668220804776 -0.0325234732461247 0.323995124450865 0.0323531140399789 0.037905252061773 0.99875746198867 0.11616053386681 3.32007335530991e-05 2.94771833619296e-05 -2.65926921771963e-06 -6.28118284851947e-06 5.26281914133783e-06 1.00911015107981e-05 2.94771833619296e-05 5.30607039261914e-05 -2.68301380687782e-06 -3.87349547219342e-06 4.43140802783058e-06 2.89723833767676e-05 -2.65926921771963e-06 -2.68301380687782e-06 1.50315499306453e-05 2.62814340056997e-06 6.45412664754347e-06 3.36989130496121e-06 -6.28118284851947e-06 -3.87349547219342e-06 2.62814340056997e-06 0.000151049568515125 -7.5141827226014e-05 -6.67764714975279e-05 5.26281914133783e-06 4.43140802783058e-06 6.45412664754347e-06 -7.5141827226014e-05 6.90088097960102e-05 4.79224320778612e-05 1.00911015107981e-05 2.89723833767676e-05 3.36989130496121e-06 -6.67764714975279e-05 4.79224320778612e-05 0.000254724302869326 670 670 0 0 0 669 669 0 0 0 0 0 0 0 0 0 0 0 1578 0 272 257 0 0 2075 +715 612 0.98253546426962 -0.184579853017897 -0.0235444114892114 -0.670345889549403 0.182721017718803 0.980985727495803 -0.0654219545209014 0.498710110541051 0.0351723063828161 0.0599773316297209 0.997579885800777 0.52164219224706 4.80835758728028e-05 3.49258268870688e-05 7.27180101499509e-07 -7.4876277861683e-07 -3.81832646175279e-06 8.70214461734122e-06 3.49258268870688e-05 4.40604160989109e-05 -1.94369194090411e-06 -3.92767719198731e-06 1.91181395841944e-06 4.56893896387681e-06 7.27180101499509e-07 -1.94369194090411e-06 1.57560975803249e-05 5.06031475615839e-06 4.62290178632713e-06 1.9177087294761e-06 -7.4876277861683e-07 -3.92767719198731e-06 5.06031475615839e-06 6.80642131703681e-05 -6.22782020315588e-05 1.09671030911976e-05 -3.81832646175279e-06 1.91181395841944e-06 4.62290178632713e-06 -6.22782020315588e-05 0.000114876354566239 6.90378163564055e-06 8.70214461734122e-06 4.56893896387681e-06 1.9177087294761e-06 1.09671030911976e-05 6.90378163564055e-06 0.00024090084965019 136 124 0 0 174 136 124 0 0 167 0 0 0 0 0 0 0 0 719 0 0 0 0 0 1963 +715 611 0.990293982948743 -0.129555994003194 -0.0503296309678321 -0.705382508522529 0.127465563822191 0.990921412699849 -0.04274674130769 0.514658769142674 0.0554108055798215 0.0359165459193943 0.997817440393891 0.455991926710573 2.99315001073834e-05 2.21403852830308e-05 1.6283544081917e-06 -5.5547085685021e-07 -6.38582541324806e-07 5.99204589728226e-06 2.21403852830308e-05 3.39152024191868e-05 -3.06138431380251e-07 1.81736415792823e-07 1.22241432611844e-06 7.62870238844156e-06 1.6283544081917e-06 -3.06138431380251e-07 1.40595197473563e-05 5.09322081633226e-06 4.24808243286008e-06 1.87124654290025e-06 -5.5547085685021e-07 1.81736415792823e-07 5.09322081633226e-06 2.41022834649681e-05 1.12506777943446e-06 2.04882520312823e-05 -6.38582541324806e-07 1.22241432611844e-06 4.24808243286008e-06 1.12506777943446e-06 2.40607248067516e-05 -5.7967986215544e-06 5.99204589728226e-06 7.62870238844156e-06 1.87124654290025e-06 2.04882520312823e-05 -5.7967986215544e-06 0.000189332741784782 269 237 0 0 122 269 237 0 0 118 0 0 0 0 0 0 0 0 863 0 0 0 0 0 1682 +715 609 0.999520803565384 0.00575674284637631 -0.0304141932625263 -0.791857845344707 -0.00679597110105487 0.999392687162865 -0.0341770628079952 0.510994846524148 0.0301989737706968 0.034367379259826 0.998952904408415 0.246135163664804 2.45718545885577e-05 1.60714381828951e-05 2.14881412365546e-06 4.78739009788103e-06 -2.13178113289323e-07 -1.27332336282062e-05 1.60714381828951e-05 3.06554905914014e-05 7.2607516035414e-07 -1.84527981634405e-06 3.24113573821601e-06 -7.30533410068983e-06 2.14881412365546e-06 7.2607516035414e-07 1.31038661849745e-05 3.88491207119813e-06 6.10824789598125e-06 -2.62471694067998e-06 4.78739009788103e-06 -1.84527981634405e-06 3.88491207119813e-06 6.59396516858727e-05 -3.29966212416637e-05 7.64021250488079e-06 -2.13178113289323e-07 3.24113573821601e-06 6.10824789598125e-06 -3.29966212416637e-05 5.15350855034078e-05 -5.71379179802346e-06 -1.27332336282062e-05 -7.30533410068983e-06 -2.62471694067998e-06 7.64021250488079e-06 -5.71379179802346e-06 7.09373810374463e-05 507 507 0 0 0 495 495 0 0 0 0 0 0 0 0 0 0 0 1363 0 54 40 0 0 2038 +716 607 0.982084441432947 0.18451197043827 -0.0382816230105786 -0.892778083081125 -0.185432621989614 0.982409518947405 -0.0220517523926348 0.503015360470139 0.0335394185607665 0.0287553446600079 0.99902364214071 0.0894866031206171 4.53532480394414e-05 2.32248802487012e-05 1.50503384741889e-06 -6.53035815487824e-06 4.78590872806146e-06 9.89697466435205e-06 2.32248802487012e-05 6.71851982416649e-05 1.63608148873076e-06 -2.51858581388127e-05 1.65620317286972e-05 1.63304170737471e-05 1.50503384741889e-06 1.63608148873076e-06 1.44512829233962e-05 4.16637367124064e-06 6.52830189843335e-06 -5.13891734990906e-06 -6.53035815487824e-06 -2.51858581388127e-05 4.16637367124064e-06 0.00015229422290205 -8.02841117949678e-05 -5.85046115812842e-05 4.78590872806146e-06 1.65620317286972e-05 6.52830189843335e-06 -8.02841117949678e-05 7.17603038040195e-05 4.63118895702884e-05 9.89697466435205e-06 1.63304170737471e-05 -5.13891734990906e-06 -5.85046115812842e-05 4.63118895702884e-05 0.000260779978990511 723 723 0 0 0 719 719 0 0 0 0 0 0 0 0 37 37 0 1598 0 264 243 0 0 1704 +716 609 0.999377792307158 0.031395705775261 -0.0160728933967617 -0.830245517512799 -0.0320539383268381 0.998582994067949 -0.0424799834749266 0.586134519124317 0.0147164289489566 0.0429687516360903 0.998968024063747 0.275364347513039 2.98870317614585e-05 1.13223769381886e-05 3.44453932046264e-06 -1.33222687532364e-06 8.46903010515489e-07 -3.64942983693058e-06 1.13223769381886e-05 3.11372698078535e-05 -4.61151251153525e-06 -1.4321555909898e-06 3.8165059358195e-06 -4.93334210223214e-07 3.44453932046264e-06 -4.61151251153525e-06 1.58492128113483e-05 2.52418496237936e-06 6.10496621430705e-06 -1.28948718017075e-06 -1.33222687532364e-06 -1.4321555909898e-06 2.52418496237936e-06 5.84091969727e-05 -2.40753335671583e-05 7.3793602980877e-06 8.46903010515489e-07 3.8165059358195e-06 6.10496621430705e-06 -2.40753335671583e-05 4.24290919098159e-05 1.91402558686647e-06 -3.64942983693058e-06 -4.93334210223214e-07 -1.28948718017075e-06 7.3793602980877e-06 1.91402558686647e-06 0.00010445917777456 553 553 0 0 7 536 536 0 0 0 0 0 0 0 0 0 0 0 1429 0 109 94 0 0 1876 +716 611 0.993571512681273 -0.104514492254872 -0.0435013804028499 -0.783170469841359 0.102072642604504 0.993254744914592 -0.0550107929081348 0.623410055517673 0.0489573775847969 0.0502168558688691 0.997537689797566 0.482064256279252 3.6390126584207e-05 1.95960202692798e-05 6.75572015375526e-06 -8.45680616692484e-06 6.05252340230337e-06 -2.15069513699872e-05 1.95960202692798e-05 5.83396200062913e-05 -1.39303347853205e-06 4.81597723783775e-09 2.07679931694671e-06 9.97703400534422e-06 6.75572015375526e-06 -1.39303347853205e-06 1.79650308355824e-05 -1.15344730678179e-06 7.5270068113913e-06 -3.1684741086e-06 -8.45680616692484e-06 4.81597723783775e-09 -1.15344730678179e-06 0.000103291734294478 -9.02814891392561e-05 -2.45963223908099e-05 6.05252340230337e-06 2.07679931694671e-06 7.5270068113913e-06 -9.02814891392561e-05 0.000136111338865518 3.33049578403652e-05 -2.15069513699872e-05 9.97703400534422e-06 -3.1684741086e-06 -2.45963223908099e-05 3.33049578403652e-05 0.000103555002726498 300 265 0 0 131 300 265 0 0 128 0 0 0 0 0 0 0 0 934 0 0 0 0 0 1601 +717 605 0.889893620040503 0.455039999203087 0.0320615679040259 -1.02801587986371 -0.455243641078166 0.890366279664102 -0.0010560752811946 0.50659586382204 -0.0290270954300188 -0.0136560302562861 0.999485337845701 0.0218539542283292 3.93780762066615e-05 2.98237139833475e-06 -1.94875659190593e-06 -3.19255468591788e-06 1.46247609542522e-06 5.9801697777438e-06 2.98237139833475e-06 6.31240494309559e-05 -1.07775028247711e-06 2.02258824106523e-05 -2.36619598723584e-06 -7.01965818654528e-06 -1.94875659190593e-06 -1.07775028247711e-06 1.31861063904796e-05 5.92495366197338e-06 5.58647705566194e-06 2.00378814290877e-06 -3.19255468591788e-06 2.02258824106523e-05 5.92495366197338e-06 0.000788291750889376 -0.000264903936152224 -4.05025098219877e-05 1.46247609542522e-06 -2.36619598723584e-06 5.58647705566194e-06 -0.000264903936152224 0.000115100772425616 6.42398921499364e-06 5.9801697777438e-06 -7.01965818654528e-06 2.00378814290877e-06 -4.05025098219877e-05 6.42398921499364e-06 0.00014333114536615 811 811 0 0 0 807 807 0 0 0 0 0 0 0 0 505 371 0 2822 0 835 815 0 0 968 +717 610 0.997597094136855 0.00304554168396786 -0.0692153338903589 -0.830954887796246 -0.00536961287520384 0.999427098371021 -0.0334161981567695 0.693011419558271 0.0690739098884166 0.0337075617263138 0.997041922516397 0.371684569869795 3.33096565471109e-05 2.45483835121613e-05 -4.23080021707148e-07 4.82735929675161e-06 -3.31540076610458e-06 -1.60602619737336e-05 2.45483835121613e-05 5.23792389240149e-05 -8.83794112236157e-07 2.22601784096681e-05 -2.41336869350114e-05 2.1854226803913e-05 -4.23080021707148e-07 -8.83794112236157e-07 1.77340218682505e-05 5.19860365734882e-06 1.10617948811786e-06 1.7190441648505e-06 4.82735929675161e-06 2.22601784096681e-05 5.19860365734882e-06 0.000115286105638958 -9.5380557942745e-05 5.53993181002742e-05 -3.31540076610458e-06 -2.41336869350114e-05 1.10617948811786e-06 -9.5380557942745e-05 0.000136209798996296 -6.11254898885017e-05 -1.60602619737336e-05 2.1854226803913e-05 1.7190441648505e-06 5.53993181002742e-05 -6.11254898885017e-05 0.000159845164313773 419 413 0 0 26 411 411 0 0 17 0 0 0 0 0 0 0 0 1380 0 57 46 0 0 1598 +718 612 0.993089473557653 -0.110960806275829 -0.0382229901970142 -0.855344515641149 0.10802727759988 0.99155453545661 -0.0717614834697908 0.786085767979452 0.0458628913539205 0.0671364482680205 0.996689165442574 0.563358484348948 7.91197092700013e-05 3.21160484077625e-05 -8.9488429040238e-06 1.06582505592962e-05 1.10965395211138e-05 0.000135978313899291 3.21160484077625e-05 7.61636974538038e-05 -1.01564546016074e-05 9.34167531069738e-06 -3.89446956555968e-06 4.22711416436285e-05 -8.9488429040238e-06 -1.01564546016074e-05 2.14875812805469e-05 -1.36559330443585e-07 1.77856224687476e-06 -1.58731527908443e-05 1.06582505592962e-05 9.34167531069738e-06 -1.36559330443585e-07 3.84306910593701e-05 3.54874502297645e-06 8.03137654091331e-05 1.10965395211138e-05 -3.89446956555968e-06 1.77856224687476e-06 3.54874502297645e-06 3.73333295976033e-05 1.01450436871344e-05 0.000135978313899291 4.22711416436285e-05 -1.58731527908443e-05 8.03137654091331e-05 1.01450436871344e-05 0.000826724542499997 103 94 0 0 141 103 94 0 0 130 0 0 0 0 0 0 0 0 945 0 0 0 0 0 1527 +720 623 0.99687959774891 -0.0520898983034694 -0.0593102865168017 -0.953245259659527 0.0516502611385797 0.99862537396862 -0.00892261118458874 0.893073996883898 0.0596935349622337 0.00583137726176595 0.998199717953749 0.744700036176409 0.000187401344261972 0.000168564841385305 3.35824771701583e-06 -2.17102227007004e-05 2.23408908839528e-05 -0.000121071369948555 0.000168564841385305 0.000236510173481049 1.15139527575869e-05 -6.00313852520012e-05 3.28898962897817e-05 -0.000105966817213821 3.35824771701583e-06 1.15139527575869e-05 1.94967473527469e-05 -2.87660176730407e-06 7.12045560244828e-06 2.91670223340657e-08 -2.17102227007004e-05 -6.00313852520012e-05 -2.87660176730407e-06 0.000120877538653035 -7.05856710581534e-05 6.8531790587103e-05 2.23408908839528e-05 3.28898962897817e-05 7.12045560244828e-06 -7.05856710581534e-05 0.000137839075004222 -8.49363353780373e-05 -0.000121071369948555 -0.000105966817213821 2.91670223340657e-08 6.8531790587103e-05 -8.49363353780373e-05 0.000397647146046978 63 59 0 0 55 63 59 0 0 40 0 0 0 0 0 0 0 0 747 0 0 0 0 0 879 +721 623 0.994291682476374 -0.0721246271546293 -0.078626257167103 -1.0863611553192 0.0737179176942901 0.997124705196272 0.0175496694574579 0.984017117185831 0.0771344201321277 -0.0232456543262146 0.996749678096676 0.735528661172555 0.000121840451227283 9.20681855480366e-05 1.5257863011247e-06 -6.13334719349954e-05 7.35370771509794e-05 8.92384881019761e-05 9.20681855480366e-05 0.000100110392250019 -2.95620068002213e-07 -6.18413160742493e-05 7.47926846602323e-05 6.70190609214612e-05 1.5257863011247e-06 -2.95620068002213e-07 1.71884362306004e-05 3.24864237391017e-06 9.3175889302769e-06 3.07890925722504e-06 -6.13334719349954e-05 -6.18413160742493e-05 3.24864237391017e-06 0.000146242502531476 -0.00013230583790054 -0.000212764610878719 7.35370771509794e-05 7.47926846602323e-05 9.3175889302769e-06 -0.00013230583790054 0.000202789649131968 0.000277041937342551 8.92384881019761e-05 6.70190609214612e-05 3.07890925722504e-06 -0.000212764610878719 0.000277041937342551 0.000746753131778416 44 41 0 0 69 44 41 0 0 53 0 0 0 0 0 0 0 0 724 0 0 0 0 0 710 +721 624 0.992663921176994 -0.108724439380206 -0.052889846615159 -1.09354075066345 0.111528899065445 0.992329570772313 0.0533228623020727 1.00134373116325 0.0466866604798935 -0.0588304279458853 0.99717567984831 0.754902869755484 0.000144013681278794 0.00011843005406728 1.27062657880898e-05 -1.12592686399073e-05 1.31629633327659e-05 -9.85885024739818e-05 0.00011843005406728 0.000157104312751779 1.08371157591243e-05 -2.09801688192287e-05 5.65741941691244e-06 -7.7618515436812e-05 1.27062657880898e-05 1.08371157591243e-05 2.10711994544749e-05 4.91159323180925e-06 8.30699499936468e-06 -1.03608026815573e-05 -1.12592686399073e-05 -2.09801688192287e-05 4.91159323180925e-06 4.16949705879839e-05 6.18225638468396e-06 8.17533905073796e-05 1.31629633327659e-05 5.65741941691244e-06 8.30699499936468e-06 6.18225638468396e-06 5.93516086067588e-05 -0.000122929646027663 -9.85885024739818e-05 -7.7618515436812e-05 -1.03608026815573e-05 8.17533905073796e-05 -0.000122929646027663 0.000666141155680832 30 23 0 0 76 30 23 0 0 70 0 0 0 0 0 0 0 0 703 0 0 0 0 0 679 +722 726 0.999995865941693 -0.000752268482419893 0.00277528226552244 0.330173584299131 0.000820244610997524 0.999697673780728 -0.0245741375470187 -0.377392056557184 -0.00275595687576842 0.0245763123664235 0.999694158016424 0.00741302552195883 0.000159748155596752 0.000134834682675854 6.73764704391982e-06 1.66345315555898e-05 -1.93064138777609e-05 -5.09991555938855e-05 0.000134834682675854 0.000148103786645137 8.43731582736095e-06 1.87589627712061e-05 -2.06360956852986e-05 -2.88622525130685e-05 6.73764704391982e-06 8.43731582736095e-06 1.53875608911565e-05 4.60245846336443e-06 -5.22352159094443e-08 -1.03904320380906e-05 1.66345315555898e-05 1.87589627712061e-05 4.60245846336443e-06 4.40857458107745e-05 -2.22168186304889e-05 -2.73453012494684e-05 -1.93064138777609e-05 -2.06360956852986e-05 -5.22352159094443e-08 -2.22168186304889e-05 4.90664403419805e-05 2.45558651510304e-05 -5.09991555938855e-05 -2.88622525130685e-05 -1.03904320380906e-05 -2.73453012494684e-05 2.45558651510304e-05 0.000547931058247434 1587 1566 0 0 43 1561 1560 0 0 16 0 0 0 0 0 0 0 0 678 0 56 32 0 0 2087 +722 589 -0.00494023969991405 0.999353370660098 0.0356150892461194 -1.67278110901811 -0.988942638995896 0.000396289422699259 -0.148298009867046 0.552874682517635 -0.148216229905973 -0.0359539080628951 0.988301201905302 -0.248815355837107 7.60454119207358e-05 5.52557226373537e-05 -2.47583247201126e-06 -9.90311890974477e-06 -1.21412350653619e-05 1.16371547856193e-05 5.52557226373537e-05 7.12916470867323e-05 -1.28241515600567e-06 -2.34667532056617e-05 -2.33353680113708e-05 -1.57497660659695e-05 -2.47583247201126e-06 -1.28241515600567e-06 1.86997834352302e-05 9.06256152321283e-07 1.33137811463738e-05 -1.10376524254258e-05 -9.90311890974477e-06 -2.34667532056617e-05 9.06256152321283e-07 0.000141240437262487 8.43422349035281e-05 -0.000182681536331634 -1.21412350653619e-05 -2.33353680113708e-05 1.33137811463738e-05 8.43422349035281e-05 0.000111101845178844 -0.000145047454238018 1.16371547856193e-05 -1.57497660659695e-05 -1.10376524254258e-05 -0.000182681536331634 -0.000145047454238018 0.000477452649660005 0 0 0 487 0 0 0 0 477 0 0 0 0 0 0 0 0 0 1349 0 542 547 0 54 0 +722 623 0.992623395783852 -0.0922068048709589 -0.078719116344276 -1.23628860313641 0.0955644349111714 0.994619207317671 0.0400008901760552 1.10718324874144 0.0746071908239632 -0.0472285673110803 0.996093986281967 0.67962156260844 0.00012985283749234 6.8546737447647e-05 4.539692980445e-07 -1.05280490822177e-05 1.25766627389244e-05 6.39584562517471e-05 6.8546737447647e-05 0.000102560803457132 2.97575429163028e-06 -3.26946031634671e-05 5.73232871394617e-06 -7.9192765758397e-05 4.539692980445e-07 2.97575429163028e-06 1.73707616630098e-05 2.1243541251504e-06 3.91699585593376e-06 -1.86877700554906e-06 -1.05280490822177e-05 -3.26946031634671e-05 2.1243541251504e-06 4.59720796168798e-05 7.96043908184227e-06 4.64555222254729e-05 1.25766627389244e-05 5.73232871394617e-06 3.91699585593376e-06 7.96043908184227e-06 3.90541579178545e-05 2.41083640504269e-05 6.39584562517471e-05 -7.9192765758397e-05 -1.86877700554906e-06 4.64555222254729e-05 2.41083640504269e-05 0.000682534309162884 37 34 0 0 73 37 34 0 0 65 0 0 0 0 0 0 0 0 860 0 0 0 0 0 654 +723 587 0.259309945301232 0.961252068082111 0.0935564742587905 -1.71719685275042 -0.95798371395807 0.268297985004553 -0.101407075855678 0.698160271391453 -0.122578774912194 -0.0633297153819649 0.990436162047138 -0.139838466038995 0.000538883894997677 0.000433459806867792 -5.5249912563453e-05 -0.000312573353046844 -0.000168558076198661 0.000118241788780842 0.000433459806867792 0.000370835836889782 -4.22871422891648e-05 -0.000275604763035072 -0.00014541683562279 8.86626364572572e-05 -5.5249912563453e-05 -4.22871422891648e-05 2.26660150253501e-05 2.45368951322434e-05 2.70479601529088e-05 -1.57921562171749e-05 -0.000312573353046844 -0.000275604763035072 2.45368951322434e-05 0.000493639556676399 0.00022886777603118 -0.000326358195798809 -0.000168558076198661 -0.00014541683562279 2.70479601529088e-05 0.00022886777603118 0.000146344892078949 -0.000155641794373928 0.000118241788780842 8.86626364572572e-05 -1.57921562171749e-05 -0.000326358195798809 -0.000155641794373928 0.000630091495967579 221 233 0 231 0 220 232 0 231 0 0 0 0 0 0 0 0 0 2262 0 572 572 0 0 0 +724 727 0.996763800427833 -0.0282767772696444 0.0752485881854694 0.25732471197096 0.0294348416401463 0.999464043577638 -0.0143253514112949 -0.31476962530725 -0.0748031834501911 0.0164939219920704 0.997061900928441 0.0288423306475689 5.48438790845488e-05 3.55461064271121e-05 -1.64069725638321e-06 1.25247774964604e-06 7.92437826909916e-07 -2.23192517915752e-06 3.55461064271121e-05 5.47473210169012e-05 1.22024840790134e-06 6.1238989405712e-06 -5.85598401632499e-06 1.08958875529056e-05 -1.64069725638321e-06 1.22024840790134e-06 1.33713114454874e-05 4.04152521313985e-06 -1.33024872632244e-06 4.90792768925563e-06 1.25247774964604e-06 6.1238989405712e-06 4.04152521313985e-06 6.64266297132721e-05 -3.93345655254072e-05 -7.75445765942595e-06 7.92437826909916e-07 -5.85598401632499e-06 -1.33024872632244e-06 -3.93345655254072e-05 7.16372172190412e-05 5.16177406557822e-07 -2.23192517915752e-06 1.08958875529056e-05 4.90792768925563e-06 -7.75445765942595e-06 5.16177406557822e-07 0.00033259464678992 1802 1780 0 0 79 1797 1780 0 0 57 0 0 0 0 0 0 0 0 1050 0 26 6 0 0 2372 +725 727 0.999113943771228 -0.030226522338595 0.0292862546123326 0.170973765982574 0.0306121703647767 0.99944924144572 -0.0128104956630343 -0.208271230857363 -0.0288829082237548 0.0136956606590974 0.999488972671359 -0.00543028920942993 2.72593170258725e-05 1.689428834607e-05 7.18446499869586e-07 -1.6510430812503e-06 1.0594119949141e-06 -1.39641737085805e-05 1.689428834607e-05 3.63112405541892e-05 6.83091375017938e-07 -3.3064130591792e-06 2.98019652796836e-06 3.19740359778921e-07 7.18446499869586e-07 6.83091375017938e-07 1.32581076573262e-05 3.57578872775827e-06 -1.84789639378907e-06 7.02459871367348e-09 -1.6510430812503e-06 -3.3064130591792e-06 3.57578872775827e-06 5.75498969800838e-05 -3.70195642393682e-05 -1.33746142573518e-06 1.0594119949141e-06 2.98019652796836e-06 -1.84789639378907e-06 -3.70195642393682e-05 6.52575105125631e-05 2.03167541755504e-06 -1.39641737085805e-05 3.19740359778921e-07 7.02459871367348e-09 -1.33746142573518e-06 2.03167541755504e-06 0.000146717346852142 1808 1788 0 0 71 1805 1788 0 0 48 0 0 0 0 0 0 0 0 1155 0 20 2 0 0 2987 +732 734 0.993156625530468 0.116034237069216 -0.0132654812464493 0.156062020137611 -0.116160608489607 0.993187952943042 -0.00918711946877827 -0.181342690846197 0.0121090957655419 0.0106651749434521 0.999869803446012 0.0119970763541907 3.08400658605055e-05 1.88833858679143e-05 -2.63226620086018e-06 -5.9505714855975e-06 6.06254698970292e-06 1.66683428640089e-06 1.88833858679143e-05 2.88220901764244e-05 2.66276369343377e-07 6.11137292577124e-06 -5.12165339157343e-06 -1.3555801443844e-05 -2.63226620086018e-06 2.66276369343377e-07 1.24311057604868e-05 2.55696312881407e-06 1.19240815616957e-06 3.22206536143339e-06 -5.9505714855975e-06 6.11137292577124e-06 2.55696312881407e-06 4.66804292767132e-05 -1.94251366198565e-05 -1.85391528661817e-06 6.06254698970292e-06 -5.12165339157343e-06 1.19240815616957e-06 -1.94251366198565e-05 4.18105543148447e-05 -7.23362466952849e-06 1.66683428640089e-06 -1.3555801443844e-05 3.22206536143339e-06 -1.85391528661817e-06 -7.23362466952849e-06 0.000234539546054568 1353 1353 0 0 0 1339 1339 0 0 0 0 0 0 0 0 0 0 0 1002 0 126 74 0 0 3698 +733 735 0.992885524136036 0.118254240529093 -0.0139380973592576 0.155194481327827 -0.118277404052195 0.992980230946227 -0.000846546308339782 -0.184860515663339 0.0137401474439811 0.00248908554814112 0.999902501647712 0.02190854211287 3.12911607489971e-05 2.12978772037686e-05 -4.44882088790629e-06 3.82434315735549e-06 1.8853357647159e-06 1.948206599887e-05 2.12978772037686e-05 3.62075912606987e-05 -1.04016888207574e-06 8.74138885131109e-07 -8.63495046739574e-07 2.92793801794913e-05 -4.44882088790629e-06 -1.04016888207574e-06 1.494592419896e-05 -3.37470128194961e-06 -2.67731683794738e-06 5.23317030522533e-06 3.82434315735549e-06 8.74138885131109e-07 -3.37470128194961e-06 8.8635479605816e-05 -2.93332297235205e-05 -2.75345327914801e-05 1.8853357647159e-06 -8.63495046739574e-07 -2.67731683794738e-06 -2.93332297235205e-05 4.97114848326019e-05 1.39847015701944e-06 1.948206599887e-05 2.92793801794913e-05 5.23317030522533e-06 -2.75345327914801e-05 1.39847015701944e-06 0.000370276082067043 1450 1450 0 0 0 1450 1450 0 0 0 0 0 0 0 0 0 0 0 679 0 134 86 0 0 3774 +734 737 0.973000933206482 0.230380745301574 0.0139246606280427 0.261118107977639 -0.23040997943283 0.97309351049141 0.000511094186311848 -0.309482223208305 -0.0134322506333818 -0.00370567588915429 0.999902916591969 0.0376089095682156 4.83058868010328e-05 3.13861773045582e-05 1.62207614605453e-06 -6.70913384267333e-06 -2.42080733737102e-07 -2.17213307838724e-05 3.13861773045582e-05 5.61474787169233e-05 4.83664821577631e-07 2.50612103871859e-05 -8.52351459261959e-06 6.21910710657281e-06 1.62207614605453e-06 4.83664821577631e-07 1.3493875307835e-05 -6.58318726111572e-07 -4.10710451946275e-06 1.24711170875026e-05 -6.70913384267333e-06 2.50612103871859e-05 -6.58318726111572e-07 0.00014136677238696 -4.17868035621049e-05 7.52727962167095e-05 -2.42080733737102e-07 -8.52351459261959e-06 -4.10710451946275e-06 -4.17868035621049e-05 5.32625383182987e-05 -7.73206287962038e-05 -2.17213307838724e-05 6.21910710657281e-06 1.24711170875026e-05 7.52727962167095e-05 -7.73206287962038e-05 0.000589190176600813 1664 1664 0 0 0 1664 1664 0 0 0 0 0 0 0 0 0 0 0 174 0 410 371 0 0 3816 +734 736 0.987057392702529 0.158641987156683 -0.0234611044553319 0.170987109303291 -0.158588177157433 0.987336102809348 0.0041485123998871 -0.193713376100965 0.0238221236913927 -0.000374166043355457 0.999716142923882 -0.0385327468699108 2.86476007014968e-05 1.60651202810319e-05 -4.3295891892017e-06 -4.59537532229906e-06 3.12344781822871e-06 3.91146160065407e-06 1.60651202810319e-05 2.77805632424893e-05 -4.12337525838433e-06 2.79447138079773e-06 4.09737144480772e-07 -1.54488260908275e-05 -4.3295891892017e-06 -4.12337525838433e-06 1.37455528018586e-05 -1.90670615235778e-06 -1.86367628692992e-06 2.70876793382877e-07 -4.59537532229906e-06 2.79447138079773e-06 -1.90670615235778e-06 3.30831934188831e-05 5.70801539853691e-06 -1.12951027979008e-05 3.12344781822871e-06 4.09737144480772e-07 -1.86367628692992e-06 5.70801539853691e-06 2.50585176526853e-05 8.1651714422444e-06 3.91146160065407e-06 -1.54488260908275e-05 2.70876793382877e-07 -1.12951027979008e-05 8.1651714422444e-06 0.000158550569003102 1624 1624 0 0 0 1579 1579 0 0 0 0 0 0 0 0 0 0 0 435 0 415 366 0 0 3821 +735 737 0.986938459484192 0.15958569043367 0.0220200953626016 0.175530876958457 -0.1595879388535 0.98718230972338 -0.00166647583380673 -0.19441209483819 -0.0220037942969112 -0.00186943254009025 0.999756139395261 0.0229769989923645 2.64428626544016e-05 2.17422446470602e-05 -3.68725087909144e-06 -3.14031551859018e-06 2.91185131032857e-06 -1.9457703816769e-05 2.17422446470602e-05 2.56948214238898e-05 -2.92640752710384e-06 -6.0751586977752e-07 4.98128437260638e-07 -1.47939351475848e-05 -3.68725087909144e-06 -2.92640752710384e-06 1.0538041250129e-05 6.31187152365212e-07 4.00960854206656e-06 4.44552388901601e-06 -3.14031551859018e-06 -6.0751586977752e-07 6.31187152365212e-07 5.02954356250319e-05 -3.58621149049042e-06 -1.41956106276692e-05 2.91185131032857e-06 4.98128437260638e-07 4.00960854206656e-06 -3.58621149049042e-06 1.66988299864487e-05 2.45015402128707e-06 -1.9457703816769e-05 -1.47939351475848e-05 4.44552388901601e-06 -1.41956106276692e-05 2.45015402128707e-06 9.37896290949153e-05 1942 1942 0 0 0 1884 1884 0 0 0 0 0 0 0 0 0 0 0 231 0 486 447 0 0 3815 +736 710 0.962785910456753 -0.242398448758218 -0.119525238613323 -2.65180656605285 0.248619371732714 0.967775330758926 0.0399914637601881 1.55177043908672 0.105979708554008 -0.0682195075770982 0.99202540298157 0.0226424253441594 8.60221852396079e-05 5.77813733631021e-05 -1.41780488418584e-06 2.38382384743231e-06 1.04012963533745e-05 -4.02792664215576e-05 5.77813733631021e-05 0.000116781174809349 -4.44416092238878e-06 1.78111296969882e-05 -8.19622131753086e-06 -3.78437097651743e-05 -1.41780488418584e-06 -4.44416092238878e-06 2.84172145598507e-05 -1.69673723806699e-06 -2.23089044675793e-06 1.77514620473657e-06 2.38382384743231e-06 1.78111296969882e-05 -1.69673723806699e-06 3.36344726721443e-05 -2.54273914676507e-06 9.96289289476083e-07 1.04012963533745e-05 -8.19622131753086e-06 -2.23089044675793e-06 -2.54273914676507e-06 3.21671365868014e-05 -1.12085154384668e-05 -4.02792664215576e-05 -3.78437097651743e-05 1.77514620473657e-06 9.96289289476083e-07 -1.12085154384668e-05 0.000145114757342721 93 89 0 0 90 93 89 0 0 88 0 0 0 0 0 95 95 0 0 0 0 0 0 0 452 +736 739 0.98148416734123 0.190679062676198 0.0181748264206277 0.290091491125509 -0.190177227532471 0.981399728191257 -0.0262144165334544 -0.287443688199819 -0.0228353100823298 0.0222725966841148 0.999491110540955 0.0440538932637467 5.21258116218329e-05 4.41520530873867e-05 -2.68707900588294e-06 -1.08812702230586e-05 5.41847428482674e-06 -3.25759972243997e-05 4.41520530873867e-05 6.08903283369363e-05 -2.63078160251856e-07 -9.24931281261242e-06 -5.14345397342857e-07 -3.05852299275998e-05 -2.68707900588294e-06 -2.63078160251856e-07 1.4564573840448e-05 -3.97240741364914e-06 -4.87026287067968e-07 9.88844333382365e-06 -1.08812702230586e-05 -9.24931281261242e-06 -3.97240741364914e-06 0.000111342682136726 -1.50751447700184e-05 -9.46020343252568e-05 5.41847428482674e-06 -5.14345397342857e-07 -4.87026287067968e-07 -1.50751447700184e-05 2.63782688140284e-05 2.31702702669776e-05 -3.25759972243997e-05 -3.05852299275998e-05 9.88844333382365e-06 -9.46020343252568e-05 2.31702702669776e-05 0.000403173476489573 2383 2383 0 0 0 2327 2327 0 0 0 0 0 0 0 0 0 0 0 218 0 564 540 0 0 3778 +736 738 0.990450057184641 0.131336304178514 0.0419459107383464 0.199740735251623 -0.130956464491648 0.991319192173602 -0.011690322327681 -0.194864048743934 -0.0431171500772968 0.00608559224778238 0.999051488631194 -0.00811536917334781 0.000202720446037707 0.000271225915452617 -3.8706321818041e-06 -1.78480970060171e-05 2.01834701333571e-05 -0.000180866900336338 0.000271225915452617 0.000448358680188775 -1.44422296147749e-06 -1.52458571868003e-05 1.98449954120659e-05 -0.000261572655452318 -3.8706321818041e-06 -1.44422296147749e-06 1.25460385497682e-05 -1.72934136298901e-06 1.70875851009032e-06 4.20004918476752e-06 -1.78480970060171e-05 -1.52458571868003e-05 -1.72934136298901e-06 7.0783362444735e-05 -8.87065007606101e-06 -1.01039366165579e-05 2.01834701333571e-05 1.98449954120659e-05 1.70875851009032e-06 -8.87065007606101e-06 2.28110271570725e-05 -2.41353904819507e-05 -0.000180866900336338 -0.000261572655452318 4.20004918476752e-06 -1.01039366165579e-05 -2.41353904819507e-05 0.000637774343965836 2028 2028 0 0 0 1975 1975 0 0 0 0 0 0 0 0 0 0 0 530 0 414 386 0 0 3781 +741 744 0.98667524866813 0.159753359621234 0.0308353329058254 0.380072628621515 -0.160569375371126 0.986679736877556 0.0260877850375018 -0.156412622605517 -0.0262569868532342 -0.0306913819331269 0.999183971907288 0.0295422901162078 4.71602111814532e-05 2.69839560649203e-05 -5.46182166088011e-06 1.78905759200239e-05 3.23647984383407e-06 -1.94307157599363e-05 2.69839560649203e-05 5.74715667840862e-05 -5.1376416851784e-07 -4.60617865643751e-06 -1.82450848456169e-07 -5.76230282946452e-05 -5.46182166088011e-06 -5.1376416851784e-07 1.17939632978961e-05 3.59493921421499e-06 4.01835233202745e-06 1.25740299318323e-06 1.78905759200239e-05 -4.60617865643751e-06 3.59493921421499e-06 0.000785411133840398 -1.76724249289371e-05 0.000206667357956416 3.23647984383407e-06 -1.82450848456169e-07 4.01835233202745e-06 -1.76724249289371e-05 1.23479955435698e-05 -3.72212979826973e-06 -1.94307157599363e-05 -5.76230282946452e-05 1.25740299318323e-06 0.000206667357956416 -3.72212979826973e-06 0.000224745941724743 3129 3032 0 1056 0 3122 3025 0 1056 0 0 0 0 0 0 0 0 0 149 0 219 236 0 0 3836 +743 746 0.988092042394479 0.146777535532357 -0.0461570235149043 0.374053265283303 -0.147721884978322 0.98886977991931 -0.0177426903480384 -0.0973574522588123 0.043039057321915 0.0243498136621764 0.998776614723962 0.0125295394918694 2.9470129536466e-05 1.3108656340525e-05 -6.13045437651207e-06 -1.04351259020539e-05 -1.64574413896821e-06 -4.68464205313022e-06 1.3108656340525e-05 5.12096412113834e-05 3.62558273492733e-06 5.31015275314605e-06 -2.83203685327329e-06 -4.63398163653501e-05 -6.13045437651207e-06 3.62558273492733e-06 1.16638206267635e-05 5.73054226436497e-06 4.29950282890752e-06 -8.97045404960726e-06 -1.04351259020539e-05 5.31015275314605e-06 5.73054226436497e-06 0.000461442099746572 8.41348695846138e-06 -0.000142393771652572 -1.64574413896821e-06 -2.83203685327329e-06 4.29950282890752e-06 8.41348695846138e-06 1.18764113041161e-05 2.40419371853837e-06 -4.68464205313022e-06 -4.63398163653501e-05 -8.97045404960726e-06 -0.000142393771652572 2.40419371853837e-06 0.000179430550648385 3213 3136 0 1356 0 3228 3151 0 1179 0 0 0 0 0 0 0 0 0 1464 0 82 110 0 0 3861 +746 749 0.999807680198352 0.000225326953607304 0.0196099934766354 0.366836637901469 -0.00071073341711921 0.999693429894855 0.0247495673309745 0.00125554956080825 -0.0195984048942636 -0.0247587449767679 0.999501329200105 0.0507721516858247 4.10768606230861e-05 2.46063565604882e-06 -7.69390464898164e-06 7.22981961455988e-07 -4.02991186334219e-07 -7.09609877796995e-07 2.46063565604882e-06 3.77421600298534e-05 -1.18564073336966e-06 2.84540450472998e-06 1.01503851872006e-06 -1.33475123171964e-05 -7.69390464898164e-06 -1.18564073336966e-06 1.18395555170606e-05 2.80523576692861e-06 4.77471917963257e-06 1.47747448331853e-07 7.22981961455988e-07 2.84540450472998e-06 2.80523576692861e-06 0.000378738918386393 9.81429307286268e-06 -0.000126564640952418 -4.02991186334219e-07 1.01503851872006e-06 4.77471917963257e-06 9.81429307286268e-06 1.16758289749841e-05 -1.37646204996009e-06 -7.09609877796995e-07 -1.33475123171964e-05 1.47747448331853e-07 -0.000126564640952418 -1.37646204996009e-06 0.000251722810518979 3359 3320 0 613 401 3359 3320 0 495 431 0 0 0 0 0 0 0 0 3104 0 0 0 0 0 3431 +747 750 0.997990764416963 -0.0600299514741566 0.0202691653616116 0.43242552872374 0.0594154111191958 0.997792304390124 0.0296702918991792 0.0407699744710343 -0.0220055233971587 -0.0284063764999332 0.999354208833965 0.0709128489220208 5.08126884332647e-05 -2.15564663641135e-05 3.76777279500189e-07 3.30957507786581e-05 1.5630820598222e-06 1.63083990037593e-05 -2.15564663641135e-05 0.000451111817818509 -1.41140232441561e-06 8.12861886682247e-05 -4.047425057752e-06 -0.000569090830865421 3.76777279500189e-07 -1.41140232441561e-06 1.15193015305546e-05 1.39014666196646e-05 4.25318164969874e-06 -1.68074124674175e-06 3.30957507786581e-05 8.12861886682247e-05 1.39014666196646e-05 0.00131905849935748 2.02748152472095e-05 -0.000348126410339845 1.5630820598222e-06 -4.047425057752e-06 4.25318164969874e-06 2.02748152472095e-05 1.09456065783647e-05 -2.73254910054107e-08 1.63083990037593e-05 -0.000569090830865421 -1.68074124674175e-06 -0.000348126410339845 -2.73254910054107e-08 0.000844127541463295 3171 3120 0 506 690 3171 3120 0 404 736 0 0 0 0 0 0 0 0 3120 0 0 0 0 0 3120 +747 749 0.998964083484817 -0.0292135559518543 0.0348902286605715 0.270466026460016 0.0286418928652504 0.999448991374159 0.0167736583449089 0.0206495642054421 -0.0353610220501982 -0.0157569600438692 0.999250377197698 0.0792798104636672 5.1915939626645e-05 -3.87662617136329e-06 -1.00122528689341e-05 -1.84291978191008e-07 -1.17945962541729e-07 1.02782637009969e-06 -3.87662617136329e-06 5.20922839131852e-05 -7.17910855327269e-07 3.68257232739382e-05 1.20762337555852e-06 -4.64568397530252e-05 -1.00122528689341e-05 -7.17910855327269e-07 1.74025254068564e-05 -6.37950362368932e-06 1.55719552044704e-06 -8.00389962834679e-07 -1.84291978191008e-07 3.68257232739382e-05 -6.37950362368932e-06 0.000338872593469237 1.35804631062832e-05 -6.27444129013197e-05 -1.17945962541729e-07 1.20762337555852e-06 1.55719552044704e-06 1.35804631062832e-05 1.44273544658564e-05 1.4072238531501e-07 1.02782637009969e-06 -4.64568397530252e-05 -8.00389962834679e-07 -6.27444129013197e-05 1.4072238531501e-07 0.000135239879314871 3318 3279 0 299 377 3318 3279 0 191 416 0 0 0 0 0 0 0 0 3439 0 0 0 0 0 3447 +748 750 0.997965352182874 -0.0564066857500982 -0.0297227462594084 0.244379052205557 0.0569871895122859 0.998192976445739 0.0190589088325346 0.0290193773016981 0.0285939866755638 -0.0207139464391922 0.999376463775745 0.0614501326295935 4.13617690983878e-05 -1.86768848847084e-05 -4.18219962906663e-06 3.86102389741134e-05 -8.26408588528225e-07 2.27976535571874e-05 -1.86768848847084e-05 0.000433828161620833 4.60948138282005e-08 0.000270180061187835 5.89634849536066e-06 -0.000397993176324626 -4.18219962906663e-06 4.60948138282005e-08 1.23397663630691e-05 -1.60795392903222e-06 4.04262007981827e-06 1.36483361087799e-06 3.86102389741134e-05 0.000270180061187835 -1.60795392903222e-06 0.00648645911245552 0.000205864807559068 2.86506248374768e-05 -8.26408588528225e-07 5.89634849536066e-06 4.04262007981827e-06 0.000205864807559068 1.74776937786184e-05 2.51294400057828e-06 2.27976535571874e-05 -0.000397993176324626 1.36483361087799e-06 2.86506248374768e-05 2.51294400057828e-06 0.000462200674477598 3214 3163 0 144 405 3214 3163 0 50 449 0 0 0 0 0 0 0 0 3497 0 0 0 0 0 3406 +749 753 0.990923619071587 -0.1306770684056 -0.0315259410483968 0.527559801515679 0.131625325557153 0.990840987998456 0.0301481371599672 0.0941499314849136 0.0272975243940201 -0.0340241134368122 0.999048149423639 0.0543658497931439 2.8241461593802e-05 -2.17493565451317e-06 -4.90431772945281e-06 3.24394110777731e-06 -3.58581982378873e-06 8.99921410861603e-06 -2.17493565451317e-06 0.000198939181927198 6.66853211958004e-06 5.51250259140022e-05 -5.99152829836083e-07 -0.000148644262944729 -4.90431772945281e-06 6.66853211958004e-06 1.05551152858497e-05 3.96580967594569e-06 2.89586934512082e-06 -7.18125475165959e-06 3.24394110777731e-06 5.51250259140022e-05 3.96580967594569e-06 0.000350683856858932 -1.52190252741318e-05 -4.14423583570004e-05 -3.58581982378873e-06 -5.99152829836083e-07 2.89586934512082e-06 -1.52190252741318e-05 1.16522119846598e-05 -2.97848911316643e-06 8.99921410861603e-06 -0.000148644262944729 -7.18125475165959e-06 -4.14423583570004e-05 -2.97848911316643e-06 0.000543606158065122 3127 3036 0 491 1041 3127 3036 0 349 1088 0 0 0 0 0 0 0 0 1544 0 0 0 0 0 2762 +756 760 0.996057615914217 0.0104162581996735 0.0880949904614608 0.650654227674935 -0.0132876523056272 0.999397265576972 0.0320709191242673 -0.0196879014475558 -0.0877078336039142 -0.0331150588462148 0.995595665319069 -0.0125607270794455 3.46452503333291e-05 1.61004105818868e-05 6.9969629391138e-07 1.17082979313399e-05 7.14453135170542e-07 -1.57669684977188e-05 1.61004105818868e-05 0.000309350239925167 6.30881333506276e-06 0.000146592016017 -3.2109422978741e-06 -0.0003283171235069 6.9969629391138e-07 6.30881333506276e-06 9.32849012062993e-06 5.35665006044442e-06 3.67473747842546e-06 -9.30598444999263e-06 1.17082979313399e-05 0.000146592016017 5.35665006044442e-06 0.000294701502735064 -6.71844896811668e-06 -0.000234409962894277 7.14453135170542e-07 -3.2109422978741e-06 3.67473747842546e-06 -6.71844896811668e-06 1.08306201344193e-05 1.10901930968539e-05 -1.57669684977188e-05 -0.0003283171235069 -9.30598444999263e-06 -0.000234409962894277 1.10901930968539e-05 0.000622823772998554 3029 2974 0 1387 706 3029 2974 0 1344 740 0 0 0 0 0 0 0 0 1112 0 0 0 0 0 3120 +757 760 0.994854414258408 -0.0162368129816516 0.100005301533268 0.486341375057103 0.0133092554719524 0.99946512111878 0.0298719832921149 0.00303290107083331 -0.100436836615572 -0.028387278334158 0.994538387534356 -0.00255321158198005 5.14228324984167e-05 -2.22393082086498e-05 2.29556495396387e-06 -9.24384165399723e-06 3.01806138001892e-07 3.6593243770361e-06 -2.22393082086498e-05 0.000158654345470522 2.34227021285611e-06 -5.61611271734514e-05 -1.91907650274726e-06 -0.000137006806725278 2.29556495396387e-06 2.34227021285611e-06 1.24837702936471e-05 -8.38656441909393e-06 3.76710029917101e-06 -1.93793582437691e-06 -9.24384165399723e-06 -5.61611271734514e-05 -8.38656441909393e-06 0.000215799547514449 3.69856260400153e-06 6.85963034232746e-05 3.01806138001892e-07 -1.91907650274726e-06 3.76710029917101e-06 3.69856260400153e-06 1.17603362297705e-05 8.44444268000016e-06 3.6593243770361e-06 -0.000137006806725278 -1.93793582437691e-06 6.85963034232746e-05 8.44444268000016e-06 0.000601347978002093 3032 2977 0 915 567 3032 2977 0 761 602 0 0 0 0 0 0 0 0 1486 0 0 0 0 0 3248 +759 763 0.992768724760135 -0.106772747150466 -0.0548620051044294 0.5771265739177 0.108587795660044 0.993596042344668 0.0312345204974408 0.0491272903268663 0.0511756755874148 -0.0369659992825187 0.998005293134869 0.0718848649798113 3.1237098464134e-05 -7.14371046338489e-07 -1.02156229119491e-05 -1.12666365990115e-06 -2.97926861939212e-07 -5.80348754454996e-06 -7.14371046338489e-07 3.07608203839458e-05 -5.50673836228128e-07 -1.2081492327137e-05 1.33153874618161e-06 -1.84728427998469e-05 -1.02156229119491e-05 -5.50673836228128e-07 1.2582927187534e-05 3.58879446393145e-06 2.80019932928655e-06 2.51671312549899e-07 -1.12666365990115e-06 -1.2081492327137e-05 3.58879446393145e-06 0.00030945215357311 -1.46085316849562e-05 -6.88820770088677e-05 -2.97926861939212e-07 1.33153874618161e-06 2.80019932928655e-06 -1.46085316849562e-05 1.34640575432231e-05 3.41744847911159e-06 -5.80348754454996e-06 -1.84728427998469e-05 2.51671312549899e-07 -6.88820770088677e-05 3.41744847911159e-06 9.18000698832932e-05 3442 3351 0 806 1002 3442 3351 0 633 1045 0 0 0 0 0 0 0 0 1066 0 0 0 0 0 2802 +758 761 0.996344923650458 -0.0651188174595679 0.0552841091872833 0.47326229802522 0.0633745636481349 0.997452628583065 0.032740165166687 0.0244893873439392 -0.0572752808668145 -0.0291168910668862 0.997933739712325 0.0175444411055611 4.95894702164438e-05 -1.83338537809197e-06 -4.92468925862887e-06 -1.73312849640806e-05 9.95269150962054e-07 -8.99583415410892e-06 -1.83338537809197e-06 3.32057877935926e-05 2.01964993898918e-06 2.69757655171901e-07 -1.36173251166114e-06 -1.69048440614643e-05 -4.92468925862887e-06 2.01964993898918e-06 1.39489485990317e-05 -3.69182812297717e-06 3.15259655452502e-06 -2.61982140344319e-06 -1.73312849640806e-05 2.69757655171901e-07 -3.69182812297717e-06 0.000197707406795043 5.03224862607339e-07 5.17246290185284e-05 9.95269150962054e-07 -1.36173251166114e-06 3.15259655452502e-06 5.03224862607339e-07 1.1870983865403e-05 2.22418041793598e-07 -8.99583415410892e-06 -1.69048440614643e-05 -2.61982140344319e-06 5.17246290185284e-05 2.22418041793598e-07 0.00013157279703377 3354 3283 0 669 723 3354 3283 0 525 751 0 0 0 0 0 0 0 0 1649 0 0 0 0 0 3054 +758 760 0.996466408158629 -0.0321536917534616 0.077594055945437 0.326149817477175 0.030834702365275 0.999359920435798 0.0181375454954985 0.0130664072748202 -0.0781275786229494 -0.0156808651923211 0.996820039889515 0.0325715454823639 5.22251157803409e-05 -4.11919577049958e-05 -9.6708043591236e-06 7.4181175241359e-06 5.6911685833463e-07 -8.5243849220041e-05 -4.11919577049958e-05 0.000645267922128955 5.80492810849339e-06 -0.000204953602438708 8.25015815564457e-06 0.00107099866343195 -9.6708043591236e-06 5.80492810849339e-06 1.40759867054343e-05 -9.4167746256693e-06 3.67963446839353e-06 -3.91824342366635e-07 7.4181175241359e-06 -0.000204953602438708 -9.4167746256693e-06 0.000219219000825202 -3.83729673317995e-06 -0.000521984560911722 5.6911685833463e-07 8.25015815564457e-06 3.67963446839353e-06 -3.83729673317995e-06 1.17941483893974e-05 2.72252984163409e-05 -8.5243849220041e-05 0.00107099866343195 -3.91824342366635e-07 -0.000521984560911722 2.72252984163409e-05 0.00301755076449279 3193 3138 0 440 431 3193 3138 0 319 460 0 0 0 0 0 0 0 0 1987 0 0 0 0 0 3389 +759 761 0.998454318109962 -0.0555708755893316 -0.000923273418948339 0.314789865965551 0.0555769143314618 0.998160008015334 0.0242446899798893 0.0184663502662543 -0.000425724047316525 -0.0242585280893672 0.999705627959537 0.039434442520036 4.4910469467436e-05 -5.23980515421789e-06 -5.06827216104855e-06 -1.13905766995315e-05 1.1154902679812e-06 7.82997794892825e-06 -5.23980515421789e-06 3.46978786338706e-05 4.14576244152526e-06 -3.04954436636245e-06 -2.08209607122098e-06 -1.95006665367282e-05 -5.06827216104855e-06 4.14576244152526e-06 1.23992945725919e-05 -3.62022458860671e-06 3.99761159714846e-06 -5.35966663329837e-06 -1.13905766995315e-05 -3.04954436636245e-06 -3.62022458860671e-06 0.000193797418832332 -5.0865379701016e-06 1.06074672383248e-05 1.1154902679812e-06 -2.08209607122098e-06 3.99761159714846e-06 -5.0865379701016e-06 1.17098200058207e-05 2.27421762062251e-06 7.82997794892825e-06 -1.95006665367282e-05 -5.35966663329837e-06 1.06074672383248e-05 2.27421762062251e-06 0.000119025036521791 3370 3299 0 333 477 3370 3299 0 215 512 0 0 0 0 0 0 0 0 2038 0 0 0 0 0 3324 +760 762 0.997679044571047 -0.0534362713564023 -0.0422029492728759 0.328899818608517 0.0549476080321321 0.99785790487339 0.0355015781794961 0.0183445890339223 0.0402154745757298 -0.0377381317133299 0.998478116444941 0.019167299578122 3.34569736027295e-05 1.83221776692338e-06 -8.17914535159502e-06 1.63135272641018e-06 -1.4224853067339e-06 3.68882649209066e-07 1.83221776692338e-06 2.64416184970686e-05 -8.76194909642556e-07 -1.0447841953364e-05 -9.49981355115875e-07 7.02341154892473e-06 -8.17914535159502e-06 -8.76194909642556e-07 1.1895304009851e-05 -5.25985539596967e-06 1.73125736644133e-06 -5.56702243963457e-06 1.63135272641018e-06 -1.0447841953364e-05 -5.25985539596967e-06 0.000207788549353502 -3.51124360002414e-06 3.10038534999966e-05 -1.4224853067339e-06 -9.49981355115875e-07 1.73125736644133e-06 -3.51124360002414e-06 1.19320665947643e-05 2.71942383128402e-07 3.68882649209066e-07 7.02341154892473e-06 -5.56702243963457e-06 3.10038534999966e-05 2.71942383128402e-07 0.000212153664264047 3341 3261 0 375 480 3341 3261 0 255 514 0 0 0 0 0 0 0 0 1715 0 0 0 0 0 3338 +761 763 0.99739886609994 -0.0510114053018506 -0.0509248311895552 0.270004899730764 0.0515241553127923 0.998632919735803 0.00880642034243466 0.0165155406940916 0.0504059849805321 -0.0114073725754322 0.998663661364059 0.06096157602666 2.91473530245885e-05 -6.67734839794085e-06 -3.86394608590446e-06 8.94389888685175e-06 -9.63370317534246e-07 -8.37016531195553e-06 -6.67734839794085e-06 0.000118502179951177 1.10096299217218e-06 -4.21593260397626e-05 1.84783127667036e-06 -1.9909018685586e-05 -3.86394608590446e-06 1.10096299217218e-06 9.93597564450482e-06 4.93198863300507e-06 3.79776165266872e-06 -5.25588753568325e-06 8.94389888685175e-06 -4.21593260397626e-05 4.93198863300507e-06 0.000323680105769087 -1.19324055280415e-05 -0.000173435926669534 -9.63370317534246e-07 1.84783127667036e-06 3.79776165266872e-06 -1.19324055280415e-05 1.13012722370757e-05 -5.89972819846594e-06 -8.37016531195553e-06 -1.9909018685586e-05 -5.25588753568325e-06 -0.000173435926669534 -5.89972819846594e-06 0.000701418377022011 3399 3308 0 284 400 3399 3308 0 160 422 0 0 0 0 0 0 0 0 1555 0 0 0 0 0 3430 +760 764 0.992507168653014 -0.101630965952523 -0.0678282163405151 0.546498473462838 0.102578824445077 0.994668058914277 0.010631902518836 0.0453365037835039 0.0663860297641354 -0.0175099781627812 0.997640363917226 0.0691094169937339 4.97863734243012e-05 -1.07232076150072e-06 -1.11267546059766e-05 9.76761445379162e-06 2.94398890346289e-06 2.46889314847726e-05 -1.07232076150072e-06 8.53379716981649e-05 2.35870566869509e-06 -7.30856921840849e-06 -9.5855244271597e-07 -4.42233019072534e-05 -1.11267546059766e-05 2.35870566869509e-06 1.52518016164781e-05 -4.30197718173678e-06 1.99699499114382e-06 -1.87939469076198e-06 9.76761445379162e-06 -7.30856921840849e-06 -4.30197718173678e-06 0.000293258292734594 -1.45711743225442e-05 -6.40550947202508e-05 2.94398890346289e-06 -9.5855244271597e-07 1.99699499114382e-06 -1.45711743225442e-05 1.47004266780574e-05 7.57611036120409e-06 2.46889314847726e-05 -4.42233019072534e-05 -1.87939469076198e-06 -6.40550947202508e-05 7.57611036120409e-06 0.000189379190836604 3283 3190 0 738 930 3283 3190 0 628 960 0 0 0 0 0 0 0 0 1118 0 0 0 0 0 2887 +761 764 0.995671968100204 -0.0718218228218349 -0.0589826898845401 0.387641877371314 0.0716133687415317 0.997416502967484 -0.00564313969386383 0.0253969146887745 0.0592356088595051 0.0013947668851848 0.998243055206686 0.0595285628414491 3.12209513899358e-05 4.52856495376412e-06 -3.95267262087373e-06 9.92102728580294e-06 -2.0689080584632e-07 -1.00110643010162e-06 4.52856495376412e-06 3.69816957128251e-05 8.86100521244824e-07 -9.75804456353774e-07 7.09183480789389e-07 -3.02409359265688e-06 -3.95267262087373e-06 8.86100521244824e-07 1.13254852027684e-05 1.86808636069836e-06 3.19729332812661e-06 -5.21154171806312e-06 9.92102728580294e-06 -9.75804456353774e-07 1.86808636069836e-06 0.000349595237296264 -2.21875430581256e-05 -6.9472098184066e-05 -2.0689080584632e-07 7.09183480789389e-07 3.19729332812661e-06 -2.21875430581256e-05 1.38756008609431e-05 6.76907040433312e-06 -1.00110643010162e-06 -3.02409359265688e-06 -5.21154171806312e-06 -6.9472098184066e-05 6.76907040433312e-06 0.000317593001471575 3443 3350 0 487 596 3443 3350 0 376 623 0 0 0 0 0 0 0 0 1331 0 0 0 0 0 3227 +765 767 0.989263098909584 0.052299859427871 -0.1364670137419 0.293517481449554 -0.0561514257267885 0.998120988917157 -0.0245256778068683 -0.0428119263521337 0.134927901208964 0.0319251654163654 0.99034097425507 0.0479475310798379 2.86574629537124e-05 1.23149456912221e-05 -6.18397444215219e-06 -3.93832716737929e-06 -3.18064099866086e-06 -1.37903834102902e-05 1.23149456912221e-05 7.07810003502129e-05 1.61553973757207e-06 1.97561582827956e-06 -2.64921529356369e-06 -7.43154746170748e-05 -6.18397444215219e-06 1.61553973757207e-06 1.14799961373128e-05 -3.20614358546397e-06 3.00693710334702e-06 -1.76268906731872e-06 -3.93832716737929e-06 1.97561582827956e-06 -3.20614358546397e-06 0.000160502852247893 -2.1803088049515e-07 2.26104388417485e-06 -3.18064099866086e-06 -2.64921529356369e-06 3.00693710334702e-06 -2.1803088049515e-07 1.10867479405023e-05 7.93715157021932e-06 -1.37903834102902e-05 -7.43154746170748e-05 -1.76268906731872e-06 2.26104388417485e-06 7.93715157021932e-06 0.00024612112405023 2888 2814 0 748 98 2888 2814 0 599 114 0 0 0 0 0 0 0 0 1809 0 0 0 0 0 3745 +765 769 0.993089493293429 0.109392513675193 -0.0425033676550789 0.58313247971376 -0.110059088519677 0.99383109363189 -0.0136658100623375 -0.0981153668312392 0.0407462310455585 0.0182492542933857 0.999002857540116 0.00210215181209355 4.06078306339945e-05 6.43138358054119e-06 -1.86821683630966e-06 -1.18845045858203e-05 -3.38852962335688e-07 -1.24849721677271e-05 6.43138358054119e-06 7.47345893152715e-05 2.88546240484945e-06 -2.62657961385079e-05 -1.78437258917666e-06 -6.2597687614394e-05 -1.86821683630966e-06 2.88546240484945e-06 1.19746435677889e-05 -5.01596901061203e-06 2.94410557657613e-06 -1.39011715464542e-06 -1.18845045858203e-05 -2.62657961385079e-05 -5.01596901061203e-06 9.0767896609032e-05 1.38871411705793e-06 2.96822425370518e-05 -3.38852962335688e-07 -1.78437258917666e-06 2.94410557657613e-06 1.38871411705793e-06 1.13869169272031e-05 7.96806627947045e-07 -1.24849721677271e-05 -6.2597687614394e-05 -1.39011715464542e-06 2.96822425370518e-05 7.96806627947045e-07 0.000104624839702903 3337 3285 0 1823 251 3337 3285 0 1653 265 0 0 0 0 0 0 0 0 1485 0 0 0 0 0 3613 +766 769 0.99672104853946 0.0789109534570614 -0.0178944914120794 0.445375274000641 -0.0787369090623327 0.996842922268523 0.010231689716791 -0.0680637497257418 0.018645389502755 -0.00878918355982074 0.999787527278993 0.0275136526568165 4.38545104539092e-05 -1.45904180257879e-07 -2.93802212556546e-06 -5.85485959510288e-06 5.47365083195413e-07 -2.15814434761405e-05 -1.45904180257879e-07 8.47372126283331e-05 2.50811845207526e-06 -1.69273341290495e-05 1.18887589367186e-06 -1.73875452523816e-05 -2.93802212556546e-06 2.50811845207526e-06 1.29644385254885e-05 -6.47095311469441e-06 2.60464777959639e-06 -3.41825817880783e-06 -5.85485959510288e-06 -1.69273341290495e-05 -6.47095311469441e-06 9.32200491713785e-05 3.26191933692381e-06 6.46665885028679e-06 5.47365083195413e-07 1.18887589367186e-06 2.60464777959639e-06 3.26191933692381e-06 1.16923546856788e-05 -1.03239573050093e-06 -2.15814434761405e-05 -1.73875452523816e-05 -3.41825817880783e-06 6.46665885028679e-06 -1.03239573050093e-06 0.0002842634019526 3338 3286 0 1257 201 3338 3286 0 1087 218 0 0 0 0 0 0 0 0 2060 0 0 0 0 0 3651 +767 770 0.998373000537465 0.0434031331000083 0.0369799923596746 0.44425939817481 -0.0441895800387869 0.998808242542927 0.0207213813319684 -0.0528603656240067 -0.03603654830605 -0.0223217979878899 0.999101148293191 0.0442857951877485 4.91653253190331e-05 -4.45588424215628e-06 -2.49695116814804e-06 -4.45396239888456e-06 1.03409407698442e-06 -1.26975850354562e-06 -4.45588424215628e-06 0.000322839867952831 -5.28768697738711e-07 0.00010023056077329 3.16850159450177e-06 -0.000145654634940863 -2.49695116814804e-06 -5.28768697738711e-07 1.03696049853355e-05 -3.56419646507174e-06 3.72998402412293e-06 -9.77557270340259e-07 -4.45396239888456e-06 0.00010023056077329 -3.56419646507174e-06 0.000125463273231715 1.78673575849193e-06 -1.31199608219099e-05 1.03409407698442e-06 3.16850159450177e-06 3.72998402412293e-06 1.78673575849193e-06 1.06873724596987e-05 -8.50185788168878e-07 -1.26975850354562e-06 -0.000145654634940863 -9.77557270340259e-07 -1.31199608219099e-05 -8.50185788168878e-07 0.00013940859026951 3120 3069 0 1083 311 3120 3069 0 928 331 0 0 0 0 0 0 0 0 2567 0 0 0 0 0 3526 +768 771 0.998484140885879 -0.0245788400490372 0.049247345321675 0.462154591925408 0.024448828611711 0.999695830035499 0.00324070812465409 -0.0162310656290532 -0.0493120186050382 -0.00203175576235574 0.998781355848025 0.0419209092722755 3.85539301637396e-05 1.16412400457414e-06 -4.4967287739555e-06 -1.62797569039672e-05 -1.33662083491552e-06 -5.95298859373091e-06 1.16412400457414e-06 7.55922143244236e-05 -3.66786098328002e-06 -9.10729997506654e-06 5.85862200425299e-07 -2.84318196526136e-05 -4.4967287739555e-06 -3.66786098328002e-06 1.0004475995524e-05 2.29142711519372e-06 4.58357059975435e-06 2.76615464458652e-06 -1.62797569039672e-05 -9.10729997506654e-06 2.29142711519372e-06 9.68221226783374e-05 -4.33483090233704e-07 3.19278229382379e-05 -1.33662083491552e-06 5.85862200425299e-07 4.58357059975435e-06 -4.33483090233704e-07 1.00056602876121e-05 5.74142517074172e-06 -5.95298859373091e-06 -2.84318196526136e-05 2.76615464458652e-06 3.19278229382379e-05 5.74142517074172e-06 0.00027647791945332 3104 3052 0 840 557 3104 3052 0 701 594 0 0 0 0 0 0 0 0 2836 0 0 0 0 0 3248 +767 769 0.998184596323233 0.0540647895133872 0.0265426109849406 0.286430561700781 -0.0545012971363421 0.998385393911011 0.0160066809679833 -0.0401449456157864 -0.0256343572862847 -0.0174242291085658 0.999519522553958 -0.00798609095296685 3.63247015110717e-05 1.04397940010456e-05 -4.02642480826228e-07 -6.74149327313398e-06 1.82478798855012e-07 -1.56605339410603e-05 1.04397940010456e-05 2.81430000626958e-05 1.46221971270784e-06 -6.57138286108089e-06 -4.18112328078423e-07 -2.28550132876841e-05 -4.02642480826228e-07 1.46221971270784e-06 1.19590947342347e-05 -6.67629690936978e-07 3.15736024903242e-06 1.08166909728226e-07 -6.74149327313398e-06 -6.57138286108089e-06 -6.67629690936978e-07 7.36497156005562e-05 -7.12904618956148e-07 -9.58567926176485e-06 1.82478798855012e-07 -4.18112328078423e-07 3.15736024903242e-06 -7.12904618956148e-07 1.09289319623173e-05 -9.37766717181688e-07 -1.56605339410603e-05 -2.28550132876841e-05 1.08166909728226e-07 -9.58567926176485e-06 -9.37766717181688e-07 7.7636675580391e-05 3424 3372 0 709 111 3424 3372 0 576 133 0 0 0 0 0 0 0 0 2633 0 0 0 0 0 3735 +767 771 0.998732434473272 0.0134011913541768 0.0485173412439313 0.600675723952043 -0.0138215211876734 0.999869709969679 0.00833838336907404 -0.0562535795584943 -0.0483992756469561 -0.00899839738173934 0.998787534444343 0.00837604409046559 5.69745906966284e-05 4.47227751161468e-06 3.79959991783211e-06 -4.77753568119625e-06 7.48580049420594e-07 -2.60519503088381e-06 4.47227751161468e-06 5.78503873366933e-05 4.00934840829816e-06 -9.10134858571543e-06 -4.65948937855763e-08 -2.97558655560687e-05 3.79959991783211e-06 4.00934840829816e-06 1.60064633917343e-05 -7.46724869277652e-06 2.91704227724571e-06 5.47822681803171e-08 -4.77753568119625e-06 -9.10134858571543e-06 -7.46724869277652e-06 0.000133882636187703 1.13439073564141e-06 -1.64586312570722e-06 7.48580049420594e-07 -4.65948937855763e-08 2.91704227724571e-06 1.13439073564141e-06 1.33018697707564e-05 1.42140770134945e-06 -2.60519503088381e-06 -2.97558655560687e-05 5.47822681803171e-08 -1.64586312570722e-06 1.42140770134945e-06 0.000192376223594439 3287 3235 0 1463 603 3287 3235 0 1287 629 0 0 0 0 0 0 0 0 2198 0 0 0 0 0 3220 +768 770 0.997605625001989 0.00530444568404132 0.0689556366106187 0.294841076062068 -0.00602043020437377 0.999930062705338 0.0101795932262708 -0.019666471155932 -0.0688968169405881 -0.0105703620601723 0.997567790208451 0.0243255723449756 3.92888513652141e-05 2.60563475288032e-06 8.92525917276115e-08 -1.35769303383299e-05 -9.15173406201706e-08 -2.04566020707799e-05 2.60563475288032e-06 2.98945170989946e-05 2.63186169381396e-06 -2.54140711934984e-07 -1.08272689540194e-06 -1.20660017341786e-05 8.92525917276115e-08 2.63186169381396e-06 1.12175383066783e-05 -1.63546173961753e-06 3.37555114726873e-06 -1.45176495121011e-06 -1.35769303383299e-05 -2.54140711934984e-07 -1.63546173961753e-06 8.8310558590236e-05 2.53760227294356e-06 2.70855236015308e-05 -9.15173406201706e-08 -1.08272689540194e-06 3.37555114726873e-06 2.53760227294356e-06 1.09297944598901e-05 1.37171787841174e-06 -2.04566020707799e-05 -1.20660017341786e-05 -1.45176495121011e-06 2.70855236015308e-05 1.37171787841174e-06 0.000106400779757426 3367 3316 0 533 260 3367 3316 0 412 282 0 0 0 0 0 0 0 0 3139 0 0 0 0 0 3568 +768 772 0.996200278228367 -0.0601660543498186 0.0629686553905827 0.578386370333911 0.0590477680797728 0.998065193530026 0.0194738426785494 -0.0094065368037634 -0.0640184875057249 -0.0156816889347481 0.997825494708185 0.0355511463560905 3.01040243183405e-05 1.25945299360465e-05 4.0436141006815e-06 6.29280342082309e-06 -1.30842422637045e-07 -7.67281876069079e-06 1.25945299360465e-05 0.000320301303155169 -6.08094010246913e-06 9.30761532813201e-06 1.0412872030972e-06 -0.000206088862203738 4.0436141006815e-06 -6.08094010246913e-06 1.1509443806584e-05 1.16441204019138e-06 1.95180212811379e-06 4.06348487915068e-06 6.29280342082309e-06 9.30761532813201e-06 1.16441204019138e-06 8.6226881781153e-05 -2.83811447515073e-06 8.53422334329429e-06 -1.30842422637045e-07 1.0412872030972e-06 1.95180212811379e-06 -2.83811447515073e-06 1.21536595615375e-05 3.32020154971802e-06 -7.67281876069079e-06 -0.000206088862203738 4.06348487915068e-06 8.53422334329429e-06 3.32020154971802e-06 0.000283921238334399 3240 3185 0 1054 825 3240 3185 0 898 861 0 0 0 0 0 0 0 0 2627 0 0 0 0 0 2970 +770 773 0.994722558181251 -0.09670458674697 -0.0342819945079956 0.432053973065541 0.0967228511888872 0.995310712842372 -0.00112914086869533 0.0245957789419782 0.0342304294924977 -0.00219267035979948 0.999411561816979 0.0357904354668838 5.14975421242137e-05 -2.84162111506266e-05 4.29390186383032e-06 -1.73005323294996e-05 -3.44094279573561e-06 1.37751490426551e-05 -2.84162111506266e-05 0.000437962136348997 -1.0165614088183e-05 0.000136488077347196 -5.38358978784414e-06 -0.000201038599091824 4.29390186383032e-06 -1.0165614088183e-05 1.41912833497576e-05 -5.98664824105271e-06 2.46510275669753e-06 5.56063402542908e-06 -1.73005323294996e-05 0.000136488077347196 -5.98664824105271e-06 0.00031299580631513 -1.23905419641323e-05 2.87661914000411e-05 -3.44094279573561e-06 -5.38358978784414e-06 2.46510275669753e-06 -1.23905419641323e-05 1.37987732464277e-05 -5.49561565863531e-06 1.37751490426551e-05 -0.000201038599091824 5.56063402542908e-06 2.87661914000411e-05 -5.49561565863531e-06 0.000179508728724863 3338 3258 0 479 744 3338 3258 0 352 776 0 0 0 0 0 0 0 0 3237 0 0 0 0 0 3049 +769 771 0.999061012172484 -0.040006504769616 0.0166305000829803 0.299946899110695 0.0401246561475674 0.999171321324146 -0.00683246751911355 -0.000445634779280019 -0.0163433755978011 0.00749334501267288 0.999838358863367 0.0093229478988493 4.09001224706368e-05 -1.01005511869014e-06 -7.34323392042069e-06 2.45663163617156e-06 -3.87073806886319e-07 -9.98640981870196e-07 -1.01005511869014e-06 1.99362920215538e-05 -1.17609085192607e-07 -1.57588234567534e-06 1.03683805672475e-08 -1.74588856164072e-05 -7.34323392042069e-06 -1.17609085192607e-07 1.30606979597094e-05 -2.73536199228734e-06 3.74268560806677e-06 1.43601060654472e-06 2.45663163617156e-06 -1.57588234567534e-06 -2.73536199228734e-06 0.000105498185217234 -3.4915459513799e-07 6.42469583637257e-06 -3.87073806886319e-07 1.03683805672475e-08 3.74268560806677e-06 -3.4915459513799e-07 1.08372526513981e-05 5.9970697339547e-07 -9.98640981870196e-07 -1.74588856164072e-05 1.43601060654472e-06 6.42469583637257e-06 5.9970697339547e-07 7.95596812613924e-05 3447 3395 0 396 399 3447 3395 0 276 432 0 0 0 0 0 0 0 0 3326 0 0 0 0 0 3410 +769 772 0.99711569269482 -0.0758949053485024 0.000508649064362445 0.437738371387814 0.0758898930098527 0.997094217803284 0.00662155285484576 0.00898995419467801 -0.00100971316814547 -0.00656385293850087 0.999977947913813 0.0134961179099285 5.03269984092328e-05 2.27222091552313e-06 -5.84717199134614e-06 -6.58004987375819e-06 -1.58903347299815e-06 -1.63305691109116e-05 2.27222091552313e-06 3.22297341841051e-05 4.24759391495771e-08 -7.1287696136093e-07 -2.74195077449294e-07 -1.20455862495048e-05 -5.84717199134614e-06 4.24759391495771e-08 1.23093535312985e-05 -3.62209622361629e-06 3.81603027306524e-06 1.23854164883236e-06 -6.58004987375819e-06 -7.1287696136093e-07 -3.62209622361629e-06 8.55043588516462e-05 -6.75667009103297e-07 3.58848962184644e-05 -1.58903347299815e-06 -2.74195077449294e-07 3.81603027306524e-06 -6.75667009103297e-07 1.18256049945773e-05 -2.43405312935125e-06 -1.63305691109116e-05 -1.20455862495048e-05 1.23854164883236e-06 3.58848962184644e-05 -2.43405312935125e-06 0.000159459244734796 3343 3288 0 579 680 3343 3288 0 446 718 0 0 0 0 0 0 0 0 3136 0 0 0 0 0 3114 +771 773 0.997617334200111 -0.0669453612902354 -0.0166725254590573 0.292529913945275 0.0670610706116415 0.997727830429435 0.00647990702040192 0.0134620645213592 0.0162008429374368 -0.00758254497464218 0.99984000605088 0.00354999100189338 3.20594980584176e-05 6.506917677532e-06 -2.34723331169986e-06 8.37735172875019e-06 -1.7085634096252e-06 2.65542432372974e-07 6.506917677532e-06 8.47932634507519e-05 5.52811754199088e-06 -2.13680366040007e-05 -3.24118689641444e-07 -5.81384267590601e-05 -2.34723331169986e-06 5.52811754199088e-06 1.17136024749968e-05 -4.06318102430334e-07 2.3936225490193e-06 -3.28784947913547e-06 8.37735172875019e-06 -2.13680366040007e-05 -4.06318102430334e-07 0.000145583564266785 -4.41129742172872e-07 1.72670006664169e-05 -1.7085634096252e-06 -3.24118689641444e-07 2.3936225490193e-06 -4.41129742172872e-07 1.13282895579953e-05 -1.05289479534509e-06 2.65542432372974e-07 -5.81384267590601e-05 -3.28784947913547e-06 1.72670006664169e-05 -1.05289479534509e-06 0.000194080316824312 3299 3219 0 271 463 3299 3219 0 156 498 0 0 0 0 0 0 0 0 3455 0 0 0 0 0 3330 +772 774 0.998354191269888 -0.0541626775593353 -0.018849751548775 0.270920560610242 0.0541563824201097 0.998532109060041 -0.000844641505720055 0.0096220207608002 0.0188678302147836 -0.000177582966043385 0.999821970876454 0.0294619639102547 3.85923417535313e-05 4.93570539132817e-05 -3.46893378464822e-06 -2.97108440383273e-06 -1.17805105005769e-06 -4.04641393630138e-05 4.93570539132817e-05 0.000473784597047438 -3.31650275279936e-06 4.58570598597846e-05 -1.7405447185083e-06 -0.000319139687208505 -3.46893378464822e-06 -3.31650275279936e-06 1.23090057772413e-05 -3.34558936491987e-06 3.24722889995134e-06 2.77960662198714e-06 -2.97108440383273e-06 4.58570598597846e-05 -3.34558936491987e-06 0.000134666936856796 -1.3744660750723e-06 -4.14136977195953e-05 -1.17805105005769e-06 -1.7405447185083e-06 3.24722889995134e-06 -1.3744660750723e-06 1.07968759127728e-05 2.98117324359079e-06 -4.04641393630138e-05 -0.000319139687208505 2.77960662198714e-06 -4.14136977195953e-05 2.98117324359079e-06 0.000386659084698362 3061 2980 0 275 387 3061 2980 0 156 424 0 0 0 0 0 0 0 0 3337 0 0 0 0 0 3400 +773 775 0.999513692942699 -0.0275824238489662 0.0145460480772234 0.2718987085701 0.0275599298923337 0.999618630546403 0.00174462857478496 -0.000692722608440168 -0.0145886217436249 -0.00134289208437788 0.999892678619296 0.0373558987758834 5.42968847168781e-05 2.19965196765686e-05 -5.58586238295366e-06 1.40927595649754e-05 -3.86416872310428e-07 -8.53665143484197e-06 2.19965196765686e-05 0.000105379466346379 1.07351002300598e-06 3.1407529795659e-05 -5.7359140410722e-07 -7.96409469736346e-05 -5.58586238295366e-06 1.07351002300598e-06 1.23327177447171e-05 -3.65855444005205e-06 3.97407204181701e-06 -4.44761363820602e-06 1.40927595649754e-05 3.1407529795659e-05 -3.65855444005205e-06 0.000243141261452888 -1.25591768932453e-05 1.52998366057602e-05 -3.86416872310428e-07 -5.7359140410722e-07 3.97407204181701e-06 -1.25591768932453e-05 1.21291268372711e-05 -9.86368484891681e-07 -8.53665143484197e-06 -7.96409469736346e-05 -4.44761363820602e-06 1.52998366057602e-05 -9.86368484891681e-07 0.000206610796598597 3269 3185 0 380 318 3269 3185 0 257 338 0 0 0 0 0 0 0 0 3040 0 0 0 0 0 3481 +773 777 0.997675207100319 0.0582944801709958 0.0352978004828898 0.564678384910624 -0.0586113545055012 0.998248748332118 0.00800909335625842 -0.0349036982631521 -0.0347690992170776 -0.010059325770258 0.999344745172896 0.0061339251028767 4.23860467730154e-05 1.75852881421893e-05 -6.07248145244439e-07 -7.71257460406854e-06 -1.57546900042015e-07 -9.46260751600216e-06 1.75852881421893e-05 3.26224344620942e-05 -1.75270750520791e-06 -9.38692957928526e-06 1.41971198765244e-07 -6.28934973014482e-06 -6.07248145244439e-07 -1.75270750520791e-06 1.2747036875398e-05 -1.15796283896976e-06 3.1166080156709e-06 2.09551099333736e-06 -7.71257460406854e-06 -9.38692957928526e-06 -1.15796283896976e-06 8.58448482351323e-05 1.4911045222149e-06 1.71352728659524e-05 -1.57546900042015e-07 1.41971198765244e-07 3.1166080156709e-06 1.4911045222149e-06 1.13180235550935e-05 2.02683950900623e-06 -9.46260751600216e-06 -6.28934973014482e-06 2.09551099333736e-06 1.71352728659524e-05 2.02683950900623e-06 0.000234449221001674 3387 3330 0 1416 452 3387 3330 0 1272 472 0 0 0 0 0 0 0 0 2401 0 0 0 0 0 3375 +776 778 0.996426528106817 0.0814684410720215 -0.0222950037965922 0.281930678355718 -0.081747017131788 0.996582291085679 -0.0118811735310228 -0.0385487197771627 0.0212508652776932 0.013661266548665 0.999680834327255 0.00862335601590917 3.42166186225527e-05 1.23891189335425e-05 -2.04494640137939e-06 -1.15775055206345e-06 -9.42914763791949e-07 -1.45202664488493e-05 1.23891189335425e-05 3.45247112159237e-05 -7.2019186017365e-08 1.00963296172978e-05 1.56832454284246e-07 -1.43157874712831e-05 -2.04494640137939e-06 -7.2019186017365e-08 1.16110042642404e-05 2.76935264151036e-07 3.77750978351664e-06 -2.07064727943317e-06 -1.15775055206345e-06 1.00963296172978e-05 2.76935264151036e-07 7.65211953801257e-05 2.73513642608645e-07 -1.59410275257804e-05 -9.42914763791949e-07 1.56832454284246e-07 3.77750978351664e-06 2.73513642608645e-07 1.04016018492075e-05 3.96043606373165e-06 -1.45202664488493e-05 -1.43157874712831e-05 -2.07064727943317e-06 -1.59410275257804e-05 3.96043606373165e-06 0.000154426473125703 3399 3355 0 753 30 3399 3355 0 625 49 0 0 0 0 0 0 0 0 3018 0 0 0 0 0 3813 +774 778 0.99399906477943 0.109163566491047 -0.00701248661841615 0.575936552443366 -0.109204237287468 0.994002965922458 -0.00570423490218541 -0.0691688295419719 0.00634773787117193 0.00643579741070719 0.999959142533137 0.0208230097592599 4.40479332922704e-05 3.41308266953236e-05 -4.57564325619835e-06 3.23922070547926e-06 3.13823170860995e-08 -3.47283337493523e-05 3.41308266953236e-05 8.05383938791598e-05 -1.21576281927762e-06 4.10215221784036e-06 3.78924962815427e-07 -3.28175760776421e-05 -4.57564325619835e-06 -1.21576281927762e-06 1.11385269613292e-05 -7.16329414846312e-08 3.83158678213804e-06 1.51046915504908e-06 3.23922070547926e-06 4.10215221784036e-06 -7.16329414846312e-08 0.000119820015558094 -4.5858517044387e-07 -4.14183100269157e-05 3.13823170860995e-08 3.78924962815427e-07 3.83158678213804e-06 -4.5858517044387e-07 1.14803308217723e-05 -2.09421865452333e-07 -3.47283337493523e-05 -3.28175760776421e-05 1.51046915504908e-06 -4.14183100269157e-05 -2.09421865452333e-07 0.000152509622171623 3147 3103 0 1685 286 3147 3103 0 1513 307 0 0 0 0 0 0 0 0 2056 0 0 0 0 0 3562 +775 778 0.993247202278902 0.113537454769931 -0.023858783068284 0.424435210277415 -0.113583349503448 0.993528305829771 -0.000572914131180478 -0.0649863057217056 0.0236393291087363 0.00327900585391292 0.999715174557183 0.0122931105137976 4.33568506112234e-05 5.48013676908157e-05 8.13517639438407e-07 1.09844346986665e-05 -2.41369165891614e-06 -5.7128190372835e-05 5.48013676908157e-05 0.000278886619204926 4.59440529406772e-06 8.8844332572226e-05 -2.38191910022468e-06 -0.000286989289664917 8.13517639438407e-07 4.59440529406772e-06 1.06188465642114e-05 1.55280981654053e-06 3.11490887133356e-06 -7.41009050081293e-06 1.09844346986665e-05 8.8844332572226e-05 1.55280981654053e-06 0.000142567089184257 8.18699095281489e-07 -0.000102241227775287 -2.41369165891614e-06 -2.38191910022468e-06 3.11490887133356e-06 8.18699095281489e-07 1.00886650510739e-05 8.8028923361595e-06 -5.7128190372835e-05 -0.000286989289664917 -7.41009050081293e-06 -0.000102241227775287 8.8028923361595e-06 0.000653581923549713 3031 2987 0 1270 93 3031 2987 0 1106 113 0 0 0 0 0 0 0 0 2492 0 0 0 0 0 3756 +776 780 0.994120730217307 0.108135330933269 0.00554291946178537 0.564588507444668 -0.10773172848528 0.992947273248867 -0.0494933048524098 -0.0645916782626774 -0.0108558016646144 0.0486051720662726 0.998759074461217 0.00863069352481316 3.8780331571212e-05 1.22085972126513e-05 -1.4971068905073e-06 3.47484798388506e-06 -7.81346684080772e-07 -1.23924800591154e-05 1.22085972126513e-05 2.76206840614581e-05 -1.08568731290449e-07 -9.02320271957941e-06 1.16531188239135e-08 -1.2934128337402e-06 -1.4971068905073e-06 -1.08568731290449e-07 1.10707556488525e-05 -1.81147237864928e-06 3.53783583190615e-06 2.63615801095852e-06 3.47484798388506e-06 -9.02320271957941e-06 -1.81147237864928e-06 0.00010088339886732 2.95734586430421e-06 4.40553151983387e-06 -7.81346684080772e-07 1.16531188239135e-08 3.53783583190615e-06 2.95734586430421e-06 1.08733101558606e-05 7.76332679232756e-06 -1.23924800591154e-05 -1.2934128337402e-06 2.63615801095852e-06 4.40553151983387e-06 7.76332679232756e-06 0.000226742642513733 3342 3309 0 1614 296 3342 3309 0 1443 313 0 0 0 0 0 0 0 0 2148 0 0 0 0 0 3561 +777 781 0.998872276037647 0.0359566839400477 0.0310047261462895 0.575308614620734 -0.033736153059743 0.997019066244555 -0.0693891455601358 -0.0198993740178137 -0.0334073066873174 0.0682649135711138 0.99710774414555 0.0333104647152993 4.00727540024733e-05 1.09752688005872e-05 -2.71270159225013e-06 -1.05291461444043e-05 7.01017445400034e-07 4.19409843528857e-06 1.09752688005872e-05 4.12779417777775e-05 -4.41272383092464e-07 -2.37045298705671e-05 -1.53991455868846e-07 -1.03871960354936e-05 -2.71270159225013e-06 -4.41272383092464e-07 1.20618029971828e-05 1.45020843718374e-06 2.72690687609106e-06 -5.54959819276781e-06 -1.05291461444043e-05 -2.37045298705671e-05 1.45020843718374e-06 0.000102487615123781 -2.7944812003522e-06 -2.58564512704751e-05 7.01017445400034e-07 -1.53991455868846e-07 2.72690687609106e-06 -2.7944812003522e-06 1.23696457560854e-05 1.61361004028169e-05 4.19409843528857e-06 -1.03871960354936e-05 -5.54959819276781e-06 -2.58564512704751e-05 1.61361004028169e-05 0.000203742180287449 3300 3258 0 1304 566 3300 3258 0 1147 599 0 0 0 0 0 0 0 0 2423 0 0 0 0 0 3263 +777 751 0.999947201457465 0.00702156660052855 -0.00750279280385526 -3.76875299062859 -0.00696839015436826 0.999950583058613 0.00709034409583803 8.53430212104762e-05 0.00755220736207263 -0.00703768734849906 0.999946716140788 -0.20166183636701 4.34149737445987e-05 3.15303631860493e-05 1.91199664165378e-06 8.76624217764301e-06 9.20020661620099e-07 -3.96970598250907e-05 3.15303631860493e-05 0.00145359772817143 8.1187401091544e-06 0.0013469171042483 1.98276397392444e-05 0.000416298153741827 1.91199664165378e-06 8.1187401091544e-06 1.87736718923582e-05 2.01075039858199e-05 2.31167126418091e-06 2.23226215115094e-05 8.76624217764301e-06 0.0013469171042483 2.01075039858199e-05 0.0023180938150764 1.37450138012455e-05 0.00159856679452692 9.20020661620099e-07 1.98276397392444e-05 2.31167126418091e-06 1.37450138012455e-05 1.15962256178325e-05 -6.8894543864022e-06 -3.96970598250907e-05 0.000416298153741827 2.23226215115094e-05 0.00159856679452692 -6.8894543864022e-06 0.00236575280394111 339 339 0 0 0 339 339 0 0 0 0 0 0 0 0 85 85 0 0 0 257 257 0 0 0 +778 781 0.998250970807206 0.0115640551572655 0.0579764772195582 0.435494122221898 -0.00828218099398178 0.998366489918175 -0.0565310294125704 0.00444904538045863 -0.0585355000017353 0.0559519833141033 0.996716093380038 0.06291036369253 3.82117725571039e-05 -2.67130921309277e-06 2.08359669846214e-06 -1.19822317495927e-05 4.09693904662927e-07 -4.1066616241307e-06 -2.67130921309277e-06 0.000163800357911669 -3.25051615443512e-06 -2.28878767567245e-05 -6.79978772310435e-06 -0.000104760374223966 2.08359669846214e-06 -3.25051615443512e-06 1.19486894169186e-05 -2.18230467357758e-06 3.07445970007206e-06 4.27292380472234e-06 -1.19822317495927e-05 -2.28878767567245e-05 -2.18230467357758e-06 0.000194454911959964 -6.54000366219482e-07 -2.98875888596917e-05 4.09693904662927e-07 -6.79978772310435e-06 3.07445970007206e-06 -6.54000366219482e-07 1.09737659681594e-05 6.21568795809444e-06 -4.1066616241307e-06 -0.000104760374223966 4.27292380472234e-06 -2.98875888596917e-05 6.21568795809444e-06 0.000166843632739543 3147 3105 0 792 458 3147 3105 0 673 501 0 0 0 0 0 0 0 0 2944 0 0 0 0 0 3361 +778 782 0.999140548358992 -0.0204951794505558 0.0360293247811038 0.586028059802205 0.0217077911446965 0.999199800381923 -0.0335936113024883 0.00868258319805342 -0.0353119870371377 0.0343468562755596 0.998785941548776 0.0505360372084192 3.36706826529357e-05 -4.85919558251715e-06 -6.17918598349431e-07 1.6768826722e-06 -6.55495276265861e-07 3.89673270062975e-06 -4.85919558251715e-06 6.37620457837337e-05 1.88759133497233e-07 -5.14649937157355e-06 -4.28884392261642e-07 -5.91657790780793e-06 -6.17918598349431e-07 1.88759133497233e-07 1.12802770492852e-05 2.51937681551459e-06 2.60930271610979e-06 -2.82707074355127e-06 1.6768826722e-06 -5.14649937157355e-06 2.51937681551459e-06 0.000115363233543196 -5.79845363782172e-07 7.50995651951597e-06 -6.55495276265861e-07 -4.28884392261642e-07 2.60930271610979e-06 -5.79845363782172e-07 1.21407925293898e-05 1.76003496677037e-05 3.89673270062975e-06 -5.91657790780793e-06 -2.82707074355127e-06 7.50995651951597e-06 1.76003496677037e-05 0.000293010974500759 3034 2984 0 1079 766 3034 2984 0 933 816 0 0 0 0 0 0 0 0 2664 0 0 0 0 0 3024 +779 782 0.99789244312339 -0.0392887089852035 0.0516436763167288 0.453878014413062 0.0404662258671892 0.998939645691194 -0.0219560659139496 0.021557283112656 -0.0507262902378706 0.0239996169266941 0.998424189343425 0.00526953830635781 4.93468638065444e-05 3.98200027886267e-06 -3.53197083437755e-06 1.06429789747374e-06 3.84758889300084e-06 7.20909490540212e-08 3.98200027886267e-06 8.80095982049277e-05 -1.17226843008715e-06 2.33640901929065e-05 -2.33222606143672e-06 -0.000101178721346865 -3.53197083437755e-06 -1.17226843008715e-06 1.49295611506676e-05 -3.83366629238008e-06 1.4413179168957e-06 3.29616929392846e-06 1.06429789747374e-06 2.33640901929065e-05 -3.83366629238008e-06 0.000130962819790076 -5.97460492963027e-07 -4.50425416116493e-05 3.84758889300084e-06 -2.33222606143672e-06 1.4413179168957e-06 -5.97460492963027e-07 1.17546380508882e-05 4.23579204889775e-06 7.20909490540212e-08 -0.000101178721346865 3.29616929392846e-06 -4.50425416116493e-05 4.23579204889775e-06 0.000193368491086321 3191 3141 0 649 642 3191 3141 0 543 688 0 0 0 0 0 0 0 0 3090 0 0 0 0 0 3152 +780 782 0.99885192595738 -0.0475498010628591 0.00581776848244488 0.300709253958014 0.0475383783735339 0.998867233446844 0.00208627128211096 0.0223441610314993 -0.00591038009332149 -0.00180730880879802 0.999980900338613 0.0397227326039205 4.53625227980519e-05 -4.63603566427131e-06 -1.1652859519985e-05 -3.01991499459586e-06 1.40640206840616e-06 -1.80111493781653e-06 -4.63603566427131e-06 3.18431045167917e-05 -9.32901325494242e-07 -4.02012738320983e-06 -1.17120851343544e-06 -2.2608176476677e-05 -1.1652859519985e-05 -9.32901325494242e-07 1.5985664096595e-05 4.44338622872247e-06 2.61356131125778e-06 2.76985587707975e-06 -3.01991499459586e-06 -4.02012738320983e-06 4.44338622872247e-06 6.45232609497803e-05 6.299682720372e-07 2.49043555078076e-05 1.40640206840616e-06 -1.17120851343544e-06 2.61356131125778e-06 6.299682720372e-07 1.09824952340806e-05 1.82866458084397e-06 -1.80111493781653e-06 -2.2608176476677e-05 2.76985587707975e-06 2.49043555078076e-05 1.82866458084397e-06 6.68443992718807e-05 3313 3263 0 289 449 3313 3263 0 180 487 0 0 0 0 0 0 0 0 3491 0 0 0 0 0 3347 +780 783 0.997362966432844 -0.0725191587106345 0.00284337971072437 0.443659269517448 0.0723367914854693 0.996498693303294 0.041925443854724 0.0328389961597795 -0.00587382208321646 -0.0416092040867125 0.999116696061779 0.0238052484887062 4.01932843434657e-05 3.14009770398963e-06 -8.81317570127889e-06 6.03467924587833e-06 -3.30261499854479e-07 -9.5459801492517e-07 3.14009770398963e-06 2.88696620012355e-05 2.23213086514375e-08 9.25871599885075e-06 -4.52744227476351e-07 -1.95410355600142e-05 -8.81317570127889e-06 2.23213086514375e-08 1.54695838431024e-05 -2.14474175756466e-06 1.01822370949091e-06 2.19055898774583e-06 6.03467924587833e-06 9.25871599885075e-06 -2.14474175756466e-06 0.000135041143696268 -3.90653282587592e-07 -7.17769517975538e-07 -3.30261499854479e-07 -4.52744227476351e-07 1.01822370949091e-06 -3.90653282587592e-07 1.2372383622678e-05 -1.92715580673143e-06 -9.5459801492517e-07 -1.95410355600142e-05 2.19055898774583e-06 -7.17769517975538e-07 -1.92715580673143e-06 9.20533130679165e-05 3294 3238 0 506 729 3294 3238 0 388 775 0 0 0 0 0 0 0 0 3259 0 0 0 0 0 3063 +782 784 0.998493346838887 -0.0495051322647149 -0.0236701964066974 0.284241103821135 0.0502633248309151 0.998204197414747 0.0325880106867919 0.0196889273753359 0.0220144156275032 -0.0337286546282776 0.999188542449094 -0.0155739397762178 4.34869508183242e-05 1.09803117199624e-05 -8.69106090662966e-06 8.82754493951451e-06 7.27029268012129e-07 -1.31300529227003e-05 1.09803117199624e-05 4.0884774239861e-05 3.62673364490282e-07 -3.89338547724573e-06 3.15464480111447e-07 -8.35293356808547e-06 -8.69106090662966e-06 3.62673364490282e-07 1.32270966389067e-05 -3.65353519786208e-06 2.52621705856641e-06 -5.69593940850224e-07 8.82754493951451e-06 -3.89338547724573e-06 -3.65353519786208e-06 9.91542710707723e-05 2.34670075186704e-06 -1.17465523176071e-05 7.27029268012129e-07 3.15464480111447e-07 2.52621705856641e-06 2.34670075186704e-06 1.07362036371952e-05 3.90835180516303e-06 -1.31300529227003e-05 -8.35293356808547e-06 -5.69593940850224e-07 -1.17465523176071e-05 3.90835180516303e-06 0.000273862501546678 3351 3283 0 280 421 3351 3283 0 168 457 0 0 0 0 0 0 0 0 3480 0 0 0 0 0 3394 +781 784 0.996679675324307 -0.0784578290118482 -0.0217714000969588 0.433810684240503 0.0795291527560968 0.995384402044626 0.0537122521233321 0.0336303525830143 0.0174567653742519 -0.0552653710112451 0.998319087321112 -0.0186671287287072 4.60245741823932e-05 -5.73696145929234e-06 -6.66849156499525e-06 -4.48939234288205e-06 3.63984786959612e-08 -2.31274656507254e-05 -5.73696145929234e-06 3.40150482364766e-05 2.21608643551887e-06 -1.63937494229748e-05 1.70312144407346e-07 -1.47828874796384e-07 -6.66849156499525e-06 2.21608643551887e-06 1.40969765649449e-05 -9.12482531973365e-06 3.05139891122058e-06 -3.23967661723907e-06 -4.48939234288205e-06 -1.63937494229748e-05 -9.12482531973365e-06 0.000128014943601451 3.37959742111482e-08 1.87666969793731e-05 3.63984786959612e-08 1.70312144407346e-07 3.05139891122058e-06 3.37959742111482e-08 1.12551737320655e-05 -8.01376537372702e-07 -2.31274656507254e-05 -1.47828874796384e-07 -3.23967661723907e-06 1.87666969793731e-05 -8.01376537372702e-07 0.000302575375019422 3352 3284 0 482 719 3352 3284 0 360 763 0 0 0 0 0 0 0 0 3255 0 0 0 0 0 3080 +782 785 0.997790531121022 -0.06625617391852 -0.00491685091374258 0.429414907041963 0.0663453503703516 0.997575954409305 0.0209883221959352 0.0347601196630975 0.0035143263172932 -0.0212681593478123 0.999767630456443 0.021338599944771 4.5104295320827e-05 1.18877368602619e-05 -7.34147402360439e-06 1.56781621701082e-05 1.2276386473536e-06 -9.21020972483732e-06 1.18877368602619e-05 0.00010353631595651 -7.52969096201892e-06 2.4003114032757e-05 -1.05525467505413e-07 -0.000102492054244414 -7.34147402360439e-06 -7.52969096201892e-06 1.40339896287187e-05 -5.69087512855862e-07 1.09301061632961e-06 9.23681021912429e-06 1.56781621701082e-05 2.4003114032757e-05 -5.69087512855862e-07 0.000212381493295814 -8.16499628935669e-06 1.20317107947047e-05 1.2276386473536e-06 -1.05525467505413e-07 1.09301061632961e-06 -8.16499628935669e-06 1.21294544654549e-05 -2.9141530864969e-06 -9.21020972483732e-06 -0.000102492054244414 9.23681021912429e-06 1.20317107947047e-05 -2.9141530864969e-06 0.00019216622382937 3261 3186 0 501 666 3261 3186 0 381 706 0 0 0 0 0 0 0 0 3199 0 0 0 0 0 3134 +783 786 0.99888658908651 -0.0333321789305105 0.0333848467251566 0.444083033253241 0.0335654225193399 0.99941570635791 -0.00645044930352389 0.0237330570814717 -0.0331503326411057 0.00756384378894572 0.999421754672631 0.00171827696595981 4.17972482085465e-05 1.72774977245272e-05 -2.12321635121397e-06 1.20564081196508e-06 5.2565377715024e-07 -2.0511339764013e-05 1.72774977245272e-05 9.27268233908639e-05 1.47856708167297e-06 4.89412059940764e-05 -1.96457925021605e-06 -5.89681282702204e-05 -2.12321635121397e-06 1.47856708167297e-06 1.37252966919697e-05 -1.23559023977488e-06 2.02656917555229e-06 -1.2541398055854e-06 1.20564081196508e-06 4.89412059940764e-05 -1.23559023977488e-06 0.000102793803061377 -1.14533792272317e-06 -2.50311849211553e-05 5.2565377715024e-07 -1.96457925021605e-06 2.02656917555229e-06 -1.14533792272317e-06 1.12894488874185e-05 2.0817015328029e-06 -2.0511339764013e-05 -5.89681282702204e-05 -1.2541398055854e-06 -2.50311849211553e-05 2.0817015328029e-06 0.000175198214285704 3210 3136 0 701 583 3210 3136 0 564 617 0 0 0 0 0 0 0 0 2887 0 0 0 0 0 3221 +783 785 0.999106162201669 -0.0419909669032901 -0.00486162001581527 0.291878107461258 0.0419139838499763 0.999008907327417 -0.0149806888461375 0.02140761703843 0.00548585530936736 0.0147635286773742 0.999875964113808 -0.00246602077581828 4.43072623776259e-05 6.10749824226285e-06 -8.46290648706525e-06 3.43946666543502e-07 1.92081545295884e-06 -1.0669904129458e-05 6.10749824226285e-06 2.91422520247252e-05 2.49393821649717e-07 -7.89675533270496e-06 7.08221163917628e-07 -1.07556553533622e-05 -8.46290648706525e-06 2.49393821649717e-07 1.51549656792445e-05 -2.89704513924108e-07 1.54746850179256e-06 -1.58884923504223e-06 3.43946666543502e-07 -7.89675533270496e-06 -2.89704513924108e-07 0.000118958251700806 -2.99945689103028e-06 -8.67908277382218e-06 1.92081545295884e-06 7.08221163917628e-07 1.54746850179256e-06 -2.99945689103028e-06 1.22945901208452e-05 2.42431929834126e-06 -1.0669904129458e-05 -1.07556553533622e-05 -1.58884923504223e-06 -8.67908277382218e-06 2.42431929834126e-06 9.78115582335324e-05 3346 3271 0 321 410 3346 3271 0 208 436 0 0 0 0 0 0 0 0 3396 0 0 0 0 0 3407 +783 787 0.999908154131589 0.00784583983015095 0.0110510677546221 0.579815179326396 -0.00783788922090444 0.999968992509429 -0.000762569497452333 0.0210488067315106 -0.0110567080868793 0.000675882413761178 0.999938644312362 0.038580506893822 5.02219807150695e-05 1.45634990463663e-05 -1.8083308751591e-06 2.24382268249115e-06 1.37467484971277e-06 -1.18163340994994e-05 1.45634990463663e-05 3.82475271761995e-05 2.44951089042299e-07 2.02210066887615e-05 -9.59067636139595e-07 -2.39556203681632e-05 -1.8083308751591e-06 2.44951089042299e-07 1.26262635876817e-05 -3.96049688433287e-06 3.28787951547448e-06 7.34973801578495e-07 2.24382268249115e-06 2.02210066887615e-05 -3.96049688433287e-06 0.000124596687160939 -1.88260332350323e-06 -8.57487074150372e-06 1.37467484971277e-06 -9.59067636139595e-07 3.28787951547448e-06 -1.88260332350323e-06 1.09741729146249e-05 7.0681103340696e-07 -1.18163340994994e-05 -2.39556203681632e-05 7.34973801578495e-07 -8.57487074150372e-06 7.0681103340696e-07 0.000108081986848035 3186 3123 0 1185 680 3186 3123 0 1021 717 0 0 0 0 0 0 0 0 2418 0 0 0 0 0 3132 +785 789 0.995211542700498 0.0965649072234947 -0.0151394837630559 0.597646509547182 -0.096551112813716 0.995326674646709 0.00164114324700307 -0.0327873826074609 0.0152272088751376 -0.000171550697894203 0.99988404461729 0.0256546310254464 3.23135676121782e-05 1.34170937344837e-05 -4.48412220860252e-06 2.19072823972761e-06 -3.74435789235978e-08 -2.42507210683578e-06 1.34170937344837e-05 3.75678297269745e-05 -9.88566908063276e-07 4.092717601302e-06 1.81444679196696e-06 5.39922239542813e-05 -4.48412220860252e-06 -9.88566908063276e-07 1.34875819814649e-05 -3.92765836204495e-06 2.30725084091038e-06 -1.22158135123171e-05 2.19072823972761e-06 4.092717601302e-06 -3.92765836204495e-06 0.000111410653420391 4.89071717364804e-06 4.22701974827513e-05 -3.74435789235978e-08 1.81444679196696e-06 2.30725084091038e-06 4.89071717364804e-06 1.13673031559548e-05 1.69974091813429e-05 -2.42507210683578e-06 5.39922239542813e-05 -1.22158135123171e-05 4.22701974827513e-05 1.69974091813429e-05 0.000610521651229979 3155 3107 0 1648 406 3155 3107 0 1465 431 0 0 0 0 0 0 0 0 2073 0 0 0 0 0 3448 +786 789 0.995134462757013 0.0879617215048802 -0.0443862206457015 0.434294981354389 -0.0882171576574908 0.996093920745108 -0.00382546068762725 -0.0249259717618649 0.0438763504424013 0.00772247399070203 0.99900712173003 0.0728793481123782 5.35842949736293e-05 2.80314980320203e-05 -6.40621783459876e-06 -1.02867662378292e-05 -1.57800801565757e-06 -3.0952238764744e-05 2.80314980320203e-05 0.000436814890982133 4.10551288705637e-06 0.000384342887686939 8.88492292159916e-06 -0.000397063069571 -6.40621783459876e-06 4.10551288705637e-06 1.49514622449384e-05 -3.02737891650159e-06 2.43999982789708e-06 -4.22822971028392e-06 -1.02867662378292e-05 0.000384342887686939 -3.02737891650159e-06 0.000654251538384108 2.03791778498437e-05 -0.000312473411434506 -1.57800801565757e-06 8.88492292159916e-06 2.43999982789708e-06 2.03791778498437e-05 1.15715610301131e-05 -5.59148053506099e-06 -3.0952238764744e-05 -0.000397063069571 -4.22822971028392e-06 -0.000312473411434506 -5.59148053506099e-06 0.000483335592180017 2885 2837 0 1126 205 2885 2837 0 971 227 0 0 0 0 0 0 0 0 2597 0 0 0 0 0 3643 +786 790 0.99567480702739 0.0898551741518102 -0.0236162302054764 0.582750333776738 -0.0904309258449102 0.99559986658345 -0.0245591797470599 -0.0328933025267732 0.0213055462685787 0.0265885941178526 0.999419391627476 0.061365674091175 5.90515786200397e-05 3.11771416851402e-05 -8.39566105718836e-06 4.84754244784786e-06 7.78859434372131e-07 -3.72595257778257e-05 3.11771416851402e-05 6.3992631205688e-05 -7.56038037061359e-07 4.24863040776405e-05 3.41368163497472e-06 -2.19574567723979e-05 -8.39566105718836e-06 -7.56038037061359e-07 1.49150127408651e-05 -6.84016111808511e-06 3.66277440877071e-06 2.87536443562767e-06 4.84754244784786e-06 4.24863040776405e-05 -6.84016111808511e-06 0.000208678494453862 9.80912602989952e-06 1.10823903215801e-05 7.78859434372131e-07 3.41368163497472e-06 3.66277440877071e-06 9.80912602989952e-06 1.24959617053669e-05 3.78362995064365e-06 -3.72595257778257e-05 -2.19574567723979e-05 2.87536443562767e-06 1.10823903215801e-05 3.78362995064365e-06 0.000188201207823461 3160 3112 0 1562 393 3160 3112 0 1387 429 0 0 0 0 0 0 0 0 2136 0 0 0 0 0 3465 +787 789 0.998410555432202 0.0464892569412629 -0.0318608190511611 0.303684874631911 -0.0468199042971349 0.998856140336124 -0.00971120355204825 -0.00612902194953967 0.0313729081082503 0.0111874886311194 0.99944513643069 -0.0124015474287444 4.3049396118229e-05 2.16088875197078e-06 -1.47071860796165e-05 1.33667146170005e-06 2.33184338983944e-06 2.83329517146377e-06 2.16088875197078e-06 1.76605858330102e-05 3.25447586185693e-06 -4.97072756314982e-06 -7.67156903388832e-07 -1.44706264856324e-05 -1.47071860796165e-05 3.25447586185693e-06 2.03166976145707e-05 -3.85891699248144e-06 2.86190615101957e-07 -3.40810475879501e-06 1.33667146170005e-06 -4.97072756314982e-06 -3.85891699248144e-06 8.32643464467137e-05 3.33172063610652e-06 5.42338176195821e-06 2.33184338983944e-06 -7.67156903388832e-07 2.86190615101957e-07 3.33172063610652e-06 1.34732880455135e-05 1.38489519761481e-06 2.83329517146377e-06 -1.44706264856324e-05 -3.40810475879501e-06 5.42338176195821e-06 1.38489519761481e-06 5.26683094664662e-05 3486 3438 0 638 182 3486 3438 0 520 201 0 0 0 0 0 0 0 0 3101 0 0 0 0 0 3663 +788 791 0.999054397840274 -0.00238063945627375 0.0434124718460873 0.444613276233496 0.00261728789441962 0.99998202097717 -0.00539513915406146 4.58890678890471e-05 -0.0433988474511226 0.00550366043585495 0.999042666637277 0.0421044648206168 3.86226701738783e-05 3.03659968656883e-06 -3.01197918061556e-06 -1.20023114076447e-05 1.80029969152867e-07 -1.4258477910287e-07 3.03659968656883e-06 3.07186957558021e-05 -2.84315575448977e-07 1.16002029594795e-05 1.10073214871554e-06 -2.58632648158942e-05 -3.01197918061556e-06 -2.84315575448977e-07 1.02253995249375e-05 -2.61850505687377e-06 3.1779673116412e-06 -8.93444519595726e-07 -1.20023114076447e-05 1.16002029594795e-05 -2.61850505687377e-06 9.83254745702397e-05 1.40537804608921e-06 -1.09069240616981e-05 1.80029969152867e-07 1.10073214871554e-06 3.1779673116412e-06 1.40537804608921e-06 1.00799096674053e-05 5.97661448635144e-07 -1.4258477910287e-07 -2.58632648158942e-05 -8.93444519595726e-07 -1.09069240616981e-05 5.97661448635144e-07 7.80058368802959e-05 3175 3122 0 811 483 3175 3122 0 676 525 0 0 0 0 0 0 0 0 2920 0 0 0 0 0 3323 +788 762 0.997857776284766 -0.0503450253517913 0.0417760305719636 -3.76690372665625 0.0475268729923448 0.996693037313982 0.0659104370596788 -0.067598860573581 -0.0449561414224093 -0.06378375805921 0.996950639478331 -0.237363178511991 7.53824200515603e-05 1.14855778331179e-05 -5.41185298131217e-08 -1.70929886355502e-05 1.55155704044962e-06 4.25807504282664e-06 1.14855778331179e-05 6.01183681440546e-05 4.66695764405237e-06 -1.32312780062668e-05 9.10378907782722e-07 -5.2363980538445e-05 -5.41185298131217e-08 4.66695764405237e-06 2.34071631983157e-05 -1.4516087361841e-05 3.2183220076403e-06 -8.07540064448052e-06 -1.70929886355502e-05 -1.32312780062668e-05 -1.4516087361841e-05 0.000261481576276426 -5.40578160597102e-07 -1.88105740652697e-05 1.55155704044962e-06 9.10378907782722e-07 3.2183220076403e-06 -5.40578160597102e-07 1.06212147839335e-05 -1.47334958676612e-06 4.25807504282664e-06 -5.2363980538445e-05 -8.07540064448052e-06 -1.88105740652697e-05 -1.47334958676612e-06 0.000141269072488752 385 385 0 0 0 384 384 0 0 0 0 0 0 0 0 75 75 0 0 0 272 272 0 0 0 +789 791 0.999385679849148 -0.0231360596988086 0.0263246206823672 0.29225555961275 0.0236575135842879 0.999526542751016 -0.019672630409053 0.00730307355180796 -0.0258570099483019 0.0202833201871667 0.999459855101103 0.0304727692131057 4.76606649361613e-05 -1.8744121921116e-06 -4.89685519702297e-06 -1.34234130727167e-05 -2.04200217536097e-06 -9.60048815040873e-06 -1.8744121921116e-06 3.76585663716681e-05 -7.73253591211985e-07 5.74614728178353e-06 -3.97868853738058e-07 -1.82101855296254e-05 -4.89685519702297e-06 -7.73253591211985e-07 1.25813805577891e-05 -3.91553416045283e-06 4.09118535887533e-06 -1.32467823496088e-06 -1.34234130727167e-05 5.74614728178353e-06 -3.91553416045283e-06 0.000106028790657369 4.27903041865958e-07 4.1087318324249e-06 -2.04200217536097e-06 -3.97868853738058e-07 4.09118535887533e-06 4.27903041865958e-07 1.0194361041407e-05 4.26321653329634e-06 -9.60048815040873e-06 -1.82101855296254e-05 -1.32467823496088e-06 4.1087318324249e-06 4.26321653329634e-06 0.000162637733633457 3269 3216 0 395 350 3269 3216 0 283 383 0 0 0 0 0 0 0 0 3353 0 0 0 0 0 3465 +791 794 0.994959175311563 -0.0942483716412646 -0.0342561513644509 0.465075267925799 0.0957541878402533 0.994371256879834 0.045353489416712 0.014732509296825 0.0297888397623605 -0.0484050403799893 0.998383481980458 0.025532628919364 5.29621594776527e-05 5.19296329131875e-06 -4.8400766251205e-06 1.4404655342886e-06 2.54387103172669e-06 -8.50732020930286e-06 5.19296329131875e-06 4.30571197494179e-05 2.72812876457104e-06 1.18107387844272e-05 -1.00610581466272e-06 -3.16843098135221e-05 -4.8400766251205e-06 2.72812876457104e-06 1.48809888452982e-05 3.04231534386451e-07 3.19800046565848e-06 -1.10308227759102e-06 1.4404655342886e-06 1.18107387844272e-05 3.04231534386451e-07 7.25621872371699e-05 -3.25806147806826e-07 -9.8798667404343e-06 2.54387103172669e-06 -1.00610581466272e-06 3.19800046565848e-06 -3.25806147806826e-07 1.15107320780016e-05 2.16466296239191e-06 -8.50732020930286e-06 -3.16843098135221e-05 -1.10308227759102e-06 -9.8798667404343e-06 2.16466296239191e-06 7.75655605752939e-05 3189 3112 0 579 761 3189 3112 0 437 795 0 0 0 0 0 0 0 0 3141 0 0 0 0 0 3020 +790 792 0.998232857780707 -0.0552965702151671 0.0217589284984839 0.298640095625946 0.0558027004319364 0.998167928815315 -0.0233847067342529 0.0124155693680317 -0.0204259705146805 0.0245575896004178 0.999489722068992 0.0256389510337607 4.2078874641084e-05 -1.4736155931498e-05 -7.98371786839776e-06 -1.24509782031337e-05 9.5675424608316e-07 2.30459685207529e-06 -1.4736155931498e-05 0.00019119608680328 -6.70574901578649e-06 9.86484150625338e-05 -2.12431936408565e-06 -0.000101801510582675 -7.98371786839776e-06 -6.70574901578649e-06 2.08842740158737e-05 -7.8400174624941e-06 8.16601697006892e-07 -8.22859026659868e-06 -1.24509782031337e-05 9.86484150625338e-05 -7.8400174624941e-06 0.000185804306206117 -2.02968736707859e-06 -3.50488568613348e-05 9.5675424608316e-07 -2.12431936408565e-06 8.16601697006892e-07 -2.02968736707859e-06 1.29684615017676e-05 1.79751549679186e-05 2.30459685207529e-06 -0.000101801510582675 -8.22859026659868e-06 -3.50488568613348e-05 1.79751549679186e-05 0.000407078683082906 3234 3180 0 307 446 3234 3180 0 181 481 0 0 0 0 0 0 0 0 3437 0 0 0 0 0 3358 +789 793 0.995889376922085 -0.0882890602246803 0.020233407483283 0.604966603518196 0.0883817053585105 0.996079698010199 -0.00372952675701405 0.0218062087961678 -0.0198248100032063 0.00550245913684317 0.999788327523273 0.0580704785703895 5.62949883251493e-05 -5.05122167657199e-06 -9.71570714923145e-06 1.81078208373255e-05 1.87403864071973e-06 1.28432369908667e-05 -5.05122167657199e-06 3.85238370774126e-05 5.51181809931386e-06 4.53342054694547e-06 -2.23964417360489e-07 -3.0264266167508e-05 -9.71570714923145e-06 5.51181809931386e-06 1.66140695077805e-05 -7.63548038069618e-06 2.46756947366991e-06 -1.00483966335702e-05 1.81078208373255e-05 4.53342054694547e-06 -7.63548038069618e-06 0.000141348638920148 -1.4581657549809e-06 1.29724086949766e-05 1.87403864071973e-06 -2.23964417360489e-07 2.46756947366991e-06 -1.4581657549809e-06 1.18519958545668e-05 4.28728860367225e-06 1.28432369908667e-05 -3.0264266167508e-05 -1.00483966335702e-05 1.29724086949766e-05 4.28728860367225e-06 0.000169330289847383 3078 3006 0 958 970 3078 3006 0 804 1015 0 0 0 0 0 0 0 0 2763 0 0 0 0 0 2809 +793 796 0.998706404001653 -0.0504504626936138 0.00634581910292819 0.456326095988458 0.0504698117815969 0.998721298580872 -0.00292674899266274 -0.00235566754602618 -0.00619004885416784 0.00324323525760251 0.999975582062006 0.0447089110995617 5.37409845703193e-05 1.44377983800885e-05 -3.27226145521098e-06 -1.09587800579502e-05 1.12151184724621e-06 -1.70383749316543e-05 1.44377983800885e-05 4.90925130434355e-05 2.94615101442142e-06 1.10672609063112e-05 -8.19178459377045e-07 -3.96858669516388e-05 -3.27226145521098e-06 2.94615101442142e-06 1.37255362955586e-05 -2.40460493469404e-06 3.76869127189303e-06 -4.08479269299776e-06 -1.09587800579502e-05 1.10672609063112e-05 -2.40460493469404e-06 0.000103659533553447 -6.48785110647956e-06 1.81290730903845e-07 1.12151184724621e-06 -8.19178459377045e-07 3.76869127189303e-06 -6.48785110647956e-06 1.15890229890336e-05 2.73039007728226e-07 -1.70383749316543e-05 -3.96858669516388e-05 -4.08479269299776e-06 1.81290730903845e-07 2.73039007728226e-07 8.17470348144309e-05 3030 2944 0 747 599 3030 2944 0 614 623 0 0 0 0 0 0 0 0 2837 0 0 0 0 0 3193 +793 797 0.999641197070177 -0.0249332613025166 0.00978823788652489 0.615988230369909 0.0248358104991403 0.999641982748832 0.00995433789036304 -0.0124576990080846 -0.0100329276362169 -0.00970766742349329 0.999902546029482 0.0788414970724043 5.82329155605672e-05 2.66922173149732e-05 -2.49652079605827e-07 -5.15747705914965e-06 2.00775918545645e-06 -2.15304455560334e-05 2.66922173149732e-05 6.28028051487815e-05 6.04954812989468e-07 7.38803286554048e-06 3.1171929337194e-07 -6.1710307806837e-05 -2.49652079605827e-07 6.04954812989468e-07 1.68251496849707e-05 3.77871343038624e-06 1.52718943744351e-06 -1.81417583076353e-06 -5.15747705914965e-06 7.38803286554048e-06 3.77871343038624e-06 0.000175075323079613 -1.35018588546258e-05 -6.53401837014428e-06 2.00775918545645e-06 3.1171929337194e-07 1.52718943744351e-06 -1.35018588546258e-05 1.25982754582243e-05 1.80769067111405e-06 -2.15304455560334e-05 -6.1710307806837e-05 -1.81417583076353e-06 -6.53401837014428e-06 1.80769067111405e-06 0.000210720773333394 2812 2733 0 1280 753 2812 2733 0 1141 784 0 0 0 0 0 0 0 0 2326 0 0 0 0 0 3039 +792 796 0.996297050174603 -0.0848138107650873 -0.0140998339312544 0.60872135626738 0.0852431806077424 0.995803220170543 0.0333098612703902 0.013198616215714 0.0112155237622149 -0.0343884312157561 0.999345609799362 0.0760605077718644 4.99351124518727e-05 1.46991460375778e-05 -7.44637863324969e-06 7.23439306956109e-06 -1.39455730587417e-06 -2.23940122502979e-06 1.46991460375778e-05 4.62361892384408e-05 4.32344427519826e-07 1.4382402803219e-05 -1.44558915478276e-06 -2.05478328893441e-05 -7.44637863324969e-06 4.32344427519826e-07 1.52416452592212e-05 1.02189279094594e-06 1.87417803597609e-06 -1.27250242636201e-06 7.23439306956109e-06 1.4382402803219e-05 1.02189279094594e-06 7.75852002212283e-05 -2.04101579693088e-06 1.74619485654634e-05 -1.39455730587417e-06 -1.44558915478276e-06 1.87417803597609e-06 -2.04101579693088e-06 1.18123978567792e-05 6.78539740223215e-07 -2.23940122502979e-06 -2.05478328893441e-05 -1.27250242636201e-06 1.74619485654634e-05 6.78539740223215e-07 0.0001387741310669 2960 2874 0 1047 935 2960 2874 0 851 969 0 0 0 0 0 0 0 0 2498 0 0 0 0 0 2850 +794 798 0.999136819368311 0.0308639887943686 0.0278034238588684 0.609867755459895 -0.0287724060779291 0.996937222113693 -0.0727208622935672 -0.0419269091048289 -0.0299627240260553 0.0718581196520915 0.996964716431331 0.061816775755189 5.6367771180658e-05 2.97105366525441e-05 -7.36435012781366e-06 9.2393515340904e-07 7.7820222690691e-07 -1.94049061411664e-05 2.97105366525441e-05 8.9503777399255e-05 -5.85735379523806e-06 2.3164284550422e-05 -1.43888427310513e-06 -5.62037422708573e-05 -7.36435012781366e-06 -5.85735379523806e-06 1.57965678823959e-05 -6.18765548129217e-06 3.86444539249228e-06 4.11398743179102e-06 9.2393515340904e-07 2.3164284550422e-05 -6.18765548129217e-06 9.86544057558422e-05 2.13551863587454e-06 -4.66388403210007e-06 7.7820222690691e-07 -1.43888427310513e-06 3.86444539249228e-06 2.13551863587454e-06 1.20049302700246e-05 3.6410885064423e-06 -1.94049061411664e-05 -5.62037422708573e-05 4.11398743179102e-06 -4.66388403210007e-06 3.6410885064423e-06 9.8214966507194e-05 3042 2973 0 1568 567 3042 2973 0 1382 595 0 0 0 0 0 0 0 0 2195 0 0 0 0 0 3258 +794 797 0.99971605882329 0.00381148484827719 0.0235217838201154 0.459404303258095 -0.00328027466881121 0.999739631580628 -0.0225811612882753 -0.0250036156271701 -0.0236017272445481 0.0224975916551372 0.999468267050431 0.0119749072712017 5.6419858262069e-05 1.91428401380313e-05 -3.23392666763102e-06 -3.4464016967107e-06 1.96171856537793e-06 -1.89011242280365e-05 1.91428401380313e-05 4.67499391724653e-05 -5.25193916870164e-07 2.29023605351316e-05 -1.32209570327332e-06 -3.95336404881434e-05 -3.23392666763102e-06 -5.25193916870164e-07 1.35824042577817e-05 -1.41606945743036e-06 3.71237064234096e-06 -1.13451686843361e-07 -3.4464016967107e-06 2.29023605351316e-05 -1.41606945743036e-06 8.64933644384642e-05 -8.74674668784929e-07 -2.18166554018873e-05 1.96171856537793e-06 -1.32209570327332e-06 3.71237064234096e-06 -8.74674668784929e-07 1.07471966246414e-05 1.66277890946508e-06 -1.89011242280365e-05 -3.95336404881434e-05 -1.13451686843361e-07 -2.18166554018873e-05 1.66277890946508e-06 9.06250759494408e-05 3221 3142 0 1007 442 3221 3142 0 834 465 0 0 0 0 0 0 0 0 2567 0 0 0 0 0 3361 +793 795 0.998837801653148 -0.0455676346892163 -0.0157046699276863 0.302509301603593 0.0455409892418114 0.998960366839598 -0.00205031279868529 0.000859161173598824 0.0157817707366654 0.00133272372431717 0.999874571913843 0.0441038542756491 4.46848545901265e-05 3.27405025983263e-06 -2.54403696837896e-06 -4.76917341828113e-06 1.48325871385016e-06 -1.31560272317798e-05 3.27405025983263e-06 3.28552398632868e-05 -7.8018558027483e-07 -5.86253705128556e-06 1.04068173536609e-06 -1.88188700482915e-05 -2.54403696837896e-06 -7.8018558027483e-07 1.33686756265925e-05 9.80373792613349e-07 3.56596400527045e-06 -2.48239062749758e-06 -4.76917341828113e-06 -5.86253705128556e-06 9.80373792613349e-07 6.36546401184404e-05 -1.84943775349507e-06 4.11363454830825e-06 1.48325871385016e-06 1.04068173536609e-06 3.56596400527045e-06 -1.84943775349507e-06 1.09692996994924e-05 -6.74773440210427e-07 -1.31560272317798e-05 -1.88188700482915e-05 -2.48239062749758e-06 4.11363454830825e-06 -6.74773440210427e-07 5.37384138074166e-05 3233 3146 0 374 398 3233 3146 0 256 417 0 0 0 0 0 0 0 0 3196 0 0 0 0 0 3391 +796 800 0.996203215407282 0.0843859522136429 -0.021404781736534 0.615405842069081 -0.0853635300797544 0.995102719682694 -0.0498361817601193 -0.100042190755305 0.0170944828677196 0.0514741522426698 0.99852801177853 0.0665989160628841 7.39486121293923e-05 6.68036887179242e-05 -4.58618951267586e-06 1.52082210350536e-05 -2.70003835640688e-06 -7.43105916294567e-05 6.68036887179242e-05 0.000178484689428913 -7.66508430698495e-06 5.20798019745693e-05 -1.09911759652395e-05 -0.000191210416145094 -4.58618951267586e-06 -7.66508430698495e-06 1.41200876915796e-05 -3.66634260788691e-06 4.55545257550676e-06 1.30006074888216e-05 1.52082210350536e-05 5.20798019745693e-05 -3.66634260788691e-06 8.86596126902185e-05 -4.81096699813103e-06 -8.83035174941641e-05 -2.70003835640688e-06 -1.09911759652395e-05 4.55545257550676e-06 -4.81096699813103e-06 1.23506928254241e-05 2.66530074455661e-05 -7.43105916294567e-05 -0.000191210416145094 1.30006074888216e-05 -8.83035174941641e-05 2.66530074455661e-05 0.000415912411852191 2928 2876 0 1787 361 2928 2876 0 1611 382 0 0 0 0 0 0 0 0 1978 0 0 0 0 0 3467 +797 801 0.999020899716955 0.0424305123720072 0.0125257154915328 0.615305609716953 -0.0413842082772004 0.996365300190362 -0.0744549251684411 -0.0962733865036701 -0.0156393488993365 0.073863659511412 0.997145711804241 0.0522549649680766 4.45292419913278e-05 1.41948873238495e-05 -3.72368915365708e-06 4.73448208101479e-06 3.74742596834681e-07 -1.23319046540393e-05 1.41948873238495e-05 3.29501985017268e-05 7.43239547638759e-06 1.21611177118063e-05 -1.02008436731674e-06 -2.26875547548297e-05 -3.72368915365708e-06 7.43239547638759e-06 1.88548638729703e-05 9.94775714297796e-07 2.73076257852792e-06 -1.16889243004589e-06 4.73448208101479e-06 1.21611177118063e-05 9.94775714297796e-07 9.3144748038465e-05 -9.67158731462802e-07 -8.43745649367329e-06 3.74742596834681e-07 -1.02008436731674e-06 2.73076257852792e-06 -9.67158731462802e-07 1.3460683623454e-05 3.34291759642595e-06 -1.23319046540393e-05 -2.26875547548297e-05 -1.16889243004589e-06 -8.43745649367329e-06 3.34291759642595e-06 7.44580184450188e-05 2381 2331 0 1625 487 2381 2331 0 1465 513 0 0 0 0 0 0 0 0 2116 0 0 0 0 0 3319 +796 798 0.998654023342377 0.0516429157834663 0.00481153940699211 0.303513665491937 -0.0514263698023019 0.997969002011252 -0.0375925459848481 -0.0373685242721099 -0.00674315586651532 0.0372945072905895 0.999281566714263 0.0376580798232512 9.25436984748035e-05 6.82896341180994e-05 -3.50782589220168e-06 4.88320081145609e-05 1.51868798481898e-07 -2.66848493318399e-05 6.82896341180994e-05 0.000140559363674392 -5.12778978837154e-07 0.00013170135517021 -7.2626059908919e-06 -9.80621167866363e-05 -3.50782589220168e-06 -5.12778978837154e-07 1.92103784414644e-05 -5.92722655587976e-06 2.85422976496644e-06 -5.0460557121493e-06 4.88320081145609e-05 0.00013170135517021 -5.92722655587976e-06 0.000252888879265644 -7.50033213949762e-06 -7.78536476162093e-05 1.51868798481898e-07 -7.2626059908919e-06 2.85422976496644e-06 -7.50033213949762e-06 1.26056077360744e-05 1.54162721260064e-05 -2.66848493318399e-05 -9.80621167866363e-05 -5.0460557121493e-06 -7.78536476162093e-05 1.54162721260064e-05 0.000228687437405884 2894 2825 0 760 131 2894 2825 0 623 146 0 0 0 0 0 0 0 0 3018 0 0 0 0 0 3708 +795 799 0.997835518469479 0.0653865893289489 0.00699085235671427 0.618487449514272 -0.0650133331435221 0.996893294991619 -0.0444637483161583 -0.0760230079287887 -0.0098764666918592 0.043913008740926 0.998986537981871 0.0575365115693785 7.22648895890892e-05 4.47731710354549e-05 -1.91220492119734e-06 1.20244064659065e-05 7.56572093331098e-07 -5.97931611628146e-05 4.47731710354549e-05 7.12343068599838e-05 -1.13323892061239e-06 3.13351777716756e-05 -3.38075595650262e-07 -5.99884794609021e-05 -1.91220492119734e-06 -1.13323892061239e-06 1.44261758659596e-05 -6.76475149261159e-06 3.18234932477151e-06 7.30819649754214e-07 1.20244064659065e-05 3.13351777716756e-05 -6.76475149261159e-06 0.000112224770937 2.79970409973912e-07 -3.63301654992011e-05 7.56572093331098e-07 -3.38075595650262e-07 3.18234932477151e-06 2.79970409973912e-07 1.16367426456144e-05 1.23428609327083e-05 -5.97931611628146e-05 -5.99884794609021e-05 7.30819649754214e-07 -3.63301654992011e-05 1.23428609327083e-05 0.000264893806581003 2741 2685 0 1736 451 2741 2685 0 1553 467 0 0 0 0 0 0 0 0 2047 0 0 0 0 0 3363 +797 799 0.998578346259033 0.0444202873311849 -0.0294639518053986 0.311384579490666 -0.0457883866310009 0.997820780359157 -0.0475090931630132 -0.0437125234698764 0.0272893758137824 0.0487906584999308 0.998436158004525 0.029253500948463 5.42685412985095e-05 1.07083573237269e-05 -5.57222860714585e-06 1.41141856105496e-05 8.79310869797968e-07 -1.86535150763393e-05 1.07083573237269e-05 4.29580461881561e-05 4.32293067752832e-06 3.47525950972613e-06 -1.72277890501025e-06 -3.92395982070656e-05 -5.57222860714585e-06 4.32293067752832e-06 1.59490503814799e-05 -2.19434059329272e-06 2.9890598364662e-06 -3.60455446303149e-06 1.41141856105496e-05 3.47525950972613e-06 -2.19434059329272e-06 6.7784895267321e-05 8.86240606825358e-07 -2.42820460467116e-06 8.79310869797968e-07 -1.72277890501025e-06 2.9890598364662e-06 8.86240606825358e-07 1.13426079543221e-05 3.37532005382442e-06 -1.86535150763393e-05 -3.92395982070656e-05 -3.60455446303149e-06 -2.42820460467116e-06 3.37532005382442e-06 9.90577150407795e-05 2917 2861 0 755 146 2917 2861 0 620 169 0 0 0 0 0 0 0 0 3047 0 0 0 0 0 3662 +796 799 0.997143413636831 0.0688096185738152 -0.0311488207226936 0.457346950974146 -0.0700917212957036 0.996650410665363 -0.0421320486846928 -0.0684178050182091 0.0281453947652872 0.0441949693097526 0.998626377300948 0.0449475440615302 4.94897197981923e-05 2.77241195548092e-05 -3.49235722215366e-06 3.54876836971371e-06 -1.54377676951895e-06 -2.79281463025097e-05 2.77241195548092e-05 8.10653241149644e-05 -2.3472123901445e-06 2.41984277293154e-05 -5.49031005402897e-06 -8.20899435659411e-05 -3.49235722215366e-06 -2.3472123901445e-06 1.46676159794933e-05 -3.66946595468527e-07 4.36428835376674e-06 4.88510588510067e-06 3.54876836971371e-06 2.41984277293154e-05 -3.66946595468527e-07 7.302610360355e-05 -3.35824684126607e-06 -4.39289388865517e-05 -1.54377676951895e-06 -5.49031005402897e-06 4.36428835376674e-06 -3.35824684126607e-06 1.17958410701536e-05 9.32458956716195e-06 -2.79281463025097e-05 -8.20899435659411e-05 4.88510588510067e-06 -4.39289388865517e-05 9.32458956716195e-06 0.000145535480782288 2992 2936 0 1257 225 2992 2936 0 1090 245 0 0 0 0 0 0 0 0 2531 0 0 0 0 0 3589 +799 801 0.998785253667901 -0.00160062661882392 0.0492489091247026 0.313419319950498 0.00268921755361393 0.999753350623275 -0.0220455443680857 -0.0377510953229536 -0.0492014752268205 0.0221512056548399 0.998543208340802 0.00762208510188431 6.18776378770312e-05 2.27967123848785e-07 -6.04325417848995e-06 -1.45978050959066e-05 2.13140350894864e-06 -5.15677580550319e-06 2.27967123848785e-07 4.27710144559501e-05 -1.31821516146874e-06 -2.01086743830782e-06 -1.68150717481163e-06 -3.15619278661417e-05 -6.04325417848995e-06 -1.31821516146874e-06 1.5094504590545e-05 3.49744237635194e-06 4.43997529770726e-06 1.39278569056368e-06 -1.45978050959066e-05 -2.01086743830782e-06 3.49744237635194e-06 6.51584430333501e-05 -1.11805407787659e-06 1.62323084817741e-05 2.13140350894864e-06 -1.68150717481163e-06 4.43997529770726e-06 -1.11805407787659e-06 1.33753993903741e-05 1.64684233129371e-05 -5.15677580550319e-06 -3.15619278661417e-05 1.39278569056368e-06 1.62323084817741e-05 1.64684233129371e-05 0.000189915147695614 2932 2882 0 576 280 2932 2882 0 463 308 0 0 0 0 0 0 0 0 3197 0 0 0 0 0 3518 +799 803 0.998316777048494 -0.0489918029715964 0.03103894175226 0.605331149820008 0.0486173425676337 0.998736649720432 0.0127066323968457 -0.0559392937551371 -0.0316222495273386 -0.0111762134374525 0.999437404537188 0.044727897653465 7.10715614673504e-05 1.45386941040364e-05 -1.35997945400216e-06 2.35844123104103e-06 3.18223562553493e-06 1.11592247575599e-05 1.45386941040364e-05 6.18136310783616e-05 2.39661340200345e-06 2.71595744814463e-06 -7.49264039548829e-07 -3.5898528163845e-05 -1.35997945400216e-06 2.39661340200345e-06 1.91332101003988e-05 -3.75126599669864e-06 4.02662221867444e-06 -7.54807893098062e-06 2.35844123104103e-06 2.71595744814463e-06 -3.75126599669864e-06 0.000134287405049969 -7.90939139261513e-06 4.22827894279491e-06 3.18223562553493e-06 -7.49264039548829e-07 4.02662221867444e-06 -7.90939139261513e-06 1.3635655148601e-05 1.39947100875416e-05 1.11592247575599e-05 -3.5898528163845e-05 -7.54807893098062e-06 4.22827894279491e-06 1.39947100875416e-05 0.000279308623238578 2589 2508 0 1192 674 2589 2508 0 1046 714 0 0 0 0 0 0 0 0 2565 0 0 0 0 0 2994 +798 800 0.999199984002744 0.0337274973367528 -0.0214906466239484 0.313798356465591 -0.0340727645373118 0.999292749138076 -0.0159074899607449 -0.045725229370931 0.0209389275203149 0.0166270094564725 0.999642488028012 0.0267953400457279 7.18068025688273e-05 2.75148001052593e-05 -3.62170325724727e-06 2.67090670539242e-05 1.42437917130809e-06 -4.11411949709111e-05 2.75148001052593e-05 0.000107874990087931 1.34090642945544e-07 4.70958574059279e-05 -4.28469950690427e-06 -9.87369800204342e-05 -3.62170325724727e-06 1.34090642945544e-07 1.82854077727397e-05 -1.25601308751861e-06 4.25853013794984e-06 1.71651397140451e-06 2.67090670539242e-05 4.70958574059279e-05 -1.25601308751861e-06 0.000138878391094334 -6.55850239976798e-06 -8.64918030080368e-05 1.42437917130809e-06 -4.28469950690427e-06 4.25853013794984e-06 -6.55850239976798e-06 1.29286507605739e-05 1.76397867253874e-05 -4.11411949709111e-05 -9.87369800204342e-05 1.71651397140451e-06 -8.64918030080368e-05 1.76397867253874e-05 0.000345420155130804 2457 2405 0 694 181 2457 2405 0 568 206 0 0 0 0 0 0 0 0 3088 0 0 0 0 0 3638 +800 803 0.997534782311435 -0.0639570753644557 0.0288764712127768 0.460849336986686 0.0632787623199466 0.997711497278123 0.0238236529168246 -0.02973549614921 -0.0303340784948662 -0.0219376550677358 0.999299045817615 0.0265119282105745 6.4857265087952e-05 2.73884858475498e-05 -2.31372471797725e-06 3.28219399156191e-05 -2.87286407234225e-06 -2.60074365347757e-05 2.73884858475498e-05 0.000134955333494409 8.34286544015048e-06 8.43672104426499e-05 -1.00465725982655e-05 -0.000160819238558058 -2.31372471797725e-06 8.34286544015048e-06 1.60069240501954e-05 4.62690355597619e-06 3.36108322205243e-06 -1.19459643332605e-05 3.28219399156191e-05 8.43672104426499e-05 4.62690355597619e-06 0.00019139641241196 -1.56293540238041e-05 -0.000114370589238909 -2.87286407234225e-06 -1.00465725982655e-05 3.36108322205243e-06 -1.56293540238041e-05 1.24772860376594e-05 2.47670554687303e-05 -2.60074365347757e-05 -0.000160819238558058 -1.19459643332605e-05 -0.000114370589238909 2.47670554687303e-05 0.00051954428163889 2209 2128 0 711 542 2209 2128 0 580 577 0 0 0 0 0 0 0 0 3065 0 0 0 0 0 3124 +798 802 0.999913873631068 0.00139032538222247 0.013050376065258 0.613517732738399 -0.000959945229300345 0.999457301935657 -0.0329268904188366 -0.0788118614368419 -0.0130890727429354 0.0329115268990801 0.999372556943556 0.0761671874034661 6.08543629545461e-05 2.05253834529365e-05 -3.05802823879302e-06 2.2137699770818e-05 1.41552135853524e-06 -1.40782816183281e-05 2.05253834529365e-05 4.43339196942927e-05 7.31247170032052e-06 4.48412893717592e-06 -1.19402626538088e-06 -3.89231802270778e-05 -3.05802823879302e-06 7.31247170032052e-06 1.58240412624209e-05 1.62544002798854e-06 2.90448359962726e-06 -8.57726265565681e-06 2.2137699770818e-05 4.48412893717592e-06 1.62544002798854e-06 8.27892601376748e-05 1.13860240627814e-07 8.74614019078125e-06 1.41552135853524e-06 -1.19402626538088e-06 2.90448359962726e-06 1.13860240627814e-07 1.26901395956015e-05 6.26241912358384e-06 -1.40782816183281e-05 -3.89231802270778e-05 -8.57726265565681e-06 8.74614019078125e-06 6.26241912358384e-06 0.000110465117909951 2370 2318 0 1438 612 2370 2318 0 1276 646 0 0 0 0 0 0 0 0 2333 0 0 0 0 0 3173 +802 805 0.995718768501565 -0.0871654003314319 -0.030762429013124 0.447896284152001 0.0888303785673372 0.99437396378902 0.0577025474489308 -0.00648859329530808 0.025559692825029 -0.0601881477001392 0.997859754163438 0.0382183186510086 5.02435843019178e-05 5.34362701100066e-06 4.50229443944679e-07 5.70627595455831e-07 -2.97063310826542e-07 -4.91792302373045e-06 5.34362701100066e-06 3.98988069021974e-05 1.9141676561666e-06 1.48907062972615e-06 -5.32465073917851e-07 -2.86272964380958e-05 4.50229443944679e-07 1.9141676561666e-06 1.73859741188661e-05 -5.53866228929782e-06 5.42465526793592e-06 -6.43426553340473e-07 5.70627595455831e-07 1.48907062972615e-06 -5.53866228929782e-06 0.00010146383538693 -6.01802109551044e-06 -1.74976888177527e-05 -2.97063310826542e-07 -5.32465073917851e-07 5.42465526793592e-06 -6.01802109551044e-06 1.24131763818442e-05 5.24290643562595e-06 -4.91792302373045e-06 -2.86272964380958e-05 -6.43426553340473e-07 -1.74976888177527e-05 5.24290643562595e-06 0.000136053959787456 3222 3084 0 576 239 3222 3084 0 453 272 0 0 0 0 0 0 0 0 3198 0 0 0 0 0 3075 +802 806 0.995434737329065 -0.0949739521963479 0.00946742429706862 0.597087491072792 0.0943002812561692 0.993963449888056 0.056072428533478 -0.00986838740230316 -0.01473569386294 -0.0549236623946404 0.998381816058134 0.00838269843198342 0.000111381477538815 3.22808765251322e-05 -1.92069474163334e-07 2.70738656340704e-05 -1.6728809480252e-06 -3.39807209548634e-05 3.22808765251322e-05 6.28750172526984e-05 2.79127748085663e-06 3.50061005236214e-05 -4.43403927545129e-06 -5.17933448214147e-05 -1.92069474163334e-07 2.79127748085663e-06 1.92216777825097e-05 -6.59492622747184e-06 5.06893439177212e-06 -4.89565463492123e-06 2.70738656340704e-05 3.50061005236214e-05 -6.59492622747184e-06 0.000140898249626964 -1.17031601641751e-05 -3.24875317871848e-05 -1.6728809480252e-06 -4.43403927545129e-06 5.06893439177212e-06 -1.17031601641751e-05 1.39580014249378e-05 4.96491254655009e-06 -3.39807209548634e-05 -5.17933448214147e-05 -4.89565463492123e-06 -3.24875317871848e-05 4.96491254655009e-06 0.000143302341486101 2776 2668 0 957 156 2776 2668 0 809 184 0 0 0 0 0 0 0 0 2800 0 0 0 0 0 2846 +800 804 0.995285039442801 -0.0969843371372877 0.00131476666480802 0.613398052583497 0.0967706989533061 0.99382787041819 0.0542364803811488 -0.0247701877812567 -0.0065667408530082 -0.0538535266262764 0.998527253300821 0.0539979652476047 6.55662792105791e-05 9.18386602672962e-06 -8.65554250634134e-06 -1.09149672887744e-06 1.15580009420896e-06 -1.93830229069341e-05 9.18386602672962e-06 8.72994839783789e-05 -1.1068524783703e-06 1.59568403316355e-05 -1.98112129647227e-06 -8.4614460906816e-05 -8.65554250634134e-06 -1.1068524783703e-06 1.84003091046453e-05 -6.46930155477585e-07 3.68845059742881e-06 1.98941623549568e-07 -1.09149672887744e-06 1.59568403316355e-05 -6.46930155477585e-07 9.17868427010513e-05 -7.95908723620712e-06 -3.19771087983506e-05 1.15580009420896e-06 -1.98112129647227e-06 3.68845059742881e-06 -7.95908723620712e-06 1.27983780204644e-05 3.57979154266304e-06 -1.93830229069341e-05 -8.4614460906816e-05 1.98941623549568e-07 -3.19771087983506e-05 3.57979154266304e-06 0.000128777565150632 2584 2498 0 1012 615 2584 2498 0 860 658 0 0 0 0 0 0 0 0 2749 0 0 0 0 0 2803 +801 805 0.993744608301739 -0.103292063766744 -0.0424547174531904 0.586700178478459 0.105197396528035 0.993414406263355 0.0454018192603479 -0.0121584329376186 0.0374854803216736 -0.0495839388434697 0.998066266223751 0.0421653298122299 4.07596637627963e-05 8.18574897851741e-06 -3.09149998620792e-06 -4.54644819652918e-06 -1.18394676869969e-06 -6.98856993552328e-06 8.18574897851741e-06 3.73943623078554e-05 3.32396499434064e-07 1.08353988412409e-05 -2.01289083290408e-06 -2.32809901317957e-05 -3.09149998620792e-06 3.32396499434064e-07 1.47547933162951e-05 -2.31612319115148e-06 4.18855883888273e-06 -1.26854034009288e-06 -4.54644819652918e-06 1.08353988412409e-05 -2.31612319115148e-06 9.38295411821774e-05 -8.61289528281757e-06 1.43860183938746e-05 -1.18394676869969e-06 -2.01289083290408e-06 4.18855883888273e-06 -8.61289528281757e-06 1.3218020614441e-05 1.3430929378757e-06 -6.98856993552328e-06 -2.32809901317957e-05 -1.26854034009288e-06 1.43860183938746e-05 1.3430929378757e-06 7.21442077264658e-05 3193 3054 0 898 435 3193 3054 0 754 476 0 0 0 0 0 0 0 0 2872 0 0 0 0 0 2828 +805 808 0.997310237438089 0.0511424227629027 0.0525046940294214 0.431140466349656 -0.051230804917678 0.998686782935285 0.00033796132559719 -0.0589622963855176 -0.0524184598082532 -0.00302691002695989 0.998620620099054 0.0711367929102829 9.21063935112686e-05 2.91245336175465e-05 1.77916857935275e-06 4.59847141398108e-06 1.92002997330043e-06 -2.41634885661595e-05 2.91245336175465e-05 6.65767880886556e-05 7.40750231616084e-07 4.17217956039505e-05 -2.43965028686073e-06 -4.10879601028781e-05 1.77916857935275e-06 7.40750231616084e-07 1.84058543346989e-05 1.40449263947448e-06 3.9984075625379e-06 -4.41717373206284e-06 4.59847141398108e-06 4.17217956039505e-05 1.40449263947448e-06 0.00014116844981683 -1.06557725010284e-05 -6.46380305045861e-05 1.92002997330043e-06 -2.43965028686073e-06 3.9984075625379e-06 -1.06557725010284e-05 1.29532334827964e-05 5.99215205311809e-06 -2.41634885661595e-05 -4.10879601028781e-05 -4.41717373206284e-06 -6.46380305045861e-05 5.99215205311809e-06 0.000230984783402622 2689 2604 0 1076 1 2689 2604 0 931 1 0 0 0 0 0 0 0 0 2725 0 13 13 0 0 2662 +803 807 0.998926091293831 -0.0432053992921485 0.0167319336728972 0.589297650442976 0.0426899199593866 0.998637000032984 0.0300285347458507 -0.0223719821023256 -0.0180065228817055 -0.0292820019316919 0.999408990101942 0.0770918616236287 6.71808541242343e-05 1.0310450417742e-05 -3.35650679506241e-06 1.0251952710344e-05 -2.3235122975643e-06 5.54154099715128e-06 1.0310450417742e-05 3.64557995079338e-05 1.37300790356443e-06 1.30203771516757e-05 -2.29463913134528e-06 -2.90112657922838e-05 -3.35650679506241e-06 1.37300790356443e-06 1.63821309000709e-05 6.55879040631376e-07 3.83360039981945e-06 -2.50888242409568e-06 1.0251952710344e-05 1.30203771516757e-05 6.55879040631376e-07 7.87273317581042e-05 -2.62984331245162e-06 -7.95852567587027e-06 -2.3235122975643e-06 -2.29463913134528e-06 3.83360039981945e-06 -2.62984331245162e-06 1.31279166935487e-05 2.66280050501552e-06 5.54154099715128e-06 -2.90112657922838e-05 -2.50888242409568e-06 -7.95852567587027e-06 2.66280050501552e-06 0.000163492125270245 3011 2867 0 1128 266 3011 2867 0 975 235 0 0 0 0 0 0 0 0 2663 0 0 0 0 0 2909 +805 809 0.997069503696482 0.0744021683955881 0.017796688919168 0.583785943748584 -0.0737582383574597 0.996680887410837 -0.0344518641636601 -0.0921154737429943 -0.0203009131039775 0.0330382506798056 0.999247890625326 0.0340843982310889 8.03927380445803e-05 2.58960855524579e-05 -7.54233363937444e-07 1.87649705098081e-05 4.67822238654953e-08 -2.48806924609485e-05 2.58960855524579e-05 5.35268998457976e-05 1.99375621873284e-06 1.02467014620949e-05 -4.1382009464762e-07 -4.04772269811594e-05 -7.54233363937444e-07 1.99375621873284e-06 1.41893307693009e-05 1.9824669040586e-06 5.18789204860425e-06 -3.52459345789352e-06 1.87649705098081e-05 1.02467014620949e-05 1.9824669040586e-06 7.12807126032612e-05 -1.63301101776099e-06 -1.95255620819206e-05 4.67822238654953e-08 -4.1382009464762e-07 5.18789204860425e-06 -1.63301101776099e-06 1.24515954101088e-05 1.38076642732724e-05 -2.48806924609485e-05 -4.04772269811594e-05 -3.52459345789352e-06 -1.95255620819206e-05 1.38076642732724e-05 0.000225289660946002 2622 2543 0 1595 10 2605 2526 0 1433 0 0 0 0 0 0 0 0 0 2197 0 79 55 0 0 2645 +803 806 0.997883496666835 -0.0630943371776329 0.0157363177422644 0.447087950261507 0.0626685709069385 0.997689844924806 0.0262225771883335 -0.0128933300160747 -0.0173544605347545 -0.025180904472065 0.999532262985801 0.0135043343317124 5.76992394323201e-05 -6.02818287083791e-06 7.48635578703504e-07 -1.02089371995646e-05 4.20328613473376e-06 3.02664633888565e-05 -6.02818287083791e-06 5.19053235461112e-05 4.24559445368551e-06 2.33614516154101e-05 -3.03188301934684e-06 -5.5222458422436e-05 7.48635578703504e-07 4.24559445368551e-06 1.173677970604e-05 3.13638544282104e-07 5.13294301882111e-06 -7.68482204024194e-07 -1.02089371995646e-05 2.33614516154101e-05 3.13638544282104e-07 7.20330159880789e-05 -4.4220567390375e-06 -4.0212487780052e-05 4.20328613473376e-06 -3.03188301934684e-06 5.13294301882111e-06 -4.4220567390375e-06 1.21147374950607e-05 8.65464520067643e-06 3.02664633888565e-05 -5.5222458422436e-05 -7.68482204024194e-07 -4.0212487780052e-05 8.65464520067643e-06 0.00023947184625593 3212 3047 0 684 342 3212 3047 0 564 294 0 0 0 0 0 0 0 0 3094 0 0 0 0 0 3107 +805 807 0.999207373454485 0.0139457529106196 0.037284592125232 0.29134674377033 -0.014159651091595 0.999884735772384 0.00547900085366628 -0.0327181071578903 -0.0372038857534164 -0.00600259486773248 0.99928966758378 0.0773571575248268 7.58997070481953e-05 2.25702926455246e-05 -2.09897959550055e-06 2.16242727586177e-05 1.02268442391548e-06 -3.61185392710722e-05 2.25702926455246e-05 0.000105766880766093 1.32172419551057e-06 5.52519732125474e-05 -5.73737648034597e-06 -0.000106622030406738 -2.09897959550055e-06 1.32172419551057e-06 1.4601334730694e-05 -2.62918963059376e-06 5.42167643760355e-06 2.7723577750178e-06 2.16242727586177e-05 5.52519732125474e-05 -2.62918963059376e-06 0.000126938998285527 -1.00032114870635e-05 -8.91600014981341e-05 1.02268442391548e-06 -5.73737648034597e-06 5.42167643760355e-06 -1.00032114870635e-05 1.23204162680822e-05 7.54535467627952e-06 -3.61185392710722e-05 -0.000106622030406738 2.7723577750178e-06 -8.91600014981341e-05 7.54535467627952e-06 0.000204055823972259 3164 3047 0 590 75 3143 3047 0 462 48 0 0 0 0 0 0 0 0 3214 0 55 28 0 0 2967 +804 807 0.999028128370072 -0.0102077871108245 0.0428788969971338 0.436175820581821 0.0101831398328366 0.999947835888618 0.000793199101028209 -0.0307161397974727 -0.0428847570651347 -0.000355786409325424 0.999079962279044 0.0863693877058581 8.30199966236481e-05 3.89520244746956e-05 -4.0577800812402e-06 2.15030047728371e-05 -1.95329402883512e-06 -2.48199143658897e-05 3.89520244746956e-05 0.000131670583787739 -1.18100320732175e-06 9.36465647797264e-05 -1.27475434230094e-05 -0.000117863367655424 -4.0577800812402e-06 -1.18100320732175e-06 1.48985649762114e-05 -4.827531717815e-06 5.35845200962386e-06 -1.79794976986831e-06 2.15030047728371e-05 9.36465647797264e-05 -4.827531717815e-06 0.000227043350625785 -2.39554503878092e-05 -0.000100831635649675 -1.95329402883512e-06 -1.27475434230094e-05 5.35845200962386e-06 -2.39554503878092e-05 1.4742496372436e-05 1.74757751082776e-05 -2.48199143658897e-05 -0.000117863367655424 -1.79794976986831e-06 -0.000100831635649675 1.74757751082776e-05 0.000388620493798887 2718 2603 0 849 82 2718 2603 0 722 54 0 0 0 0 0 0 0 0 2944 0 19 0 0 0 2939 +806 808 0.998128959785713 0.059407747328014 0.0144671764522871 0.284808285744994 -0.0595022479211638 0.998208971323234 0.00619128921464427 -0.0478845327985653 -0.014073454779091 -0.0070405345835286 0.999876176705575 0.057602703407547 2.73320430258002e-05 7.92619638488554e-06 6.24174266180544e-07 -4.58988274678781e-06 -2.1909643618067e-07 -5.66410800122553e-06 7.92619638488554e-06 2.46613325230167e-05 5.07878592570333e-07 7.12529603172653e-06 -4.41893613747719e-07 -1.53255352142781e-05 6.24174266180544e-07 5.07878592570333e-07 1.12370849178004e-05 -8.92730363699327e-07 5.53536994871254e-06 7.03079746584024e-07 -4.58988274678781e-06 7.12529603172653e-06 -8.92730363699327e-07 6.4410606780033e-05 -1.45625579622987e-06 -2.33515270610927e-05 -2.1909643618067e-07 -4.41893613747719e-07 5.53536994871254e-06 -1.45625579622987e-06 1.08558564217828e-05 2.76699515492499e-06 -5.66410800122553e-06 -1.53255352142781e-05 7.03079746584024e-07 -2.33515270610927e-05 2.76699515492499e-06 9.31359785663436e-05 3449 3364 0 732 21 3389 3304 0 604 0 0 0 0 0 0 0 0 0 3093 0 218 150 0 0 3369 +807 810 0.993287837772972 0.0909564381538741 -0.0714576636243801 0.425339869032991 -0.093282815551038 0.995190102170035 -0.0299161639530514 -0.0909418145483618 0.0683928918467819 0.0363811338629693 0.996994897401024 0.0247071013587178 6.55247136078071e-05 2.39739285809897e-05 4.77889521458983e-06 7.14486867633521e-06 5.53757962828471e-07 4.92155254188673e-07 2.39739285809897e-05 6.91766993419659e-05 2.82796123492522e-06 5.85666136218406e-06 5.3163269247159e-06 6.9280439995502e-05 4.77889521458983e-06 2.82796123492522e-06 1.26792964334381e-05 1.34242302517277e-06 6.12248404550666e-06 -2.85310589180877e-07 7.14486867633521e-06 5.85666136218406e-06 1.34242302517277e-06 8.39881190459796e-05 -4.84818534904122e-06 -5.16241628663456e-05 5.53757962828471e-07 5.3163269247159e-06 6.12248404550666e-06 -4.84818534904122e-06 1.61799630660357e-05 6.74093973622739e-05 4.92155254188673e-07 6.9280439995502e-05 -2.85310589180877e-07 -5.16241628663456e-05 6.74093973622739e-05 0.00128631156343502 2551 2478 0 1185 1 2495 2422 0 1042 0 0 0 0 0 0 0 0 0 2627 0 244 186 0 0 2897 +806 809 0.996282241277853 0.0818746380466833 -0.0267999880429466 0.433361186939892 -0.0824416445221205 0.996379183594173 -0.0207821497612234 -0.0824033303908814 0.0250014192170326 0.0229143218301174 0.999424765999022 0.0142831316465595 3.93959551692988e-05 6.98143508896558e-06 -1.10205056605983e-06 9.62886207854691e-06 -3.30086437106202e-06 -2.77866220560117e-05 6.98143508896558e-06 4.78602814800774e-05 -1.92322678764869e-07 1.52071605532666e-05 -3.27936927359276e-06 -2.09342744123483e-05 -1.10205056605983e-06 -1.92322678764869e-07 9.90830312982217e-06 1.12681267192581e-06 5.08638964476239e-06 -2.2029849297011e-06 9.62886207854691e-06 1.52071605532666e-05 1.12681267192581e-06 8.62970004267956e-05 -3.58621725971238e-06 -1.72603240619956e-05 -3.30086437106202e-06 -3.27936927359276e-06 5.08638964476239e-06 -3.58621725971238e-06 1.14136964676258e-05 6.68625253559772e-06 -2.77866220560117e-05 -2.09342744123483e-05 -2.2029849297011e-06 -1.72603240619956e-05 6.68625253559772e-06 0.00011102520275523 2880 2801 0 1199 7 2822 2743 0 1052 0 0 0 0 0 0 0 0 0 2605 0 239 171 0 0 3135 +807 809 0.997568190522554 0.059959175540651 -0.0355331187210398 0.287345355011801 -0.0615056015546447 0.997129579706707 -0.0441549799153748 -0.0536299620929503 0.0327836275442391 0.0462330892587903 0.998392575704882 0.042902161565665 5.96292084822154e-05 2.54278531884363e-05 -1.39509053095221e-06 3.14813516007553e-05 -5.93142102266011e-06 -3.6099845021749e-05 2.54278531884363e-05 9.54220153082721e-05 -1.30146259632922e-06 7.37174390461844e-05 -1.16903781148678e-05 -7.53932966644762e-05 -1.39509053095221e-06 -1.30146259632922e-06 1.04564229876259e-05 -1.39653200378184e-06 5.9508905098751e-06 2.17289524155766e-06 3.14813516007553e-05 7.37174390461844e-05 -1.39653200378184e-06 0.000167042122606213 -1.94198871716699e-05 -0.000116155885495617 -5.93142102266011e-06 -1.16903781148678e-05 5.9508905098751e-06 -1.94198871716699e-05 1.4726990528513e-05 3.21300159510943e-05 -3.6099845021749e-05 -7.53932966644762e-05 2.17289524155766e-06 -0.000116155885495617 3.21300159510943e-05 0.000388119429084158 2503 2423 0 744 29 2447 2368 0 612 0 0 0 0 0 0 0 0 0 3077 0 204 141 0 0 3291 +808 812 0.997052582828687 0.0743368752127097 -0.0189783049362537 0.573643390379698 -0.07440963015187 0.997222767798895 -0.00315568125346736 -0.107358991072874 0.0186910142931122 0.00455854879556975 0.999814915680684 0.0655970490939687 3.25389337892241e-05 -2.24018429673654e-06 1.98340298162691e-06 -1.29960327394451e-05 3.03479036218332e-07 9.27246216788403e-06 -2.24018429673654e-06 4.73909309234274e-05 2.50416161289076e-07 1.7417158039326e-05 1.58646985045658e-07 -3.58769912173841e-05 1.98340298162691e-06 2.50416161289076e-07 1.09189985189111e-05 3.40624341709281e-07 5.69950479038817e-06 1.2387613403668e-06 -1.29960327394451e-05 1.7417158039326e-05 3.40624341709281e-07 6.85050399383689e-05 -4.57804100041827e-07 -3.47180647263557e-05 3.03479036218332e-07 1.58646985045658e-07 5.69950479038817e-06 -4.57804100041827e-07 1.11173757649768e-05 2.86977768978853e-06 9.27246216788403e-06 -3.58769912173841e-05 1.2387613403668e-06 -3.47180647263557e-05 2.86977768978853e-06 0.000179830991256225 2548 2483 0 1484 19 2501 2436 0 1347 0 0 0 0 0 0 0 0 0 2288 0 140 98 0 0 2729 +808 811 0.996272845446265 0.0772906980102254 -0.0382957625266054 0.421268659491085 -0.0781332460013093 0.996721435551166 -0.0210137046263255 -0.0840008243658362 0.0365460435026953 0.0239275555357356 0.999045473835092 0.0474090993649716 4.44056566733779e-05 4.46089020670433e-06 -6.51883329496505e-06 4.25203981552787e-06 4.59160915385572e-07 -1.73674001518445e-05 4.46089020670433e-06 3.81272538816314e-05 -2.1911388133819e-06 5.12120861181362e-06 -1.83847289444207e-06 -5.51418941611833e-06 -6.51883329496505e-06 -2.1911388133819e-06 1.39707006881424e-05 2.62799815361117e-06 4.57091350338242e-06 -1.05537565983443e-06 4.25203981552787e-06 5.12120861181362e-06 2.62799815361117e-06 8.06915055250581e-05 5.75183292754026e-06 9.8752779297599e-06 4.59160915385572e-07 -1.83847289444207e-06 4.57091350338242e-06 5.75183292754026e-06 1.31493660250584e-05 9.21013431724906e-06 -1.73674001518445e-05 -5.51418941611833e-06 -1.05537565983443e-06 9.8752779297599e-06 9.21013431724906e-06 0.000214630622513761 2749 2689 0 1090 0 2749 2689 0 968 0 0 0 0 0 0 0 0 0 2719 0 5 5 0 0 2588 +809 812 0.998415047003206 0.0508374842534436 0.0241442355929348 0.43180342031175 -0.0515635358364445 0.998204893239541 0.0304662581338862 -0.0723869034317181 -0.0225520661942531 -0.0316629327039957 0.999244145843723 0.029874183703125 3.40632385630001e-05 3.68246144336959e-06 -1.52613839239219e-06 7.72941431883642e-06 9.37876097823781e-07 -6.14980258386085e-07 3.68246144336959e-06 4.42375949663373e-05 1.07287426237897e-06 1.35732212863131e-05 -2.17155745317316e-06 -3.22785782829443e-05 -1.52613839239219e-06 1.07287426237897e-06 9.91346032338375e-06 2.26143193280409e-07 5.17907990088373e-06 3.93757342224994e-07 7.72941431883642e-06 1.35732212863131e-05 2.26143193280409e-07 5.83097888152809e-05 9.86187117351623e-07 -2.14249040098285e-05 9.37876097823781e-07 -2.17155745317316e-06 5.17907990088373e-06 9.86187117351623e-07 1.16775586810115e-05 5.65464550113964e-06 -6.14980258386085e-07 -3.22785782829443e-05 3.93757342224994e-07 -2.14249040098285e-05 5.65464550113964e-06 0.000220185272045151 3013 2930 0 993 74 2934 2869 0 869 0 0 0 0 0 0 0 0 0 2792 0 159 107 0 0 2846 +812 838 0.999305930312831 0.0350262376921745 -0.0126814949725494 3.73645169544627 -0.0347455332200068 0.99916020488407 0.0217171107028832 -0.053299051770911 0.0134315137964752 -0.0212614122098034 0.999683723378539 0.487624898961029 5.40849814096017e-05 5.80922098473338e-06 -9.890785091454e-08 1.67461978278884e-05 -1.19134058994121e-05 -3.7041460726503e-05 5.80922098473338e-06 8.63033884636759e-05 3.54867470441932e-06 -9.15347083597684e-06 3.63613325967445e-06 -3.24578202948157e-05 -9.890785091454e-08 3.54867470441932e-06 1.50517882023585e-05 -3.50772307103275e-06 -5.55444611542867e-07 -1.31480191150639e-06 1.67461978278884e-05 -9.15347083597684e-06 -3.50772307103275e-06 9.83049233080574e-05 2.03273751604091e-05 -1.91668201638152e-05 -1.19134058994121e-05 3.63613325967445e-06 -5.55444611542867e-07 2.03273751604091e-05 5.11404276426302e-05 -3.60687585620797e-06 -3.7041460726503e-05 -3.24578202948157e-05 -1.31480191150639e-06 -1.91668201638152e-05 -3.60687585620797e-06 0.00013874821427666 2982 2914 0 3683 629 2982 2914 0 3683 590 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1441 +810 812 0.997815960491807 0.0194125372398354 0.0631384382585107 0.292852356792249 -0.0205271149394069 0.999643863924162 0.0170523567589851 -0.0340837489566491 -0.062784922872264 -0.0183111637173428 0.997859085614417 0.0207062307106758 7.16191926866313e-05 2.82400908193924e-06 -2.17941554698686e-06 2.94408920175399e-05 2.99612623242503e-06 -1.89609179066384e-05 2.82400908193924e-06 3.72886421184427e-05 -1.67932227676628e-07 4.90513580918774e-06 -3.50076348146546e-07 -2.84665261797977e-05 -2.17941554698686e-06 -1.67932227676628e-07 1.34295924001188e-05 -1.3315022874796e-06 6.93323844148901e-06 -2.01503060528878e-07 2.94408920175399e-05 4.90513580918774e-06 -1.3315022874796e-06 8.01131238187573e-05 2.16034044135555e-06 -1.63172021312771e-05 2.99612623242503e-06 -3.50076348146546e-07 6.93323844148901e-06 2.16034044135555e-06 1.21132855117245e-05 2.24965374327612e-06 -1.89609179066384e-05 -2.84665261797977e-05 -2.01503060528878e-07 -1.63172021312771e-05 2.24965374327612e-06 0.000170812084972412 2943 2843 0 535 84 2908 2841 0 434 39 0 0 0 0 0 0 0 0 3256 0 78 42 0 0 1845 +811 814 0.998532416864253 -0.0529871378003236 0.0111971290500703 0.4494547677783 0.0526373475159284 0.998177463987234 0.0295137262049746 -0.00627723577503403 -0.012740569756561 -0.0288810251851338 0.999501657960873 0.0510231721910002 2.51539026789185e-05 -6.49797067412875e-06 -3.83867594275313e-06 -2.99142372639373e-06 3.1808913682067e-07 2.41667068569989e-05 -6.49797067412875e-06 6.82551403960937e-05 4.19009429755467e-07 2.06967494673433e-05 -8.07989588801403e-07 -8.42697521693202e-05 -3.83867594275313e-06 4.19009429755467e-07 1.29680068527463e-05 1.28751370580659e-06 3.45746928902568e-06 -5.08801072720408e-06 -2.99142372639373e-06 2.06967494673433e-05 1.28751370580659e-06 7.97251971785209e-05 -1.43725378566999e-06 -4.93341445445595e-05 3.1808913682067e-07 -8.07989588801403e-07 3.45746928902568e-06 -1.43725378566999e-06 1.23738856772425e-05 8.30704578641185e-06 2.41667068569989e-05 -8.42697521693202e-05 -5.08801072720408e-06 -4.93341445445595e-05 8.30704578641185e-06 0.000420662262267259 2667 2574 0 593 117 2667 2574 0 492 87 0 0 0 0 0 0 0 0 3178 0 0 0 0 0 2527 +810 814 0.998646970615182 -0.0302407215869377 0.0423051632666782 0.584890093633854 0.0287268254901158 0.998940740640501 0.0359467131441471 -0.0386897534017469 -0.0433474056706906 -0.0346827831424827 0.998457864396446 0.00372384927442158 6.17400096422252e-05 1.58215096486759e-05 -2.05006113955497e-07 2.58525755304282e-05 1.31553575486474e-06 -1.98094029280975e-05 1.58215096486759e-05 3.76784947420498e-05 1.175500696197e-06 1.49519889659103e-05 -1.2656291532263e-06 -3.47060344615305e-05 -2.05006113955497e-07 1.175500696197e-06 1.165191496995e-05 2.7020095675173e-06 4.78243274593829e-06 -8.82990995329545e-07 2.58525755304282e-05 1.49519889659103e-05 2.7020095675173e-06 8.22654724018653e-05 -2.83171385536254e-06 -1.65860582112866e-05 1.31553575486474e-06 -1.2656291532263e-06 4.78243274593829e-06 -2.83171385536254e-06 1.10236929128704e-05 4.76551310671539e-07 -1.98094029280975e-05 -3.47060344615305e-05 -8.82990995329545e-07 -1.65860582112866e-05 4.76551310671539e-07 7.77138445895821e-05 2706 2618 0 1048 56 2706 2618 0 921 32 0 0 0 0 0 0 0 0 2703 0 0 0 0 0 1395 +810 813 0.99866555058921 0.00766035882710465 0.0510728594166271 0.438842870860204 -0.00858243518166183 0.999803673654157 0.0178593380057605 -0.0380705131618096 -0.0509260235312274 -0.0182738351281669 0.998535230764045 0.05045652732333 5.92638596513029e-05 1.2733065347762e-05 1.10782987982321e-06 1.22208866595407e-05 1.88290985933928e-06 -9.91457926343935e-06 1.2733065347762e-05 3.41934685097063e-05 1.1320106335941e-06 1.1688436647363e-05 -1.12537282938876e-06 -3.12145859318143e-05 1.10782987982321e-06 1.1320106335941e-06 1.13830349193089e-05 -4.93633754110979e-08 5.46708650832004e-06 -3.11438359478874e-06 1.22208866595407e-05 1.1688436647363e-05 -4.93633754110979e-08 7.14333861986382e-05 -7.77285951185964e-07 -1.71467941518194e-05 1.88290985933928e-06 -1.12537282938876e-06 5.46708650832004e-06 -7.77285951185964e-07 1.1338141361559e-05 3.27073619196175e-06 -9.91457926343935e-06 -3.12145859318143e-05 -3.11438359478874e-06 -1.71467941518194e-05 3.27073619196175e-06 0.00011313261658179 2740 2675 0 804 7 2740 2675 0 689 1 0 0 0 0 0 0 0 0 2969 0 0 0 0 0 1978 +811 813 0.999804268741737 -0.0153710334364334 0.0124561445438561 0.30156311449807 0.0152508586910232 0.99983678243284 0.00968606233368344 -0.0107082789449886 -0.0126029962702459 -0.00949419956824194 0.99987550458023 0.0694028305931108 3.57673338431818e-05 -2.11898617153603e-05 -1.83246423686825e-06 -9.94746836625579e-06 7.30280289598205e-07 9.67928274158168e-06 -2.11898617153603e-05 0.000191049831480263 -3.76153545744923e-07 5.69204068672628e-05 -9.47296852658793e-06 -0.00010390595858137 -1.83246423686825e-06 -3.76153545744923e-07 1.3309864005595e-05 -2.00657616101154e-07 4.24617378870389e-06 -1.51095385169399e-06 -9.94746836625579e-06 5.69204068672628e-05 -2.00657616101154e-07 0.000114492259100666 -3.66021072727156e-06 -3.92129634026638e-05 7.30280289598205e-07 -9.47296852658793e-06 4.24617378870389e-06 -3.66021072727156e-06 1.32581808105521e-05 9.74117145987963e-06 9.67928274158168e-06 -0.00010390595858137 -1.51095385169399e-06 -3.92129634026638e-05 9.74117145987963e-06 0.000174862316325701 2364 2281 0 399 91 2364 2281 0 306 50 0 0 0 0 0 0 0 0 3392 0 11 0 0 0 2964 +813 839 0.994844153501635 0.101269271124453 -0.00544471941770895 3.72366331692928 -0.101226917312602 0.994834626378647 0.00756157188990092 -0.0946752439799995 0.00618235028149847 -0.0069714334236635 0.999956587888202 0.444433974795278 3.55137154997069e-05 -5.92967251234828e-06 2.06960250587509e-06 8.06337970593831e-06 -5.75887701287278e-06 -2.22150668564118e-05 -5.92967251234828e-06 0.000119811155698638 4.31386915558444e-07 1.21645391131861e-05 -3.99412720302909e-06 -1.38137617170249e-05 2.06960250587509e-06 4.31386915558444e-07 1.40980379044702e-05 3.43833488556367e-06 5.26140322126036e-06 3.24273021260879e-06 8.06337970593831e-06 1.21645391131861e-05 3.43833488556367e-06 8.03468671619745e-05 -1.6653839901022e-05 -2.83786433761442e-07 -5.75887701287278e-06 -3.99412720302909e-06 5.26140322126036e-06 -1.6653839901022e-05 4.03680241018031e-05 -1.20208108568216e-05 -2.22150668564118e-05 -1.38137617170249e-05 3.24273021260879e-06 -2.83786433761442e-07 -1.20208108568216e-05 0.000108977384488094 2868 2804 0 3899 442 2868 2804 0 3899 398 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1778 +812 815 0.995916917280174 -0.0835857809912451 -0.0341014822440059 0.44743166222471 0.0842316031898743 0.996284328119938 0.0179603609837591 0.0107062100533426 0.0324735415256513 -0.0207594498647482 0.999256981132529 0.00313516390315593 7.7465249821507e-05 -2.26437595109061e-07 -2.22586416410992e-06 2.53420674971186e-05 -2.66707361762872e-06 -1.48074833041491e-05 -2.26437595109061e-07 4.92103544221793e-05 1.81212751541535e-06 1.1275324210117e-06 1.02329560285829e-07 -2.50416238460444e-05 -2.22586416410992e-06 1.81212751541535e-06 1.17385480048337e-05 -3.58141461256889e-06 4.91595276469062e-06 -2.59635400602672e-06 2.53420674971186e-05 1.1275324210117e-06 -3.58141461256889e-06 8.05914333405957e-05 -2.73042497531807e-06 2.75397769461807e-06 -2.66707361762872e-06 1.02329560285829e-07 4.91595276469062e-06 -2.73042497531807e-06 1.27181627700232e-05 -1.22336395140914e-06 -1.48074833041491e-05 -2.50416238460444e-05 -2.59635400602672e-06 2.75397769461807e-06 -1.22336395140914e-06 9.39693976702381e-05 3112 3001 0 458 312 3112 3001 0 385 243 0 0 0 0 0 0 0 0 3314 0 0 0 0 0 1895 +812 814 0.998682161147187 -0.0477341295117327 -0.018851893436497 0.293094214257751 0.0479236206148212 0.998803603143377 0.0097308239617522 0.0023184586599326 0.018364846679202 -0.0106214512927872 0.999774933261924 0.0305471465575603 2.80260796243369e-05 -1.74857326540846e-05 -3.05812383077745e-06 -3.06559531590346e-06 -3.74967787182412e-07 2.99329305134991e-05 -1.74857326540846e-05 6.17588875388488e-05 2.25945943782651e-06 8.69290446117238e-06 -1.02629768185117e-06 -5.9603151619743e-05 -3.05812383077745e-06 2.25945943782651e-06 8.69788151042153e-06 4.68381922332116e-07 5.08148382561318e-06 -2.17897331609258e-06 -3.06559531590346e-06 8.69290446117238e-06 4.68381922332116e-07 4.86606244604417e-05 1.28935911476396e-07 -1.46325074515296e-05 -3.74967787182412e-07 -1.02629768185117e-06 5.08148382561318e-06 1.28935911476396e-07 1.08321396167098e-05 1.13159115807403e-06 2.99329305134991e-05 -5.9603151619743e-05 -2.17897331609258e-06 -1.46325074515296e-05 1.13159115807403e-06 0.000178536054982725 3128 2992 0 273 284 3128 2992 0 195 211 0 0 0 0 0 0 0 0 3511 0 0 0 0 0 3085 +813 815 0.997209467434192 -0.0725443112566479 -0.0176238748268777 0.297760933348156 0.0730128832963023 0.996949487545328 0.0275832948697097 0.0101090046038733 0.0155691018487066 -0.028793092703067 0.999464136865459 0.00962383139394146 5.81357052995994e-05 -6.87842204393525e-06 5.97763140765659e-07 1.67591187130628e-06 -1.16897169250925e-06 -6.40064622483575e-07 -6.87842204393525e-06 6.6736823706513e-05 3.16611078682477e-06 7.37200083524042e-06 -2.99005458050456e-06 -4.52914417657073e-05 5.97763140765659e-07 3.16611078682477e-06 1.16852317427048e-05 -3.09293259289958e-06 6.52972719824531e-06 -4.43345118468021e-06 1.67591187130628e-06 7.37200083524042e-06 -3.09293259289958e-06 6.63600418248632e-05 -1.96406505117563e-06 -1.5541759045389e-06 -1.16897169250925e-06 -2.99005458050456e-06 6.52972719824531e-06 -1.96406505117563e-06 1.26167907501977e-05 3.97756013248114e-06 -6.40064622483575e-07 -4.52914417657073e-05 -4.43345118468021e-06 -1.5541759045389e-06 3.97756013248114e-06 0.000201113902135726 3096 2981 0 231 267 3096 2981 0 132 207 0 0 0 0 0 0 0 0 3549 0 0 0 0 0 2249 +814 840 0.984251479883361 0.169362976888006 -0.0506478667571114 3.69533280345711 -0.17124935455218 0.984586571936768 -0.0355378801740479 -0.247280512500268 0.0438484083277285 0.0436516256448243 0.998084090979156 0.442073765042263 3.92242511986526e-05 -4.34750578078577e-07 -1.22976188247678e-06 1.54576275634093e-05 -1.09994378136127e-05 -1.58785136632011e-05 -4.34750578078577e-07 9.06460101849206e-05 -3.17617559572893e-06 2.73650562843526e-05 -9.05628211697671e-07 -4.74063583403903e-05 -1.22976188247678e-06 -3.17617559572893e-06 1.45087322624594e-05 -1.92063018590907e-06 4.88251623912462e-06 1.51731199000998e-06 1.54576275634093e-05 2.73650562843526e-05 -1.92063018590907e-06 8.61497169417976e-05 2.96781890347953e-07 -1.99565298507569e-05 -1.09994378136127e-05 -9.05628211697671e-07 4.88251623912462e-06 2.96781890347953e-07 4.53724070853643e-05 -2.94717086291038e-06 -1.58785136632011e-05 -4.74063583403903e-05 1.51731199000998e-06 -1.99565298507569e-05 -2.94717086291038e-06 0.000121536389886228 2944 2893 0 3881 390 2944 2893 0 3881 331 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2050 +816 842 0.955671652843011 0.277270316992261 -0.0990598973718307 3.62212698299241 -0.279549052939922 0.960083052811624 -0.0096363221358302 -0.476578452639465 0.0924338625867122 0.0369012603974977 0.995034812470587 0.487787909538309 4.31136762377013e-05 3.09280415216443e-05 -4.2870131460619e-06 2.34709530861883e-05 -1.68472024163218e-05 -2.33163575356362e-05 3.09280415216443e-05 0.000206598938254378 1.45718665815366e-06 2.4807465917457e-05 -1.18272396063165e-05 -7.97777157764941e-05 -4.2870131460619e-06 1.45718665815366e-06 1.62617303169645e-05 -4.94460157901061e-06 1.11049425779045e-05 -3.46256110352824e-06 2.34709530861883e-05 2.4807465917457e-05 -4.94460157901061e-06 9.37816045780113e-05 -1.24012384772469e-05 -1.06460912242397e-05 -1.68472024163218e-05 -1.18272396063165e-05 1.11049425779045e-05 -1.24012384772469e-05 4.5159232076915e-05 8.38234375911254e-06 -2.33163575356362e-05 -7.97777157764941e-05 -3.46256110352824e-06 -1.06460912242397e-05 8.38234375911254e-06 0.000104706567917023 2802 2773 0 3879 265 2802 2773 0 3879 265 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2139 +814 818 0.998760448587467 -0.0107606660210636 0.0485980905401091 0.57890823872028 0.00890655256302959 0.999230088712874 0.0382086787563233 -0.0150780881768451 -0.0489718251528724 -0.0377284756867415 0.998087332082494 0.0527660138372091 4.73782315691801e-05 9.70267198475447e-06 1.10239251246995e-06 1.46466789337365e-05 -8.28864979342222e-07 -1.09195198363749e-05 9.70267198475447e-06 6.10768889247506e-05 4.61797708319474e-06 1.26825361049153e-05 -1.78942473486481e-06 -4.83628537700891e-05 1.10239251246995e-06 4.61797708319474e-06 1.34718325753802e-05 7.38090224997501e-07 5.31674737752297e-06 -5.52160559297334e-06 1.46466789337365e-05 1.26825361049153e-05 7.38090224997501e-07 6.87774705191819e-05 4.42396278822594e-07 -3.0041100821031e-05 -8.28864979342222e-07 -1.78942473486481e-06 5.31674737752297e-06 4.42396278822594e-07 1.49402399641391e-05 -2.3008781257595e-06 -1.09195198363749e-05 -4.83628537700891e-05 -5.52160559297334e-06 -3.0041100821031e-05 -2.3008781257595e-06 0.00016974437491072 2565 2526 0 1076 138 2565 2526 0 946 96 0 0 0 0 0 0 0 0 2721 0 7 0 0 0 1489 +815 819 0.994593129270795 0.068220731492635 0.0782971200104877 0.570635695547661 -0.0684542897284207 0.997654208828118 0.000299708725382162 -0.055715793536601 -0.078093004969103 -0.00565786197714646 0.996930023207619 0.057944306663808 2.93727157675202e-05 2.23586226562394e-06 4.09390383797949e-07 1.01325624664453e-05 2.51059254119467e-06 -1.0555835192392e-05 2.23586226562394e-06 3.42990004207179e-05 2.10897556285055e-07 -4.52617186449829e-07 -1.75152117373674e-07 -1.60614055619513e-05 4.09390383797949e-07 2.10897556285055e-07 1.33178380077754e-05 -4.83273903782097e-07 6.44052056236057e-06 -1.03088506346176e-06 1.01325624664453e-05 -4.52617186449829e-07 -4.83273903782097e-07 5.93889463797556e-05 6.90525709758478e-06 -2.74065848292523e-05 2.51059254119467e-06 -1.75152117373674e-07 6.44052056236057e-06 6.90525709758478e-06 1.40248556122308e-05 -9.59682903350797e-07 -1.0555835192392e-05 -1.60614055619513e-05 -1.03088506346176e-06 -2.74065848292523e-05 -9.59682903350797e-07 0.000108609594913485 2684 2683 0 1062 31 2643 2643 0 923 0 0 0 0 0 0 0 0 0 2438 0 70 62 0 0 2056 +815 841 0.968126141056602 0.239453018817219 -0.0734440384386218 3.67308552281261 -0.242313917383364 0.969644612880607 -0.0327611073369855 -0.408003944656065 0.0633698701685697 0.0495133970854137 0.996761096283297 0.403697353049574 3.36273193329077e-05 3.64141813091643e-06 -2.87096370492246e-06 1.31213188719882e-05 -1.21171337229478e-05 -8.04543460278509e-06 3.64141813091643e-06 0.000132789851925524 -1.2854326460651e-06 1.4614750482683e-05 4.65269121516961e-06 -2.87093437703187e-05 -2.87096370492246e-06 -1.2854326460651e-06 1.47003855428746e-05 -8.20084589590291e-07 8.93961496936541e-06 -2.78038727271097e-06 1.31213188719882e-05 1.4614750482683e-05 -8.20084589590291e-07 7.66280680387592e-05 -1.34062116517814e-05 1.46809770299384e-05 -1.21171337229478e-05 4.65269121516961e-06 8.93961496936541e-06 -1.34062116517814e-05 4.43175242970911e-05 -4.22504857159456e-07 -8.04543460278509e-06 -2.87093437703187e-05 -2.78038727271097e-06 1.46809770299384e-05 -4.22504857159456e-07 0.000108615117829573 2783 2741 0 3894 267 2783 2741 0 3894 245 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1814 +818 844 0.962466642936399 0.245752351143148 -0.11516832525635 3.56875139371718 -0.252947521850782 0.966056076380591 -0.0524710251251579 -0.403209862838427 0.0983641826290744 0.0796331538729407 0.991959196933 0.636735713825854 3.93445689924604e-05 1.38827414382599e-05 -2.52550208627943e-06 1.25424988188296e-05 -1.49811010850291e-05 -3.5794470328587e-06 1.38827414382599e-05 0.000162915840002291 -5.18420126514858e-06 8.25038358027686e-06 -3.41398579103252e-06 -6.50166517704567e-05 -2.52550208627943e-06 -5.18420126514858e-06 1.52675934735341e-05 -1.83891486902704e-06 5.18395444195845e-06 8.82434159385959e-06 1.25424988188296e-05 8.25038358027686e-06 -1.83891486902704e-06 6.54039096296429e-05 1.79847433690611e-06 -3.32096427197807e-05 -1.49811010850291e-05 -3.41398579103252e-06 5.18395444195845e-06 1.79847433690611e-06 4.10674942769419e-05 -2.4955018403392e-05 -3.5794470328587e-06 -6.50166517704567e-05 8.82434159385959e-06 -3.32096427197807e-05 -2.4955018403392e-05 0.000398230732405006 2832 2824 0 3889 444 2832 2824 0 3889 431 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1899 +817 843 0.953983877334642 0.276865557488635 -0.115153049729786 3.57260094076467 -0.280705702927315 0.959620132753724 -0.0182622331002357 -0.484033519489371 0.10544700152041 0.0497459937103756 0.993179875943991 0.661612538693792 2.53102161676131e-05 -1.94128120837384e-06 -2.98202066086421e-06 9.62657861092977e-06 -7.15762269996697e-07 7.6814974974844e-06 -1.94128120837384e-06 0.000101874415572227 1.44523161262874e-06 8.69759165184445e-06 -1.34159501345985e-05 1.563012839686e-05 -2.98202066086421e-06 1.44523161262874e-06 1.6155734770474e-05 -1.19135207075815e-05 7.73041774125087e-06 -9.95917364387083e-06 9.62657861092977e-06 8.69759165184445e-06 -1.19135207075815e-05 9.39928504745899e-05 5.22550769879476e-06 5.10318925146167e-05 -7.15762269996697e-07 -1.34159501345985e-05 7.73041774125087e-06 5.22550769879476e-06 4.86794766703178e-05 -9.84285925374602e-06 7.6814974974844e-06 1.563012839686e-05 -9.95917364387083e-06 5.10318925146167e-05 -9.84285925374602e-06 0.000260792942409855 2898 2873 0 3881 318 2898 2873 0 3881 311 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2202 +816 820 0.993901026295893 0.110265773993385 -0.00148627507882493 0.56642544664434 -0.110275782760854 0.99380569632283 -0.0137655255176072 -0.0943685268729137 -4.07976859857664e-05 0.0138454700871674 0.999904146052818 0.0846082302792707 3.83626947927776e-05 9.90051997552925e-06 2.15596198032223e-06 4.94227361190467e-06 -2.88291452341681e-06 -1.3632768450123e-05 9.90051997552925e-06 8.70949494237228e-05 -3.62314204319928e-08 -1.35209887738833e-05 1.40289098501117e-06 -4.87858730087345e-05 2.15596198032223e-06 -3.62314204319928e-08 1.21940516971126e-05 4.95859112416694e-06 4.78510841261008e-06 1.91539512608906e-07 4.94227361190467e-06 -1.35209887738833e-05 4.95859112416694e-06 5.77168016120166e-05 1.33883080378107e-06 -3.29290909437707e-05 -2.88291452341681e-06 1.40289098501117e-06 4.78510841261008e-06 1.33883080378107e-06 1.51349795989955e-05 -3.09241284398707e-06 -1.3632768450123e-05 -4.87858730087345e-05 1.91539512608906e-07 -3.29290909437707e-05 -3.09241284398707e-06 0.000203350025002677 2759 2698 0 869 0 2725 2664 0 731 0 0 0 0 0 0 0 0 0 2283 0 111 85 0 0 1974 +815 818 0.997261628967009 0.0246879249607428 0.0697119053763403 0.43290649656059 -0.0268354559773777 0.999188426600759 0.0300390820363483 -0.0335126976793495 -0.0689137264451234 -0.0318275746520683 0.997114789680312 0.0627097877462892 2.17158611243713e-05 3.00410587908967e-06 2.81517722107445e-06 5.23622681601191e-06 8.07520823704957e-09 -5.68218368431748e-06 3.00410587908967e-06 5.02770465421142e-05 3.6798439400555e-06 9.36810525613468e-06 5.70082020748831e-07 -2.29808841945241e-05 2.81517722107445e-06 3.6798439400555e-06 1.01232708308988e-05 5.39718059829043e-06 4.64517693636293e-06 -4.34191043954126e-06 5.23622681601191e-06 9.36810525613468e-06 5.39718059829043e-06 3.93989189639099e-05 -1.05378517902778e-06 -1.90314205015132e-05 8.07520823704957e-09 5.70082020748831e-07 4.64517693636293e-06 -1.05378517902778e-06 1.29262224331427e-05 -3.22524281209989e-06 -5.68218368431748e-06 -2.29808841945241e-05 -4.34191043954126e-06 -1.90314205015132e-05 -3.22524281209989e-06 0.000100538209914648 2728 2677 0 876 111 2695 2670 0 749 73 0 0 0 0 0 0 0 0 2927 0 93 50 0 0 2558 +816 819 0.995299725062931 0.0815961635217405 0.0521586367554523 0.426080545098248 -0.0820655141099888 0.996602929664714 0.00691751238330976 -0.0584390705674267 -0.0514170077262091 -0.01116542351384 0.998614853001015 0.0314340623793714 3.65273772889754e-05 5.51478948105759e-07 2.70056631224259e-06 1.51146755921272e-06 -6.65454096440623e-07 -1.95905122883911e-05 5.51478948105759e-07 4.36107759319166e-05 -2.58865023385567e-06 1.0836409409764e-05 -6.62813699869984e-07 -2.23320319699673e-05 2.70056631224259e-06 -2.58865023385567e-06 1.2722261935967e-05 -1.42335159983946e-06 6.01954794286686e-06 -1.04929588184558e-06 1.51146755921272e-06 1.0836409409764e-05 -1.42335159983946e-06 6.38186413392886e-05 1.95040618313524e-06 -1.29890798611765e-05 -6.65454096440623e-07 -6.62813699869984e-07 6.01954794286686e-06 1.95040618313524e-06 1.32271853222225e-05 1.82966693427229e-06 -1.95905122883911e-05 -2.23320319699673e-05 -1.04929588184558e-06 -1.29890798611765e-05 1.82966693427229e-06 7.17432702144184e-05 2677 2677 0 756 0 2661 2661 0 628 0 0 0 0 0 0 0 0 0 2742 0 106 53 0 0 2336 +816 818 0.998400267990076 0.038915578640823 0.0410180767027644 0.284829072953931 -0.040601059052326 0.998330106850992 0.0410919914182281 -0.0333206139106752 -0.0393504622739489 -0.0426916325986266 0.998313059929044 0.0629738183814783 3.52105090463736e-05 -4.38127303669853e-06 6.77742867554846e-07 2.67471046124837e-06 -3.30497238225572e-06 -4.97878074492403e-06 -4.38127303669853e-06 5.01278634244124e-05 1.21070280861658e-06 5.00777931960259e-06 -1.14191274350907e-07 -2.01358217004665e-05 6.77742867554846e-07 1.21070280861658e-06 1.03257300026867e-05 2.56025613539753e-06 6.4272402979661e-06 -1.34918215011554e-06 2.67471046124837e-06 5.00777931960259e-06 2.56025613539753e-06 3.5685723299079e-05 8.79442329979289e-07 -1.45675651907445e-06 -3.30497238225572e-06 -1.14191274350907e-07 6.4272402979661e-06 8.79442329979289e-07 1.32393421079627e-05 -6.0374729882967e-06 -4.97878074492403e-06 -2.01358217004665e-05 -1.34918215011554e-06 -1.45675651907445e-06 -6.0374729882967e-06 0.000127207995211535 2908 2889 0 600 67 2850 2842 0 488 11 0 0 0 0 0 0 0 0 3207 0 139 102 0 0 2680 +818 821 0.99210656267223 0.11034496660257 -0.0595697628681657 0.436051456674989 -0.113889571612293 0.99169194545019 -0.0598017625759194 -0.079263960129785 0.052476030534523 0.0661140958850375 0.996431228206264 0.0396149031525235 2.13715591459045e-05 2.61505097119196e-06 2.17336876815298e-06 2.91364912463646e-06 4.71282014944222e-07 -4.07819352652766e-06 2.61505097119196e-06 5.04108570253378e-05 9.77037758233048e-07 -1.98269971085996e-06 6.56497198853019e-07 -1.41411702772125e-05 2.17336876815298e-06 9.77037758233048e-07 1.33624903405822e-05 6.57684051677594e-07 5.99426867616449e-06 -2.95856580438458e-06 2.91364912463646e-06 -1.98269971085996e-06 6.57684051677594e-07 6.03415009648145e-05 3.44313102700742e-06 -3.40662800885154e-06 4.71282014944222e-07 6.56497198853019e-07 5.99426867616449e-06 3.44313102700742e-06 1.39246045796553e-05 1.14716884566057e-07 -4.07819352652766e-06 -1.41411702772125e-05 -2.95856580438458e-06 -3.40662800885154e-06 1.14716884566057e-07 7.91005698743174e-05 2612 2557 0 402 0 2586 2531 0 399 0 0 0 0 0 0 0 0 0 2665 0 96 80 0 0 3035 +818 822 0.991827708247447 0.127503286128788 -0.00455073389442804 0.579195377812495 -0.127545276504127 0.99000804111437 -0.0601355217020229 -0.101165733027467 -0.00316221348162149 0.0602245012868435 0.99817984844949 0.0562799142387151 5.60218713940565e-05 1.25680124736832e-05 9.48513286253426e-07 8.94896591975346e-06 -6.92732804185312e-06 -5.66990819305651e-05 1.25680124736832e-05 7.09525146237376e-05 3.16933231999867e-06 1.46229622240475e-05 -3.75358838667077e-06 -5.86041174998506e-05 9.48513286253426e-07 3.16933231999867e-06 1.16498289171859e-05 4.90068556057935e-06 6.34197952516417e-06 -6.96725284905338e-06 8.94896591975346e-06 1.46229622240475e-05 4.90068556057935e-06 3.55517085124908e-05 1.01757787323392e-07 -3.56441409664899e-05 -6.92732804185312e-06 -3.75358838667077e-06 6.34197952516417e-06 1.01757787323392e-07 1.66699073881217e-05 2.68743882945621e-05 -5.66990819305651e-05 -5.86041174998506e-05 -6.96725284905338e-06 -3.56441409664899e-05 2.68743882945621e-05 0.00044623759049269 2612 2589 0 700 0 2564 2541 0 699 0 0 0 0 0 0 0 0 0 2228 0 201 157 0 0 1521 +819 845 0.964571217494519 0.220545067875924 -0.144783422451418 3.54290353592618 -0.222341888789585 0.974961135548334 0.00385599011711253 -0.251395457317437 0.142008629563916 0.0284720425313586 0.989455856480455 0.754031011479391 2.5192083747238e-05 -8.17569950014663e-06 -2.17101170371579e-06 -1.64735899144373e-06 -7.72845491917577e-06 1.95935663214169e-05 -8.17569950014663e-06 0.000127775274067866 -4.46451206710873e-06 -9.8183151588257e-06 -9.42180052579453e-06 -2.07219939987435e-05 -2.17101170371579e-06 -4.46451206710873e-06 1.44567760511137e-05 -8.07134762498644e-06 4.29061724058098e-06 1.25085053079992e-05 -1.64735899144373e-06 -9.8183151588257e-06 -8.07134762498644e-06 7.15483670453485e-05 1.00879202381036e-05 -2.13548639590235e-05 -7.72845491917577e-06 -9.42180052579453e-06 4.29061724058098e-06 1.00879202381036e-05 4.60210713738127e-05 -2.72633595869142e-05 1.95935663214169e-05 -2.07219939987435e-05 1.25085053079992e-05 -2.13548639590235e-05 -2.72633595869142e-05 0.000268293122601844 2634 2637 0 3881 491 2634 2637 0 3881 477 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2131 +817 820 0.99284512337242 0.103839398923737 -0.0589571049726928 0.430042126137151 -0.105048276393771 0.994308151727767 -0.0177808614642109 -0.0810753571884759 0.0567751761098282 0.0238469838526504 0.998102149451062 0.0119314726656414 7.51405469339886e-05 1.37869339039265e-05 5.82624441777234e-07 2.56062077425076e-05 -9.22894139831485e-06 -2.34156215559006e-05 1.37869339039265e-05 4.48539111555489e-05 7.54660187922593e-08 7.44752136765423e-06 5.19803239000982e-08 -1.15021408655254e-05 5.82624441777234e-07 7.54660187922593e-08 1.24279460084149e-05 1.86253753334197e-06 6.48600845399102e-06 8.62984496538633e-08 2.56062077425076e-05 7.44752136765423e-06 1.86253753334197e-06 6.28657060296405e-05 -2.40560043038021e-06 -2.65167017165382e-05 -9.22894139831485e-06 5.19803239000982e-08 6.48600845399102e-06 -2.40560043038021e-06 1.51091227483521e-05 7.50761210649478e-06 -2.34156215559006e-05 -1.15021408655254e-05 8.62984496538633e-08 -2.65167017165382e-05 7.50761210649478e-06 0.000209265232855752 2827 2766 0 494 0 2810 2749 0 372 0 0 0 0 0 0 0 0 0 2663 0 86 58 0 0 1005 +817 821 0.988146011162803 0.143047603922982 -0.0557211237766671 0.567404271260012 -0.144803143779605 0.989040184751034 -0.0288368254005756 -0.114286734890532 0.0509853917763123 0.0365635878919709 0.998029856199644 0.0841168614482254 1.70162359687444e-05 4.66074476586408e-06 2.34739595870351e-06 4.50580478814764e-06 2.14934535333225e-06 -6.57470660077696e-06 4.66074476586408e-06 3.54667019276784e-05 2.61028827411499e-07 2.59685176238017e-06 3.63504991901335e-08 -1.41209023477103e-05 2.34739595870351e-06 2.61028827411499e-07 1.01382278658173e-05 2.36443514611039e-06 5.94686385601939e-06 -2.53293370963313e-06 4.50580478814764e-06 2.59685176238017e-06 2.36443514611039e-06 3.9602200034999e-05 1.01472890296518e-06 1.34496673490374e-07 2.14934535333225e-06 3.63504991901335e-08 5.94686385601939e-06 1.01472890296518e-06 1.3192499260324e-05 -9.61988222198866e-07 -6.57470660077696e-06 -1.41209023477103e-05 -2.53293370963313e-06 1.34496673490374e-07 -9.61988222198866e-07 3.88226232661881e-05 2556 2501 0 841 0 2530 2475 0 714 0 0 0 0 0 0 0 0 0 2197 0 146 118 0 0 3523 +819 822 0.995890336378234 0.0860755536498835 -0.028168013283033 0.436195370138488 -0.0868454449144569 0.995846165689061 -0.0273547615600048 -0.0610438767944957 0.025696431776749 0.0296886063374609 0.999228842682036 0.0760632258922044 2.85748718863735e-05 1.98105891534599e-06 -1.41328442300966e-06 1.05543676931133e-05 -3.3475298467791e-06 -1.01599651382203e-05 1.98105891534599e-06 3.32257134712806e-05 1.65241566510787e-06 -5.34043213353239e-07 -1.60052954306718e-06 -1.01724349796831e-05 -1.41328442300966e-06 1.65241566510787e-06 1.09933857985234e-05 3.91339188169656e-06 5.55983898601495e-06 -3.91189200237725e-07 1.05543676931133e-05 -5.34043213353239e-07 3.91339188169656e-06 3.71605107355057e-05 4.24460700837863e-06 -1.37924235124996e-05 -3.3475298467791e-06 -1.60052954306718e-06 5.55983898601495e-06 4.24460700837863e-06 1.40628384733664e-05 3.13773824116632e-06 -1.01599651382203e-05 -1.01724349796831e-05 -3.91189200237725e-07 -1.37924235124996e-05 3.13773824116632e-06 9.44217852193453e-05 2774 2752 0 698 4 2747 2725 0 698 0 0 0 0 0 0 0 0 0 2293 0 119 103 0 0 2684 +818 820 0.995997516150028 0.071335840797996 -0.0538530002935642 0.286182621785755 -0.0737275315152111 0.996315574997269 -0.0438123968134059 -0.0495263589043936 0.0505291887887508 0.047607487179064 0.997587253449464 0.0319262196377306 4.1467783890551e-05 1.18493380262069e-05 -4.84414443240622e-06 1.33356701045335e-05 -4.02654754351257e-06 -1.54275221385758e-06 1.18493380262069e-05 4.33226623943458e-05 -1.41240245777863e-06 8.54680606129044e-06 4.47296249392249e-07 -1.35527383192628e-05 -4.84414443240622e-06 -1.41240245777863e-06 1.17189212668895e-05 -4.54672346812449e-07 6.31780356977513e-06 3.00436850409178e-06 1.33356701045335e-05 8.54680606129044e-06 -4.54672346812449e-07 7.53309134068156e-05 2.96521377250286e-06 -3.2508613670238e-05 -4.02654754351257e-06 4.47296249392249e-07 6.31780356977513e-06 2.96521377250286e-06 1.51046562065664e-05 7.46165648513544e-07 -1.54275221385758e-06 -1.35527383192628e-05 3.00436850409178e-06 -3.2508613670238e-05 7.46165648513544e-07 0.000181922460052703 2932 2874 0 198 9 2902 2844 0 196 0 0 0 0 0 0 0 0 0 3138 0 83 48 0 0 1346 +819 821 0.996334569342337 0.0690334508562133 -0.0505154292894993 0.289341290447973 -0.0705747465325663 0.997073439414974 -0.0293898207728082 -0.0463661390069964 0.0483387120772124 0.0328472080408145 0.998290754158647 0.0621452954513791 3.74211060314885e-05 -9.96598029883563e-06 -1.36304533766168e-06 6.68763181041503e-06 1.4245662947955e-06 1.46378042740485e-06 -9.96598029883563e-06 4.8041840532504e-05 -2.9105864009891e-07 1.02393349212812e-06 -1.78960933026542e-06 -3.81986539801678e-05 -1.36304533766168e-06 -2.9105864009891e-07 1.06508216820769e-05 8.41699005216235e-09 5.21759271258343e-06 -3.60663695532516e-06 6.68763181041503e-06 1.02393349212812e-06 8.41699005216235e-09 4.0851201606331e-05 5.31997392022331e-06 -7.18413229459062e-07 1.4245662947955e-06 -1.78960933026542e-06 5.21759271258343e-06 5.31997392022331e-06 1.48529105615702e-05 1.12886426252956e-05 1.46378042740485e-06 -3.81986539801678e-05 -3.60663695532516e-06 -7.18413229459062e-07 1.12886426252956e-05 0.000236904843278045 2770 2715 0 395 9 2689 2634 0 395 0 0 0 0 0 0 0 0 0 2898 0 227 158 0 0 2447 +820 823 0.998269617119063 0.0402538080971309 0.0428649328780366 0.443458713039586 -0.0395038098867966 0.999053606897304 -0.0182027346823072 -0.031352894356923 -0.0435570951899579 0.0164779088226024 0.99891504042108 0.0895386230070893 8.24306977540275e-05 -1.68942486732433e-05 4.22199207201837e-06 2.15540007433815e-05 -1.21293761479666e-05 -0.0001082477076299 -1.68942486732433e-05 0.000265483895377285 -6.98474488483954e-06 3.1173910120098e-05 7.66223546392716e-06 0.000118288518603348 4.22199207201837e-06 -6.98474488483954e-06 1.36992572223635e-05 2.97460483136375e-06 5.02436451076921e-06 -1.44361089476619e-05 2.15540007433815e-05 3.1173910120098e-05 2.97460483136375e-06 7.58205266712162e-05 -9.95060858871831e-06 -0.000170233845236365 -1.21293761479666e-05 7.66223546392716e-06 5.02436451076921e-06 -9.95060858871831e-06 2.26533606567495e-05 7.20638062380592e-05 -0.0001082477076299 0.000118288518603348 -1.44361089476619e-05 -0.000170233845236365 7.20638062380592e-05 0.00123230861456322 2472 2462 0 751 23 2463 2461 0 691 6 0 0 0 0 0 0 0 0 2023 0 18 8 0 0 1152 +820 822 0.998006921631199 0.0579975174991641 0.0248691041284632 0.2973116632862 -0.0577076598393326 0.998258740487094 -0.0122193713827137 -0.0301528923859946 -0.0255344937699198 0.0107598794163761 0.99961603359633 0.0479315759604937 2.85031052466556e-05 7.11628080017025e-07 3.60289237352891e-07 6.50579290002224e-06 -4.16570977573829e-07 1.36855443877038e-05 7.11628080017025e-07 0.000165712423328945 -3.01391631344525e-06 4.14980036123553e-05 -6.14201501786642e-06 -0.000135760401296407 3.60289237352891e-07 -3.01391631344525e-06 1.12666100653826e-05 -1.64267783282525e-06 4.44319617346745e-06 7.32150722463837e-07 6.50579290002224e-06 4.14980036123553e-05 -1.64267783282525e-06 6.47790030087825e-05 5.89611491568314e-06 -6.06556651229879e-05 -4.16570977573829e-07 -6.14201501786642e-06 4.44319617346745e-06 5.89611491568314e-06 1.62193302175232e-05 1.07966439418856e-05 1.36855443877038e-05 -0.000135760401296407 7.32150722463837e-07 -6.06556651229879e-05 1.07966439418856e-05 0.000345068273920905 2437 2414 0 580 24 2410 2387 0 523 0 0 0 0 0 0 0 0 0 2509 0 52 36 0 0 3492 +821 823 0.999406781260542 -0.000849281578853668 0.0344291198150925 0.296209536175154 0.00101416157830105 0.999988100683543 -0.00477178872265417 -0.000377490482393683 -0.0344246575398402 0.00480387469865435 0.999395750311729 0.0587130121853554 2.76952591465993e-05 4.14209335054538e-06 -2.37519817945554e-06 3.69764411488762e-06 -3.89608326691794e-06 7.69008463726486e-06 4.14209335054538e-06 0.000179409380305695 -1.72476758349566e-06 7.12006607703942e-06 9.32900075019712e-07 -1.66400749417053e-05 -2.37519817945554e-06 -1.72476758349566e-06 1.26374551113916e-05 1.39775503358224e-06 4.8587804313708e-06 -1.49593189421768e-06 3.69764411488762e-06 7.12006607703942e-06 1.39775503358224e-06 4.84807500108334e-05 1.87867107219431e-06 -1.27228679100816e-05 -3.89608326691794e-06 9.32900075019712e-07 4.8587804313708e-06 1.87867107219431e-06 1.8232663600565e-05 6.41319257748692e-06 7.69008463726486e-06 -1.66400749417053e-05 -1.49593189421768e-06 -1.27228679100816e-05 6.41319257748692e-06 0.000179060233230448 2541 2510 0 347 73 2539 2510 0 263 55 0 0 0 0 0 0 0 0 2707 0 22 0 0 0 3216 +822 848 0.963111680561151 0.209587318291042 -0.168786986400745 3.45380710588379 -0.207041801051147 0.977783988674231 0.032743917142111 0.0131646809680725 0.171899922583383 0.0034099125915122 0.985108516414281 0.767498630096415 5.86496537825648e-05 -2.36466347182826e-05 -2.55540805955273e-06 1.71626709602264e-05 -5.85382308645569e-06 8.92807994143308e-06 -2.36466347182826e-05 5.89317006483376e-05 -6.93262935761267e-08 -1.00953923268754e-05 -3.8499306434355e-06 -4.12108030104623e-05 -2.55540805955273e-06 -6.93262935761267e-08 1.15169484929632e-05 -2.26919761998634e-06 6.91924277972739e-06 1.90948780189101e-06 1.71626709602264e-05 -1.00953923268754e-05 -2.26919761998634e-06 5.29441730519596e-05 -3.76808632427804e-06 2.06451722249494e-06 -5.85382308645569e-06 -3.8499306434355e-06 6.91924277972739e-06 -3.76808632427804e-06 2.96391213839426e-05 -4.27250839387146e-06 8.92807994143308e-06 -4.12108030104623e-05 1.90948780189101e-06 2.06451722249494e-06 -4.27250839387146e-06 0.000171742658502169 2795 2856 0 3914 554 2795 2856 0 3914 550 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1696 +821 825 0.992735913675996 -0.119349945959762 0.0151985557632294 0.583776444932607 0.118999022148541 0.992645838522398 0.0222142294905121 0.0300672193621265 -0.0177380502191506 -0.0202442501359774 0.9996377003249 0.0869689848952507 4.36459914551546e-05 -3.86901353618699e-06 1.46251019004868e-06 1.41275958988912e-05 -3.41603593816107e-06 1.36978761312029e-05 -3.86901353618699e-06 5.45711951907758e-05 5.68716841738981e-06 -2.52599012811234e-06 2.92138777175239e-07 -3.95673579017845e-05 1.46251019004868e-06 5.68716841738981e-06 1.20321262820479e-05 5.30845005697684e-06 6.30333278136434e-06 -4.19786271819948e-06 1.41275958988912e-05 -2.52599012811234e-06 5.30845005697684e-06 3.4916288561772e-05 -1.0121456417633e-06 6.73053712264198e-06 -3.41603593816107e-06 2.92138777175239e-07 6.30333278136434e-06 -1.0121456417633e-06 1.9471717152834e-05 -2.46865436175488e-06 1.36978761312029e-05 -3.95673579017845e-05 -4.19786271819948e-06 6.73053712264198e-06 -2.46865436175488e-06 0.000151199914301342 2987 2934 0 423 349 2987 2934 0 313 316 0 0 0 0 0 0 0 0 2067 0 0 0 0 0 2859 +822 824 0.997711977529171 -0.0669699177811521 -0.00926498824697096 0.297044781624599 0.067163962246184 0.997487863134051 0.0225158849627748 0.017411560109488 0.00773382636370626 -0.0230866414328603 0.999703553518305 0.0349709653232856 3.50345777363408e-05 -1.99896792468754e-05 -9.48649830682263e-07 -3.43326867126084e-06 -4.29966318704736e-06 2.14455181887072e-05 -1.99896792468754e-05 5.9564285317032e-05 6.12244311020552e-07 1.36251379350403e-05 -7.9404775014127e-07 -2.19257628367075e-05 -9.48649830682263e-07 6.12244311020552e-07 9.5539993616864e-06 1.54590739027259e-06 5.41684512353838e-06 5.53005679980973e-07 -3.43326867126084e-06 1.36251379350403e-05 1.54590739027259e-06 4.16636092131045e-05 -3.01545648849966e-07 -8.2707445720343e-06 -4.29966318704736e-06 -7.9404775014127e-07 5.41684512353838e-06 -3.01545648849966e-07 1.44054467332154e-05 -2.66000209398165e-06 2.14455181887072e-05 -2.19257628367075e-05 5.53005679980973e-07 -8.2707445720343e-06 -2.66000209398165e-06 0.000138907435965713 3177 3130 0 59 303 3177 3130 0 22 248 0 0 0 0 0 0 0 0 2719 0 0 0 0 0 3278 +821 847 0.973348774060435 0.19942427154632 -0.11323481776056 3.52440782662152 -0.19524627288636 0.979628703192948 0.0469733627121573 -0.0129673804714786 0.12029570632002 -0.0236127888806589 0.992457243029766 0.58607069374053 2.58943159303211e-05 1.22107014869291e-06 -8.28028161239507e-07 8.68563933568202e-06 -2.90931336636962e-06 -8.44539975232832e-06 1.22107014869291e-06 3.49575900750861e-05 2.34429659706086e-06 -6.66289579713607e-06 1.23772369775796e-06 -1.93968806085824e-05 -8.28028161239507e-07 2.34429659706086e-06 1.28953241999195e-05 -4.8646086451372e-06 7.56202908971367e-06 -2.95812230888047e-06 8.68563933568202e-06 -6.66289579713607e-06 -4.8646086451372e-06 6.35569461907838e-05 -5.7353932777285e-06 4.34630667391283e-06 -2.90931336636962e-06 1.23772369775796e-06 7.56202908971367e-06 -5.7353932777285e-06 3.59734785830794e-05 -1.68140874955436e-05 -8.44539975232832e-06 -1.93968806085824e-05 -2.95812230888047e-06 4.34630667391283e-06 -1.68140874955436e-05 9.80394778521635e-05 2904 2948 0 3903 604 2904 2948 0 3903 592 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1868 +823 825 0.993035457285303 -0.115183140413422 -0.0247674128376746 0.298678094970689 0.115808688510997 0.992943992974074 0.0255063615999212 0.0290526672617267 0.0216547509690787 -0.0281970030536035 0.99936780055156 0.00861826033667443 4.193827862173e-05 2.43779073540098e-07 -7.41477395595871e-07 4.9483782048532e-06 -4.78847906343837e-06 2.79925689283851e-05 2.43779073540098e-07 3.29611018157571e-05 1.88478100801915e-07 3.9728383344262e-06 -1.23094425679723e-06 -7.93333707601412e-06 -7.41477395595871e-07 1.88478100801915e-07 1.04948807594097e-05 1.55198806277812e-06 4.55155690529792e-06 -1.30278526008184e-06 4.9483782048532e-06 3.9728383344262e-06 1.55198806277812e-06 4.38937882514064e-05 1.50450626574466e-06 2.00512328323612e-06 -4.78847906343837e-06 -1.23094425679723e-06 4.55155690529792e-06 1.50450626574466e-06 1.65058854228268e-05 1.10981353279597e-06 2.79925689283851e-05 -7.93333707601412e-06 -1.30278526008184e-06 2.00512328323612e-06 1.10981353279597e-06 0.000163013740648635 3113 3069 0 0 386 3142 3098 0 0 324 0 0 0 0 0 81 78 0 2877 0 0 0 0 0 2928 +823 826 0.987522009164007 -0.150069444254248 -0.0477435159776009 0.447789057955094 0.151141721380767 0.988316128027071 0.0196827625001423 0.0530687671826146 0.0442319056195964 -0.0266531983596632 0.998665682569727 0.0268048150015464 4.00793269278919e-05 7.55799967124351e-07 -1.08799124715306e-06 4.06239722219276e-06 -1.5799794246305e-06 2.21395091584075e-05 7.55799967124351e-07 3.46069956823255e-05 -2.96732945323471e-06 2.88095260789116e-06 1.60629558170879e-06 -1.99573933242684e-05 -1.08799124715306e-06 -2.96732945323471e-06 1.09283795311726e-05 -1.20586024799001e-06 3.60706900841133e-06 2.23529783149924e-06 4.06239722219276e-06 2.88095260789116e-06 -1.20586024799001e-06 5.55711085011619e-05 4.22917926592378e-06 5.17764734689256e-06 -1.5799794246305e-06 1.60629558170879e-06 3.60706900841133e-06 4.22917926592378e-06 2.0615031124545e-05 -1.77866276606587e-06 2.21395091584075e-05 -1.99573933242684e-05 2.23529783149924e-06 5.17764734689256e-06 -1.77866276606587e-06 0.000183789061429364 3203 3153 0 0 558 3220 3170 0 0 483 0 0 0 0 0 35 31 0 2589 0 0 0 0 0 1890 +820 824 0.999458247662281 -0.00958327398149731 0.0314860610371967 0.591764726378183 0.00906132391429409 0.999819847851261 0.0166782568513898 -0.0299467863476273 -0.0316402210605862 -0.0163839159689082 0.999365030261096 0.0848535337225097 2.90040889638128e-05 6.96707321782886e-06 -1.80428300266695e-07 3.68327241952659e-07 1.50219133247539e-06 6.72309592489411e-06 6.96707321782886e-06 3.22335781212596e-05 9.18351831810008e-07 2.73841631532432e-06 1.62396082875818e-06 -3.77084373195593e-06 -1.80428300266695e-07 9.18351831810008e-07 9.97832097019401e-06 3.27400857225325e-06 5.52105348695895e-06 -4.85322497251031e-07 3.68327241952659e-07 2.73841631532432e-06 3.27400857225325e-06 3.636297351847e-05 3.95675388512191e-06 -2.54497558277761e-05 1.50219133247539e-06 1.62396082875818e-06 5.52105348695895e-06 3.95675388512191e-06 1.61975069744474e-05 9.50035747215906e-07 6.72309592489411e-06 -3.77084373195593e-06 -4.85322497251031e-07 -2.54497558277761e-05 9.50035747215906e-07 0.000305214437951338 3081 3037 0 850 194 3081 3037 0 766 143 0 0 0 0 0 0 0 0 1739 0 9 0 0 0 3218 +821 824 0.998144931862973 -0.0500423887968608 0.0346764231108954 0.444680775065036 0.0493037014418423 0.998545017936868 0.0218401505854044 0.0066608877745575 -0.0357189028442322 -0.0200899596058149 0.999159923887383 0.0883538414329613 3.76228254475835e-05 1.0808402402052e-05 -1.60390136246616e-06 6.33899036032831e-06 -2.00026263001886e-06 -3.13526723197567e-06 1.0808402402052e-05 0.000172890977892798 -1.77716734555617e-06 3.90235709545336e-05 -2.55565758556409e-06 -0.000117791426239631 -1.60390136246616e-06 -1.77716734555617e-06 1.10632375509014e-05 2.3006833437455e-06 6.10846483057962e-06 3.66080714712425e-06 6.33899036032831e-06 3.90235709545336e-05 2.3006833437455e-06 5.29965660298739e-05 -1.21595192264659e-06 -4.97164231281009e-05 -2.00026263001886e-06 -2.55565758556409e-06 6.10846483057962e-06 -1.21595192264659e-06 1.61531823898997e-05 7.0012977095685e-06 -3.13526723197567e-06 -0.000117791426239631 3.66080714712425e-06 -4.97164231281009e-05 7.0012977095685e-06 0.000312302361851801 2972 2944 0 392 141 2972 2944 0 291 125 0 0 0 0 0 0 0 0 2210 0 0 0 0 0 1881 +822 826 0.984469191934809 -0.170263683649033 -0.0427865418266833 0.588611327046847 0.170726117918258 0.985290960269875 0.00736995732885983 0.0685294866139335 0.0409023567998921 -0.0145602761213535 0.999057053209417 0.0384104365332622 2.29767088440636e-05 2.91614846272305e-06 -1.79626394698047e-07 1.97266780527638e-06 -1.40388501776857e-06 -3.64851712045055e-06 2.91614846272305e-06 4.11583296045413e-05 -7.15626521753405e-07 6.96225316187718e-06 2.80222651031387e-06 -1.25989889803238e-05 -1.79626394698047e-07 -7.15626521753405e-07 1.04123437311643e-05 2.47843057967341e-06 3.52723512697652e-06 -4.6156807527501e-06 1.97266780527638e-06 6.96225316187718e-06 2.47843057967341e-06 4.1822889602111e-05 1.56569492826877e-07 6.21230846415612e-06 -1.40388501776857e-06 2.80222651031387e-06 3.52723512697652e-06 1.56569492826877e-07 1.71402729287251e-05 1.68365885162649e-06 -3.64851712045055e-06 -1.25989889803238e-05 -4.6156807527501e-06 6.21230846415612e-06 1.68365885162649e-06 0.000141014759944115 3243 3189 0 49 576 3243 3189 0 9 532 0 0 0 0 0 0 0 0 2335 0 0 0 0 0 2832 +824 826 0.994230889858407 -0.103643137714612 -0.0276231362453759 0.296050056161347 0.103183269532317 0.994506861734307 -0.0175873492033898 0.0299059608835203 0.0292942065941699 0.0146356403362022 0.999463679926373 0.0226741123592059 3.52179579217757e-05 -1.10880047243213e-05 -3.79913615106032e-07 3.54482048403082e-06 1.07473870195606e-06 2.2257255668441e-05 -1.10880047243213e-05 9.08077475556654e-05 1.50185644615272e-06 1.18491252711125e-05 -5.82591216585739e-06 -5.38936601016757e-05 -3.79913615106032e-07 1.50185644615272e-06 1.15947827176714e-05 1.46844288301088e-06 3.51369110072e-06 -4.03410791891226e-06 3.54482048403082e-06 1.18491252711125e-05 1.46844288301088e-06 4.70183896457172e-05 5.3206380553797e-07 -8.70325606752082e-06 1.07473870195606e-06 -5.82591216585739e-06 3.51369110072e-06 5.3206380553797e-07 1.98325740545665e-05 1.19597532801694e-05 2.2257255668441e-05 -5.38936601016757e-05 -4.03410791891226e-06 -8.70325606752082e-06 1.19597532801694e-05 0.000171201160398136 3173 3126 0 1 320 3204 3161 0 0 285 0 0 0 0 0 160 165 0 2764 0 0 0 0 0 2761 +823 849 0.946236122023136 0.265272104215281 -0.185115942327542 3.4052387300513 -0.262757131148009 0.964095648065698 0.0384482953022641 -0.0876352906726206 0.188668734583887 0.0122593680905306 0.981964264362271 0.826196321346121 2.58646315793114e-05 -1.54837689639842e-07 -5.1069592121307e-06 7.06318481056489e-06 -5.0249921257315e-06 -7.06266817066881e-06 -1.54837689639842e-07 7.03763150287839e-05 2.89460273635882e-06 -1.24262664972722e-05 -3.10165594733654e-06 -4.34380002217084e-05 -5.1069592121307e-06 2.89460273635882e-06 1.26083956641256e-05 -3.75479211745147e-06 7.29147031093446e-06 -5.19151959282569e-06 7.06318481056489e-06 -1.24262664972722e-05 -3.75479211745147e-06 5.64099911286256e-05 7.32465156515407e-06 2.26002835329869e-05 -5.0249921257315e-06 -3.10165594733654e-06 7.29147031093446e-06 7.32465156515407e-06 2.91770115936099e-05 9.73146552071613e-06 -7.06266817066881e-06 -4.34380002217084e-05 -5.19151959282569e-06 2.26002835329869e-05 9.73146552071613e-06 8.99553978212369e-05 2716 2803 0 3884 534 2716 2803 0 3884 526 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1688 +823 827 0.988277427380171 -0.151840735300718 -0.0158782125621175 0.581881002556625 0.152174820270066 0.988097017913988 0.0225190422810612 0.0670318766245356 0.0122699065442084 -0.0246713253154426 0.999620315470117 0.0791132324600541 4.34074375531096e-05 1.27005050525897e-05 -3.04777839393714e-06 6.09149826679928e-06 -2.70844735201562e-06 -1.08655480908868e-05 1.27005050525897e-05 0.000136830218718846 -6.75154083341107e-06 4.70048063534925e-05 -5.91625044419465e-06 -0.000163864276506751 -3.04777839393714e-06 -6.75154083341107e-06 1.16051730573119e-05 2.38778073114453e-06 4.47196774107463e-06 3.96020421945922e-08 6.09149826679928e-06 4.70048063534925e-05 2.38778073114453e-06 5.92140762655573e-05 1.09067344543481e-06 -5.95665018598751e-05 -2.70844735201562e-06 -5.91625044419465e-06 4.47196774107463e-06 1.09067344543481e-06 1.61564934257899e-05 1.62648434746062e-05 -1.08655480908868e-05 -0.000163864276506751 3.96020421945922e-08 -5.95665018598751e-05 1.62648434746062e-05 0.000444082249658607 3269 3190 0 8 432 3269 3190 0 7 388 0 0 0 0 0 0 0 0 2192 0 0 0 0 0 1330 +824 851 0.912242710218988 0.374221756080381 -0.166647276990751 3.43555237490499 -0.380775952508169 0.924632233532405 -0.00805646972150624 -0.372962149659869 0.151072537689061 0.0708047314025898 0.985983660294223 0.894459416432858 4.83202531672271e-05 3.01977824404459e-05 -6.38558186382157e-07 -4.91177303810564e-06 -1.26683197110212e-05 -3.71490570159037e-05 3.01977824404459e-05 0.000162180960296994 2.11797770317996e-06 -1.44738828960627e-05 -2.69289190674638e-05 -0.00023154369633894 -6.38558186382157e-07 2.11797770317996e-06 1.22639098348464e-05 -2.48725519268862e-06 3.07779980093778e-06 -8.8364813391748e-06 -4.91177303810564e-06 -1.44738828960627e-05 -2.48725519268862e-06 5.30087923895527e-05 8.04177421740754e-06 5.96540192953754e-05 -1.26683197110212e-05 -2.69289190674638e-05 3.07779980093778e-06 8.04177421740754e-06 4.8701594319342e-05 7.27172626026764e-05 -3.71490570159037e-05 -0.00023154369633894 -8.8364813391748e-06 5.96540192953754e-05 7.27172626026764e-05 0.000762467740833079 2463 2621 0 3271 450 2463 2621 0 3271 450 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1830 +825 852 0.879541758631313 0.450248591577216 -0.153891197300141 3.33805813457132 -0.457695470574388 0.888983542410867 -0.0149371194785278 -0.667873454021884 0.130081324714301 0.0835731243005743 0.987974889283737 0.89485800102937 5.49643935616996e-05 3.72853628071096e-05 3.20876748412088e-06 -8.85387623710261e-06 -1.55308970287765e-05 -3.49422499082771e-05 3.72853628071096e-05 0.000180948494357603 1.39535395736958e-05 -5.3520503729972e-05 -5.46915421098524e-05 -0.000143693284484548 3.20876748412088e-06 1.39535395736958e-05 1.5443019676482e-05 -3.48773573125356e-06 2.39844614729216e-07 -1.21176297848724e-05 -8.85387623710261e-06 -5.3520503729972e-05 -3.48773573125356e-06 6.20945739496951e-05 2.66177179349779e-05 4.52032801565273e-05 -1.55308970287765e-05 -5.46915421098524e-05 2.39844614729216e-07 2.66177179349779e-05 4.8774269114801e-05 4.36622471019418e-05 -3.49422499082771e-05 -0.000143693284484548 -1.21176297848724e-05 4.52032801565273e-05 4.36622471019418e-05 0.000290285463794558 1974 2057 0 2997 497 1974 2057 0 2997 497 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1668 +825 851 0.887542184906431 0.434820881984858 -0.152314380809656 3.26873310815313 -0.439615064460393 0.898182963988678 0.00244096292415371 -0.604789585301262 0.13786756366529 0.0647932387709031 0.988329080366744 0.8164872671422 2.46845843504399e-05 -3.05788112170299e-06 -3.3228894324428e-07 -1.71694566802231e-06 -7.57662310118081e-06 8.20850390069099e-06 -3.05788112170299e-06 5.86300773572667e-05 -2.6686201844898e-06 -4.73364888393459e-06 -8.25914751202184e-07 -4.33842006670634e-05 -3.3228894324428e-07 -2.6686201844898e-06 1.473021951761e-05 -2.62173867139376e-06 4.40810526528909e-06 4.9562379952646e-06 -1.71694566802231e-06 -4.73364888393459e-06 -2.62173867139376e-06 5.29214081556517e-05 1.01651826529924e-05 -6.16422275745038e-06 -7.57662310118081e-06 -8.25914751202184e-07 4.40810526528909e-06 1.01651826529924e-05 3.09620471431943e-05 -9.10760730566196e-06 8.20850390069099e-06 -4.33842006670634e-05 4.9562379952646e-06 -6.16422275745038e-06 -9.10760730566196e-06 0.000105956207651559 2699 2864 0 3430 487 2699 2864 0 3430 487 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2152 +825 829 0.999431781884835 0.0130148022427516 0.0310922543583683 0.569096726181987 -0.0125610180818554 0.999812373750232 -0.0147457831489003 -0.0194932336447706 -0.0312783340868837 0.0143468539585916 0.999407741414004 0.0733647154362777 2.50459590560868e-05 4.5997961119158e-06 9.57239157586116e-07 -7.03622093964372e-07 -2.17175334937272e-06 -8.51936848194655e-06 4.5997961119158e-06 3.25608861913308e-05 4.4275300200709e-07 -3.93941524071234e-06 -1.16875070765526e-06 -2.55508738692781e-05 9.57239157586116e-07 4.4275300200709e-07 9.93221705132234e-06 1.74059828105189e-06 4.21701419313243e-06 1.20903702848256e-06 -7.03622093964372e-07 -3.93941524071234e-06 1.74059828105189e-06 4.04941404670295e-05 2.19568730700111e-06 -1.45792687396487e-05 -2.17175334937272e-06 -1.16875070765526e-06 4.21701419313243e-06 2.19568730700111e-06 1.47629992380102e-05 1.92131098054285e-06 -8.51936848194655e-06 -2.55508738692781e-05 1.20903702848256e-06 -1.45792687396487e-05 1.92131098054285e-06 9.60809129424308e-05 3518 3405 0 520 168 3518 3405 0 519 109 0 0 0 0 0 0 0 0 1653 0 35 0 0 0 3070 +826 828 0.998856610062723 0.0269581017269407 0.0394807964114901 0.288194591014384 -0.026696321055184 0.999618069508566 -0.00714293735702724 -0.0191097132447093 -0.0396582775234143 0.00608077817781512 0.99919479840551 0.054383549803323 2.34143177897446e-05 5.43561433938968e-06 7.71113277256126e-07 3.3531046339799e-06 2.14679349402441e-08 -3.91830261602607e-06 5.43561433938968e-06 2.17486325607936e-05 -2.77471143454825e-06 2.6181841176546e-06 1.76966812861077e-06 -9.22829879770343e-06 7.71113277256126e-07 -2.77471143454825e-06 1.02572635221253e-05 2.52119925466174e-07 4.1833650970571e-06 -2.13616883155987e-06 3.3531046339799e-06 2.6181841176546e-06 2.52119925466174e-07 4.31961015402592e-05 9.42392180823747e-07 -7.40159361546476e-07 2.14679349402441e-08 1.76966812861077e-06 4.1833650970571e-06 9.42392180823747e-07 1.67775405481001e-05 1.99487370334476e-06 -3.91830261602607e-06 -9.22829879770343e-06 -2.13616883155987e-06 -7.40159361546476e-07 1.99487370334476e-06 5.80757038620893e-05 3627 3502 0 206 120 3572 3497 0 212 50 0 0 0 0 0 0 0 0 2423 0 115 54 0 0 2768 +826 852 0.865125878126811 0.483162126108567 -0.134579251333792 3.17687680987402 -0.488349059350243 0.872624754882309 -0.0064213237205088 -0.78303087735354 0.114334645786162 0.0712769041193589 0.990882027141532 0.870030216432053 4.25404127886799e-05 8.98716392330028e-06 1.64960906159434e-06 1.28197422367177e-06 -1.09118563055698e-07 -2.32576031714933e-05 8.98716392330028e-06 6.16243760033491e-05 2.49130149288942e-06 -8.59561377833601e-06 5.02120112109057e-07 -2.97806316105983e-05 1.64960906159434e-06 2.49130149288942e-06 1.11035719809534e-05 1.34522954175213e-06 5.51307725406361e-06 -3.63555672793045e-06 1.28197422367177e-06 -8.59561377833601e-06 1.34522954175213e-06 4.1684427577105e-05 3.77790593789903e-06 -1.05217660741178e-05 -1.09118563055698e-07 5.02120112109057e-07 5.51307725406361e-06 3.77790593789903e-06 3.01800989153795e-05 5.91479303896474e-06 -2.32576031714933e-05 -2.97806316105983e-05 -3.63555672793045e-06 -1.05217660741178e-05 5.91479303896474e-06 0.000150196181068565 1842 1924 0 2950 453 1842 1924 0 2950 453 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1667 +825 828 0.999673616956859 -0.00936432364632423 0.023769076613093 0.43243361808387 0.00964226918781954 0.99988615691738 -0.0116060264475565 -0.00488705400968316 -0.0236576880802376 0.0118314262723751 0.99965010436005 0.0656409357851254 1.96227127372259e-05 2.79233698637065e-06 -1.36226986548628e-06 5.83944227227597e-06 -8.60094216303645e-07 7.90988069240424e-07 2.79233698637065e-06 3.00114370391905e-05 -6.77358952972147e-07 3.03031384367121e-06 1.72228126984049e-08 -9.367117835423e-06 -1.36226986548628e-06 -6.77358952972147e-07 1.05651557698982e-05 -1.93229717470343e-07 5.20776084608512e-06 -3.88283782252573e-06 5.83944227227597e-06 3.03031384367121e-06 -1.93229717470343e-07 4.08587450902271e-05 3.4961884136821e-06 1.25436125626854e-05 -8.60094216303645e-07 1.72228126984049e-08 5.20776084608512e-06 3.4961884136821e-06 1.51578159828893e-05 5.25803781335666e-06 7.90988069240424e-07 -9.367117835423e-06 -3.88283782252573e-06 1.25436125626854e-05 5.25803781335666e-06 7.60705619455314e-05 3617 3494 0 207 217 3617 3494 0 207 160 0 0 0 0 0 0 0 0 2084 0 14 0 0 0 3287 +826 830 0.99739581404825 0.0716206633491209 0.0084894464165644 0.563892620506363 -0.0712260368797399 0.996653716046008 -0.0401026428317305 -0.0595961086074017 -0.0113332161999038 0.0393935384690853 0.999159500448978 0.0768179628465481 2.92348349122806e-05 5.90700907466143e-06 2.24442426359119e-07 -2.72111266088392e-07 -1.25090079772108e-06 -2.75650924544076e-06 5.90700907466143e-06 4.31297287073415e-05 3.2335808967439e-07 3.17025865950277e-06 -2.28120960854991e-06 -3.0526293341383e-05 2.24442426359119e-07 3.2335808967439e-07 8.63840353006319e-06 3.9154417199564e-06 4.01096874670849e-06 1.13008983997207e-06 -2.72111266088392e-07 3.17025865950277e-06 3.9154417199564e-06 2.49814562862912e-05 1.49792814671874e-06 -6.35162325188049e-06 -1.25090079772108e-06 -2.28120960854991e-06 4.01096874670849e-06 1.49792814671874e-06 1.45779738390528e-05 3.28321005643277e-06 -2.75650924544076e-06 -3.0526293341383e-05 1.13008983997207e-06 -6.35162325188049e-06 3.28321005643277e-06 0.000103523006793186 3265 3198 0 878 21 3263 3198 0 877 10 0 0 0 0 0 0 0 0 1354 0 39 7 0 0 2445 +826 853 0.857972415096974 0.50063046424805 -0.11511938672286 3.22837127180415 -0.50667993831101 0.861642050685611 -0.0291275917893486 -0.847506670149264 0.0846095446496258 0.0833193540366063 0.992924523917657 0.940011225795937 4.05574153846973e-05 6.34707554648797e-06 2.50587135996397e-06 -2.58709832823588e-06 -8.04707714822759e-06 -7.2453212426123e-06 6.34707554648797e-06 0.000124341134744377 -1.93248920131542e-06 -2.20043700033903e-05 -1.07815823172828e-05 -0.000109383330664509 2.50587135996397e-06 -1.93248920131542e-06 1.39733339037136e-05 1.14308587193468e-06 4.53388929059566e-06 5.36157642799545e-06 -2.58709832823588e-06 -2.20043700033903e-05 1.14308587193468e-06 5.24837855494021e-05 6.59858863185798e-06 2.6761696443855e-06 -8.04707714822759e-06 -1.07815823172828e-05 4.53388929059566e-06 6.59858863185798e-06 3.43779911420848e-05 7.36487753926639e-06 -7.2453212426123e-06 -0.000109383330664509 5.36157642799545e-06 2.6761696443855e-06 7.36487753926639e-06 0.000207619532652308 1545 1564 0 2534 343 1545 1564 0 2534 343 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1705 +827 853 0.854953024482578 0.497587940718993 -0.14649766953479 3.05403172461548 -0.507009499026066 0.861290898517938 -0.0334567784985528 -0.845036477727184 0.109529419908216 0.102879684006101 0.988645071192576 1.00762823586196 5.33438723062563e-05 1.98201863388824e-05 5.52166998501987e-06 -8.31717439989208e-06 -2.24618533065717e-05 -1.20112662642911e-05 1.98201863388824e-05 6.28364270434271e-05 9.21794085887302e-06 -1.06976632904719e-05 -1.93082044911086e-05 -1.7541917359319e-05 5.52166998501987e-06 9.21794085887302e-06 1.59669766300312e-05 -2.47311875309587e-06 -1.25139001510329e-06 2.12553316367754e-06 -8.31717439989208e-06 -1.06976632904719e-05 -2.47311875309587e-06 5.61737676332775e-05 1.85839296542517e-05 -1.38404759167025e-05 -2.24618533065717e-05 -1.93082044911086e-05 -1.25139001510329e-06 1.85839296542517e-05 5.36160193366169e-05 -1.9141461339581e-05 -1.20112662642911e-05 -1.7541917359319e-05 2.12553316367754e-06 -1.38404759167025e-05 -1.9141461339581e-05 0.000107749219498129 1711 1733 0 2308 360 1711 1733 0 2308 360 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1704 +827 830 0.997106940889806 0.0706693128802933 -0.0279927963304884 0.418184381763695 -0.0718321025977188 0.996490491960029 -0.0429749749232144 -0.053386882054218 0.0248575434378338 0.0448614271985111 0.998683911397369 0.0930347006143822 2.66643884919235e-05 3.2305771816317e-06 3.23715528187705e-07 7.90265321281001e-07 -1.06859039100966e-06 -2.79085697894721e-07 3.2305771816317e-06 6.69198101874236e-05 -5.42765157239263e-07 1.04940739585715e-05 -6.92908378987524e-06 -6.39570583407338e-05 3.23715528187705e-07 -5.42765157239263e-07 9.91675355293957e-06 2.04668104138319e-06 3.96392193942246e-06 2.15047417131875e-06 7.90265321281001e-07 1.04940739585715e-05 2.04668104138319e-06 4.29025600218877e-05 -2.48132505335832e-06 -2.94278454226773e-05 -1.06859039100966e-06 -6.92908378987524e-06 3.96392193942246e-06 -2.48132505335832e-06 1.91204889854462e-05 1.66302113172598e-05 -2.79085697894721e-07 -6.39570583407338e-05 2.15047417131875e-06 -2.94278454226773e-05 1.66302113172598e-05 0.000160348628690026 3284 3217 0 876 30 3229 3162 0 826 13 0 0 0 0 0 0 0 0 1409 0 191 148 0 0 2241 +826 829 0.99760150232008 0.0505869529933939 0.0472461930272001 0.429056989539068 -0.0502461238008445 0.998701753464765 -0.00837464443391464 -0.0381754134125987 -0.0476085035651143 0.00598061980470645 0.998848167928961 0.0687677352137281 2.37826588686675e-05 7.82128848043682e-06 -7.62897405834279e-07 1.24126022512832e-05 3.23879163536374e-06 3.10869907002649e-06 7.82128848043682e-06 3.26592386526744e-05 -2.72621597955944e-06 9.50624946542364e-06 1.68954399168364e-06 -1.72548890888851e-05 -7.62897405834279e-07 -2.72621597955944e-06 1.07834588524116e-05 1.02476255756373e-06 4.02936822748016e-06 -4.54255877025017e-06 1.24126022512832e-05 9.50624946542364e-06 1.02476255756373e-06 5.19363062881722e-05 6.67290425202993e-06 7.85742609912996e-06 3.23879163536374e-06 1.68954399168364e-06 4.02936822748016e-06 6.67290425202993e-06 1.62981972733393e-05 8.26665692415001e-06 3.10869907002649e-06 -1.72548890888851e-05 -4.54255877025017e-06 7.85742609912996e-06 8.26665692415001e-06 0.000112085927013932 3434 3351 0 518 65 3384 3320 0 518 15 0 0 0 0 0 0 0 0 1774 0 125 71 0 0 3103 +827 829 0.998612445379126 0.0505002740553854 0.0149300453533759 0.278071623001533 -0.0503478767391484 0.998677454230103 -0.0104131513165095 -0.0319265671106943 -0.0154361666803134 0.00964700641712078 0.999834316287156 0.0667391762732251 2.2935535849766e-05 5.59470767392484e-06 -2.28803770607492e-06 7.86904952616229e-06 -3.63096470033926e-07 6.36125143722212e-06 5.59470767392484e-06 2.81282210840768e-05 -1.28828877670668e-06 4.46561435670395e-06 6.79776051225154e-07 -5.87695530493008e-06 -2.28803770607492e-06 -1.28828877670668e-06 1.08123700180569e-05 -1.88308147016217e-06 3.07819624197161e-06 -1.4777349446366e-06 7.86904952616229e-06 4.46561435670395e-06 -1.88308147016217e-06 4.85192801843152e-05 3.10300732198115e-06 5.7402287258236e-06 -3.63096470033926e-07 6.79776051225154e-07 3.07819624197161e-06 3.10300732198115e-06 1.79649997090362e-05 2.43935299119729e-06 6.36125143722212e-06 -5.87695530493008e-06 -1.4777349446366e-06 5.7402287258236e-06 2.43935299119729e-06 7.99351793523491e-05 3608 3540 0 518 20 3598 3534 0 482 10 0 0 0 0 0 0 0 0 2045 0 80 74 0 0 2774 +829 855 0.871735989025134 0.456349716245212 -0.178385262623588 2.87220210944214 -0.476860821244835 0.873848405184434 -0.0948299631884483 -0.753625605265084 0.112606050459437 0.167731634581959 0.979380404215028 1.15925343881098 3.59751652786714e-05 3.60276671658946e-05 -2.76114430383105e-06 -7.12161338125095e-07 -1.91800329170778e-05 4.04468550798887e-06 3.60276671658946e-05 0.000317334618753559 -1.0713659287962e-05 -3.45362975047176e-05 -3.44087460039036e-05 2.48044368269544e-05 -2.76114430383105e-06 -1.0713659287962e-05 1.76851225896299e-05 -5.23863092978439e-06 -4.16577453750938e-08 5.46827497852781e-06 -7.12161338125095e-07 -3.45362975047176e-05 -5.23863092978439e-06 0.000118419443673769 3.00755001729329e-05 -6.17906892067931e-05 -1.91800329170778e-05 -3.44087460039036e-05 -4.16577453750938e-08 3.00755001729329e-05 6.29233532756186e-05 1.24717632382247e-05 4.04468550798887e-06 2.48044368269544e-05 5.46827497852781e-06 -6.17906892067931e-05 1.24717632382247e-05 0.000354909804578369 1037 1057 0 1219 61 1037 1057 0 1219 61 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1588 +828 832 0.99312219238651 0.0958013746760748 -0.067308302605147 0.556019283313462 -0.0978837628980355 0.994794096829926 -0.0283456147093684 -0.0854304070927217 0.0642423532440467 0.0347390489579827 0.997329493460994 0.106255666082878 2.19021425355165e-05 3.24117794988347e-06 4.05325856632275e-07 -4.61793501209128e-06 -6.36615074595342e-06 1.61990551968817e-06 3.24117794988347e-06 8.22675680255649e-05 -2.91638276936557e-06 9.23991922510263e-06 7.44612834516924e-07 -4.02550456361445e-05 4.05325856632275e-07 -2.91638276936557e-06 1.04284932007999e-05 -4.74703917186742e-07 8.16739759787938e-07 2.25927751211731e-06 -4.61793501209128e-06 9.23991922510263e-06 -4.74703917186742e-07 4.8454241850151e-05 1.13862782095143e-05 -1.56892273833233e-05 -6.36615074595342e-06 7.44612834516924e-07 8.16739759787938e-07 1.13862782095143e-05 1.93040878609801e-05 -1.05244945793829e-06 1.61990551968817e-06 -4.02550456361445e-05 2.25927751211731e-06 -1.56892273833233e-05 -1.05244945793829e-06 0.000144595514061901 3217 3165 0 1343 10 3175 3123 0 1231 8 0 0 0 0 0 0 0 0 1338 0 179 160 0 0 2546 +829 831 0.995541200036078 0.0501659217800102 -0.0798817834220507 0.276000777999204 -0.0539167787123221 0.997507771931358 -0.0455107230202437 -0.0383256369156839 0.0773996124280478 0.0496147682499953 0.995764869217371 0.0658479433745232 4.79569382499692e-05 7.01915159227867e-06 2.42928710897479e-06 -7.43717257739792e-06 -5.91788696468575e-06 2.16026075577461e-05 7.01915159227867e-06 0.00010963717405813 -4.35174778296365e-06 2.92574738337093e-05 -8.86665387810813e-06 -0.00014402380672288 2.42928710897479e-06 -4.35174778296365e-06 1.13623259896105e-05 -4.581941803558e-06 1.65203172200113e-06 1.41047194568836e-05 -7.43717257739792e-06 2.92574738337093e-05 -4.581941803558e-06 6.10240136871153e-05 5.4278992334261e-06 -8.63885983319757e-05 -5.91788696468575e-06 -8.86665387810813e-06 1.65203172200113e-06 5.4278992334261e-06 2.30063939695848e-05 2.20404155434278e-05 2.16026075577461e-05 -0.00014402380672288 1.41047194568836e-05 -8.63885983319757e-05 2.20404155434278e-05 0.000447457197797868 3211 3150 0 571 36 3160 3108 0 488 6 0 0 0 0 0 0 0 0 2302 0 163 106 0 0 2410 +828 830 0.99835920864429 0.042472983298382 -0.0384048981886736 0.273958728217447 -0.0438655991770595 0.998382227953049 -0.0361764580403248 -0.0327764803311541 0.0368062457197766 0.0378017538910722 0.99860719388495 0.0622272196376611 2.48751859178601e-05 5.53924802740274e-06 -2.43172554826998e-06 5.19358972427271e-06 -7.16884688455475e-07 1.12544379119248e-05 5.53924802740274e-06 4.58028185693898e-05 2.50340498840211e-07 2.59689333274637e-06 -3.61080046705824e-06 -2.24747687510431e-05 -2.43172554826998e-06 2.50340498840211e-07 1.01370270607262e-05 2.21260616915802e-06 2.41078396826878e-06 -2.2407945714173e-06 5.19358972427271e-06 2.59689333274637e-06 2.21260616915802e-06 4.69155072405138e-05 3.77763819211105e-06 -4.48257774969458e-06 -7.16884688455475e-07 -3.61080046705824e-06 2.41078396826878e-06 3.77763819211105e-06 1.96669539539423e-05 1.22244343269428e-05 1.12544379119248e-05 -2.24747687510431e-05 -2.2407945714173e-06 -4.48257774969458e-06 1.22244343269428e-05 9.88706572500757e-05 3392 3324 0 555 14 3389 3324 0 462 10 0 0 0 0 0 0 0 0 2144 0 89 56 0 0 2771 +828 831 0.995117809633107 0.0733023080031697 -0.0660856761516178 0.417640678228541 -0.0764792216710533 0.995967755372133 -0.0468951907084915 -0.0616433338335345 0.0623816768257952 0.0517204205358419 0.996711354653893 0.0458354120854498 3.73784525383466e-05 -2.00545996246771e-06 7.60382155319445e-07 -5.4225296343661e-07 4.98218692882333e-07 1.69722074982323e-05 -2.00545996246771e-06 0.000161773479996583 -6.63625120455078e-06 2.87655841714431e-05 -1.36259258725004e-05 -0.000175072297176909 7.60382155319445e-07 -6.63625120455078e-06 1.03587584973312e-05 -3.36806729822258e-06 3.28243180196943e-06 1.47227890828216e-05 -5.4225296343661e-07 2.87655841714431e-05 -3.36806729822258e-06 5.8156500791808e-05 4.79335037622438e-06 -8.04416082513858e-05 4.98218692882333e-07 -1.36259258725004e-05 3.28243180196943e-06 4.79335037622438e-06 2.23465689132227e-05 2.79396857153837e-05 1.69722074982323e-05 -0.000175072297176909 1.47227890828216e-05 -8.04416082513858e-05 2.79396857153837e-05 0.000461792548678435 3159 3103 0 954 18 3116 3060 0 850 9 0 0 0 0 0 0 0 0 1614 0 161 115 0 0 2282 +829 832 0.994410143380464 0.0732040876197637 -0.076089607028844 0.420352513867019 -0.0752487103354033 0.996867274866728 -0.0243570912188018 -0.0596785168085693 0.0740682005647803 0.0299465833700679 0.996803442916183 0.0827695317419725 2.8555255922566e-05 -5.70306746787665e-06 1.18344984218608e-07 -4.1164137865396e-07 -1.49142543734677e-06 4.19081672092712e-06 -5.70306746787665e-06 0.000135546481489165 -2.24716111376304e-06 1.4467194258283e-05 -6.34665290805699e-06 -0.00013860438460681 1.18344984218608e-07 -2.24716111376304e-06 1.12208586728011e-05 -3.34862355915236e-06 2.92288475514029e-06 4.09872951498229e-06 -4.1164137865396e-07 1.4467194258283e-05 -3.34862355915236e-06 5.80246175170098e-05 4.95544046959503e-06 -3.74731006549061e-05 -1.49142543734677e-06 -6.34665290805699e-06 2.92288475514029e-06 4.95544046959503e-06 1.92828759728867e-05 1.32826280879782e-05 4.19081672092712e-06 -0.00013860438460681 4.09872951498229e-06 -3.74731006549061e-05 1.32826280879782e-05 0.000313782694093684 3223 3171 0 926 22 3168 3117 0 835 5 0 0 0 0 0 0 0 0 1868 0 167 144 0 0 2183 +830 832 0.998050679918465 0.0521129587611794 -0.0343377320661315 0.283067144839009 -0.0519300908162767 0.998631497077264 0.00619666951154242 -0.0402844382838591 0.0346136675621505 -0.00440142867460575 0.999391075327131 0.0471086036674427 3.13102028460008e-05 1.16789293708666e-05 1.43979515385731e-08 1.82340412695892e-06 -3.5693840200587e-06 9.52345136601307e-06 1.16789293708666e-05 3.13521052497566e-05 -4.18159883189083e-07 1.33344858805218e-06 5.84302242925088e-07 4.44954980471545e-06 1.43979515385731e-08 -4.18159883189083e-07 1.04110895097339e-05 -3.39456659561555e-06 1.18958106772252e-06 -8.86515851940268e-07 1.82340412695892e-06 1.33344858805218e-06 -3.39456659561555e-06 5.97207342035663e-05 1.22650846522697e-05 -6.92175082925361e-06 -3.5693840200587e-06 5.84302242925088e-07 1.18958106772252e-06 1.22650846522697e-05 2.17753799018566e-05 2.58989527509922e-06 9.52345136601307e-06 4.44954980471545e-06 -8.86515851940268e-07 -6.92175082925361e-06 2.58989527509922e-06 0.000138104054507107 3422 3369 0 578 49 3341 3290 0 499 0 0 0 0 0 0 0 0 0 2654 0 160 99 0 0 2856 +829 833 0.997303533767842 0.0591537213810038 -0.0434338437276047 0.552885377145334 -0.0606255020670774 0.99760203084845 -0.0333876705710803 -0.0793280295825382 0.0413546857476902 0.0359308404275039 0.998498254716994 0.141284605793014 5.06540663691797e-05 2.47843478245903e-05 2.76445782620391e-07 -9.25136026743485e-06 -1.04184547416663e-05 2.12700280879815e-05 2.47843478245903e-05 9.06947362104626e-05 -3.38764461720644e-06 6.83491506778557e-06 1.70396805478541e-06 -2.43481159093421e-05 2.76445782620391e-07 -3.38764461720644e-06 1.17263544594875e-05 -9.92367874250557e-07 1.53981752000166e-06 9.58648341585163e-06 -9.25136026743485e-06 6.83491506778557e-06 -9.92367874250557e-07 4.66414961347298e-05 7.37944316282298e-06 -4.03595435076121e-05 -1.04184547416663e-05 1.70396805478541e-06 1.53981752000166e-06 7.37944316282298e-06 2.31336458176648e-05 -9.67185927670626e-06 2.12700280879815e-05 -2.43481159093421e-05 9.58648341585163e-06 -4.03595435076121e-05 -9.67185927670626e-06 0.000235523030878068 3194 3132 0 1205 14 3177 3124 0 1094 0 0 0 0 0 0 0 0 0 1550 0 62 14 0 0 2234 +830 834 0.999764624951063 0.0166335438162562 -0.0139291032221458 0.566013121558372 -0.0167025634643778 0.999848722632599 -0.00485347542262431 -0.0487017256477428 0.0138462655679768 0.00508498476617895 0.999891206011808 0.108541604956789 2.01845147122991e-05 4.71049855343242e-06 3.01230609305414e-07 1.16667779471375e-06 -1.20529824129406e-07 -6.31742488995834e-06 4.71049855343242e-06 3.46866229575888e-05 2.76025979321708e-06 -5.74751514865279e-06 -1.03669321771078e-06 -2.54826615395594e-05 3.01230609305414e-07 2.76025979321708e-06 1.21570798778095e-05 -2.55546803272486e-06 1.07014283688353e-06 -4.34815385521219e-06 1.16667779471375e-06 -5.74751514865279e-06 -2.55546803272486e-06 5.10852774901396e-05 1.43483761630341e-05 6.7690465688483e-07 -1.20529824129406e-07 -1.03669321771078e-06 1.07014283688353e-06 1.43483761630341e-05 2.60473627745857e-05 1.86343410471851e-06 -6.31742488995834e-06 -2.54826615395594e-05 -4.34815385521219e-06 6.7690465688483e-07 1.86343410471851e-06 7.24298266522347e-05 3396 3279 0 1050 191 3387 3279 0 941 108 0 0 0 0 0 0 0 0 1828 0 39 0 0 0 2766 +830 858 0.858026906417579 0.484662771703511 -0.169975955911855 2.86085300655724 -0.492795611784108 0.870120279676368 -0.00657144597835451 -0.727232969576551 0.144714591074312 0.0894018826456688 0.985426298872526 1.29889016250707 8.65010698881563e-05 2.46840155742643e-05 4.08629679314463e-06 2.30054977434738e-06 -2.33804108000463e-05 9.72051143446425e-05 2.46840155742643e-05 0.000393275934157015 -2.05667973330153e-05 1.04484686178327e-05 7.42540450745437e-06 -0.000176804350537271 4.08629679314463e-06 -2.05667973330153e-05 1.87701918527463e-05 7.52660716610699e-06 1.91535345793016e-07 3.31879837680541e-05 2.30054977434738e-06 1.04484686178327e-05 7.52660716610699e-06 5.1655065688982e-05 1.89075555175863e-06 -4.30120128517356e-06 -2.33804108000463e-05 7.42540450745437e-06 1.91535345793016e-07 1.89075555175863e-06 7.5028666445518e-05 0.000172382212035724 9.72051143446425e-05 -0.000176804350537271 3.31879837680541e-05 -4.30120128517356e-06 0.000172382212035724 0.00262312754202631 171 185 0 743 0 171 185 0 743 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1581 +831 834 0.999599612946341 -0.014109551906144 0.0245261970662725 0.429229752198758 0.0139137605474067 0.999870103149516 0.00813536079134727 -0.0132910222683547 -0.02463779748588 -0.00779085186509094 0.999666085031527 0.0745103069180286 1.63113009223131e-05 -2.83681561278306e-07 1.38122497933966e-06 1.5691711695024e-06 -5.75391627875954e-07 -4.06458899823142e-06 -2.83681561278306e-07 2.18989546821608e-05 -1.34397549819726e-07 6.7200640464844e-07 7.45465885724567e-07 -1.18684230802908e-05 1.38122497933966e-06 -1.34397549819726e-07 1.03805718930987e-05 -3.18454702381179e-06 1.8114729568055e-07 -2.86151055988293e-06 1.5691711695024e-06 6.7200640464844e-07 -3.18454702381179e-06 5.25182465390578e-05 1.84327582332076e-05 1.62095812287344e-06 -5.75391627875954e-07 7.45465885724567e-07 1.8114729568055e-07 1.84327582332076e-05 2.49916784318057e-05 3.79268318859401e-06 -4.06458899823142e-06 -1.18684230802908e-05 -2.86151055988293e-06 1.62095812287344e-06 3.79268318859401e-06 6.00558057358285e-05 3562 3450 0 617 222 3562 3450 0 528 161 0 0 0 0 0 0 0 0 2475 0 11 0 0 0 3532 +830 833 0.99916094563675 0.0407565072999443 0.00403879028745286 0.4296683688046 -0.0407891754314456 0.999132747521563 0.00836636107485036 -0.0500326180419176 -0.00369430398034507 -0.00852408016865171 0.999956845156519 0.0765384768719241 3.41841472538541e-05 1.92779059163663e-06 2.14650980863471e-06 -1.64841002828361e-06 -5.44874261837947e-06 2.63669101440626e-05 1.92779059163663e-06 5.89449017295897e-05 -1.01314256714052e-06 6.88324188774546e-07 -3.17098318462773e-06 -2.22066061868774e-05 2.14650980863471e-06 -1.01314256714052e-06 1.17919931180086e-05 -8.25316284398747e-07 6.96352478487477e-07 6.1345358156094e-06 -1.64841002828361e-06 6.88324188774546e-07 -8.25316284398747e-07 5.44030923191666e-05 1.18498250639817e-05 -4.759969290473e-05 -5.44874261837947e-06 -3.17098318462773e-06 6.96352478487477e-07 1.18498250639817e-05 2.37729943627289e-05 -6.96488322545131e-06 2.63669101440626e-05 -2.22066061868774e-05 6.1345358156094e-06 -4.759969290473e-05 -6.96488322545131e-06 0.000283869566334549 3284 3188 0 829 103 3222 3169 0 748 35 0 0 0 0 0 0 0 0 2165 0 125 75 0 0 2888 +831 833 0.999642961010895 0.00869325862481734 0.02526613852277 0.284903684061238 -0.00914415803755117 0.999800008591105 0.0177855895322976 -0.0192967149469875 -0.0251064707825304 -0.0180102769470412 0.999522533537457 0.063721167329496 1.99133107580293e-05 4.24873318120624e-06 1.64291894906453e-07 9.68983743460696e-07 3.0163605550445e-06 1.26096427465938e-05 4.24873318120624e-06 9.36825519430154e-05 -1.97659163959168e-06 1.49224002391874e-05 1.64926298100706e-06 -3.33556217586551e-05 1.64291894906453e-07 -1.97659163959168e-06 9.91241356581757e-06 -1.06350471012325e-06 1.61451995245883e-06 -1.86214586384008e-06 9.68983743460696e-07 1.49224002391874e-05 -1.06350471012325e-06 4.61038992298014e-05 7.87599501591857e-06 -1.22877081671498e-05 3.0163605550445e-06 1.64926298100706e-06 1.61451995245883e-06 7.87599501591857e-06 1.73487028833762e-05 3.88484476708791e-06 1.26096427465938e-05 -3.33556217586551e-05 -1.86214586384008e-06 -1.22877081671498e-05 3.88484476708791e-06 0.000125555517094677 3210 3098 0 433 146 3185 3098 0 357 89 0 0 0 0 0 0 0 0 2856 0 94 35 0 0 3903 +832 834 0.999126787825371 -0.0356787727701459 0.0217413666399379 0.283511888867961 0.0358997640731215 0.999306749911891 -0.00986035090790497 0.00715200048371157 -0.0213744892161221 0.0106322506624471 0.999715002616546 0.0594038659031831 3.38858672583775e-05 3.80889604238736e-06 1.25411248806948e-06 -2.87481885118022e-06 5.59050802228383e-07 2.13775079466089e-05 3.80889604238736e-06 2.42399833234024e-05 1.42619030640177e-06 -1.84077025746881e-06 -2.31038897003627e-07 -1.66857115853504e-06 1.25411248806948e-06 1.42619030640177e-06 1.074028530947e-05 -7.86814574572953e-07 -5.0873850140872e-08 -1.89597883257534e-06 -2.87481885118022e-06 -1.84077025746881e-06 -7.86814574572953e-07 4.47621665054414e-05 1.1667244386001e-05 -7.34909312697217e-06 5.59050802228383e-07 -2.31038897003627e-07 -5.0873850140872e-08 1.1667244386001e-05 2.4287961693775e-05 8.80784534738767e-06 2.13775079466089e-05 -1.66857115853504e-06 -1.89597883257534e-06 -7.34909312697217e-06 8.80784534738767e-06 0.00013566757004172 3573 3462 0 266 224 3573 3462 0 192 165 0 0 0 0 0 0 0 0 2956 0 0 0 0 0 2197 +832 835 0.999157444204421 -0.040382416998066 -0.00732544116654059 0.428621602042274 0.040700087519258 0.997908987168351 0.0502111163444968 0.00547069480625799 0.00528247733690198 -0.0504669567740136 0.998711761073812 0.0633101771647899 3.0479961834476e-05 -1.15892196385443e-05 8.51636755803997e-07 -2.2441955362863e-06 -9.0037224246965e-07 5.59530360392058e-05 -1.15892196385443e-05 0.00017305794564489 -2.41599175982119e-07 5.9284377271739e-05 -8.42225322259203e-07 -0.000249257030296868 8.51636755803997e-07 -2.41599175982119e-07 9.58942180345886e-06 2.20411148627329e-06 3.3345617764703e-06 -3.44369821433914e-07 -2.2441955362863e-06 5.9284377271739e-05 2.20411148627329e-06 6.18522472986387e-05 4.39937598996608e-06 -0.000105620765321251 -9.0037224246965e-07 -8.42225322259203e-07 3.3345617764703e-06 4.39937598996608e-06 1.4921386436273e-05 -2.09299026669937e-06 5.59530360392058e-05 -0.000249257030296868 -3.44369821433914e-07 -0.000105620765321251 -2.09299026669937e-06 0.000741311342572106 3217 3127 0 494 295 3217 3127 0 426 220 0 0 0 0 0 0 0 0 2615 0 0 0 0 0 3009 +832 859 0.894285099011024 0.430182081613509 -0.123278296327904 2.64598697100715 -0.436539565453548 0.899220942262202 -0.0288947190798817 -0.57808861992409 0.0984244353830356 0.0796559706220846 0.991951388357204 1.17898163375773 8.95329362141876e-05 -5.30873538819521e-06 2.46721554164509e-06 6.65879759234511e-06 -1.65961223453059e-05 -9.60826541594109e-06 -5.30873538819521e-06 0.000198808405036087 -4.92594888331839e-06 1.93248665655064e-06 -1.26828239386209e-05 -0.000208731203687096 2.46721554164509e-06 -4.92594888331839e-06 1.48550425767318e-05 2.19962800976692e-06 8.67079657814661e-06 2.76539813062377e-06 6.65879759234511e-06 1.93248665655064e-06 2.19962800976692e-06 5.26396808884154e-05 8.37878741211158e-06 5.70716966994445e-06 -1.65961223453059e-05 -1.26828239386209e-05 8.67079657814661e-06 8.37878741211158e-06 4.13681269317547e-05 3.78705931549661e-05 -9.60826541594109e-06 -0.000208731203687096 2.76539813062377e-06 5.70716966994445e-06 3.78705931549661e-05 0.00039489534118714 405 411 0 1214 0 405 411 0 1214 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1666 +832 836 0.998861731217381 -0.0443978723403382 -0.017437627162788 0.568238272399222 0.0454839143993806 0.996660598642339 0.0678149293651787 0.0139167904067553 0.0143685573502419 -0.0685308692892873 0.99754552002108 0.0620006675214971 2.11354674704199e-05 -5.37460730602266e-07 -1.01541283623821e-06 3.15933381953855e-06 -4.70318154587916e-06 -2.54506448533879e-06 -5.37460730602266e-07 3.72397538868304e-05 2.46692850679541e-07 2.70557982104054e-07 3.92468075159188e-07 -3.32959978061604e-05 -1.01541283623821e-06 2.46692850679541e-07 9.00463668239128e-06 3.61621716517287e-06 3.78575501190271e-06 4.40330797237498e-07 3.15933381953855e-06 2.70557982104054e-07 3.61621716517287e-06 2.78465417728761e-05 3.28868667585457e-06 -4.91737549051855e-06 -4.70318154587916e-06 3.92468075159188e-07 3.78575501190271e-06 3.28868667585457e-06 1.51885636324481e-05 -1.33330515874284e-06 -2.54506448533879e-06 -3.32959978061604e-05 4.40330797237498e-07 -4.91737549051855e-06 -1.33330515874284e-06 8.21967963216258e-05 3318 3241 0 738 318 3318 3241 0 656 235 0 0 0 0 0 0 0 0 2374 0 0 0 0 0 2516 +833 935 0.966485463474916 0.0547174019345004 -0.250822357092058 2.67092831640575 -0.0462010153411087 0.998142093808095 0.039721867401244 -0.51757342662169 0.252529830065931 -0.0268023598574773 0.967217823674141 0.829667495215011 2.7196226264309e-05 2.73829420837196e-06 -1.11528422077222e-06 -5.48061167470884e-07 -6.70230635628795e-06 -3.42135436172521e-06 2.73829420837196e-06 9.39411634852521e-05 2.27560111609262e-06 -1.83254344685873e-06 -4.20764977459548e-06 -8.88117310782326e-05 -1.11528422077222e-06 2.27560111609262e-06 1.21755728356568e-05 5.55797240144037e-07 4.47719964934087e-06 -2.93472379857379e-06 -5.48061167470884e-07 -1.83254344685873e-06 5.55797240144037e-07 6.09148195206979e-05 -2.0901107929157e-06 -1.02500213692683e-05 -6.70230635628795e-06 -4.20764977459548e-06 4.47719964934087e-06 -2.0901107929157e-06 2.48175391130957e-05 3.11289113412299e-06 -3.42135436172521e-06 -8.88117310782326e-05 -2.93472379857379e-06 -1.02500213692683e-05 3.11289113412299e-06 0.000185838766449942 1431 1429 0 3111 0 1431 1429 0 3111 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 789 +833 934 0.966483234496656 0.103275763295433 -0.235041005257864 2.61312539812095 -0.0936889075376277 0.994262068977479 0.0516268030874357 -0.548019729471896 0.239024153677589 -0.0278757046255117 0.970613413800955 0.949571087759604 4.51668266298021e-05 9.94613099339836e-06 2.99181913344531e-06 9.35739799520123e-06 -3.58153793345266e-06 9.64841337508562e-05 9.94613099339836e-06 0.000205629140153669 1.11282462641646e-05 -6.90167096168448e-06 -6.40429156084338e-07 -0.000220541447565515 2.99181913344531e-06 1.11282462641646e-05 1.44547871785522e-05 3.14733060637343e-06 5.81451268788469e-06 1.41173306591243e-05 9.35739799520123e-06 -6.90167096168448e-06 3.14733060637343e-06 7.41382888485339e-05 7.40224391823273e-06 7.47953772874625e-05 -3.58153793345266e-06 -6.40429156084338e-07 5.81451268788469e-06 7.40224391823273e-06 2.73515629417469e-05 4.05142512470714e-06 9.64841337508562e-05 -0.000220541447565515 1.41173306591243e-05 7.47953772874625e-05 4.05142512470714e-06 0.00115011908110465 1171 1174 0 2691 0 1171 1174 0 2691 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 869 +833 837 0.999722368477167 -0.0171668857293135 -0.0161395167449576 0.563636140969325 0.0179593107768436 0.998572258556668 0.0503081265548122 0.0200899089010703 0.0152528398282032 -0.0505840140300367 0.99860332885575 0.0571812859894622 3.59550407397939e-05 2.14932475683599e-06 1.01531727305641e-06 -6.40526700766549e-07 -6.16413435604381e-07 -2.35288296747087e-05 2.14932475683599e-06 5.05027114186003e-05 -5.40696345370355e-07 9.82565856415148e-06 2.25239774275634e-06 -4.33734140163405e-05 1.01531727305641e-06 -5.40696345370355e-07 1.02273351974584e-05 3.66051874059772e-06 4.04856997904586e-06 -2.07914825256125e-06 -6.40526700766549e-07 9.82565856415148e-06 3.66051874059772e-06 3.38191165581792e-05 3.36978296782138e-06 -7.15734599467912e-06 -6.16413435604381e-07 2.25239774275634e-06 4.04856997904586e-06 3.36978296782138e-06 1.54877078268387e-05 1.90207562611923e-06 -2.35288296747087e-05 -4.33734140163405e-05 -2.07914825256125e-06 -7.15734599467912e-06 1.90207562611923e-06 0.000120788659139403 3451 3374 0 808 305 3451 3374 0 712 273 0 0 0 0 0 0 0 0 2468 0 0 0 0 0 1969 +833 933 0.968770174943311 0.173528305712225 -0.177122204302429 2.56599878353276 -0.170641887281048 0.984828832963611 0.0315200899220554 -0.578785909599025 0.179904681555174 -0.000311255806472736 0.983683998382791 1.07769711319106 2.87676023536812e-05 1.64634022036932e-05 -6.0855573312092e-06 2.13486257912317e-06 -1.05939953160595e-05 -4.03121465629167e-06 1.64634022036932e-05 0.000194560953527781 1.20790639516174e-05 -2.82130794781031e-05 -1.06006043724613e-05 -0.000272256788403137 -6.0855573312092e-06 1.20790639516174e-05 1.43408754063036e-05 -1.6250265894912e-06 6.58815373518722e-06 -2.19967013046773e-05 2.13486257912317e-06 -2.82130794781031e-05 -1.6250265894912e-06 7.46358555358082e-05 6.3842323972919e-06 7.62693462540861e-05 -1.05939953160595e-05 -1.06006043724613e-05 6.58815373518722e-06 6.3842323972919e-06 2.76641412020169e-05 2.62927554936759e-05 -4.03121465629167e-06 -0.000272256788403137 -2.19967013046773e-05 7.62693462540861e-05 2.62927554936759e-05 0.000631019124196511 1004 1012 0 2069 0 1004 1012 0 2069 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1021 +833 835 0.999161435479917 -0.0279378050150172 -0.0299316705289672 0.285157426101692 0.0291709720862562 0.99870894593545 0.0415872059177516 0.0032454199766146 0.0287311718740225 -0.0424254682878751 0.998686436977743 0.0376631435164334 7.24305903645473e-05 1.03826405989864e-05 1.76832739094607e-06 1.25380718047094e-05 -1.13079404446858e-07 1.38800661078309e-05 1.03826405989864e-05 2.58810816622582e-05 -4.44976371892418e-06 7.19100793351207e-06 2.95224465249753e-06 -7.31412661829754e-06 1.76832739094607e-06 -4.44976371892418e-06 1.34052806571076e-05 -2.69908070273797e-06 8.00519491139714e-07 -1.18137448934345e-06 1.25380718047094e-05 7.19100793351207e-06 -2.69908070273797e-06 6.20897101202136e-05 1.21424602580468e-05 4.73036173880691e-06 -1.13079404446858e-07 2.95224465249753e-06 8.00519491139714e-07 1.21424602580468e-05 2.39818145480678e-05 1.01917011364286e-05 1.38800661078309e-05 -7.31412661829754e-06 -1.18137448934345e-06 4.73036173880691e-06 1.01917011364286e-05 0.000102914885544211 3605 3515 0 291 247 3605 3515 0 203 198 0 0 0 0 0 0 0 0 2962 0 2 0 0 0 766 +834 837 0.999573774592591 -0.0185698129707302 -0.0225262334391091 0.417689563899153 0.0199535769446426 0.997823784437304 0.0628454451677366 -0.00163570106090049 0.0213101833365028 -0.0632681377744664 0.997769020780218 0.0425686943760868 4.49211860386075e-05 -1.05683768604643e-05 -0.000296778603374646 -3.10638396319893e-05 0.000184315914700778 -2.65644410835222e-05 -1.05683768604643e-05 0.000251417256411585 0.000179527701824737 2.00292164014004e-05 -0.000145989419332973 -0.000363004814559624 -0.000296778603374646 0.000179527701824737 0.00531436178760663 0.000715081961226488 -0.00333925497716749 0.000284217065676092 -3.10638396319893e-05 2.00292164014004e-05 0.000715081961226488 0.000451535315884727 -0.000345702936070464 7.7908635452285e-05 0.000184315914700778 -0.000145989419332973 -0.00333925497716749 -0.000345702936070464 0.00217777367620774 -0.000102196213565638 -2.65644410835222e-05 -0.000363004814559624 0.000284217065676092 7.7908635452285e-05 -0.000102196213565638 0.000903994735487679 3101 3024 0 572 266 3101 3024 0 483 265 0 0 0 0 0 0 0 0 2744 0 0 0 0 0 2144 +834 838 0.999089814531313 0.0426423687046695 0.00108207718864449 0.554221869410285 -0.0426266974643116 0.997138313276329 0.062435157241123 0.00309881172164339 0.00158340237249023 -0.0624244550452204 0.998048435823249 0.036810874417634 1.77360614644752e-05 -1.69834527620649e-06 1.92151985434698e-06 2.25627025299664e-06 -7.59496499220699e-07 -1.3211603867997e-06 -1.69834527620649e-06 3.061892473559e-05 4.92087228337781e-07 1.61711359429878e-06 1.79056358305804e-09 -1.63825389088628e-05 1.92151985434698e-06 4.92087228337781e-07 9.76538692222592e-06 2.20388296251435e-06 4.93391658883628e-06 -1.17491875526576e-06 2.25627025299664e-06 1.61711359429878e-06 2.20388296251435e-06 3.27397584106341e-05 4.45891928880546e-06 -1.16225646030583e-05 -7.59496499220699e-07 1.79056358305804e-09 4.93391658883628e-06 4.45891928880546e-06 1.48768621786399e-05 -3.25827961621482e-06 -1.3211603867997e-06 -1.63825389088628e-05 -1.17491875526576e-06 -1.16225646030583e-05 -3.25827961621482e-06 7.24711950944558e-05 3448 3380 0 983 259 3448 3380 0 889 248 0 0 0 0 0 0 0 0 2631 0 0 0 0 0 2935 +834 836 0.999318982444565 -0.00722323075161402 -0.0361855808778565 0.284935292316061 0.00994862749480871 0.997080032103654 0.0757128416528308 -0.00212152488855048 0.0355330288172637 -0.0760212767433304 0.996472864329674 0.0222054208809657 3.01050237806657e-05 7.21081382234215e-06 2.3804204417163e-06 -3.54654499928909e-06 -4.89313573379838e-06 4.48727181891808e-06 7.21081382234215e-06 3.56454924745917e-05 2.42750895710395e-06 -1.00271999947678e-06 -2.09862438393508e-06 -1.01726642986053e-05 2.3804204417163e-06 2.42750895710395e-06 1.07475510574031e-05 -6.14716896641173e-07 1.71467382524333e-06 3.11447631650446e-06 -3.54654499928909e-06 -1.00271999947678e-06 -6.14716896641173e-07 4.66963026203448e-05 8.08374028509555e-06 -2.10023298102224e-05 -4.89313573379838e-06 -2.09862438393508e-06 1.71467382524333e-06 8.08374028509555e-06 1.8172448047243e-05 -1.97144357184552e-06 4.48727181891808e-06 -1.01726642986053e-05 3.11447631650446e-06 -2.10023298102224e-05 -1.97144357184552e-06 0.000102389148242071 3343 3266 0 349 203 3343 3266 0 276 192 0 0 0 0 0 0 0 0 2998 0 0 0 0 0 1834 +834 933 0.965994028221569 0.195425625871158 -0.16930552912747 2.41410555187116 -0.190786645942159 0.980671219804373 0.0434098419433167 -0.629169057089427 0.174516455299802 -0.00963241404159362 0.984607141670892 1.05248330452139 2.274574325186e-05 2.01098220902973e-05 -1.5943321863087e-06 -7.57600916507939e-06 -6.37370631076295e-06 -1.01358420756108e-05 2.01098220902973e-05 0.000140297851298668 5.40608719193047e-06 -1.83677852949347e-05 2.06401448079662e-06 -0.000138624254609373 -1.5943321863087e-06 5.40608719193047e-06 1.11894157305108e-05 -1.79362583544499e-06 5.20563072526864e-06 -4.54339556165138e-06 -7.57600916507939e-06 -1.83677852949347e-05 -1.79362583544499e-06 6.98178098064071e-05 6.96991907336954e-06 2.17400131221461e-05 -6.37370631076295e-06 2.06401448079662e-06 5.20563072526864e-06 6.96991907336954e-06 2.30616354990657e-05 -5.69839235604265e-06 -1.01358420756108e-05 -0.000138624254609373 -4.54339556165138e-06 2.17400131221461e-05 -5.69839235604265e-06 0.000276055003124505 978 986 0 1756 0 978 986 0 1756 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1076 +834 936 0.96983110852141 0.029007707149491 -0.242045809445365 2.55979377300025 -0.0167154570846284 0.998471271778607 0.0526850351358173 -0.541874438826419 0.243204059255976 -0.047049679687961 0.96883337741981 0.667179869474499 2.79776345073868e-05 4.14692807230112e-06 -1.36708689508613e-06 -3.71546798052482e-06 -4.32160432733686e-06 1.31046963128715e-05 4.14692807230112e-06 9.94556245906952e-05 1.85639048357839e-06 4.71720938789067e-07 -9.38495784332128e-08 -9.82276301893622e-05 -1.36708689508613e-06 1.85639048357839e-06 1.23708902711929e-05 5.63286368134267e-07 5.36355586611875e-06 6.48151575283672e-06 -3.71546798052482e-06 4.71720938789067e-07 5.63286368134267e-07 5.46336728123971e-05 2.22540586317102e-06 -8.26888776550595e-06 -4.32160432733686e-06 -9.38495784332128e-08 5.36355586611875e-06 2.22540586317102e-06 1.78748031878283e-05 -5.5600296329828e-06 1.31046963128715e-05 -9.82276301893622e-05 6.48151575283672e-06 -8.26888776550595e-06 -5.5600296329828e-06 0.000257334900807661 1744 1737 0 3238 0 1744 1737 0 3238 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 711 +835 838 0.998628441587864 0.0465457959065069 0.0239734130908211 0.408681690727956 -0.0464734258586295 0.998913156511545 -0.0035674132229197 0.00554524912884659 -0.0241134058306956 0.00244839367144967 0.999706231363831 0.0524281558763106 2.62197553757904e-05 -5.5025044022737e-07 8.9453067838964e-07 3.13348576435992e-06 -1.62975470152342e-06 1.0431775166448e-05 -5.5025044022737e-07 4.58595027657346e-05 1.35823323699576e-06 1.47976880835801e-06 -1.20492414829764e-06 -3.49380108398608e-05 8.9453067838964e-07 1.35823323699576e-06 9.17925158454668e-06 3.51237891355561e-06 4.37438909884251e-06 -3.94265788692494e-06 3.13348576435992e-06 1.47976880835801e-06 3.51237891355561e-06 2.93610227714393e-05 2.37449226976312e-06 -1.29024580564954e-05 -1.62975470152342e-06 -1.20492414829764e-06 4.37438909884251e-06 2.37449226976312e-06 1.52121869212382e-05 -5.67965400957457e-07 1.0431775166448e-05 -3.49380108398608e-05 -3.94265788692494e-06 -1.29024580564954e-05 -5.67965400957457e-07 0.000191888414669372 3396 3328 0 710 187 3396 3328 0 636 167 0 0 0 0 0 0 0 0 2967 0 0 0 0 0 3162 +835 936 0.975477179621475 0.0321510376136256 -0.21773971346105 2.42693959129866 -0.0348554288574421 0.999355448686464 -0.0085898928887356 -0.584810362030958 0.217323195073367 0.0159686555803358 0.97596907272826 0.58008790546827 2.80208863917384e-05 1.9474137487238e-05 1.06328971760855e-06 -5.94613481079343e-06 -2.52989607647016e-06 -5.65841486771244e-06 1.9474137487238e-05 0.000187663890207672 6.97447622866052e-06 -2.07407075519961e-05 -7.37971384764488e-06 -0.000136592114004825 1.06328971760855e-06 6.97447622866052e-06 1.22935415997549e-05 5.53771766186763e-07 4.13457079258863e-06 1.06838611780924e-06 -5.94613481079343e-06 -2.07407075519961e-05 5.53771766186763e-07 6.50909268233873e-05 6.86649589860783e-06 1.11353978216408e-05 -2.52989607647016e-06 -7.37971384764488e-06 4.13457079258863e-06 6.86649589860783e-06 2.11624138130666e-05 7.48639419204588e-06 -5.65841486771244e-06 -0.000136592114004825 1.06838611780924e-06 1.11353978216408e-05 7.48639419204588e-06 0.000334513743514713 1900 1893 0 3313 0 1900 1893 0 3312 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 619 +835 861 0.879542302429697 0.441368332236234 -0.177762013759048 2.1972620245747 -0.461119402393128 0.882798683335767 -0.0896402891407698 -0.730510220560783 0.117363686774367 0.160811939854108 0.97998228811907 1.10612834555156 4.06996097435368e-05 3.80287798872104e-06 -9.4040104776088e-07 -4.98010049039212e-06 -5.8694074676177e-06 4.66784316325206e-05 3.80287798872104e-06 0.000201096619384649 -3.60602429134904e-06 -1.16769188553899e-05 -6.55516178661173e-06 2.10730370487536e-05 -9.4040104776088e-07 -3.60602429134904e-06 1.71733304533747e-05 -2.15336056102667e-06 2.93706081913229e-06 9.09224808941751e-06 -4.98010049039212e-06 -1.16769188553899e-05 -2.15336056102667e-06 7.20569018765838e-05 1.18576192499644e-05 -2.22649849526558e-05 -5.8694074676177e-06 -6.55516178661173e-06 2.93706081913229e-06 1.18576192499644e-05 6.29680199485817e-05 4.60260756378554e-05 4.66784316325206e-05 2.10730370487536e-05 9.09224808941751e-06 -2.22649849526558e-05 4.60260756378554e-05 0.000505333392325744 407 420 0 1003 0 407 420 0 1003 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1612 +835 937 0.981240508607048 -0.00568551011924447 -0.192703760324665 2.48181593507292 0.00476837143478806 0.999974992305563 -0.00522277678520795 -0.537798278445137 0.192728635398173 0.00420591704295015 0.981243080668285 0.453307344587554 3.12926858535049e-05 6.73461894998901e-06 -1.18092738857784e-06 4.45104471948967e-06 -2.92722817776822e-07 1.18451948132993e-05 6.73461894998901e-06 4.87885744991812e-05 3.81248780651197e-06 -9.04147981082054e-06 -3.40487243695976e-06 -3.9518498368453e-05 -1.18092738857784e-06 3.81248780651197e-06 1.32924306622586e-05 7.36889326308752e-07 2.93581813788255e-06 -9.79248688255144e-07 4.45104471948967e-06 -9.04147981082054e-06 7.36889326308752e-07 6.28002180231678e-05 7.00866199471723e-06 2.61301665020874e-05 -2.92722817776822e-07 -3.40487243695976e-06 2.93581813788255e-06 7.00866199471723e-06 2.39463259363371e-05 -7.13312796700132e-06 1.18451948132993e-05 -3.9518498368453e-05 -9.79248688255144e-07 2.61301665020874e-05 -7.13312796700132e-06 0.000214699592099735 2603 2591 0 3821 0 2603 2591 0 3820 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 574 +835 837 0.999877648973624 0.0093826742757788 0.0125160899011575 0.277668847540777 -0.00938507648935145 0.999955950327269 0.00013320802070892 0.0078568506885222 -0.0125142887240243 -0.000250656183640828 0.999921661806168 0.0177567617245344 1.64483550471433e-05 5.55244622309362e-06 -7.3091452839843e-07 3.98675515948659e-07 7.94170905906373e-07 5.38183469689891e-06 5.55244622309362e-06 5.19530697778286e-05 -1.83254132290672e-06 8.80046215159259e-06 -7.01347758108342e-07 -2.11588443146721e-05 -7.3091452839843e-07 -1.83254132290672e-06 9.79337405241435e-06 1.0757957948215e-06 3.23191551907179e-06 -2.05646584385662e-08 3.98675515948659e-07 8.80046215159259e-06 1.0757957948215e-06 4.62824913480341e-05 4.98754244148956e-06 -1.39808126749634e-05 7.94170905906373e-07 -7.01347758108342e-07 3.23191551907179e-06 4.98754244148956e-06 1.69944523620744e-05 1.46733109492996e-06 5.38183469689891e-06 -2.11588443146721e-05 -2.05646584385662e-08 -1.39808126749634e-05 1.46733109492996e-06 0.000111350051178625 3514 3437 0 379 199 3514 3437 0 310 174 0 0 0 0 0 0 0 0 3124 0 0 0 0 0 3702 +835 839 0.99440238534967 0.103848613089583 0.0194772064284721 0.537257883590452 -0.103363034202478 0.994342592518338 -0.0244722672502362 -0.00379839331849274 -0.0219084269481965 0.0223220577743146 0.999510753601669 0.0860140990745381 2.23686775989278e-05 1.14726324195126e-06 2.18717846557962e-06 6.99741544485026e-06 -2.71807276706154e-07 -3.0806058057904e-06 1.14726324195126e-06 3.45432716573303e-05 -1.76668994898652e-07 -1.92173463472552e-06 -2.99516391503148e-06 -1.28130253890592e-05 2.18717846557962e-06 -1.76668994898652e-07 1.00872790245286e-05 2.92574137204144e-06 3.88618647445275e-06 -1.05954855796182e-06 6.99741544485026e-06 -1.92173463472552e-06 2.92574137204144e-06 3.49764886062598e-05 6.15634990460362e-06 -8.17651342280469e-06 -2.71807276706154e-07 -2.99516391503148e-06 3.88618647445275e-06 6.15634990460362e-06 1.70654777937398e-05 -1.70366750400877e-06 -3.0806058057904e-06 -1.28130253890592e-05 -1.05954855796182e-06 -8.17651342280469e-06 -1.70366750400877e-06 0.000101154496922301 3460 3396 0 1131 131 3460 3396 0 1039 106 0 0 0 0 0 0 0 0 2711 0 0 0 0 0 3201 +836 934 0.970227698673379 0.136821797417931 -0.199844961103065 2.2057840219702 -0.13965235408585 0.990200593514399 -6.78381382117337e-05 -0.680841768623634 0.197877317359113 0.0279746377109575 0.97982752917016 0.771274468809585 4.41054773005491e-05 2.11840719096581e-05 3.86323287852584e-06 7.17108971641626e-06 -4.65657086689813e-06 1.29377999430478e-05 2.11840719096581e-05 0.000296059939726636 1.96066861743858e-05 -6.63914351460358e-05 -1.42730797911096e-05 -0.000192338011916797 3.86323287852584e-06 1.96066861743858e-05 1.47771238540418e-05 -2.30912872571135e-06 1.01048759435039e-07 -1.68622728783189e-05 7.17108971641626e-06 -6.63914351460358e-05 -2.30912872571135e-06 9.30625585339381e-05 5.91219553107433e-06 0.000119672322581991 -4.65657086689813e-06 -1.42730797911096e-05 1.01048759435039e-07 5.91219553107433e-06 2.96774329480651e-05 1.62309176593349e-05 1.29377999430478e-05 -0.000192338011916797 -1.68622728783189e-05 0.000119672322581991 1.62309176593349e-05 0.000489534253356734 1357 1360 0 2559 0 1357 1360 0 2559 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 754 +836 838 0.99799094716689 0.0511686746582037 0.0373608900677877 0.276270001808841 -0.0503986881989111 0.998502682479623 -0.0212688812311932 0.00144461620544837 -0.0383932494165753 0.0193432110757384 0.999075471916169 0.0156267794763 3.33435867852032e-05 2.32839702486239e-06 5.26332624878407e-07 -1.74551592764478e-07 -9.56512220505938e-07 3.10270349651256e-05 2.32839702486239e-06 4.23413187138776e-05 2.84968020386431e-07 4.50836447126807e-06 -2.39350908435716e-06 -1.74423917537567e-05 5.26332624878407e-07 2.84968020386431e-07 1.23108459879751e-05 -5.62587814731016e-06 7.64278824549224e-07 -1.95283579204708e-06 -1.74551592764478e-07 4.50836447126807e-06 -5.62587814731016e-06 6.06657268898049e-05 1.78019830609563e-05 -1.32242014393984e-05 -9.56512220505938e-07 -2.39350908435716e-06 7.64278824549224e-07 1.78019830609563e-05 2.17226788381022e-05 2.59541711098687e-06 3.10270349651256e-05 -1.74423917537567e-05 -1.95283579204708e-06 -1.32242014393984e-05 2.59541711098687e-06 0.00022986575085199 3389 3321 0 505 99 3388 3321 0 424 82 0 0 0 0 0 0 0 0 3289 0 9 2 0 0 2190 +836 936 0.977613500534641 0.0368075345684772 -0.207164304288639 2.29364970723132 -0.0426329868702869 0.99880907747365 -0.0237245692638271 -0.606211255533034 0.206044344748706 0.0320254922714163 0.978018453732776 0.545857063670627 3.04677139421935e-05 -2.57744077235162e-05 -7.16328085011953e-07 -1.85315322418106e-06 -2.74800638685941e-06 6.75494154231325e-05 -2.57744077235162e-05 0.000248784929382533 -5.00622606496784e-06 -6.88406492954868e-06 -3.73435244490878e-07 -0.00024117490879578 -7.16328085011953e-07 -5.00622606496784e-06 1.15006277122131e-05 2.35026980899734e-06 4.83088541370408e-06 1.33390387006739e-05 -1.85315322418106e-06 -6.88406492954868e-06 2.35026980899734e-06 4.82916520071622e-05 3.03284933073826e-06 -1.53094430121977e-07 -2.74800638685941e-06 -3.73435244490878e-07 4.83088541370408e-06 3.03284933073826e-06 1.83394327312902e-05 -3.45760332482877e-06 6.75494154231325e-05 -0.00024117490879578 1.33390387006739e-05 -1.53094430121977e-07 -3.45760332482877e-06 0.000510647710811061 2022 2015 0 3232 0 2022 2015 0 3204 0 0 0 0 0 0 0 0 0 8 0 0 0 0 0 621 +836 932 0.952087476420797 0.294153808424319 -0.0836837752025332 2.12548007756425 -0.297007787936804 0.954580736931397 -0.0237063405948177 -0.754772130736709 0.0729096094322659 0.047425242951197 0.996210336818211 0.993919652323672 3.04516459485781e-05 -2.99702972333158e-05 -2.41678850609666e-06 1.84400052569425e-06 -6.71464841648015e-06 2.51611505223177e-05 -2.99702972333158e-05 0.000218345149983133 2.0728525530487e-06 3.67809814830907e-07 -1.1615853544411e-05 -0.000174237174165983 -2.41678850609666e-06 2.0728525530487e-06 1.31722615284591e-05 -9.34190430967398e-07 7.65176367527022e-06 -1.63943623052631e-06 1.84400052569425e-06 3.67809814830907e-07 -9.34190430967398e-07 6.38216086202685e-05 -1.30006200445666e-07 8.75449271441477e-06 -6.71464841648015e-06 -1.1615853544411e-05 7.65176367527022e-06 -1.30006200445666e-07 2.76860569314034e-05 4.92797187257907e-06 2.51611505223177e-05 -0.000174237174165983 -1.63943623052631e-06 8.75449271441477e-06 4.92797187257907e-06 0.000196625716414811 1032 1047 0 1896 0 1032 1047 0 1896 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1093 +836 839 0.993377210893231 0.109435477499573 0.0350084724377545 0.406081545136726 -0.108234972554568 0.993525531520595 -0.0345283786591837 -0.00715792760140616 -0.0385604407922979 0.0305105634356475 0.998790367356806 0.037961423597423 2.94519534294785e-05 2.67355613056306e-06 3.79435566132111e-06 1.332326996283e-07 -1.72797368603668e-06 4.60613625165408e-06 2.67355613056306e-06 7.93312607840237e-05 -1.46412833518768e-06 5.46746814490244e-06 -3.98828098901619e-06 -2.17195794166374e-05 3.79435566132111e-06 -1.46412833518768e-06 1.12468369136824e-05 -2.03353123883061e-06 9.24619929849226e-07 2.34908996346045e-06 1.332326996283e-07 5.46746814490244e-06 -2.03353123883061e-06 4.3389701054688e-05 1.53604139819438e-05 -2.3764204107752e-05 -1.72797368603668e-06 -3.98828098901619e-06 9.24619929849226e-07 1.53604139819438e-05 2.0959338440518e-05 -7.20855617172102e-06 4.60613625165408e-06 -2.17195794166374e-05 2.34908996346045e-06 -2.3764204107752e-05 -7.20855617172102e-06 0.000198054328062621 3372 3319 0 896 33 3360 3312 0 808 19 0 0 0 0 0 0 0 0 2953 0 55 38 0 0 2489 +836 840 0.98986558821034 0.14112382171918 -0.0158172127876518 0.530741086201889 -0.141858151061248 0.987778178072282 -0.0645796864477255 -0.0145790857380868 0.00651016547263892 0.0661690098730158 0.997787191678638 0.0559353561638119 2.73986496167148e-05 1.36568604011223e-06 1.02950717663075e-06 4.14966073989079e-06 -2.8858913335851e-06 6.33579093874501e-06 1.36568604011223e-06 4.34274901844343e-05 9.60325035377416e-07 -2.65194917956864e-06 -3.51479192563341e-06 -3.07177857254648e-05 1.02950717663075e-06 9.60325035377416e-07 1.02666446851e-05 3.91229893463302e-07 5.20118875955723e-06 9.93518510014381e-07 4.14966073989079e-06 -2.65194917956864e-06 3.91229893463302e-07 3.7467895945779e-05 7.44754201658486e-06 -6.04433603353152e-06 -2.8858913335851e-06 -3.51479192563341e-06 5.20118875955723e-06 7.44754201658486e-06 1.59380355875013e-05 3.698157464426e-06 6.33579093874501e-06 -3.07177857254648e-05 9.93518510014381e-07 -6.04433603353152e-06 3.698157464426e-06 0.000152559978273475 3431 3383 0 1246 41 3424 3381 0 1141 27 0 0 0 0 0 0 0 0 2586 0 49 34 0 0 2941 +837 932 0.9546627096303 0.279838027755238 -0.101537131451462 1.98117900989261 -0.282369110267387 0.959240679429466 -0.0111805408858425 -0.716478241151308 0.0942698064500889 0.0393445949242629 0.994768921127972 1.03405093150595 5.75925857810582e-05 1.43067517193855e-05 9.8692608432363e-07 -6.72312578473484e-06 -1.66694479276424e-05 -2.12581044988653e-05 1.43067517193855e-05 4.88860017451759e-05 1.43390286701938e-06 -1.80042703751949e-06 -2.22133643176367e-06 -4.4948548931987e-05 9.8692608432363e-07 1.43390286701938e-06 1.53604950023373e-05 -5.30247929811439e-06 3.30328759828466e-06 -4.74326032238478e-06 -6.72312578473484e-06 -1.80042703751949e-06 -5.30247929811439e-06 8.51372580627083e-05 7.54530749606432e-06 3.44600068796437e-05 -1.66694479276424e-05 -2.22133643176367e-06 3.30328759828466e-06 7.54530749606432e-06 3.29224908419339e-05 8.11035300960485e-06 -2.12581044988653e-05 -4.4948548931987e-05 -4.74326032238478e-06 3.44600068796437e-05 8.11035300960485e-06 0.000114185061816503 944 959 0 1503 0 944 959 0 1503 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1077 +837 936 0.975261194789579 0.0230173721740623 -0.219854048213363 2.16329596514981 -0.0258437133834 0.9996161005334 -0.00998769407603068 -0.572122194204766 0.219539755889816 0.0154224554659888 0.975481646906409 0.556582866467141 3.05283455064542e-05 4.83612254823284e-07 -1.24640094089224e-06 1.33530775529127e-05 -1.01803609493613e-06 4.64385119817995e-05 4.83612254823284e-07 0.000363034223128785 5.02181007112116e-06 -4.54539903673538e-05 4.01261462515289e-06 -0.000466174468880641 -1.24640094089224e-06 5.02181007112116e-06 1.1419132897991e-05 4.80557484910593e-06 3.80771130459762e-06 -3.27568100416341e-06 1.33530775529127e-05 -4.54539903673538e-05 4.80557484910593e-06 7.14921320565912e-05 6.43839509454814e-07 0.000122909213300506 -1.01803609493613e-06 4.01261462515289e-06 3.80771130459762e-06 6.43839509454814e-07 1.98707734715971e-05 -6.2152519459054e-06 4.64385119817995e-05 -0.000466174468880641 -3.27568100416341e-06 0.000122909213300506 -6.2152519459054e-06 0.00106353686177822 1953 1946 0 2797 0 1953 1946 0 2753 0 0 0 0 0 0 0 0 0 99 0 0 0 0 0 656 +837 935 0.970504341139602 0.0720751506114645 -0.230057593861888 2.11651751633383 -0.0749131352556612 0.997183515190506 -0.00361375130208115 -0.609616705133663 0.229149178474097 0.0207414969720362 0.973170305911563 0.70578387819013 2.42650106474373e-05 -4.59188686342322e-07 -2.6723599029392e-06 6.09374935716422e-06 -2.07674446728306e-06 8.20234436535697e-06 -4.59188686342322e-07 4.40870321117e-05 -7.38128536246111e-07 -6.26874057465872e-06 -2.67050914250244e-07 -4.00638403739637e-05 -2.6723599029392e-06 -7.38128536246111e-07 1.17764597332111e-05 1.65192340649523e-06 5.29864780589788e-06 -1.4213539938143e-06 6.09374935716422e-06 -6.26874057465872e-06 1.65192340649523e-06 5.92837483882696e-05 3.51857537167959e-06 1.88134719821761e-05 -2.07674446728306e-06 -2.67050914250244e-07 5.29864780589788e-06 3.51857537167959e-06 1.9411822311579e-05 -5.4665964746896e-07 8.20234436535697e-06 -4.00638403739637e-05 -1.4213539938143e-06 1.88134719821761e-05 -5.4665964746896e-07 0.000104024797157054 1488 1486 0 2357 0 1488 1486 0 2325 0 0 0 0 0 0 0 0 0 51 0 0 0 0 0 735 +837 937 0.978885336879257 -0.0139541225847488 -0.203933272679261 2.21468230810335 0.0135363609275846 0.999902450336567 -0.00344336227651109 -0.525545234130891 0.203961428156458 0.000610142457909872 0.97897873498384 0.452613948608228 2.3207807133522e-05 1.42909954473263e-06 -1.32392688965098e-06 7.63193326971638e-07 -1.63433107759166e-06 8.82268410872295e-07 1.42909954473263e-06 0.000160696747586642 -8.86994192584e-07 6.04506396066595e-06 -4.72129265386338e-06 -0.00015246163905792 -1.32392688965098e-06 -8.86994192584e-07 1.21046814386554e-05 -6.57336537006842e-07 3.61191602110019e-06 5.6879661308504e-07 7.63193326971638e-07 6.04506396066595e-06 -6.57336537006842e-07 7.51478277444391e-05 6.66524875320372e-06 -6.93098782587137e-06 -1.63433107759166e-06 -4.72129265386338e-06 3.61191602110019e-06 6.66524875320372e-06 1.80797203788259e-05 -2.77649163318373e-06 8.82268410872295e-07 -0.00015246163905792 5.6879661308504e-07 -6.93098782587137e-06 -2.77649163318373e-06 0.000246037123621097 2445 2435 0 3475 0 2445 2435 0 3426 0 0 0 0 0 0 0 0 0 123 0 0 0 0 0 590 +837 934 0.970718750604181 0.122268320619945 -0.206774188423596 2.07233213873731 -0.123128245866391 0.992352146615462 0.00875512293175693 -0.644566143339683 0.206263283924512 0.0169609811173428 0.978349519764901 0.796493641850235 3.58187586864393e-05 -1.42435399578854e-05 -4.59670186170042e-07 3.22071952527576e-06 -8.11531293099407e-06 6.57418095892302e-05 -1.42435399578854e-05 0.000310817434056352 1.08751715370893e-06 -6.02578055894954e-06 1.54782016041115e-05 -0.000472331530939246 -4.59670186170042e-07 1.08751715370893e-06 1.22652840954818e-05 6.10637281747632e-07 2.56657778912666e-06 2.72636861381958e-06 3.22071952527576e-06 -6.02578055894954e-06 6.10637281747632e-07 5.87195954932797e-05 2.74589885502771e-06 1.1450348508963e-06 -8.11531293099407e-06 1.54782016041115e-05 2.56657778912666e-06 2.74589885502771e-06 2.36044653775017e-05 -3.4937096152408e-05 6.57418095892302e-05 -0.000472331530939246 2.72636861381958e-06 1.1450348508963e-06 -3.4937096152408e-05 0.0011044010398797 1197 1199 0 2243 0 1197 1199 0 2216 0 0 0 0 0 0 0 0 0 17 0 0 0 0 0 931 +837 841 0.984736632814663 0.160558002883481 -0.0671929438476054 0.519431898710217 -0.163864581932655 0.985364540922062 -0.0469587082604587 -0.0321579925634728 0.0586699478513103 0.0572525039061424 0.996634330141001 0.0793566279736027 3.7442513593793e-05 1.90946950242028e-05 1.59531872783733e-06 5.42412546348208e-06 -6.2961102738606e-06 -3.06011166680977e-05 1.90946950242028e-05 6.64276492719337e-05 3.07376275193977e-06 5.94595443084594e-06 -5.45448032999668e-06 -6.16534792886921e-05 1.59531872783733e-06 3.07376275193977e-06 9.37990143831887e-06 3.43320900322233e-06 4.42321838101041e-06 -6.50418810059017e-06 5.42412546348208e-06 5.94595443084594e-06 3.43320900322233e-06 2.79723420872178e-05 1.44715484184182e-06 -1.48164837006572e-05 -6.2961102738606e-06 -5.45448032999668e-06 4.42321838101041e-06 1.44715484184182e-06 1.4922612706897e-05 1.73120005227687e-05 -3.06011166680977e-05 -6.16534792886921e-05 -6.50418810059017e-06 -1.48164837006572e-05 1.73120005227687e-05 0.000266285112814836 3319 3286 0 1286 12 3300 3269 0 1185 6 0 0 0 0 0 0 0 0 2561 0 112 101 0 0 2502 +837 839 0.995588717399188 0.0936376035556618 0.0059249462269733 0.261751039599452 -0.0934824697119962 0.995365685018555 -0.0225428690296621 -0.00810629972674315 -0.00800834839311608 0.0218895474575309 0.999728320129083 0.0655520454756225 2.22911979915381e-05 6.12164943952109e-06 6.95284381499852e-07 -3.2184685209038e-06 -4.05890705908904e-06 1.89283757803337e-05 6.12164943952109e-06 5.91506312747382e-05 6.80239378098281e-07 -1.59101188315711e-06 -8.69815528046153e-06 -7.81246881825136e-06 6.95284381499852e-07 6.80239378098281e-07 1.02488806198562e-05 -3.18081248439104e-07 1.18456953563401e-06 4.63523094791134e-06 -3.2184685209038e-06 -1.59101188315711e-06 -3.18081248439104e-07 4.9649629175124e-05 1.03027498488746e-05 -3.46919789980646e-05 -4.05890705908904e-06 -8.69815528046153e-06 1.18456953563401e-06 1.03027498488746e-05 1.90366166938164e-05 -7.43996346095388e-06 1.89283757803337e-05 -7.81246881825136e-06 4.63523094791134e-06 -3.46919789980646e-05 -7.43996346095388e-06 0.000187856944668027 3444 3397 0 602 0 3425 3378 0 538 0 0 0 0 0 0 0 0 0 3250 0 117 100 0 0 3338 +837 840 0.99167255008041 0.127363575792918 -0.0190806964825499 0.397701289256216 -0.128205659306822 0.990353234954366 -0.0525716552633264 -0.0140286836565221 0.0122009154869859 0.0545801207095097 0.998434849193784 0.0504437952844409 2.41307562454676e-05 1.75968156665268e-05 7.3070988893081e-07 1.32174675543786e-06 -2.8445516643065e-06 -1.89753666712882e-05 1.75968156665268e-05 7.98011539963919e-05 -7.27457603968755e-07 4.08440849189036e-06 -3.60560777395196e-06 -6.239329520458e-05 7.3070988893081e-07 -7.27457603968755e-07 9.74830860255232e-06 1.7593986424543e-06 4.23700173459898e-06 2.43594608606461e-06 1.32174675543786e-06 4.08440849189036e-06 1.7593986424543e-06 3.92340866446087e-05 7.42809644138896e-06 -1.47511747780878e-05 -2.8445516643065e-06 -3.60560777395196e-06 4.23700173459898e-06 7.42809644138896e-06 1.49830135612609e-05 2.1376221375402e-06 -1.89753666712882e-05 -6.239329520458e-05 2.43594608606461e-06 -1.47511747780878e-05 2.1376221375402e-06 0.000126504852703156 3351 3315 0 941 7 3328 3292 0 852 1 0 0 0 0 0 0 0 0 2895 0 111 96 0 0 2337 +838 935 0.969481047832998 0.0343757670718014 -0.242744319255585 1.99546439287199 -0.0381361246857593 0.999214106395211 -0.0108076627802667 -0.531837356157729 0.242182026349158 0.0197351518627294 0.970030097416761 0.695453400962434 3.47174529244064e-05 -7.37004835807005e-07 1.51812723358643e-06 1.14220901108317e-06 -4.51127684732494e-06 4.4835731062636e-05 -7.37004835807005e-07 0.000301810423345208 6.84484731961539e-06 -2.56748393010364e-05 -1.10344259517183e-05 -0.000367197077418354 1.51812723358643e-06 6.84484731961539e-06 1.33164412123708e-05 3.08958189544314e-06 2.5858101108409e-06 2.47313342269934e-06 1.14220901108317e-06 -2.56748393010364e-05 3.08958189544314e-06 8.87187631294627e-05 5.10411122359994e-06 1.81884868380563e-05 -4.51127684732494e-06 -1.10344259517183e-05 2.5858101108409e-06 5.10411122359994e-06 1.84656783155059e-05 7.05880798627253e-06 4.4835731062636e-05 -0.000367197077418354 2.47313342269934e-06 1.81884868380563e-05 7.05880798627253e-06 0.000847378779761453 1146 1144 0 2126 0 1146 1144 0 2100 0 0 0 0 0 0 0 0 0 199 0 0 0 0 0 723 +838 936 0.972022244377627 -0.0145734782440057 -0.234436281677886 2.03803502109017 0.01094107107051 0.999799217063102 -0.016787451380065 -0.494301491403973 0.234633862430195 0.0137527921484872 0.971986528357883 0.564572482284491 2.53119095120505e-05 7.29463139776886e-06 -1.82042982585343e-06 -6.70905532247289e-07 -2.37290717779743e-06 -6.44793886660023e-06 7.29463139776886e-06 0.00022955466793508 7.57967724265408e-06 -2.18007882792284e-05 -2.66238866032678e-06 -0.000282403209690633 -1.82042982585343e-06 7.57967724265408e-06 1.21723553636512e-05 8.99872594269686e-07 3.72882973882972e-06 -1.13242943870677e-05 -6.70905532247289e-07 -2.18007882792284e-05 8.99872594269686e-07 6.51415363143236e-05 1.4685702833041e-06 4.11983471892296e-05 -2.37290717779743e-06 -2.66238866032678e-06 3.72882973882972e-06 1.4685702833041e-06 2.03631644463668e-05 1.52310790612759e-06 -6.44793886660023e-06 -0.000282403209690633 -1.13242943870677e-05 4.11983471892296e-05 1.52310790612759e-06 0.00046189043568646 1694 1688 0 2512 0 1694 1688 0 2474 0 0 0 0 0 0 0 0 0 282 0 0 0 0 0 631 +837 938 0.976662109366788 -0.0547879109590952 -0.207676211781594 2.28050916035382 0.0582167177383237 0.998249482498295 0.0104299792742784 -0.47518042064039 0.206741234162399 -0.0222767929609221 0.978142017598868 0.381279687618995 3.93942970271362e-05 1.3854397979282e-05 1.81940536454967e-06 -1.83664435744769e-06 -1.87141384191789e-06 3.90738020545391e-05 1.3854397979282e-05 6.68828979473823e-05 5.2718367741734e-06 -1.1272911394892e-05 -2.03008303001495e-06 -5.93320801842523e-06 1.81940536454967e-06 5.2718367741734e-06 1.26383112745185e-05 1.20732635498139e-06 4.56332904341098e-06 8.24010110122351e-06 -1.83664435744769e-06 -1.1272911394892e-05 1.20732635498139e-06 5.20616404308582e-05 2.50657143016378e-06 -8.23132887351967e-06 -1.87141384191789e-06 -2.03008303001495e-06 4.56332904341098e-06 2.50657143016378e-06 1.38976636539184e-05 4.03342646441689e-06 3.90738020545391e-05 -5.93320801842523e-06 8.24010110122351e-06 -8.23132887351967e-06 4.03342646441689e-06 0.000371354980495753 2704 2802 0 3665 65 2704 2802 0 3614 65 0 0 0 0 0 0 0 0 134 0 0 0 0 0 432 +838 840 0.994645344026963 0.0887032939539053 -0.0530317381123031 0.253701402567516 -0.0913596219100455 0.994564078328567 -0.049957117439869 -0.00363488203915278 0.0483121008644662 0.0545345738057464 0.997342429243781 0.0652911921143172 2.98720858488866e-05 1.8490856266682e-06 -6.71443349770056e-07 2.638465134738e-07 -6.91146180467156e-06 3.32534921659604e-06 1.8490856266682e-06 4.71281166336036e-05 3.04223984006186e-08 2.56303601658679e-06 -3.69715773362783e-06 -2.92871051760468e-05 -6.71443349770056e-07 3.04223984006186e-08 1.23613149585415e-05 -3.79546712430402e-06 -3.4279630906915e-07 4.44521881425155e-06 2.638465134738e-07 2.56303601658679e-06 -3.79546712430402e-06 5.34585152461001e-05 1.7853458870218e-05 -3.19390833941962e-05 -6.91146180467156e-06 -3.69715773362783e-06 -3.4279630906915e-07 1.7853458870218e-05 2.47797088301917e-05 -7.05379256319572e-06 3.32534921659604e-06 -2.92871051760468e-05 4.44521881425155e-06 -3.19390833941962e-05 -7.05379256319572e-06 0.000137180746447391 3330 3294 0 564 6 3317 3281 0 506 2 0 0 0 0 0 0 0 0 3268 0 106 91 0 0 1904 +838 938 0.971376559148012 -0.0911019525620692 -0.219380980436197 2.16122147293011 0.0946231422246289 0.995497557165114 0.00557446264935785 -0.39433029148545 0.217885385680881 -0.0261734200606251 0.975623344733522 0.360885108828393 2.91197590283843e-05 7.33004950719562e-06 -4.1301495172178e-07 2.37949854414791e-06 -5.48092368991439e-07 -1.71782246408333e-05 7.33004950719562e-06 0.000309208856185102 1.31784171949492e-05 -1.83275740082542e-05 -1.96990589201357e-06 -0.000355839376910239 -4.1301495172178e-07 1.31784171949492e-05 1.27596637335788e-05 1.96590237086559e-06 4.464429691839e-06 -1.8181778033053e-05 2.37949854414791e-06 -1.83275740082542e-05 1.96590237086559e-06 7.60736966362456e-05 1.03539569062524e-06 5.08430329480544e-05 -5.48092368991439e-07 -1.96990589201357e-06 4.464429691839e-06 1.03539569062524e-06 1.53046071329103e-05 -5.48704717849628e-06 -1.71782246408333e-05 -0.000355839376910239 -1.8181778033053e-05 5.08430329480544e-05 -5.48704717849628e-06 0.000607225255992041 2426 2524 0 3443 65 2426 2524 0 3396 65 0 0 0 0 0 0 0 0 345 0 0 0 0 0 412 +838 933 0.973194043321224 0.153865059932687 -0.170935360227188 1.88908291146218 -0.158880734318231 0.987168499255837 -0.0159770566588133 -0.60553413884778 0.166283692244872 0.0427071119240098 0.985152696938156 0.92229051972969 4.04917702781156e-05 1.93861549137436e-05 4.18730878115134e-06 -1.64544046941497e-05 -1.46042107874747e-05 -5.77643556069491e-06 1.93861549137436e-05 0.000149514690783741 7.90347073547262e-06 -2.96556723387258e-05 -2.14552720131769e-05 -0.000209450726371804 4.18730878115134e-06 7.90347073547262e-06 1.26814770231664e-05 -2.82782649125387e-06 1.09274723229783e-06 -1.99288400263508e-06 -1.64544046941497e-05 -2.96556723387258e-05 -2.82782649125387e-06 6.21711327537349e-05 1.26655093577306e-05 2.45418984978509e-05 -1.46042107874747e-05 -2.14552720131769e-05 1.09274723229783e-06 1.26655093577306e-05 2.97311647756205e-05 3.65929175120634e-05 -5.77643556069491e-06 -0.000209450726371804 -1.99288400263508e-06 2.45418984978509e-05 3.65929175120634e-05 0.00072262971887164 964 971 0 1386 0 964 971 0 1371 0 0 0 0 0 0 0 0 0 49 0 0 0 0 0 1146 +838 841 0.989400614016985 0.123360003631741 -0.0766076659792591 0.386232487244801 -0.127167495875353 0.990768426928656 -0.0469718234062558 -0.016611217422768 0.0701060124069612 0.0562159559670848 0.995954272704878 0.0506556675181663 1.8953455378061e-05 8.79774532194388e-06 -5.95935074631412e-07 4.46945531325338e-06 -2.94442641374731e-06 -1.07588422850203e-05 8.79774532194388e-06 5.72198564950375e-05 -1.08179708556311e-06 1.68294815168007e-05 -2.01783376585305e-06 -4.46840916745914e-05 -5.95935074631412e-07 -1.08179708556311e-06 9.63202085623876e-06 2.45763904296524e-06 3.827736259818e-06 -7.47490987563361e-08 4.46945531325338e-06 1.68294815168007e-05 2.45763904296524e-06 3.47667213788516e-05 4.49902989386434e-06 -1.56502140492965e-05 -2.94442641374731e-06 -2.01783376585305e-06 3.827736259818e-06 4.49902989386434e-06 1.39982216486049e-05 2.92897486811514e-06 -1.07588422850203e-05 -4.46840916745914e-05 -7.47490987563361e-08 -1.56502140492965e-05 2.92897486811514e-06 8.55796266306862e-05 3358 3325 0 876 14 3339 3308 0 807 6 0 0 0 0 0 0 0 0 2973 0 99 88 0 0 2801 +838 842 0.983359583690116 0.151408357311469 -0.100396406813418 0.499163123378466 -0.155310192580557 0.987340363474507 -0.0322141387378037 -0.0362859490032044 0.0942479349662002 0.0472706673347302 0.994425869919089 0.113580819676638 2.81718324251598e-05 4.5339620335208e-06 -1.07190741515963e-06 7.98253950698329e-06 -7.2852399260534e-07 -1.68348661371982e-05 4.5339620335208e-06 6.19831974285183e-05 1.07747279602296e-06 7.13054524450509e-07 -2.79615960729686e-06 -2.84121941179983e-05 -1.07190741515963e-06 1.07747279602296e-06 9.86004660520105e-06 3.95443440067553e-06 5.39620536398549e-06 -2.31695516826814e-06 7.98253950698329e-06 7.13054524450509e-07 3.95443440067553e-06 3.11025145751268e-05 1.2531805149805e-06 -9.11165221272474e-06 -7.2852399260534e-07 -2.79615960729686e-06 5.39620536398549e-06 1.2531805149805e-06 1.32053290404396e-05 4.41718609285439e-06 -1.68348661371982e-05 -2.84121941179983e-05 -2.31695516826814e-06 -9.11165221272474e-06 4.41718609285439e-06 0.000143472123730317 3032 3009 0 1151 12 3017 2994 0 1074 4 0 0 0 0 0 0 0 0 2662 0 90 86 0 0 2622 +838 930 0.921749949580985 0.387085840053774 -0.0232719332526557 1.81646395675941 -0.38754947376689 0.921620608405373 -0.0205148615768326 -0.675636627854603 0.0135068808560266 0.0279285981097112 0.999518662945904 1.16018685104544 3.93513258871442e-05 -2.12679281868754e-05 -2.6629549054443e-06 -6.89947559154871e-06 3.54345824835025e-06 3.18017199821219e-05 -2.12679281868754e-05 0.00025637626328833 2.5105398718135e-06 -4.0110772198771e-05 -2.28874290320032e-05 -8.25784508467637e-05 -2.6629549054443e-06 2.5105398718135e-06 1.36904328545335e-05 -2.66511023326625e-06 1.03740205313156e-06 -1.73625270709176e-06 -6.89947559154871e-06 -4.0110772198771e-05 -2.66511023326625e-06 7.38288834886076e-05 1.74714619839191e-05 3.55251122963449e-06 3.54345824835025e-06 -2.28874290320032e-05 1.03740205313156e-06 1.74714619839191e-05 4.47028718349963e-05 2.19040056058658e-05 3.18017199821219e-05 -8.25784508467637e-05 -1.73625270709176e-06 3.55251122963449e-06 2.19040056058658e-05 0.000271912792996466 461 483 0 1097 0 461 483 0 1097 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1029 +839 841 0.994891372130147 0.0667139697726148 -0.0757654531971727 0.25327285785896 -0.0689996268627677 0.997224829497503 -0.0279587361387124 -0.00090418719827086 0.0736899528687131 0.0330436933597617 0.996733617961867 0.0354385748613842 2.05632710286347e-05 1.67213815713466e-07 1.73858003623994e-07 7.00664679713029e-07 -1.2649444274565e-06 -3.79108892430505e-06 1.67213815713466e-07 3.05356654596795e-05 -1.74241673364475e-07 2.55807489829579e-06 1.59044573496701e-06 -2.44916720092438e-05 1.73858003623994e-07 -1.74241673364475e-07 8.91063655356693e-06 1.71752321629595e-06 4.57301623786212e-06 -7.9708311349285e-07 7.00664679713029e-07 2.55807489829579e-06 1.71752321629595e-06 2.94093387876788e-05 6.13070997079766e-06 -9.1397766016999e-06 -1.2649444274565e-06 1.59044573496701e-06 4.57301623786212e-06 6.13070997079766e-06 1.26431194038871e-05 3.32933915767363e-07 -3.79108892430505e-06 -2.44916720092438e-05 -7.9708311349285e-07 -9.1397766016999e-06 3.32933915767363e-07 0.000102071872353515 3430 3391 0 489 48 3425 3387 0 431 37 0 0 0 0 0 0 0 0 3381 0 38 30 0 0 2732 +839 933 0.981932306405447 0.0972748124166667 -0.162316223793502 1.80284366564064 -0.099409618547095 0.995033715174343 -0.00506294446596367 -0.484028635279504 0.161017618221116 0.0211072626279833 0.986725802888904 0.880451373780026 4.38172534947872e-05 -1.79628544891569e-05 2.27791625382526e-07 -4.35143992046331e-06 -5.94570928731714e-06 1.50515238780684e-05 -1.79628544891569e-05 0.000175182770832904 2.32195653526238e-06 1.77178994065994e-05 -3.01590983778195e-06 -0.000126109038371698 2.27791625382526e-07 2.32195653526238e-06 1.17184168691574e-05 8.88509965914951e-07 3.78866449591276e-06 -7.78162066504745e-06 -4.35143992046331e-06 1.77178994065994e-05 8.88509965914951e-07 7.24908927541123e-05 1.2300660757835e-05 5.29580625480353e-05 -5.94570928731714e-06 -3.01590983778195e-06 3.78866449591276e-06 1.2300660757835e-05 2.14341405624312e-05 2.44789561428337e-05 1.50515238780684e-05 -0.000126109038371698 -7.78162066504745e-06 5.29580625480353e-05 2.44789561428337e-05 0.00036294925808961 1036 1044 0 1403 0 1036 1044 0 1387 0 0 0 0 0 0 0 0 0 164 0 0 0 0 0 1109 +839 937 0.971162977440591 -0.109296694465065 -0.211888423062082 1.97530925751327 0.111264501289841 0.993787292791369 -0.00265093174644008 -0.323378566924956 0.210861760405837 -0.0210011729532289 0.977290268412174 0.431981873534437 2.84528080404346e-05 -6.26561561342635e-06 1.11471738901686e-06 -2.75093784096214e-06 3.35413887602207e-08 1.22515624509391e-05 -6.26561561342635e-06 8.28521071762545e-05 2.53674832189788e-06 -4.00197080433977e-05 -4.13864169204198e-07 -8.29948603960023e-05 1.11471738901686e-06 2.53674832189788e-06 1.27660515839566e-05 -1.83852504606082e-06 2.05411224695294e-06 3.11817663943318e-06 -2.75093784096214e-06 -4.00197080433977e-05 -1.83852504606082e-06 8.09245434453148e-05 5.81994610338023e-06 2.27020564211794e-05 3.35413887602207e-08 -4.13864169204198e-07 2.05411224695294e-06 5.81994610338023e-06 1.93306198275662e-05 -4.23661313590114e-06 1.22515624509391e-05 -8.29948603960023e-05 3.11817663943318e-06 2.27020564211794e-05 -4.23661313590114e-06 0.000231733226301342 2431 2423 0 2724 0 2431 2423 0 2674 0 0 0 0 0 0 0 0 0 632 0 0 0 0 0 578 +839 930 0.942266135739716 0.33320419429383 -0.0333090729853505 1.71015334856519 -0.333225686293963 0.942833476210769 0.00506735929597074 -0.54873229909457 0.0330933744435475 0.00632463764314005 0.999432252594753 1.14982500711113 6.03907710348527e-05 -1.71432362751199e-06 -2.8812715934961e-06 8.02706425107408e-06 -9.44925581078667e-06 5.33108124152729e-05 -1.71432362751199e-06 0.000183590527874576 6.58658488558889e-06 -3.98467893465718e-05 -1.84570906349431e-05 -0.000142223686170037 -2.8812715934961e-06 6.58658488558889e-06 1.43219700638367e-05 -9.97321760084493e-06 6.75762635993769e-06 -6.8451156194703e-06 8.02706425107408e-06 -3.98467893465718e-05 -9.97321760084493e-06 8.58608501627956e-05 8.65650707066454e-06 7.26500690600445e-05 -9.44925581078667e-06 -1.84570906349431e-05 6.75762635993769e-06 8.65650707066454e-06 2.99277399316214e-05 2.15488938333535e-05 5.33108124152729e-05 -0.000142223686170037 -6.8451156194703e-06 7.26500690600445e-05 2.15488938333535e-05 0.000484688320715243 471 493 0 1056 0 471 493 0 1056 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1150 +839 934 0.975866585078568 0.0267377589812691 -0.216724480324107 1.84918997082664 -0.0255922709483135 0.999639722057663 0.00809084372527788 -0.448281008448265 0.216862730303764 -0.00234911241500428 0.976199281845699 0.778016659331315 3.13726573086904e-05 -1.5309760272712e-05 -7.64967709297077e-07 8.27383526034372e-06 -2.87601512706263e-06 4.46708232279102e-05 -1.5309760272712e-05 0.000222959508178979 6.27173613104657e-06 -3.67770886853955e-05 -3.03096653521692e-06 -0.000298125534237702 -7.64967709297077e-07 6.27173613104657e-06 1.20312574956826e-05 6.3383626408528e-06 4.41434888324946e-06 -8.49751188800446e-06 8.27383526034372e-06 -3.67770886853955e-05 6.3383626408528e-06 6.66275778908989e-05 4.04098184132652e-06 7.4690283310241e-05 -2.87601512706263e-06 -3.03096653521692e-06 4.41434888324946e-06 4.04098184132652e-06 1.8317776626442e-05 6.55931427368543e-07 4.46708232279102e-05 -0.000298125534237702 -8.49751188800446e-06 7.4690283310241e-05 6.55931427368543e-07 0.000633881367719924 1087 1089 0 1619 0 1087 1089 0 1589 0 0 0 0 0 0 0 0 0 310 0 0 0 0 0 906 +839 936 0.968699100963816 -0.0719477079637093 -0.237582783700045 1.92811421139752 0.0715326254152778 0.997384256707307 -0.0103792087179633 -0.371842208827374 0.237708088404857 -0.00694059011772741 0.971311841231088 0.56449674992351 2.29164988922342e-05 -8.06797842622503e-06 -7.98702092830767e-07 1.2879716429488e-06 -7.63093562059584e-07 2.70322417853242e-05 -8.06797842622503e-06 0.00013720489522432 -1.24826337557452e-06 -1.15983869114044e-05 -2.61251358767781e-06 -0.000198623079701832 -7.98702092830767e-07 -1.24826337557452e-06 1.17230214559622e-05 5.86868052723947e-06 3.99586510542413e-06 8.23564696931003e-06 1.2879716429488e-06 -1.15983869114044e-05 5.86868052723947e-06 5.32401744295118e-05 4.52126098663063e-06 4.45485554057173e-06 -7.63093562059584e-07 -2.61251358767781e-06 3.99586510542413e-06 4.52126098663063e-06 1.72356160730289e-05 2.24497120910586e-06 2.70322417853242e-05 -0.000198623079701832 8.23564696931003e-06 4.45485554057173e-06 2.24497120910586e-06 0.000485508422302619 1696 1690 0 2145 0 1696 1690 0 2098 0 0 0 0 0 0 0 0 0 551 0 0 0 0 0 600 +839 843 0.993621011920222 0.101450646325898 -0.0492448071444179 0.499292163729674 -0.10210401866621 0.994713655237549 -0.0109322210079041 -0.0242151684442209 0.0478754012290626 0.0158905772082967 0.998726907374155 0.0656060727324587 3.42889989149019e-05 -1.34778892926865e-05 1.40804718394186e-06 2.41908556562887e-06 1.8414219803561e-06 2.48380573439871e-05 -1.34778892926865e-05 0.000164376051485886 -1.46790082501744e-06 4.0823502468305e-06 -4.07005032649467e-06 -0.000102264470598945 1.40804718394186e-06 -1.46790082501744e-06 9.17270182472649e-06 2.75745896364092e-06 4.09468992584924e-06 -1.58143728728953e-06 2.41908556562887e-06 4.0823502468305e-06 2.75745896364092e-06 2.49244947574709e-05 1.19386348639948e-06 -1.92800420201411e-06 1.8414219803561e-06 -4.07005032649467e-06 4.09468992584924e-06 1.19386348639948e-06 1.45400032861518e-05 9.92579222178556e-06 2.48380573439871e-05 -0.000102264470598945 -1.58143728728953e-06 -1.92800420201411e-06 9.92579222178556e-06 0.000266021020173803 3183 3158 0 974 135 3183 3158 0 901 125 0 0 0 0 0 0 0 0 2867 0 0 0 0 0 2282 +840 935 0.978244499472408 -0.0561834526234326 -0.199702576105789 1.80326832329311 0.0616674131577333 0.997868547161621 0.0213422758859094 -0.338090249792428 0.198077836737004 -0.0331931052609929 0.979624105642935 0.591307260119898 7.15634911219481e-05 -0.000113113919669914 4.70328065437169e-06 1.55853207354488e-05 6.05457791171123e-06 0.000296442345098027 -0.000113113919669914 0.000439488732767754 -1.43095560357142e-05 -2.87325805264344e-05 -1.09905931947067e-05 -0.000862807448214129 4.70328065437169e-06 -1.43095560357142e-05 1.28547765414893e-05 4.35182414246489e-06 4.94994654476722e-06 3.52394543554584e-05 1.55853207354488e-05 -2.87325805264344e-05 4.35182414246489e-06 6.67918623515313e-05 1.18983851689244e-06 8.93940168539986e-05 6.05457791171123e-06 -1.09905931947067e-05 4.94994654476722e-06 1.18983851689244e-06 1.9627503561321e-05 3.24609090386629e-05 0.000296442345098027 -0.000862807448214129 3.52394543554584e-05 8.93940168539986e-05 3.24609090386629e-05 0.00228511931296477 1426 1424 0 2085 0 1426 1424 0 2038 0 0 0 0 0 0 0 0 0 723 0 0 0 0 0 780 +839 938 0.965165128520655 -0.148965101044648 -0.21509456840763 2.04889902299657 0.154973637312237 0.987854576157314 0.0112475821077084 -0.269290588222264 0.210806656502877 -0.0441897616627694 0.976528452498065 0.338434826096511 2.99738329868393e-05 -3.8516713363005e-06 2.67730521086495e-07 2.36488437898048e-06 -3.21886116076975e-06 -1.0991237040348e-05 -3.8516713363005e-06 0.000158826033783564 -2.49358745456708e-06 8.05847702086869e-07 8.79305789375402e-07 -0.000182500062302595 2.67730521086495e-07 -2.49358745456708e-06 1.2308663928957e-05 4.01819045573095e-06 3.45211680089762e-06 -1.17640057622949e-06 2.36488437898048e-06 8.05847702086869e-07 4.01819045573095e-06 6.16184747032086e-05 5.14422641817808e-07 -4.72302473209208e-06 -3.21886116076975e-06 8.79305789375402e-07 3.45211680089762e-06 5.14422641817808e-07 1.49917974572686e-05 -9.64852437187848e-07 -1.0991237040348e-05 -0.000182500062302595 -1.17640057622949e-06 -4.72302473209208e-06 -9.64852437187848e-07 0.000294616804916299 2452 2553 0 3116 65 2452 2553 0 3055 65 0 0 0 0 0 0 0 0 668 0 0 0 0 0 427 +840 843 0.997417342715572 0.0691060754688221 -0.0195702525150992 0.37256696976248 -0.0687465783448289 0.997462923453528 0.0184830814914227 -0.0154654967148976 0.0207978945108773 -0.0170899581286129 0.999637624799645 0.061791422622401 2.13625187950733e-05 -7.31677037085578e-07 -4.6534928340728e-07 1.21948869602424e-06 -3.18208862287366e-06 -1.4547685380851e-06 -7.31677037085578e-07 2.66334545669838e-05 1.78496233102839e-06 -3.41862306373004e-06 -2.41287088281672e-06 -1.36457286615543e-05 -4.6534928340728e-07 1.78496233102839e-06 1.02100810392518e-05 -1.74026518065526e-06 4.15947296252908e-06 1.91523415341617e-06 1.21948869602424e-06 -3.41862306373004e-06 -1.74026518065526e-06 3.7391194887562e-05 6.81878632796109e-06 -1.47664166183031e-05 -3.18208862287366e-06 -2.41287088281672e-06 4.15947296252908e-06 6.81878632796109e-06 1.51152370275702e-05 -3.60942045873094e-06 -1.4547685380851e-06 -1.36457286615543e-05 1.91523415341617e-06 -1.47664166183031e-05 -3.60942045873094e-06 7.83529750595819e-05 3517 3492 0 639 132 3517 3492 0 586 124 0 0 0 0 0 0 0 0 3204 0 0 0 0 0 2422 +840 844 0.996912662444454 0.0701059915992243 -0.0353594881156254 0.493719740720637 -0.0692976523371662 0.997317033037878 0.0235917568884028 -0.0240041263915451 0.0369185432874429 -0.0210685916571032 0.99909615933959 0.126618539971456 1.95814938381632e-05 -2.00013969930104e-06 -3.31213530719887e-07 -8.23263843606572e-07 -4.12174386040404e-06 1.77985516591054e-05 -2.00013969930104e-06 0.000195288836358306 -1.33506796933224e-06 1.82204771364356e-05 -3.43764155935912e-06 -0.000415227720308093 -3.31213530719887e-07 -1.33506796933224e-06 9.46686415812578e-06 6.3997403226254e-07 3.9632300837109e-06 1.12806742118577e-06 -8.23263843606572e-07 1.82204771364356e-05 6.3997403226254e-07 4.02186837939187e-05 2.19425387849703e-06 -6.55721510390222e-05 -4.12174386040404e-06 -3.43764155935912e-06 3.9632300837109e-06 2.19425387849703e-06 1.45860938006129e-05 1.24332747940219e-05 1.77985516591054e-05 -0.000415227720308093 1.12806742118577e-06 -6.55721510390222e-05 1.24332747940219e-05 0.00121824777489959 3260 3252 0 835 224 3260 3252 0 782 214 0 0 0 0 0 0 0 0 3025 0 0 0 0 0 2513 +840 936 0.975315529757488 -0.105246450665133 -0.194120586327835 1.83164287106675 0.110630469719448 0.993714917283961 0.0170751965431037 -0.300651415782737 0.191103418555307 -0.0381293560098134 0.980829055252113 0.46314639927919 2.56046675833984e-05 -1.01908459808646e-05 -8.00273598338361e-07 5.13442239770995e-06 1.37549631249141e-06 9.32157541292772e-06 -1.01908459808646e-05 0.000107122996077386 1.07758932964676e-06 -1.75119091828267e-05 -3.99566319539804e-06 -9.69303577322952e-05 -8.00273598338361e-07 1.07758932964676e-06 1.01256179787145e-05 1.82178939246854e-06 4.17564513797293e-06 -2.05277910498592e-06 5.13442239770995e-06 -1.75119091828267e-05 1.82178939246854e-06 5.84409693073075e-05 2.76149054097149e-06 2.46729517652341e-05 1.37549631249141e-06 -3.99566319539804e-06 4.17564513797293e-06 2.76149054097149e-06 1.56503138984556e-05 1.18671806355691e-06 9.32157541292772e-06 -9.69303577322952e-05 -2.05277910498592e-06 2.46729517652341e-05 1.18671806355691e-06 0.000152727841406497 2076 2069 0 2397 0 2076 2069 0 2342 0 0 0 0 0 0 0 0 0 908 0 0 0 0 0 645 +840 937 0.971331399419555 -0.140937675625917 -0.1914468179177 1.87372850752063 0.14914414307707 0.988387760639969 0.0290802201317927 -0.255841312256826 0.185125193011259 -0.0567997025192101 0.981072095570083 0.35746155218881 2.89622288976818e-05 -5.93413730212195e-06 2.88549747538864e-07 -1.48920051913512e-06 -2.08239753335257e-06 5.047122282876e-05 -5.93413730212195e-06 8.87694987255589e-05 1.53734306569669e-06 3.02268039166725e-06 6.91216563486411e-07 -9.9887866530857e-06 2.88549747538864e-07 1.53734306569669e-06 1.16178864712355e-05 9.07006257788518e-07 4.84966328087277e-06 7.50662249550708e-06 -1.48920051913512e-06 3.02268039166725e-06 9.07006257788518e-07 6.45231385023469e-05 3.02185035083285e-06 8.70560063844858e-06 -2.08239753335257e-06 6.91216563486411e-07 4.84966328087277e-06 3.02185035083285e-06 1.67713696863966e-05 -5.62758995816845e-06 5.047122282876e-05 -9.9887866530857e-06 7.50662249550708e-06 8.70560063844858e-06 -5.62758995816845e-06 0.000309017722806672 2671 2659 0 2790 0 2671 2659 0 2719 0 0 0 0 0 0 0 0 0 997 0 0 0 0 0 524 +840 932 0.984354027320192 0.156899007622088 -0.0801863473773614 1.68980207211658 -0.1541422963989 0.987257869068652 0.0395228088943238 -0.440799770559924 0.0853656919341293 -0.0265443283815475 0.995996032758856 0.908347492596431 5.66105598243184e-05 -2.99068584809316e-05 -2.91672838481861e-06 1.55875667930919e-05 1.38956420097903e-06 8.17062048342072e-05 -2.99068584809316e-05 0.000282008285494064 1.77625888929875e-06 -6.06627145636772e-05 -1.80075683666375e-05 -0.000419576666213368 -2.91672838481861e-06 1.77625888929875e-06 1.22424956363487e-05 -3.57390028066194e-06 6.31000751797382e-06 -4.26758406937559e-06 1.55875667930919e-05 -6.06627145636772e-05 -3.57390028066194e-06 7.61342749665499e-05 8.43784858945404e-06 7.91393875283222e-05 1.38956420097903e-06 -1.80075683666375e-05 6.31000751797382e-06 8.43784858945404e-06 2.55498971592635e-05 4.65001551394188e-05 8.17062048342072e-05 -0.000419576666213368 -4.26758406937559e-06 7.91393875283222e-05 4.65001551394188e-05 0.00129762736526672 929 944 0 1774 0 929 944 0 1752 0 0 0 0 0 0 0 0 0 210 0 0 0 0 0 972 +840 934 0.981308090795016 -0.00518972517361577 -0.192373328954051 1.75603420792275 0.0123258295971636 0.999278764920784 0.0359169027497495 -0.371592323863167 0.192048183706545 -0.0376167081363536 0.980664304644562 0.741115862927974 4.16381750801447e-05 -2.75841825451314e-05 1.50348844793333e-06 3.1678061087053e-06 -5.48148190745855e-06 8.98496956090211e-05 -2.75841825451314e-05 0.000271134375608706 3.59359987281015e-06 -1.79695835799221e-05 5.53640182629446e-06 -0.000347331969576834 1.50348844793333e-06 3.59359987281015e-06 1.35820780847821e-05 -4.80318230424493e-06 5.56464969047023e-06 8.37323628553832e-06 3.1678061087053e-06 -1.79695835799221e-05 -4.80318230424493e-06 8.09073422639667e-05 1.937137543978e-06 3.15345461954148e-05 -5.48148190745855e-06 5.53640182629446e-06 5.56464969047023e-06 1.937137543978e-06 1.93894274407704e-05 -1.44494302109074e-05 8.98496956090211e-05 -0.000347331969576834 8.37323628553832e-06 3.15345461954148e-05 -1.44494302109074e-05 0.00103859291307658 1061 1064 0 1811 0 1061 1064 0 1773 0 0 0 0 0 0 0 0 0 562 0 0 0 0 0 828 +840 933 0.989881666371334 0.0651593918594398 -0.12604975301213 1.71903076520795 -0.0627548488524857 0.997764876603833 0.0229582220835967 -0.407026660926474 0.127263960049232 -0.0148156899348645 0.99175822648685 0.837566634926619 3.49280129724713e-05 -1.63001618027579e-05 -2.30508269067205e-06 5.26794261293023e-06 -4.66013867127017e-06 2.53971569323925e-05 -1.63001618027579e-05 9.88924776381202e-05 -1.64033099422833e-06 3.39201490382289e-06 -3.61236727797052e-06 -0.000100994797067223 -2.30508269067205e-06 -1.64033099422833e-06 1.26112433999713e-05 -4.31211661012176e-06 5.50663242935446e-06 -6.72745509534947e-07 5.26794261293023e-06 3.39201490382289e-06 -4.31211661012176e-06 6.80811172136407e-05 3.61667277113227e-06 -5.88707518291211e-06 -4.66013867127017e-06 -3.61236727797052e-06 5.50663242935446e-06 3.61667277113227e-06 2.26015721464841e-05 5.49439614401502e-06 2.53971569323925e-05 -0.000100994797067223 -6.72745509534947e-07 -5.88707518291211e-06 5.49439614401502e-06 0.000228471071111854 1043 1051 0 1627 0 1043 1051 0 1604 0 0 0 0 0 0 0 0 0 317 0 0 0 0 0 939 +840 842 0.997042191004013 0.0630045949677095 -0.0440146608628589 0.2497321467391 -0.0624510749326059 0.997952047593575 0.0138410239344231 -0.00925131478831227 0.0447965690391535 -0.0110513219456366 0.998935000731066 0.0333352974546293 2.1535610072737e-05 -3.74048790494811e-06 -1.006915454372e-06 1.61599169527287e-06 -2.77609172163933e-06 -5.98509868675439e-07 -3.74048790494811e-06 2.36649608159836e-05 -1.52263204750873e-07 -5.25616802093247e-07 -3.65132125173262e-07 -1.56084552090603e-05 -1.006915454372e-06 -1.52263204750873e-07 9.28358955605531e-06 2.94933806411698e-06 4.38740585421477e-06 -4.75338095669075e-07 1.61599169527287e-06 -5.25616802093247e-07 2.94933806411698e-06 2.77796939290807e-05 3.74984173087424e-06 -4.27849104787333e-06 -2.77609172163933e-06 -3.65132125173262e-07 4.38740585421477e-06 3.74984173087424e-06 1.53590237006254e-05 -7.83307926822504e-07 -5.98509868675439e-07 -1.56084552090603e-05 -4.75338095669075e-07 -4.27849104787333e-06 -7.83307926822504e-07 5.96744520609465e-05 3378 3349 0 457 54 3376 3348 0 408 44 0 0 0 0 0 0 0 0 3397 0 16 12 0 0 2626 +840 939 0.949485822337585 -0.233490618949993 -0.20966354962718 2.00331332669124 0.243347445093562 0.969686431412749 0.0221414927329649 -0.137742773873528 0.198138068392613 -0.0720441225663622 0.977522864314328 0.229827678695957 2.93067210823266e-05 -1.4879992346797e-05 -1.86691781552783e-06 8.10775289961321e-06 7.26238890756727e-07 2.1879466230104e-05 -1.4879992346797e-05 4.24546912764242e-05 9.48709140107457e-07 -1.43736215662194e-05 -7.63032662523609e-07 -4.15822954487507e-05 -1.86691781552783e-06 9.48709140107457e-07 1.22558428106936e-05 -1.67509483086284e-06 4.9268789896125e-06 -1.74705738434377e-06 8.10775289961321e-06 -1.43736215662194e-05 -1.67509483086284e-06 7.17209059935191e-05 -3.09421382359652e-06 3.01306798928473e-05 7.26238890756727e-07 -7.63032662523609e-07 4.9268789896125e-06 -3.09421382359652e-06 1.68463075997196e-05 -8.02712505360569e-08 2.1879466230104e-05 -4.15822954487507e-05 -1.74705738434377e-06 3.01306798928473e-05 -8.02712505360569e-08 0.000133916775615784 2677 2735 0 2805 392 2677 2735 0 2743 392 0 0 0 0 0 0 0 0 913 0 0 0 0 0 251 +840 866 0.927293394615365 0.334178081378371 -0.168677118273296 1.66628011085637 -0.346181378801698 0.937001913667785 -0.0467532539387729 -0.462033912832511 0.142426869914591 0.101746860930346 0.984561914262965 1.07907506633134 5.97565842759483e-05 -7.33383088269124e-05 3.93632812388683e-06 4.81992845371637e-06 -7.61301652867443e-07 5.35274182016302e-05 -7.33383088269124e-05 0.000233853654049316 -2.01103593786909e-05 -1.46054241888041e-05 -3.28286441561252e-06 -0.000201818065890448 3.93632812388683e-06 -2.01103593786909e-05 1.64704102865839e-05 -6.74363895727455e-06 8.54593528274673e-06 2.33910854747663e-05 4.81992845371637e-06 -1.46054241888041e-05 -6.74363895727455e-06 7.31853051935362e-05 -1.72468082901372e-06 4.59140592807297e-06 -7.61301652867443e-07 -3.28286441561252e-06 8.54593528274673e-06 -1.72468082901372e-06 3.31023009137401e-05 8.06171026657226e-06 5.35274182016302e-05 -0.000201818065890448 2.33910854747663e-05 4.59140592807297e-06 8.06171026657226e-06 0.000368019728029467 214 222 0 812 0 214 222 0 806 0 0 0 0 0 0 0 0 0 14 0 0 0 0 0 1412 +841 932 0.991746505617396 0.121036346330536 -0.0422974167371945 1.60417850080772 -0.119841627813498 0.992347691653885 0.0297328624961661 -0.388580899836906 0.0455725009045616 -0.0244184712084839 0.998662548324079 0.870492664106324 4.70746841702176e-05 -1.81706046180505e-05 4.34768352078928e-07 -1.08878404228405e-05 -9.19600703734202e-06 1.04539662079609e-05 -1.81706046180505e-05 0.000177172562183152 2.43190532811251e-06 -2.34335940138619e-06 -7.23116474347416e-06 -0.000100865727408883 4.34768352078928e-07 2.43190532811251e-06 1.37352282089321e-05 -4.47434231558539e-06 5.98106898722001e-06 2.7375023749159e-06 -1.08878404228405e-05 -2.34335940138619e-06 -4.47434231558539e-06 8.57037643986077e-05 7.46405143804104e-06 -3.74135083648823e-05 -9.19600703734202e-06 -7.23116474347416e-06 5.98106898722001e-06 7.46405143804104e-06 2.44320050923292e-05 -9.66526971263276e-07 1.04539662079609e-05 -0.000100865727408883 2.7375023749159e-06 -3.74135083648823e-05 -9.66526971263276e-07 0.000293975411316294 971 984 0 1692 0 971 984 0 1673 0 0 0 0 0 0 0 0 0 322 0 0 0 0 0 1140 +841 930 0.962550404153344 0.267383738752 0.0447510414988917 1.57739116480592 -0.268915736825783 0.962612497956428 0.0325807499228087 -0.419666849504442 -0.0343663491176954 -0.0433948733042142 0.998466744072747 1.01468796219889 4.86469624409721e-05 -1.944450565413e-05 -3.35512334114596e-06 1.36865582880466e-06 2.9885122604781e-06 1.68425011751972e-05 -1.944450565413e-05 6.56503682101391e-05 1.10915004226048e-06 -9.39811585345482e-06 -7.37574663075795e-06 -4.14912425467681e-05 -3.35512334114596e-06 1.10915004226048e-06 1.28442932801184e-05 -7.11806988377383e-06 6.93007492427617e-06 1.00278331841898e-06 1.36865582880466e-06 -9.39811585345482e-06 -7.11806988377383e-06 6.49084558092773e-05 -7.53882406866097e-07 -8.25441393843786e-06 2.9885122604781e-06 -7.37574663075795e-06 6.93007492427617e-06 -7.53882406866097e-07 3.13874629925419e-05 2.51243429472697e-06 1.68425011751972e-05 -4.14912425467681e-05 1.00278331841898e-06 -8.25441393843786e-06 2.51243429472697e-06 0.000172051771785619 694 716 0 1574 0 694 716 0 1569 0 0 0 0 0 0 0 0 0 109 0 0 0 0 0 1148 +841 936 0.976214997114045 -0.140853840371114 -0.164816489048679 1.72526058107006 0.143770920998203 0.989593737575569 0.00584438418862511 -0.243181798817913 0.162278161454193 -0.0294011939200508 0.9863069340277 0.414339200866006 4.23764234087455e-05 -4.81189104441282e-06 2.09581383609726e-06 3.93813771697204e-06 -3.49999124521657e-06 8.58015642706468e-05 -4.81189104441282e-06 7.5961142220861e-05 4.09523987594384e-07 1.27070646006001e-05 1.65076970670059e-06 6.89780686352286e-05 2.09581383609726e-06 4.09523987594384e-07 1.17724022910453e-05 4.79004641754815e-06 4.37151689730454e-06 1.16846541237163e-05 3.93813771697204e-06 1.27070646006001e-05 4.79004641754815e-06 4.8083921452391e-05 1.38411104101798e-06 4.93990909893926e-05 -3.49999124521657e-06 1.65076970670059e-06 4.37151689730454e-06 1.38411104101798e-06 1.65111380939863e-05 -3.86210120766038e-06 8.58015642706468e-05 6.89780686352286e-05 1.16846541237163e-05 4.93990909893926e-05 -3.86210120766038e-06 0.000836510588612843 2081 2073 0 2110 0 2081 2073 0 2062 0 0 0 0 0 0 0 0 0 1214 0 0 0 0 0 656 +841 938 0.964900950949968 -0.220377634222176 -0.14282805463383 1.82142476175571 0.226344551262848 0.973679486324479 0.0267656874471503 -0.139318143783077 0.13317018799066 -0.0581545892044248 0.989385539001353 0.206390039986314 3.93326688633458e-05 -1.4511358880603e-05 5.89175723074505e-07 7.86642738099265e-06 -1.26952993199748e-06 1.95204887714563e-05 -1.4511358880603e-05 7.96171090240061e-05 3.77521077219288e-07 2.60676252440296e-05 -1.70066961719976e-06 -1.66233932795991e-05 5.89175723074505e-07 3.77521077219288e-07 1.18778935984744e-05 5.47491862747831e-07 3.60502407585943e-06 2.98969283286512e-06 7.86642738099265e-06 2.60676252440296e-05 5.47491862747831e-07 7.71518085127631e-05 1.05974280394121e-06 9.14456874106892e-06 -1.26952993199748e-06 -1.70066961719976e-06 3.60502407585943e-06 1.05974280394121e-06 1.40199639196874e-05 -4.26117037771002e-06 1.95204887714563e-05 -1.66233932795991e-05 2.98969283286512e-06 9.14456874106892e-06 -4.26117037771002e-06 0.000191187306108121 2940 3038 0 2404 65 2940 3038 0 2340 65 0 0 0 0 0 0 0 0 1359 0 0 0 0 0 458 +841 935 0.982170007449485 -0.0921285587521488 -0.163873137301177 1.70483595423394 0.095366872993194 0.995370007698843 0.0119877983426857 -0.280495785082858 0.162009987353183 -0.0274021246595361 0.986408580438129 0.520637189075125 3.92740289373715e-05 -1.36117019608432e-05 3.49860843040665e-07 7.84062674930013e-06 8.83101474633186e-07 1.4491740936908e-05 -1.36117019608432e-05 5.24794778267113e-05 2.15315169914087e-06 -2.39996211075814e-06 -1.43649404921404e-06 -3.73541973445047e-05 3.49860843040665e-07 2.15315169914087e-06 1.12270246824853e-05 4.51106481369063e-06 3.77883976003576e-06 -1.65135111474373e-06 7.84062674930013e-06 -2.39996211075814e-06 4.51106481369063e-06 4.85790792561814e-05 2.24647989635885e-06 1.59224737245118e-05 8.83101474633186e-07 -1.43649404921404e-06 3.77883976003576e-06 2.24647989635885e-06 1.60769034033821e-05 2.76980864263519e-06 1.4491740936908e-05 -3.73541973445047e-05 -1.65135111474373e-06 1.59224737245118e-05 2.76980864263519e-06 0.000160660534283237 1733 1731 0 2094 0 1733 1731 0 2051 0 0 0 0 0 0 0 0 0 999 0 0 0 0 0 668 +841 937 0.974824474586088 -0.178547929546076 -0.133558528753375 1.77217408619281 0.182243659258765 0.983125192972789 0.015877770693395 -0.194321031163458 0.12846981127071 -0.0398182344790191 0.990913727725599 0.277124474455854 3.62438364263976e-05 -1.49052889816704e-05 1.08767015838596e-06 1.58998160538124e-06 1.14898085362462e-06 3.870504027305e-05 -1.49052889816704e-05 0.000115199295542977 1.85250919506617e-06 1.94909707236932e-05 1.76613255120246e-06 -0.000100708208587189 1.08767015838596e-06 1.85250919506617e-06 1.23398376972368e-05 -2.4222796758642e-06 1.59806292329482e-06 5.72349023400768e-06 1.58998160538124e-06 1.94909707236932e-05 -2.4222796758642e-06 9.60141855994435e-05 8.16943010541151e-06 -9.33399882832741e-06 1.14898085362462e-06 1.76613255120246e-06 1.59806292329482e-06 8.16943010541151e-06 1.92809307733275e-05 -6.32740255610599e-08 3.870504027305e-05 -0.000100708208587189 5.72349023400768e-06 -9.33399882832741e-06 -6.32740255610599e-08 0.000465169318721799 2766 2754 0 2419 0 2766 2754 0 2359 0 0 0 0 0 0 0 0 0 1374 0 0 0 0 0 602 +841 867 0.940567151939392 0.318840623935002 -0.116936261362155 1.61154887654131 -0.328069804964932 0.942040158231624 -0.0702178278587976 -0.417858997333374 0.0877703581107593 0.10440783882293 0.990654009949707 1.01932659786002 4.07211840671563e-05 -3.30080750336503e-05 4.97217931153107e-06 -1.44063700901732e-05 -1.15892098679847e-06 2.87536964892576e-05 -3.30080750336503e-05 0.000129245271662789 -1.19798816888444e-05 3.8466148716116e-06 8.70246894680337e-06 -7.95124698234878e-05 4.97217931153107e-06 -1.19798816888444e-05 1.76573318320764e-05 -1.19721198217513e-05 5.21820310068018e-06 1.78292453808681e-05 -1.44063700901732e-05 3.8466148716116e-06 -1.19721198217513e-05 0.000111520515345081 8.17065659515319e-06 -2.95074718285445e-05 -1.15892098679847e-06 8.70246894680337e-06 5.21820310068018e-06 8.17065659515319e-06 4.06549602188857e-05 3.21715442706832e-06 2.87536964892576e-05 -7.95124698234878e-05 1.78292453808681e-05 -2.95074718285445e-05 3.21715442706832e-06 0.000206389884039792 273 285 0 876 0 273 285 0 874 0 0 0 0 0 0 0 0 0 47 0 0 0 0 0 1654 +841 844 0.99926817412473 0.0349549376537679 0.0155328205761095 0.375747663729266 -0.0352919118437735 0.999135365182184 0.0219773292434534 -0.0110201791984623 -0.0147511741851193 -0.0225094285997009 0.999637798647228 0.0719802821386281 3.07546538984213e-05 -6.5827907712911e-06 5.39154720258062e-06 1.83566592070635e-06 -2.14563452032593e-06 -1.20561820682915e-07 -6.5827907712911e-06 2.75155807091837e-05 -3.83342637440511e-06 4.94168769805346e-06 1.94375517385888e-06 -1.06414647688864e-05 5.39154720258062e-06 -3.83342637440511e-06 1.12704679037318e-05 -1.030600880321e-06 2.84287794273739e-06 2.21860984747153e-07 1.83566592070635e-06 4.94168769805346e-06 -1.030600880321e-06 3.97348386951937e-05 9.52347950599263e-06 4.27258985423014e-07 -2.14563452032593e-06 1.94375517385888e-06 2.84287794273739e-06 9.52347950599263e-06 1.70261387486955e-05 4.36251695608356e-06 -1.20561820682915e-07 -1.06414647688864e-05 2.21860984747153e-07 4.27258985423014e-07 4.36251695608356e-06 0.00012535236209579 3547 3539 0 549 229 3547 3539 0 503 219 0 0 0 0 0 0 0 0 3320 0 0 0 0 0 2758 +841 939 0.947285442282288 -0.269415616093569 -0.173394107872707 1.88543440732061 0.275601936910287 0.961194616249753 0.0121853216530225 -0.0738671729606205 0.163382567036228 -0.0593307297899847 0.984777132802768 0.157840576668395 3.48870497405195e-05 -1.5142149312534e-05 -1.79423333301486e-06 2.43556519441048e-06 -4.84264222540641e-07 1.34879203494772e-05 -1.5142149312534e-05 8.90877127277568e-05 -1.85489036559989e-06 6.77784089734432e-06 -1.69438662751642e-06 -1.49634978971064e-05 -1.79423333301486e-06 -1.85489036559989e-06 1.1171387442443e-05 3.07849362086495e-06 5.74670809187485e-06 2.02847914672396e-06 2.43556519441048e-06 6.77784089734432e-06 3.07849362086495e-06 5.23434789780581e-05 2.36005324517681e-06 1.99646071404118e-05 -4.84264222540641e-07 -1.69438662751642e-06 5.74670809187485e-06 2.36005324517681e-06 1.55866354553743e-05 2.21543692520375e-07 1.34879203494772e-05 -1.49634978971064e-05 2.02847914672396e-06 1.99646071404118e-05 2.21543692520375e-07 0.000157596257097085 2794 2852 0 2422 392 2794 2852 0 2358 392 0 0 0 0 0 0 0 0 1293 0 0 0 0 0 250 +842 936 0.971947194029442 -0.168558090447219 -0.164032991081314 1.60412869436647 0.169372120732444 0.98551003389966 -0.00911360530666234 -0.199642162762116 0.163192330508789 -0.0189246724642258 0.986412753382291 0.391230990699354 2.61893701290612e-05 -1.73931022987887e-06 3.01807462041433e-07 -2.13146401547954e-07 -4.87852700807432e-07 1.30014590122581e-05 -1.73931022987887e-06 9.72393573484754e-05 2.9301254568851e-06 2.12292598957538e-06 -2.26707808296732e-06 -2.40598215158544e-05 3.01807462041433e-07 2.9301254568851e-06 1.07735118870077e-05 3.73390551496907e-06 4.01762155347655e-06 6.49372057732642e-07 -2.13146401547954e-07 2.12292598957538e-06 3.73390551496907e-06 4.01477226504658e-05 3.09499357134377e-06 1.08091621316139e-05 -4.87852700807432e-07 -2.26707808296732e-06 4.01762155347655e-06 3.09499357134377e-06 1.50034965874936e-05 -1.69570981558381e-06 1.30014590122581e-05 -2.40598215158544e-05 6.49372057732642e-07 1.08091621316139e-05 -1.69570981558381e-06 0.000164492826338093 2289 2281 0 1768 0 2289 2281 0 1716 0 0 0 0 0 0 0 0 0 1574 0 0 0 0 0 627 +842 932 0.994693817800267 0.0938046091532709 -0.04224812577536 1.49599242346682 -0.0931317420401496 0.995497748025113 0.0176270332584864 -0.35391056699092 0.0437114110329966 -0.0135988594569855 0.998951642256508 0.826656683122684 6.36147913528909e-05 -1.24555885548851e-05 1.01744335168255e-06 -2.36221050958811e-06 -7.0104250291927e-06 2.3283645769674e-05 -1.24555885548851e-05 0.000105526307029399 -1.43934458196095e-06 1.50382381676632e-07 1.69751160654428e-07 -4.62579219749649e-05 1.01744335168255e-06 -1.43934458196095e-06 1.44110296008205e-05 -5.94643583801187e-06 6.7939518921835e-06 4.94728016239962e-06 -2.36221050958811e-06 1.50382381676632e-07 -5.94643583801187e-06 6.71373029858321e-05 1.81983732152743e-06 2.19907606913463e-06 -7.0104250291927e-06 1.69751160654428e-07 6.7939518921835e-06 1.81983732152743e-06 2.36867326296175e-05 1.03319578039854e-05 2.3283645769674e-05 -4.62579219749649e-05 4.94728016239962e-06 2.19907606913463e-06 1.03319578039854e-05 0.000234472535769986 1162 1177 0 1649 0 1162 1177 0 1627 0 0 0 0 0 0 0 0 0 537 0 0 0 0 0 1085 +842 931 0.985295145346742 0.169748922039329 0.0194622717745829 1.48141111233891 -0.169889980764052 0.985445807041404 0.00582716230311489 -0.37922050263672 -0.018189859596261 -0.0090479197058153 0.999793610780178 0.927218577604653 5.16267850525465e-05 -2.63636952068045e-05 -2.56721649846064e-06 1.20502554339401e-05 -6.76275062645697e-06 2.85751698866284e-05 -2.63636952068045e-05 0.000110536440993434 5.39325904645942e-07 -2.06941728960492e-06 -4.70316774962799e-06 -7.38534314179876e-05 -2.56721649846064e-06 5.39325904645942e-07 1.52269601161654e-05 -2.77819354524744e-06 8.19177436132352e-06 2.20088293906831e-06 1.20502554339401e-05 -2.06941728960492e-06 -2.77819354524744e-06 6.75491216910464e-05 3.90499368023811e-07 -1.44585363962604e-06 -6.76275062645697e-06 -4.70316774962799e-06 8.19177436132352e-06 3.90499368023811e-07 2.98206193645394e-05 3.40418420303248e-06 2.85751698866284e-05 -7.38534314179876e-05 2.20088293906831e-06 -1.44585363962604e-06 3.40418420303248e-06 0.00019724946275886 903 921 0 1618 0 903 921 0 1602 0 0 0 0 0 0 0 0 0 291 0 0 0 0 0 1300 +842 846 0.99890177570318 0.0450705291491686 -0.0128019490409525 0.48987942220567 -0.0442544418935265 0.997327399266584 0.0581343533966247 -0.0233732384976791 0.0153878806118872 -0.0575039657272879 0.998226681198168 0.120064081205538 1.9825641307305e-05 -2.60006285370451e-06 8.78652012381278e-07 1.71776823259684e-07 -8.49913176378266e-07 1.14159175653332e-05 -2.60006285370451e-06 2.7730210394523e-05 1.96491730443076e-06 -8.33031580946534e-07 -1.19621677253369e-06 -1.29713697740534e-05 8.78652012381278e-07 1.96491730443076e-06 1.08104194230486e-05 1.1753989704006e-06 2.43346875550261e-06 -3.46485007847527e-07 1.71776823259684e-07 -8.33031580946534e-07 1.1753989704006e-06 2.72172164740523e-05 5.3492452113436e-06 9.83383318006891e-06 -8.49913176378266e-07 -1.19621677253369e-06 2.43346875550261e-06 5.3492452113436e-06 1.81010185740844e-05 -1.86863246144295e-06 1.14159175653332e-05 -1.29713697740534e-05 -3.46485007847527e-07 9.83383318006891e-06 -1.86863246144295e-06 0.000118582780441295 3501 3520 0 705 292 3501 3520 0 666 289 0 0 0 0 0 0 0 0 3167 0 0 0 0 0 3043 +842 845 0.999782728155539 0.019631404678813 0.00700745547284956 0.378281695325175 -0.0198617047090737 0.999208468052012 0.0344666514068279 -0.00545073805508633 -0.00632528006627768 -0.0345983427852681 0.999381281347913 0.113253570190566 6.7353930455302e-05 -2.02167460580782e-06 2.41832227870562e-06 -9.43155794770467e-06 -5.50237592450362e-06 -5.58279407697829e-05 -2.02167460580782e-06 3.75872453497558e-05 -1.13548050126743e-06 1.18434394434673e-06 2.14467883470057e-06 -2.10900422520521e-05 2.41832227870562e-06 -1.13548050126743e-06 1.12938115536596e-05 -1.54194318715973e-06 2.71881043522232e-06 -7.12050552431872e-06 -9.43155794770467e-06 1.18434394434673e-06 -1.54194318715973e-06 3.9187669831288e-05 1.10632178229531e-05 2.99689548460075e-05 -5.50237592450362e-06 2.14467883470057e-06 2.71881043522232e-06 1.10632178229531e-05 1.79347864321184e-05 1.03289288174393e-05 -5.58279407697829e-05 -2.10900422520521e-05 -7.12050552431872e-06 2.99689548460075e-05 1.03289288174393e-05 0.000256798488560004 3450 3453 0 470 264 3450 3453 0 431 260 0 0 0 0 0 0 0 0 3397 0 0 0 0 0 2483 +842 935 0.978491998933712 -0.120169218438082 -0.167668622475073 1.57804201204965 0.120678894898624 0.992665601175458 -0.0071839104262722 -0.241673907629341 0.167302158828733 -0.0132046651963026 0.985817236848849 0.523064327383428 3.81389689190286e-05 -7.47594353968821e-06 -2.53041278814355e-06 6.2699671914101e-06 -3.61628198056096e-06 2.08137585404026e-05 -7.47594353968821e-06 4.4815360008193e-05 7.7972297692418e-07 6.37577519680886e-06 2.23127202312736e-07 -7.0139704352836e-06 -2.53041278814355e-06 7.7972297692418e-07 1.34775829072742e-05 4.06755889864795e-06 6.87189397262282e-06 -2.53182328680542e-06 6.2699671914101e-06 6.37577519680886e-06 4.06755889864795e-06 5.8052256755705e-05 1.30156839398425e-06 2.31832459218454e-05 -3.61628198056096e-06 2.23127202312736e-07 6.87189397262282e-06 1.30156839398425e-06 1.7714751047539e-05 -5.32264700764054e-06 2.08137585404026e-05 -7.0139704352836e-06 -2.53182328680542e-06 2.31832459218454e-05 -5.32264700764054e-06 0.000177754176264068 1761 1759 0 1756 0 1761 1759 0 1712 0 0 0 0 0 0 0 0 0 1293 0 0 0 0 0 784 +842 933 0.996511331731197 0.00233432157340784 -0.0834249163865818 1.52499839005804 -0.0022833411755158 0.999997143602633 0.000706498161470121 -0.318239912161616 0.0834263272857701 -0.000513545877102787 0.996513815351418 0.741421818524159 1.82432899688391e-05 -6.81761700688468e-06 -9.20138692624625e-07 1.87155941795438e-06 -4.52472228405379e-06 5.62459984666817e-06 -6.81761700688468e-06 6.10237819767121e-05 2.94811612183423e-06 -1.42196519869527e-05 -6.894818970375e-06 -3.60250874698365e-05 -9.20138692624625e-07 2.94811612183423e-06 1.07880585738162e-05 1.70383748062106e-06 4.05660534441096e-06 -8.12842733259069e-07 1.87155941795438e-06 -1.42196519869527e-05 1.70383748062106e-06 4.59700130842523e-05 1.91308819995929e-06 5.26338007783462e-06 -4.52472228405379e-06 -6.894818970375e-06 4.05660534441096e-06 1.91308819995929e-06 2.20262386865469e-05 3.89624332878036e-06 5.62459984666817e-06 -3.60250874698365e-05 -8.12842733259069e-07 5.26338007783462e-06 3.89624332878036e-06 9.16427868144774e-05 1317 1326 0 1531 0 1317 1326 0 1505 0 0 0 0 0 0 0 0 0 696 0 0 0 0 0 1054 +842 930 0.969389654928287 0.239688677374634 0.0532262609659563 1.47168757037819 -0.240958787454834 0.970353399512534 0.0187920941559331 -0.39430418081702 -0.0471440310783218 -0.0310421969723113 0.99840564017879 0.971789214877674 6.17768150194406e-05 -1.93350235511545e-05 -5.1177598327029e-06 1.85053563833409e-05 -9.26005271637337e-06 2.55382827304137e-05 -1.93350235511545e-05 0.000206541222861642 -8.77390410646365e-07 -2.16548914780733e-05 -1.71950940885337e-05 -0.000193991237807421 -5.1177598327029e-06 -8.77390410646365e-07 1.4253707473583e-05 -8.31734474571742e-06 9.91158027747765e-06 6.29425531395651e-06 1.85053563833409e-05 -2.16548914780733e-05 -8.31734474571742e-06 6.39656919029255e-05 -7.20268594429886e-07 -4.75075331696909e-06 -9.26005271637337e-06 -1.71950940885337e-05 9.91158027747765e-06 -7.20268594429886e-07 2.72736807257299e-05 1.51120579067406e-05 2.55382827304137e-05 -0.000193991237807421 6.29425531395651e-06 -4.75075331696909e-06 1.51120579067406e-05 0.000506410519550919 717 740 0 1594 0 717 740 0 1581 0 0 0 0 0 0 0 0 0 207 0 0 0 0 0 895 +842 937 0.967589377514322 -0.205328007940133 -0.147007502110548 1.64108079453489 0.207805587495917 0.97816895030054 0.00153051410194596 -0.150541287812902 0.143483916614102 -0.0320298895295685 0.989134193044503 0.268823088748073 2.88682488300221e-05 -1.36417845371133e-05 1.27307360184632e-06 3.58277154968978e-07 2.90858295114144e-07 1.83019349803324e-05 -1.36417845371133e-05 4.28223988190558e-05 -1.14884238963251e-06 -4.54658193921645e-06 -1.45639506809213e-06 -2.97696734882919e-05 1.27307360184632e-06 -1.14884238963251e-06 1.13683909183342e-05 -5.46894230735802e-07 2.31347289373711e-06 3.18390497096829e-06 3.58277154968978e-07 -4.54658193921645e-06 -5.46894230735802e-07 5.56226914910261e-05 4.99597853766502e-06 1.01085839513446e-06 2.90858295114144e-07 -1.45639506809213e-06 2.31347289373711e-06 4.99597853766502e-06 1.73289874314901e-05 1.21989271741241e-06 1.83019349803324e-05 -2.97696734882919e-05 3.18390497096829e-06 1.01085839513446e-06 1.21989271741241e-06 0.000175690797483428 2869 2857 0 1999 0 2869 2857 0 1934 0 0 0 0 0 0 0 0 0 1794 0 0 0 0 0 521 +842 938 0.957417400803008 -0.246211258685542 -0.150771140262627 1.70435864376415 0.251245324810029 0.967807200247865 0.0150003303127432 -0.0915029194476876 0.142224144928752 -0.0522421213664753 0.988454881800083 0.169706350461051 3.04673596011404e-05 -1.05603777583195e-05 5.55062617281464e-07 1.52765066816138e-06 1.9703894940039e-06 7.75523975382994e-06 -1.05603777583195e-05 3.86451493344057e-05 -9.11746098619514e-07 -3.54994661374984e-07 -1.22092970556388e-06 -3.64253431465147e-06 5.55062617281464e-07 -9.11746098619514e-07 9.16557066792883e-06 2.35943033247888e-06 2.57408678668714e-06 7.8969465858825e-07 1.52765066816138e-06 -3.54994661374984e-07 2.35943033247888e-06 3.66688126793674e-05 2.04321030342362e-06 7.09000741441217e-06 1.9703894940039e-06 -1.22092970556388e-06 2.57408678668714e-06 2.04321030342362e-06 1.33580920596187e-05 -3.84339679332904e-06 7.75523975382994e-06 -3.64253431465147e-06 7.8969465858825e-07 7.09000741441217e-06 -3.84339679332904e-06 0.000114548249256473 3094 3192 0 2005 65 3094 3192 0 1939 65 0 0 0 0 0 0 0 0 1730 0 0 0 0 0 415 +842 939 0.94086066086861 -0.296958447479365 -0.163085552090085 1.76689732449222 0.300006393062546 0.953917106323178 -0.00619018461884308 -0.0216089291312615 0.157408325546914 -0.0431026070517771 0.986592511786835 0.129343721599342 3.10634192613612e-05 -1.39681179224537e-05 -7.23594463796318e-07 3.97750388690983e-06 2.47481097326825e-06 1.24933778590231e-05 -1.39681179224537e-05 3.35469607339269e-05 3.26684323653086e-07 -1.07203150765769e-05 9.6918629154036e-07 -1.41957851067886e-05 -7.23594463796318e-07 3.26684323653086e-07 1.01858520127811e-05 1.12148608541034e-06 3.32909316871521e-06 -1.93319387731597e-06 3.97750388690983e-06 -1.07203150765769e-05 1.12148608541034e-06 5.4183770067124e-05 2.91755407993754e-07 3.23325271354689e-05 2.47481097326825e-06 9.6918629154036e-07 3.32909316871521e-06 2.91755407993754e-07 1.39552703664489e-05 -1.69707641548257e-06 1.24933778590231e-05 -1.41957851067886e-05 -1.93319387731597e-06 3.23325271354689e-05 -1.69707641548257e-06 0.00012903790399014 3084 3142 0 2009 392 3084 3142 0 1947 392 0 0 0 0 0 0 0 0 1686 0 0 0 0 0 253 +843 846 0.998480324894208 0.0401485318239007 -0.0377509760342869 0.362260990694915 -0.0380949698526548 0.997834079609709 0.0536276313235058 -0.0248274778812241 0.039822281088373 -0.0521080124532664 0.997847153108676 0.0929287251472138 6.16458914412871e-05 -1.84904878376615e-06 6.15317586510096e-07 -4.25582150986224e-06 -2.45187566963645e-06 -4.05576880554412e-05 -1.84904878376615e-06 3.82047464442032e-05 2.11716216590457e-06 -1.36846078038691e-06 -1.58846432586931e-06 -1.93329949224139e-05 6.15317586510096e-07 2.11716216590457e-06 1.13723161977792e-05 -1.91270065524249e-06 1.02200898594534e-06 -1.93177935385077e-06 -4.25582150986224e-06 -1.36846078038691e-06 -1.91270065524249e-06 3.85039309059077e-05 9.79042586249725e-06 1.16042774900421e-05 -2.45187566963645e-06 -1.58846432586931e-06 1.02200898594534e-06 9.79042586249725e-06 2.15385725497504e-05 -3.52639650786751e-07 -4.05576880554412e-05 -1.93329949224139e-05 -1.93177935385077e-06 1.16042774900421e-05 -3.52639650786751e-07 0.000156920641849444 3408 3427 0 509 191 3408 3427 0 482 190 0 0 0 0 0 0 0 0 3373 0 0 0 0 0 1097 +843 935 0.973002421523226 -0.125043599375255 -0.193985530298575 1.44090245623392 0.125644232318178 0.992032202624879 -0.00925396349717419 -0.237063566314291 0.193597041803624 -0.015369034143761 0.980960742432832 0.520277531306585 2.61151149815055e-05 -7.32239422470476e-06 -8.76958086442776e-07 -3.3270728421837e-06 2.15430585912562e-06 1.22916221086982e-05 -7.32239422470476e-06 4.77906823217839e-05 -1.20826248971579e-07 5.75811378360523e-07 -7.48867634513324e-07 -4.53307235837619e-05 -8.76958086442776e-07 -1.20826248971579e-07 1.18037606407799e-05 3.36223343751529e-06 2.7881374458748e-06 2.48574775863615e-06 -3.3270728421837e-06 5.75811378360523e-07 3.36223343751529e-06 4.9532624611365e-05 -6.9020313689167e-07 -6.95584037967539e-06 2.15430585912562e-06 -7.48867634513324e-07 2.7881374458748e-06 -6.9020313689167e-07 1.71668097400397e-05 5.30920883194024e-07 1.22916221086982e-05 -4.53307235837619e-05 2.48574775863615e-06 -6.95584037967539e-06 5.30920883194024e-07 0.000142987222472069 1322 1320 0 1094 0 1322 1320 0 1061 0 0 0 0 0 0 0 0 0 1354 0 0 0 0 0 833 +843 937 0.962319763087769 -0.209726975128918 -0.173075906682515 1.51434357811402 0.212297395364819 0.97719795865663 -0.00373704677896915 -0.144198617745602 0.169913182219668 -0.0331473302181171 0.984901398621911 0.274966430781237 3.3487962033762e-05 -2.33264510174732e-05 1.231645716909e-07 -1.14676443094466e-06 -1.44791299093547e-06 2.74164162430712e-05 -2.33264510174732e-05 7.47041911634151e-05 -1.44908928614226e-06 -2.2818392887912e-06 -2.13752397647834e-06 -0.000111458021483175 1.231645716909e-07 -1.44908928614226e-06 1.05875233966813e-05 9.19288615440013e-07 4.85413489992333e-06 3.90119565047104e-07 -1.14676443094466e-06 -2.2818392887912e-06 9.19288615440013e-07 5.15116568147646e-05 1.33031777428175e-06 6.93370677455429e-06 -1.44791299093547e-06 -2.13752397647834e-06 4.85413489992333e-06 1.33031777428175e-06 1.37624318559693e-05 4.10271484831385e-06 2.74164162430712e-05 -0.000111458021483175 3.90119565047104e-07 6.93370677455429e-06 4.10271484831385e-06 0.000294220439744683 2464 2454 0 1550 0 2464 2454 0 1495 0 0 0 0 0 0 0 0 0 2004 0 0 0 0 0 426 +843 845 0.999741198046068 0.0145049731404746 -0.0175254866867315 0.252584717149669 -0.0140629629884153 0.999586369258942 0.0250863202505223 -0.00731182849456474 0.017882114008113 -0.0248333675911951 0.999531657253877 0.0550816903904945 2.94342267118619e-05 -7.53040691629077e-06 2.61764542617014e-06 -1.98417094119359e-07 -1.90853078759653e-06 1.07851908202547e-05 -7.53040691629077e-06 2.42854379811231e-05 -1.76427419345621e-06 2.21464633655077e-07 -5.29130778656585e-07 -1.24119610391772e-05 2.61764542617014e-06 -1.76427419345621e-06 1.03895340154314e-05 -6.02163946165586e-07 3.2064122747247e-06 1.76802009584759e-07 -1.98417094119359e-07 2.21464633655077e-07 -6.02163946165586e-07 3.47234759926811e-05 9.80811250145143e-06 9.99834556158854e-06 -1.90853078759653e-06 -5.29130778656585e-07 3.2064122747247e-06 9.80811250145143e-06 1.55024716282844e-05 2.73149298228711e-06 1.07851908202547e-05 -1.24119610391772e-05 1.76802009584759e-07 9.99834556158854e-06 2.73149298228711e-06 0.000139826749704821 3430 3433 0 292 180 3430 3433 0 257 179 0 0 0 0 0 0 0 0 3577 0 0 0 0 0 2996 +843 847 0.996854016397206 0.0596166167594816 -0.0522295797313305 0.483819619107456 -0.0576623221561815 0.997606620065657 0.0381587238352094 -0.033257362247438 0.054379468518137 -0.0350269982631704 0.997905798558339 0.135816664487996 1.41059923532603e-05 -3.05050403382148e-06 2.78927731867529e-07 -4.68343906669147e-08 -1.20040345786433e-06 5.20768463815673e-06 -3.05050403382148e-06 3.28496460939878e-05 2.24358460319572e-06 -2.46838849438703e-06 -2.00788486456265e-06 -2.42113077297047e-05 2.78927731867529e-07 2.24358460319572e-06 9.94698089567826e-06 1.09411935504179e-06 3.33118263030335e-06 -1.24028639107287e-06 -4.68343906669147e-08 -2.46838849438703e-06 1.09411935504179e-06 3.00132357016401e-05 1.40052443237081e-07 2.30617094960563e-06 -1.20040345786433e-06 -2.00788486456265e-06 3.33118263030335e-06 1.40052443237081e-07 1.53899068501148e-05 -1.80984779645754e-06 5.20768463815673e-06 -2.42113077297047e-05 -1.24028639107287e-06 2.30617094960563e-06 -1.80984779645754e-06 9.41949730239081e-05 3350 3394 0 724 262 3350 3394 0 691 262 0 0 0 0 0 0 0 0 3168 0 0 0 0 0 2860 +843 931 0.986435470645803 0.164148379310154 0.000609771796384205 1.33932964061323 -0.164149434446021 0.986431807516404 0.00269300779261438 -0.375880517626217 -0.000159445430652529 -0.00275657210487798 0.999996187936427 0.911876121402371 9.49879240369201e-05 -0.000103748081182389 1.79441994151705e-07 1.5738607281958e-05 -2.68280418605951e-06 0.000117163239731743 -0.000103748081182389 0.000582393785607718 -6.29973461224918e-06 -3.3001149491999e-05 -1.30421974732426e-05 -0.000676461601808592 1.79441994151705e-07 -6.29973461224918e-06 1.55279681557105e-05 -5.91249751293145e-06 8.16385880376446e-06 1.15565484314666e-05 1.5738607281958e-05 -3.3001149491999e-05 -5.91249751293145e-06 8.60133814377967e-05 1.58032812339896e-05 5.25242586832947e-05 -2.68280418605951e-06 -1.30421974732426e-05 8.16385880376446e-06 1.58032812339896e-05 3.21542151934471e-05 2.12261897226529e-05 0.000117163239731743 -0.000676461601808592 1.15565484314666e-05 5.25242586832947e-05 2.12261897226529e-05 0.00159314545993426 684 702 0 1206 0 684 702 0 1191 0 0 0 0 0 0 0 0 0 258 0 0 0 0 0 640 +843 938 0.95135936839193 -0.250586051688037 -0.179226066386305 1.57117503635278 0.256189978610684 0.966589494939849 0.00845240388207299 -0.0858357809851626 0.171119978472313 -0.053957195732627 0.983771606622343 0.191078446387194 3.53234599446049e-05 -1.96118142717957e-05 -1.48191514356805e-06 1.13898129269396e-05 -5.63279626560036e-07 2.7787979085252e-05 -1.96118142717957e-05 9.32914917339233e-05 3.57887574860125e-06 1.28846823347718e-06 -6.754229375328e-07 -7.82930251425096e-05 -1.48191514356805e-06 3.57887574860125e-06 1.09020774881114e-05 2.00344266107665e-06 3.72045564578417e-06 -2.07022425942457e-06 1.13898129269396e-05 1.28846823347718e-06 2.00344266107665e-06 5.95330626598432e-05 1.83302327801229e-06 1.12355464264292e-05 -5.63279626560036e-07 -6.754229375328e-07 3.72045564578417e-06 1.83302327801229e-06 1.30792506639084e-05 -6.22063584057191e-06 2.7787979085252e-05 -7.82930251425096e-05 -2.07022425942457e-06 1.12355464264292e-05 -6.22063584057191e-06 0.000256399502893337 2675 2773 0 1683 65 2675 2773 0 1623 65 0 0 0 0 0 0 0 0 2084 0 0 0 0 0 343 +843 895 0.949275373007523 0.313911395033806 -0.0183276367641212 1.33322393027071 -0.313697970569078 0.949425139003968 0.0136194231939825 -0.395159715849362 0.0216760112167689 -0.007179240574383 0.999739270531325 1.02659503681766 7.35910275930325e-05 -6.02802857645214e-05 -4.33362926570119e-06 2.26797914492673e-05 -3.50158890385583e-06 -1.32226865439487e-05 -6.02802857645214e-05 0.000225831421801472 1.86665679804313e-06 -1.7569886378691e-05 -5.51925241337313e-06 3.34219428589442e-05 -4.33362926570119e-06 1.86665679804313e-06 1.24205290467303e-05 -3.83268537687739e-06 7.11169075930538e-06 3.54335355463184e-06 2.26797914492673e-05 -1.7569886378691e-05 -3.83268537687739e-06 4.63588373015524e-05 6.65013957953153e-06 -4.98409719831124e-05 -3.50158890385583e-06 -5.51925241337313e-06 7.11169075930538e-06 6.65013957953153e-06 2.7028853822028e-05 -4.59549711856861e-05 -1.32226865439487e-05 3.34219428589442e-05 3.54335355463184e-06 -4.98409719831124e-05 -4.59549711856861e-05 0.00239162420705968 352 365 0 1158 0 352 365 0 1144 0 0 0 0 0 0 0 0 0 101 0 0 0 0 0 945 +843 939 0.935359968513277 -0.301372873503922 -0.185138111740481 1.64251402683339 0.304282581904754 0.95249055779254 -0.0131851304670523 -0.0140529172177942 0.180315943976728 -0.0440014594308591 0.982624054211852 0.136241268802275 3.53115996383049e-05 -2.07604863497852e-05 -1.31741020644811e-06 8.79020356040946e-06 3.8414814020058e-07 1.89480503776684e-05 -2.07604863497852e-05 4.01111881056241e-05 1.83265622588096e-07 -6.69713375522795e-06 6.94783495382915e-07 -3.76947494388527e-05 -1.31741020644811e-06 1.83265622588096e-07 1.11824851194568e-05 1.99361438114914e-06 3.56613716884618e-06 -6.76039852310702e-07 8.79020356040946e-06 -6.69713375522795e-06 1.99361438114914e-06 5.9971870043016e-05 2.27801744538148e-08 8.950486767754e-06 3.8414814020058e-07 6.94783495382915e-07 3.56613716884618e-06 2.27801744538148e-08 1.34928128180786e-05 -1.18297049793067e-06 1.89480503776684e-05 -3.76947494388527e-05 -6.76039852310702e-07 8.950486767754e-06 -1.18297049793067e-06 9.85061492577272e-05 2753 2811 0 1690 392 2753 2811 0 1636 392 0 0 0 0 0 0 0 0 2042 0 0 0 0 0 236 +843 894 0.949367740631251 0.313690691015775 -0.0172928719060401 1.33501925478136 -0.313526442968835 0.949508889039148 0.0115775297430966 -0.398361477223876 0.0200514988971681 -0.00556956063687829 0.999783435242997 1.02160185733308 9.46556217778418e-05 -0.000137600848658586 -4.47918424630427e-06 3.36038258395043e-05 -5.25738802454636e-06 7.32810928669788e-05 -0.000137600848658586 0.000460826431059272 1.04996186837758e-06 -3.62426791711675e-05 -1.53426634983994e-06 -0.00033649237033937 -4.47918424630427e-06 1.04996186837758e-06 1.33093914214089e-05 -7.47337045992423e-06 8.8911137675344e-06 -1.64259073704977e-06 3.36038258395043e-05 -3.62426791711675e-05 -7.47337045992423e-06 7.37529381519823e-05 7.08687400003817e-06 1.56857039643327e-06 -5.25738802454636e-06 -1.53426634983994e-06 8.8911137675344e-06 7.08687400003817e-06 2.60625814247006e-05 -7.89612547272055e-06 7.32810928669788e-05 -0.00033649237033937 -1.64259073704977e-06 1.56857039643327e-06 -7.89612547272055e-06 0.00120880157247853 334 345 0 1136 0 334 345 0 1128 0 0 0 0 0 0 0 0 0 90 0 0 0 0 0 1318 +844 935 0.976362434091022 -0.127324879008681 -0.174656155005424 1.32978478195245 0.126410214412031 0.991842506396249 -0.0163981766642115 -0.23515756829773 0.175319294397845 -0.00606775832009238 0.984492929035456 0.46326195795783 2.51965782445369e-05 -1.58885874631349e-05 4.18490544145829e-07 2.70884185735131e-06 2.89859043244569e-06 1.87614069149749e-05 -1.58885874631349e-05 4.49293931217261e-05 -1.4728123828238e-06 -1.54228627166433e-06 -1.23982371575033e-06 -4.40876942026118e-05 4.18490544145829e-07 -1.4728123828238e-06 1.02080157857764e-05 2.63059526239355e-06 4.06383947446695e-06 7.65131418974754e-07 2.70884185735131e-06 -1.54228627166433e-06 2.63059526239355e-06 4.24877723014314e-05 1.56566660167366e-06 2.63993929403232e-06 2.89859043244569e-06 -1.23982371575033e-06 4.06383947446695e-06 1.56566660167366e-06 1.52597069940402e-05 3.48301458909616e-06 1.87614069149749e-05 -4.40876942026118e-05 7.65131418974754e-07 2.63993929403232e-06 3.48301458909616e-06 0.000127922012903036 1700 1698 0 1184 0 1700 1698 0 1138 0 0 0 0 0 0 0 0 0 1707 0 0 0 0 0 809 +844 895 0.94983443893833 0.312109142309041 -0.0200604559724444 1.20802056710672 -0.312012575056456 0.950045491885047 0.00785597578525868 -0.398903705415824 0.021510267626117 -0.00120276182753524 0.999767903941029 0.963102885382301 5.72908858426388e-05 -3.88585238580779e-05 -2.47902130813166e-06 -3.26078164868039e-06 -6.17459984621283e-06 4.01127348776862e-05 -3.88585238580779e-05 6.39262826099375e-05 1.65997960978454e-06 3.60417620029306e-06 5.14390524384493e-06 -2.04265630110111e-05 -2.47902130813166e-06 1.65997960978454e-06 1.20880609929788e-05 -7.6270518283524e-06 6.80047033389637e-06 -5.26934546788969e-06 -3.26078164868039e-06 3.60417620029306e-06 -7.6270518283524e-06 6.0301798169882e-05 6.16344698262122e-06 1.38245440506255e-05 -6.17459984621283e-06 5.14390524384493e-06 6.80047033389637e-06 6.16344698262122e-06 2.25433993833285e-05 1.09636874736015e-05 4.01127348776862e-05 -2.04265630110111e-05 -5.26934546788969e-06 1.38245440506255e-05 1.09636874736015e-05 0.000267561066140468 460 480 0 1314 0 460 480 0 1291 0 0 0 0 0 0 0 0 0 308 0 0 0 0 0 1345 +844 936 0.968126280823871 -0.174849152539763 -0.179330081788489 1.35241394678409 0.174029318683815 0.984528759662389 -0.020418561067946 -0.193196949412993 0.180125791092187 -0.0114409463666779 0.983577045345025 0.348218447080758 2.28639939535218e-05 -7.09740122608122e-06 -2.07892437780466e-06 -1.07663330417378e-06 -2.16704310807246e-06 6.7302956502482e-06 -7.09740122608122e-06 0.000115103280447267 2.00306204603252e-06 -2.14349929463123e-05 -1.11225412838711e-06 -0.000158756597651121 -2.07892437780466e-06 2.00306204603252e-06 1.09713931078595e-05 -3.58300566222273e-07 5.7057777429745e-06 -4.25527572989972e-06 -1.07663330417378e-06 -2.14349929463123e-05 -3.58300566222273e-07 6.03852929175996e-05 3.49363090488157e-07 3.87522232303057e-05 -2.16704310807246e-06 -1.11225412838711e-06 5.7057777429745e-06 3.49363090488157e-07 1.62598094209386e-05 1.20251157069365e-06 6.7302956502482e-06 -0.000158756597651121 -4.25527572989972e-06 3.87522232303057e-05 1.20251157069365e-06 0.000381567569101545 2005 1998 0 1254 0 2005 1998 0 1197 0 0 0 0 0 0 0 0 0 2069 0 0 0 0 0 655 +844 934 0.984086177560378 -0.0763682455997435 -0.160444028242315 1.29988017898738 0.0764887247477913 0.997055637318751 -0.00543425039496356 -0.277755051006221 0.160386627001943 -0.00692438841456766 0.987029980661187 0.603968689803117 3.06398084728828e-05 -2.10696461786296e-05 -3.20483875715428e-07 4.41486780066773e-06 -1.51234570962475e-06 2.06990007559093e-05 -2.10696461786296e-05 0.000140697378182482 1.47077651979211e-07 -6.57727892212516e-06 2.00152676192897e-06 -0.000186547430485273 -3.20483875715428e-07 1.47077651979211e-07 1.16119104204715e-05 7.95814947666917e-07 5.93713193347117e-06 -5.98261949703084e-06 4.41486780066773e-06 -6.57727892212516e-06 7.95814947666917e-07 5.07845459039951e-05 4.29620360041716e-06 7.13725103696327e-06 -1.51234570962475e-06 2.00152676192897e-06 5.93713193347117e-06 4.29620360041716e-06 1.62857041948532e-05 -5.54175090207567e-06 2.06990007559093e-05 -0.000186547430485273 -5.98261949703084e-06 7.13725103696327e-06 -5.54175090207567e-06 0.000409318870283517 1301 1304 0 1092 0 1301 1304 0 1053 0 0 0 0 0 0 0 0 0 1348 0 0 0 0 0 836 +844 847 0.997380728154972 0.0578849462490129 -0.0433706825264214 0.359711778495809 -0.0562641788015038 0.997703762549199 0.0377033735753798 -0.0295264360620275 0.0454535508937548 -0.0351644023541014 0.998347354139944 0.0745954301359574 2.64338833548504e-05 -2.90160833869233e-05 -6.11040745438338e-07 2.55873738566693e-06 5.36902429032021e-07 2.55375190534027e-05 -2.90160833869233e-05 0.000112170427112689 6.28775754998329e-06 -8.28003824841188e-06 -3.10689316281831e-06 -8.82899750509019e-05 -6.11040745438338e-07 6.28775754998329e-06 1.01173442129726e-05 1.00969604178394e-07 2.83182709546819e-06 -8.07432015872869e-06 2.55873738566693e-06 -8.28003824841188e-06 1.00969604178394e-07 3.11886856194838e-05 2.42562291866731e-06 9.60888201536385e-06 5.36902429032021e-07 -3.10689316281831e-06 2.83182709546819e-06 2.42562291866731e-06 1.38372858446283e-05 4.36482398038052e-07 2.55375190534027e-05 -8.82899750509019e-05 -8.07432015872869e-06 9.60888201536385e-06 4.36482398038052e-07 0.000217145968092742 3183 3227 0 546 172 3183 3227 0 517 183 0 0 0 0 0 0 0 0 3342 0 0 0 0 0 2414 +844 848 0.994626523517268 0.0875452288064576 -0.0552622079650998 0.475637960046441 -0.0858601421686093 0.995787746620539 0.0321683022115641 -0.0457417790935316 0.057845610920269 -0.0272506255637062 0.997953550373787 0.126453628029691 2.62157887780785e-05 -2.61408857360552e-05 4.1852369252855e-07 1.84919602492529e-06 -4.53681501265994e-07 2.6649880404088e-05 -2.61408857360552e-05 0.000121559833311185 4.39596997408111e-06 -4.65558783638457e-06 1.82681140313874e-06 -0.00013125000483966 4.1852369252855e-07 4.39596997408111e-06 9.84010091431205e-06 3.50064950943575e-06 3.36512877451358e-06 -8.74884134531326e-06 1.84919602492529e-06 -4.65558783638457e-06 3.50064950943575e-06 2.4440408252144e-05 8.52077653054345e-07 8.45297490484858e-06 -4.53681501265994e-07 1.82681140313874e-06 3.36512877451358e-06 8.52077653054345e-07 1.46546881557135e-05 -3.27696322177972e-07 2.6649880404088e-05 -0.00013125000483966 -8.74884134531326e-06 8.45297490484858e-06 -3.27696322177972e-07 0.000234514179276476 3126 3187 0 782 200 3126 3187 0 743 212 0 0 0 0 0 0 0 0 3118 0 0 0 0 0 2346 +844 938 0.954932070080663 -0.253942185245344 -0.153681840450584 1.4501861655457 0.256992128696003 0.966413496063461 -2.03640900496634e-05 -0.0819583856974914 0.148525376012844 -0.0394755769966487 0.988120383101687 0.141902824292526 3.79311182561343e-05 -2.0539208341482e-05 -1.3281077937976e-06 6.48603244586111e-06 4.6735238678356e-07 2.65252241960391e-05 -2.0539208341482e-05 3.65876949155878e-05 1.6653298994488e-06 -9.42643003149804e-06 -1.62187140842147e-07 -2.71855041596267e-05 -1.3281077937976e-06 1.6653298994488e-06 1.12863628456288e-05 5.83104178506708e-07 4.38450546540384e-06 -1.55503887005349e-06 6.48603244586111e-06 -9.42643003149804e-06 5.83104178506708e-07 5.1726994569297e-05 1.64629058175447e-06 9.15327356626167e-06 4.6735238678356e-07 -1.62187140842147e-07 4.38450546540384e-06 1.64629058175447e-06 1.30536721289957e-05 -4.54806596635476e-06 2.65252241960391e-05 -2.71855041596267e-05 -1.55503887005349e-06 9.15327356626167e-06 -4.54806596635476e-06 0.000153262152154796 3056 3154 0 1401 65 3056 3154 0 1339 65 0 0 0 0 0 0 0 0 2339 0 0 0 0 0 453 +844 932 0.995081256820521 0.085640624429118 -0.0497893138322265 1.2338791586556 -0.0853595916349108 0.996320086997011 0.00774753910535186 -0.352747502977733 0.0502695975756168 -0.00345943545371839 0.998729693093145 0.791435499543407 5.25687176315928e-05 -2.41684235278133e-05 7.73837627293271e-07 -1.08396449493105e-05 -5.49188932267143e-06 1.840587921326e-05 -2.41684235278133e-05 0.000145727302998009 -6.66135436569413e-07 3.24738128962687e-06 -2.41343334707586e-06 -6.14341426648201e-05 7.73837627293271e-07 -6.66135436569413e-07 1.34973323919657e-05 -3.33239483453911e-06 4.75732448723471e-06 3.04503527464018e-06 -1.08396449493105e-05 3.24738128962687e-06 -3.33239483453911e-06 8.31952543960644e-05 1.1299674533718e-05 -3.92128162132153e-06 -5.49188932267143e-06 -2.41343334707586e-06 4.75732448723471e-06 1.1299674533718e-05 2.5836458776068e-05 -2.82461952787451e-06 1.840587921326e-05 -6.14341426648201e-05 3.04503527464018e-06 -3.92128162132153e-06 -2.82461952787451e-06 0.00018776403297615 1005 1020 0 1276 0 1005 1020 0 1243 0 0 0 0 0 0 0 0 0 716 0 0 0 0 0 1243 +844 930 0.971886415931708 0.233217475592912 0.032348162320124 1.21108294098652 -0.23364702291066 0.972268495605446 0.0101509180918807 -0.390471069184839 -0.0290837276222489 -0.017423591225462 0.999425112380314 0.942612861562481 3.80531687125067e-05 8.53956364995229e-08 -1.35067137732222e-06 -5.19145438446589e-06 -3.71990910970025e-07 5.14548796775465e-05 8.53956364995229e-08 0.000115474866996221 2.30654259432555e-06 -3.82632695751453e-06 -3.02599553368244e-06 1.7895860730648e-06 -1.35067137732222e-06 2.30654259432555e-06 1.38896284516435e-05 -5.73175184696265e-06 8.08933924756416e-06 2.53321807081497e-06 -5.19145438446589e-06 -3.82632695751453e-06 -5.73175184696265e-06 7.78939052620966e-05 9.6122642451458e-06 -2.60571922384541e-05 -3.71990910970025e-07 -3.02599553368244e-06 8.08933924756416e-06 9.6122642451458e-06 2.82781722922953e-05 1.071831609245e-05 5.14548796775465e-05 1.7895860730648e-06 2.53321807081497e-06 -2.60571922384541e-05 1.071831609245e-05 0.000348338683221581 715 738 0 1351 0 715 738 0 1332 0 0 0 0 0 0 0 0 0 280 0 0 0 0 0 1252 +844 939 0.937326264181694 -0.303888602480799 -0.170502761729705 1.51355922750102 0.305202547768189 0.952095881671584 -0.01910070521774 -0.0117767708067829 0.1681394638715 -0.0341342846164383 0.985172051624856 0.0877876217369841 4.00837100458726e-05 -1.68686100378615e-05 1.57522966123988e-06 3.68489687433883e-06 1.82326531084804e-06 4.13465811118069e-05 -1.68686100378615e-05 0.000109549818331704 -3.25793598844385e-06 1.37350003150229e-05 -1.79406287510631e-06 -4.14958869761872e-05 1.57522966123988e-06 -3.25793598844385e-06 9.94856934232436e-06 4.98241768238791e-06 4.87045914863629e-06 4.91205971957194e-06 3.68489687433883e-06 1.37350003150229e-05 4.98241768238791e-06 4.94683114775782e-05 1.18226249502289e-06 5.11090762729912e-06 1.82326531084804e-06 -1.79406287510631e-06 4.87045914863629e-06 1.18226249502289e-06 1.4689887507485e-05 2.44351795559737e-08 4.13465811118069e-05 -4.14958869761872e-05 4.91205971957194e-06 5.11090762729912e-06 2.44351795559737e-08 0.000221801235172584 2870 2928 0 1372 392 2870 2928 0 1316 392 0 0 0 0 0 0 0 0 2306 0 0 0 0 0 257 +844 937 0.965573280433117 -0.212595701176528 -0.14990432934005 1.39466768231106 0.213410634844871 0.976902690114699 -0.0108182707386386 -0.142066424288514 0.148741860445333 -0.0215453449247338 0.988641318711359 0.2086716996145 3.88716415277953e-05 -2.56243652473606e-05 4.96179143148778e-08 4.76314914334288e-06 -2.44023274543949e-06 3.36145824815944e-05 -2.56243652473606e-05 5.32660328940419e-05 -1.73457151976002e-06 5.76484651636782e-07 -8.77338620076038e-07 -5.87776318013558e-05 4.96179143148778e-08 -1.73457151976002e-06 1.04148532769065e-05 3.61633561232855e-07 3.85854604823532e-06 1.28159573317585e-06 4.76314914334288e-06 5.76484651636782e-07 3.61633561232855e-07 5.92350994256651e-05 3.46433705769521e-07 1.25588557087515e-05 -2.44023274543949e-06 -8.77338620076038e-07 3.85854604823532e-06 3.46433705769521e-07 1.46821949021342e-05 -2.55450637980298e-06 3.36145824815944e-05 -5.87776318013558e-05 1.28159573317585e-06 1.25588557087515e-05 -2.55450637980298e-06 0.000195411686213874 2772 2760 0 1434 0 2772 2760 0 1372 0 0 0 0 0 0 0 0 0 2358 0 0 0 0 0 632 +844 940 0.933466047211029 -0.319356219346566 -0.163256680931856 1.58729305127285 0.310712331434933 0.947405069014649 -0.0766908227861516 0.0648278903406312 0.179161898288911 0.0208624152488843 0.983598380352213 0.0545244095365895 5.06817200255987e-05 -2.29107301939257e-05 3.11695087192694e-08 -9.22011859264656e-06 4.36097222411343e-06 1.0124780747549e-05 -2.29107301939257e-05 4.23579039266878e-05 -3.03223386732021e-06 6.79006121277698e-06 5.6348088583817e-08 6.65347863141258e-06 3.11695087192694e-08 -3.03223386732021e-06 1.57133210932534e-05 -2.11699699025415e-06 3.93332808500458e-06 -3.53258816331751e-06 -9.22011859264656e-06 6.79006121277698e-06 -2.11699699025415e-06 9.62448187254721e-05 3.5173114999509e-06 8.44305407827817e-05 4.36097222411343e-06 5.6348088583817e-08 3.93332808500458e-06 3.5173114999509e-06 1.69204196337143e-05 1.15796018429251e-05 1.0124780747549e-05 6.65347863141258e-06 -3.53258816331751e-06 8.44305407827817e-05 1.15796018429251e-05 0.000309100919995983 2899 2945 0 1501 668 2899 2945 0 1435 668 0 0 0 0 0 0 0 0 2269 0 0 0 0 0 158 +845 848 0.9959342520244 0.0746558972118932 -0.0504129215190494 0.349015114882557 -0.0743695211901112 0.997202282997619 0.00753532363534637 -0.0399494463788671 0.0508344367781546 -0.00375550207336412 0.998700033163925 0.0795519779819739 2.98792496898679e-05 -1.85248897460497e-05 -1.46493748406753e-06 3.29561285931583e-06 2.47838505498033e-06 1.7992314857653e-05 -1.85248897460497e-05 4.06414692964099e-05 2.41677735530762e-06 -3.44733530673753e-07 -4.91595357420691e-07 -2.85750595320298e-05 -1.46493748406753e-06 2.41677735530762e-06 9.71187039181426e-06 3.08379640069297e-07 3.48547139330606e-06 -2.14937675378333e-06 3.29561285931583e-06 -3.44733530673753e-07 3.08379640069297e-07 2.87073670811485e-05 5.65129441097333e-06 1.9880678641614e-06 2.47838505498033e-06 -4.91595357420691e-07 3.48547139330606e-06 5.65129441097333e-06 1.51803376125654e-05 -1.95982678129241e-06 1.7992314857653e-05 -2.85750595320298e-05 -2.14937675378333e-06 1.9880678641614e-06 -1.95982678129241e-06 0.000120782409562343 3330 3391 0 578 138 3330 3391 0 550 153 0 0 0 0 0 0 0 0 3325 0 0 0 0 0 2302 +845 935 0.977348144005342 -0.139004928435881 -0.15958770403715 1.21763211973755 0.134521010962112 0.99015793714984 -0.038618093025235 -0.224301661916101 0.163385137081206 0.0162754222590394 0.986428105647465 0.391299310910987 7.89449771690005e-05 -0.000119541166199805 5.46045007506054e-06 -7.86830574427914e-06 -7.71834230208717e-07 0.000368994660565288 -0.000119541166199805 0.00029841398803462 -1.06056316931415e-05 2.66836539367203e-05 -2.58758621787899e-07 -0.000815324038120857 5.46045007506054e-06 -1.06056316931415e-05 1.22311494572915e-05 2.05112199819837e-06 5.23434556438178e-06 3.27173013507194e-05 -7.86830574427914e-06 2.66836539367203e-05 2.05112199819837e-06 6.76693259157736e-05 3.57443992121487e-06 -9.93687944806892e-05 -7.71834230208717e-07 -2.58758621787899e-07 5.23434556438178e-06 3.57443992121487e-06 1.50240865536708e-05 -5.96559041583015e-06 0.000368994660565288 -0.000815324038120857 3.27173013507194e-05 -9.93687944806892e-05 -5.96559041583015e-06 0.00271272929781773 1416 1414 0 906 0 1416 1414 0 880 0 0 0 0 0 0 0 0 0 1905 0 0 0 0 0 798 +845 847 0.998470538688633 0.0450236153930041 -0.0320851589956258 0.235212608314209 -0.0446651195886682 0.99893227509674 0.0118041036161317 -0.0235833760430602 0.032582364293613 -0.0103529622327744 0.999415431995146 0.0448509865038429 3.42473930222982e-05 -5.89373651754749e-06 9.51063788332761e-09 3.33827133033295e-06 -2.97171634794349e-07 8.16624043588288e-06 -5.89373651754749e-06 2.5387909328209e-05 2.7874675233685e-06 -2.97814391944705e-06 -1.54525749778398e-06 -1.92130118062632e-05 9.51063788332761e-09 2.7874675233685e-06 1.01996298579603e-05 -1.23662807913553e-06 2.8035528795397e-06 -2.19412042203687e-06 3.33827133033295e-06 -2.97814391944705e-06 -1.23662807913553e-06 3.2031426396435e-05 4.90313591077918e-06 5.26082549375366e-06 -2.97171634794349e-07 -1.54525749778398e-06 2.8035528795397e-06 4.90313591077918e-06 1.61777892697543e-05 6.75152774346617e-07 8.16624043588288e-06 -1.92130118062632e-05 -2.19412042203687e-06 5.26082549375366e-06 6.75152774346617e-07 0.00013778294840566 3346 3390 0 357 95 3346 3390 0 335 112 0 0 0 0 0 0 0 0 3532 0 0 0 0 0 2082 +845 938 0.951175228672673 -0.265068166948936 -0.158128274605836 1.32162648673767 0.265581698754693 0.963915286202366 -0.0182669732572995 -0.0645672476694903 0.157264254190388 -0.024620883325797 0.987249596838711 0.0808190434586524 3.25377267785432e-05 -1.67285402796121e-05 -5.86975609445122e-07 5.84324995391496e-06 -4.84186636714492e-07 1.19006299634928e-05 -1.67285402796121e-05 7.15986461621074e-05 2.12326427454043e-06 7.2760296630884e-06 -6.53861945266868e-07 -6.06291278001031e-05 -5.86975609445122e-07 2.12326427454043e-06 1.02171655791605e-05 1.71324081067051e-06 3.62437192768369e-06 -2.8950486189635e-06 5.84324995391496e-06 7.2760296630884e-06 1.71324081067051e-06 5.06273983404974e-05 1.24359755375404e-06 -3.172352461584e-06 -4.84186636714492e-07 -6.53861945266868e-07 3.62437192768369e-06 1.24359755375404e-06 1.3482043856106e-05 -4.87097043749641e-06 1.19006299634928e-05 -6.06291278001031e-05 -2.8950486189635e-06 -3.172352461584e-06 -4.87097043749641e-06 0.000199970864472769 2800 2898 0 1054 65 2800 2898 0 1009 65 0 0 0 0 0 0 0 0 2685 0 0 0 0 0 441 +845 849 0.992374315070951 0.113887666516199 -0.0471467729856011 0.466107307872889 -0.114093527664967 0.993468576015344 -0.00168979732750323 -0.0616196448468216 0.0466463903472092 0.00705605311343636 0.998886543298105 0.140758752093955 2.57657356090944e-05 -1.93149643209149e-05 5.43378476735427e-06 -2.47139363491476e-06 -3.66420340818241e-06 2.28797412817557e-05 -1.93149643209149e-05 5.42343705148861e-05 -2.61543671750288e-06 3.56051985264301e-06 4.55103243058104e-06 -5.70690179241138e-05 5.43378476735427e-06 -2.61543671750288e-06 1.08268508300122e-05 1.89164319697753e-07 3.99226849609404e-06 2.20573085895737e-06 -2.47139363491476e-06 3.56051985264301e-06 1.89164319697753e-07 2.68250514280651e-05 6.2002890462202e-06 -6.3082906027621e-06 -3.66420340818241e-06 4.55103243058104e-06 3.99226849609404e-06 6.2002890462202e-06 1.59426770928133e-05 -6.07786390615105e-06 2.28797412817557e-05 -5.70690179241138e-05 2.20573085895737e-06 -6.3082906027621e-06 -6.07786390615105e-06 0.000143634386908002 3223 3311 0 819 154 3223 3311 0 801 162 0 0 0 0 0 0 0 0 3082 0 0 0 0 0 2377 +845 894 0.953995028692553 0.299800310206297 0.00364132257599164 1.11093718507906 -0.299699902139999 0.95388202042891 -0.0170017575484414 -0.402865436549752 -0.00857052432289529 0.0151282881605643 0.999848829078757 0.930074473306857 0.000100780136985954 -0.000153047944402427 5.35723904982213e-06 -1.490444238451e-05 -1.80973871904944e-05 0.000119776417500541 -0.000153047944402427 0.000376675844414405 -1.15053463085405e-05 3.92543704180082e-05 3.02385331115148e-05 -0.000300646208429031 5.35723904982213e-06 -1.15053463085405e-05 1.45174730092068e-05 -8.36848475758535e-06 8.13976375484724e-06 7.63162677014941e-06 -1.490444238451e-05 3.92543704180082e-05 -8.36848475758535e-06 6.63320605188697e-05 1.05260916764732e-05 -3.5162759843072e-05 -1.80973871904944e-05 3.02385331115148e-05 8.13976375484724e-06 1.05260916764732e-05 2.88027189570222e-05 -2.7108698067127e-05 0.000119776417500541 -0.000300646208429031 7.63162677014941e-06 -3.5162759843072e-05 -2.7108698067127e-05 0.000376219825877449 332 343 0 1049 0 332 343 0 1041 0 0 0 0 0 0 0 0 0 175 0 0 0 0 0 1158 +845 929 0.960006452983655 0.279970604185871 -0.00201767726344765 1.09763498319621 -0.279966454352844 0.960007456521586 0.00211373131050561 -0.400550856478647 0.00252876784985266 -0.00146431374848319 0.99999573055009 0.884297895810104 6.33345794942944e-05 -3.37770667814841e-05 -6.17140070820843e-06 1.83264568384128e-05 2.24487311588225e-06 1.89607452435166e-05 -3.37770667814841e-05 5.30033237370248e-05 5.76164775871611e-06 -1.10969963947194e-05 -2.666935630262e-06 -1.65159165463181e-05 -6.17140070820843e-06 5.76164775871611e-06 1.36124045836221e-05 -5.77070009054777e-06 8.29917245077934e-06 -7.07218463154795e-06 1.83264568384128e-05 -1.10969963947194e-05 -5.77070009054777e-06 5.19495020778163e-05 5.76212367531106e-06 2.09012020130352e-06 2.24487311588225e-06 -2.666935630262e-06 8.29917245077934e-06 5.76212367531106e-06 3.15967999329507e-05 -1.57508321104831e-06 1.89607452435166e-05 -1.65159165463181e-05 -7.07218463154795e-06 2.09012020130352e-06 -1.57508321104831e-06 0.000345018322328711 440 464 0 1113 0 440 464 0 1108 0 0 0 0 0 0 0 0 0 349 0 0 0 0 0 1194 +845 934 0.985314403561591 -0.0882069580916731 -0.146202115847478 1.19020708056949 0.0853843600724857 0.996022156399024 -0.0254828377001317 -0.268556309995834 0.147868310293577 0.0126252329266818 0.988926471637032 0.530529309485096 4.27351643733248e-05 -3.84867805846798e-05 -1.61467122893252e-06 9.02787260799512e-06 2.66158182234474e-07 5.9573412381954e-05 -3.84867805846798e-05 0.000235884661905588 5.90044711875908e-06 -6.51593442672506e-06 -2.42020662832949e-06 -0.000397243178548795 -1.61467122893252e-06 5.90044711875908e-06 1.18307095329723e-05 -1.66972766917951e-06 7.09293087446541e-06 -1.28429893635557e-05 9.02787260799512e-06 -6.51593442672506e-06 -1.66972766917951e-06 7.09814526176351e-05 2.53020775928354e-06 2.39552645477429e-05 2.66158182234474e-07 -2.42020662832949e-06 7.09293087446541e-06 2.53020775928354e-06 1.66012916353988e-05 5.20631529364424e-06 5.9573412381954e-05 -0.000397243178548795 -1.28429893635557e-05 2.39552645477429e-05 5.20631529364424e-06 0.00107559178952354 1016 1018 0 818 0 1016 1018 0 796 0 0 0 0 0 0 0 0 0 1507 0 0 0 0 0 825 +845 937 0.963035488758965 -0.224478601822824 -0.148902668594126 1.27068486801894 0.221663596294844 0.974478351641299 -0.0354569070858298 -0.125456468022817 0.153061743974183 0.00113995882681019 0.988215969829194 0.186106953475097 3.82920829650819e-05 -3.41372312802781e-05 -9.45202206472571e-07 3.03892760730587e-06 -1.67557201540882e-06 4.37448137292823e-05 -3.41372312802781e-05 0.000169872478488591 -6.9312533040138e-07 9.72183781454653e-06 -9.0101651883687e-07 -0.000209945022666913 -9.45202206472571e-07 -6.9312533040138e-07 1.05774287084434e-05 7.57634571410947e-07 4.42504647330974e-06 3.42934521477029e-06 3.03892760730587e-06 9.72183781454653e-06 7.57634571410947e-07 5.8185144821677e-05 6.98808671562386e-07 -8.45816083655982e-06 -1.67557201540882e-06 -9.0101651883687e-07 4.42504647330974e-06 6.98808671562386e-07 1.42480402601247e-05 3.71984089959064e-06 4.37448137292823e-05 -0.000209945022666913 3.42934521477029e-06 -8.45816083655982e-06 3.71984089959064e-06 0.000590536197419479 2470 2460 0 982 0 2470 2460 0 940 0 0 0 0 0 0 0 0 0 2562 0 0 0 0 0 651 +845 939 0.933662926958205 -0.315255396618796 -0.169963448207442 1.38891117815469 0.313280664273056 0.948858098559207 -0.0390324761095118 0.00890075437607775 0.173576393027598 -0.0168030860657336 0.984677049637188 0.0334098612794572 3.43174652681482e-05 -2.27820850595102e-05 -2.2480313206964e-06 1.46195760081648e-05 8.28101167352011e-07 2.14463716705003e-05 -2.27820850595102e-05 3.83739338804739e-05 1.59463735654537e-06 -4.73524686664579e-06 -1.05608417024841e-06 -1.75225361014601e-05 -2.2480313206964e-06 1.59463735654537e-06 1.10221212040919e-05 1.77569723685858e-06 4.2378642243372e-06 -3.44238204752392e-06 1.46195760081648e-05 -4.73524686664579e-06 1.77569723685858e-06 5.94507757494134e-05 -3.47645095112491e-07 3.95374597848168e-05 8.28101167352011e-07 -1.05608417024841e-06 4.2378642243372e-06 -3.47645095112491e-07 1.48639659762291e-05 -2.81089210384608e-06 2.14463716705003e-05 -1.75225361014601e-05 -3.44238204752392e-06 3.95374597848168e-05 -2.81089210384608e-06 0.000128899463083276 2818 2876 0 1013 392 2818 2876 0 970 392 0 0 0 0 0 0 0 0 2673 0 0 0 0 0 238 +845 940 0.929741497671212 -0.330440877245265 -0.162448681599669 1.46032411039761 0.317658181551993 0.942920865691499 -0.0999675984340712 0.0857703296362096 0.186209632407059 0.0413408718942183 0.981639906029626 0.010101003671273 4.69616917691858e-05 -4.82874339900219e-05 -2.78392010218642e-07 -1.46538316195481e-05 3.54007744190626e-06 2.94622645808718e-06 -4.82874339900219e-05 0.000195982317345832 -1.30564540865845e-05 8.75240140572078e-05 -4.33263290624278e-06 5.38463163052255e-05 -2.78392010218642e-07 -1.30564540865845e-05 1.22665704264292e-05 -6.01145538139792e-07 1.31630393529995e-06 -3.10234022352188e-06 -1.46538316195481e-05 8.75240140572078e-05 -6.01145538139792e-07 0.000103349462375141 -4.42388043524692e-06 9.11423697386532e-05 3.54007744190626e-06 -4.33263290624278e-06 1.31630393529995e-06 -4.42388043524692e-06 1.86521286217858e-05 9.96402558848688e-06 2.94622645808718e-06 5.38463163052255e-05 -3.10234022352188e-06 9.11423697386532e-05 9.96402558848688e-06 0.000444311950061484 2553 2599 0 1115 668 2553 2599 0 1067 668 0 0 0 0 0 0 0 0 2668 0 0 0 0 0 134 +846 848 0.998310128904753 0.0485391236320893 -0.0319505868992241 0.23446147235539 -0.0490101515703153 0.998698359757072 -0.0141276771476335 -0.022710899643062 0.0312232536618277 0.0156697063010703 0.999389598072347 0.0675484198243391 4.3531350033451e-05 -1.18426233120556e-05 -1.31217052936435e-07 1.72894221317793e-06 -6.06221941062338e-07 -6.94084129310212e-06 -1.18426233120556e-05 2.1120962639057e-05 1.8737281723201e-06 -2.18677490670745e-07 -2.59259826428879e-07 -1.10360843420148e-05 -1.31217052936435e-07 1.8737281723201e-06 9.93940031503647e-06 -4.84014664275628e-07 1.51606241065073e-06 -3.69608668002551e-06 1.72894221317793e-06 -2.18677490670745e-07 -4.84014664275628e-07 3.23858393305522e-05 8.73393040376856e-06 7.25665801179934e-06 -6.06221941062338e-07 -2.59259826428879e-07 1.51606241065073e-06 8.73393040376856e-06 1.82917282560528e-05 4.89514510764345e-06 -6.94084129310212e-06 -1.10360843420148e-05 -3.69608668002551e-06 7.25665801179934e-06 4.89514510764345e-06 8.03046156861604e-05 3602 3663 0 348 88 3602 3663 0 330 111 0 0 0 0 0 0 0 0 3564 0 0 0 0 0 1798 +846 936 0.967687895659775 -0.212517886388285 -0.135706612066667 1.13239950786785 0.204351865784943 0.976270321878029 -0.0716698930540782 -0.140710391167937 0.147717472032829 0.0416221886164853 0.988153399969359 0.227958621085337 2.2859555667245e-05 -4.34014238090092e-06 -1.15701607818604e-07 7.09198708183049e-07 5.71210181828758e-07 2.59672697085073e-05 -4.34014238090092e-06 0.00010376752021556 -6.3082275113509e-07 3.06544163023613e-07 3.92689900149095e-07 -6.31943115888419e-05 -1.15701607818604e-07 -6.3082275113509e-07 1.04297535559748e-05 1.68552562982858e-06 4.62692425554621e-06 3.67309455589808e-06 7.09198708183049e-07 3.06544163023613e-07 1.68552562982858e-06 5.46592988255646e-05 3.05117828801611e-06 2.87976661004504e-06 5.71210181828758e-07 3.92689900149095e-07 4.62692425554621e-06 3.05117828801611e-06 1.3637962512215e-05 -1.62886651201782e-07 2.59672697085073e-05 -6.31943115888419e-05 3.67309455589808e-06 2.87976661004504e-06 -1.62886651201782e-07 0.000235058754749548 2289 2281 0 733 0 2289 2281 0 702 0 0 0 0 0 0 0 0 0 2646 0 0 0 0 0 637 +846 849 0.995647246494329 0.088404779237193 -0.0295153444208967 0.351577203500628 -0.0890844103395883 0.995768486648523 -0.0225629969675736 -0.0422429812430247 0.0273957730810585 0.02509414285713 0.999309639506973 0.110866314802051 4.40285782220188e-05 -1.90183030066348e-05 4.35553889823635e-06 2.66339799497729e-06 -3.12258419932072e-06 3.80138669669076e-06 -1.90183030066348e-05 5.38313833921588e-05 -1.4226592061542e-06 -2.04766937792479e-06 1.80947741680457e-06 -3.51825311862016e-05 4.35553889823635e-06 -1.4226592061542e-06 1.1270024164611e-05 -1.42573691526071e-06 1.68653163556355e-06 -2.97441597936159e-06 2.66339799497729e-06 -2.04766937792479e-06 -1.42573691526071e-06 4.06507318443966e-05 1.25413224783728e-05 1.9818333365763e-05 -3.12258419932072e-06 1.80947741680457e-06 1.68653163556355e-06 1.25413224783728e-05 2.2954074111557e-05 8.87412862703672e-06 3.80138669669076e-06 -3.51825311862016e-05 -2.97441597936159e-06 1.9818333365763e-05 8.87412862703672e-06 0.00012616715066264 3353 3440 0 597 105 3353 3440 0 578 134 0 0 0 0 0 0 0 0 3328 0 0 0 0 0 1857 +846 934 0.985372846502084 -0.114522522399486 -0.126194077672602 1.0855115812939 0.10846264954531 0.992637640465451 -0.0539107446136092 -0.240285706824946 0.131438985959231 0.0394348398556619 0.990539593542614 0.481597807474129 4.47954784190482e-05 -2.90720495074545e-05 -1.04746222668445e-06 1.29482866904723e-05 1.32133081304549e-06 5.16276701823208e-05 -2.90720495074545e-05 0.000110942649726022 4.11567132131169e-07 -8.90246982277927e-06 2.9835692914765e-06 -6.16685279515889e-05 -1.04746222668445e-06 4.11567132131169e-07 1.12115026331445e-05 -6.17185417820636e-07 5.33411621622096e-06 5.32009284756091e-07 1.29482866904723e-05 -8.90246982277927e-06 -6.17185417820636e-07 7.21448487804332e-05 7.20954368868797e-06 2.84736301776354e-05 1.32133081304549e-06 2.9835692914765e-06 5.33411621622096e-06 7.20954368868797e-06 1.7447244408822e-05 2.6172961168993e-06 5.16276701823208e-05 -6.16685279515889e-05 5.32009284756091e-07 2.84736301776354e-05 2.6172961168993e-06 0.000206456075029603 1540 1543 0 745 0 1540 1543 0 721 0 0 0 0 0 0 0 0 0 1799 0 0 0 0 0 788 +846 932 0.998680611747175 0.0476192350910846 -0.0192209305089178 1.03041818964849 -0.0483737369038224 0.997991136997798 -0.0409105371732383 -0.327375889715294 0.0172341898053955 0.0417863485265602 0.998977919565077 0.678745597722402 4.4177455885752e-05 -4.36423869272031e-05 -1.48951633848558e-06 -1.03968166522633e-06 -3.72500490509448e-06 4.67239985704279e-05 -4.36423869272031e-05 0.000135720265139324 3.36791352491196e-06 -5.13265604290473e-06 -6.85156429254149e-07 -0.000130319746899664 -1.48951633848558e-06 3.36791352491196e-06 1.15033823130319e-05 -3.21062912418569e-06 7.24985636953926e-06 -3.51285945943413e-07 -1.03968166522633e-06 -5.13265604290473e-06 -3.21062912418569e-06 5.54667583848061e-05 4.327778479854e-06 -4.92108262016253e-06 -3.72500490509448e-06 -6.85156429254149e-07 7.24985636953926e-06 4.327778479854e-06 1.84330225758179e-05 -3.92407686059227e-06 4.67239985704279e-05 -0.000130319746899664 -3.51285945943413e-07 -4.92108262016253e-06 -3.92407686059227e-06 0.000228932203125475 1160 1175 0 983 0 1160 1175 0 962 0 0 0 0 0 0 0 0 0 1041 0 0 0 0 0 1346 +846 933 0.996999800555931 -0.0425640249486282 -0.0646506107597399 1.05528874263899 0.0386001354634353 0.997368341707315 -0.0613711699595582 -0.286151100940358 0.0670926764530921 0.0586915218764438 0.996019014891878 0.599834985168252 3.87201579740544e-05 -1.78789854502509e-05 -6.20119805412371e-07 1.00605171522125e-05 -2.72092647361885e-06 1.45496165460913e-05 -1.78789854502509e-05 0.000196715649476539 2.11374109477111e-06 -3.11876548095379e-06 -1.67794841356348e-06 -0.000261536670081442 -6.20119805412371e-07 2.11374109477111e-06 1.09200014187398e-05 3.30173188018364e-08 3.6731517692253e-06 -3.78228304737705e-06 1.00605171522125e-05 -3.11876548095379e-06 3.30173188018364e-08 5.45699612761957e-05 4.22966554230751e-06 1.0414787365435e-06 -2.72092647361885e-06 -1.67794841356348e-06 3.6731517692253e-06 4.22966554230751e-06 1.7413493709727e-05 2.3530093747752e-06 1.45496165460913e-05 -0.000261536670081442 -3.78228304737705e-06 1.0414787365435e-06 2.3530093747752e-06 0.000491971209075553 1318 1326 0 819 0 1318 1326 0 794 0 0 0 0 0 0 0 0 0 1214 0 0 0 0 0 663 +846 850 0.991227384851026 0.128873704274549 -0.0293230262413823 0.459290197417822 -0.12965167172444 0.991208606382735 -0.0263807250062355 -0.0671191066287399 0.0256654542226431 0.0299510764306197 0.999221805947104 0.172953224756826 2.7638318700736e-05 -3.8695619582269e-06 -5.56794741875524e-06 -2.9187226615239e-07 -1.10631994924395e-07 3.96427832033495e-06 -3.8695619582269e-06 3.69570524733824e-05 7.09201996751636e-06 -1.14787590813017e-05 -3.84790934592406e-06 -2.43748704326863e-05 -5.56794741875524e-06 7.09201996751636e-06 1.17708063646834e-05 -1.30427297429988e-06 3.3452999155939e-06 -5.69828399854725e-06 -2.9187226615239e-07 -1.14787590813017e-05 -1.30427297429988e-06 3.00481297727148e-05 6.58132748515303e-06 1.59552140410803e-05 -1.10631994924395e-07 -3.84790934592406e-06 3.3452999155939e-06 6.58132748515303e-06 1.70981178095952e-05 4.89987984758728e-06 3.96427832033495e-06 -2.43748704326863e-05 -5.69828399854725e-06 1.59552140410803e-05 4.89987984758728e-06 7.08613429688803e-05 3482 3602 0 822 134 3482 3602 0 809 157 0 0 0 0 0 0 0 0 3099 0 0 0 0 0 2997 +846 930 0.978243305101205 0.194471449577351 0.0722557355782472 1.00830383607689 -0.192483801359711 0.980725101259218 -0.0335896111053911 -0.373878194240583 -0.0773952339539407 0.0189507535306588 0.996820368322114 0.816647208826846 4.6863225280073e-05 -1.58080639198525e-05 -4.17504046803139e-06 5.34911894318792e-07 -4.74393713514601e-07 6.11995392543725e-05 -1.58080639198525e-05 0.000125917934843413 4.36664865567438e-07 -5.10267338921016e-06 -3.76113473316957e-06 -3.84508943302004e-05 -4.17504046803139e-06 4.36664865567438e-07 1.18929870434084e-05 -5.5557840669085e-06 7.40582122902987e-06 -6.45525984799953e-06 5.34911894318792e-07 -5.10267338921016e-06 -5.5557840669085e-06 5.65528327590972e-05 4.62282063063588e-06 -2.9924254278827e-06 -4.74393713514601e-07 -3.76113473316957e-06 7.40582122902987e-06 4.62282063063588e-06 2.43804481462513e-05 9.92242958930638e-06 6.11995392543725e-05 -3.84508943302004e-05 -6.45525984799953e-06 -2.9924254278827e-06 9.92242958930638e-06 0.000351174129619572 764 786 0 1155 0 764 786 0 1137 0 0 0 0 0 0 0 0 0 537 0 0 0 0 0 1154 +846 937 0.959588234076216 -0.24943491056098 -0.130279109668148 1.15931493414644 0.243341892432221 0.968019193296826 -0.0610210193004591 -0.0850099608555047 0.141333451135939 0.0268526870610262 0.989597791422155 0.12420616915827 3.08334522091809e-05 -1.38673741732292e-05 -1.22578335914822e-06 5.63622645381642e-06 -1.28975522185649e-07 2.02210781199364e-05 -1.38673741732292e-05 4.71670139034768e-05 2.4440658001946e-06 -7.16516781016312e-06 -1.29167280651448e-07 -1.91538828846924e-05 -1.22578335914822e-06 2.4440658001946e-06 1.02109476181029e-05 2.44524786094004e-06 4.05930097459851e-06 4.11010433973133e-07 5.63622645381642e-06 -7.16516781016312e-06 2.44524786094004e-06 4.55439700654253e-05 2.8035486772847e-06 1.0864497298775e-05 -1.28975522185649e-07 -1.29167280651448e-07 4.05930097459851e-06 2.8035486772847e-06 1.38648980839249e-05 -4.03512929443575e-06 2.02210781199364e-05 -1.91538828846924e-05 4.11010433973133e-07 1.0864497298775e-05 -4.03512929443575e-06 0.000113287495167165 2903 2891 0 742 0 2903 2891 0 715 0 0 0 0 0 0 0 0 0 3066 0 0 0 0 0 599 +846 931 0.991043663547085 0.124849199466579 0.0473828485395946 1.02326413491427 -0.122571552443664 0.991284931229556 -0.048274213082805 -0.357897969220801 -0.0529969006142997 0.0420340636837346 0.997709610064727 0.76408426760218 6.25836753217704e-05 -4.62513434825505e-05 -2.99211851739007e-06 1.46629270218803e-05 3.98684216922512e-06 4.93196973364154e-05 -4.62513434825505e-05 0.000125633516036462 1.64452998977842e-06 -8.64690855893503e-06 -8.93396589106577e-06 -8.75380671210639e-05 -2.99211851739007e-06 1.64452998977842e-06 1.25176658629462e-05 -3.4228451233481e-06 7.29261545189531e-06 -4.35614183630325e-06 1.46629270218803e-05 -8.64690855893503e-06 -3.4228451233481e-06 6.9486629917895e-05 1.41302977171037e-05 1.9865921812062e-05 3.98684216922512e-06 -8.93396589106577e-06 7.29261545189531e-06 1.41302977171037e-05 2.574524008121e-05 1.56334499949218e-05 4.93196973364154e-05 -8.75380671210639e-05 -4.35614183630325e-06 1.9865921812062e-05 1.56334499949218e-05 0.00025246051035275 936 954 0 1102 0 936 954 0 1086 0 0 0 0 0 0 0 0 0 728 0 0 0 0 0 1383 +846 896 0.961161470875756 0.275636617893892 0.0138953870032509 1.01385991752147 -0.274934155740001 0.960674540792135 -0.0389311787819542 -0.384905043438349 -0.0240798029785574 0.0335988325665708 0.999145275492347 0.860138762187769 5.60608763460757e-05 -7.26482733433343e-05 -1.3100463208428e-06 -7.98906375542784e-06 -6.0986852124869e-06 8.50041553975412e-05 -7.26482733433343e-05 0.000192203273772669 7.52270455386044e-07 2.08890060782072e-05 3.78860111621303e-06 -0.000127782225035012 -1.3100463208428e-06 7.52270455386044e-07 1.16725649983041e-05 -6.58989875482211e-06 6.97331708979053e-06 2.83265160627416e-06 -7.98906375542784e-06 2.08890060782072e-05 -6.58989875482211e-06 6.10360171211191e-05 5.40481710506065e-06 -3.28593059042905e-05 -6.0986852124869e-06 3.78860111621303e-06 6.97331708979053e-06 5.40481710506065e-06 2.30860737608153e-05 -4.49421328312088e-06 8.50041553975412e-05 -0.000127782225035012 2.83265160627416e-06 -3.28593059042905e-05 -4.49421328312088e-06 0.000319770765715341 528 552 0 1115 0 528 552 0 1099 0 0 0 0 0 0 0 0 0 477 0 0 0 0 0 1618 +846 935 0.974569942917317 -0.164211300779259 -0.152473194557339 1.10177976033303 0.155697021171872 0.98557887648648 -0.0662775665052227 -0.192464326516536 0.161157885194434 0.0408525020045566 0.986082759772031 0.367823040145422 2.73475132995358e-05 -9.44465964400861e-06 -5.21030746372945e-07 8.72471391450154e-06 1.53761443860937e-07 2.07337110906288e-05 -9.44465964400861e-06 4.7214404888182e-05 -2.15948202875385e-06 1.77345589790556e-05 1.11616768484739e-06 7.14734901057723e-06 -5.21030746372945e-07 -2.15948202875385e-06 1.0355492178681e-05 1.67342681798081e-06 5.10732444170812e-06 -2.32046059654329e-06 8.72471391450154e-06 1.77345589790556e-05 1.67342681798081e-06 7.38222224080918e-05 5.47330597828246e-06 3.49359291572326e-05 1.53761443860937e-07 1.11616768484739e-06 5.10732444170812e-06 5.47330597828246e-06 1.59255240216158e-05 4.26781509252603e-06 2.07337110906288e-05 7.14734901057723e-06 -2.32046059654329e-06 3.49359291572326e-05 4.26781509252603e-06 0.000132060469585218 1863 1861 0 714 0 1863 1861 0 690 0 0 0 0 0 0 0 0 0 2195 0 0 0 0 0 776 +846 929 0.96685178100548 0.254892256846778 0.0150854554484996 1.00346290185558 -0.254524289993379 0.966799800627249 -0.0227053145866183 -0.385301903863339 -0.0203720241973799 0.0181130590091055 0.999628379810935 0.839953204113976 7.06574695215966e-05 -3.11862468387262e-05 -5.89454955214508e-06 2.71403712683632e-06 7.53739365746937e-06 2.40050376062096e-05 -3.11862468387262e-05 5.8246012218416e-05 6.2400775301688e-06 1.09858114577317e-06 5.31171691798981e-07 -4.59295770210849e-05 -5.89454955214508e-06 6.2400775301688e-06 1.50292873491255e-05 -7.54878837361686e-06 6.74055945377525e-06 -8.99507681749525e-06 2.71403712683632e-06 1.09858114577317e-06 -7.54878837361686e-06 5.3286640877534e-05 5.67323646652913e-06 6.8057765706067e-06 7.53739365746937e-06 5.31171691798981e-07 6.74055945377525e-06 5.67323646652913e-06 2.95536352774287e-05 -1.04846261494556e-05 2.40050376062096e-05 -4.59295770210849e-05 -8.99507681749525e-06 6.8057765706067e-06 -1.04846261494556e-05 0.00023438400140562 554 577 0 1127 0 554 577 0 1113 0 0 0 0 0 0 0 0 0 593 0 0 0 0 0 1303 +846 940 0.922704957162971 -0.354339257180564 -0.151852734080116 1.33490936714582 0.337698249106412 0.932922906063508 -0.124958968835704 0.133095694552413 0.185944762167004 0.0640198575658 0.980472336815227 -0.0478266740062004 5.83973339827825e-05 -2.36713684787647e-05 -1.36027050012554e-06 -1.21131091526517e-05 1.32288067342482e-06 -5.1098300269268e-06 -2.36713684787647e-05 5.5769435002253e-05 7.7889065826506e-07 1.24852147358631e-05 6.69009444525088e-07 3.01380985672672e-05 -1.36027050012554e-06 7.7889065826506e-07 1.25975812114761e-05 9.4841525491873e-07 2.69433639400102e-06 -1.20654828620406e-05 -1.21131091526517e-05 1.24852147358631e-05 9.4841525491873e-07 8.9387319241982e-05 4.53454364369192e-06 0.000138449280207171 1.32288067342482e-06 6.69009444525088e-07 2.69433639400102e-06 4.53454364369192e-06 1.82440264925316e-05 2.3001234768304e-05 -5.1098300269268e-06 3.01380985672672e-05 -1.20654828620406e-05 0.000138449280207171 2.3001234768304e-05 0.00056812735902434 2848 2894 0 655 668 2848 2894 0 617 668 0 0 0 0 0 0 0 0 3099 0 0 0 0 0 120 +846 938 0.94635313157763 -0.290078884239767 -0.142372719547758 1.20759087516905 0.286601720937585 0.957001400529794 -0.0448081793830972 -0.0209862906922135 0.149248798684704 0.0016000944425348 0.98879837974632 0.0332738135191324 2.98264348851156e-05 -1.79783357596133e-05 -1.22946681818407e-06 1.00936248760679e-05 6.04636397818274e-07 2.09312090715712e-05 -1.79783357596133e-05 7.14948494132432e-05 2.97454904308385e-07 1.23746573383226e-05 -1.91440665839935e-07 -3.7558143902827e-05 -1.22946681818407e-06 2.97454904308385e-07 1.02797668249712e-05 1.60578676812977e-06 5.42662094163629e-06 -6.0718703450308e-07 1.00936248760679e-05 1.23746573383226e-05 1.60578676812977e-06 6.41841299375138e-05 3.9183103893511e-07 1.31089921183139e-05 6.04636397818274e-07 -1.91440665839935e-07 5.42662094163629e-06 3.9183103893511e-07 1.43695783842667e-05 -2.86107562433657e-06 2.09312090715712e-05 -3.7558143902827e-05 -6.0718703450308e-07 1.31089921183139e-05 -2.86107562433657e-06 0.000180002655431235 2929 3027 0 668 65 2929 3027 0 632 65 0 0 0 0 0 0 0 0 3063 0 0 0 0 0 486 +846 895 0.961123207987869 0.275990826781551 0.00844053313142059 1.01009824484215 -0.275500110977292 0.960564749445327 -0.0376171632973133 -0.3820160115993 -0.0184896705921701 0.0338293608493034 0.999256576873988 0.85191121160222 4.77154253048197e-05 -6.27905911768449e-05 -3.69952112794494e-06 1.86134803179066e-06 -8.34804745154115e-06 4.40636465338012e-05 -6.27905911768449e-05 0.000183848195490883 4.40696072766384e-07 1.92367828244124e-05 1.76036340587798e-05 -5.27143847712326e-05 -3.69952112794494e-06 4.40696072766384e-07 1.23919579740605e-05 -9.70934165881088e-06 7.03389928654034e-06 -6.01889248978115e-06 1.86134803179066e-06 1.92367828244124e-05 -9.70934165881088e-06 6.74180755589158e-05 8.21892662225884e-06 2.28197206304895e-05 -8.34804745154115e-06 1.76036340587798e-05 7.03389928654034e-06 8.21892662225884e-06 2.82092245843266e-05 4.6778798212653e-07 4.40636465338012e-05 -5.27143847712326e-05 -6.01889248978115e-06 2.28197206304895e-05 4.6778798212653e-07 0.000242382517800028 517 535 0 1125 0 517 535 0 1109 0 0 0 0 0 0 0 0 0 522 0 0 0 0 0 1604 +846 898 0.96111946785708 0.275951385415441 0.010010064606303 1.00934950975074 -0.275366291507082 0.960520593404361 -0.0396685662429594 -0.384941546660101 -0.020561469007851 0.0353697969097025 0.999162751236657 0.86628190508204 6.72429444670365e-05 -7.11952089381933e-05 -6.14753584635393e-06 9.37250670851849e-06 -4.85825083605947e-07 8.19642247092914e-05 -7.11952089381933e-05 0.000174448398712509 4.91142942039292e-06 -3.10742184148137e-06 -7.12904842072635e-06 -8.57608758184815e-05 -6.14753584635393e-06 4.91142942039292e-06 1.17940230132279e-05 -6.16847964456615e-06 6.65428286389251e-06 -2.47478874988649e-06 9.37250670851849e-06 -3.10742184148137e-06 -6.16847964456615e-06 6.07593020957262e-05 8.69075808620402e-06 -2.34695276741985e-05 -4.85825083605947e-07 -7.12904842072635e-06 6.65428286389251e-06 8.69075808620402e-06 2.7301014972098e-05 -2.60628313687567e-06 8.19642247092914e-05 -8.57608758184815e-05 -2.47478874988649e-06 -2.34695276741985e-05 -2.60628313687567e-06 0.000359181566887152 515 529 0 1119 0 515 529 0 1107 0 0 0 0 0 0 0 0 0 478 0 0 0 0 0 1629 +846 894 0.961377432805164 0.275192207582293 0.00476241314225166 1.00179864713733 -0.274762376377765 0.960600327431539 -0.0418646326350016 -0.388820058018251 -0.016095596298259 0.0389391810957113 0.999111941653886 0.861708853248989 9.53416551221322e-05 -0.000124905109091565 -3.18723766093485e-07 1.02600407483691e-06 3.92710302842528e-06 7.8952569691939e-05 -0.000124905109091565 0.000322026228969611 -5.77446053217603e-06 1.37159415771868e-05 -5.02717813388616e-06 -0.000140715261386863 -3.18723766093485e-07 -5.77446053217603e-06 1.55494027779e-05 -8.54605672512268e-06 7.31507150123698e-06 -2.77442924833143e-07 1.02600407483691e-06 1.37159415771868e-05 -8.54605672512268e-06 6.63314711218485e-05 1.62394280457818e-05 4.96495422349228e-06 3.92710302842528e-06 -5.02717813388616e-06 7.31507150123698e-06 1.62394280457818e-05 3.60338835994647e-05 2.10362958344328e-05 7.8952569691939e-05 -0.000140715261386863 -2.77442924833143e-07 4.96495422349228e-06 2.10362958344328e-05 0.000269952783866722 516 536 0 1069 0 516 536 0 1053 0 0 0 0 0 0 0 0 0 432 0 0 0 0 0 757 +846 939 0.929082739523996 -0.339807185938439 -0.146069639224533 1.27678080499226 0.333609628180888 0.940413584816905 -0.0657792176665852 0.0563691010243461 0.15971812390457 0.0123840977232031 0.987084978621388 -0.0222006604015701 3.18890701773006e-05 -1.74415256628382e-05 -1.20521161261185e-06 6.99259576540406e-06 -1.45082467506019e-06 2.82748721025997e-05 -1.74415256628382e-05 3.25124351935294e-05 1.4459102796557e-06 -6.81243403472438e-06 1.81701609665058e-06 -8.16957289310237e-06 -1.20521161261185e-06 1.4459102796557e-06 1.11412794717812e-05 1.00743633726869e-06 4.88238101314837e-06 1.8073496412588e-06 6.99259576540406e-06 -6.81243403472438e-06 1.00743633726869e-06 5.93609353633156e-05 -8.19933773355367e-07 1.0284490336404e-05 -1.45082467506019e-06 1.81701609665058e-06 4.88238101314837e-06 -8.19933773355367e-07 1.40029062401517e-05 -2.02202409955297e-06 2.82748721025997e-05 -8.16957289310237e-06 1.8073496412588e-06 1.0284490336404e-05 -2.02202409955297e-06 0.000140809902840402 3014 3072 0 608 392 3014 3072 0 576 392 0 0 0 0 0 0 0 0 3070 0 0 0 0 0 241 +847 851 0.989919501191158 0.140470762633924 -0.0180927058919524 0.450545412151315 -0.141056967432912 0.989319948458572 -0.036728347642635 -0.0788837353660212 0.0127402158568576 0.0389102098037471 0.999161489686702 0.184709197069605 3.28626297521014e-05 -1.76041732536768e-05 7.647568940635e-06 1.12442419969347e-06 -1.1124335926733e-06 2.20490423217324e-05 -1.76041732536768e-05 4.37983279967369e-05 -3.75122710788859e-06 8.73825218634331e-06 3.18327214668761e-06 -3.1804432630782e-05 7.647568940635e-06 -3.75122710788859e-06 1.36949787615473e-05 3.34416004237261e-06 4.38100208739894e-06 2.91560529046018e-06 1.12442419969347e-06 8.73825218634331e-06 3.34416004237261e-06 3.64305475781687e-05 4.96359572860587e-06 -5.04953070610472e-06 -1.1124335926733e-06 3.18327214668761e-06 4.38100208739894e-06 4.96359572860587e-06 1.90896758289396e-05 -2.92945645915764e-06 2.20490423217324e-05 -3.1804432630782e-05 2.91560529046018e-06 -5.04953070610472e-06 -2.92945645915764e-06 0.000105154506779584 3178 3345 0 810 124 3178 3345 0 810 159 0 0 0 0 0 0 0 0 3008 0 0 0 0 0 1974 +847 933 0.997019806116931 -0.0612408212574244 -0.046915541372478 0.952063751451906 0.0588930178159879 0.997016841401382 -0.0498901835488517 -0.253465640076552 0.0498309006850391 0.0469785033151182 0.9976521946867 0.557422330284222 5.19498396710918e-05 -4.56506572521039e-05 -1.39692935421778e-06 -4.41711566085516e-06 -2.09639426130678e-06 4.79547969641556e-05 -4.56506572521039e-05 0.000135833340702009 1.42372702526603e-06 1.68904469013941e-05 3.44191848291131e-06 -0.000133172382334177 -1.39692935421778e-06 1.42372702526603e-06 1.13345923783418e-05 1.42291756583244e-06 5.58149399197765e-06 -1.27239480707962e-06 -4.41711566085516e-06 1.68904469013941e-05 1.42291756583244e-06 5.7800761464574e-05 6.14430600202647e-06 -1.77951743969163e-05 -2.09639426130678e-06 3.44191848291131e-06 5.58149399197765e-06 6.14430600202647e-06 1.86640519020737e-05 -3.65138521711347e-06 4.79547969641556e-05 -0.000133172382334177 -1.27239480707962e-06 -1.77951743969163e-05 -3.65138521711347e-06 0.00021050057306306 1288 1296 0 628 0 1288 1296 0 628 0 0 0 0 0 0 0 0 0 1398 0 0 0 0 0 1283 +847 849 0.997518318394155 0.0694483141573427 -0.011581715278831 0.233369926655695 -0.0696184961137311 0.997460879214524 -0.0150019810508624 -0.0295898252453367 0.0105104456118323 0.0157710525105669 0.999820386087296 0.0567265275135822 1.53623553591569e-05 -5.41634559944531e-06 1.29881226161594e-06 2.12880319069688e-06 1.54738974866733e-06 7.89423791590485e-07 -5.41634559944531e-06 3.91556705990177e-05 -5.27449279532929e-07 -1.20496846497442e-06 -1.89577853989995e-06 -2.58966579617537e-05 1.29881226161594e-06 -5.27449279532929e-07 9.45133377428724e-06 -5.18864055406708e-10 1.80278359059214e-06 -1.26244396666945e-06 2.12880319069688e-06 -1.20496846497442e-06 -5.18864055406708e-10 3.19979754675473e-05 9.93433012764961e-06 4.3240289409138e-06 1.54738974866733e-06 -1.89577853989995e-06 1.80278359059214e-06 9.93433012764961e-06 1.94247778217693e-05 8.64375013323892e-07 7.89423791590485e-07 -2.58966579617537e-05 -1.26244396666945e-06 4.3240289409138e-06 8.64375013323892e-07 6.85161614376642e-05 3294 3381 0 395 24 3294 3381 0 395 67 0 0 0 0 0 0 0 0 3530 0 0 0 0 0 3313 +847 931 0.992691043806193 0.106561585974963 0.0566490947983506 0.917151091330395 -0.104904887271529 0.993984394495976 -0.0314640767386366 -0.320752181667794 -0.0596611781103907 0.0252913402762202 0.997898237263456 0.714636925079055 5.79445596871571e-05 -6.56997866065897e-05 -4.0612571596312e-06 8.28386569735772e-06 2.57887352962591e-06 4.25269552163318e-05 -6.56997866065897e-05 0.000194122128597288 6.20204938735959e-06 -3.43300733766165e-05 -2.04177517445888e-05 -5.06946835505976e-05 -4.0612571596312e-06 6.20204938735959e-06 1.46569539486276e-05 -9.62536455557625e-06 8.28645368362295e-06 -2.40143517189264e-06 8.28386569735772e-06 -3.43300733766165e-05 -9.62536455557625e-06 6.12149676256363e-05 4.38094987051956e-06 1.33472400902541e-06 2.57887352962591e-06 -2.04177517445888e-05 8.28645368362295e-06 4.38094987051956e-06 2.3770202560796e-05 1.32054481509664e-05 4.25269552163318e-05 -5.06946835505976e-05 -2.40143517189264e-06 1.33472400902541e-06 1.32054481509664e-05 0.000206417709467237 897 915 0 933 0 897 915 0 933 0 0 0 0 0 0 0 0 0 914 0 0 0 0 0 640 +847 932 0.999526150749409 0.0299105846418041 -0.00726848639368297 0.928669794035249 -0.0300962336213898 0.999183955713168 -0.0269376941699398 -0.291858826575027 0.00645683280536247 0.0271436838283229 0.999610689087683 0.639253873839299 4.14365163844649e-05 -4.52575298337979e-05 -3.88902686023128e-06 3.43763312462264e-06 -3.38107696191919e-06 5.88861044678545e-05 -4.52575298337979e-05 0.000189091438638216 9.06007767347749e-06 -1.1749032318117e-05 -4.04333184080943e-06 -0.000141858764230306 -3.88902686023128e-06 9.06007767347749e-06 1.429639637294e-05 -6.29630671166687e-06 6.23749256947691e-06 -3.34537883604269e-06 3.43763312462264e-06 -1.1749032318117e-05 -6.29630671166687e-06 6.23253492676794e-05 5.11808496033335e-06 -1.94116052517023e-06 -3.38107696191919e-06 -4.04333184080943e-06 6.23749256947691e-06 5.11808496033335e-06 2.19283949381319e-05 3.21007677032023e-06 5.88861044678545e-05 -0.000141858764230306 -3.34537883604269e-06 -1.94116052517023e-06 3.21007677032023e-06 0.000220089776436851 1100 1115 0 788 0 1100 1115 0 788 0 0 0 0 0 0 0 0 0 1241 0 0 0 0 0 633 +847 938 0.94255905822768 -0.308813310801203 -0.12734504633062 1.08952558175646 0.306822182968171 0.951105917739439 -0.0354638023859026 0.00755327803728999 0.132070321388246 -0.00564555692731466 0.991224272248912 -0.0225755542937505 5.6286154882998e-05 -1.74022001251104e-05 -3.73556123179357e-06 2.03694248395384e-05 -1.8731546460077e-07 3.54870027876052e-05 -1.74022001251104e-05 5.99698437966374e-05 3.39285554401045e-06 -3.54440387418313e-06 -1.49810465999975e-06 -1.39166410304604e-05 -3.73556123179357e-06 3.39285554401045e-06 1.19526187936354e-05 -4.33480360136154e-06 4.67765883360108e-06 -8.21068876038901e-06 2.03694248395384e-05 -3.54440387418313e-06 -4.33480360136154e-06 8.25352635650392e-05 3.08232799045344e-06 4.900389857624e-05 -1.8731546460077e-07 -1.49810465999975e-06 4.67765883360108e-06 3.08232799045344e-06 1.2913141525183e-05 2.27519390963037e-06 3.54870027876052e-05 -1.39166410304604e-05 -8.21068876038901e-06 4.900389857624e-05 2.27519390963037e-06 0.000176546907729438 2961 3059 0 301 65 2961 3059 0 301 65 0 0 0 0 0 0 0 0 3418 0 0 0 0 0 251 +847 934 0.98520882102967 -0.133078162035483 -0.107952682942969 0.980573644091671 0.128966520614901 0.990661372753256 -0.0442456901304671 -0.209648124607855 0.112832688197233 0.0296689622988834 0.993170950617412 0.441659911693173 5.48010863953506e-05 -2.47297368741276e-05 -2.93442791181355e-07 5.50227379347704e-06 -7.00876338198785e-07 5.08883313787183e-05 -2.47297368741276e-05 0.000120953217801493 8.72841811834334e-07 1.51098049256033e-05 2.88665083489486e-06 -2.30856204057048e-05 -2.93442791181355e-07 8.72841811834334e-07 1.30646152445355e-05 -5.13327643861369e-06 4.92626722812626e-06 -3.90654599949785e-06 5.50227379347704e-06 1.51098049256033e-05 -5.13327643861369e-06 0.00011112920481671 1.02947022711937e-05 3.56479464498079e-05 -7.00876338198785e-07 2.88665083489486e-06 4.92626722812626e-06 1.02947022711937e-05 1.7322076684251e-05 4.08901734655447e-07 5.08883313787183e-05 -2.30856204057048e-05 -3.90654599949785e-06 3.56479464498079e-05 4.08901734655447e-07 0.000263995219592818 1486 1489 0 514 0 1486 1489 0 514 0 0 0 0 0 0 0 0 0 2005 0 0 0 0 0 945 +847 936 0.967239321966169 -0.231050198616206 -0.105185073854794 1.02583333821127 0.225173154308875 0.972158313573046 -0.0648480063641352 -0.110690049053983 0.117239688762031 0.0390386868404079 0.99233605009027 0.188839609297326 4.41706826301156e-05 -6.94299595996483e-06 4.18273506025184e-06 1.25154868793072e-05 -1.32688555333773e-07 5.40369618480762e-05 -6.94299595996483e-06 0.000164880597249564 -3.55269028582404e-06 4.48428766781323e-05 8.02667671057834e-07 3.27451655554153e-05 4.18273506025184e-06 -3.55269028582404e-06 1.17944508685746e-05 2.10819303861902e-06 3.68602985977492e-06 -1.36134285443891e-06 1.25154868793072e-05 4.48428766781323e-05 2.10819303861902e-06 9.54409830236775e-05 5.94551744589217e-06 6.29081633069614e-05 -1.32688555333773e-07 8.02667671057834e-07 3.68602985977492e-06 5.94551744589217e-06 1.42463391973236e-05 3.0940257675235e-06 5.40369618480762e-05 3.27451655554153e-05 -1.36134285443891e-06 6.29081633069614e-05 3.0940257675235e-06 0.000286056794097801 2360 2352 0 455 0 2360 2352 0 455 0 0 0 0 0 0 0 0 0 2917 0 0 0 0 0 574 +847 937 0.956855449752405 -0.267028875550332 -0.114556658040676 1.04683951959359 0.263057201338616 0.963546712873704 -0.0487713126148375 -0.054836770413128 0.123404040059544 0.0165321424082003 0.992218791983087 0.0686278039076748 2.42213784164975e-05 -1.27562971255092e-05 1.03925313619175e-06 -1.37631836329503e-06 -1.1537391234126e-06 1.55311566671774e-05 -1.27562971255092e-05 2.96889386513858e-05 -2.79388437473603e-06 6.23005834315958e-06 7.06389798374433e-07 -1.40548729923619e-05 1.03925313619175e-06 -2.79388437473603e-06 1.04464445757639e-05 1.95229851890901e-06 5.93558686880457e-06 1.44985747423555e-06 -1.37631836329503e-06 6.23005834315958e-06 1.95229851890901e-06 5.37215219995155e-05 5.34432609352782e-06 8.92410056694426e-06 -1.1537391234126e-06 7.06389798374433e-07 5.93558686880457e-06 5.34432609352782e-06 1.35389402377355e-05 1.15549717488801e-06 1.55311566671774e-05 -1.40548729923619e-05 1.44985747423555e-06 8.92410056694426e-06 1.15549717488801e-06 8.01053706710289e-05 2910 2898 0 414 0 2910 2898 0 414 0 0 0 0 0 0 0 0 0 3392 0 0 0 0 0 391 +847 929 0.970991012449118 0.236409860968707 0.0358724320306472 0.909674939468878 -0.23620818268854 0.971652843819797 -0.00982066840281576 -0.348951282482972 -0.0371772534490402 0.00106241877679979 0.999308122198718 0.809399681298487 5.89090083496645e-05 -4.85965295490168e-05 -1.02762261963059e-05 1.7368993852848e-05 3.92629212868232e-06 6.47572246237478e-05 -4.85965295490168e-05 0.000103405587663963 9.07911266955187e-06 -4.92805405846285e-06 -6.59828915241628e-06 -2.36340503486523e-05 -1.02762261963059e-05 9.07911266955187e-06 1.35859349803743e-05 -1.09046252256272e-05 6.16453139467363e-06 -1.08794887933738e-05 1.7368993852848e-05 -4.92805405846285e-06 -1.09046252256272e-05 6.37678597667986e-05 5.90334456186509e-06 2.94145053409462e-05 3.92629212868232e-06 -6.59828915241628e-06 6.16453139467363e-06 5.90334456186509e-06 2.56219498568568e-05 1.39220038302787e-05 6.47572246237478e-05 -2.36340503486523e-05 -1.08794887933738e-05 2.94145053409462e-05 1.39220038302787e-05 0.000304370730253421 531 555 0 999 0 531 555 0 999 0 0 0 0 0 0 0 0 0 699 0 0 0 0 0 1057 +847 930 0.980641836320129 0.175885845414575 0.0860567152608393 0.905926164639529 -0.174837836905399 0.984401606322236 -0.0196267230184472 -0.339073376967565 -0.0881664315084028 0.00420081575436756 0.996096899654884 0.780898614590084 4.16828146146113e-05 -3.34670624703462e-05 -1.58390968307406e-06 1.00343486066278e-05 6.47774061336243e-07 3.38482560748945e-05 -3.34670624703462e-05 0.000106352443113147 2.86462520454888e-06 -1.08107539845513e-05 -3.12002472815561e-06 -4.88164220059863e-05 -1.58390968307406e-06 2.86462520454888e-06 1.13245158392065e-05 -6.20770038632049e-06 7.07524684231172e-06 -6.04226917893497e-06 1.00343486066278e-05 -1.08107539845513e-05 -6.20770038632049e-06 4.56848458752587e-05 -3.5397909891538e-08 1.58903176993582e-05 6.47774061336243e-07 -3.12002472815561e-06 7.07524684231172e-06 -3.5397909891538e-08 1.90480533013537e-05 6.5241411724811e-06 3.38482560748945e-05 -4.88164220059863e-05 -6.04226917893497e-06 1.58903176993582e-05 6.5241411724811e-06 0.00017613164670765 729 751 0 1007 0 729 751 0 1007 0 0 0 0 0 0 0 0 0 665 0 0 0 0 0 1203 +847 850 0.993802705890449 0.109997642974145 -0.0160218695836434 0.341651314452875 -0.110182591521379 0.993848753047718 -0.0111558321576318 -0.0505754989886889 0.0146961998644425 0.0128520272964575 0.999809405388805 0.118866700641115 3.73630973595437e-05 -1.61501121843985e-05 -5.66550900385805e-06 1.27779955017625e-05 3.95198359312633e-06 2.23875033788658e-05 -1.61501121843985e-05 3.17984990373574e-05 7.09548015610559e-06 -7.38877422004108e-06 -4.42999884144892e-06 -5.90440228465529e-06 -5.66550900385805e-06 7.09548015610559e-06 1.24603923768038e-05 -4.53920358244958e-06 2.37809176208582e-07 -1.00515622437049e-05 1.27779955017625e-05 -7.38877422004108e-06 -4.53920358244958e-06 4.50308945629048e-05 1.59112691301045e-05 3.33729183344098e-05 3.95198359312633e-06 -4.42999884144892e-06 2.37809176208582e-07 1.59112691301045e-05 2.54778158028162e-05 2.05643929552163e-05 2.23875033788658e-05 -5.90440228465529e-06 -1.00515622437049e-05 3.33729183344098e-05 2.05643929552163e-05 0.000157321162602286 3489 3609 0 621 59 3489 3609 0 621 101 0 0 0 0 0 0 0 0 3302 0 0 0 0 0 1889 +847 935 0.973443402078771 -0.181628787476121 -0.139351808417622 0.992578903177349 0.175629142362911 0.982957150166499 -0.0543106369823004 -0.161260163061934 0.146841231614885 0.0283940926340081 0.988752460528577 0.314096234204952 2.72664684518159e-05 -8.26741916715026e-06 -1.59277036177374e-06 5.15303181679957e-06 3.25559304615971e-07 4.96241535138525e-06 -8.26741916715026e-06 3.91660584512067e-05 -2.61334261906318e-07 5.67735877623088e-06 -3.78074444426139e-07 -2.24991028724481e-05 -1.59277036177374e-06 -2.61334261906318e-07 1.16547350681138e-05 2.99438150989246e-06 3.4999731225247e-06 7.03984645700702e-07 5.15303181679957e-06 5.67735877623088e-06 2.99438150989246e-06 6.75443487304896e-05 -7.80052440995795e-07 1.09709008244667e-05 3.25559304615971e-07 -3.78074444426139e-07 3.4999731225247e-06 -7.80052440995795e-07 1.78690158297241e-05 9.61055164680586e-07 4.96241535138525e-06 -2.24991028724481e-05 7.03984645700702e-07 1.09709008244667e-05 9.61055164680586e-07 8.87662038327043e-05 1814 1812 0 486 0 1814 1812 0 486 0 0 0 0 0 0 0 0 0 2461 0 0 0 0 0 713 +847 939 0.924827687069016 -0.357651918467089 -0.129533217544323 1.15524161576551 0.353049128697759 0.933823780353633 -0.0577014728737802 0.0854712569110322 0.141598241360293 0.00763233010689324 0.989894785106383 -0.073675338237376 3.73986533524792e-05 -1.93790413730299e-05 -1.71327435582801e-06 4.21000996989516e-06 -8.49304155342101e-07 1.79171235814664e-05 -1.93790413730299e-05 3.26577612649822e-05 3.35390733678626e-06 -8.18225601402083e-06 -4.41199908163854e-07 -1.3621058180773e-05 -1.71327435582801e-06 3.35390733678626e-06 1.22718566202135e-05 -1.59205314766716e-06 5.18576176834284e-06 -4.28045705454935e-06 4.21000996989516e-06 -8.18225601402083e-06 -1.59205314766716e-06 5.9137127105854e-05 2.95290233678079e-06 1.6890122747748e-05 -8.49304155342101e-07 -4.41199908163854e-07 5.18576176834284e-06 2.95290233678079e-06 1.46030059171766e-05 -4.30031216926838e-06 1.79171235814664e-05 -1.3621058180773e-05 -4.28045705454935e-06 1.6890122747748e-05 -4.30031216926838e-06 9.71972031505556e-05 2977 3035 0 222 392 2977 3035 0 222 392 0 0 0 0 0 0 0 0 3455 0 0 0 0 0 193 +847 894 0.965899839913233 0.257342210752183 0.0285041369062532 0.910916062064475 -0.256582502368014 0.966123508192691 -0.027763040107591 -0.351403385532574 -0.0346831188643631 0.0195026532201799 0.999208050299443 0.822228278425647 6.56990766146091e-05 -4.59318117202885e-05 -2.33046175093641e-06 3.79129923354629e-06 -7.17447835277061e-06 3.72963452750299e-05 -4.59318117202885e-05 0.000146788011138949 -2.43955603319167e-06 3.51444749710434e-05 1.10533331908518e-05 -5.5406986546685e-05 -2.33046175093641e-06 -2.43955603319167e-06 1.398597470178e-05 -1.21517849909849e-05 8.37402076063521e-06 3.19176212187943e-06 3.79129923354629e-06 3.51444749710434e-05 -1.21517849909849e-05 8.311578601211e-05 1.02176351514274e-05 -3.86274482455651e-05 -7.17447835277061e-06 1.10533331908518e-05 8.37402076063521e-06 1.02176351514274e-05 3.07934143660365e-05 -2.27753739374585e-05 3.72963452750299e-05 -5.5406986546685e-05 3.19176212187943e-06 -3.86274482455651e-05 -2.27753739374585e-05 0.000242957949130544 493 509 0 960 0 493 509 0 960 0 0 0 0 0 0 0 0 0 548 0 0 0 0 0 1413 +847 899 0.965524734251507 0.25801273577841 0.034516890426251 0.921168999102036 -0.257087010189021 0.965950669576592 -0.0290787402857085 -0.34998551316894 -0.0408442987530445 0.0192023988260204 0.998980986374965 0.83428639634353 6.85500274296392e-05 -7.45294091123205e-05 1.21394003150022e-06 -1.16445311207743e-05 -5.74555618248448e-06 0.000109906690509532 -7.45294091123205e-05 0.000166989751775121 -1.74531162502233e-06 2.70623543943682e-05 6.4568410941962e-06 -0.000159353088397638 1.21394003150022e-06 -1.74531162502233e-06 1.31578401317525e-05 -7.51847447584064e-06 7.24588846772324e-06 4.18229452172993e-06 -1.16445311207743e-05 2.70623543943682e-05 -7.51847447584064e-06 6.63403117769948e-05 1.25388409461101e-05 -3.16309720158419e-05 -5.74555618248448e-06 6.4568410941962e-06 7.24588846772324e-06 1.25388409461101e-05 2.81910281075894e-05 -6.04836123273462e-06 0.000109906690509532 -0.000159353088397638 4.18229452172993e-06 -3.16309720158419e-05 -6.04836123273462e-06 0.000370941182765978 498 512 0 990 0 498 512 0 990 0 0 0 0 0 0 0 0 0 585 0 0 0 0 0 1380 +848 935 0.9691150812685 -0.21127572418804 -0.12719484119558 0.878145800382004 0.206314989491496 0.977148310883706 -0.0511400395799978 -0.121967970364813 0.135092873124651 0.0233183812890052 0.990558513529104 0.254155894824938 3.09609361714887e-05 -1.11073481535947e-05 8.21309135306988e-07 6.40806862972378e-06 -5.90263601139282e-07 2.63402296620363e-05 -1.11073481535947e-05 4.82310461755203e-05 -5.18193420423057e-07 4.8927794852885e-06 1.90022251902388e-06 7.29425027023466e-06 8.21309135306988e-07 -5.18193420423057e-07 1.11623760002208e-05 3.45093183007495e-06 6.15158104452418e-06 -3.66503593863124e-06 6.40806862972378e-06 4.8927794852885e-06 3.45093183007495e-06 5.3443368026693e-05 2.6083465076677e-06 3.29292343238961e-05 -5.90263601139282e-07 1.90022251902388e-06 6.15158104452418e-06 2.6083465076677e-06 1.40806118376663e-05 8.05959244037419e-07 2.63402296620363e-05 7.29425027023466e-06 -3.66503593863124e-06 3.29292343238961e-05 8.05959244037419e-07 0.000165056350117604 1856 1854 0 243 0 1856 1854 0 245 0 0 0 0 0 0 0 0 0 3013 0 0 0 0 0 702 +848 937 0.949393126202773 -0.295101654198159 -0.10755326870177 0.927380983681636 0.291864453965877 0.955398080960199 -0.0450516082817335 -0.0159322068088821 0.116050990646895 0.0113807111851704 0.993178054017906 -0.00264932857287359 3.98181881180597e-05 -1.62018995133209e-05 -2.13707514386811e-06 8.94689594136395e-06 -1.58111578557405e-06 3.1051857262994e-05 -1.62018995133209e-05 4.10372445251985e-05 2.86208043343198e-06 -5.7602875658773e-06 -1.10562655049874e-06 -1.02412211401724e-05 -2.13707514386811e-06 2.86208043343198e-06 1.14791496982715e-05 1.08032297939476e-06 5.81007877389888e-06 -4.23926377724281e-06 8.94689594136395e-06 -5.7602875658773e-06 1.08032297939476e-06 5.24247279086256e-05 2.88888273613495e-06 3.22980802079928e-05 -1.58111578557405e-06 -1.10562655049874e-06 5.81007877389888e-06 2.88888273613495e-06 1.28871450461573e-05 -3.51670862449852e-06 3.1051857262994e-05 -1.02412211401724e-05 -4.23926377724281e-06 3.22980802079928e-05 -3.51670862449852e-06 0.000134586512423575 2895 2883 0 75 0 2895 2883 0 77 0 0 0 0 0 0 0 0 0 3715 0 0 0 0 0 408 +848 850 0.996779645033875 0.0801888597779846 -0.000293280836479905 0.225823096327707 -0.0801880441046497 0.996734935136984 -0.00945233622671016 -0.0316467245504208 -0.000465648808732307 0.00944541396545169 0.999955282663284 0.0687178521807076 3.76720982234223e-05 -1.58550452908277e-05 -6.0375202488149e-06 -2.41139347165775e-06 -6.01530824673861e-07 -1.81938642911669e-05 -1.58550452908277e-05 2.4034072483723e-05 6.98163266299468e-06 -4.88252926747461e-06 -2.88969346851378e-06 4.12578602796895e-06 -6.0375202488149e-06 6.98163266299468e-06 1.17988611440698e-05 -2.2700808596431e-06 5.96362568999982e-07 -6.98905396854538e-06 -2.41139347165775e-06 -4.88252926747461e-06 -2.2700808596431e-06 4.48066954904851e-05 1.60435333983083e-05 3.34145838507755e-05 -6.01530824673861e-07 -2.88969346851378e-06 5.96362568999982e-07 1.60435333983083e-05 2.41762972472487e-05 1.9520178906471e-05 -1.81938642911669e-05 4.12578602796895e-06 -6.98905396854538e-06 3.34145838507755e-05 1.9520178906471e-05 0.000232697599945897 3540 3660 0 403 1 3540 3660 0 405 52 0 0 0 0 0 0 0 0 3518 0 0 0 0 0 1759 +848 851 0.993759220697599 0.11140394306672 -0.00563673200420933 0.334843169731261 -0.111520948846096 0.993343223588239 -0.0288499240864157 -0.0561855143882604 0.00238521423916203 0.0292984917788019 0.999567861194287 0.129051242301831 3.94996657354268e-05 -2.11002997625333e-05 3.79010638768211e-06 -1.1512112233294e-05 -4.08418295826688e-06 1.52825948279086e-05 -2.11002997625333e-05 4.03017362314869e-05 -3.50663105303981e-06 5.89783420121923e-06 6.55596366236975e-06 -2.24261579561808e-05 3.79010638768211e-06 -3.50663105303981e-06 1.22612872285442e-05 1.69591330321878e-06 2.63316916519136e-06 4.93120042708903e-06 -1.1512112233294e-05 5.89783420121923e-06 1.69591330321878e-06 3.5530236779803e-05 8.52710873673801e-06 6.81663732856993e-06 -4.08418295826688e-06 6.55596366236975e-06 2.63316916519136e-06 8.52710873673801e-06 2.28672757645766e-05 -1.84031707964299e-06 1.52825948279086e-05 -2.24261579561808e-05 4.93120042708903e-06 6.81663732856993e-06 -1.84031707964299e-06 0.000110030228339822 3175 3342 0 601 63 3175 3342 0 603 117 0 0 0 0 0 0 0 0 3315 0 0 0 0 0 1500 +848 931 0.994608340696682 0.0770090848114206 0.0694539377796508 0.814283676079949 -0.0753481274525109 0.996812262479153 -0.0262292405645417 -0.281693306508421 -0.071252426667394 0.0208545972797331 0.997240280707868 0.670236167872812 7.86568402181338e-05 -9.15976568984893e-05 -6.40632480312435e-06 6.54084514126426e-06 7.59779082136815e-07 0.00010000526581553 -9.15976568984893e-05 0.000174530818545129 7.21053324890268e-06 -1.24968077001853e-05 -1.37243650233965e-05 -0.000155691329676713 -6.40632480312435e-06 7.21053324890268e-06 1.25420313514939e-05 -7.10730233819618e-06 5.63728275464843e-06 -8.18196595244792e-06 6.54084514126426e-06 -1.24968077001853e-05 -7.10730233819618e-06 6.283763539795e-05 1.27626663013853e-05 5.43631745369784e-06 7.59779082136815e-07 -1.37243650233965e-05 5.63728275464843e-06 1.27626663013853e-05 2.90870646826136e-05 1.73531183625611e-05 0.00010000526581553 -0.000155691329676713 -8.18196595244792e-06 5.43631745369784e-06 1.73531183625611e-05 0.000300128505620265 905 923 0 749 0 905 923 0 751 0 0 0 0 0 0 0 0 0 1151 0 0 0 0 0 789 +848 930 0.984003871758461 0.146273586803714 0.101687846707141 0.806919556938169 -0.14601318922943 0.989231697383774 -0.0100397939355685 -0.296425210612268 -0.102061397871132 -0.00496857069932648 0.994765693201065 0.727927133627611 4.03150887290753e-05 -5.00871793348084e-05 -3.36051683374892e-06 8.19608115686779e-06 1.18024171805967e-06 4.49948056868175e-05 -5.00871793348084e-05 0.000144045099373603 5.16000541591982e-06 -1.00591949498026e-05 -5.64034350953925e-06 -9.29673225260735e-05 -3.36051683374892e-06 5.16000541591982e-06 1.2566319728911e-05 -4.91400453517285e-06 7.01252948010054e-06 -4.75598012360685e-06 8.19608115686779e-06 -1.00591949498026e-05 -4.91400453517285e-06 4.33989030532717e-05 8.94620060900732e-07 1.36350081839117e-05 1.18024171805967e-06 -5.64034350953925e-06 7.01252948010054e-06 8.94620060900732e-07 2.36736177269571e-05 6.08709998454874e-06 4.49948056868175e-05 -9.29673225260735e-05 -4.75598012360685e-06 1.36350081839117e-05 6.08709998454874e-06 0.000147686782417071 743 766 0 839 0 743 766 0 841 0 0 0 0 0 0 0 0 0 915 0 0 0 0 0 1272 +848 939 0.915926461890553 -0.385011579313517 -0.113334902846231 1.03721977007921 0.380919403703809 0.922870491533483 -0.0566609542690664 0.129996731823173 0.126408560986145 0.00872580375999298 0.991939885304626 -0.126349619309144 3.70041830844502e-05 -1.94818377474224e-05 -9.13866495478097e-07 2.47932880788454e-06 -9.98467327875677e-07 4.12562338901909e-05 -1.94818377474224e-05 3.20737626635216e-05 6.48825228561325e-07 1.50143557244896e-06 -3.99254488467384e-07 -9.97097034900421e-06 -9.13866495478097e-07 6.48825228561325e-07 1.09058202073092e-05 -9.61717078145744e-07 4.46606914221739e-06 -1.31171024411297e-06 2.47932880788454e-06 1.50143557244896e-06 -9.61717078145744e-07 9.09957305919386e-05 -2.36097567102104e-06 4.0891857396849e-05 -9.98467327875677e-07 -3.99254488467384e-07 4.46606914221739e-06 -2.36097567102104e-06 1.41681218062714e-05 -3.44221387835615e-06 4.12562338901909e-05 -9.97097034900421e-06 -1.31171024411297e-06 4.0891857396849e-05 -3.44221387835615e-06 0.000177068421424945 2916 3006 0 0 392 2920 3010 0 0 392 0 0 0 0 0 126 94 0 3652 0 0 0 0 0 203 +848 933 0.995456825306747 -0.0904253752395737 -0.0298154400100714 0.850778377071524 0.0890325060157969 0.995005530589705 -0.045135429193114 -0.212788026686131 0.0337479158283731 0.0422758277113745 0.998535844408481 0.506078627371644 3.23859237309798e-05 -2.89379815855017e-05 -2.57068628433086e-06 1.40216625567332e-06 -2.8660203857918e-06 3.37185100625831e-05 -2.89379815855017e-05 6.88318053207832e-05 5.63975584324297e-06 4.19573701420675e-06 2.69746338791089e-06 -4.90527614972688e-05 -2.57068628433086e-06 5.63975584324297e-06 1.10100314547317e-05 -1.37884074152967e-07 5.68498015799473e-06 -3.42366319639426e-06 1.40216625567332e-06 4.19573701420675e-06 -1.37884074152967e-07 6.5030236232049e-05 8.40875297896411e-06 1.07851218380969e-05 -2.8660203857918e-06 2.69746338791089e-06 5.68498015799473e-06 8.40875297896411e-06 1.65689334266357e-05 8.51608761771319e-07 3.37185100625831e-05 -4.90527614972688e-05 -3.42366319639426e-06 1.07851218380969e-05 8.51608761771319e-07 0.000159697394198125 1317 1325 0 459 0 1317 1325 0 461 0 0 0 0 0 0 0 0 0 1688 0 0 0 0 0 1283 +848 894 0.972240579425495 0.228561787512419 0.0500775898731765 0.819568067969268 -0.227699457093178 0.973474394828904 -0.0223731949432914 -0.310670761149073 -0.0538629089248831 0.0103494879886081 0.998494704613161 0.791430039318137 4.43982868114397e-05 -3.81653027593217e-05 -1.01811619121248e-06 -8.41079360712712e-06 -8.10838653382468e-06 5.45271101503057e-05 -3.81653027593217e-05 8.22166629874568e-05 1.88545727159022e-06 1.60421591291774e-05 7.56020247941407e-06 -8.99892100432169e-05 -1.01811619121248e-06 1.88545727159022e-06 1.21730769733789e-05 -8.04219048707296e-06 7.10902455513957e-06 -2.02354242466255e-06 -8.41079360712712e-06 1.60421591291774e-05 -8.04219048707296e-06 5.98461654488765e-05 1.04702588919808e-05 -1.47978175298302e-05 -8.10838653382468e-06 7.56020247941407e-06 7.10902455513957e-06 1.04702588919808e-05 2.8042373127147e-05 -1.02146917754243e-06 5.45271101503057e-05 -8.99892100432169e-05 -2.02354242466255e-06 -1.47978175298302e-05 -1.02146917754243e-06 0.000205247370761777 493 505 0 831 0 493 505 0 831 0 0 0 0 0 0 0 0 0 681 0 0 0 0 0 1393 +848 936 0.961464847136774 -0.259129907665326 -0.091853354177291 0.912352330115125 0.25452467987467 0.965268738981063 -0.0589359727212955 -0.0700636627001459 0.10393524452733 0.0332859204359478 0.994026917364805 0.12782067579607 4.93183709945601e-05 -1.82237191815952e-05 1.8387840215612e-06 9.90845465857646e-06 1.90244540548609e-06 5.87028989146566e-05 -1.82237191815952e-05 0.00013019708010942 -2.11746289689843e-07 -1.31953157486949e-06 -2.98889946503867e-06 7.24073799251141e-07 1.8387840215612e-06 -2.11746289689843e-07 1.08542959354597e-05 1.6086596990228e-06 4.45907552122774e-06 -1.32655979405656e-06 9.90845465857646e-06 -1.31953157486949e-06 1.6086596990228e-06 7.18663937619583e-05 4.29868076109891e-06 5.56760134254494e-05 1.90244540548609e-06 -2.98889946503867e-06 4.45907552122774e-06 4.29868076109891e-06 1.3702584355266e-05 1.6609105580949e-06 5.87028989146566e-05 7.24073799251141e-07 -1.32655979405656e-06 5.56760134254494e-05 1.6609105580949e-06 0.000289867108406747 2391 2383 0 176 0 2391 2383 0 179 0 0 0 0 0 0 0 0 0 3200 0 0 0 0 0 550 +848 899 0.972411354135874 0.229028839829686 0.0442938920609184 0.815117530534337 -0.228322573951744 0.973370442352427 -0.0204642170309751 -0.308153365680196 -0.047801261193474 0.00978634154873127 0.998808924142854 0.779646584065495 6.85503670212838e-05 -8.22642595320093e-05 -6.05989288733482e-06 2.41544932638549e-06 -3.53103944752571e-06 8.20215332573455e-05 -8.22642595320093e-05 0.000224724511643184 7.88599423200809e-06 1.3612501771613e-05 4.63413292670858e-06 -0.000102229760220951 -6.05989288733482e-06 7.88599423200809e-06 1.33204709737813e-05 -7.2968763217884e-06 8.61128078630009e-06 -7.0461875333893e-06 2.41544932638549e-06 1.3612501771613e-05 -7.2968763217884e-06 4.99882661720407e-05 1.73024971763759e-06 3.32855760465135e-06 -3.53103944752571e-06 4.63413292670858e-06 8.61128078630009e-06 1.73024971763759e-06 2.44904745771689e-05 7.39108255073314e-06 8.20215332573455e-05 -0.000102229760220951 -7.0461875333893e-06 3.32855760465135e-06 7.39108255073314e-06 0.000215394547118644 516 530 0 856 0 516 530 0 857 0 0 0 0 0 0 0 0 0 799 0 0 0 0 0 1416 +848 934 0.982636856803279 -0.162071808043496 -0.0903190826419536 0.877014947635764 0.158879750622918 0.986424312315704 -0.0415247024611884 -0.168725104923377 0.0958229225904273 0.0264538297795092 0.995046814173196 0.383561161283068 3.57429913299465e-05 -2.73035093145397e-05 -1.74332442677337e-06 1.15204932595191e-05 2.35245553091091e-06 3.27345556323876e-05 -2.73035093145397e-05 8.53791159019247e-05 1.69523850502938e-06 -2.25601661945822e-06 -1.1737260886705e-06 -9.59593074935761e-05 -1.74332442677337e-06 1.69523850502938e-06 1.10688285021058e-05 1.643309913915e-06 5.29898320764106e-06 -1.76828632104962e-06 1.15204932595191e-05 -2.25601661945822e-06 1.643309913915e-06 5.97516688172301e-05 6.9303225225919e-06 -5.69542366541271e-06 2.35245553091091e-06 -1.1737260886705e-06 5.29898320764106e-06 6.9303225225919e-06 1.78763290935804e-05 -1.51937356052348e-07 3.27345556323876e-05 -9.59593074935761e-05 -1.76828632104962e-06 -5.69542366541271e-06 -1.51937356052348e-07 0.000178041256282815 1528 1531 0 313 0 1528 1531 0 315 0 0 0 0 0 0 0 0 0 2325 0 0 0 0 0 1153 +848 938 0.934734819259412 -0.337132816869773 -0.112304414221023 0.968376524524472 0.33549126932002 0.941437344345534 -0.033783648140331 0.0482562815837782 0.117117145944207 -0.00609839823887634 0.993099382571958 -0.0811206052457219 5.01031536039588e-05 -1.90031131030499e-05 -2.89654423989867e-06 1.21955085915492e-05 1.26908484668325e-06 3.12867465135848e-05 -1.90031131030499e-05 6.11009176592102e-05 3.7523709326222e-06 4.49157989692777e-06 -4.12121685413681e-06 -1.04773167354199e-05 -2.89654423989867e-06 3.7523709326222e-06 1.28845533509862e-05 -1.10937086416327e-06 6.26493738880438e-06 -4.75895968844673e-06 1.21955085915492e-05 4.49157989692777e-06 -1.10937086416327e-06 6.85939549947275e-05 -5.90711150362863e-07 4.50429250643438e-05 1.26908484668325e-06 -4.12121685413681e-06 6.26493738880438e-06 -5.90711150362863e-07 1.44636398519669e-05 -4.82702799903276e-06 3.12867465135848e-05 -1.04773167354199e-05 -4.75895968844673e-06 4.50429250643438e-05 -4.82702799903276e-06 0.000231462482678499 2924 3040 0 0 65 2925 3041 0 0 65 0 0 0 0 0 39 21 0 3691 0 0 0 0 0 295 +848 929 0.977017727380763 0.20736766696735 0.0493458314373872 0.812165731526904 -0.207532644286232 0.978226413021525 -0.0018128493056538 -0.305593804445906 -0.0486473220156369 -0.00846968497400997 0.998780107179327 0.752926780884486 5.20515028688033e-05 -4.12450809384097e-05 -9.62446646689705e-06 8.23295083634832e-06 8.10092103584313e-06 4.83867170877234e-05 -4.12450809384097e-05 7.83030057003864e-05 1.06066895204758e-05 3.089936479529e-06 -8.23973283184108e-06 -3.12498020762645e-05 -9.62446646689705e-06 1.06066895204758e-05 1.45517814792911e-05 -7.00551707537661e-06 4.32075140674422e-06 -1.00100529126461e-05 8.23295083634832e-06 3.089936479529e-06 -7.00551707537661e-06 5.58902460988008e-05 1.33316754777096e-05 6.07658059085147e-06 8.10092103584313e-06 -8.23973283184108e-06 4.32075140674422e-06 1.33316754777096e-05 3.16464617758223e-05 8.32715075669263e-06 4.83867170877234e-05 -3.12498020762645e-05 -1.00100529126461e-05 6.07658059085147e-06 8.32715075669263e-06 0.000203857084864499 549 574 0 849 0 549 574 0 851 0 0 0 0 0 0 0 0 0 924 0 0 0 0 0 1030 +848 895 0.972555283360794 0.229151259567934 0.0403227112857524 0.811736509152327 -0.228543712743935 0.973345408948814 -0.0191438304287236 -0.304491875689651 -0.0436347587620526 0.00940293128207066 0.999003299649747 0.760219726821969 9.40913282329872e-05 -8.34159337501804e-05 -7.37137608332446e-06 1.31864109547911e-05 -1.8353485368271e-06 5.30779030807956e-07 -8.34159337501804e-05 0.000235174959344255 7.69526415745409e-06 2.20596957537971e-06 5.42717089506265e-06 9.02754367903971e-05 -7.37137608332446e-06 7.69526415745409e-06 1.45069546686897e-05 -6.37901522628325e-06 8.47955418391988e-06 4.48937227017024e-06 1.31864109547911e-05 2.20596957537971e-06 -6.37901522628325e-06 5.81550373861106e-05 3.58212056107686e-06 2.52337452476509e-05 -1.8353485368271e-06 5.42717089506265e-06 8.47955418391988e-06 3.58212056107686e-06 2.31946026108531e-05 2.37171058951401e-05 5.30779030807956e-07 9.02754367903971e-05 4.48937227017024e-06 2.52337452476509e-05 2.37171058951401e-05 0.000899500801022702 521 539 0 854 0 521 539 0 854 0 0 0 0 0 0 0 0 0 832 0 0 0 0 0 857 +848 932 0.999892350600567 -0.000291856796092628 0.0146697658496775 0.829780545901282 0.000627656838336252 0.99973776439289 -0.0228912318060905 -0.252452613349554 -0.0146592379531502 0.0228979751575867 0.999630326408876 0.589675387185162 3.97546886009542e-05 -3.760534055756e-05 -4.16745468348469e-06 4.41695879873155e-06 -3.66435750790205e-06 4.06889456411969e-05 -3.760534055756e-05 0.000133927233403353 7.40034411981925e-06 -9.73237966569328e-07 6.96082454419752e-07 -0.000122624934131263 -4.16745468348469e-06 7.40034411981925e-06 1.39596130825672e-05 -6.67009709414835e-06 6.34571139691502e-06 -3.46950396551748e-06 4.41695879873155e-06 -9.73237966569328e-07 -6.67009709414835e-06 5.98057686517652e-05 2.6891876893552e-06 -6.28327240422314e-06 -3.66435750790205e-06 6.96082454419752e-07 6.34571139691502e-06 2.6891876893552e-06 2.16541015604951e-05 -3.67887364907597e-06 4.06889456411969e-05 -0.000122624934131263 -3.46950396551748e-06 -6.28327240422314e-06 -3.67887364907597e-06 0.00017566974058826 1133 1148 0 617 0 1133 1148 0 619 0 0 0 0 0 0 0 0 0 1469 0 0 0 0 0 739 +848 898 0.972538005053998 0.229132814551141 0.0408409356095387 0.810979781370305 -0.228491074610523 0.973344509498473 -0.0198064295748879 -0.30586495900487 -0.0442906033930282 0.00993071624048129 0.998969330523231 0.759660542837671 8.02708553560537e-05 -6.32604467306236e-05 -7.2924375042344e-06 1.72774359948888e-05 2.84424284381827e-06 4.69855778766989e-05 -6.32604467306236e-05 0.000218909810309468 4.55337858861052e-06 2.13793732968991e-05 1.67813068452277e-05 0.000102788363414245 -7.2924375042344e-06 4.55337858861052e-06 1.4152205087583e-05 -7.40441337551878e-06 5.55008003259545e-06 -6.32884852730569e-06 1.72774359948888e-05 2.13793732968991e-05 -7.40441337551878e-06 6.26013303034289e-05 1.17955418441645e-05 2.72730810536972e-05 2.84424284381827e-06 1.67813068452277e-05 5.55008003259545e-06 1.17955418441645e-05 3.27617052053926e-05 3.69485509231281e-05 4.69855778766989e-05 0.000102788363414245 -6.32884852730569e-06 2.72730810536972e-05 3.69485509231281e-05 0.00106696468903396 515 529 0 860 0 515 529 0 860 0 0 0 0 0 0 0 0 0 835 0 0 0 0 0 815 +848 897 0.97270733632345 0.228618139314256 0.0396759907126024 0.808440096364565 -0.227883213784677 0.973435106337857 -0.0222111373903367 -0.311160498840439 -0.043699871140614 0.0125634440139898 0.998965705686037 0.747744751383058 7.75365910647646e-05 -5.95355876142407e-05 3.19418835830228e-06 -1.18232586423054e-05 -9.80211135621325e-06 2.2119088832955e-05 -5.95355876142407e-05 0.000155509185424898 -2.73664861855201e-06 2.14475958573542e-05 1.48623870015547e-05 3.30399381145515e-05 3.19418835830228e-06 -2.73664861855201e-06 1.42447013362635e-05 -8.32990064880401e-06 6.13601660639689e-06 -9.02541822569891e-06 -1.18232586423054e-05 2.14475958573542e-05 -8.32990064880401e-06 6.08811094576184e-05 1.53301400775787e-05 5.15621547041139e-05 -9.80211135621325e-06 1.48623870015547e-05 6.13601660639689e-06 1.53301400775787e-05 3.06107257122209e-05 4.04206377755234e-05 2.2119088832955e-05 3.30399381145515e-05 -9.02541822569891e-06 5.15621547041139e-05 4.04206377755234e-05 0.00115315967256372 569 579 0 815 0 569 579 0 815 0 0 0 0 0 0 0 0 0 812 0 0 0 0 0 1224 +848 896 0.972206030206363 0.229133321229527 0.0480973588953812 0.821983465330374 -0.22834470999449 0.973345781453356 -0.0213701461035715 -0.307014536647911 -0.0517119739317389 0.00979340743981649 0.998614019991108 0.772160192045098 0.000109401138903816 -0.000124529349906271 -8.56146717379265e-06 -1.55483127290789e-06 -9.45049688142434e-06 0.000110863794174629 -0.000124529349906271 0.000241906197482237 9.71840326325974e-06 2.2090395951574e-05 1.06282542648329e-05 -0.000142239881344361 -8.56146717379265e-06 9.71840326325974e-06 1.43902220146644e-05 -2.24464892428529e-06 8.5532300895246e-06 -5.57542924833268e-06 -1.55483127290789e-06 2.2090395951574e-05 -2.24464892428529e-06 5.45833369570903e-05 6.84222291858324e-06 -2.62922713592294e-05 -9.45049688142434e-06 1.06282542648329e-05 8.5532300895246e-06 6.84222291858324e-06 2.61539381364905e-05 -2.09784824273135e-05 0.000110863794174629 -0.000142239881344361 -5.57542924833268e-06 -2.62922713592294e-05 -2.09784824273135e-05 0.000356164518665574 514 541 0 855 0 514 541 0 858 0 0 0 0 0 0 0 0 0 759 0 0 0 0 0 849 +848 900 0.972359809141312 0.229496348166043 0.0429863669681584 0.81481145346148 -0.228748396414869 0.973244930568233 -0.0216443124367777 -0.309839016722084 -0.0468035543981113 0.0112129969983528 0.998841176561128 0.781283094288029 7.64816643720543e-05 -6.2629406343985e-05 -2.5184580705673e-06 2.9813075140201e-06 1.09752247125678e-06 9.70689607365348e-05 -6.2629406343985e-05 0.000152193895255346 4.43805580678622e-06 -1.28827856006039e-05 -1.35637163749955e-05 -0.000105149442407355 -2.5184580705673e-06 4.43805580678622e-06 1.65504590042329e-05 -9.30952842820909e-06 5.54084551797475e-06 -3.36634758525783e-06 2.9813075140201e-06 -1.28827856006039e-05 -9.30952842820909e-06 5.0659943746728e-05 6.10136789847551e-06 -1.63215947959056e-05 1.09752247125678e-06 -1.35637163749955e-05 5.54084551797475e-06 6.10136789847551e-06 2.99124331813117e-05 -4.6597820675746e-06 9.70689607365348e-05 -0.000105149442407355 -3.36634758525783e-06 -1.63215947959056e-05 -4.6597820675746e-06 0.000284138530771181 550 572 0 849 0 550 572 0 849 0 0 0 0 0 0 0 0 0 721 0 0 0 0 0 1157 +849 936 0.949963760359189 -0.2985033169573 -0.0920033899903676 0.785880918641815 0.294518218018584 0.954088777959823 -0.0545309364149236 -0.0288632716398232 0.104057067320713 0.0247057389409967 0.994264428210118 0.0905648488226466 3.6003457898706e-05 -2.09775610051581e-05 1.93530328335469e-06 6.52074521021332e-06 -9.46290431746795e-07 2.40303776705129e-05 -2.09775610051581e-05 3.77427242013428e-05 -2.80157189732583e-07 -4.65546419631906e-06 5.93979355623942e-07 -1.63331218558328e-05 1.93530328335469e-06 -2.80157189732583e-07 1.01129215277446e-05 2.85437457283812e-06 4.27401027103418e-06 -5.21587097015025e-07 6.52074521021332e-06 -4.65546419631906e-06 2.85437457283812e-06 6.03114119997744e-05 3.74777260223758e-06 1.85219994821103e-05 -9.46290431746795e-07 5.93979355623942e-07 4.27401027103418e-06 3.74777260223758e-06 1.34340410959241e-05 4.89035040730687e-07 2.40303776705129e-05 -1.63331218558328e-05 -5.21587097015025e-07 1.85219994821103e-05 4.89035040730687e-07 0.000113830703079491 2479 2479 0 0 0 2493 2493 0 0 0 0 0 0 0 0 168 160 0 3395 0 0 0 0 0 556 +849 934 0.975491535851342 -0.20240283696651 -0.0863096464498527 0.75451596131523 0.200130733260679 0.979168532721649 -0.0343026840389365 -0.126000087488064 0.0914546504390731 0.0161887651054865 0.995677644018096 0.34097920903213 2.38864201290961e-05 -1.93292729719343e-05 6.15051897086229e-07 5.55687885460795e-06 -8.07887328785083e-07 2.30645273668273e-05 -1.93292729719343e-05 6.37539075443072e-05 1.25482499804654e-06 9.58368605691846e-06 3.34587207972174e-06 -6.74934328861031e-05 6.15051897086229e-07 1.25482499804654e-06 1.09361463902905e-05 2.71100617774401e-07 7.44598312601411e-06 -3.8702110596531e-06 5.55687885460795e-06 9.58368605691846e-06 2.71100617774401e-07 5.76970873494701e-05 1.13179840636107e-06 -6.67563921514286e-06 -8.07887328785083e-07 3.34587207972174e-06 7.44598312601411e-06 1.13179840636107e-06 1.69986728410553e-05 -2.90135935420418e-06 2.30645273668273e-05 -6.74934328861031e-05 -3.8702110596531e-06 -6.67563921514286e-06 -2.90135935420418e-06 0.000146900831940024 1636 1639 0 77 0 1636 1639 0 84 0 0 0 0 0 0 0 0 0 2840 0 0 0 0 0 1220 +849 853 0.992611746555374 0.113539808606277 0.0427858909214312 0.407625924417861 -0.111224607143664 0.992376372201058 -0.0530869349539455 -0.097157162907327 -0.0484871876481649 0.0479358713148795 0.997672864658178 0.244742977291262 3.75395458994645e-05 -1.26714400803945e-05 3.85934650458499e-07 -2.51266588968171e-06 3.52768334676484e-06 4.25929171756273e-05 -1.26714400803945e-05 5.58858029544467e-05 1.67965605089254e-06 -4.01434400834945e-07 -4.62355379541022e-06 -4.68378796191065e-05 3.85934650458499e-07 1.67965605089254e-06 1.12859157030618e-05 3.86167786216627e-07 3.70757787027863e-06 -4.26500229333643e-06 -2.51266588968171e-06 -4.01434400834945e-07 3.86167786216627e-07 3.22700091427443e-05 4.08146213728587e-06 -1.21774456077228e-05 3.52768334676484e-06 -4.62355379541022e-06 3.70757787027863e-06 4.08146213728587e-06 2.02280012513798e-05 7.90184479580519e-06 4.25929171756273e-05 -4.68378796191065e-05 -4.26500229333643e-06 -1.21774456077228e-05 7.90184479580519e-06 0.000230339085046501 2151 2176 0 562 79 2151 2176 0 575 102 0 0 0 0 0 0 0 0 2525 0 0 0 0 0 1784 +849 933 0.991179101298049 -0.130917186311306 -0.0206077528692943 0.741421681440503 0.130140223591022 0.990864474393755 -0.0353711123385602 -0.165490290680457 0.0250501767193351 0.032377209773528 0.999161751136227 0.448636745927176 3.32195888532486e-05 -2.80574605395695e-05 2.79504148931669e-07 -3.63489419703919e-06 -3.85581557396292e-06 2.68436431756134e-05 -2.80574605395695e-05 6.1702330897595e-05 5.55156423712344e-07 1.34190837950261e-05 2.77269553418037e-06 -4.22192390562874e-05 2.79504148931669e-07 5.55156423712344e-07 1.01327855608594e-05 4.27498583761974e-07 6.6951837289196e-06 -2.66540663103703e-06 -3.63489419703919e-06 1.34190837950261e-05 4.27498583761974e-07 5.53869843519486e-05 2.74202053971466e-06 -6.66696188715107e-06 -3.85581557396292e-06 2.77269553418037e-06 6.6951837289196e-06 2.74202053971466e-06 1.57426133892164e-05 -3.62734743706021e-06 2.68436431756134e-05 -4.22192390562874e-05 -2.66540663103703e-06 -6.66696188715107e-06 -3.62734743706021e-06 9.77409383518553e-05 1455 1464 0 243 0 1455 1464 0 252 0 0 0 0 0 0 0 0 0 2119 0 0 0 0 0 1288 +849 931 0.996052063863376 0.0364633010197786 0.0809364797371983 0.7168270708714 -0.0367688468132178 0.999321179378419 0.00228743300508847 -0.227470955841141 -0.0807981310274873 -0.00525434339072573 0.996716636711757 0.645556526993139 0.00334538639937785 0.00103024408630722 -1.73554759386869e-05 -0.000401790070117231 0.000734643970234914 -0.000918852561520823 0.00103024408630722 0.000449803749143776 -2.30179766627244e-06 -0.000141119288550722 0.000239851436746425 -0.000352795001029516 -1.73554759386869e-05 -2.30179766627244e-06 1.32427337563041e-05 -5.90711484733649e-06 3.20548489501511e-06 1.8808964196687e-08 -0.000401790070117231 -0.000141119288550722 -5.90711484733649e-06 0.000110822369393364 -8.90870386352256e-05 0.00013279894568945 0.000734643970234914 0.000239851436746425 3.20548489501511e-06 -8.90870386352256e-05 0.000192517427945082 -0.000200326942310017 -0.000918852561520823 -0.000352795001029516 1.8808964196687e-08 0.00013279894568945 -0.000200326942310017 0.000416429934688957 998 1016 0 535 0 998 1016 0 542 0 0 0 0 0 0 0 0 0 1525 0 0 0 0 0 1076 +849 932 0.999029492677838 -0.0402120011003402 0.0179740848826527 0.724069242532122 0.0404452980210985 0.999099634166763 -0.0128101083455387 -0.205135969012636 -0.0174427815398544 0.0135246432613271 0.999756387024763 0.553846006177654 3.93073713202695e-05 -4.06296665684667e-05 -5.99521115165548e-06 1.11338952107913e-05 -4.11763159870924e-07 5.3205194185427e-05 -4.06296665684667e-05 0.000111702177383789 6.51537432129446e-06 -4.91583054752827e-06 -2.75675332184195e-06 -9.0612824487805e-05 -5.99521115165548e-06 6.51537432129446e-06 1.37612737035703e-05 -6.33809590032342e-06 6.73678200665702e-06 -8.56292960606303e-06 1.11338952107913e-05 -4.91583054752827e-06 -6.33809590032342e-06 5.34967782525091e-05 2.76055266113263e-06 2.0073982312605e-05 -4.11763159870924e-07 -2.75675332184195e-06 6.73678200665702e-06 2.76055266113263e-06 1.87707005836216e-05 7.22080578340246e-06 5.3205194185427e-05 -9.0612824487805e-05 -8.56292960606303e-06 2.0073982312605e-05 7.22080578340246e-06 0.000181293638075093 1220 1235 0 397 0 1220 1235 0 401 0 0 0 0 0 0 0 0 0 1863 0 0 0 0 0 768 +849 851 0.997460352949918 0.0711480964337431 -0.00328521945679295 0.218617391906066 -0.0711965553719146 0.997294214712158 -0.0183111934300654 -0.0331266807716671 0.00197352380234021 0.0184985857706517 0.999826938789052 0.0939653617322033 3.70898792731156e-05 -6.10816953913086e-06 -1.36518468038465e-06 9.68822547594307e-07 1.03234649978748e-06 -8.69040896177574e-06 -6.10816953913086e-06 2.8934216991637e-05 1.9263201025725e-07 2.94368294160371e-06 2.62595325970622e-06 -4.64097754667498e-06 -1.36518468038465e-06 1.9263201025725e-07 1.16125926836295e-05 1.89461168352892e-06 2.93070570179304e-06 -3.25679943994131e-06 9.68822547594307e-07 2.94368294160371e-06 1.89461168352892e-06 2.96789061432571e-05 7.66027822121633e-06 1.28074390139788e-05 1.03234649978748e-06 2.62595325970622e-06 2.93070570179304e-06 7.66027822121633e-06 1.85628680598346e-05 8.58853309029187e-06 -8.69040896177574e-06 -4.64097754667498e-06 -3.25679943994131e-06 1.28074390139788e-05 8.58853309029187e-06 0.000107585110657871 3322 3489 0 355 13 3322 3489 0 366 86 0 0 0 0 0 0 0 0 3567 0 0 0 0 0 1285 +849 939 0.898105553894517 -0.422757893950979 -0.121170034108912 0.89796228034965 0.420337554279342 0.906193088770521 -0.0461565415407529 0.172530394987363 0.129316489769414 -0.00947886948297159 0.991558065121273 -0.182032440765435 3.29928236581595e-05 -1.92797317413133e-05 -1.63602106169359e-06 1.30966869682641e-05 2.65471447267292e-06 2.93651694525912e-05 -1.92797317413133e-05 3.75739396959311e-05 1.38827567889372e-06 -2.61721249647588e-06 -2.91930131712064e-06 6.29067298383289e-07 -1.63602106169359e-06 1.38827567889372e-06 1.1303216983932e-05 7.54230554840464e-07 4.25142786347479e-06 -2.7005623496861e-06 1.30966869682641e-05 -2.61721249647588e-06 7.54230554840464e-07 7.66500054917757e-05 -2.24787088407162e-06 4.0085837671337e-05 2.65471447267292e-06 -2.91930131712064e-06 4.25142786347479e-06 -2.24787088407162e-06 1.54229390742966e-05 -1.28063621417481e-06 2.93651694525912e-05 6.29067298383289e-07 -2.7005623496861e-06 4.0085837671337e-05 -1.28063621417481e-06 0.000156169116748528 2552 2642 0 0 392 2565 2655 0 0 392 0 0 0 0 0 530 498 0 3512 0 0 0 0 0 198 +849 938 0.922793468667548 -0.375942281007241 -0.084377814238035 0.851787688944649 0.37490063074623 0.926627597433298 -0.0284747737668407 0.0967428159937342 0.0888916826851348 -0.00535696052500092 0.99602689307234 -0.122820119908317 4.19452353377266e-05 -2.76941124412374e-05 2.25513458047188e-07 -3.53125900585277e-08 -5.77830245081886e-07 2.39204396975163e-05 -2.76941124412374e-05 7.44723505085783e-05 1.30125872461279e-06 9.47978210098285e-06 -1.19951002919892e-06 -3.6858144164106e-05 2.25513458047188e-07 1.30125872461279e-06 9.10981507053845e-06 1.602134577544e-06 4.46654434673335e-06 -1.48893048909517e-06 -3.53125900585277e-08 9.47978210098285e-06 1.602134577544e-06 5.33876385799158e-05 3.17562010276014e-06 1.36393046918002e-05 -5.77830245081886e-07 -1.19951002919892e-06 4.46654434673335e-06 3.17562010276014e-06 1.11062383729072e-05 -3.33383944883188e-06 2.39204396975163e-05 -3.6858144164106e-05 -1.48893048909517e-06 1.36393046918002e-05 -3.33383944883188e-06 0.000117551593510888 2538 2658 0 0 65 2551 2671 0 0 65 0 0 0 0 0 398 376 0 3654 0 0 0 0 0 233 +849 899 0.980203488281431 0.189270967319029 0.0581173166193487 0.720448132188743 -0.188989185345945 0.981924544051012 -0.0103574906462582 -0.260175169859766 -0.0590271918965373 -0.000831095861078469 0.998256029231218 0.745280008429026 5.44739951714708e-05 -5.40915475873899e-05 -3.17120140780736e-06 -1.72150127305429e-06 -5.87305337785766e-06 6.78006468993974e-05 -5.40915475873899e-05 0.000146927114025966 6.48027366371799e-06 7.03748294673921e-06 1.73221947843977e-06 -6.28284950846276e-05 -3.17120140780736e-06 6.48027366371799e-06 1.10353150046258e-05 -6.26074754170332e-06 6.57493305163883e-06 -2.01389302458844e-06 -1.72150127305429e-06 7.03748294673921e-06 -6.26074754170332e-06 4.78938616721753e-05 5.71662629783026e-06 -7.68746878479325e-06 -5.87305337785766e-06 1.73221947843977e-06 6.57493305163883e-06 5.71662629783026e-06 2.20573410185979e-05 -8.76446261727188e-06 6.78006468993974e-05 -6.28284950846276e-05 -2.01389302458844e-06 -7.68746878479325e-06 -8.76446261727188e-06 0.000225663568337991 531 549 0 664 0 531 549 0 673 0 0 0 0 0 0 0 0 0 1075 0 0 0 0 0 1340 +849 929 0.983677862346536 0.167746131237201 0.0651083603257026 0.720686031828066 -0.168600134784102 0.985653571149544 0.00781231277752308 -0.259084470933287 -0.0628638026222756 -0.0186620774594617 0.997847618218716 0.736877601339508 6.9255222618249e-05 -3.23452812767814e-05 -6.80159234057456e-06 7.7503898067606e-06 3.2231422545376e-06 2.32121386274722e-05 -3.23452812767814e-05 9.3316900743096e-05 4.60091533709471e-06 5.54819846826587e-06 -3.53747980300523e-06 7.08029607919997e-06 -6.80159234057456e-06 4.60091533709471e-06 1.3481857776527e-05 -6.83781158879661e-06 6.93271960047069e-06 -5.29123695409071e-06 7.7503898067606e-06 5.54819846826587e-06 -6.83781158879661e-06 4.74258423304727e-05 4.67917280643703e-06 1.73189898441754e-05 3.2231422545376e-06 -3.53747980300523e-06 6.93271960047069e-06 4.67917280643703e-06 2.52995360099597e-05 -7.33914742407954e-07 2.32121386274722e-05 7.08029607919997e-06 -5.29123695409071e-06 1.73189898441754e-05 -7.33914742407954e-07 0.000269935819310679 599 625 0 668 0 599 625 0 678 0 0 0 0 0 0 0 0 0 1155 0 0 0 0 0 1122 +849 930 0.987743381804278 0.106445637924021 0.11415926536553 0.713431169643983 -0.107281929943804 0.994227927913327 0.00118948085498087 -0.249864201006214 -0.113373714808072 -0.0134221281516712 0.993461749271958 0.693370877460841 5.06611833860569e-05 -4.05745546087045e-05 -5.01860539839082e-06 8.08988091387798e-07 9.10568825680038e-07 6.40190462145596e-05 -4.05745546087045e-05 9.80518081462528e-05 4.76511783247918e-06 4.08175436683867e-06 -2.29374870460239e-06 -6.49519213584476e-05 -5.01860539839082e-06 4.76511783247918e-06 1.26127305339869e-05 -5.20442713362508e-06 7.40683542429981e-06 -8.46897524104862e-06 8.08988091387798e-07 4.08175436683867e-06 -5.20442713362508e-06 4.52772137799883e-05 -9.09812709015323e-07 -5.26709826053037e-06 9.10568825680038e-07 -2.29374870460239e-06 7.40683542429981e-06 -9.09812709015323e-07 2.23796835360452e-05 2.63488513703227e-06 6.40190462145596e-05 -6.49519213584476e-05 -8.46897524104862e-06 -5.26709826053037e-06 2.63488513703227e-06 0.000254233211515929 780 803 0 637 0 780 803 0 644 0 0 0 0 0 0 0 0 0 1192 0 0 0 0 0 1396 +849 898 0.980388131200075 0.18975971658086 0.0532011481565656 0.718737526812867 -0.189667775397236 0.981824652465804 -0.00681812190168702 -0.254792182465283 -0.0535280036792797 -0.00340613762994534 0.998560539501014 0.730741458044806 8.78404145735192e-05 -0.000117368519000142 -7.30876055994248e-06 -1.8815164472401e-05 7.33783651187874e-07 9.48285594837931e-05 -0.000117368519000142 0.000229295847877368 7.89075879122615e-06 5.42777960108084e-05 6.46255269098725e-06 -0.000123121025580453 -7.30876055994248e-06 7.89075879122615e-06 1.28254097734859e-05 -4.37108917486254e-06 4.90081760118087e-06 -8.44347066995912e-06 -1.8815164472401e-05 5.42777960108084e-05 -4.37108917486254e-06 6.25909796305626e-05 1.00612792586795e-05 -2.35900903847423e-05 7.33783651187874e-07 6.46255269098725e-06 4.90081760118087e-06 1.00612792586795e-05 2.90408845147398e-05 1.85970080120632e-06 9.48285594837931e-05 -0.000123121025580453 -8.44347066995912e-06 -2.35900903847423e-05 1.85970080120632e-06 0.000296799049955857 519 541 0 675 0 519 541 0 682 0 0 0 0 0 0 0 0 0 1117 0 0 0 0 0 1016 +849 935 0.962290493532976 -0.25095082526421 -0.104979471113511 0.772869256241618 0.246927861966967 0.967747169989214 -0.0499203962553297 -0.077130539277137 0.114121150714856 0.0221155663974207 0.9932206525654 0.213964078598783 5.64733153821724e-05 -7.40451597492238e-05 1.84660805878005e-06 -1.46279197512714e-05 -3.37729471769233e-06 0.000115720792723653 -7.40451597492238e-05 0.000281868529762638 -1.0394228645624e-05 0.000135149325804396 1.30067985932993e-05 -0.000290149993893871 1.84660805878005e-06 -1.0394228645624e-05 1.27392523476115e-05 -3.64119051384605e-06 6.02401294371716e-06 9.80345493448665e-06 -1.46279197512714e-05 0.000135149325804396 -3.64119051384605e-06 0.000142749494034318 1.37665847880389e-05 -0.000120206799566885 -3.37729471769233e-06 1.30067985932993e-05 6.02401294371716e-06 1.37665847880389e-05 1.78614383512034e-05 -1.18969067458756e-05 0.000115720792723653 -0.000290149993893871 9.80345493448665e-06 -0.000120206799566885 -1.18969067458756e-05 0.000578418195635402 1769 1769 0 0 0 1776 1775 0 2 0 0 0 0 0 0 27 25 0 3268 0 0 0 0 0 655 +849 895 0.98018975439798 0.189792394758659 0.0566294293190437 0.723668869879646 -0.189734835542867 0.98181424374531 -0.0064407266939788 -0.254138712082947 -0.0568219812638416 -0.00443144114241959 0.998374491247975 0.725989792543923 5.73000578519442e-05 -5.54546109242307e-05 -3.18780369326123e-06 4.77372487175548e-06 -1.27683096297574e-06 3.2298205776607e-05 -5.54546109242307e-05 0.000136612303529498 6.88668516935656e-06 5.98656702067338e-06 1.62878699282183e-06 -9.19405400496503e-06 -3.18780369326123e-06 6.88668516935656e-06 1.26334053122276e-05 -3.34710792862288e-06 7.51354121309035e-06 -9.1858217997276e-07 4.77372487175548e-06 5.98656702067338e-06 -3.34710792862288e-06 5.50244697535621e-05 6.10960131154049e-06 -3.89220198427812e-06 -1.27683096297574e-06 1.62878699282183e-06 7.51354121309035e-06 6.10960131154049e-06 2.63708925424737e-05 1.99613011622463e-06 3.2298205776607e-05 -9.19405400496503e-06 -9.1858217997276e-07 -3.89220198427812e-06 1.99613011622463e-06 0.000205243689192925 532 556 0 683 0 532 556 0 692 0 0 0 0 0 0 0 0 0 1157 0 0 0 0 0 1063 +849 937 0.937828119180908 -0.33395449677419 -0.094619305418593 0.807908558670177 0.331754074735343 0.942577064061834 -0.0385708724437208 0.0285028297207382 0.102066903402112 0.00478250863781527 0.994766040253201 -0.0428007667623655 4.45823180942264e-05 -1.3985797899447e-05 -1.18107481910492e-07 6.8616694481142e-06 -1.56915470788731e-06 2.60848893989261e-05 -1.3985797899447e-05 9.79740843976299e-05 3.17578665763127e-06 1.13867363741513e-05 -1.4242506255163e-06 1.26776048087181e-05 -1.18107481910492e-07 3.17578665763127e-06 9.94153187509969e-06 1.07679747941331e-06 5.68032803185494e-06 -8.78317716068913e-07 6.8616694481142e-06 1.13867363741513e-05 1.07679747941331e-06 6.5917380817377e-05 2.30082549254583e-06 3.50088850373609e-05 -1.56915470788731e-06 -1.4242506255163e-06 5.68032803185494e-06 2.30082549254583e-06 1.38374203479752e-05 -6.22888973143769e-06 2.60848893989261e-05 1.26776048087181e-05 -8.78317716068913e-07 3.50088850373609e-05 -6.22888973143769e-06 0.000146743486908871 2731 2735 0 0 0 2740 2744 0 0 0 0 0 0 0 0 286 270 0 3732 0 0 0 0 0 396 +849 852 0.99568332931688 0.0923821962499914 0.00895754076080558 0.32090804671523 -0.0919388075444883 0.994908191337061 -0.0412909975383876 -0.0597508079683982 -0.0127264837151103 0.0402892122837572 0.999107009276686 0.157471533008797 1.62548533174318e-05 -1.54680118968031e-06 -1.72186147038812e-07 -6.71070257312989e-07 1.36956738820104e-08 4.11912699770171e-06 -1.54680118968031e-06 2.61285968069098e-05 1.6907328208193e-06 -1.88831141147636e-06 -2.86014343612754e-06 -5.15019150202548e-06 -1.72186147038812e-07 1.6907328208193e-06 1.04379374205761e-05 1.22089707437742e-06 4.90255504772826e-06 -6.31180652536611e-08 -6.71070257312989e-07 -1.88831141147636e-06 1.22089707437742e-06 2.80231546334883e-05 4.66627591382533e-06 -2.53120757455033e-06 1.36956738820104e-08 -2.86014343612754e-06 4.90255504772826e-06 4.66627591382533e-06 1.59553293757807e-05 9.14524043215577e-07 4.11912699770171e-06 -5.15019150202548e-06 -6.31180652536611e-08 -2.53120757455033e-06 9.14524043215577e-07 7.02116049046174e-05 2679 2766 0 424 87 2679 2766 0 436 145 0 0 0 0 0 0 0 0 3131 0 0 0 0 0 3201 +849 940 0.897772534613668 -0.433173134856991 -0.0797841546393631 0.967889367824245 0.424244635026238 0.8991140524782 -0.107751613851873 0.261707577575679 0.118410158959461 0.0628884399106554 0.990971280300695 -0.190686083845734 4.94141733391943e-05 -1.72732274702653e-05 -1.31229618880286e-06 -2.24855056300044e-05 3.65518839069264e-06 -4.06217139169952e-05 -1.72732274702653e-05 5.70101269080605e-05 -3.09608499574552e-06 2.52707563578055e-05 -1.81145569398204e-06 5.94565877401565e-05 -1.31229618880286e-06 -3.09608499574552e-06 1.15668965008696e-05 2.10873576427371e-06 3.24524946442829e-06 -4.96747262756748e-06 -2.24855056300044e-05 2.52707563578055e-05 2.10873576427371e-06 8.08873168337753e-05 2.45397460216632e-06 0.000111155892095112 3.65518839069264e-06 -1.81145569398204e-06 3.24524946442829e-06 2.45397460216632e-06 1.67539412107033e-05 1.07156936410699e-05 -4.06217139169952e-05 5.94565877401565e-05 -4.96747262756748e-06 0.000111155892095112 1.07156936410699e-05 0.000433528558802372 2399 2478 0 0 668 2415 2494 0 0 668 0 0 0 0 0 518 485 0 3749 0 0 0 0 0 130 +849 897 0.980468303934243 0.188784259626671 0.0551580302179 0.7163054710738 -0.188637014986393 0.982015015302279 -0.00791115022534415 -0.260074704562104 -0.0556595145265616 -0.00264821412922174 0.998446295703777 0.730589179800971 6.41477412060491e-05 -7.22011727951448e-05 -3.99004860480817e-06 -1.81250474068674e-08 -5.93498366494632e-07 4.17070886748108e-05 -7.22011727951448e-05 0.000196179804552001 8.78587806285516e-06 1.78848503875908e-07 -4.36747430222468e-07 6.71261178340301e-05 -3.99004860480817e-06 8.78587806285516e-06 1.26715938645239e-05 -5.21823695009784e-06 7.07848868616443e-06 -5.42214697127798e-07 -1.81250474068674e-08 1.78848503875908e-07 -5.21823695009784e-06 4.94522827456235e-05 5.45149911874136e-06 -1.79841318847739e-05 -5.93498366494632e-07 -4.36747430222468e-07 7.07848868616443e-06 5.45149911874136e-06 2.4513005731397e-05 8.4249187621323e-06 4.17070886748108e-05 6.71261178340301e-05 -5.42214697127798e-07 -1.79841318847739e-05 8.4249187621323e-06 0.000382446405065877 561 581 0 646 0 561 581 0 655 0 0 0 0 0 0 0 0 0 1068 0 0 0 0 0 889 +849 893 0.980098252458711 0.189433710248333 0.0593488411759805 0.726485628862037 -0.189219485134817 0.981891150043927 -0.00926044873265529 -0.257298539798602 -0.0600283430780492 -0.0021538075508081 0.998194349383094 0.739046026179197 5.87764092136889e-05 -6.3037404581318e-05 -5.94412944158932e-06 4.64987334793078e-06 1.85857507865799e-06 7.52799951857434e-05 -6.3037404581318e-05 0.000130072142275154 8.6240447425009e-06 -1.70558371013669e-06 -2.61205147627018e-06 -0.00011205407985267 -5.94412944158932e-06 8.6240447425009e-06 1.27412597813151e-05 -6.47250824936134e-06 7.37623959381383e-06 -9.20829110738339e-06 4.64987334793078e-06 -1.70558371013669e-06 -6.47250824936134e-06 5.96424751635917e-05 1.125851068153e-05 1.31954762388458e-06 1.85857507865799e-06 -2.61205147627018e-06 7.37623959381383e-06 1.125851068153e-05 3.17448220329428e-05 1.50176242167599e-06 7.52799951857434e-05 -0.00011205407985267 -9.20829110738339e-06 1.31954762388458e-06 1.50176242167599e-06 0.000196828655102208 578 602 0 646 0 578 602 0 653 0 0 0 0 0 0 0 0 0 1055 0 0 0 0 0 1509 +849 894 0.980147525840827 0.189176001474764 0.0593571230276992 0.723781332695581 -0.188840464412353 0.981943181589264 -0.0112635310129888 -0.261360079961403 -0.0604161119953286 -0.000169104624119511 0.998173263925153 0.749650296915504 5.1320133629036e-05 -5.17506119015642e-05 4.19330477313676e-06 -1.04109060987611e-05 -4.9557689683119e-06 4.57568844660373e-05 -5.17506119015642e-05 0.000132585246403026 -4.14385252543194e-06 3.62604831738978e-05 1.18129744969717e-05 -6.31557536192746e-05 4.19330477313676e-06 -4.14385252543194e-06 1.30178308841993e-05 -8.11548336003457e-06 7.02291902805695e-06 -1.06363817703209e-06 -1.04109060987611e-05 3.62604831738978e-05 -8.11548336003457e-06 6.96022881450294e-05 1.1146441869732e-05 -6.87858091921108e-06 -4.9557689683119e-06 1.18129744969717e-05 7.02291902805695e-06 1.1146441869732e-05 2.76220675776403e-05 7.1398953321427e-06 4.57568844660373e-05 -6.31557536192746e-05 -1.06363817703209e-06 -6.87858091921108e-06 7.1398953321427e-06 0.000164854130065511 533 551 0 649 0 533 551 0 656 0 0 0 0 0 0 0 0 0 990 0 0 0 0 0 1346 +849 896 0.98007304624794 0.18958526192897 0.0592811308732196 0.725748832620997 -0.189492499135261 0.981855519279259 -0.00723408821686832 -0.255557898947241 -0.059576982046399 -0.00414339476519841 0.99821511483751 0.733480773151949 5.97173115353102e-05 -6.69699156617771e-05 -3.27501550618841e-06 5.52621524393921e-06 2.35082222458539e-09 5.20925991865519e-05 -6.69699156617771e-05 0.000152962600626044 4.90930600187719e-06 5.60190737425634e-06 5.02338618080197e-06 -1.24794341859654e-05 -3.27501550618841e-06 4.90930600187719e-06 1.26383828546896e-05 -5.54342883365887e-06 6.7683463415793e-06 -4.33235274428289e-06 5.52621524393921e-06 5.60190737425634e-06 -5.54342883365887e-06 5.62708042217514e-05 8.09137515370028e-06 3.27457380076618e-06 2.35082222458539e-09 5.02338618080197e-06 6.7683463415793e-06 8.09137515370028e-06 2.7348187345913e-05 1.25848086633035e-05 5.20925991865519e-05 -1.24794341859654e-05 -4.33235274428289e-06 3.27457380076618e-06 1.25848086633035e-05 0.00024318147592142 566 590 0 684 0 566 590 0 694 0 0 0 0 0 0 0 0 0 1059 0 0 0 0 0 1114 +850 934 0.966498333448776 -0.239943544900005 -0.0911485968161728 0.654869092548995 0.237135295595104 0.970626067708419 -0.0406434283484407 -0.0844962637482109 0.0982233323796362 0.0176672563153306 0.995007560288126 0.304529083269903 4.96978486094987e-05 -4.39979291582294e-05 -6.55044849641306e-06 1.27302039258158e-05 2.50994099539695e-06 4.79468290084314e-05 -4.39979291582294e-05 8.30601077537351e-05 8.59817678011639e-06 -8.03947540833392e-06 -3.80066697221849e-06 -7.90996332244754e-05 -6.55044849641306e-06 8.59817678011639e-06 1.31521541619346e-05 -2.45609972959086e-06 7.01120768982236e-06 -1.02504676394611e-05 1.27302039258158e-05 -8.03947540833392e-06 -2.45609972959086e-06 6.66482043575264e-05 5.11414680152809e-06 1.58976385385555e-05 2.50994099539695e-06 -3.80066697221849e-06 7.01120768982236e-06 5.11414680152809e-06 1.69946628882302e-05 5.28916998042425e-06 4.79468290084314e-05 -7.90996332244754e-05 -1.02504676394611e-05 1.58976385385555e-05 5.28916998042425e-06 0.000174234550004213 1427 1427 0 0 0 1441 1441 0 0 0 0 0 0 0 0 109 112 0 3025 0 0 0 0 0 631 +850 852 0.998582066426112 0.0530214688598097 0.00475188931937906 0.213240031077169 -0.052768019960945 0.997674691866364 -0.0431363568090492 -0.0367945073077341 -0.00702799271177122 0.0428244445300173 0.999057893352101 0.116195168056896 6.35419846382486e-05 -5.53242151757637e-06 -3.7207265916228e-06 2.01420412126767e-07 -3.43678958864257e-06 5.04062701935143e-06 -5.53242151757637e-06 4.87770496303261e-05 7.42985713473959e-06 -4.5473808866708e-06 -7.0086926843436e-06 -1.88279249229787e-05 -3.7207265916228e-06 7.42985713473959e-06 1.43933047238657e-05 1.54485304526906e-06 3.80302519590342e-06 -4.79736004930283e-06 2.01420412126767e-07 -4.5473808866708e-06 1.54485304526906e-06 2.95694524832004e-05 8.06290680975087e-06 6.37023042916733e-06 -3.43678958864257e-06 -7.0086926843436e-06 3.80302519590342e-06 8.06290680975087e-06 2.41836321321226e-05 8.76021799538288e-06 5.04062701935143e-06 -1.88279249229787e-05 -4.79736004930283e-06 6.37023042916733e-06 8.76021799538288e-06 0.000144627519066786 2457 2544 0 213 24 2457 2544 0 226 111 0 0 0 0 0 0 0 0 3610 0 0 0 0 0 1064 +850 854 0.995479780436834 0.0849572727877093 0.0424531334757271 0.363184876886339 -0.0814610517369646 0.993602021417961 -0.078224804787539 -0.104655474001631 -0.0488272853161092 0.074412934592151 0.996031430916738 0.272659564481096 2.35306580022638e-05 -1.76197193025645e-05 1.44243852866303e-06 1.14670246170631e-06 9.08266509099473e-07 1.44897399131348e-05 -1.76197193025645e-05 3.45850499390616e-05 -1.23071037592529e-06 -2.19218511703641e-06 -2.77221033274343e-06 -1.91355748294335e-05 1.44243852866303e-06 -1.23071037592529e-06 1.12535787539531e-05 3.14076735358029e-08 4.98899580028925e-06 5.17652091413642e-07 1.14670246170631e-06 -2.19218511703641e-06 3.14076735358029e-08 3.64708288695034e-05 2.28449919297071e-06 -5.71255287680363e-06 9.08266509099473e-07 -2.77221033274343e-06 4.98899580028925e-06 2.28449919297071e-06 1.89303798775119e-05 4.33385741319605e-06 1.44897399131348e-05 -1.91355748294335e-05 5.17652091413642e-07 -5.71255287680363e-06 4.33385741319605e-06 0.000146422054609771 1809 1830 0 369 0 1809 1830 0 386 0 0 0 0 0 0 0 0 0 2657 0 0 0 0 0 2198 +850 853 0.996756363884665 0.0734977838560428 0.0327845516009061 0.299141987387408 -0.0717266758852878 0.996053670053273 -0.0522720799266005 -0.0706373524284708 -0.0364970549752845 0.0497510014136042 0.998094586117205 0.199889528128539 3.54458834035609e-05 -2.37281511357526e-05 -6.83477978926553e-06 3.38251296997455e-06 2.5661680212831e-06 2.46968528911142e-05 -2.37281511357526e-05 5.75062180554992e-05 5.93098273352398e-06 -7.19803265731328e-07 -2.55206471687692e-06 -2.10677941934152e-05 -6.83477978926553e-06 5.93098273352398e-06 1.22862866426331e-05 -1.71208270592403e-06 2.50554827586244e-06 -4.97486133432716e-06 3.38251296997455e-06 -7.19803265731328e-07 -1.71208270592403e-06 3.39153796207737e-05 8.03440865320935e-06 6.16091804569096e-06 2.5661680212831e-06 -2.55206471687692e-06 2.50554827586244e-06 8.03440865320935e-06 1.9843966112151e-05 5.76620744539675e-06 2.46968528911142e-05 -2.10677941934152e-05 -4.97486133432716e-06 6.16091804569096e-06 5.76620744539675e-06 0.000123295916290743 2023 2049 0 358 51 2023 2049 0 377 83 0 0 0 0 0 0 0 0 3017 0 0 0 0 0 3093 +850 935 0.949302542349973 -0.289737372941612 -0.12197105315923 0.649711437069857 0.284904425352433 0.956933766757127 -0.0557425730893094 -0.0414378219461588 0.132868926022898 0.0181664735408492 0.99096711738413 0.177298112460962 3.19583665339629e-05 -1.82959765183083e-05 -1.64066845527513e-07 1.21983156085526e-06 -1.45337750536386e-07 8.88271944252571e-06 -1.82959765183083e-05 4.37724509882423e-05 -7.03921756898944e-07 7.40453207401269e-06 -1.34520537572608e-06 -4.94642254342703e-06 -1.64066845527513e-07 -7.03921756898944e-07 1.15380610143195e-05 -1.30163898264983e-06 5.09249880737759e-06 -1.80901988953509e-06 1.21983156085526e-06 7.40453207401269e-06 -1.30163898264983e-06 7.75194924451732e-05 1.60461755922259e-06 2.3246104072719e-05 -1.45337750536386e-07 -1.34520537572608e-06 5.09249880737759e-06 1.60461755922259e-06 1.72942848065588e-05 -6.02695187275153e-08 8.88271944252571e-06 -4.94642254342703e-06 -1.80901988953509e-06 2.3246104072719e-05 -6.02695187275153e-08 9.04402080983536e-05 1653 1653 0 0 0 1669 1669 0 0 0 0 0 0 0 0 231 229 0 3453 0 0 0 0 0 978 +850 937 0.922528177133928 -0.371184530268583 -0.105658917670227 0.694485606753443 0.368457582118497 0.928555571248153 -0.0449840114196897 0.0689694813369949 0.114807545803154 0.00256818872114872 0.993384433053664 -0.0733545209254199 2.19893261906979e-05 -1.01997718663307e-05 -6.84757955346072e-07 4.14153242893483e-06 1.61114802850956e-07 2.68954667195677e-05 -1.01997718663307e-05 3.8115424557316e-05 1.6005647913007e-06 4.03396710642036e-06 -1.74453091788558e-06 -4.82609185249257e-06 -6.84757955346072e-07 1.6005647913007e-06 1.11521784820354e-05 1.8592066909544e-06 5.85769643730405e-06 4.74956756431678e-08 4.14153242893483e-06 4.03396710642036e-06 1.8592066909544e-06 4.72640534450395e-05 8.9860378418906e-07 6.79347803386484e-06 1.61114802850956e-07 -1.74453091788558e-06 5.85769643730405e-06 8.9860378418906e-07 1.32539551798982e-05 -5.28424573240211e-06 2.68954667195677e-05 -4.82609185249257e-06 4.74956756431678e-08 6.79347803386484e-06 -5.28424573240211e-06 0.000119317658315011 2346 2350 0 0 0 2368 2372 0 0 0 0 0 0 0 0 573 557 0 3564 0 0 0 0 0 772 +850 898 0.987936775378258 0.15041711757715 0.0368187261456958 0.599261417075341 -0.15020820586654 0.98861877012677 -0.00839179619550027 -0.224640416518017 -0.0376619535548142 0.00276008927637765 0.999286725200341 0.676112459530551 7.01220766765744e-05 -7.56504253031052e-05 -4.09670994779992e-06 1.30151767862062e-06 -6.57530085573233e-08 7.50338272931548e-05 -7.56504253031052e-05 0.000134533743611659 5.54336483490117e-06 1.16643057004514e-05 2.62390444512835e-06 -0.000104060956240026 -4.09670994779992e-06 5.54336483490117e-06 1.22456520155209e-05 -7.81766230257889e-06 7.40574255896606e-06 -5.48932262804535e-06 1.30151767862062e-06 1.16643057004514e-05 -7.81766230257889e-06 5.53069491688479e-05 1.92405986459502e-06 -4.83351625193606e-06 -6.57530085573233e-08 2.62390444512835e-06 7.40574255896606e-06 1.92405986459502e-06 2.36183313026814e-05 -2.0951688045042e-06 7.50338272931548e-05 -0.000104060956240026 -5.48932262804535e-06 -4.83351625193606e-06 -2.0951688045042e-06 0.000166512735618438 509 530 0 497 0 509 530 0 515 0 0 0 0 0 0 0 0 0 1526 0 0 0 0 0 1513 +850 936 0.937295067599496 -0.336553324265542 -0.090608035954158 0.680340225086844 0.332376664924596 0.94134606162692 -0.0582524237529239 0.0144798057388312 0.104898564657769 0.0244837126535203 0.99418149195579 0.0319789092318702 2.42359716961612e-05 -1.76296959215866e-05 1.32811005900768e-06 6.0423534830443e-06 3.08396176385702e-06 1.92412390704163e-05 -1.76296959215866e-05 7.27878612037511e-05 -5.06855715240007e-07 -2.7918038563729e-06 -4.45210776688135e-06 -6.01895550244848e-05 1.32811005900768e-06 -5.06855715240007e-07 9.6975348043247e-06 2.52634068685004e-06 4.26586880593589e-06 2.4808224448305e-07 6.0423534830443e-06 -2.7918038563729e-06 2.52634068685004e-06 5.33746654075719e-05 1.79242981036173e-06 -1.50861914696865e-06 3.08396176385702e-06 -4.45210776688135e-06 4.26586880593589e-06 1.79242981036173e-06 1.33020082505143e-05 2.18667980660735e-06 1.92412390704163e-05 -6.01895550244848e-05 2.4808224448305e-07 -1.50861914696865e-06 2.18667980660735e-06 0.000130869547089753 2100 2100 0 0 0 2121 2121 0 0 0 0 0 0 0 0 392 384 0 3631 0 0 0 0 0 869 +850 939 0.882036862933879 -0.458514311751771 -0.108515429062235 0.792568269466481 0.454944035843364 0.888686448977669 -0.0571167195662785 0.224047612339481 0.122625024674057 0.00101060489846707 0.992452559068405 -0.204465359059622 3.46721613312541e-05 -2.11438022872087e-05 -3.47509776102425e-06 1.34761102637459e-05 1.33779432719013e-07 3.01668919516965e-05 -2.11438022872087e-05 3.23644239954411e-05 2.74714562577112e-06 -5.51192386883017e-06 5.25232117666942e-07 -1.34167672954837e-05 -3.47509776102425e-06 2.74714562577112e-06 1.05947217426512e-05 2.16361459755326e-07 4.06582380401541e-06 -4.42168677150636e-06 1.34761102637459e-05 -5.51192386883017e-06 2.16361459755326e-07 5.28385448048052e-05 1.47501733767879e-06 2.63725114835818e-05 1.33779432719013e-07 5.25232117666942e-07 4.06582380401541e-06 1.47501733767879e-06 1.30228047285383e-05 -3.13435945036759e-06 3.01668919516965e-05 -1.34167672954837e-05 -4.42168677150636e-06 2.63725114835818e-05 -3.13435945036759e-06 0.000114517481649539 2345 2435 0 0 392 2375 2465 0 0 392 0 0 0 0 0 835 803 0 3375 0 0 0 0 0 261 +850 929 0.990752738664542 0.128154370279549 0.0445585929643351 0.600686098281856 -0.128699464894792 0.991637410463764 0.00957569342217489 -0.224423505121876 -0.0429588007805532 -0.0152218115536066 0.998960879058096 0.68105267357277 5.02984436366833e-05 -3.70190451647062e-05 -4.98757293617941e-06 2.84753436373855e-06 1.322353767376e-06 8.624007974132e-05 -3.70190451647062e-05 6.5731792139082e-05 5.76549997272534e-06 -2.33856465439619e-06 -5.55817482469522e-06 -1.53510512745209e-05 -4.98757293617941e-06 5.76549997272534e-06 1.22210017114006e-05 -4.60973041740365e-06 6.2534550944278e-06 -2.79141614069154e-06 2.84753436373855e-06 -2.33856465439619e-06 -4.60973041740365e-06 4.32466772605331e-05 4.92746741236302e-06 -2.5087344296965e-05 1.322353767376e-06 -5.55817482469522e-06 6.2534550944278e-06 4.92746741236302e-06 2.29585161843875e-05 -1.13788018029388e-05 8.624007974132e-05 -1.53510512745209e-05 -2.79141614069154e-06 -2.5087344296965e-05 -1.13788018029388e-05 0.000436007129835679 578 603 0 487 0 578 603 0 506 0 0 0 0 0 0 0 0 0 1589 0 0 0 0 0 1599 +850 932 0.996740437504536 -0.0805258755021458 0.00490750627913014 0.608180948197365 0.0805864246362962 0.996653027120199 -0.0137321410013999 -0.170788413521852 -0.0037852883120498 0.0140828586145246 0.999893666689432 0.513676334682539 4.04200501431047e-05 -4.18572018932085e-05 -2.23847004612218e-06 3.50505342699697e-06 1.10187093587555e-07 4.40144904210206e-05 -4.18572018932085e-05 9.65260850186327e-05 7.66649703775758e-06 -9.43331982917748e-06 -3.90409921766947e-06 -6.42441471089537e-05 -2.23847004612218e-06 7.66649703775758e-06 1.25280428879226e-05 -3.75240215632581e-06 5.84799265184217e-06 -6.03593796327168e-06 3.50505342699697e-06 -9.43331982917748e-06 -3.75240215632581e-06 6.12079225762807e-05 7.51783793035056e-07 1.08785213657631e-05 1.10187093587555e-07 -3.90409921766947e-06 5.84799265184217e-06 7.51783793035056e-07 1.94264118380175e-05 8.27941142499848e-06 4.40144904210206e-05 -6.42441471089537e-05 -6.03593796327168e-06 1.08785213657631e-05 8.27941142499848e-06 0.000186000466333121 1144 1159 0 181 0 1144 1159 0 202 0 0 0 0 0 0 0 0 0 2293 0 0 0 0 0 1498 +850 933 0.985070649121695 -0.16955639259342 -0.0297732425118387 0.632553803380144 0.168478547243361 0.985061837746675 -0.0356111630519123 -0.127088663167253 0.0353665853275275 0.0300633588584069 0.998922118634091 0.399387579415074 2.77527793406412e-05 -2.60936694637728e-05 -2.07074004496181e-06 2.67250169671859e-06 1.46017007831603e-06 4.13990744096143e-05 -2.60936694637728e-05 6.10019155988227e-05 5.44627990162298e-06 -7.93651487070275e-06 -4.85961208837974e-06 -7.19422972378707e-05 -2.07074004496181e-06 5.44627990162298e-06 1.23007433853013e-05 -5.69114867472269e-06 5.6044133450362e-06 -3.24415536558999e-06 2.67250169671859e-06 -7.93651487070275e-06 -5.69114867472269e-06 7.37518235232715e-05 1.10006154506485e-05 1.65007014471893e-06 1.46017007831603e-06 -4.85961208837974e-06 5.6044133450362e-06 1.10006154506485e-05 1.74446128307369e-05 5.71249959624805e-06 4.13990744096143e-05 -7.19422972378707e-05 -3.24415536558999e-06 1.65007014471893e-06 5.71249959624805e-06 0.000198894148502772 1384 1392 0 27 0 1384 1392 0 39 0 0 0 0 0 0 2 4 0 2606 0 0 0 0 0 818 +850 931 0.9971963985714 -0.0033434145060371 0.0747540250131802 0.607207329347354 0.00420667686770528 0.999926242511125 -0.0113935686820916 -0.198419070951089 -0.0747104179212047 0.0116760916844484 0.997136912533587 0.586803511645492 8.12385064511101e-05 -0.000109530260971097 -4.9798436852716e-06 3.12250214035019e-07 -2.48019041652165e-06 9.03091123721427e-05 -0.000109530260971097 0.000307579594571026 4.57281184909895e-06 1.27835068278957e-05 2.98269248709142e-06 -6.69357843889778e-05 -4.9798436852716e-06 4.57281184909895e-06 1.24157940895003e-05 -5.21215801266345e-06 7.92401936303302e-06 -7.93781312776067e-06 3.12250214035019e-07 1.27835068278957e-05 -5.21215801266345e-06 5.09498408351465e-05 5.84722057423027e-06 -7.53686758555003e-06 -2.48019041652165e-06 2.98269248709142e-06 7.92401936303302e-06 5.84722057423027e-06 2.28270761430442e-05 6.32510733460555e-06 9.03091123721427e-05 -6.69357843889778e-05 -7.93781312776067e-06 -7.53686758555003e-06 6.32510733460555e-06 0.000399013959117698 919 937 0 333 0 919 937 0 353 0 0 0 0 0 0 0 0 0 1969 0 0 0 0 0 1320 +850 930 0.992667000119155 0.0664861825819459 0.100954516491923 0.603229031549986 -0.0676487776571073 0.997676050315135 0.00813274302380842 -0.212517401172639 -0.100179188237563 -0.0149025552598267 0.994857800939808 0.626474415842952 5.45505062593599e-05 -5.76914926380915e-05 -1.84628110502809e-06 -3.15653807145663e-06 -4.55840950211697e-06 5.05394305713424e-05 -5.76914926380915e-05 0.000140490800423552 4.07111518563016e-06 3.79206348610179e-06 8.02665238570221e-07 -9.62488331887406e-05 -1.84628110502809e-06 4.07111518563016e-06 1.22093802267737e-05 -4.01497230388181e-06 7.00954152347902e-06 -2.91998378089828e-06 -3.15653807145663e-06 3.79206348610179e-06 -4.01497230388181e-06 4.42695791681641e-05 5.20934520457698e-06 -4.88915338917566e-06 -4.55840950211697e-06 8.02665238570221e-07 7.00954152347902e-06 5.20934520457698e-06 2.0192521663447e-05 -2.37205017378318e-06 5.05394305713424e-05 -9.62488331887406e-05 -2.91998378089828e-06 -4.88915338917566e-06 -2.37205017378318e-06 0.000161942548605121 768 791 0 465 0 768 791 0 484 0 0 0 0 0 0 0 0 0 1695 0 0 0 0 0 1266 +850 899 0.987739990866382 0.150669339009622 0.0408467957823234 0.605197077586355 -0.150416021007583 0.988579765180547 -0.00922325863356491 -0.224712407428747 -0.041769978064701 0.00296616890598929 0.999122850691793 0.691895505784367 9.14028289146796e-05 -0.000135795622281237 -6.90020094340491e-06 -1.15068684311971e-05 -2.63599843443395e-06 9.33170143216961e-05 -0.000135795622281237 0.000308312038870706 1.47250848232345e-05 3.49368651678861e-05 8.0458031464701e-06 -0.000131105515300844 -6.90020094340491e-06 1.47250848232345e-05 1.56231405572182e-05 -8.37127544719557e-06 6.36315305943861e-06 -7.11820385625818e-06 -1.15068684311971e-05 3.49368651678861e-05 -8.37127544719557e-06 5.24309687670941e-05 5.73828834418391e-06 -9.08354413396834e-06 -2.63599843443395e-06 8.0458031464701e-06 6.36315305943861e-06 5.73828834418391e-06 2.87610806167497e-05 2.25027120315248e-06 9.33170143216961e-05 -0.000131105515300844 -7.11820385625818e-06 -9.08354413396834e-06 2.25027120315248e-06 0.000214340285219899 525 540 0 485 0 525 540 0 502 0 0 0 0 0 0 0 0 0 1500 0 0 0 0 0 1265 +850 938 0.905405404249581 -0.411269448627102 -0.105349392886777 0.741027136732707 0.410146807707148 0.91141792642672 -0.0331203791592638 0.140876527236444 0.109638725290331 -0.0132213469048049 0.993883567578584 -0.165587038765962 2.48851342733833e-05 -1.39943534202409e-05 3.66661851432408e-07 6.38900295132686e-06 1.78044774643076e-07 2.71607446100721e-05 -1.39943534202409e-05 7.33432265878657e-05 9.78877773148907e-07 2.24517959940179e-05 -5.32722770114541e-06 -9.29507966988463e-06 3.66661851432408e-07 9.78877773148907e-07 1.0319145959858e-05 3.39302431583852e-06 6.16531145009398e-06 -2.28952363041177e-06 6.38900295132686e-06 2.24517959940179e-05 3.39302431583852e-06 6.31019429808313e-05 -2.3541713193094e-06 1.55506722027181e-05 1.78044774643076e-07 -5.32722770114541e-06 6.16531145009398e-06 -2.3541713193094e-06 1.47636592522349e-05 -7.1220832017836e-06 2.71607446100721e-05 -9.29507966988463e-06 -2.28952363041177e-06 1.55506722027181e-05 -7.1220832017836e-06 0.000152872891371963 2346 2466 0 0 65 2378 2498 0 0 65 0 0 0 0 0 718 696 0 3472 0 0 0 0 0 532 +850 940 0.87630882861372 -0.469966858535735 -0.105896122552725 0.842153368675999 0.45847455433194 0.881072547992877 -0.116242196312133 0.305785888244833 0.147932146350203 0.0533133852929298 0.987559498473297 -0.247587151761931 4.46873229900937e-05 -3.64432722331444e-05 -1.62044867604009e-06 -7.01313825736322e-07 2.68564959216115e-06 2.96047004126254e-05 -3.64432722331444e-05 7.69907740331281e-05 -8.38673212279438e-07 2.25779815282402e-05 -5.96204250432005e-06 -1.98486027141007e-05 -1.62044867604009e-06 -8.38673212279438e-07 1.23160334362291e-05 2.06645037529908e-06 3.61608235124109e-06 -3.17866258905236e-06 -7.01313825736322e-07 2.25779815282402e-05 2.06645037529908e-06 8.60798499240101e-05 -2.36816324899992e-06 3.43344868821526e-05 2.68564959216115e-06 -5.96204250432005e-06 3.61608235124109e-06 -2.36816324899992e-06 1.75955350169938e-05 4.40721968903331e-06 2.96047004126254e-05 -1.98486027141007e-05 -3.17866258905236e-06 3.43344868821526e-05 4.40721968903331e-06 0.000166132892199587 1999 2078 0 0 668 2031 2110 0 0 668 0 0 0 0 0 882 849 0 3517 0 0 0 0 0 128 +850 893 0.987202387107284 0.149576443810304 0.055302209239256 0.615924135190006 -0.149399499482727 0.988749645841112 -0.0073435279931097 -0.222774852692526 -0.0557784586017762 -0.00101257401604681 0.998442656465494 0.68305136264105 7.26873776163353e-05 -9.87991010005448e-05 -3.26233313361881e-06 7.28612942850397e-07 4.75461886168062e-07 0.00011007177057143 -9.87991010005448e-05 0.00028097158515747 7.97148548871899e-06 1.40376552191902e-05 -4.27269631917456e-06 -0.000299386273816459 -3.26233313361881e-06 7.97148548871899e-06 1.26178109846793e-05 -4.72251659611188e-06 6.73981479993663e-06 -8.07763205516153e-06 7.28612942850397e-07 1.40376552191902e-05 -4.72251659611188e-06 5.19597519908356e-05 5.22640000090891e-06 -2.67468868095543e-05 4.75461886168062e-07 -4.27269631917456e-06 6.73981479993663e-06 5.22640000090891e-06 2.45217656822511e-05 -9.28206115509153e-06 0.00011007177057143 -0.000299386273816459 -8.07763205516153e-06 -2.67468868095543e-05 -9.28206115509153e-06 0.000436784520540101 549 574 0 510 0 549 574 0 527 0 0 0 0 0 0 0 0 0 1434 0 0 0 0 0 974 +850 896 0.987802977199594 0.150282848731033 0.0407473141802458 0.605881086335413 -0.150013125349259 0.988637245166032 -0.00961559636558341 -0.224508899681267 -0.0417293716531407 0.00338568276770605 0.999123213969944 0.674798679990879 0.000100673892074334 -0.000132179806937474 -9.4817936015013e-06 5.58694989491957e-06 -5.9256199110204e-06 8.61574434594678e-05 -0.000132179806937474 0.000258297527836887 1.07908881075701e-05 1.49611217865076e-05 1.18618820351447e-05 -0.000157580879720151 -9.4817936015013e-06 1.07908881075701e-05 1.32350426263505e-05 -8.09990249346174e-06 7.93223471746795e-06 -4.95915831096959e-06 5.58694989491957e-06 1.49611217865076e-05 -8.09990249346174e-06 5.10712927703013e-05 4.15169857590826e-06 -2.29306417498418e-05 -5.9256199110204e-06 1.18618820351447e-05 7.93223471746795e-06 4.15169857590826e-06 2.57007148987929e-05 -1.05311391988922e-05 8.61574434594678e-05 -0.000157580879720151 -4.95915831096959e-06 -2.29306417498418e-05 -1.05311391988922e-05 0.000225752367891173 532 559 0 500 0 532 559 0 516 0 0 0 0 0 0 0 0 0 1469 0 0 0 0 0 1518 +850 894 0.987863927830721 0.149708578779243 0.0413787569987271 0.603972676955355 -0.149397489033972 0.988721165957953 -0.0105283549089869 -0.226918064205612 -0.0424882379159802 0.0042186996390309 0.999088060289057 0.695672558434787 0.000111846746989675 -0.000178630869163398 -3.28134884437154e-06 -1.77607840731416e-05 -6.32591724444081e-06 0.000140687212626037 -0.000178630869163398 0.000410852695706902 6.13774625264702e-06 4.71822310521238e-05 6.01088061895125e-06 -0.000268870735412919 -3.28134884437154e-06 6.13774625264702e-06 1.18631552707651e-05 -6.07335286391665e-06 6.60535916864185e-06 -6.92006998113627e-06 -1.77607840731416e-05 4.71822310521238e-05 -6.07335286391665e-06 5.43867938488123e-05 5.00517794550245e-06 -2.82548227063938e-05 -6.32591724444081e-06 6.01088061895125e-06 6.60535916864185e-06 5.00517794550245e-06 2.54759939754419e-05 4.39246883821642e-06 0.000140687212626037 -0.000268870735412919 -6.92006998113627e-06 -2.82548227063938e-05 4.39246883821642e-06 0.000300882210172199 491 503 0 497 0 491 503 0 509 0 0 0 0 0 0 0 0 0 1390 0 0 0 0 0 1077 +850 897 0.987870892168876 0.149744887497411 0.0410800325444993 0.602844443620399 -0.14949242453682 0.988720369929271 -0.00916761108629489 -0.22742392670312 -0.0419894678648411 0.00291526247774675 0.999113800241551 0.680155521009461 5.24483821844216e-05 -5.31244905461998e-05 -1.64638203149618e-06 -1.68324785357823e-06 -4.55049808213362e-06 3.12834371100384e-05 -5.31244905461998e-05 9.69509902726455e-05 2.06135446503178e-06 7.37443975844481e-06 2.74297856721555e-06 -4.2253558546245e-05 -1.64638203149618e-06 2.06135446503178e-06 1.23159621349378e-05 -8.87551959427242e-06 7.08320531654743e-06 -5.0880091829662e-06 -1.68324785357823e-06 7.37443975844481e-06 -8.87551959427242e-06 5.05975113947697e-05 5.95076091741057e-06 5.79510014376015e-06 -4.55049808213362e-06 2.74297856721555e-06 7.08320531654743e-06 5.95076091741057e-06 2.53599632595299e-05 7.97549310530636e-06 3.12834371100384e-05 -4.2253558546245e-05 -5.0880091829662e-06 5.79510014376015e-06 7.97549310530636e-06 0.000138129114974764 549 568 0 477 0 549 568 0 493 0 0 0 0 0 0 0 0 0 1429 0 0 0 0 0 1453 +850 892 0.987575272658249 0.149525182051935 0.048345638544963 0.607335308480272 -0.149262994566751 0.988756488873242 -0.00900911560724038 -0.224883337072273 -0.049149153471352 0.00168096501876718 0.998790035527816 0.695369322393896 8.08648552253112e-05 -8.62673541181194e-05 -3.0523035190643e-06 -8.92914168660959e-06 1.05522965476617e-06 0.000120483940184501 -8.62673541181194e-05 0.000174510325617682 4.18227996296611e-06 2.52477077286494e-05 -7.13520667043507e-07 -0.000146878547496512 -3.0523035190643e-06 4.18227996296611e-06 1.14849092680615e-05 -5.1046360280881e-06 6.24458106796776e-06 -6.40572261498186e-06 -8.92914168660959e-06 2.52477077286494e-05 -5.1046360280881e-06 5.02058409181724e-05 4.25538369472277e-06 -1.85852461371738e-05 1.05522965476617e-06 -7.13520667043507e-07 6.24458106796776e-06 4.25538369472277e-06 2.17712513962848e-05 1.15009374889516e-05 0.000120483940184501 -0.000146878547496512 -6.40572261498186e-06 -1.85852461371738e-05 1.15009374889516e-05 0.000330144623261862 533 560 0 507 0 533 560 0 523 0 0 0 0 0 0 0 0 0 1483 0 0 0 0 0 1449 +850 900 0.987357216928984 0.149461470208891 0.0527919984585525 0.61271077554617 -0.14936046892606 0.98876535496953 -0.0058756390433388 -0.224077026215682 -0.0530770807452556 -0.00208368303180295 0.998588244355292 0.681107205842385 0.000109895101482346 -0.000175956159729473 -8.78519721959483e-07 -2.68130305096672e-05 -1.20022243028663e-05 0.000142523122615397 -0.000175956159729473 0.00037723534513236 3.80401896908243e-06 5.75831662284679e-05 2.4374955207323e-05 -0.000280309186504521 -8.78519721959483e-07 3.80401896908243e-06 1.12013820291061e-05 -5.94534470908732e-06 6.0930225201328e-06 -3.6893671495745e-06 -2.68130305096672e-05 5.75831662284679e-05 -5.94534470908732e-06 5.41025772190583e-05 1.01964916482352e-05 -5.18079963407083e-05 -1.20022243028663e-05 2.4374955207323e-05 6.0930225201328e-06 1.01964916482352e-05 2.41389517295477e-05 -1.65695020154702e-05 0.000142523122615397 -0.000280309186504521 -3.6893671495745e-06 -5.18079963407083e-05 -1.65695020154702e-05 0.000352342005095709 559 584 0 507 0 559 584 0 522 0 0 0 0 0 0 0 0 0 1468 0 0 0 0 0 1376 +851 853 0.998508368956904 0.0416967913146223 0.0352479037261488 0.191201341216546 -0.0408735740344651 0.998881736008158 -0.0237619110127523 -0.0451210598799157 -0.0361992827093593 0.0222857592061319 0.999096069889144 0.133734212773438 2.56359892332226e-05 -1.84151496659241e-05 -5.81393636889464e-06 2.76943239512864e-06 1.71588633144086e-06 3.27133663741014e-05 -1.84151496659241e-05 5.58329807801155e-05 7.46327384615593e-06 -6.06078060743331e-06 -8.16721825346173e-06 -5.15766925974968e-05 -5.81393636889464e-06 7.46327384615593e-06 1.27184870604288e-05 -2.6633869751837e-06 4.52768232882996e-06 -6.14429194810619e-06 2.76943239512864e-06 -6.06078060743331e-06 -2.6633869751837e-06 4.16606165133899e-05 9.01251930186222e-06 1.18823520861705e-06 1.71588633144086e-06 -8.16721825346173e-06 4.52768232882996e-06 9.01251930186222e-06 2.00157975939953e-05 1.02404153910458e-05 3.27133663741014e-05 -5.15766925974968e-05 -6.14429194810619e-06 1.18823520861705e-06 1.02404153910458e-05 0.000197489343892076 2096 2122 0 202 0 2096 2122 0 221 63 0 0 0 0 0 0 0 0 3335 0 0 0 0 0 3376 +851 855 0.997176491270841 0.060760893329713 0.0441266257326479 0.315319512849912 -0.0561536306070799 0.993496927361971 -0.0990485996466698 -0.102095266864473 -0.0498579484778261 0.0962910648196285 0.994103724874565 0.305224186045307 2.43809134982066e-05 -1.53669658064569e-05 2.47691484614423e-06 1.08191749794881e-06 -1.18421117890909e-06 1.39096624963482e-05 -1.53669658064569e-05 4.14551914787197e-05 8.67718510884081e-07 7.85756429524437e-06 3.70371834409631e-06 -2.79046359341032e-05 2.47691484614423e-06 8.67718510884081e-07 1.22436334613678e-05 7.32719346797017e-08 6.865223799458e-06 -1.01537705118513e-06 1.08191749794881e-06 7.85756429524437e-06 7.32719346797017e-08 4.35064126443506e-05 2.67933951841858e-06 -1.5350955584405e-05 -1.18421117890909e-06 3.70371834409631e-06 6.865223799458e-06 2.67933951841858e-06 1.91477236772665e-05 -3.84418506235211e-06 1.39096624963482e-05 -2.79046359341032e-05 -1.01537705118513e-06 -1.5350955584405e-05 -3.84418506235211e-06 8.11810921066445e-05 1594 1615 0 235 0 1594 1615 0 252 0 0 0 0 0 0 0 0 0 2271 0 0 0 0 0 2669 +851 854 0.99771881195784 0.0527938473832233 0.0420711533465958 0.252715905061874 -0.0505883194048842 0.99737177690286 -0.0518686859041301 -0.0760589982402384 -0.0446989284572379 0.0496220547348536 0.997767336345837 0.206281066760983 3.70180538985092e-05 -2.65122485782697e-05 1.356065693708e-06 -5.57801010004649e-06 -5.19124090559437e-06 9.25813983671139e-06 -2.65122485782697e-05 6.19567602208436e-05 -9.77670992389981e-07 2.00002570066461e-05 1.3012775465436e-05 1.33644896801221e-05 1.356065693708e-06 -9.77670992389981e-07 1.08466116509986e-05 7.67652198096238e-07 4.6942613920596e-06 1.70058689698408e-07 -5.57801010004649e-06 2.00002570066461e-05 7.67652198096238e-07 4.21365501319017e-05 9.05632060662666e-06 1.39882820515749e-05 -5.19124090559437e-06 1.3012775465436e-05 4.6942613920596e-06 9.05632060662666e-06 2.09430941367358e-05 1.25293575190832e-05 9.25813983671139e-06 1.33644896801221e-05 1.70058689698408e-07 1.39882820515749e-05 1.25293575190832e-05 0.000194373735018043 1858 1879 0 212 0 1858 1879 0 231 0 0 0 0 0 0 0 0 0 2984 0 0 0 0 0 2599 +851 936 0.92597958014266 -0.366460227344323 -0.0909324965761405 0.566131313618899 0.364726187487406 0.930433697006752 -0.0356081961807893 0.0475048112732464 0.0976556466351255 -0.000193000245802544 0.995220245689958 -0.0167666584562743 2.41188940748077e-05 -1.78303058097124e-05 1.62091166078796e-06 8.05512256905736e-06 1.40183609585931e-06 2.79368207562366e-05 -1.78303058097124e-05 8.35516362110813e-05 -4.63681774900387e-07 1.17998055408041e-05 -1.53820735288435e-06 -6.86024141065775e-06 1.62091166078796e-06 -4.63681774900387e-07 9.06899485682195e-06 3.26254278621961e-06 4.25815745118934e-06 -7.67750724290155e-07 8.05512256905736e-06 1.17998055408041e-05 3.26254278621961e-06 4.77348948810302e-05 2.8001839375525e-06 3.23346849713139e-05 1.40183609585931e-06 -1.53820735288435e-06 4.25815745118934e-06 2.8001839375525e-06 1.3536017578466e-05 -1.93444295378817e-06 2.79368207562366e-05 -6.86024141065775e-06 -7.67750724290155e-07 3.23346849713139e-05 -1.93444295378817e-06 0.000175286577862077 1966 1966 0 0 0 1985 1985 0 0 0 0 0 0 0 0 559 549 0 3528 0 0 0 0 0 783 +851 935 0.939819407393239 -0.319586066606904 -0.120847952062703 0.54408251472334 0.317392667527991 0.947552160946879 -0.0375072910827458 -0.00453101665155579 0.126496545749234 -0.00310617379216409 0.991962184560422 0.144690846971581 3.48029684745714e-05 -2.2139613087571e-05 -2.14417711285818e-06 8.4631371640461e-06 -9.90254750704141e-07 2.01307274353457e-05 -2.2139613087571e-05 6.63296835479046e-05 8.15658252987609e-08 5.16918619513051e-06 -2.43628719536532e-06 -5.38145186845885e-05 -2.14417711285818e-06 8.15658252987609e-08 1.21721724946191e-05 2.68667610278153e-06 6.97128564386227e-06 -1.43797493630205e-09 8.4631371640461e-06 5.16918619513051e-06 2.68667610278153e-06 6.33361890312242e-05 1.54987707681828e-06 1.98107481697578e-05 -9.90254750704141e-07 -2.43628719536532e-06 6.97128564386227e-06 1.54987707681828e-06 2.09254987632075e-05 7.87757895857292e-07 2.01307274353457e-05 -5.38145186845885e-05 -1.43797493630205e-09 1.98107481697578e-05 7.87757895857292e-07 0.0001995994916412 1360 1360 0 0 0 1374 1374 0 0 0 0 0 0 0 0 354 352 0 3379 0 0 0 0 0 912 +851 934 0.958116537128385 -0.27221502453594 -0.0889476345835541 0.538369221946818 0.271750807945656 0.962208121208778 -0.0175222675689186 -0.048513388175289 0.090355960854805 -0.00738321723716647 0.995882165941952 0.243696443321314 4.91206378718497e-05 -4.0192430709478e-05 -4.55314454612656e-06 1.60926581145324e-05 3.1487374832436e-06 6.4150452393208e-05 -4.0192430709478e-05 9.5256820362882e-05 3.95731953801341e-06 -7.14992078268518e-06 -6.7831982135227e-06 -6.39444363673991e-05 -4.55314454612656e-06 3.95731953801341e-06 1.24299320578188e-05 -8.26805205921107e-06 6.33148162674682e-06 -7.90178506381338e-06 1.60926581145324e-05 -7.14992078268518e-06 -8.26805205921107e-06 0.00010102292753086 6.58427524961872e-06 3.58479023197562e-05 3.1487374832436e-06 -6.7831982135227e-06 6.33148162674682e-06 6.58427524961872e-06 1.8712977421577e-05 8.52493072810664e-06 6.4150452393208e-05 -6.39444363673991e-05 -7.90178506381338e-06 3.58479023197562e-05 8.52493072810664e-06 0.000194880832300712 1330 1330 0 0 0 1342 1342 0 0 0 0 0 0 0 0 243 246 0 3113 0 0 0 0 0 552 +851 937 0.910274816072195 -0.401264725234125 -0.101913588434091 0.578441962347454 0.401063271368779 0.915752306753795 -0.0233658946774324 0.0994359212068735 0.102703513005665 -0.0196044116944457 0.994518805985292 -0.135223783294327 2.85056492511079e-05 -2.17901924034807e-05 -2.51685363658269e-06 1.19815231344737e-05 5.78043794571649e-09 3.00746220910773e-05 -2.17901924034807e-05 3.55046441550426e-05 2.9288860705674e-06 -3.10885883979117e-06 -7.85207227767493e-07 -2.15798124816021e-05 -2.51685363658269e-06 2.9288860705674e-06 1.15802536617371e-05 -2.15098786903218e-06 4.75998216709686e-06 -4.74415758996092e-06 1.19815231344737e-05 -3.10885883979117e-06 -2.15098786903218e-06 6.15561806303264e-05 1.09678078125207e-06 2.89833812329287e-05 5.78043794571649e-09 -7.85207227767493e-07 4.75998216709686e-06 1.09678078125207e-06 1.54175952800273e-05 -1.81536005681558e-06 3.00746220910773e-05 -2.15798124816021e-05 -4.74415758996092e-06 2.89833812329287e-05 -1.81536005681558e-06 0.000118744382822632 2169 2173 0 0 0 2192 2196 0 0 0 0 0 0 0 0 770 754 0 3407 0 0 0 0 0 661 +851 899 0.992226488198737 0.118237336060024 0.0388140242467918 0.497184453198975 -0.118872237339447 0.992804103009317 0.0144708063969823 -0.179087166411207 -0.0368237329274985 -0.0189722273150453 0.999141665272743 0.655870061974697 0.000114787569409003 -0.000174709002115605 -6.03604520016671e-06 -3.29645518922512e-05 -1.26151422855519e-05 0.000201887939202014 -0.000174709002115605 0.000360745289258001 1.03993116014035e-05 6.61962813125057e-05 2.16839530098498e-05 -0.000406302864587171 -6.03604520016671e-06 1.03993116014035e-05 1.34609220445018e-05 -4.69060782491965e-06 6.72933738780723e-06 -1.17261139705999e-05 -3.29645518922512e-05 6.61962813125057e-05 -4.69060782491965e-06 7.35409390410627e-05 1.88674628474713e-05 -7.07551629117351e-05 -1.26151422855519e-05 2.16839530098498e-05 6.72933738780723e-06 1.88674628474713e-05 3.01711530575209e-05 -2.2155156553403e-05 0.000201887939202014 -0.000406302864587171 -1.17261139705999e-05 -7.07551629117351e-05 -2.2155156553403e-05 0.00060882059225803 525 540 0 351 0 525 540 0 363 0 0 0 0 0 0 0 0 0 1677 0 0 0 0 0 937 +851 898 0.991925813772461 0.117742155749921 0.0471165016868084 0.50269227954108 -0.11884797105079 0.99268202529661 0.0213905687192011 -0.174179951634214 -0.0442531326456366 -0.0268175579123376 0.998660342077659 0.631989726240487 8.59699368278481e-05 -9.64230725933613e-05 -7.53543461869032e-06 -1.05713056906595e-05 -8.26566437799619e-06 0.000114593861322215 -9.64230725933613e-05 0.000173606533492267 1.07036839330695e-05 2.3951863089151e-05 1.33715800214917e-05 -7.93760026243841e-05 -7.53543461869032e-06 1.07036839330695e-05 1.23665668889285e-05 -5.55683065558018e-06 7.64792340280955e-06 -6.46844214485397e-06 -1.05713056906595e-05 2.3951863089151e-05 -5.55683065558018e-06 4.29958435184069e-05 3.37405234674427e-06 -3.12233213115061e-05 -8.26566437799619e-06 1.33715800214917e-05 7.64792340280955e-06 3.37405234674427e-06 2.18467291518527e-05 -1.30783408076303e-05 0.000114593861322215 -7.93760026243841e-05 -6.46844214485397e-06 -3.12233213115061e-05 -1.30783408076303e-05 0.000527291454427897 500 522 0 374 0 500 522 0 391 0 0 0 0 0 0 0 0 0 1750 0 0 0 0 0 1555 +851 933 0.979096840818291 -0.201551577436628 -0.0273191861600782 0.524766748704422 0.201295174198972 0.97945882799092 -0.0118598952296934 -0.0859562460627381 0.0291483986497937 0.00611276561476162 0.999556404087679 0.345936757648551 2.04784556334472e-05 -1.72046594550156e-05 5.90190967434874e-07 3.29025211050723e-06 1.7316666668345e-06 2.05454123179946e-05 -1.72046594550156e-05 5.11612689907889e-05 1.75655822301794e-06 2.44053288399062e-06 -4.80917117644028e-07 -5.23243763333812e-05 5.90190967434874e-07 1.75655822301794e-06 1.27109976290748e-05 -4.81634398076662e-07 6.36804037053766e-06 -2.59501383352323e-06 3.29025211050723e-06 2.44053288399062e-06 -4.81634398076662e-07 6.07650287608848e-05 5.86796930009892e-06 -6.01064370785184e-06 1.7316666668345e-06 -4.80917117644028e-07 6.36804037053766e-06 5.86796930009892e-06 1.69167122937602e-05 -2.91601122234457e-07 2.05454123179946e-05 -5.23243763333812e-05 -2.59501383352323e-06 -6.01064370785184e-06 -2.91601122234457e-07 0.00011866441941281 1356 1356 0 0 0 1373 1373 0 0 0 0 0 0 0 0 129 138 0 2806 0 0 0 0 0 485 +851 931 0.996931519543736 -0.0355973085737644 0.0697164038266645 0.500235850043662 0.0346095481258908 0.999283394888477 0.0153256607910264 -0.153246671153264 -0.0702119969716003 -0.0128657810670068 0.997449120085228 0.533304960898153 4.47771217912554e-05 -5.69245797286988e-05 -4.42286204411885e-06 -4.8300266881353e-06 -1.7305105166164e-06 4.4874111452523e-05 -5.69245797286988e-05 0.00013012939736836 4.85775271923448e-06 1.72795253262761e-05 3.10405160474635e-06 -5.75527445596264e-05 -4.42286204411885e-06 4.85775271923448e-06 1.18118505057112e-05 -3.46390772886318e-06 8.00852200768111e-06 -1.3247927768244e-06 -4.8300266881353e-06 1.72795253262761e-05 -3.46390772886318e-06 4.23502143490508e-05 1.76320518609582e-08 -1.25423340211698e-05 -1.7305105166164e-06 3.10405160474635e-06 8.00852200768111e-06 1.76320518609582e-08 1.69828024467771e-05 -7.87457547234822e-07 4.4874111452523e-05 -5.75527445596264e-05 -1.3247927768244e-06 -1.25423340211698e-05 -7.87457547234822e-07 0.000137702763053212 942 960 0 168 0 942 960 0 187 0 0 0 0 0 0 0 0 0 2244 0 0 0 0 0 1364 +851 932 0.993605074930704 -0.112740759169616 0.00620292622957919 0.502108413418849 0.112657976448013 0.993556688006764 0.0123809555232497 -0.127215401833909 -0.0075587971655474 -0.0116029711233115 0.999904113226124 0.454473364247117 3.97965358372851e-05 -2.85738817016402e-05 -3.68838309546913e-06 7.93818778756853e-06 8.07517197339433e-07 4.4051970986275e-05 -2.85738817016402e-05 0.000101337717774769 7.07685986611882e-06 -2.13667055511401e-06 -4.63940261801106e-06 -4.62990393727239e-05 -3.68838309546913e-06 7.07685986611882e-06 1.20947658819523e-05 -5.1649760329e-06 7.12165245854934e-06 -7.71278919111754e-06 7.93818778756853e-06 -2.13667055511401e-06 -5.1649760329e-06 5.14825650113637e-05 2.79647165843919e-06 2.59473425311054e-05 8.07517197339433e-07 -4.63940261801106e-06 7.12165245854934e-06 2.79647165843919e-06 1.84261837015724e-05 1.05172115035985e-05 4.4051970986275e-05 -4.62990393727239e-05 -7.71278919111754e-06 2.59473425311054e-05 1.05172115035985e-05 0.000153358996644169 1186 1201 0 38 0 1186 1201 0 54 0 0 0 0 0 0 1 2 0 2581 0 0 0 0 0 1433 +851 929 0.9941535981872 0.0959020653806395 0.0496126704297436 0.499382502042113 -0.0978040500549757 0.994501162539002 0.0374406931214916 -0.176191181706706 -0.0457492186194106 -0.0420741198874253 0.998066519542366 0.633469791794004 4.27488283343443e-05 -3.60518256788907e-05 -7.79557462441659e-06 3.60737234019728e-06 3.25921980102609e-06 4.33703648090126e-05 -3.60518256788907e-05 5.76097480327764e-05 8.41758763498289e-06 -4.8629684430957e-06 -3.77078960140132e-06 -5.70738707313879e-06 -7.79557462441659e-06 8.41758763498289e-06 1.21537013414905e-05 -5.51412100996386e-06 5.19326084377252e-06 -4.93882385211953e-06 3.60737234019728e-06 -4.8629684430957e-06 -5.51412100996386e-06 3.90581991932497e-05 2.84436881415129e-06 -9.28981705662454e-06 3.25921980102609e-06 -3.77078960140132e-06 5.19326084377252e-06 2.84436881415129e-06 2.22231503616912e-05 -8.35195009212476e-07 4.33703648090126e-05 -5.70738707313879e-06 -4.93882385211953e-06 -9.28981705662454e-06 -8.35195009212476e-07 0.00018731032739668 605 631 0 360 0 605 631 0 376 0 0 0 0 0 0 0 0 0 1808 0 0 0 0 0 1609 +851 930 0.994439122015296 0.0347484690313013 0.0994151724105923 0.496979377720266 -0.0383598354406241 0.998663136726797 0.0346476892153444 -0.167749667398043 -0.0980783137620919 -0.0382685672971375 0.994442638429492 0.587996781008516 4.18922662072094e-05 -3.17010300428409e-05 -4.8484571547277e-06 5.24636489422724e-06 1.95704955420656e-06 5.89955149708078e-05 -3.17010300428409e-05 5.76393170130422e-05 6.75184390801764e-06 -3.5328092046545e-06 -5.78278442651589e-06 -5.60077923669477e-05 -4.8484571547277e-06 6.75184390801764e-06 1.29062621845374e-05 -5.61232497991369e-06 6.56327522660245e-06 -7.69764369388747e-06 5.24636489422724e-06 -3.5328092046545e-06 -5.61232497991369e-06 3.73040455057292e-05 -3.69826440838664e-06 -1.45972556461857e-05 1.95704955420656e-06 -5.78278442651589e-06 6.56327522660245e-06 -3.69826440838664e-06 1.82200491116485e-05 9.99927176963675e-06 5.89955149708078e-05 -5.60077923669477e-05 -7.69764369388747e-06 -1.45972556461857e-05 9.99927176963675e-06 0.000308879028845402 786 809 0 301 0 786 809 0 319 0 0 0 0 0 0 0 0 0 1903 0 0 0 0 0 1050 +851 896 0.991891343392363 0.117999216999695 0.047199022137665 0.504367490759213 -0.119013201234982 0.992705594637431 0.0192733055635273 -0.175686428146213 -0.0445804983719839 -0.0247343316667829 0.998699550416392 0.624947615775212 0.000132709629196567 -0.000163244789204156 -7.21638973263162e-06 -2.64191367942932e-05 -2.13443996840273e-05 0.000135529247820189 -0.000163244789204156 0.000302842925750576 1.25846601934804e-05 5.28527191799772e-05 3.40728745294526e-05 -0.000195436476145805 -7.21638973263162e-06 1.25846601934804e-05 1.22009551495068e-05 -5.54263711336994e-06 7.71639525612893e-06 -7.55512981859911e-06 -2.64191367942932e-05 5.28527191799772e-05 -5.54263711336994e-06 6.3701947445644e-05 1.38263078108724e-05 -4.09947160623106e-05 -2.13443996840273e-05 3.40728745294526e-05 7.71639525612893e-06 1.38263078108724e-05 2.76688600615237e-05 -2.71692325696245e-05 0.000135529247820189 -0.000195436476145805 -7.55512981859911e-06 -4.09947160623106e-05 -2.71692325696245e-05 0.000405743810275151 539 565 0 386 0 539 565 0 402 0 0 0 0 0 0 0 0 0 1712 0 0 0 0 0 1606 +851 938 0.891155854026183 -0.440255258173231 -0.109620032319312 0.618702648036359 0.441971810554798 0.896979335010022 -0.00943351683585623 0.167931423548907 0.102480059083605 -0.040042230404914 0.993928798895786 -0.238438359865375 3.61058855135705e-05 -2.55416304146481e-05 -2.47284761817739e-06 5.7948076855253e-06 -1.54569882323271e-06 3.45177821692959e-05 -2.55416304146481e-05 6.0658758872799e-05 2.80468335208026e-06 9.3890580188346e-06 -9.45345351622019e-07 2.47978675684965e-07 -2.47284761817739e-06 2.80468335208026e-06 1.0628631117146e-05 -4.63816736504531e-08 4.71363424558236e-06 -4.43836102311503e-06 5.7948076855253e-06 9.3890580188346e-06 -4.63816736504531e-08 6.11475751444334e-05 1.6639367771492e-06 2.57973803712201e-05 -1.54569882323271e-06 -9.45345351622019e-07 4.71363424558236e-06 1.6639367771492e-06 1.32935515089776e-05 -6.41882482237943e-06 3.45177821692959e-05 2.47978675684965e-07 -4.43836102311503e-06 2.57973803712201e-05 -6.41882482237943e-06 0.000152908769013687 2273 2393 0 0 65 2301 2421 0 0 65 0 0 0 0 0 941 919 0 3217 0 0 0 0 0 434 +851 939 0.866324601129529 -0.48714927146232 -0.110305361571834 0.66220827071541 0.486526416406732 0.872990998867155 -0.0343331040739131 0.249386910469209 0.113020934415644 -0.0239228595836217 0.99330456818297 -0.286656991616135 5.64434598877507e-05 -4.9686411732904e-05 -5.99286277630306e-07 -3.85057965325652e-05 2.62432636719084e-06 -9.90831164615495e-05 -4.9686411732904e-05 0.000150901561485574 -2.37369018727126e-06 0.000163511831996415 -1.9145397277606e-05 0.000472614213932851 -5.99286277630306e-07 -2.37369018727126e-06 1.14806139908438e-05 -6.59087848633309e-06 5.48358201241858e-06 -2.30689506271049e-05 -3.85057965325652e-05 0.000163511831996415 -6.59087848633309e-06 0.00030912666381706 -2.74437756732452e-05 0.000755516645017521 2.62432636719084e-06 -1.9145397277606e-05 5.48358201241858e-06 -2.74437756732452e-05 1.8041931140903e-05 -8.54329824229947e-05 -9.90831164615495e-05 0.000472614213932851 -2.30689506271049e-05 0.000755516645017521 -8.54329824229947e-05 0.00222344126056638 2103 2193 0 0 392 2131 2221 0 0 392 0 0 0 0 0 1064 1032 0 3150 0 0 0 0 0 212 +851 892 0.991784442079366 0.117899195674107 0.049632651639003 0.505686927849492 -0.118898147694964 0.992749217468014 0.0176697960189805 -0.175410124395693 -0.0471895213371195 -0.0234258591314077 0.998611224751619 0.640406071016715 8.28135914444127e-05 -0.000103746977380675 -4.43097628132927e-06 -7.28673113872929e-06 -5.62486868550655e-07 9.67998893060748e-05 -0.000103746977380675 0.000182894166248703 4.57397345544721e-06 3.19264204893982e-05 7.90595009746818e-06 -0.000139190495852685 -4.43097628132927e-06 4.57397345544721e-06 1.40974921538435e-05 -7.79429181181746e-06 6.27196358275707e-06 -8.61386891700968e-06 -7.28673113872929e-06 3.19264204893982e-05 -7.79429181181746e-06 4.92743569563524e-05 7.1294367177583e-06 -7.40286355702919e-06 -5.62486868550655e-07 7.90595009746818e-06 6.27196358275707e-06 7.1294367177583e-06 2.80097000256727e-05 5.34223080481913e-06 9.67998893060748e-05 -0.000139190495852685 -8.61386891700968e-06 -7.40286355702919e-06 5.34223080481913e-06 0.000219024951226684 549 575 0 380 0 549 575 0 397 0 0 0 0 0 0 0 0 0 1730 0 0 0 0 0 971 +851 894 0.991919892446082 0.118099900165217 0.0463394060246614 0.502771306029146 -0.118906070749171 0.992791671907025 0.0150347108734025 -0.179088274321411 -0.0442297785292403 -0.0204232654837463 0.998812603503898 0.65750652295728 8.34102056083027e-05 -0.000116728971483901 1.99952998205164e-06 -2.2920935404694e-05 -1.50773267921384e-05 0.000116777338294652 -0.000116728971483901 0.000212195290405589 -1.11102153005651e-06 4.81106401533197e-05 2.27594350236902e-05 -0.000197084971094761 1.99952998205164e-06 -1.11102153005651e-06 1.47962155092835e-05 -9.28057675938749e-06 5.42180605161047e-06 5.03614327862217e-06 -2.2920935404694e-05 4.81106401533197e-05 -9.28057675938749e-06 7.55108044520617e-05 2.16674308929172e-05 -6.18357467499294e-05 -1.50773267921384e-05 2.27594350236902e-05 5.42180605161047e-06 2.16674308929172e-05 3.46680569983902e-05 -3.95062238078625e-05 0.000116777338294652 -0.000197084971094761 5.03614327862217e-06 -6.18357467499294e-05 -3.95062238078625e-05 0.000281898245008978 496 506 0 354 0 496 506 0 371 0 0 0 0 0 0 0 0 0 1583 0 0 0 0 0 950 +851 901 0.991757474931517 0.118110322125715 0.0496695351782257 0.506338061267814 -0.119182958984348 0.992686487099974 0.0192083475824339 -0.175884519019224 -0.0470375722714975 -0.0249697844698797 0.998580981522446 0.636838605574314 0.000104105699142737 -0.00011856684794159 -5.73869170081186e-06 -1.20076329688625e-05 -8.12112957667171e-06 0.000126745572051721 -0.00011856684794159 0.000183343989599679 9.61509891440886e-06 2.59935768742571e-05 1.10605447011588e-05 -0.000197430914665014 -5.73869170081186e-06 9.61509891440886e-06 1.33081197256437e-05 -5.68265723818275e-06 7.35530539804851e-06 -1.00249967942831e-05 -1.20076329688625e-05 2.59935768742571e-05 -5.68265723818275e-06 4.80383952759304e-05 5.98024343693447e-06 -2.52494176537549e-05 -8.12112957667171e-06 1.10605447011588e-05 7.35530539804851e-06 5.98024343693447e-06 2.23482656027653e-05 -1.00995216886515e-05 0.000126745572051721 -0.000197430914665014 -1.00249967942831e-05 -2.52494176537549e-05 -1.00995216886515e-05 0.000279133505426899 532 553 0 377 0 532 553 0 397 0 0 0 0 0 0 0 0 0 1638 0 0 0 0 0 1020 +851 893 0.991860699366183 0.118117594122192 0.0475456308361904 0.505853108816503 -0.119088988881317 0.992717956562747 0.0181348130707248 -0.175656716271379 -0.0450573609974199 -0.0236493694772104 0.9987044315228 0.635807219739308 4.8408749598747e-05 -4.67170443930471e-05 -8.29304019599255e-07 -4.27787339532471e-06 -2.33412321850392e-06 3.7166935657386e-05 -4.67170443930471e-05 7.7592751459082e-05 3.01963912998248e-06 9.3048107709992e-06 9.29168659138183e-07 -7.18844493903593e-05 -8.29304019599255e-07 3.01963912998248e-06 1.34268033590051e-05 -7.47282324765376e-06 6.76757097483204e-06 -5.34798006051748e-06 -4.27787339532471e-06 9.3048107709992e-06 -7.47282324765376e-06 4.6417161820274e-05 4.04207097026355e-06 -1.69595799861436e-06 -2.33412321850392e-06 9.29168659138183e-07 6.76757097483204e-06 4.04207097026355e-06 2.44624512464329e-05 2.42355363461866e-06 3.7166935657386e-05 -7.18844493903593e-05 -5.34798006051748e-06 -1.69595799861436e-06 2.42355363461866e-06 0.000168372417017306 567 593 0 374 0 567 593 0 391 0 0 0 0 0 0 0 0 0 1649 0 0 0 0 0 1303 +851 891 0.992115147944506 0.118130295188802 0.0418660551958055 0.504611060644334 -0.118828623180642 0.992807506811165 0.0145949557173511 -0.175288207597567 -0.0398408274518081 -0.0194547623476856 0.999016626833583 0.642489708768286 4.7343316484462e-05 -4.903344160314e-05 -5.4515861272332e-06 1.94288041095552e-06 2.29697148853955e-06 4.37078320898432e-05 -4.903344160314e-05 8.70833814120375e-05 6.95031621456257e-06 9.37922588697684e-06 2.32867443397534e-06 -3.6734492369031e-05 -5.4515861272332e-06 6.95031621456257e-06 1.24169450228335e-05 -9.21422284844137e-06 5.76866101530761e-06 -8.59176679302654e-06 1.94288041095552e-06 9.37922588697684e-06 -9.21422284844137e-06 6.53017127411278e-05 9.38200106038166e-06 2.33734343474373e-05 2.29697148853955e-06 2.32867443397534e-06 5.76866101530761e-06 9.38200106038166e-06 2.57444513364198e-05 9.97484805571189e-06 4.37078320898432e-05 -3.6734492369031e-05 -8.59176679302654e-06 2.33734343474373e-05 9.97484805571189e-06 0.000132189150812764 562 588 0 369 0 562 588 0 388 0 0 0 0 0 0 0 0 0 1615 0 0 0 0 0 1796 +851 900 0.991817311632852 0.117800097408341 0.0492093222465819 0.503640579594075 -0.118816446102198 0.992748398085684 0.0182556904539581 -0.178891400547747 -0.0467019537174437 -0.0239531866124829 0.998621636241716 0.644001628653275 0.000105582939845157 -0.000131342333482769 -5.09824588725981e-07 -1.77302851990185e-05 -9.1823470296449e-06 0.000112514278124926 -0.000131342333482769 0.000238633976822723 3.47879250121494e-06 3.64289306239695e-05 1.56483481974042e-05 -0.000184286433608633 -5.09824588725981e-07 3.47879250121494e-06 1.2697672736566e-05 -7.04899248736235e-06 8.02656418411987e-06 -6.9102508130212e-06 -1.77302851990185e-05 3.64289306239695e-05 -7.04899248736235e-06 5.33446928278623e-05 8.20520703188915e-06 -1.09427089722897e-05 -9.1823470296449e-06 1.56483481974042e-05 8.02656418411987e-06 8.20520703188915e-06 2.45712860937288e-05 -6.30487976589279e-06 0.000112514278124926 -0.000184286433608633 -6.9102508130212e-06 -1.09427089722897e-05 -6.30487976589279e-06 0.000238454880427773 557 581 0 376 0 557 581 0 391 0 0 0 0 0 0 0 0 0 1652 0 0 0 0 0 1504 +851 897 0.991638478492492 0.117366824620456 0.0536484524623694 0.507264280431432 -0.118666806540028 0.992696679654953 0.0217138487519411 -0.176193300372235 -0.0507081551497165 -0.0278985784681148 0.99832377128904 0.635747301514998 6.66046193867878e-05 -7.17975659265411e-05 -1.29828141742546e-06 -8.37468106720794e-06 -9.62020275344513e-06 3.20935111927795e-05 -7.17975659265411e-05 0.000115821509513716 1.08013497132618e-06 1.95045943050799e-05 1.00562748378158e-05 -6.19745262649527e-06 -1.29828141742546e-06 1.08013497132618e-06 1.16108619981915e-05 -5.76213796598801e-06 6.57544698138175e-06 4.11299024694866e-08 -8.37468106720794e-06 1.95045943050799e-05 -5.76213796598801e-06 4.31503490304768e-05 2.58633474114768e-06 -3.27345661696937e-06 -9.62020275344513e-06 1.00562748378158e-05 6.57544698138175e-06 2.58633474114768e-06 2.21226288111224e-05 -3.13478985327558e-06 3.20935111927795e-05 -6.19745262649527e-06 4.11299024694866e-08 -3.27345661696937e-06 -3.13478985327558e-06 0.00023770093151876 544 565 0 378 0 544 565 0 394 0 0 0 0 0 0 0 0 0 1641 0 0 0 0 0 1476 +851 895 0.991888119599122 0.117881331080177 0.0475599619520745 0.504665024888281 -0.119043988348503 0.992636428172394 0.0223930860587369 -0.173403177333284 -0.0445700239645254 -0.0278731635792999 0.998617343989119 0.613976979343744 4.04949849632248e-05 -3.75823709697079e-05 -3.1413908347119e-06 7.74985064902117e-06 2.4080585500316e-06 2.15285542957885e-05 -3.75823709697079e-05 8.76003062614585e-05 5.89419527344377e-06 2.57226350818932e-06 -2.62813847054876e-06 1.17293712382809e-05 -3.1413908347119e-06 5.89419527344377e-06 1.36182304473344e-05 -1.02241083574046e-05 4.0318536428438e-06 1.00757625522741e-05 7.74985064902117e-06 2.57226350818932e-06 -1.02241083574046e-05 6.00281294498206e-05 9.42399084786009e-06 -2.51476772974025e-05 2.4080585500316e-06 -2.62813847054876e-06 4.0318536428438e-06 9.42399084786009e-06 2.53256924724747e-05 -1.14671750420924e-05 2.15285542957885e-05 1.17293712382809e-05 1.00757625522741e-05 -2.51476772974025e-05 -1.14671750420924e-05 0.00030204485190725 554 578 0 384 0 554 578 0 398 0 0 0 0 0 0 0 0 0 1779 0 0 0 0 0 1550 +852 856 0.997347192398672 0.0516700845067457 0.0512716313525507 0.259219397197648 -0.0475448079500245 0.995767570826438 -0.0786539009039603 -0.0934411724330683 -0.0551186815107309 0.0760075473718267 0.995582635290029 0.306674481463377 2.76539834521031e-05 -1.17451427981963e-05 1.18881775080133e-06 3.99422405617125e-06 7.87819421987473e-07 3.24042610840884e-06 -1.17451427981963e-05 4.26910268576771e-05 -4.80249529091224e-07 4.59131929483689e-06 1.25060659017501e-06 -8.19296865720071e-06 1.18881775080133e-06 -4.80249529091224e-07 1.38218078979782e-05 1.05508099660646e-06 4.5000745964331e-06 8.94239525994619e-08 3.99422405617125e-06 4.59131929483689e-06 1.05508099660646e-06 4.68433366125778e-05 2.32659354652041e-06 -1.08833408221987e-05 7.87819421987473e-07 1.25060659017501e-06 4.5000745964331e-06 2.32659354652041e-06 2.3291195022462e-05 5.2856765576584e-06 3.24042610840884e-06 -8.19296865720071e-06 8.94239525994619e-08 -1.08833408221987e-05 5.2856765576584e-06 7.37022597711344e-05 1571 1591 0 193 0 1571 1591 0 210 0 0 0 0 0 0 0 0 0 2490 0 0 0 0 0 1398 +852 854 0.998778235728974 0.0330010321184249 0.0367827094330566 0.155624722799646 -0.0318754061711579 0.999017805286346 -0.0307795906775176 -0.050137915007924 -0.0377623399108384 0.0295695214700967 0.998849162328571 0.1459910692719 2.13794575454241e-05 -1.22557302276555e-05 1.611466107439e-06 -2.18628867968245e-06 7.90382100272883e-07 1.45956842283951e-05 -1.22557302276555e-05 3.10402771859085e-05 -1.93611547297141e-07 3.75940244457743e-06 -1.21353910651684e-06 2.20079227093906e-06 1.611466107439e-06 -1.93611547297141e-07 1.08359093773624e-05 2.98402821676383e-06 4.41334331323712e-06 5.32384884300286e-07 -2.18628867968245e-06 3.75940244457743e-06 2.98402821676383e-06 3.19120071413978e-05 5.85244296122457e-06 -2.40405876656954e-06 7.90382100272883e-07 -1.21353910651684e-06 4.41334331323712e-06 5.85244296122457e-06 1.67849982028669e-05 1.41300196221528e-06 1.45956842283951e-05 2.20079227093906e-06 5.32384884300286e-07 -2.40405876656954e-06 1.41300196221528e-06 7.09906052733149e-05 2074 2095 0 133 0 2074 2095 0 146 0 0 0 0 0 0 0 0 0 3366 0 0 0 0 0 2236 +852 855 0.998544076833898 0.0397564990751934 0.0364574738732993 0.215473005624043 -0.0367503987927749 0.996140136943916 -0.0797134603309188 -0.0740328021648184 -0.0394858811287042 0.078257576953552 0.996150900637473 0.240397031005082 2.57378120664596e-05 -1.24605982570179e-05 1.55729841037927e-06 2.93399228340544e-06 -1.47124764717528e-07 1.30096396643254e-05 -1.24605982570179e-05 3.48898959629926e-05 1.9876862119081e-06 4.74915186761068e-06 -8.51815146483252e-07 -1.8309679362148e-05 1.55729841037927e-06 1.9876862119081e-06 1.39781365959753e-05 2.45660306129241e-06 5.37588421126138e-06 1.94413156749862e-06 2.93399228340544e-06 4.74915186761068e-06 2.45660306129241e-06 6.67909201719887e-05 7.97368774016134e-06 -2.0957296362759e-05 -1.47124764717528e-07 -8.51815146483252e-07 5.37588421126138e-06 7.97368774016134e-06 2.40645494004066e-05 -4.1551601768609e-06 1.30096396643254e-05 -1.8309679362148e-05 1.94413156749862e-06 -2.0957296362759e-05 -4.1551601768609e-06 8.81904699793176e-05 1732 1751 0 196 0 1732 1751 0 208 0 0 0 0 0 0 0 0 0 2680 0 0 0 0 0 1828 +852 937 0.902007087469065 -0.419022573287191 -0.103938911055273 0.484087183725022 0.420901246908536 0.907096674215095 -0.00421473353288298 0.126434497449297 0.0960487090304453 -0.0399462977470259 0.994574752741035 -0.229721515180387 5.60009802847339e-05 2.89719876445122e-05 -2.59268431494067e-06 4.45583258403544e-05 -2.87952539588297e-06 0.000126510201597514 2.89719876445122e-05 0.000304858630592014 -5.60223577336475e-06 0.000169272558062632 -1.30692146017909e-05 0.00032844392132057 -2.59268431494067e-06 -5.60223577336475e-06 1.12206424173576e-05 -7.36431001050527e-06 4.68178906052903e-06 -1.13969095408766e-05 4.45583258403544e-05 0.000169272558062632 -7.36431001050527e-06 0.000191589223119314 -4.4315807211338e-06 0.000271781023180462 -2.87952539588297e-06 -1.30692146017909e-05 4.68178906052903e-06 -4.4315807211338e-06 1.52980834086561e-05 -1.42072626464357e-05 0.000126510201597514 0.00032844392132057 -1.13969095408766e-05 0.000271781023180462 -1.42072626464357e-05 0.000667547545932679 2042 2046 0 0 0 2072 2076 0 0 0 0 0 0 0 0 926 910 0 3119 0 0 0 0 0 303 +852 899 0.99433055358798 0.0989179428195192 0.0390127003650822 0.404533537268949 -0.100357348265346 0.994269096064106 0.036842465457871 -0.139264825317461 -0.0351447414355183 -0.040548800231581 0.998559283142073 0.582847794813839 5.55406857377802e-05 -5.63267367322713e-05 -1.83590939268288e-06 -8.29445218694275e-06 -5.36714190468441e-06 5.69474009170213e-05 -5.63267367322713e-05 0.000147919681327811 3.70964792798706e-06 2.29975280451093e-05 1.17102794401174e-05 5.50489068000422e-06 -1.83590939268288e-06 3.70964792798706e-06 1.16096590614472e-05 -5.95353619660411e-06 8.25296444674253e-06 -2.53441256087144e-06 -8.29445218694275e-06 2.29975280451093e-05 -5.95353619660411e-06 4.71738330834202e-05 5.09818521422062e-06 1.29457609895813e-05 -5.36714190468441e-06 1.17102794401174e-05 8.25296444674253e-06 5.09818521422062e-06 2.37904658120073e-05 6.52277152051884e-06 5.69474009170213e-05 5.50489068000422e-06 -2.53441256087144e-06 1.29457609895813e-05 6.52277152051884e-06 0.000200067778639681 676 694 0 279 0 676 694 0 302 0 0 0 0 0 0 0 0 0 2041 0 0 0 0 0 1388 +852 900 0.994222931311976 0.0986313732958689 0.0423392850104091 0.407647600171597 -0.1001429276906 0.994350285473612 0.0351980654596312 -0.140208094874142 -0.0386284466032076 -0.0392347037750545 0.998483090058468 0.593400049070746 5.04964252579291e-05 -3.9930049013684e-05 9.72082894495847e-07 -5.09425560102752e-06 -4.77964539425931e-06 4.81564306596403e-05 -3.9930049013684e-05 8.59862283559354e-05 -3.92741519175254e-07 2.02844965579247e-05 1.16290932918573e-05 2.14990260307188e-05 9.72082894495847e-07 -3.92741519175254e-07 1.23621114869766e-05 -5.32940837465405e-06 6.69666223471219e-06 5.71651974282332e-07 -5.09425560102752e-06 2.02844965579247e-05 -5.32940837465405e-06 4.45414520071029e-05 5.78940080186484e-06 1.70106620098813e-05 -4.77964539425931e-06 1.16290932918573e-05 6.69666223471219e-06 5.78940080186484e-06 2.42986860532284e-05 1.77329021705888e-05 4.81564306596403e-05 2.14990260307188e-05 5.71651974282332e-07 1.70106620098813e-05 1.77329021705888e-05 0.000224848134112577 671 687 0 287 0 671 687 0 311 0 0 0 0 0 0 0 0 0 1944 0 0 0 0 0 869 +852 929 0.996244159172845 0.0774198152691579 0.0387781835273576 0.400848595060432 -0.0794923476882543 0.99531104152452 0.055108050939808 -0.139064232368945 -0.03432989911144 -0.0579836427198589 0.99772709455238 0.559842421539821 5.50650188838692e-05 -3.2681494445633e-05 -9.01490954717279e-06 5.98947554273796e-06 8.74461287220489e-06 3.3016570331277e-05 -3.2681494445633e-05 5.72503543329132e-05 8.17175212576947e-06 -4.18311533957986e-07 -8.93129194086813e-06 1.55724880285002e-05 -9.01490954717279e-06 8.17175212576947e-06 1.44610771304991e-05 -7.21022396795623e-06 5.54408588236306e-06 -4.54981346228688e-06 5.98947554273796e-06 -4.18311533957986e-07 -7.21022396795623e-06 3.57774673811445e-05 -2.9064276382942e-07 8.13760561663843e-06 8.74461287220489e-06 -8.93129194086813e-06 5.54408588236306e-06 -2.9064276382942e-07 2.52280223348767e-05 7.56901253298001e-06 3.3016570331277e-05 1.55724880285002e-05 -4.54981346228688e-06 8.13760561663843e-06 7.56901253298001e-06 0.000144469636719468 728 753 0 269 0 728 753 0 294 0 0 0 0 0 0 0 0 0 2181 0 0 0 0 0 1235 +852 898 0.994529431692838 0.0993162363402943 0.0323650227239014 0.400293839274234 -0.100454698308291 0.994301571159607 0.0356824771747651 -0.138742516936365 -0.0286367436086955 -0.0387384923394823 0.998838959055339 0.577102482521222 4.67384660976304e-05 -3.47045628221203e-05 -6.33680068335762e-06 -1.87671816924226e-06 3.66857314186516e-06 4.78357168840243e-05 -3.47045628221203e-05 9.64900295027623e-05 6.79139067356097e-06 7.44852615415859e-06 -5.29534091972009e-06 6.6084422507474e-05 -6.33680068335762e-06 6.79139067356097e-06 1.43562252943473e-05 -9.24804079254789e-06 3.00678761041883e-06 -3.93627450577472e-06 -1.87671816924226e-06 7.44852615415859e-06 -9.24804079254789e-06 5.90550360460364e-05 1.38109371709695e-05 6.08201845659443e-06 3.66857314186516e-06 -5.29534091972009e-06 3.00678761041883e-06 1.38109371709695e-05 2.84355436503941e-05 5.09145161686836e-06 4.78357168840243e-05 6.6084422507474e-05 -3.93627450577472e-06 6.08201845659443e-06 5.09145161686836e-06 0.000322517747098501 658 678 0 273 0 658 678 0 298 0 0 0 0 0 0 0 0 0 2057 0 0 0 0 0 1362 +852 934 0.951903040350341 -0.291479075186606 -0.0944486659521321 0.439411495660163 0.29219951361531 0.956335839896713 -0.00641915664433015 -0.0182195229820669 0.0921956941226236 -0.021487439526605 0.995509037592245 0.200130127409377 4.02996703606374e-05 -3.46596322965587e-05 -1.92213306780667e-06 1.0903413973529e-05 -1.73633959184892e-06 3.78091406983358e-05 -3.46596322965587e-05 6.96075692213209e-05 2.63746333418282e-06 1.95548247483218e-06 -6.68595575542697e-07 -2.86912141051816e-05 -1.92213306780667e-06 2.63746333418282e-06 1.14264144162358e-05 -9.13339713432266e-07 7.27316529537628e-06 -2.19512752752762e-06 1.0903413973529e-05 1.95548247483218e-06 -9.13339713432266e-07 5.84697455000011e-05 -5.48529264264974e-07 5.9950983015312e-06 -1.73633959184892e-06 -6.68595575542697e-07 7.27316529537628e-06 -5.48529264264974e-07 1.81372090466762e-05 3.45339542910094e-08 3.78091406983358e-05 -2.86912141051816e-05 -2.19512752752762e-06 5.9950983015312e-06 3.45339542910094e-08 8.16421788100015e-05 1601 1601 0 0 0 1614 1614 0 0 0 0 0 0 0 0 366 368 0 3314 0 0 0 0 0 1215 +852 893 0.994439353358764 0.0986718425362626 0.0367999997541157 0.403276673867829 -0.10000101224346 0.994327996227998 0.036216480606168 -0.138386104994433 -0.0330177231451113 -0.0396951307808985 0.99866617372904 0.578628484073402 3.57367947164037e-05 -3.78478488765207e-05 -1.46463458965217e-06 -3.14660908673373e-06 -4.34985851324866e-07 3.65212532577952e-05 -3.78478488765207e-05 0.000148763383128343 1.59134156870314e-06 3.68299126752666e-05 1.28432942872372e-05 2.96969128171153e-05 -1.46463458965217e-06 1.59134156870314e-06 9.88945442260205e-06 -3.96093726121103e-06 6.56812675242833e-06 -2.47610947452261e-06 -3.14660908673373e-06 3.68299126752666e-05 -3.96093726121103e-06 4.42979255220591e-05 4.49477261838326e-06 3.56849000581829e-05 -4.34985851324866e-07 1.28432942872372e-05 6.56812675242833e-06 4.49477261838326e-06 2.2708275662948e-05 2.2704821659032e-05 3.65212532577952e-05 2.96969128171153e-05 -2.47610947452261e-06 3.56849000581829e-05 2.2704821659032e-05 0.000214811784654642 705 728 0 271 0 705 728 0 300 0 0 0 0 0 0 0 0 0 1996 0 0 0 0 0 1605 +852 933 0.974528295241438 -0.221549921734753 -0.0347884169392911 0.425336647782525 0.221835911822311 0.975073443192161 0.00453967040070806 -0.0547829040043288 0.0329154978662207 -0.0121413574491424 0.999384389231446 0.278587943021466 3.09219259527039e-05 -2.65240010459529e-05 -4.68561009296715e-08 4.23987757628258e-06 9.03243448680387e-08 2.90001376415586e-05 -2.65240010459529e-05 9.03225330102353e-05 4.32019856238709e-06 6.46074221187565e-06 1.01013678442791e-06 2.10520219737414e-05 -4.68561009296715e-08 4.32019856238709e-06 1.013362322361e-05 3.54548287379358e-06 6.52032721541629e-06 1.65870899864336e-06 4.23987757628258e-06 6.46074221187565e-06 3.54548287379358e-06 3.8480966353374e-05 4.18327280746388e-06 1.41810218919807e-05 9.03243448680387e-08 1.01013678442791e-06 6.52032721541629e-06 4.18327280746388e-06 1.45622159578694e-05 2.24546083666096e-06 2.90001376415586e-05 2.10520219737414e-05 1.65870899864336e-06 1.41810218919807e-05 2.24546083666096e-06 0.000127332920142768 1692 1692 0 0 0 1716 1716 0 0 0 0 0 0 0 0 246 255 0 3048 0 0 0 0 0 1363 +852 930 0.995216722190178 0.0153566352892549 0.096477197438725 0.400515380959193 -0.0204652767917973 0.998427585837813 0.0521874341572012 -0.131374523968464 -0.0955240719341101 -0.0539122397111259 0.993966107113546 0.537998610342887 2.60718265241775e-05 -1.7663752365855e-05 -1.55237261735952e-06 3.30422407445863e-06 -1.20535685797668e-06 2.20007319123703e-05 -1.7663752365855e-05 6.85097717078326e-05 1.45924823864502e-06 7.49265736002211e-07 -1.34673904781261e-06 -1.99668608186419e-05 -1.55237261735952e-06 1.45924823864502e-06 1.12065016584447e-05 -7.31220372580805e-06 6.69424974452231e-06 -4.07598150681862e-06 3.30422407445863e-06 7.49265736002211e-07 -7.31220372580805e-06 3.88614894583402e-05 -1.35381159434289e-06 1.1246945960392e-05 -1.20535685797668e-06 -1.34673904781261e-06 6.69424974452231e-06 -1.35381159434289e-06 1.87047957710127e-05 5.99443327423241e-06 2.20007319123703e-05 -1.99668608186419e-05 -4.07598150681862e-06 1.1246945960392e-05 5.99443327423241e-06 0.000107531694049184 922 944 0 199 0 922 944 0 225 0 0 0 0 0 0 0 0 0 2221 0 0 0 0 0 1387 +852 932 0.991180040099838 -0.132280769664086 -0.0079953789629341 0.401416526798755 0.132469313444108 0.990683754822781 0.0315844728605968 -0.0943934991582013 0.00374287367279645 -0.0323650414384439 0.999469106570762 0.375179240236783 4.87206857693728e-05 -2.08070459990547e-05 -1.41050904710809e-06 2.56908878203192e-06 -2.12981736454128e-06 4.69691639107811e-05 -2.08070459990547e-05 0.000101040071604078 4.59743648283575e-06 8.12731973148562e-06 1.95112405656615e-06 7.43162431181855e-05 -1.41050904710809e-06 4.59743648283575e-06 1.2692275768364e-05 -3.51742425932369e-06 6.56352978525404e-06 2.34776022307827e-06 2.56908878203192e-06 8.12731973148562e-06 -3.51742425932369e-06 4.48681674089247e-05 2.07773248130659e-06 1.40794783806614e-05 -2.12981736454128e-06 1.95112405656615e-06 6.56352978525404e-06 2.07773248130659e-06 2.14205293995169e-05 8.36858473593446e-06 4.69691639107811e-05 7.43162431181855e-05 2.34776022307827e-06 1.40794783806614e-05 8.36858473593446e-06 0.000261744462854542 1318 1316 0 7 0 1341 1339 0 2 0 0 0 0 0 0 75 90 0 2989 0 0 0 0 0 514 +852 931 0.996370509634501 -0.0553541473089489 0.0646662655979481 0.401898596377851 0.0531753687672618 0.997973642590125 0.0349426508991829 -0.116607108517332 -0.0664694492767234 -0.0313771743644267 0.997294984065273 0.466743320299414 5.49844414976617e-05 -4.27639667487793e-05 -7.96986422331448e-06 1.0839399961636e-05 3.50377191204405e-06 6.61752252753197e-05 -4.27639667487793e-05 0.000189004832128773 6.54524388104973e-06 -6.69649638985985e-06 -1.40220735041464e-06 0.000105230997517926 -7.96986422331448e-06 6.54524388104973e-06 1.32358927394556e-05 -5.9325340872243e-06 5.37778534683193e-06 -7.97437593521768e-06 1.0839399961636e-05 -6.69649638985985e-06 -5.9325340872243e-06 4.86160015172608e-05 5.23912624712159e-06 4.64509276795885e-06 3.50377191204405e-06 -1.40220735041464e-06 5.37778534683193e-06 5.23912624712159e-06 2.22655025751181e-05 1.49736303166827e-05 6.61752252753197e-05 0.000105230997517926 -7.97437593521768e-06 4.64509276795885e-06 1.49736303166827e-05 0.000322697707142519 1123 1139 0 79 0 1123 1139 0 104 0 0 0 0 0 0 0 0 0 2616 0 0 0 0 0 734 +852 936 0.918453479543027 -0.385236122147976 -0.0896456139902895 0.468407183228456 0.384657627343481 0.922738346854466 -0.0243403568332884 0.0762318281442083 0.0920962303343072 -0.0121273837524017 0.995676258088708 -0.0637602014279805 3.47309548279426e-05 -1.52299979222194e-05 1.88229488364335e-06 6.90092324983804e-06 -1.3147754356887e-06 1.59190711946161e-05 -1.52299979222194e-05 3.11373972519896e-05 -1.20780999674894e-07 2.59103408137778e-06 -8.60337734312792e-07 -4.22568120153114e-06 1.88229488364335e-06 -1.20780999674894e-07 1.03081401631862e-05 4.02015225477766e-06 4.32074873938702e-06 1.08831851766452e-06 6.90092324983804e-06 2.59103408137778e-06 4.02015225477766e-06 5.38324855561957e-05 4.43284529773937e-06 1.18720794525116e-05 -1.3147754356887e-06 -8.60337734312792e-07 4.32074873938702e-06 4.43284529773937e-06 1.54224741073978e-05 4.31250197930162e-08 1.59190711946161e-05 -4.22568120153114e-06 1.08831851766452e-06 1.18720794525116e-05 4.31250197930162e-08 9.81565806807985e-05 2139 2139 0 0 0 2151 2151 0 0 0 0 0 0 0 0 744 734 0 3425 0 0 0 0 0 426 +852 897 0.994468400196085 0.0978973743613523 0.0380618589219156 0.401265141774889 -0.0993262855872485 0.994342031436355 0.037659175647695 -0.139685128789685 -0.0341597717041391 -0.0412314032283264 0.998565511814295 0.580171035014162 4.71003073310096e-05 -3.87665576404753e-05 -5.80921332853188e-07 -2.26020644027163e-06 -3.74167207923061e-06 4.81791097133147e-05 -3.87665576404753e-05 8.01861583855981e-05 6.5776372894771e-07 1.4782204655612e-05 7.72984025716475e-06 3.45430111812809e-05 -5.80921332853188e-07 6.5776372894771e-07 1.2559096147387e-05 -7.18451906175971e-06 5.85912599547775e-06 -1.39741859926455e-06 -2.26020644027163e-06 1.4782204655612e-05 -7.18451906175971e-06 4.72587656843116e-05 5.14335478612852e-06 2.05969344524925e-05 -3.74167207923061e-06 7.72984025716475e-06 5.85912599547775e-06 5.14335478612852e-06 2.37454970319772e-05 1.28464586625704e-05 4.81791097133147e-05 3.45430111812809e-05 -1.39741859926455e-06 2.05969344524925e-05 1.28464586625704e-05 0.00022515860257794 687 708 0 284 0 687 708 0 309 0 0 0 0 0 0 0 0 0 1992 0 0 0 0 0 867 +852 895 0.994331552703709 0.0984986886955296 0.0400346302979349 0.406193090525948 -0.0999809374836942 0.994305704088094 0.0368778925341467 -0.136584410209023 -0.0361742372098266 -0.0406715520129193 0.998517525844763 0.581861559628134 4.68486560295991e-05 -4.61533313379601e-05 -5.48001431418881e-06 1.98369693828487e-06 1.48799183506426e-06 3.61504070154681e-05 -4.61533313379601e-05 8.82823475188862e-05 7.46900045820114e-06 9.51494395767674e-06 3.01173421458928e-06 -5.79799669623182e-06 -5.48001431418881e-06 7.46900045820114e-06 1.19243215274077e-05 -4.52899746776484e-06 6.03663395883133e-06 -3.69195615447514e-06 1.98369693828487e-06 9.51494395767674e-06 -4.52899746776484e-06 4.76665460539739e-05 9.6035246338618e-06 2.26478957733599e-05 1.48799183506426e-06 3.01173421458928e-06 6.03663395883133e-06 9.6035246338618e-06 2.37214408709937e-05 1.32087330198634e-05 3.61504070154681e-05 -5.79799669623182e-06 -3.69195615447514e-06 2.26478957733599e-05 1.32087330198634e-05 0.000166114311931964 701 724 0 279 0 701 724 0 300 0 0 0 0 0 0 0 0 0 2053 0 0 0 0 0 1548 +852 938 0.881501861946164 -0.458321080716806 -0.113561676440713 0.516838572245555 0.461716466772345 0.887018123134173 0.00409310918391306 0.192011957504016 0.0988553068717481 -0.0560413793737184 0.993522517158611 -0.288322328012495 4.71633820015411e-05 -2.58789467681651e-05 -7.87425002092032e-07 1.47131739322495e-06 -6.6030786270878e-07 4.42216346219947e-05 -2.58789467681651e-05 0.000168015020711159 2.07267458638948e-06 8.04882820163474e-05 -1.62785420977747e-05 4.88497416690889e-05 -7.87425002092032e-07 2.07267458638948e-06 1.03984503234964e-05 5.60913535232209e-07 5.38465547031016e-06 -6.66617358050012e-06 1.47131739322495e-06 8.04882820163474e-05 5.60913535232209e-07 0.000113441402117491 -6.89689733200417e-06 9.83468748633655e-05 -6.6030786270878e-07 -1.62785420977747e-05 5.38465547031016e-06 -6.89689733200417e-06 1.71683714665819e-05 -1.43341596424759e-05 4.42216346219947e-05 4.88497416690889e-05 -6.66617358050012e-06 9.83468748633655e-05 -1.43341596424759e-05 0.000324646281742986 1916 2036 0 0 65 1944 2064 0 0 65 0 0 0 0 0 1066 1044 0 2995 0 0 0 0 0 191 +852 894 0.994340697687083 0.0986188119624991 0.0395083136854772 0.404238966866354 -0.100021975649912 0.994360038680314 0.0352663843167024 -0.139887227728488 -0.035807559400959 -0.0390185007757886 0.998596703022274 0.586243398914918 4.36035028113035e-05 -4.29351250027237e-05 5.82995025904195e-07 -1.54253923519272e-06 -6.03852839818989e-06 3.76948190543332e-05 -4.29351250027237e-05 0.000103082122369207 4.21283976228962e-08 1.71995084608747e-05 1.0940829385419e-05 -5.09064730484742e-06 5.82995025904195e-07 4.21283976228962e-08 1.09354647490201e-05 -5.28892612377648e-06 6.31707697621134e-06 1.1679919938356e-06 -1.54253923519272e-06 1.71995084608747e-05 -5.28892612377648e-06 4.01353517335132e-05 3.1993203889853e-06 5.37442694122822e-06 -6.03852839818989e-06 1.0940829385419e-05 6.31707697621134e-06 3.1993203889853e-06 2.05878919034184e-05 4.7964440345931e-06 3.76948190543332e-05 -5.09064730484742e-06 1.1679919938356e-06 5.37442694122822e-06 4.7964440345931e-06 0.000113361916629955 634 651 0 275 0 634 651 0 300 0 0 0 0 0 0 0 0 0 1959 0 0 0 0 0 1387 +852 892 0.994275449766641 0.0981188968672859 0.0422967146347142 0.4055067893738 -0.0996031582098766 0.994427654174725 0.0345376821337615 -0.139171676402069 -0.0386722234421789 -0.0385528557969624 0.998507955123011 0.589611869990428 4.65825840387677e-05 -3.9708171831943e-05 -8.36724452254197e-07 -8.83849118533807e-07 -1.29217520946438e-06 4.88099224617758e-05 -3.9708171831943e-05 7.39919111593206e-05 1.50980823945004e-06 6.48052814480955e-06 -2.14898002953058e-08 -2.13199217642526e-05 -8.36724452254197e-07 1.50980823945004e-06 1.09838840622872e-05 -6.639483385244e-06 6.64946083272162e-06 1.76422705021691e-06 -8.83849118533807e-07 6.48052814480955e-06 -6.639483385244e-06 3.45927632708562e-05 -7.26045198989109e-07 -8.29090548967046e-06 -1.29217520946438e-06 -2.14898002953058e-08 6.64946083272162e-06 -7.26045198989109e-07 1.93995603287887e-05 -3.11956544742151e-06 4.88099224617758e-05 -2.13199217642526e-05 1.76422705021691e-06 -8.29090548967046e-06 -3.11956544742151e-06 0.000152698690595084 668 682 0 274 0 668 682 0 300 0 0 0 0 0 0 0 0 0 2017 0 0 0 0 0 1348 +852 891 0.994305547375281 0.0987904697103222 0.0399615008871869 0.409751309015975 -0.100052586327417 0.99450164124441 0.0309186922648823 -0.137291120370493 -0.0366873060872207 -0.0347408787538501 0.998722740762156 0.587602679975473 4.65970674040129e-05 -3.84628352789473e-05 -6.53640087523856e-06 6.4787763856327e-06 9.36238131480926e-08 3.71038010246924e-05 -3.84628352789473e-05 7.61610400887188e-05 6.98906805254538e-06 8.13201734199442e-07 -9.71869749697917e-07 1.76723880799119e-05 -6.53640087523856e-06 6.98906805254538e-06 1.23554540600361e-05 -5.55815513539214e-06 6.88188885648143e-06 -3.21348596392737e-06 6.4787763856327e-06 8.13201734199442e-07 -5.55815513539214e-06 3.70957831198481e-05 8.5251031465007e-07 1.58037620384945e-05 9.36238131480926e-08 -9.71869749697917e-07 6.88188885648143e-06 8.5251031465007e-07 2.16427255355424e-05 6.64168075462976e-06 3.71038010246924e-05 1.76723880799119e-05 -3.21348596392737e-06 1.58037620384945e-05 6.64168075462976e-06 0.000161325238469844 707 733 0 287 0 707 733 0 311 0 0 0 0 0 0 0 0 0 1939 0 0 0 0 0 1171 +852 901 0.994326851719319 0.098821286460455 0.0393505437351063 0.404680735153307 -0.100291625281305 0.994257657633592 0.0373269357890197 -0.137979069766319 -0.0354358836263773 -0.041061704534322 0.998528033944142 0.578450832203263 3.44933435989351e-05 -4.133204857491e-05 -1.90509447413695e-06 2.8518214069025e-06 -1.24136070979816e-06 2.66694257517477e-05 -4.133204857491e-05 0.00011729985998106 3.63980171445905e-06 1.04591484410845e-05 6.06485662389839e-06 8.54556621883643e-06 -1.90509447413695e-06 3.63980171445905e-06 1.10665968174338e-05 -6.14055501776676e-06 7.16523530071035e-06 -2.46442772934513e-06 2.8518214069025e-06 1.04591484410845e-05 -6.14055501776676e-06 3.58841651510088e-05 2.24631705547873e-06 1.99871751836875e-05 -1.24136070979816e-06 6.06485662389839e-06 7.16523530071035e-06 2.24631705547873e-06 2.08259541498001e-05 1.18256720814565e-05 2.66694257517477e-05 8.54556621883643e-06 -2.46442772934513e-06 1.99871751836875e-05 1.18256720814565e-05 0.000111964660658666 682 692 0 273 0 682 692 0 299 0 0 0 0 0 0 0 0 0 1993 0 0 0 0 0 1358 +852 896 0.994601216866193 0.0989867181588458 0.0311456102272846 0.40110679656431 -0.100061863048812 0.994362145813633 0.0350933973292293 -0.138539022333724 -0.027496235587613 -0.0380204234727545 0.99889859566798 0.57356772953153 5.25170947492715e-05 -4.63065351820825e-05 -3.63946757437245e-06 5.56372380560884e-07 -2.09322269593242e-07 3.27743303427257e-05 -4.63065351820825e-05 0.000126253957196196 2.36362616475923e-06 2.65536420272847e-05 1.46886452769816e-05 6.96991550011195e-05 -3.63946757437245e-06 2.36362616475923e-06 1.19577853404982e-05 -4.9434247822452e-06 5.82088836324579e-06 -5.04824926591505e-06 5.56372380560884e-07 2.65536420272847e-05 -4.9434247822452e-06 4.85883164648031e-05 9.13834078415469e-06 4.58362116584582e-05 -2.09322269593242e-07 1.46886452769816e-05 5.82088836324579e-06 9.13834078415469e-06 2.41718253634985e-05 3.14042975329826e-05 3.27743303427257e-05 6.96991550011195e-05 -5.04824926591505e-06 4.58362116584582e-05 3.14042975329826e-05 0.000280324779738636 656 676 0 285 0 656 676 0 305 0 0 0 0 0 0 0 0 0 1994 0 0 0 0 0 1287 +852 903 0.994440944353212 0.0981907530034569 0.0380234693118071 0.401581795404264 -0.0995645190121565 0.99437618596252 0.0360958078523054 -0.139472393274647 -0.0342653578380517 -0.0396809376810423 0.998624708505144 0.586530470429278 3.37008433602678e-05 -2.78988552175026e-05 -1.01420707990826e-06 -1.87231883965866e-06 -5.0298303280158e-06 1.85797056069169e-05 -2.78988552175026e-05 5.49859459601803e-05 2.10429237744262e-06 7.16084705171482e-06 4.90057684597335e-06 -5.6617537287421e-06 -1.01420707990826e-06 2.10429237744262e-06 1.08971535608915e-05 -5.98713674405643e-06 6.89298524831917e-06 -1.51173247462762e-06 -1.87231883965866e-06 7.16084705171482e-06 -5.98713674405643e-06 3.77983642521871e-05 1.96844574317275e-06 2.59899674778606e-06 -5.0298303280158e-06 4.90057684597335e-06 6.89298524831917e-06 1.96844574317275e-06 2.0473206037182e-05 1.42974878373912e-06 1.85797056069169e-05 -5.6617537287421e-06 -1.51173247462762e-06 2.59899674778606e-06 1.42974878373912e-06 8.46261144271682e-05 649 663 0 274 0 649 663 0 300 0 0 0 0 0 0 0 0 0 1965 0 0 0 0 0 1565 +852 902 0.994435289900197 0.099007958879608 0.0359983093992565 0.402908577811907 -0.100283677253479 0.994323646389951 0.0355481406871258 -0.139229187174686 -0.0322744214143449 -0.0389603684310809 0.99871940574622 0.582618276572692 3.97156934233087e-05 -4.27700407414423e-05 -2.63755342583332e-06 -2.67455311558327e-06 -4.58733009046829e-06 3.36525758829368e-05 -4.27700407414423e-05 0.000107970245389608 4.30502525492702e-06 1.91817024145183e-05 1.22084079234046e-05 -1.2559630166588e-05 -2.63755342583332e-06 4.30502525492702e-06 1.19370819678526e-05 -5.91040670477703e-06 7.84504986604905e-06 -1.08941688266435e-06 -2.67455311558327e-06 1.91817024145183e-05 -5.91040670477703e-06 4.01473829042168e-05 2.77229710323877e-07 7.93358276557757e-06 -4.58733009046829e-06 1.22084079234046e-05 7.84504986604905e-06 2.77229710323877e-07 1.94868064345582e-05 1.97228096530641e-06 3.36525758829368e-05 -1.2559630166588e-05 -1.08941688266435e-06 7.93358276557757e-06 1.97228096530641e-06 0.000125198222214036 678 699 0 272 0 678 699 0 296 0 0 0 0 0 0 0 0 0 2037 0 0 0 0 0 1384 +852 925 0.99435593929244 0.0980572087022184 0.0405098730605129 0.406810728922435 -0.099590071733705 0.994312973253989 0.0377296810334816 -0.137589588659392 -0.036579825121572 -0.0415511135872715 0.998466534919289 0.584447037209858 3.5097141732112e-05 -2.46226694451541e-05 9.75253877172352e-07 -6.22241501903764e-06 -7.97260049358864e-06 2.46459039531421e-05 -2.46226694451541e-05 5.13542970880523e-05 3.43723048435334e-07 1.64142322978246e-05 8.42309774416511e-06 1.09863730777972e-05 9.75253877172352e-07 3.43723048435334e-07 1.23648373116578e-05 -6.67271941774438e-06 5.35194537263298e-06 -4.10510607306312e-06 -6.22241501903764e-06 1.64142322978246e-05 -6.67271941774438e-06 5.4041930931563e-05 1.0228043107266e-05 2.11041154713736e-05 -7.97260049358864e-06 8.42309774416511e-06 5.35194537263298e-06 1.0228043107266e-05 2.62305730889017e-05 8.83797696274361e-06 2.46459039531421e-05 1.09863730777972e-05 -4.10510607306312e-06 2.11041154713736e-05 8.83797696274361e-06 0.000133286342756627 638 661 0 287 0 638 661 0 314 0 0 0 0 0 0 0 0 0 1983 0 0 0 0 0 1557 +853 937 0.891326069190347 -0.437029067061824 -0.120596156343213 0.406109321768225 0.439890624517181 0.898045650159412 -0.00320135778135616 0.161502119983691 0.109699940034484 -0.0501956648808594 0.992696488552064 -0.261534550868777 3.46548392919123e-05 -3.71616182891064e-05 1.86736645122309e-06 -4.50186207489282e-06 6.0350222942395e-07 2.77603113286058e-05 -3.71616182891064e-05 8.44571410556782e-05 -3.18978902326246e-06 3.44434147903496e-05 -8.71411658974357e-07 -3.05183056417096e-05 1.86736645122309e-06 -3.18978902326246e-06 8.98228180014974e-06 1.1991705404221e-06 4.73051072400764e-06 -6.1182647342721e-07 -4.50186207489282e-06 3.44434147903496e-05 1.1991705404221e-06 6.57883966369245e-05 3.15672048558201e-06 8.77367516301607e-06 6.0350222942395e-07 -8.71411658974357e-07 4.73051072400764e-06 3.15672048558201e-06 1.34537259382828e-05 -8.03042255268902e-07 2.77603113286058e-05 -3.05183056417096e-05 -6.1182647342721e-07 8.77367516301607e-06 -8.03042255268902e-07 9.59357813636406e-05 2017 2021 0 0 0 2047 2051 0 0 0 0 0 0 0 0 1040 1024 0 2861 0 0 0 0 0 709 +853 899 0.996845773057555 0.0792073749990851 0.00496955561794551 0.305417190136622 -0.079348914816831 0.995896144446809 0.0435272235890511 -0.10639300523007 -0.00150148415803892 -0.0437842576930826 0.999039881247785 0.503076531466624 5.15944837703705e-05 -4.19486975298478e-05 -2.61512761743628e-06 -5.49369372356971e-06 -2.73786449745974e-06 4.05344047028434e-05 -4.19486975298478e-05 0.00014595386383301 5.59510396503608e-06 2.49253379871911e-05 1.21238401032071e-05 0.000109352707527272 -2.61512761743628e-06 5.59510396503608e-06 1.33559719296971e-05 -8.32081681955766e-06 6.16942917996304e-06 3.23858542538054e-06 -5.49369372356971e-06 2.49253379871911e-05 -8.32081681955766e-06 4.48512235470271e-05 5.8725525081499e-06 2.64256187873946e-05 -2.73786449745974e-06 1.21238401032071e-05 6.16942917996304e-06 5.8725525081499e-06 2.33753555540135e-05 1.76419289002011e-05 4.05344047028434e-05 0.000109352707527272 3.23858542538054e-06 2.64256187873946e-05 1.76419289002011e-05 0.000325075117329673 703 726 0 208 0 703 726 0 234 0 0 0 0 0 0 0 0 0 2380 0 0 0 0 0 1537 +853 857 0.998564381247103 0.0472594033250601 -0.0252135935945041 0.221442043454849 -0.0484445293864745 0.997639407032026 -0.0486697144979443 -0.0791275834078721 0.0228539728955937 0.0498213040189405 0.99849663674383 0.305362562786913 3.66685029639739e-05 -3.29489208261443e-05 -7.68244714737951e-07 9.27144979320943e-09 1.23177092882987e-06 2.2783477247961e-05 -3.29489208261443e-05 7.72229012960716e-05 -1.72250005749117e-06 1.47641960438647e-05 -1.09834137283468e-06 -6.40048529601575e-06 -7.68244714737951e-07 -1.72250005749117e-06 1.27675863957469e-05 -5.28556260775252e-07 5.29673098650777e-06 -1.27437660852892e-06 9.27144979320943e-09 1.47641960438647e-05 -5.28556260775252e-07 6.18823376266506e-05 1.18272507191203e-05 -8.56868597307849e-07 1.23177092882987e-06 -1.09834137283468e-06 5.29673098650777e-06 1.18272507191203e-05 2.85975971879852e-05 4.08808099032213e-06 2.2783477247961e-05 -6.40048529601575e-06 -1.27437660852892e-06 -8.56868597307849e-07 4.08808099032213e-06 0.00010897581307777 1222 1232 0 151 0 1222 1232 0 171 0 0 0 0 0 0 0 0 0 2514 0 0 0 0 0 1166 +853 856 0.999051839017957 0.0292080197281564 0.0322848964439821 0.18008138301106 -0.0267443181742154 0.996879234322455 -0.0742733708813086 -0.0625441496053468 -0.0343535209292346 0.0733395102263146 0.99671518090151 0.236399971523075 2.45630691458257e-05 -1.2931385274891e-05 1.74931739206629e-07 5.83131053585834e-06 1.77140244863521e-06 1.34578192849481e-05 -1.2931385274891e-05 5.0631756014421e-05 2.5639477508174e-06 2.34491092569818e-06 1.45258723679851e-06 -2.32385477013329e-06 1.74931739206629e-07 2.5639477508174e-06 1.15778962408373e-05 1.62456697825088e-06 5.32745233237558e-06 -1.54018275965199e-06 5.83131053585834e-06 2.34491092569818e-06 1.62456697825088e-06 4.25503722390717e-05 8.52346674227363e-06 5.83845272979338e-06 1.77140244863521e-06 1.45258723679851e-06 5.32745233237558e-06 8.52346674227363e-06 2.13325883586156e-05 4.92266564774913e-06 1.34578192849481e-05 -2.32385477013329e-06 -1.54018275965199e-06 5.83845272979338e-06 4.92266564774913e-06 6.96796387586652e-05 1545 1565 0 115 0 1545 1565 0 133 0 0 0 0 0 0 0 0 0 2760 0 0 0 0 0 2183 +853 897 0.996823645806084 0.0788878852025565 0.0109234028642894 0.308326572451515 -0.0793038868566993 0.995827023698123 0.0451600753094844 -0.106234057856935 -0.00731523692624747 -0.0458828992197173 0.998920040277452 0.499126991326736 3.98101093673953e-05 -3.50485238860255e-05 -1.88891725526015e-06 -1.90393074137208e-06 -4.69747997173308e-06 1.23408313518001e-05 -3.50485238860255e-05 6.29502562619497e-05 2.10793167596264e-06 7.43697621367107e-06 4.44199173617523e-06 3.64716937699991e-05 -1.88891725526015e-06 2.10793167596264e-06 1.14622277516694e-05 -6.68361754195976e-06 5.92444204820774e-06 -6.62928462556726e-06 -1.90393074137208e-06 7.43697621367107e-06 -6.68361754195976e-06 3.49076127172153e-05 2.80060156280255e-06 3.0676513612124e-05 -4.69747997173308e-06 4.44199173617523e-06 5.92444204820774e-06 2.80060156280255e-06 1.9703343867031e-05 1.86326903727506e-05 1.23408313518001e-05 3.64716937699991e-05 -6.62928462556726e-06 3.0676513612124e-05 1.86326903727506e-05 0.000308677105520182 759 780 0 201 0 759 780 0 227 0 0 0 0 0 0 0 0 0 2294 0 0 0 0 0 1531 +853 929 0.998289435352121 0.0577750136025298 0.00895829601942152 0.303816714368437 -0.0582465052423508 0.996054250487069 0.0669572603508799 -0.104119832870136 -0.00505449219970598 -0.0673645150644626 0.997715627931493 0.475175274453127 3.75936791059065e-05 -3.68188489322731e-05 -7.34655437320772e-06 -2.61815767892719e-07 -2.36453773923158e-06 3.41934943413117e-05 -3.68188489322731e-05 8.005773946464e-05 7.88031882737168e-06 6.91155466102464e-06 4.76068437748785e-07 -6.53052200049985e-06 -7.34655437320772e-06 7.88031882737168e-06 1.23736145913439e-05 -6.34519166975138e-06 5.15366450292494e-06 -4.6547705256306e-06 -2.61815767892719e-07 6.91155466102464e-06 -6.34519166975138e-06 3.80737403382286e-05 2.23144530681473e-06 -1.23087937582829e-05 -2.36453773923158e-06 4.76068437748785e-07 5.15366450292494e-06 2.23144530681473e-06 2.31868372380405e-05 -1.40998466625762e-05 3.41934943413117e-05 -6.53052200049985e-06 -4.6547705256306e-06 -1.23087937582829e-05 -1.40998466625762e-05 0.000180327861710713 748 774 0 183 0 748 774 0 208 0 0 0 0 0 0 0 0 0 2495 0 0 0 0 0 1648 +853 895 0.996844687537141 0.0790480415611361 0.00721637404306282 0.306129536609903 -0.0792841066695181 0.995949109460186 0.0424193563727572 -0.106084571343121 -0.00383397425616966 -0.0428576538183251 0.999073832181882 0.503147519278171 5.3117716479939e-05 -5.09843635057585e-05 -4.52330031330567e-06 3.19725774495764e-06 -2.66026127073553e-06 2.49738293579462e-05 -5.09843635057585e-05 8.95709958589105e-05 4.09211363938511e-06 1.10091965405428e-05 4.76196309912303e-06 4.44108867546592e-06 -4.52330031330567e-06 4.09211363938511e-06 1.13798803380187e-05 -5.96275561762629e-06 5.87465092577572e-06 -6.14068278977543e-06 3.19725774495764e-06 1.10091965405428e-05 -5.96275561762629e-06 4.39243188668481e-05 2.99321532486459e-06 3.7720793166161e-05 -2.66026127073553e-06 4.76196309912303e-06 5.87465092577572e-06 2.99321532486459e-06 2.40146710308575e-05 2.22686546549954e-05 2.49738293579462e-05 4.44108867546592e-06 -6.14068278977543e-06 3.7720793166161e-05 2.22686546549954e-05 0.000156811365514587 720 743 0 211 0 720 743 0 237 0 0 0 0 0 0 0 0 0 2328 0 0 0 0 0 1597 +853 855 0.999764026377417 0.0173351560571981 0.013091368381037 0.12815679941956 -0.0163270353038753 0.997158722487198 -0.073538493905475 -0.0447263538050411 -0.0143289734385069 0.0733073975269356 0.997206451036106 0.16716293127879 2.57679331510157e-05 -1.66868011375827e-05 1.40743257054094e-06 7.21098292772939e-06 3.75437535010389e-06 2.33863011975968e-05 -1.66868011375827e-05 7.42457067795748e-05 -3.32418621172208e-06 1.18990071052649e-05 8.12923402546587e-06 6.31555134503171e-06 1.40743257054094e-06 -3.32418621172208e-06 1.1107405599449e-05 1.92862348718085e-06 2.95394745337775e-06 -2.40962769362794e-06 7.21098292772939e-06 1.18990071052649e-05 1.92862348718085e-06 5.26997929109504e-05 1.09906460962034e-05 2.12481343118916e-06 3.75437535010389e-06 8.12923402546587e-06 2.95394745337775e-06 1.09906460962034e-05 2.33701295061928e-05 1.98273763183334e-05 2.33863011975968e-05 6.31555134503171e-06 -2.40962769362794e-06 2.12481343118916e-06 1.98273763183334e-05 0.000178328622919136 1727 1751 0 80 0 1727 1751 0 103 0 0 0 0 0 0 0 0 0 3116 0 0 0 0 0 2741 +853 900 0.996857996981726 0.0786460290618198 0.00943058674680518 0.307110199266931 -0.0789812510183333 0.995946843536745 0.0430330900212103 -0.108650022510478 -0.00600798145475207 -0.0436427194615776 0.999029137311239 0.49622112300105 3.63307338931035e-05 -2.67062556550752e-05 -2.75328673406108e-06 5.12301227293761e-06 -2.01308040074704e-06 3.42034672484672e-05 -2.67062556550752e-05 4.34484587518435e-05 2.31873341655932e-06 4.68476823944422e-07 1.75035469782009e-06 -5.12937449186788e-06 -2.75328673406108e-06 2.31873341655932e-06 1.16119194085266e-05 -7.59093364318881e-06 5.38385548140236e-06 -3.57900485488321e-06 5.12301227293761e-06 4.68476823944422e-07 -7.59093364318881e-06 3.7643257405633e-05 1.5278722521534e-06 2.15559451572828e-05 -2.01308040074704e-06 1.75035469782009e-06 5.38385548140236e-06 1.5278722521534e-06 2.12527979693105e-05 1.53296368451151e-05 3.42034672484672e-05 -5.12937449186788e-06 -3.57900485488321e-06 2.15559451572828e-05 1.53296368451151e-05 0.000167784916426729 752 774 0 207 0 752 774 0 231 0 0 0 0 0 0 0 0 0 2288 0 0 0 0 0 1532 +853 934 0.94230535335322 -0.309236008765339 -0.128194040129585 0.357384637356185 0.312254973431104 0.949991317481322 0.00365079137200013 0.0206370881795961 0.120654268923246 -0.0434693868485009 0.99174238580269 0.108180838000675 2.98876455026516e-05 -2.36501050320433e-05 -3.57907667238057e-06 5.8570511878073e-06 1.2427178830198e-06 2.88106449007667e-05 -2.36501050320433e-05 4.24170287571761e-05 3.99302546322323e-06 5.12398648555072e-06 -7.98858666116445e-07 -2.16574022964059e-05 -3.57907667238057e-06 3.99302546322323e-06 9.86757205649656e-06 -3.19413426393369e-08 3.38380485717222e-06 -3.76434483936764e-06 5.8570511878073e-06 5.12398648555072e-06 -3.19413426393369e-08 5.17980382929331e-05 4.05628793994103e-06 4.34835471142706e-07 1.2427178830198e-06 -7.98858666116445e-07 3.38380485717222e-06 4.05628793994103e-06 1.36748196235693e-05 5.91488880089496e-07 2.88106449007667e-05 -2.16574022964059e-05 -3.76434483936764e-06 4.34835471142706e-07 5.91488880089496e-07 7.49958566089102e-05 1541 1541 0 0 0 1562 1562 0 0 0 0 0 0 0 0 483 485 0 3326 0 0 0 0 0 745 +853 930 0.998285144482367 -0.00402074739547771 0.0584003758224359 0.300068808013257 0.000513972147711231 0.998201943443862 0.0599384345602123 -0.0987115582069112 -0.0585363659484544 -0.0598056326383998 0.996492237885609 0.458238105234177 4.063036943749e-05 -3.88795657104052e-05 -4.19668695898031e-06 3.10828469883824e-06 -2.96146409990681e-06 3.84054638539741e-05 -3.88795657104052e-05 0.000112981578871622 4.11466341465969e-06 1.06123724760195e-06 -1.92424557599752e-06 1.1683824329346e-05 -4.19668695898031e-06 4.11466341465969e-06 1.19013247113993e-05 -8.84309490353035e-06 6.66435218315929e-06 -2.42191531659987e-06 3.10828469883824e-06 1.06123724760195e-06 -8.84309490353035e-06 4.47866112858546e-05 -1.13404040423103e-06 -6.30433029680285e-06 -2.96146409990681e-06 -1.92424557599752e-06 6.66435218315929e-06 -1.13404040423103e-06 1.86960717985557e-05 -1.52919013976672e-06 3.84054638539741e-05 1.1683824329346e-05 -2.42191531659987e-06 -6.30433029680285e-06 -1.52919013976672e-06 0.000182427619861276 940 962 0 115 0 940 962 0 139 0 0 0 0 0 0 0 0 0 2578 0 0 0 0 0 1149 +853 933 0.967772200464821 -0.241027836802982 -0.072955807812354 0.329866414494384 0.242209804402897 0.970193503303451 0.00767963533553884 -0.0213794395023009 0.0689302448754403 -0.0251027495277274 0.997305606776358 0.233911776906524 1.61225952436385e-05 -1.17517645963201e-05 -1.79966340880129e-06 3.35141611802877e-06 -5.37190457892747e-07 1.60281242323605e-05 -1.17517645963201e-05 4.97534126639814e-05 2.79897499539289e-06 3.05176846028958e-06 -4.1636362637022e-07 -2.97883945999127e-05 -1.79966340880129e-06 2.79897499539289e-06 1.02074106626109e-05 -2.44182943506687e-06 5.46961101353099e-06 -9.51318544258732e-07 3.35141611802877e-06 3.05176846028958e-06 -2.44182943506687e-06 4.64402769974052e-05 4.85157739748526e-06 1.40767141020144e-06 -5.37190457892747e-07 -4.1636362637022e-07 5.46961101353099e-06 4.85157739748526e-06 1.70281050280996e-05 3.20907059421961e-06 1.60281242323605e-05 -2.97883945999127e-05 -9.51318544258732e-07 1.40767141020144e-06 3.20907059421961e-06 0.000103073445909989 1384 1384 0 0 0 1408 1408 0 0 0 0 0 0 0 0 330 335 0 3240 0 0 0 0 0 1001 +853 932 0.987858114252961 -0.15187993287291 -0.0326929976463424 0.315043990798766 0.153092508689252 0.987462494564884 0.0384773389273116 -0.059498337364468 0.0264391733572528 -0.0430152045004564 0.998724517719461 0.302320145941475 3.78350567293891e-05 -3.59657292985825e-05 -7.30404431069612e-07 -9.9165329786543e-06 -2.76186423406594e-06 5.23868835301265e-05 -3.59657292985825e-05 9.58361975823001e-05 -1.12767547720464e-06 3.82644099312224e-05 7.92931128824985e-06 -2.05186359323911e-05 -7.30404431069612e-07 -1.12767547720464e-06 1.10512605677319e-05 -5.15800484413216e-06 4.50435725774246e-06 -1.26417759357154e-06 -9.9165329786543e-06 3.82644099312224e-05 -5.15800484413216e-06 7.34924414044964e-05 8.04732772053284e-06 -3.61841570058932e-06 -2.76186423406594e-06 7.92931128824985e-06 4.50435725774246e-06 8.04732772053284e-06 1.8184446875836e-05 3.28536652425911e-06 5.23868835301265e-05 -2.05186359323911e-05 -1.26417759357154e-06 -3.61841570058932e-06 3.28536652425911e-06 0.000186890104042636 1162 1162 0 0 0 1186 1186 0 0 0 0 0 0 0 0 158 173 0 3160 0 0 0 0 0 1527 +853 931 0.996530641602193 -0.0753587428511822 0.0353233665412952 0.307699768438462 0.0738198208855626 0.996343437022558 0.0430161544829263 -0.0840374804832271 -0.0384358477510873 -0.0402593514349762 0.99844973345166 0.390513089239058 4.08323783223838e-05 -3.76868205074216e-05 -4.63159963815797e-06 4.31006357761018e-06 -1.66070929823243e-06 3.01885644397951e-05 -3.76868205074216e-05 9.26533672774864e-05 3.39722089190648e-06 1.09529790824265e-05 6.25881946866217e-07 6.75284816028973e-06 -4.63159963815797e-06 3.39722089190648e-06 1.07383883619911e-05 -5.00440870934065e-06 6.14067074120792e-06 -6.00432979649637e-06 4.31006357761018e-06 1.09529790824265e-05 -5.00440870934065e-06 4.22159311184271e-05 -1.46718591046605e-06 1.66181177243428e-05 -1.66070929823243e-06 6.25881946866217e-07 6.14067074120792e-06 -1.46718591046605e-06 1.92375161512147e-05 9.56256006101901e-06 3.01885644397951e-05 6.75284816028973e-06 -6.00432979649637e-06 1.66181177243428e-05 9.56256006101901e-06 0.000143941348533403 1120 1120 0 5 0 1139 1146 0 21 0 0 0 0 0 0 34 52 0 2875 0 0 0 0 0 1316 +853 898 0.996820768987516 0.0793941459946183 0.00670254406341484 0.307867982679641 -0.0796081677294526 0.995919651009569 0.0425039805634486 -0.10639542842697 -0.00330062810630551 -0.0429024278423017 0.999073814860214 0.485220878329141 5.38168974594209e-05 -3.83608894558549e-05 -4.52668285711952e-06 2.70890711702374e-06 -1.82870141082464e-06 1.33373799765318e-05 -3.83608894558549e-05 6.33699553552096e-05 5.96347916730354e-06 2.19714884250569e-06 -5.89482260449769e-07 3.70967294983778e-05 -4.52668285711952e-06 5.96347916730354e-06 1.21745356016249e-05 -7.73590885007628e-06 4.36477149607986e-06 -4.8160162952759e-06 2.70890711702374e-06 2.19714884250569e-06 -7.73590885007628e-06 4.66581463131579e-05 8.03167077177108e-06 2.9019858330091e-05 -1.82870141082464e-06 -5.89482260449769e-07 4.36477149607986e-06 8.03167077177108e-06 2.50563626756415e-05 1.80044166849721e-05 1.33373799765318e-05 3.70967294983778e-05 -4.8160162952759e-06 2.9019858330091e-05 1.80044166849721e-05 0.000250948877139123 725 744 0 204 0 725 744 0 231 0 0 0 0 0 0 0 0 0 2387 0 0 0 0 0 1698 +853 936 0.905391313291577 -0.402244491854963 -0.135889435161444 0.385659072616464 0.403902110683172 0.91465557465586 -0.0163787892298915 0.107436653112715 0.130880307158228 -0.0400568161902738 0.990588611218031 -0.149443175908718 2.55558653622469e-05 -1.88181777044847e-05 -3.50614096346805e-07 7.98651883873056e-06 7.23786583734392e-07 2.49189183201067e-05 -1.88181777044847e-05 6.98536184420882e-05 2.80682115744116e-06 1.5989825601326e-06 -2.54483112431749e-07 -1.30041350135662e-06 -3.50614096346805e-07 2.80682115744116e-06 9.30355112515373e-06 1.20680289472409e-06 5.34613873143873e-06 -1.25626303840295e-06 7.98651883873056e-06 1.5989825601326e-06 1.20680289472409e-06 5.83902075302175e-05 3.41286899521724e-06 3.14536173439181e-05 7.23786583734392e-07 -2.54483112431749e-07 5.34613873143873e-06 3.41286899521724e-06 1.39176130852617e-05 2.48870320127183e-07 2.49189183201067e-05 -1.30041350135662e-06 -1.25626303840295e-06 3.14536173439181e-05 2.48870320127183e-07 0.00012644302599048 1970 1970 0 0 0 1992 1992 0 0 0 0 0 0 0 0 919 909 0 3184 0 0 0 0 0 916 +853 896 0.996897957525827 0.0785017265193785 0.00565165589115765 0.303414765482193 -0.0786674410096019 0.996066499588521 0.0407794325913303 -0.108630435314655 -0.0024281692354842 -0.0410975343657835 0.999152188939812 0.496783773322409 3.70863534322332e-05 -2.75771717700294e-05 -4.86938303843247e-06 3.27689065799149e-06 -4.22205472370342e-06 1.77661063102358e-05 -2.75771717700294e-05 7.30953477699678e-05 5.7071376904557e-06 6.03760615657227e-06 6.87851962499822e-06 5.22415289421372e-05 -4.86938303843247e-06 5.7071376904557e-06 1.13699302450651e-05 -7.17114071602106e-06 5.45450203175242e-06 -5.93285228649246e-06 3.27689065799149e-06 6.03760615657227e-06 -7.17114071602106e-06 4.07275554620895e-05 3.15704958930503e-06 3.24947943134168e-05 -4.22205472370342e-06 6.87851962499822e-06 5.45450203175242e-06 3.15704958930503e-06 2.07499070322646e-05 2.29322180529652e-05 1.77661063102358e-05 5.22415289421372e-05 -5.93285228649246e-06 3.24947943134168e-05 2.29322180529652e-05 0.00031218160447025 692 716 0 206 0 692 716 0 231 0 0 0 0 0 0 0 0 0 2293 0 0 0 0 0 1711 +853 894 0.996817256117096 0.0791139904844524 0.0098150097712781 0.309526067301915 -0.0794762843181361 0.995832631043036 0.0447313221455361 -0.105418706758491 -0.00623523360966606 -0.0453690143107706 0.998950836829472 0.505369774413854 4.14605904802654e-05 -3.03268055641898e-05 -3.16212751048399e-06 3.13626589853346e-06 8.39079505557631e-07 3.72736073291925e-05 -3.03268055641898e-05 5.58512904249758e-05 3.93365868974481e-06 -9.8133081387428e-07 -2.8560022708722e-06 -9.97470215131044e-06 -3.16212751048399e-06 3.93365868974481e-06 1.18594013393048e-05 -7.45673565425642e-06 5.48070705570691e-06 -3.96055156733022e-06 3.13626589853346e-06 -9.8133081387428e-07 -7.45673565425642e-06 3.18948263795468e-05 -1.33249945463172e-06 9.36561469750447e-06 8.39079505557631e-07 -2.8560022708722e-06 5.48070705570691e-06 -1.33249945463172e-06 1.99219665681301e-05 5.24955904255268e-06 3.72736073291925e-05 -9.97470215131044e-06 -3.96055156733022e-06 9.36561469750447e-06 5.24955904255268e-06 0.000105329292344124 702 724 0 213 0 702 724 0 236 0 0 0 0 0 0 0 0 0 2295 0 0 0 0 0 1599 +853 891 0.996869094033056 0.0788771734329834 0.0055136986620839 0.308981205073915 -0.0790327173327643 0.996109021584084 0.0389954703753927 -0.104382578933093 -0.00241639249969726 -0.0393091418123291 0.999224175256617 0.508428505955857 3.69130847525301e-05 -3.42696839555468e-05 -3.77458427838569e-06 4.48950955671646e-06 -6.32078170440707e-06 2.3153762592808e-05 -3.42696839555468e-05 7.33863426933749e-05 3.7850141975762e-06 5.97853854193847e-06 4.50554659155153e-06 -6.524625359577e-06 -3.77458427838569e-06 3.7850141975762e-06 1.00128013238707e-05 -5.62855263649177e-06 5.67587396837964e-06 -4.3925407626156e-06 4.48950955671646e-06 5.97853854193847e-06 -5.62855263649177e-06 3.82233458657146e-05 3.94538700623238e-07 1.66332681970391e-05 -6.32078170440707e-06 4.50554659155153e-06 5.67587396837964e-06 3.94538700623238e-07 2.0585351436445e-05 6.31500451396879e-06 2.3153762592808e-05 -6.524625359577e-06 -4.3925407626156e-06 1.66332681970391e-05 6.31500451396879e-06 0.000113827546817247 676 699 0 201 0 676 699 0 227 0 0 0 0 0 0 0 0 0 2249 0 0 0 0 0 1827 +853 892 0.996813867910366 0.0789847164085527 0.0111142842970666 0.310181957227468 -0.0793957197518834 0.99589980493972 0.043357792910943 -0.104305954122707 -0.00764411058632164 -0.0441020758569064 0.998997785021797 0.507951229664296 3.98523478433092e-05 -3.26004804423137e-05 -2.25220622981774e-06 -5.90191386378314e-07 -1.03879390378794e-08 3.19261210072186e-05 -3.26004804423137e-05 5.20314672818654e-05 1.07095118510387e-06 8.03359320586855e-06 3.23002038840791e-07 -1.00314135996891e-05 -2.25220622981774e-06 1.07095118510387e-06 1.0580548329139e-05 -6.41963423244611e-06 6.03079554982787e-06 -5.84141284914527e-06 -5.90191386378314e-07 8.03359320586855e-06 -6.41963423244611e-06 3.61002913579048e-05 7.1329598887278e-07 1.44777221064875e-05 -1.03879390378794e-08 3.23002038840791e-07 6.03079554982787e-06 7.1329598887278e-07 1.8965770353401e-05 1.06558788471638e-05 3.19261210072186e-05 -1.00314135996891e-05 -5.84141284914527e-06 1.44777221064875e-05 1.06558788471638e-05 0.000123606802064328 725 746 0 205 0 725 746 0 229 0 0 0 0 0 0 0 0 0 2343 0 0 0 0 0 1622 +853 901 0.996837074672391 0.0793675402873668 0.00407922876578258 0.304652190356719 -0.0794695613077306 0.995914901331803 0.0428730466706356 -0.105862452343976 -0.000659836454910379 -0.0430616169459399 0.999072200474947 0.504423172323198 4.50955189356529e-05 -2.67418248653057e-05 -4.96151410332899e-06 -1.46468437344328e-06 -5.70800711782974e-07 2.25481764166655e-05 -2.67418248653057e-05 5.83281244139579e-05 4.28891148839667e-06 9.41001033345767e-06 4.77233550141208e-06 3.15893660659439e-06 -4.96151410332899e-06 4.28891148839667e-06 1.23894613635537e-05 -7.14895327705378e-06 4.50690776064707e-06 -7.66658193323487e-06 -1.46468437344328e-06 9.41001033345767e-06 -7.14895327705378e-06 4.54845730317681e-05 6.12105401001812e-06 2.27017975730272e-05 -5.70800711782974e-07 4.77233550141208e-06 4.50690776064707e-06 6.12105401001812e-06 2.39752285105754e-05 1.18853366708843e-05 2.25481764166655e-05 3.15893660659439e-06 -7.66658193323487e-06 2.27017975730272e-05 1.18853366708843e-05 0.000110219438961884 688 711 0 212 0 688 711 0 237 0 0 0 0 0 0 0 0 0 2305 0 0 0 0 0 1502 +853 893 0.996874388104707 0.078622967087215 0.00773843571203555 0.306617227937224 -0.0788865922216977 0.995932940692587 0.0435256615235608 -0.104868940306175 -0.00428484638163192 -0.0440000760206014 0.999022338790113 0.508960469152149 3.89022923538829e-05 -2.93227124269137e-05 -3.06145477931806e-06 -2.27761616846865e-06 -1.90277460382408e-06 3.80700139946795e-05 -2.93227124269137e-05 6.43264433225546e-05 3.12827141187752e-06 1.00519498377025e-05 2.72952929290587e-06 -5.39872571902447e-06 -3.06145477931806e-06 3.12827141187752e-06 1.28646645540652e-05 -8.06974722126189e-06 6.39638950142448e-06 -3.79167743170119e-06 -2.27761616846865e-06 1.00519498377025e-05 -8.06974722126189e-06 3.57701803309487e-05 8.71922772610953e-07 1.4127577837037e-05 -1.90277460382408e-06 2.72952929290587e-06 6.39638950142448e-06 8.71922772610953e-07 2.48683518934091e-05 1.34972247026261e-05 3.80700139946795e-05 -5.39872571902447e-06 -3.79167743170119e-06 1.4127577837037e-05 1.34972247026261e-05 0.000160286986492949 715 740 0 208 0 715 740 0 232 0 0 0 0 0 0 0 0 0 2303 0 0 0 0 0 907 +854 934 0.939447063467216 -0.321405089823377 -0.118903251336754 0.289588740590095 0.326869630822866 0.944618336465776 0.0291966240917214 0.0474518083330232 0.102934247889358 -0.0662945446342072 0.992476485345217 0.0267669025168534 2.87980729422527e-05 -2.48981723634671e-05 -1.32852374027071e-06 1.05521174692444e-05 6.81614562453624e-07 2.33901003638136e-05 -2.48981723634671e-05 0.00010468981676206 4.05853053175219e-06 1.65575064737405e-05 -6.30235615920936e-07 3.05551161794224e-06 -1.32852374027071e-06 4.05853053175219e-06 1.06875550527726e-05 2.92482029512536e-06 3.67985552206997e-06 -2.48961801535597e-06 1.05521174692444e-05 1.65575064737405e-05 2.92482029512536e-06 6.60575473680947e-05 8.13555649470502e-06 2.10988861896676e-05 6.81614562453624e-07 -6.30235615920936e-07 3.67985552206997e-06 8.13555649470502e-06 1.57808264377129e-05 5.42591393522399e-07 2.33901003638136e-05 3.05551161794224e-06 -2.48961801535597e-06 2.10988861896676e-05 5.42591393522399e-07 9.69433890478175e-05 1492 1492 0 0 0 1511 1511 0 0 0 0 0 0 0 0 639 636 0 3306 0 0 0 0 0 735 +854 935 0.914104776580231 -0.365625841398622 -0.175300318125083 0.295680401674444 0.372887409564764 0.927830615415491 0.00923736357360537 0.0828441393863727 0.159271583219623 -0.0738111996871823 0.984471670277745 -0.111058407459267 2.86396493857184e-05 -2.12063528667817e-05 6.37290721847828e-07 4.18746944036005e-06 1.6364273314815e-06 2.56774666798837e-05 -2.12063528667817e-05 4.69407741211681e-05 -6.84721029345578e-07 1.6359218128857e-05 7.27594062556272e-08 -2.06147444457194e-06 6.37290721847828e-07 -6.84721029345578e-07 1.10444299360912e-05 3.54329374794642e-06 3.25725008521592e-06 1.50133804345071e-06 4.18746944036005e-06 1.6359218128857e-05 3.54329374794642e-06 7.15498431667565e-05 3.1548908397466e-06 1.41884831252064e-05 1.6364273314815e-06 7.27594062556272e-08 3.25725008521592e-06 3.1548908397466e-06 1.55625243236997e-05 -1.68373284513561e-06 2.56774666798837e-05 -2.06147444457194e-06 1.50133804345071e-06 1.41884831252064e-05 -1.68373284513561e-06 8.41255025425472e-05 1625 1625 0 0 0 1644 1644 0 0 0 0 0 0 0 0 865 854 0 3075 0 0 0 0 0 827 +853 923 0.996782854571607 0.0784878335799318 0.0162357880008005 0.312654741108651 -0.0791381469573225 0.995879084276154 0.0442945052737967 -0.104150372449601 -0.0126923019283038 -0.0454368735854275 0.998886578141153 0.527003583295998 6.03507155572375e-05 -6.49249461011654e-05 -1.31751618118529e-06 -1.11051574170683e-05 -9.46217302828499e-06 -0.000155346463501478 -6.49249461011654e-05 0.000306112884322655 -1.1400948654502e-07 6.46340773175961e-05 4.59789503072515e-05 0.000918410188972901 -1.31751618118529e-06 -1.1400948654502e-07 1.44617692325956e-05 -1.04872154871749e-05 3.20728030086887e-06 -6.25942830613627e-06 -1.11051574170683e-05 6.46340773175961e-05 -1.04872154871749e-05 6.63155820427232e-05 1.72892263789282e-05 0.000234080744129754 -9.46217302828499e-06 4.59789503072515e-05 3.20728030086887e-06 1.72892263789282e-05 3.47858677415046e-05 0.000152368083776905 -0.000155346463501478 0.000918410188972901 -6.25942830613627e-06 0.000234080744129754 0.000152368083776905 0.00369862812933401 716 740 0 214 0 716 740 0 241 0 0 0 0 0 0 0 0 0 2288 0 0 0 0 0 1555 +854 932 0.985500534836624 -0.161463198591338 -0.0521376192147437 0.235612561074963 0.16449566664944 0.984531719237995 0.0603197270205512 -0.0340376135294437 0.041591723819573 -0.0680215356701963 0.996816532364298 0.218636221264961 3.0864420208434e-05 -1.63601854919957e-05 -9.59890854974255e-07 6.12343422416127e-06 -2.00669916374036e-06 -3.49993596899997e-06 -1.63601854919957e-05 6.5405379097446e-05 -5.54050328469649e-07 2.95293875254058e-06 3.40146610045523e-06 4.67770075443404e-05 -9.59890854974255e-07 -5.54050328469649e-07 1.08566539995248e-05 -4.37907088290469e-06 4.02028543800396e-06 -2.19248964832393e-06 6.12343422416127e-06 2.95293875254058e-06 -4.37907088290469e-06 6.37757773832185e-05 4.1663464177638e-06 8.27633743674922e-06 -2.00669916374036e-06 3.40146610045523e-06 4.02028543800396e-06 4.1663464177638e-06 1.81750627322172e-05 6.56064584709821e-06 -3.49993596899997e-06 4.67770075443404e-05 -2.19248964832393e-06 8.27633743674922e-06 6.56064584709821e-06 0.000139382153283605 1314 1314 0 0 0 1338 1338 0 0 0 0 0 0 0 0 244 254 0 3139 0 0 0 0 0 999 +853 902 0.996831633407938 0.0792998284908126 0.00618319000119155 0.30612320671448 -0.0794921778013406 0.99592102445372 0.0426884846235171 -0.106352423410907 -0.00277277941120109 -0.0430447470939244 0.999069297617516 0.505224564794919 4.05129724966948e-05 -3.62809353138351e-05 -4.74076709812999e-06 -4.81591691715275e-06 -2.63895063728163e-06 2.189202716184e-05 -3.62809353138351e-05 8.68235930978745e-05 1.91917031933552e-06 2.80158602789701e-05 1.48444179283019e-05 2.9039386406971e-05 -4.74076709812999e-06 1.91917031933552e-06 1.25709585508506e-05 -8.25074564787013e-06 4.51057565941988e-06 -7.17414916030527e-06 -4.81591691715275e-06 2.80158602789701e-05 -8.25074564787013e-06 5.10400639287288e-05 9.63404515219164e-06 3.48795709998986e-05 -2.63895063728163e-06 1.48444179283019e-05 4.51057565941988e-06 9.63404515219164e-06 2.78398529915858e-05 2.11963916636486e-05 2.189202716184e-05 2.9039386406971e-05 -7.17414916030527e-06 3.48795709998986e-05 2.11963916636486e-05 0.000173461039280401 718 740 0 205 0 718 740 0 232 0 0 0 0 0 0 0 0 0 2361 0 0 0 0 0 1513 +854 930 0.998965555167151 -0.0137694857720652 0.0433384454169552 0.222255651341718 0.00989762775058619 0.996043060023082 0.088319078033945 -0.0628154903928784 -0.0443830660781376 -0.0877987690200047 0.995148993670835 0.380219388919984 3.09055034238322e-05 -2.80355087960567e-05 -3.59322291243544e-06 3.09044087684737e-06 1.3825956113013e-06 1.93111497274499e-05 -2.80355087960567e-05 9.5508803359609e-05 3.87215094495299e-06 1.43188935933046e-05 7.07272424380792e-06 4.29154632966773e-05 -3.59322291243544e-06 3.87215094495299e-06 1.1849049501149e-05 -5.83031921898805e-06 3.55119206456724e-06 -2.62654618607797e-06 3.09044087684737e-06 1.43188935933046e-05 -5.83031921898805e-06 4.10204918127859e-05 6.30905783979211e-06 2.72446043706019e-05 1.3825956113013e-06 7.07272424380792e-06 3.55119206456724e-06 6.30905783979211e-06 2.02436951117472e-05 9.57234340898699e-06 1.93111497274499e-05 4.29154632966773e-05 -2.62654618607797e-06 2.72446043706019e-05 9.57234340898699e-06 0.00012308597707793 996 1015 0 73 0 996 1015 0 101 0 0 0 0 0 0 0 0 0 2706 0 0 0 0 0 1002 +853 925 0.996823921596463 0.0787671758484896 0.0117388816291187 0.310856999743054 -0.0792076331311485 0.995905862740987 0.0435621786862424 -0.104333366507144 -0.00825955124753923 -0.0443536308207553 0.998981749205763 0.508374211472498 4.21817167188214e-05 -3.2988200816864e-05 3.56509753197579e-07 -6.20074515268631e-06 -7.98834812194417e-06 1.96020863128151e-05 -3.2988200816864e-05 4.9926480214702e-05 1.53107407066373e-06 1.05353028016878e-05 5.11624678166143e-06 -2.32503126363811e-06 3.56509753197579e-07 1.53107407066373e-06 1.25965140676506e-05 -7.85989441331064e-06 4.26263835320013e-06 -2.40795306457011e-06 -6.20074515268631e-06 1.05353028016878e-05 -7.85989441331064e-06 4.83478412069323e-05 8.50944192051898e-06 2.17658855099231e-05 -7.98834812194417e-06 5.11624678166143e-06 4.26263835320013e-06 8.50944192051898e-06 2.55745952620792e-05 1.04595082183261e-05 1.96020863128151e-05 -2.32503126363811e-06 -2.40795306457011e-06 2.17658855099231e-05 1.04595082183261e-05 0.000150053810174656 718 743 0 216 0 718 743 0 241 0 0 0 0 0 0 0 0 0 2287 0 0 0 0 0 1428 +853 903 0.99677835536243 0.079618282030616 0.00968707631139593 0.310022439661492 -0.0799632789614142 0.995872184730109 0.042947243201614 -0.104230122062381 -0.00622770412821359 -0.0435834928312638 0.999030377342911 0.508976047709908 3.72494710110743e-05 -2.67660176707242e-05 -1.73981027135515e-06 -5.26940902987358e-07 -2.90483832273752e-06 3.61492883863081e-05 -2.67660176707242e-05 4.86893829608096e-05 3.90771929680403e-06 -3.50206871462671e-06 -2.59329242117406e-06 -1.27671817975132e-05 -1.73981027135515e-06 3.90771929680403e-06 1.50745005755053e-05 -8.38314176827308e-06 2.79618207060901e-06 3.06215953816192e-06 -5.26940902987358e-07 -3.50206871462671e-06 -8.38314176827308e-06 3.98687592468537e-05 6.06067171886431e-06 -5.55879133954748e-06 -2.90483832273752e-06 -2.59329242117406e-06 2.79618207060901e-06 6.06067171886431e-06 2.96865647632941e-05 -6.57156293600711e-06 3.61492883863081e-05 -1.27671817975132e-05 3.06215953816192e-06 -5.55879133954748e-06 -6.57156293600711e-06 0.000120737037056275 691 716 0 212 0 691 716 0 237 0 0 0 0 0 0 0 0 0 2246 0 0 0 0 0 891 +853 890 0.996857571422764 0.0787729382452464 -0.00835502826564221 0.315274941332057 -0.078580197228688 0.996679788895907 0.0213202019200028 -0.095500551051844 0.0100067427572402 -0.0205966649392515 0.999737786868522 0.495944836486406 4.14576023468563e-05 -5.28861364621426e-05 -2.75993114734531e-07 -5.42121356735831e-06 -1.27132733976737e-05 1.7812239960596e-05 -5.28861364621426e-05 0.000142050572450755 -9.01378240791427e-07 3.89245645808832e-05 2.97552892366364e-05 5.14030038935454e-05 -2.75993114734531e-07 -9.01378240791427e-07 1.05119388322629e-05 -6.9432333857999e-06 4.40072747100761e-06 -1.08999436952814e-06 -5.42121356735831e-06 3.89245645808832e-05 -6.9432333857999e-06 5.70656705804554e-05 1.20584334604489e-05 3.12447474872382e-05 -1.27132733976737e-05 2.97552892366364e-05 4.40072747100761e-06 1.20584334604489e-05 2.94031652033522e-05 1.83667157380198e-05 1.7812239960596e-05 5.14030038935454e-05 -1.08999436952814e-06 3.12447474872382e-05 1.83667157380198e-05 0.000225513456641574 659 676 0 183 0 659 676 0 206 0 0 0 0 0 0 0 0 0 2125 0 0 0 0 0 1830 +854 898 0.99759663363426 0.0690570698527374 -0.0056637147655495 0.23397755179033 -0.0684878188880979 0.995156676740364 0.0705167171883842 -0.0655833468464637 0.0105059614287535 -0.0699593442109744 0.997494518747862 0.432799505374495 4.42496465761861e-05 -5.46970379638619e-05 -2.94054718083562e-06 -9.30082649359027e-06 -7.85243026995293e-06 -2.27280766443189e-05 -5.46970379638619e-05 0.000113894808529477 5.21265566024279e-06 1.87811758206577e-05 1.06715915462501e-05 0.000118565153794807 -2.94054718083562e-06 5.21265566024279e-06 1.07701758676977e-05 -6.96166039162479e-07 2.19967661825076e-06 6.55303372705018e-08 -9.30082649359027e-06 1.87811758206577e-05 -6.96166039162479e-07 4.66463442000699e-05 9.67980581491705e-06 5.11350477816778e-05 -7.85243026995293e-06 1.06715915462501e-05 2.19967661825076e-06 9.67980581491705e-06 2.45033829956631e-05 2.36955828579059e-05 -2.27280766443189e-05 0.000118565153794807 6.55303372705018e-08 5.11350477816778e-05 2.36955828579059e-05 0.000339288078960037 721 741 0 165 0 721 741 0 189 0 0 0 0 0 0 0 0 0 2446 0 0 0 0 0 1715 +854 933 0.964505428148568 -0.251598139330875 -0.0801726596614401 0.252803482072746 0.254932568751509 0.966349305690347 0.0343279009195323 0.00213760470885705 0.0688379580006922 -0.0535480688449665 0.99618971077866 0.14204800593861 3.81848996308464e-05 -2.37714206833819e-05 -1.14841464543909e-06 9.3622561903685e-06 1.74061697265842e-06 2.82906487505759e-05 -2.37714206833819e-05 0.000100047139490511 9.63240574439734e-07 2.69805629763874e-05 3.07760801475972e-06 2.93056852378607e-05 -1.14841464543909e-06 9.63240574439734e-07 1.00980959051889e-05 -1.93268323631032e-06 4.21799723655632e-06 -2.76820100398453e-06 9.3622561903685e-06 2.69805629763874e-05 -1.93268323631032e-06 6.88216353121602e-05 1.06121234126542e-05 2.43477725057892e-05 1.74061697265842e-06 3.07760801475972e-06 4.21799723655632e-06 1.06121234126542e-05 1.66084007031075e-05 4.83629183136276e-06 2.82906487505759e-05 2.93056852378607e-05 -2.76820100398453e-06 2.43477725057892e-05 4.83629183136276e-06 9.29221726951221e-05 1534 1534 0 0 0 1565 1565 0 0 0 0 0 0 0 0 458 463 0 3217 0 0 0 0 0 577 +854 857 0.999072475633072 0.036477891381198 -0.0228812559267921 0.161699763470814 -0.0370023192514137 0.999052053171598 -0.0229308400114706 -0.0465626310252216 0.0220230970215884 0.0237562306352823 0.999475174630957 0.229357996364856 3.99546871887942e-05 -2.51479658472784e-05 -1.67601865161981e-06 2.66089552598438e-06 3.76480098898296e-06 3.21502832219991e-05 -2.51479658472784e-05 6.11110258777196e-05 -1.13260704960656e-06 1.19694114206022e-06 -2.26672733335688e-06 -3.04323563354092e-06 -1.67601865161981e-06 -1.13260704960656e-06 1.40284657268421e-05 2.8979584268585e-06 5.09835425844147e-06 -3.34859110285427e-06 2.66089552598438e-06 1.19694114206022e-06 2.8979584268585e-06 4.05406106358167e-05 5.93680241743656e-06 5.35811242396906e-06 3.76480098898296e-06 -2.26672733335688e-06 5.09835425844147e-06 5.93680241743656e-06 2.58217981254314e-05 1.10327079098048e-05 3.21502832219991e-05 -3.04323563354092e-06 -3.34859110285427e-06 5.35811242396906e-06 1.10327079098048e-05 8.21437341514822e-05 1319 1332 0 139 0 1319 1332 0 154 0 0 0 0 0 0 0 0 0 2606 0 0 0 0 0 1657 +854 856 0.999790668371438 0.01676727332029 0.0117251005452488 0.100397558505625 -0.0161900733036659 0.998730430480128 -0.0477012448411925 -0.0366359405202407 -0.0125100345249495 0.047501429224605 0.99879282799678 0.147142325515968 3.59522729507801e-05 -2.31282499867534e-05 4.74316859402863e-06 9.34011093118539e-08 -1.24806297563276e-06 2.0086937023951e-05 -2.31282499867534e-05 6.37242675143779e-05 -5.24724481890094e-06 3.31768052186592e-05 1.55193794340992e-05 5.7634484103447e-06 4.74316859402863e-06 -5.24724481890094e-06 1.25061005693805e-05 -3.47064096194792e-07 6.34546683870632e-06 -1.742182584709e-06 9.34011093118539e-08 3.31768052186592e-05 -3.47064096194792e-07 6.41538092976308e-05 1.94824252131466e-05 1.49438986550866e-05 -1.24806297563276e-06 1.55193794340992e-05 6.34546683870632e-06 1.94824252131466e-05 3.45478979422838e-05 2.16062097590952e-05 2.0086937023951e-05 5.7634484103447e-06 -1.742182584709e-06 1.49438986550866e-05 2.16062097590952e-05 0.000124175817059719 1637 1654 0 87 0 1637 1654 0 105 0 0 0 0 0 0 0 0 0 2972 0 0 0 0 0 2395 +854 936 0.900886966405725 -0.412659818484189 -0.134590296711486 0.31893806657542 0.416926304532998 0.908931962156887 0.00389162666359196 0.130875935787108 0.120727504524643 -0.0596201507732666 0.990893691206592 -0.207354840146754 3.99080656510363e-05 -2.35590355658646e-05 4.33060381909051e-06 -1.28449939492328e-06 -1.08004995302374e-06 1.28060262438617e-05 -2.35590355658646e-05 8.59054727857266e-05 -3.28652948265434e-06 3.72123439933838e-05 -4.63061934664752e-06 4.62747427678858e-05 4.33060381909051e-06 -3.28652948265434e-06 1.07354129776276e-05 2.5672929873493e-06 4.33386375423528e-06 1.11853867590891e-06 -1.28449939492328e-06 3.72123439933838e-05 2.5672929873493e-06 8.88058697846934e-05 9.84013511276254e-07 4.9404265393367e-05 -1.08004995302374e-06 -4.63061934664752e-06 4.33386375423528e-06 9.84013511276254e-07 1.88376920156632e-05 -3.97224752265003e-06 1.28060262438617e-05 4.62747427678858e-05 1.11853867590891e-06 4.9404265393367e-05 -3.97224752265003e-06 0.000164461402404045 1918 1918 0 0 0 1938 1938 0 0 0 0 0 0 0 0 1007 997 0 3087 0 0 0 0 0 530 +854 931 0.996347157994756 -0.0848153785825928 0.00993440041793092 0.230357094509967 0.083958952547251 0.994184928624438 0.0674330926414481 -0.0508977297490082 -0.0155959944518067 -0.0663526883548295 0.997674338501871 0.307804214626422 2.64596070952071e-05 -1.47880043534162e-05 7.72804229507035e-07 -9.07673577603351e-08 -5.22949476296329e-06 1.52297357330955e-05 -1.47880043534162e-05 7.37521140578845e-05 7.16407034655963e-07 1.30452548437422e-05 3.47019713053872e-06 3.78501850612439e-05 7.72804229507035e-07 7.16407034655963e-07 1.16362008811681e-05 6.61651383987071e-07 3.95422382181224e-07 -2.23223425279697e-06 -9.07673577603351e-08 1.30452548437422e-05 6.61651383987071e-07 4.73744835405644e-05 8.60172178825611e-06 2.30543882960346e-05 -5.22949476296329e-06 3.47019713053872e-06 3.95422382181224e-07 8.60172178825611e-06 2.35422430953763e-05 9.01309077424186e-06 1.52297357330955e-05 3.78501850612439e-05 -2.23223425279697e-06 2.30543882960346e-05 9.01309077424186e-06 0.00011771050326401 1132 1129 0 5 0 1158 1155 0 2 0 0 0 0 0 0 80 98 0 3020 0 0 0 0 0 1470 +854 858 0.997358362170252 0.0480551967716172 -0.0544701337644105 0.187573823602053 -0.0490016214089083 0.998667733201878 -0.0161740458983417 -0.0527191137652819 0.0536203180554689 0.0188004447996528 0.998384397297436 0.272248827947625 3.23028674491946e-05 -2.83983943153481e-05 -1.02943743255447e-06 1.60049134957618e-06 1.84455733443938e-06 2.9771957136937e-05 -2.83983943153481e-05 6.81975509541317e-05 -9.29748960198945e-07 1.42693587229794e-05 8.24802222152809e-07 -2.25688648232127e-05 -1.02943743255447e-06 -9.29748960198945e-07 1.31894938917113e-05 2.75132573550328e-06 2.54455176545976e-06 -2.90226168714882e-07 1.60049134957618e-06 1.42693587229794e-05 2.75132573550328e-06 5.38891728923381e-05 1.01968094350745e-05 3.31301886253768e-06 1.84455733443938e-06 8.24802222152809e-07 2.54455176545976e-06 1.01968094350745e-05 2.90313154600133e-05 4.69094587236584e-06 2.9771957136937e-05 -2.25688648232127e-05 -2.90226168714882e-07 3.31301886253768e-06 4.69094587236584e-06 7.45870650325895e-05 1055 1073 0 132 0 1055 1073 0 146 0 0 0 0 0 0 0 0 0 2425 0 0 0 0 0 2433 +854 899 0.997623652148535 0.0688984296288779 -0.000234666769573041 0.234985208013224 -0.0687167616310589 0.995229069240707 0.0692611464618959 -0.068753904917607 0.00500553141618424 -0.0690804323448438 0.997598535745864 0.434481307407275 4.60155295382581e-05 -2.36594666828859e-05 -1.97068155078543e-07 -5.60853387370756e-07 -4.56533855565929e-06 4.30091225657892e-05 -2.36594666828859e-05 0.00020978253820698 -1.24927002546855e-07 5.03859104829092e-05 2.85397693217352e-05 8.86704094905282e-05 -1.97068155078543e-07 -1.24927002546855e-07 1.23933368350577e-05 -1.82926416819452e-06 1.03232380273925e-06 -3.14121009097268e-06 -5.60853387370756e-07 5.03859104829092e-05 -1.82926416819452e-06 4.89158383982275e-05 8.76510409226291e-06 2.73893346262205e-05 -4.56533855565929e-06 2.85397693217352e-05 1.03232380273925e-06 8.76510409226291e-06 2.65336264040401e-05 1.37407426217791e-05 4.30091225657892e-05 8.86704094905282e-05 -3.14121009097268e-06 2.73893346262205e-05 1.37407426217791e-05 0.00016286142474857 764 785 0 172 0 764 785 0 195 0 0 0 0 0 0 0 0 0 2475 0 0 0 0 0 786 +854 895 0.997632643994975 0.0686613510872321 -0.00383751253685879 0.235099337468446 -0.0682209615614429 0.995175059544515 0.0705159646052125 -0.065324741934174 0.0086607181703846 -0.0700872294176857 0.99750326928453 0.432161024103861 4.77747847550969e-05 -5.41530612415759e-05 -7.85878305543026e-07 -1.37577709246185e-05 -9.11147308666956e-06 -7.06390850349211e-06 -5.41530612415759e-05 8.88176521243186e-05 9.58981691180972e-07 2.61914835887595e-05 1.1301992597849e-05 3.83654972913137e-05 -7.85878305543026e-07 9.58981691180972e-07 1.11822439990149e-05 -7.05249534773982e-07 1.40474985884627e-06 -4.89686800731352e-06 -1.37577709246185e-05 2.61914835887595e-05 -7.05249534773982e-07 5.0651950276095e-05 1.10541099228666e-05 4.7132320085915e-05 -9.11147308666956e-06 1.1301992597849e-05 1.40474985884627e-06 1.10541099228666e-05 2.63556194594018e-05 2.7057782397114e-05 -7.06390850349211e-06 3.83654972913137e-05 -4.89686800731352e-06 4.7132320085915e-05 2.7057782397114e-05 0.000210517856322415 761 784 0 177 0 761 784 0 201 0 0 0 0 0 0 0 0 0 2412 0 0 0 0 0 1701 +854 929 0.99882433489567 0.0480871086641615 -0.00613008976642753 0.22821513583566 -0.047353641263347 0.994917562284057 0.0888632484092974 -0.0688197760874594 0.0103721106495048 -0.0884684929173736 0.996024972117468 0.412525820380063 2.76467779964856e-05 -2.08799936936889e-05 -2.82901813631234e-06 3.18984306716417e-06 -4.86228231919332e-06 1.69787462848924e-05 -2.08799936936889e-05 4.46869425058624e-05 2.64705267243829e-06 2.13418796518205e-06 2.48181640591048e-06 -8.30154162062153e-06 -2.82901813631234e-06 2.64705267243829e-06 1.13679446331909e-05 -4.24953569082724e-06 3.61880343635847e-06 -2.36721411878459e-06 3.18984306716417e-06 2.13418796518205e-06 -4.24953569082724e-06 3.34616285197842e-05 -7.93590954489029e-07 4.4999601665774e-06 -4.86228231919332e-06 2.48181640591048e-06 3.61880343635847e-06 -7.93590954489029e-07 1.99050177083557e-05 -2.66974291118492e-06 1.69787462848924e-05 -8.30154162062153e-06 -2.36721411878459e-06 4.4999601665774e-06 -2.66974291118492e-06 5.10936899951964e-05 849 873 0 157 0 849 873 0 178 0 0 0 0 0 0 0 0 0 2548 0 0 0 0 0 1328 +854 892 0.997650494332735 0.0681503989491139 -0.00700101997760587 0.228968917704024 -0.0675133842991602 0.995363338513839 0.0685110741636563 -0.0689646661412515 0.0116376156545974 -0.0678774444544041 0.997625790783406 0.432990476780612 2.7011760184227e-05 -2.05227663067175e-05 -4.50570232657043e-07 2.18017783968001e-06 -1.85291397484821e-06 2.21841833157331e-05 -2.05227663067175e-05 5.2076111093054e-05 1.36046894469512e-06 1.53298055688577e-06 2.22150318828571e-06 -4.9689543292861e-06 -4.50570232657043e-07 1.36046894469512e-06 1.19661140333586e-05 -3.39634056779409e-06 2.44291617750843e-06 -1.96032644163014e-06 2.18017783968001e-06 1.53298055688577e-06 -3.39634056779409e-06 2.81245813476106e-05 -2.42491212057965e-06 7.83472062533798e-06 -1.85291397484821e-06 2.22150318828571e-06 2.44291617750843e-06 -2.42491212057965e-06 2.05599545632615e-05 3.20987034894737e-06 2.21841833157331e-05 -4.9689543292861e-06 -1.96032644163014e-06 7.83472062533798e-06 3.20987034894737e-06 6.0899121909878e-05 758 772 0 163 0 758 772 0 185 0 0 0 0 0 0 0 0 0 2430 0 0 0 0 0 736 +854 896 0.997649671165879 0.0684833005198818 -0.00227402122160278 0.236047243486019 -0.0681459499326296 0.995109594135035 0.0715054205510685 -0.0653464551867337 0.00715982753928296 -0.0711823939630384 0.997437618931279 0.434542459080831 5.73985223671727e-05 -7.42714548641206e-05 -2.96478438265613e-06 -1.48738898037783e-05 -1.15911468417524e-05 -2.46292896396959e-05 -7.42714548641206e-05 0.000153392796557031 3.76744658746396e-06 3.85871615355348e-05 2.26852205736298e-05 0.000129849665858078 -2.96478438265613e-06 3.76744658746396e-06 1.05484117729433e-05 1.03774731623578e-06 2.1588414483384e-06 -3.09218246460372e-06 -1.48738898037783e-05 3.85871615355348e-05 1.03774731623578e-06 4.51379985206301e-05 1.06723711757912e-05 6.14977361622625e-05 -1.15911468417524e-05 2.26852205736298e-05 2.1588414483384e-06 1.06723711757912e-05 2.54639765758801e-05 3.54990804667489e-05 -2.46292896396959e-05 0.000129849665858078 -3.09218246460372e-06 6.14977361622625e-05 3.54990804667489e-05 0.000316688897284695 714 733 0 172 0 714 733 0 196 0 0 0 0 0 0 0 0 0 2395 0 0 0 0 0 1723 +854 900 0.997576165972854 0.0684047599816449 -0.0127507605558975 0.224811630849437 -0.0674192035400341 0.995530582374013 0.0661325226502513 -0.0740057861410697 0.0172175514207954 -0.0651125822703423 0.9977293759097 0.416519092085832 5.3766001838835e-05 -4.88845006780217e-05 1.71950100675506e-06 -1.60450057532725e-05 -1.28805036586289e-05 -2.18065761569857e-05 -4.88845006780217e-05 7.19851640428864e-05 -1.41510280987708e-06 2.49251834135696e-05 1.61669705916983e-05 6.53315818589167e-05 1.71950100675506e-06 -1.41510280987708e-06 1.30163588202084e-05 -3.85994558376687e-06 2.02832824943157e-06 -1.25263679592801e-06 -1.60450057532725e-05 2.49251834135696e-05 -3.85994558376687e-06 4.23066947907305e-05 8.84797564268456e-06 4.66348073417115e-05 -1.28805036586289e-05 1.61669705916983e-05 2.02832824943157e-06 8.84797564268456e-06 2.64795019760721e-05 3.1669707312179e-05 -2.18065761569857e-05 6.53315818589167e-05 -1.25263679592801e-06 4.66348073417115e-05 3.1669707312179e-05 0.000234917264389046 773 788 0 171 0 773 788 0 194 0 0 0 0 0 0 0 0 0 2360 0 0 0 0 0 1105 +854 894 0.997632605183099 0.0676796514330245 -0.0121922047836703 0.221993466480905 -0.0666688077780404 0.995323906185655 0.0698970088400403 -0.0729286790688091 0.0168657980848031 -0.0689186952664825 0.997479703200886 0.426696093697119 4.41950903721685e-05 -3.97933766052106e-05 4.47367678092978e-06 -1.44854560989638e-05 -8.36757506697958e-06 2.65894471034905e-05 -3.97933766052106e-05 7.38779439902505e-05 -1.66712390768731e-06 2.79287202749516e-05 1.09209514912478e-05 -8.54908184305344e-06 4.47367678092978e-06 -1.66712390768731e-06 1.19376344691169e-05 -6.41360613820402e-07 1.14640969784762e-06 1.21762989781909e-06 -1.44854560989638e-05 2.79287202749516e-05 -6.41360613820402e-07 4.61191910068104e-05 6.35082787634367e-06 2.9190656589177e-06 -8.36757506697958e-06 1.09209514912478e-05 1.14640969784762e-06 6.35082787634367e-06 2.46355999825595e-05 2.19351533049292e-06 2.65894471034905e-05 -8.54908184305344e-06 1.21762989781909e-06 2.9190656589177e-06 2.19351533049292e-06 6.67308967698517e-05 687 704 0 170 0 687 704 0 192 0 0 0 0 0 0 0 0 0 2340 0 0 0 0 0 728 +854 902 0.997606444201303 0.0688217800127317 -0.0067041094794067 0.230306065692642 -0.0681880399488165 0.995224302598796 0.0698496866469619 -0.0681962487745722 0.011479272449564 -0.0692253574394478 0.997534999983163 0.434494378068646 3.46670893732876e-05 -2.66357140477471e-05 -1.55863966315001e-06 -8.40888004962889e-07 -3.63306986171873e-06 2.82774817143094e-05 -2.66357140477471e-05 7.2451643937922e-05 4.10720898263285e-06 7.61501604720919e-06 2.5773612192577e-06 -8.64866872205808e-06 -1.55863966315001e-06 4.10720898263285e-06 1.04554356020773e-05 -3.03468024143688e-06 1.78287151694213e-06 -2.32290682848175e-06 -8.40888004962889e-07 7.61501604720919e-06 -3.03468024143688e-06 2.79777885697864e-05 -9.66502554977878e-07 1.13752498705676e-06 -3.63306986171873e-06 2.5773612192577e-06 1.78287151694213e-06 -9.66502554977878e-07 2.13757914788362e-05 1.73681878655002e-06 2.82774817143094e-05 -8.64866872205808e-06 -2.32290682848175e-06 1.13752498705676e-06 1.73681878655002e-06 7.17300108000475e-05 732 753 0 166 0 732 753 0 189 0 0 0 0 0 0 0 0 0 2475 0 0 0 0 0 734 +854 891 0.997576549168566 0.0694189272153052 -0.00469479426730092 0.238801828834775 -0.0689610026121244 0.995446530074815 0.0658071871511027 -0.0656456815523099 0.0092416809978862 -0.0653239489489563 0.997821313174883 0.437628309261539 3.86094011915876e-05 -4.30100562489611e-05 -3.15829290216327e-06 1.78261477321023e-06 -1.34058749076786e-06 1.52152631664949e-05 -4.30100562489611e-05 7.95009625970029e-05 3.65402933106141e-06 1.24986277604643e-05 3.92022032618882e-06 2.40445168856136e-05 -3.15829290216327e-06 3.65402933106141e-06 1.29698342849227e-05 -2.62576861418948e-06 3.56872255480285e-06 -3.81907254384889e-06 1.78261477321023e-06 1.24986277604643e-05 -2.62576861418948e-06 4.14226718362414e-05 4.6029731478037e-06 3.13630019114185e-05 -1.34058749076786e-06 3.92022032618882e-06 3.56872255480285e-06 4.6029731478037e-06 2.44619551068834e-05 1.21876177831673e-05 1.52152631664949e-05 2.40445168856136e-05 -3.81907254384889e-06 3.13630019114185e-05 1.21876177831673e-05 0.000173451849676341 740 764 0 181 0 740 764 0 200 0 0 0 0 0 0 0 0 0 2321 0 0 0 0 0 1752 +854 897 0.997618062281461 0.0683212760927014 -0.0095081566482636 0.228395385208866 -0.0674972535914093 0.995283204918172 0.0696811507183122 -0.0696260306331987 0.0142240137584308 -0.0688734000966704 0.997524000809867 0.425316264499053 3.89742113671791e-05 -3.72034425410057e-05 -2.97721375691099e-06 2.25227769804603e-06 -4.27767969137307e-06 5.82481006156126e-06 -3.72034425410057e-05 6.89514703680982e-05 4.05599005592656e-06 1.99259273569554e-06 1.88577164160711e-07 3.16220691618412e-05 -2.97721375691099e-06 4.05599005592656e-06 1.06950631083498e-05 -1.41267741570905e-06 3.33977370615681e-06 -2.31313611738075e-06 2.25227769804603e-06 1.99259273569554e-06 -1.41267741570905e-06 2.67962919191604e-05 -3.16578429695685e-06 2.04933734058201e-05 -4.27767969137307e-06 1.88577164160711e-07 3.33977370615681e-06 -3.16578429695685e-06 1.82827860215061e-05 3.38017662787653e-06 5.82481006156126e-06 3.16220691618412e-05 -2.31313611738075e-06 2.04933734058201e-05 3.38017662787653e-06 0.000140999613644208 786 806 0 163 0 786 806 0 187 0 0 0 0 0 0 0 0 0 2371 0 0 0 0 0 1303 +854 901 0.99754729976976 0.0689122123906026 -0.0122675060828597 0.227890850246319 -0.0678800179536559 0.995187051904145 0.0706755607331741 -0.06840348336527 0.0170788724648867 -0.0696694962359404 0.997423918607108 0.426676227530621 4.6140942119263e-05 -3.98521814926178e-05 -8.300480617943e-07 4.12481872747316e-06 -1.08678017479974e-06 3.08604984785279e-05 -3.98521814926178e-05 0.000104115331448093 1.34428438727248e-06 2.05285363175206e-05 1.09289359710445e-05 5.01282519644111e-06 -8.300480617943e-07 1.34428438727248e-06 1.20778439590073e-05 -3.10289941608692e-06 1.3357740815605e-06 -2.91876657768793e-06 4.12481872747316e-06 2.05285363175206e-05 -3.10289941608692e-06 4.95284682003434e-05 8.77403684229386e-06 2.15761287111288e-05 -1.08678017479974e-06 1.09289359710445e-05 1.3357740815605e-06 8.77403684229386e-06 2.59587556663215e-05 1.22738499345272e-05 3.08604984785279e-05 5.01282519644111e-06 -2.91876657768793e-06 2.15761287111288e-05 1.22738499345272e-05 9.40173177358853e-05 697 705 0 164 0 697 705 0 187 0 0 0 0 0 0 0 0 0 2382 0 0 0 0 0 768 +854 893 0.997612630941886 0.0686123049901474 -0.00783518915833297 0.230258620378592 -0.0679073094274413 0.995279611940641 0.0693331910531567 -0.0681474740934557 0.0125553140754665 -0.0686356005235387 0.997562789216418 0.426411200421069 4.05274552141648e-05 -3.54873570548062e-05 -1.08983451092458e-06 -1.80059706156607e-06 -1.84846685045377e-06 3.1698110574163e-05 -3.54873570548062e-05 0.000141804086752937 7.92608481648747e-06 3.044302614867e-05 3.63601430336947e-06 -1.1467893881625e-05 -1.08983451092458e-06 7.92608481648747e-06 1.06449539300661e-05 -2.36981478421991e-07 2.84528235474487e-06 -4.58567702068356e-08 -1.80059706156607e-06 3.044302614867e-05 -2.36981478421991e-07 3.87039490607066e-05 1.27636112990058e-06 1.20971410312238e-06 -1.84846685045377e-06 3.63601430336947e-06 2.84528235474487e-06 1.27636112990058e-06 1.88014894047182e-05 -4.99286281406505e-08 3.1698110574163e-05 -1.1467893881625e-05 -4.58567702068356e-08 1.20971410312238e-06 -4.99286281406505e-08 9.61208889529966e-05 730 753 0 168 0 730 753 0 189 0 0 0 0 0 0 0 0 0 2378 0 0 0 0 0 1554 +854 923 0.997668719643462 0.0679387263971655 -0.00643857907514427 0.229653457196607 -0.0673108260255083 0.995191525764446 0.0711553212795578 -0.0699270821063369 0.0112418212376621 -0.0705560522008171 0.997444467102353 0.428540111513371 3.40127020990673e-05 -2.5275041130116e-05 -2.57443560316017e-07 2.13369268493184e-08 -5.75418524846898e-06 3.06595517127949e-05 -2.5275041130116e-05 5.29343939994333e-05 3.18647329202987e-06 3.35159785081607e-06 4.83811191017655e-06 -1.75952014257716e-05 -2.57443560316017e-07 3.18647329202987e-06 1.29119702114635e-05 -2.6694688988051e-06 1.73062421533939e-06 -2.95465948845427e-06 2.13369268493184e-08 3.35159785081607e-06 -2.6694688988051e-06 3.03246067563477e-05 1.79956211630414e-07 4.44477844569384e-06 -5.75418524846898e-06 4.83811191017655e-06 1.73062421533939e-06 1.79956211630414e-07 2.26268609285396e-05 2.18027578056558e-06 3.06595517127949e-05 -1.75952014257716e-05 -2.95465948845427e-06 4.44477844569384e-06 2.18027578056558e-06 7.04053933836086e-05 765 787 0 175 0 765 787 0 198 0 0 0 0 0 0 0 0 0 2363 0 0 0 0 0 765 +854 925 0.997592450454325 0.0689097446119384 -0.00779422183754731 0.233399288386812 -0.0681863656306862 0.995146058256468 0.0709573271670617 -0.0659478724118336 0.0126460404322397 -0.0702550342262566 0.997448899857659 0.428414728898316 4.35770954749852e-05 -5.25256458320071e-05 -2.6408688326527e-07 -1.45391050369478e-05 -1.37900202180963e-05 -2.62729892708276e-05 -5.25256458320071e-05 0.000105029474638619 1.96896640752391e-06 3.21074991862802e-05 1.99641886717191e-05 0.000101473458449509 -2.6408688326527e-07 1.96896640752391e-06 1.04941226010847e-05 6.49450156287525e-07 3.02565877116085e-06 -5.58030995379704e-07 -1.45391050369478e-05 3.21074991862802e-05 6.49450156287525e-07 5.10270779589993e-05 1.20181158154114e-05 6.44295755800169e-05 -1.37900202180963e-05 1.99641886717191e-05 3.02565877116085e-06 1.20181158154114e-05 2.74795751350051e-05 3.445853953238e-05 -2.62729892708276e-05 0.000101473458449509 -5.58030995379704e-07 6.44295755800169e-05 3.445853953238e-05 0.000299244432383135 724 747 0 172 0 724 747 0 196 0 0 0 0 0 0 0 0 0 2356 0 0 0 0 0 1718 +854 890 0.997378501953237 0.0681689951293859 -0.0242716283872266 0.237382212278675 -0.0670736481336008 0.996803832094237 0.0433963828941263 -0.0606747794547923 0.0271523400016974 -0.0416546326990584 0.998763055988325 0.424457910450041 6.26908080627796e-05 -7.57643448854631e-05 -1.86350031052107e-06 -1.96319465872461e-05 -1.71865124050573e-05 -2.07798266594396e-05 -7.57643448854631e-05 0.000155481156403076 3.43035848783046e-07 5.59319286464785e-05 3.11564915282965e-05 9.76937648222679e-05 -1.86350031052107e-06 3.43035848783046e-07 1.20947556878574e-05 -3.4866903077856e-06 3.33005996732854e-06 -8.57670727405585e-06 -1.96319465872461e-05 5.59319286464785e-05 -3.4866903077856e-06 7.00072217476025e-05 1.89157592688211e-05 8.52700681503551e-05 -1.71865124050573e-05 3.11564915282965e-05 3.33005996732854e-06 1.89157592688211e-05 3.234675797912e-05 4.52037789806742e-05 -2.07798266594396e-05 9.76937648222679e-05 -8.57670727405585e-06 8.52700681503551e-05 4.52037789806742e-05 0.000302871361645939 694 709 0 146 0 694 709 0 165 0 0 0 0 0 0 0 0 0 2207 0 0 0 0 0 1740 +854 922 0.997618623714625 0.0688166712122707 -0.00462032260766668 0.236949801035678 -0.0683341459460177 0.995264734679206 0.069127074303472 -0.0681265762185156 0.00935553929845995 -0.0686467309286584 0.99759716329651 0.431646636238734 3.76280520816278e-05 -3.69562246536002e-05 -1.39017258371065e-06 5.0589922411006e-06 -1.86621218078219e-07 1.98770177046292e-05 -3.69562246536002e-05 0.000132279025337672 5.14758536350725e-06 8.12647371471875e-06 2.70434122836842e-06 3.23810287385174e-05 -1.39017258371065e-06 5.14758536350725e-06 1.12392373831633e-05 -3.18570710021961e-06 1.86877937091129e-06 -2.53306528686672e-06 5.0589922411006e-06 8.12647371471875e-06 -3.18570710021961e-06 3.84256709417554e-05 2.36737626901865e-06 1.40807013721792e-05 -1.86621218078219e-07 2.70434122836842e-06 1.86877937091129e-06 2.36737626901865e-06 2.52997973314752e-05 1.29573533351461e-05 1.98770177046292e-05 3.23810287385174e-05 -2.53306528686672e-06 1.40807013721792e-05 1.29573533351461e-05 0.000113918890805785 781 800 0 166 0 781 800 0 189 0 0 0 0 0 0 0 0 0 2347 0 0 0 0 0 741 +855 858 0.99753771135903 0.0415629461398337 -0.0564892549496502 0.126009229121703 -0.0398344283622918 0.998713160101537 0.0313885672984705 -0.0232504701519396 0.0577211636545795 -0.0290610624062241 0.997909676232365 0.183653519227554 3.10615993420262e-05 -1.27443706060652e-05 -1.78225595571837e-07 -6.08535269921563e-08 -1.68694247733696e-06 1.78315831951603e-05 -1.27443706060652e-05 7.51587968287456e-05 2.60950210246406e-06 1.01853314467e-05 1.26932815007903e-06 1.91414341758291e-05 -1.78225595571837e-07 2.60950210246406e-06 1.20236646188396e-05 6.60532008772017e-07 1.88478430037533e-06 1.86595310441762e-06 -6.08535269921563e-08 1.01853314467e-05 6.60532008772017e-07 5.22947936472323e-05 1.20341294125473e-05 8.01076608487835e-06 -1.68694247733696e-06 1.26932815007903e-06 1.88478430037533e-06 1.20341294125473e-05 2.84207553308943e-05 2.06919613468333e-06 1.78315831951603e-05 1.91414341758291e-05 1.86595310441762e-06 8.01076608487835e-06 2.06919613468333e-06 6.12232635961942e-05 1155 1163 0 104 0 1155 1163 0 116 0 0 0 0 0 0 0 0 0 2925 0 0 0 0 0 1634 +854 903 0.997625788271352 0.0685269275946684 -0.00684447005966651 0.231143675086672 -0.067899138278972 0.995333883279985 0.0685577699152903 -0.06909360514174 0.0115105862985185 -0.0679302656348399 0.997623669232965 0.43072813809946 2.41002038543632e-05 -1.55638582506876e-05 -8.12304553935564e-07 6.63795572539302e-07 -3.37515664595326e-06 1.28575909801704e-05 -1.55638582506876e-05 4.86408443554971e-05 1.66017855093738e-06 4.01453303682508e-06 3.14745353848647e-06 -7.88205651123998e-06 -8.12304553935564e-07 1.66017855093738e-06 9.15033013558113e-06 -2.14965048202166e-06 3.35292080736641e-06 -1.36742164360663e-06 6.63795572539302e-07 4.01453303682508e-06 -2.14965048202166e-06 2.89921760954086e-05 2.02457557706639e-06 6.49147864786364e-06 -3.37515664595326e-06 3.14745353848647e-06 3.35292080736641e-06 2.02457557706639e-06 2.03552153149133e-05 8.30055569058159e-06 1.28575909801704e-05 -7.88205651123998e-06 -1.36742164360663e-06 6.49147864786364e-06 8.30055569058159e-06 7.1488204479683e-05 748 757 0 163 0 748 757 0 185 0 0 0 0 0 0 0 0 0 2370 0 0 0 0 0 1601 +854 924 0.997627071780981 0.068605219138695 -0.00579219791070606 0.232887757111248 -0.0680287227332101 0.995192421866236 0.0704566273909235 -0.0685340916547009 0.0105980438286118 -0.0698954030458874 0.997498027115873 0.427307186641603 2.83192905628564e-05 -2.3004445207372e-05 -3.60817867838791e-07 -3.34914593976244e-07 -1.81259119756146e-06 1.57575339157252e-05 -2.3004445207372e-05 7.19801975519301e-05 1.78908009118913e-06 2.54853314254801e-05 1.16379347247218e-05 2.15802550597538e-05 -3.60817867838791e-07 1.78908009118913e-06 9.43618048064446e-06 -2.03753475779035e-06 2.86111867731236e-06 -1.99916645262666e-06 -3.34914593976244e-07 2.54853314254801e-05 -2.03753475779035e-06 4.11410712322155e-05 4.5027070047706e-06 2.34204667204651e-05 -1.81259119756146e-06 1.16379347247218e-05 2.86111867731236e-06 4.5027070047706e-06 2.20726533283238e-05 1.02573997452843e-05 1.57575339157252e-05 2.15802550597538e-05 -1.99916645262666e-06 2.34204667204651e-05 1.02573997452843e-05 0.000102770499281576 735 750 0 169 0 735 750 0 192 0 0 0 0 0 0 0 0 0 2345 0 0 0 0 0 1574 +855 859 0.998547680217903 0.0294696531537944 -0.0451006637915537 0.126128047373416 -0.0278727571456553 0.998976072879144 0.0356358699074826 -0.030340040310842 0.0461046607247362 -0.0343270353796939 0.998346640652183 0.212751937499012 2.90941773733171e-05 -1.34511009184614e-05 1.1024570593302e-09 3.1983118781268e-06 -2.98668819531454e-06 7.36644159839196e-06 -1.34511009184614e-05 4.98083110707889e-05 -8.15333180342466e-07 6.00008539234223e-06 1.92535229727109e-06 9.21813660952022e-06 1.1024570593302e-09 -8.15333180342466e-07 1.18159466911398e-05 1.08816975002309e-06 4.70065377349319e-06 -2.52665319080235e-06 3.1983118781268e-06 6.00008539234223e-06 1.08816975002309e-06 4.51031519524724e-05 6.36205409153609e-06 1.06314117682379e-05 -2.98668819531454e-06 1.92535229727109e-06 4.70065377349319e-06 6.36205409153609e-06 2.52542911030803e-05 7.02644812763293e-06 7.36644159839196e-06 9.21813660952022e-06 -2.52665319080235e-06 1.06314117682379e-05 7.02644812763293e-06 5.65187993949777e-05 1077 1080 0 93 0 1077 1080 0 108 0 0 0 0 0 0 0 0 0 2824 0 0 0 0 0 2114 +855 933 0.963148299791173 -0.257939218105704 -0.0762411461901655 0.201831062042931 0.263865659149529 0.961078647452356 0.0818703080043953 0.0289050492962404 0.0521561744279347 -0.0989706682515965 0.993722567065313 0.0499215351365903 2.91510688710175e-05 -2.21746830240684e-05 -2.61880504529214e-06 7.22986258518557e-06 -1.68331085891801e-07 1.55598090742739e-05 -2.21746830240684e-05 4.70869221032712e-05 3.27927907729945e-06 -2.33292961829501e-06 -1.77847933025147e-06 -3.14203896416215e-07 -2.61880504529214e-06 3.27927907729945e-06 1.05359114936599e-05 -1.27509051200686e-07 4.4720276321651e-06 -1.60747036483118e-06 7.22986258518557e-06 -2.33292961829501e-06 -1.27509051200686e-07 6.08225944609013e-05 7.63044688423413e-06 8.57640258907808e-06 -1.68331085891801e-07 -1.77847933025147e-06 4.4720276321651e-06 7.63044688423413e-06 1.86541318194981e-05 2.73013814314719e-06 1.55598090742739e-05 -3.14203896416215e-07 -1.60747036483118e-06 8.57640258907808e-06 2.73013814314719e-06 5.6558304922367e-05 1504 1504 0 0 0 1514 1514 0 0 0 0 0 0 0 0 589 586 0 3365 0 0 0 0 0 924 +855 931 0.99541206636096 -0.0926179417478586 0.0240153078138385 0.174714035415767 0.0892108206588394 0.989121520516667 0.116961733606223 -0.0226749979179217 -0.0345868128103695 -0.114282695615684 0.99284601921065 0.230342145745983 3.5966254134844e-05 -6.75815813592532e-05 -3.73587459387375e-06 -6.18876723670232e-06 -5.66443781021843e-06 -1.43317798437629e-05 -6.75815813592532e-05 0.000231990182213503 6.72677197032292e-06 3.53905302787446e-05 4.695639846457e-06 0.000103980130531426 -3.73587459387375e-06 6.72677197032292e-06 1.10978386971921e-05 6.00241916545612e-08 2.67196289659277e-06 -1.22127786358053e-06 -6.18876723670232e-06 3.53905302787446e-05 6.00241916545612e-08 4.49373789304536e-05 -3.46521910560938e-06 2.13500506397591e-05 -5.66443781021843e-06 4.695639846457e-06 2.67196289659277e-06 -3.46521910560938e-06 2.16186769363648e-05 2.157813608383e-06 -1.43317798437629e-05 0.000103980130531426 -1.22127786358053e-06 2.13500506397591e-05 2.157813608383e-06 0.000105192242530568 1042 1041 0 0 0 1060 1060 0 0 0 0 0 0 0 0 115 126 0 3277 0 0 0 0 0 1507 +855 857 0.999184317578853 0.0292773128635719 -0.0278125593207546 0.092792334168559 -0.028540477406165 0.999240500153335 0.0265304354043034 -0.0247235230958354 0.0285681755439537 -0.0257150112736171 0.999261025729157 0.135455523979215 2.59902974870676e-05 -1.23505215752862e-05 -3.02568183150109e-06 -5.72746947825206e-07 -6.45099236320844e-07 1.29717937598131e-05 -1.23505215752862e-05 3.98599153657444e-05 2.91128547551624e-06 1.94700773510738e-06 -1.61218356539719e-06 2.24329038474811e-06 -3.02568183150109e-06 2.91128547551624e-06 1.15024057377823e-05 -1.76084823361997e-06 3.12005419826578e-06 -3.47473603137276e-06 -5.72746947825206e-07 1.94700773510738e-06 -1.76084823361997e-06 4.99361139545173e-05 1.23169908824232e-05 -1.89273569413262e-06 -6.45099236320844e-07 -1.61218356539719e-06 3.12005419826578e-06 1.23169908824232e-05 2.29075710555434e-05 -1.79624163009018e-06 1.29717937598131e-05 2.24329038474811e-06 -3.47473603137276e-06 -1.89273569413262e-06 -1.79624163009018e-06 4.32711873465112e-05 1483 1486 0 104 0 1483 1486 0 124 0 0 0 0 0 0 0 0 0 3252 0 0 0 0 0 2393 +855 934 0.937548657849767 -0.329044126248233 -0.112838278725072 0.228033920614216 0.337515266275459 0.938990800138056 0.0661794702842089 0.0584221734044528 0.0841781396510177 -0.100131115232126 0.991406980289762 -0.0413928316159699 2.63991836509051e-05 -1.64090110892576e-05 -2.03229004439855e-06 1.34466098259761e-05 -2.14560867706597e-06 1.58301744932916e-05 -1.64090110892576e-05 3.71665884733596e-05 3.56725345810158e-06 -5.33566964199634e-06 -2.84008156054669e-06 7.15571917016807e-07 -2.03229004439855e-06 3.56725345810158e-06 1.18234101005308e-05 -3.86666933481591e-07 2.34177608437358e-06 -7.96054111172928e-07 1.34466098259761e-05 -5.33566964199634e-06 -3.86666933481591e-07 7.03040792684926e-05 1.26040140547022e-06 1.73366489526728e-05 -2.14560867706597e-06 -2.84008156054669e-06 2.34177608437358e-06 1.26040140547022e-06 2.65516846163709e-05 -1.39706462506912e-06 1.58301744932916e-05 7.15571917016807e-07 -7.96054111172928e-07 1.73366489526728e-05 -1.39706462506912e-06 6.514820349101e-05 1711 1711 0 0 0 1715 1715 0 0 0 0 0 0 0 0 761 749 0 3129 0 0 0 0 0 795 +855 930 0.998949640879191 -0.0204152298489953 0.0410223521698694 0.163592373710776 0.0148093383499239 0.991060978569899 0.132585143412491 -0.0340966910045775 -0.0433624086620378 -0.13183836750463 0.990322344678105 0.289807580233147 3.36745262461692e-05 -2.89606226460629e-05 -4.42273389018297e-06 5.5880469862474e-06 -4.29568912716776e-06 1.1482098940591e-06 -2.89606226460629e-05 6.7403840581456e-05 5.53459608077977e-06 -7.78280673723528e-07 -2.12989964209304e-06 2.6169889009415e-05 -4.42273389018297e-06 5.53459608077977e-06 1.07012058525624e-05 -4.8817187006592e-06 3.05100873678474e-06 -3.5498169133397e-06 5.5880469862474e-06 -7.78280673723528e-07 -4.8817187006592e-06 3.5204647631675e-05 -1.33578944032055e-06 1.08087723952697e-05 -4.29568912716776e-06 -2.12989964209304e-06 3.05100873678474e-06 -1.33578944032055e-06 2.19753369011557e-05 -2.15272110528462e-06 1.1482098940591e-06 2.6169889009415e-05 -3.5498169133397e-06 1.08087723952697e-05 -2.15272110528462e-06 6.46912249251063e-05 1074 1088 0 45 0 1074 1090 0 68 0 0 0 0 0 0 2 10 0 2918 0 0 0 0 0 1336 +855 898 0.99803457349649 0.0621759247452425 -0.00781949408551821 0.172602862704558 -0.0608736360290058 0.991544011625427 0.114607475525648 -0.0369825357268874 0.014879198307961 -0.113906221918857 0.993380079358291 0.336247588637185 4.9886027531518e-05 -6.61536299940055e-05 -7.40080536427407e-06 -1.58997238045374e-05 -5.26993774732529e-06 -4.83282637195638e-05 -6.61536299940055e-05 0.000126112691820484 1.0735467294491e-05 2.73160761835947e-05 3.86590204919378e-06 0.000111587339543875 -7.40080536427407e-06 1.0735467294491e-05 1.22160520475351e-05 -2.69312260735625e-06 2.68207835136735e-06 8.98825429339725e-07 -1.58997238045374e-05 2.73160761835947e-05 -2.69312260735625e-06 5.18248737163644e-05 7.1008703245483e-06 5.95071263222364e-05 -5.26993774732529e-06 3.86590204919378e-06 2.68207835136735e-06 7.1008703245483e-06 2.73419870776259e-05 2.08418781777424e-05 -4.83282637195638e-05 0.000111587339543875 8.98825429339725e-07 5.95071263222364e-05 2.08418781777424e-05 0.00022097142546771 723 744 0 149 0 723 744 0 175 0 0 0 0 0 0 0 0 0 2579 0 0 0 0 0 1775 +855 932 0.984632618961727 -0.168797701273851 -0.0447877407471437 0.183083374417701 0.172668417019991 0.979378425857782 0.104897648820858 -0.00857875322371904 0.0261576650406715 -0.11101907497812 0.993473976282531 0.14530730375711 3.60181941617994e-05 -2.97720355171735e-05 -2.13990681023277e-06 -1.60226047518908e-06 -1.21465220092127e-05 -3.21918095955486e-06 -2.97720355171735e-05 0.000128178100664169 1.46542139472679e-06 3.71035683723256e-05 5.31436270333081e-06 6.64596635140556e-05 -2.13990681023277e-06 1.46542139472679e-06 1.09198501100332e-05 -1.58466427950893e-06 4.51384104477856e-06 6.78826530761195e-07 -1.60226047518908e-06 3.71035683723256e-05 -1.58466427950893e-06 6.13715869455559e-05 -1.52856640154267e-07 2.69205237928193e-05 -1.21465220092127e-05 5.31436270333081e-06 4.51384104477856e-06 -1.52856640154267e-07 2.86928708821937e-05 5.17097926774615e-07 -3.21918095955486e-06 6.64596635140556e-05 6.78826530761195e-07 2.69205237928193e-05 5.17097926774615e-07 0.000101528594492917 1221 1221 0 0 0 1253 1253 0 0 0 0 0 0 0 0 343 345 0 3433 0 0 0 0 0 1360 +855 929 0.999135118394797 0.0410196278106745 -0.00681214536616866 0.168679061790626 -0.0397100266392076 0.989871643703423 0.136298359403909 -0.0386242878967715 0.0123340575047099 -0.13590996698608 0.990644412440363 0.333408038633834 2.29363441185069e-05 -1.52553037686385e-05 -2.3819924693691e-06 5.72219515302407e-06 -5.68029979576292e-06 5.34020798432211e-06 -1.52553037686385e-05 5.33435513366206e-05 3.8460510247213e-06 -3.78065409508559e-06 6.12483838941694e-07 7.79726576666734e-06 -2.3819924693691e-06 3.8460510247213e-06 1.1188387791907e-05 -4.52574418895803e-06 2.56724996895548e-06 -9.67557708467634e-07 5.72219515302407e-06 -3.78065409508559e-06 -4.52574418895803e-06 3.54558118032424e-05 -1.83254132979191e-06 -2.24134042853286e-06 -5.68029979576292e-06 6.12483838941694e-07 2.56724996895548e-06 -1.83254132979191e-06 2.72527678731147e-05 -2.87498536605381e-06 5.34020798432211e-06 7.79726576666734e-06 -9.67557708467634e-07 -2.24134042853286e-06 -2.87498536605381e-06 3.85408538162861e-05 811 830 0 121 0 811 830 0 146 0 0 0 0 0 0 0 0 0 2689 0 0 0 0 0 1497 +855 897 0.998050544037983 0.0616555423827196 -0.00968016730113807 0.169377843695624 -0.0602243561626173 0.992125321465235 0.109819731525362 -0.0439769552437919 0.0163749342069997 -0.109022660951735 0.993904382186093 0.332625958947188 5.31618303526739e-05 -3.14277926104413e-05 4.89169007670722e-07 -6.11629836967713e-06 -1.39988445785266e-05 -4.10640481986937e-05 -3.14277926104413e-05 6.77971184741304e-05 6.69051805047408e-07 9.91074321157139e-06 4.50629618559647e-06 5.92530340085379e-05 4.89169007670722e-07 6.69051805047408e-07 1.12139339016465e-05 -4.60804302979293e-06 2.892040810663e-06 -6.51273833629784e-06 -6.11629836967713e-06 9.91074321157139e-06 -4.60804302979293e-06 3.75677966903473e-05 2.43597707182874e-06 3.72326676872029e-05 -1.39988445785266e-05 4.50629618559647e-06 2.892040810663e-06 2.43597707182874e-06 2.61704046925473e-05 1.994341690495e-05 -4.10640481986937e-05 5.92530340085379e-05 -6.51273833629784e-06 3.72326676872029e-05 1.994341690495e-05 0.000154843431121608 804 825 0 151 0 804 825 0 175 0 0 0 0 0 0 0 0 0 2475 0 0 0 0 0 1531 +855 935 0.911456444616697 -0.372097362488335 -0.175472796740451 0.233647739351991 0.386084464364091 0.920969372014496 0.0524804934039188 0.0914817979669426 0.142077218241996 -0.115581004669672 0.983084480304804 -0.19094950004288 3.73203455568921e-05 -2.21348644997607e-05 1.31810348855042e-06 2.37901667548766e-06 -1.21808829012208e-06 2.20359851348636e-05 -2.21348644997607e-05 0.000105760105279686 -2.82292828998501e-06 6.49130515876614e-05 -4.73386391611677e-06 3.09262706223295e-05 1.31810348855042e-06 -2.82292828998501e-06 1.06829117102906e-05 2.63970950801581e-06 3.2802086989209e-06 -1.05010982897182e-06 2.37901667548766e-06 6.49130515876614e-05 2.63970950801581e-06 0.000128189538670743 -8.80560619500905e-07 4.51650531451722e-05 -1.21808829012208e-06 -4.73386391611677e-06 3.2802086989209e-06 -8.80560619500905e-07 2.06796452866013e-05 -4.74135535354872e-06 2.20359851348636e-05 3.09262706223295e-05 -1.05010982897182e-06 4.51650531451722e-05 -4.74135535354872e-06 0.000107195784443858 1780 1780 0 0 0 1800 1800 0 0 0 0 0 0 0 0 927 916 0 2679 0 0 0 0 0 832 +855 899 0.997989873756795 0.0630532758706232 -0.00636366882224432 0.176236475101859 -0.0618631254509707 0.991072256404479 0.118104768298198 -0.0342174964859607 0.0137537481558148 -0.117473686361315 0.992980748768248 0.343523171944047 2.9213385393414e-05 -1.76787481039157e-05 -1.33144793533762e-06 3.11204134928551e-06 -3.21211575854348e-06 1.85694224002948e-05 -1.76787481039157e-05 6.28499542783039e-05 2.5517722213684e-06 7.28070198003021e-06 4.82803908913141e-06 6.76580766515189e-06 -1.33144793533762e-06 2.5517722213684e-06 1.14510409179422e-05 -4.25452780613163e-06 4.08926761847421e-06 -1.33004468397927e-06 3.11204134928551e-06 7.28070198003021e-06 -4.25452780613163e-06 3.93491429817804e-05 -1.13416145461375e-07 7.10166181693321e-06 -3.21211575854348e-06 4.82803908913141e-06 4.08926761847421e-06 -1.13416145461375e-07 2.37044002277135e-05 4.27937954810358e-06 1.85694224002948e-05 6.76580766515189e-06 -1.33004468397927e-06 7.10166181693321e-06 4.27937954810358e-06 4.81309941813111e-05 756 779 0 157 0 756 779 0 182 0 0 0 0 0 0 0 0 0 2601 0 0 0 0 0 1703 +855 900 0.998060344536043 0.06177262541961 -0.00772602183295377 0.171090203845742 -0.0605825908493639 0.992320682362686 0.107839756311073 -0.0455376411977949 0.0143282361291717 -0.107162521918914 0.994138267820631 0.33022277204303 3.47851895822255e-05 -1.91829383368737e-05 -3.67563610840148e-07 -4.10407918245301e-06 -5.68099892029202e-06 -5.22181794635963e-06 -1.91829383368737e-05 6.20293981785855e-05 -1.62933152011046e-07 1.40793678926543e-05 3.85467102888548e-06 3.39279057927578e-05 -3.67563610840148e-07 -1.62933152011046e-07 1.06437461597823e-05 -3.16687984347555e-06 3.06597293111548e-06 -1.87217695046812e-06 -4.10407918245301e-06 1.40793678926543e-05 -3.16687984347555e-06 4.63926844808843e-05 -1.3306942195468e-06 2.86788109167493e-05 -5.68099892029202e-06 3.85467102888548e-06 3.06597293111548e-06 -1.3306942195468e-06 2.31866897283859e-05 9.98692300361323e-06 -5.22181794635963e-06 3.39279057927578e-05 -1.87217695046812e-06 2.86788109167493e-05 9.98692300361323e-06 8.87830888119272e-05 787 800 0 143 0 787 800 0 168 0 0 0 0 0 0 0 0 0 2509 0 0 0 0 0 1516 +855 901 0.997986733018477 0.0626748862969355 -0.00971284442238655 0.172808882888562 -0.0611059651331495 0.991200868026086 0.11741763176576 -0.0365623550327571 0.0169865165426463 -0.116587725992059 0.993035125463217 0.343528224507751 3.4478335718912e-05 -1.79224305235651e-05 -2.33625190174049e-06 7.04827714958474e-06 7.86089330762019e-07 1.3556449792879e-05 -1.79224305235651e-05 7.67075200832146e-05 1.29502753879283e-06 1.8255082898852e-05 7.23672039050337e-06 2.44229545502609e-05 -2.33625190174049e-06 1.29502753879283e-06 1.15612181088716e-05 -4.78532521060394e-06 2.49711928003717e-06 -1.12508816607119e-06 7.04827714958474e-06 1.8255082898852e-05 -4.78532521060394e-06 4.82205590825728e-05 3.66521327974123e-06 1.42148487810382e-05 7.86089330762019e-07 7.23672039050337e-06 2.49711928003717e-06 3.66521327974123e-06 2.61216895970842e-05 9.91069223394858e-06 1.3556449792879e-05 2.44229545502609e-05 -1.12508816607119e-06 1.42148487810382e-05 9.91069223394858e-06 5.9036737493217e-05 726 744 0 145 0 726 744 0 170 0 0 0 0 0 0 0 0 0 2493 0 0 0 0 0 1635 +855 895 0.998039460058651 0.0618935921529376 -0.00929620439978513 0.170755744324639 -0.0604984262358323 0.992078155848719 0.110094836894346 -0.0431245407682723 0.0160367262502144 -0.109316585833125 0.993877611918572 0.325455210762389 3.3344439636657e-05 -2.97344962915593e-05 -2.55520566497214e-06 -1.80945534205727e-06 -8.3987928012656e-06 -6.45026000485955e-06 -2.97344962915593e-05 4.60861133013781e-05 3.89809469643722e-06 2.55916661960519e-06 6.66217339246421e-06 2.12516917025083e-05 -2.55520566497214e-06 3.89809469643722e-06 1.11929730836675e-05 -3.66618641945261e-06 2.9144253718677e-06 -4.29513689814158e-06 -1.80945534205727e-06 2.55916661960519e-06 -3.66618641945261e-06 3.84921595800547e-05 1.56000468634686e-07 2.03635076062454e-05 -8.3987928012656e-06 6.66217339246421e-06 2.9144253718677e-06 1.56000468634686e-07 2.52427656319097e-05 1.50356980912717e-05 -6.45026000485955e-06 2.12516917025083e-05 -4.29513689814158e-06 2.03635076062454e-05 1.50356980912717e-05 0.000105616013598684 776 797 0 140 0 776 797 0 164 0 0 0 0 0 0 0 0 0 2547 0 0 0 0 0 1750 +855 894 0.998016209067683 0.0621176262734192 -0.0102492411585602 0.169794064570366 -0.0605078046341682 0.991357590412784 0.11639988620833 -0.0395794541674792 0.0173911476482673 -0.115548814087876 0.99314954540913 0.341522500500468 3.60769871307679e-05 -2.63945891782938e-05 1.22225454231937e-06 -1.98428940430577e-06 -6.90975647329569e-06 2.75530324612617e-06 -2.63945891782938e-05 8.61672832403e-05 -4.68271598413029e-07 2.94954668774518e-05 1.0357807530738e-05 3.45065563085902e-05 1.22225454231937e-06 -4.68271598413029e-07 1.14764516002438e-05 -2.18489836621091e-06 1.99720465746668e-06 -5.80467046912118e-07 -1.98428940430577e-06 2.94954668774518e-05 -2.18489836621091e-06 5.04056115791092e-05 1.33428443942282e-06 1.86026691982611e-05 -6.90975647329569e-06 1.0357807530738e-05 1.99720465746668e-06 1.33428443942282e-06 2.81415839748016e-05 1.18028242112228e-05 2.75530324612617e-06 3.45065563085902e-05 -5.80467046912118e-07 1.86026691982611e-05 1.18028242112228e-05 7.01552626250699e-05 727 747 0 149 0 727 747 0 174 0 0 0 0 0 0 0 0 0 2454 0 0 0 0 0 1457 +855 902 0.998042589823289 0.0624407481180237 -0.00348451908932697 0.177150424315808 -0.0615938178527288 0.991093952423827 0.118063453580017 -0.0340424387878148 0.0108254561634712 -0.117617730140389 0.992999939101446 0.345502520983678 4.02845126768528e-05 -2.65156617896063e-05 -1.39733536428143e-06 -2.16334632476138e-08 -2.82408513884159e-06 1.53709150727031e-05 -2.65156617896063e-05 8.47842718774052e-05 2.72908628855267e-06 1.00026712450721e-05 -7.66257907447558e-07 1.44811695636796e-05 -1.39733536428143e-06 2.72908628855267e-06 1.21896072609005e-05 -4.52429291473533e-06 3.07738425069975e-06 -1.26453569719906e-06 -2.16334632476138e-08 1.00026712450721e-05 -4.52429291473533e-06 3.70675696964551e-05 4.91283927718466e-07 1.09053420410599e-05 -2.82408513884159e-06 -7.66257907447558e-07 3.07738425069975e-06 4.91283927718466e-07 2.37640619808722e-05 3.01043604307598e-06 1.53709150727031e-05 1.44811695636796e-05 -1.26453569719906e-06 1.09053420410599e-05 3.01043604307598e-06 5.19539651350439e-05 750 773 0 154 0 750 773 0 181 0 0 0 0 0 0 0 0 0 2572 0 0 0 0 0 1714 +855 924 0.998055931357022 0.0616296107415348 -0.00928164656270825 0.171499129713034 -0.0601325911351215 0.991363941013637 0.116540155917552 -0.0411967584317392 0.0163838141604586 -0.115755464396969 0.99314260964667 0.342233374551628 2.52043264245916e-05 -1.01453712413453e-05 1.64780556494608e-07 5.13767118548324e-06 -4.6007047971001e-07 1.40950934769535e-05 -1.01453712413453e-05 6.45633059882907e-05 2.0910445951039e-06 1.36584443005504e-05 5.42029484909302e-06 1.19382164186675e-05 1.64780556494608e-07 2.0910445951039e-06 1.31476379993958e-05 -6.16158618009802e-06 2.18052384660392e-06 -1.0108464350006e-06 5.13767118548324e-06 1.36584443005504e-05 -6.16158618009802e-06 4.45978728290466e-05 4.60569165934713e-06 1.0691897025554e-05 -4.6007047971001e-07 5.42029484909302e-06 2.18052384660392e-06 4.60569165934713e-06 3.15858251923582e-05 6.92875111061599e-06 1.40950934769535e-05 1.19382164186675e-05 -1.0108464350006e-06 1.0691897025554e-05 6.92875111061599e-06 4.86901140220809e-05 717 736 0 140 0 717 736 0 167 0 0 0 0 0 0 0 0 0 2511 0 0 0 0 0 988 +855 896 0.998000694135779 0.0620245487730875 -0.0121478333046896 0.169961924405004 -0.0603136802316699 0.992069631238649 0.110272874048527 -0.0424099256624264 0.0188911217617034 -0.109319724311331 0.993827109408412 0.329698581903535 3.6098226081852e-05 -3.37046918846375e-05 -2.12857919590109e-06 -1.56076202956468e-06 -8.03687519148262e-06 -1.38706695456181e-05 -3.37046918846375e-05 7.76934641788875e-05 5.62350476933361e-06 4.59549045685127e-06 2.01447987008491e-06 4.3524712205682e-05 -2.12857919590109e-06 5.62350476933361e-06 1.10978294298626e-05 -3.14169663712821e-06 3.71602330478811e-06 -1.32132796925979e-06 -1.56076202956468e-06 4.59549045685127e-06 -3.14169663712821e-06 4.08316946930388e-05 6.79796231761514e-07 1.7785672092868e-05 -8.03687519148262e-06 2.01447987008491e-06 3.71602330478811e-06 6.79796231761514e-07 2.55678980208069e-05 1.06203358819375e-05 -1.38706695456181e-05 4.3524712205682e-05 -1.32132796925979e-06 1.7785672092868e-05 1.06203358819375e-05 0.000109206677783229 739 743 0 136 0 739 743 0 161 0 0 0 0 0 0 0 0 0 2581 0 0 0 0 0 1764 +855 892 0.998027092468466 0.0621522878431395 -0.00888908402498939 0.1708458031812 -0.0606976856399576 0.99133293844634 0.11651092699527 -0.036470971169805 0.0160534624580702 -0.115741514882119 0.993149630255129 0.342849014972934 2.24137412986462e-05 -1.53058149263169e-05 -3.09119717256835e-06 6.2939440359252e-06 -4.53414081383195e-06 7.74562888756e-06 -1.53058149263169e-05 4.41340289639167e-05 2.93008895912084e-06 -6.87806900727487e-06 6.53020281487092e-09 -9.61655806813791e-07 -3.09119717256835e-06 2.93008895912084e-06 1.20639757614463e-05 -4.31100247030324e-06 3.67760625819414e-06 -1.88310964288772e-06 6.2939440359252e-06 -6.87806900727487e-06 -4.31100247030324e-06 3.26537620870015e-05 -2.12249308866533e-06 4.91424035901166e-06 -4.53414081383195e-06 6.53020281487092e-09 3.67760625819414e-06 -2.12249308866533e-06 2.39219424964047e-05 3.0176675799749e-06 7.74562888756e-06 -9.61655806813791e-07 -1.88310964288772e-06 4.91424035901166e-06 3.0176675799749e-06 3.73336129212941e-05 772 787 0 142 0 772 787 0 168 0 0 0 0 0 0 0 0 0 2587 0 0 0 0 0 1556 +855 893 0.99803105050785 0.0620080804569954 -0.00943505062184436 0.16975938469002 -0.0604799460446158 0.991266506133546 0.117187413762026 -0.0390049046009252 0.0166192162462117 -0.116386046310676 0.993064997810078 0.341028513555129 3.04710274863999e-05 -1.85364398605522e-05 -1.60804848161331e-06 7.85905620437004e-06 2.77594227180098e-07 1.79715355170767e-05 -1.85364398605522e-05 9.20049413685645e-05 3.21334631471627e-06 3.65963599739808e-06 -5.30180284914779e-06 9.93013088641405e-06 -1.60804848161331e-06 3.21334631471627e-06 1.32185857223458e-05 -3.49825843927044e-06 1.40572452523253e-06 -1.09234176114296e-06 7.85905620437004e-06 3.65963599739808e-06 -3.49825843927044e-06 4.61642332736497e-05 -1.81919057620214e-06 8.26540318502473e-06 2.77594227180098e-07 -5.30180284914779e-06 1.40572452523253e-06 -1.81919057620214e-06 2.79563806238201e-05 6.2904038332083e-06 1.79715355170767e-05 9.93013088641405e-06 -1.09234176114296e-06 8.26540318502473e-06 6.2904038332083e-06 5.79633516140027e-05 781 799 0 152 0 781 799 0 177 0 0 0 0 0 0 0 0 0 2509 0 0 0 0 0 1026 +855 903 0.998026127897621 0.0619672182193666 -0.010193718646016 0.170646338839807 -0.0603625835252643 0.99135139986188 0.116527938718777 -0.0390657878060447 0.0173264694567655 -0.115682608278189 0.993135100375633 0.343208556549649 2.43185815530732e-05 -1.03959739919994e-05 -1.89468168575394e-06 2.95865035159275e-06 -1.74665127189609e-06 6.58007584930209e-06 -1.03959739919994e-05 0.000101061245367521 5.28339064431758e-06 2.88903708822581e-05 4.59604614738902e-06 3.92527323873407e-05 -1.89468168575394e-06 5.28339064431758e-06 1.24483300699781e-05 -1.76492434557817e-06 1.38046947188436e-06 -5.67733526903394e-07 2.95865035159275e-06 2.88903708822581e-05 -1.76492434557817e-06 4.82124926367645e-05 6.85044137497963e-07 2.10031468674039e-05 -1.74665127189609e-06 4.59604614738902e-06 1.38046947188436e-06 6.85044137497963e-07 2.86770262122975e-05 7.85254491765489e-06 6.58007584930209e-06 3.92527323873407e-05 -5.67733526903394e-07 2.10031468674039e-05 7.85254491765489e-06 6.68824400608011e-05 741 763 0 149 0 741 763 0 175 0 0 0 0 0 0 0 0 0 2490 0 0 0 0 0 1025 +855 927 0.998038863541508 0.0622394034779048 -0.00668457294754096 0.175220820899973 -0.0610136801756828 0.991095157477553 0.118354212666736 -0.0351453208068957 0.013991343473588 -0.117714253509327 0.992948939688515 0.341076378464251 2.88798831386681e-05 -1.88584100824687e-05 -3.37914582734024e-06 8.95915388210639e-06 7.16250546535598e-07 1.85617708829421e-05 -1.88584100824687e-05 0.000110402183641173 4.41445671733907e-06 9.3901747087007e-06 3.31010596000112e-06 2.72086642640731e-05 -3.37914582734024e-06 4.41445671733907e-06 1.23824250643535e-05 -4.4461086872483e-06 3.7038987327385e-06 -2.53706073252991e-06 8.95915388210639e-06 9.3901747087007e-06 -4.4461086872483e-06 3.84818762014947e-05 1.54023045354962e-06 1.40532190180171e-05 7.16250546535598e-07 3.31010596000112e-06 3.7038987327385e-06 1.54023045354962e-06 2.46201549024151e-05 6.66235569778825e-06 1.85617708829421e-05 2.72086642640731e-05 -2.53706073252991e-06 1.40532190180171e-05 6.66235569778825e-06 6.79233100622864e-05 755 781 0 158 0 755 781 0 184 0 0 0 0 0 0 0 0 0 2569 0 0 0 0 0 926 +855 891 0.997965979181578 0.0617528225867144 -0.0158269800886841 0.169159274309063 -0.0596402434320822 0.992103516434751 0.110334283163316 -0.0406465056491297 0.0225154560139428 -0.109165935989092 0.993768510599984 0.333968652806695 4.28114924026732e-05 -4.63891172304758e-05 -2.39508766549292e-06 -6.10706491812027e-06 -8.03087799198283e-06 -1.29833048784599e-05 -4.63891172304758e-05 0.000100391302080634 3.01993212640722e-06 2.80376923741358e-05 1.08819286519106e-05 4.35351333881472e-05 -2.39508766549292e-06 3.01993212640722e-06 1.01644124013259e-05 -3.436551934978e-06 3.16716293644358e-06 -3.44112909301011e-06 -6.10706491812027e-06 2.80376923741358e-05 -3.436551934978e-06 4.84404926523172e-05 2.26021705594067e-06 3.44623946772997e-05 -8.03087799198283e-06 1.08819286519106e-05 3.16716293644358e-06 2.26021705594067e-06 3.02280680144779e-05 1.95855410414516e-05 -1.29833048784599e-05 4.35351333881472e-05 -3.44112909301011e-06 3.44623946772997e-05 1.95855410414516e-05 0.000111805487462669 719 739 0 146 0 719 739 0 171 0 0 0 0 0 0 0 0 0 2488 0 0 0 0 0 1848 +855 926 0.998072825510885 0.0615271808979267 -0.0080647992828719 0.171683450811138 -0.0601502679260392 0.99119679879903 0.117944272090596 -0.0390330232947289 0.0152505817969318 -0.117231873060652 0.992987466030436 0.342130504308184 2.6312638573574e-05 -1.98565431383519e-05 -1.47447026077999e-06 5.78383196533623e-06 -2.65110801764299e-06 1.41535440612387e-05 -1.98565431383519e-05 8.2493810010836e-05 2.88101324586327e-06 2.48938736701439e-05 1.02563357315197e-05 9.3385007024126e-06 -1.47447026077999e-06 2.88101324586327e-06 1.3839617009825e-05 -3.50264547467733e-06 2.60360691852545e-06 -1.58974904443522e-06 5.78383196533623e-06 2.48938736701439e-05 -3.50264547467733e-06 5.31727593591289e-05 6.26521041724744e-06 1.36337844869965e-05 -2.65110801764299e-06 1.02563357315197e-05 2.60360691852545e-06 6.26521041724744e-06 2.9059895110211e-05 7.3190497936669e-06 1.41535440612387e-05 9.3385007024126e-06 -1.58974904443522e-06 1.36337844869965e-05 7.3190497936669e-06 5.04866752259752e-05 748 772 0 156 0 748 772 0 182 0 0 0 0 0 0 0 0 0 2529 0 0 0 0 0 954 +855 890 0.997710040236194 0.0615556742683416 -0.0280281033475743 0.175766247494659 -0.0587905545676016 0.994149640915835 0.0906099451525569 -0.0291782525399481 0.033441685147826 -0.0887546642846749 0.995491970465954 0.34028729789672 3.14414273006809e-05 -4.0444233778737e-05 -2.21614622766304e-07 -2.51051498270049e-06 -5.76278004678555e-06 -3.01412158804279e-06 -4.0444233778737e-05 0.00010237643144683 1.4079287909809e-06 1.94134496695779e-05 9.78856002701069e-06 3.88527958491045e-05 -2.21614622766304e-07 1.4079287909809e-06 1.05871135907837e-05 -3.65214370510018e-06 3.19691484459252e-06 -2.31740324432449e-06 -2.51051498270049e-06 1.94134496695779e-05 -3.65214370510018e-06 4.42734325117335e-05 4.77268292599272e-06 2.72731154118032e-05 -5.76278004678555e-06 9.78856002701069e-06 3.19691484459252e-06 4.77268292599272e-06 2.31527946394668e-05 1.22800595525599e-05 -3.01412158804279e-06 3.88527958491045e-05 -2.31740324432449e-06 2.72731154118032e-05 1.22800595525599e-05 7.79242792669634e-05 738 749 0 125 0 738 749 0 148 0 0 0 0 0 0 0 0 0 2346 0 0 0 0 0 1845 +855 925 0.998032055154217 0.0619717012272978 -0.00956687679680109 0.172457523182907 -0.0604959888659675 0.991734183422744 0.113152749687987 -0.0398604425741055 0.0165000671446926 -0.112351313645271 0.993531544595542 0.334327551225425 2.65683071439923e-05 -1.82083848818117e-05 2.27447187566075e-07 1.21763226538228e-06 -8.12528117357937e-06 -9.81218929790489e-06 -1.82083848818117e-05 5.08838845675403e-05 -7.20560118686019e-07 1.09971454129465e-05 3.2747610401318e-06 2.93375011300485e-05 2.27447187566075e-07 -7.20560118686019e-07 1.02295946971861e-05 -2.29152641648829e-06 3.81701495209373e-06 -1.11797616868715e-06 1.21763226538228e-06 1.09971454129465e-05 -2.29152641648829e-06 4.11663068455878e-05 -3.24226818071344e-06 2.20567013363813e-05 -8.12528117357937e-06 3.2747610401318e-06 3.81701495209373e-06 -3.24226818071344e-06 2.29335415113353e-05 1.18547148444835e-05 -9.81218929790489e-06 2.93375011300485e-05 -1.11797616868715e-06 2.20567013363813e-05 1.18547148444835e-05 8.41371662707164e-05 757 782 0 151 0 757 782 0 176 0 0 0 0 0 0 0 0 0 2558 0 0 0 0 0 1710 +855 923 0.998051731410908 0.0618511256674525 -0.00819632120882778 0.171034943395543 -0.0604763683274663 0.99132829826715 0.116665393020711 -0.0396919859118845 0.0153411310407649 -0.115942413759699 0.993137455939491 0.341645293253473 2.05931512687157e-05 -1.37784756013007e-05 -3.24139582051844e-07 4.28246559962771e-06 -3.76700683994371e-06 8.19259430369343e-06 -1.37784756013007e-05 4.85125957915713e-05 1.34576170984077e-06 5.65705170091801e-06 2.67047138959036e-06 6.41602906137818e-06 -3.24139582051844e-07 1.34576170984077e-06 1.10092514404455e-05 -3.00890635152628e-06 3.75153141413236e-06 -9.85297613938605e-07 4.28246559962771e-06 5.65705170091801e-06 -3.00890635152628e-06 3.34884148918058e-05 -4.90519342354634e-06 8.31347883556327e-06 -3.76700683994371e-06 2.67047138959036e-06 3.75153141413236e-06 -4.90519342354634e-06 2.18120619339555e-05 4.18987575452229e-06 8.19259430369343e-06 6.41602906137818e-06 -9.85297613938605e-07 8.31347883556327e-06 4.18987575452229e-06 4.2631288986672e-05 798 821 0 152 0 798 821 0 176 0 0 0 0 0 0 0 0 0 2541 0 0 0 0 0 1530 +855 922 0.998003527264655 0.0626161725371025 -0.00825678533755619 0.17499963447294 -0.0612312555448467 0.991297076968636 0.1165368548479 -0.0364383872041127 0.0154820189803643 -0.11579861886155 0.9931520462437 0.346302893687343 2.44356478097366e-05 -8.43849589575467e-06 9.65289539020531e-08 6.32123369347532e-06 -4.2718472214842e-06 1.40111833665007e-05 -8.43849589575467e-06 6.12698209155505e-05 1.17054375722507e-06 5.89230608562428e-06 -1.91495132858045e-06 9.51588010416407e-06 9.65289539020531e-08 1.17054375722507e-06 1.13367277097493e-05 -4.03909718231893e-06 4.10732053996784e-06 -5.34600915728679e-07 6.32123369347532e-06 5.89230608562428e-06 -4.03909718231893e-06 3.36270430140267e-05 -5.07054054418322e-06 7.50388732250146e-06 -4.2718472214842e-06 -1.91495132858045e-06 4.10732053996784e-06 -5.07054054418322e-06 2.14583942165185e-05 9.69064619090691e-07 1.40111833665007e-05 9.51588010416407e-06 -5.34600915728679e-07 7.50388732250146e-06 9.69064619090691e-07 4.076455435082e-05 785 797 0 153 0 785 797 0 177 0 0 0 0 0 0 0 0 0 2547 0 0 0 0 0 1591 +856 932 0.981766459590359 -0.177415753894606 -0.0682515134881264 0.131507896476773 0.184076874757078 0.976912199596074 0.1084355036878 0.0111857904585964 0.0474375695317344 -0.119021865849803 0.991757769037658 0.0759753940759763 2.22722068097587e-05 -9.02538117869146e-06 -1.44540831372956e-06 -3.7051746165202e-07 -4.71549116335598e-06 4.5734541715269e-06 -9.02538117869146e-06 4.43408619710502e-05 4.43876888591698e-07 7.07302960123848e-06 4.24958153325963e-06 2.40126809395952e-05 -1.44540831372956e-06 4.43876888591698e-07 9.41096324422437e-06 5.51400644452151e-07 2.72874009011869e-06 -9.78013729013238e-07 -3.7051746165202e-07 7.07302960123848e-06 5.51400644452151e-07 5.65924839687219e-05 6.46447584390266e-06 -4.42635161168106e-07 -4.71549116335598e-06 4.24958153325963e-06 2.72874009011869e-06 6.46447584390266e-06 1.99980336497997e-05 -2.57102730962896e-06 4.5734541715269e-06 2.40126809395952e-05 -9.78013729013238e-07 -4.42635161168106e-07 -2.57102730962896e-06 6.03230183462898e-05 1388 1388 0 0 0 1391 1391 0 0 0 0 0 0 0 0 402 402 0 3377 0 0 0 0 0 1115 +855 921 0.998019327870111 0.0617972168271891 -0.0117696724723145 0.169286492304125 -0.0601268760276872 0.992067948558251 0.110389964320015 -0.0430650425020084 0.0184981073854412 -0.109463644356637 0.99381866081661 0.332342625301705 4.76478075440147e-05 -4.26750943625399e-05 2.4433555573866e-06 -1.46087138286953e-05 -1.3472357231217e-05 -3.72368873653689e-05 -4.26750943625399e-05 6.00838060722927e-05 -1.65526111657582e-06 1.99118045697044e-05 1.18954141913932e-05 5.01539080973727e-05 2.4433555573866e-06 -1.65526111657582e-06 1.07094990850202e-05 -3.47974486629531e-06 2.76485033929593e-06 -2.5362656389538e-06 -1.46087138286953e-05 1.99118045697044e-05 -3.47974486629531e-06 4.70716606768048e-05 4.82055856377319e-06 4.28401379601279e-05 -1.3472357231217e-05 1.18954141913932e-05 2.76485033929593e-06 4.82055856377319e-06 2.75734707765141e-05 2.76190825601946e-05 -3.72368873653689e-05 5.01539080973727e-05 -2.5362656389538e-06 4.28401379601279e-05 2.76190825601946e-05 0.000154703177338544 777 796 0 140 0 777 796 0 163 0 0 0 0 0 0 0 0 0 2481 0 0 0 0 0 1750 +856 934 0.931920561831865 -0.338001692463478 -0.131449314668453 0.183972237645406 0.347906489192635 0.935549926300595 0.0608885061124593 0.0719721522984526 0.102396978532751 -0.102475320398505 0.989451195105947 -0.1131686847801 4.11312559162204e-05 -1.29463981546125e-05 2.20997447976807e-06 1.31552794503651e-05 -1.12120947335762e-05 1.3918187752397e-05 -1.29463981546125e-05 0.000118306783104301 3.29636367211852e-06 4.17702671289217e-05 -1.3676235163224e-05 4.39914160074207e-05 2.20997447976807e-06 3.29636367211852e-06 1.05134993270346e-05 4.55233763756028e-06 -3.59130413972651e-07 2.63083968215119e-06 1.31552794503651e-05 4.17702671289217e-05 4.55233763756028e-06 8.9288733597267e-05 -6.2210987638894e-06 3.8413354591025e-05 -1.12120947335762e-05 -1.3676235163224e-05 -3.59130413972651e-07 -6.2210987638894e-06 3.72601024497497e-05 -9.23468933631963e-06 1.3918187752397e-05 4.39914160074207e-05 2.63083968215119e-06 3.8413354591025e-05 -9.23468933631963e-06 0.000100637443307628 1660 1660 0 0 0 1667 1667 0 0 0 0 0 0 0 0 855 843 0 3006 0 0 0 0 0 595 +856 858 0.997033182871016 0.0291717523628788 -0.0712309000235799 0.072761532759484 -0.0270667955100973 0.99917309826766 0.030339879350786 -0.0146499326868777 0.072057066516095 -0.0283218742720984 0.996998320260777 0.11317950350535 3.44906197877792e-05 -3.76319100581327e-05 1.48859574034939e-06 -1.105429153145e-05 -9.4274273847607e-06 9.00453302581817e-07 -3.76319100581327e-05 0.000107122776387807 -1.63899636346808e-07 3.44530743464173e-05 1.92086863238061e-05 1.62935906168572e-05 1.48859574034939e-06 -1.63899636346808e-07 1.1053032124325e-05 2.84610289751494e-06 -2.25584837903646e-06 -7.91287253531663e-07 -1.105429153145e-05 3.44530743464173e-05 2.84610289751494e-06 5.60671889676372e-05 1.87936529408407e-05 1.34541452163945e-05 -9.4274273847607e-06 1.92086863238061e-05 -2.25584837903646e-06 1.87936529408407e-05 3.68798541032547e-05 1.11037355158604e-05 9.00453302581817e-07 1.62935906168572e-05 -7.91287253531663e-07 1.34541452163945e-05 1.11037355158604e-05 5.82154739680835e-05 1221 1229 0 64 0 1221 1229 0 79 0 0 0 0 0 0 13 0 0 3206 0 0 0 0 0 2283 +856 933 0.959112906465079 -0.268056222115664 -0.0908201213233443 0.152018486993721 0.275186140482526 0.958229409643396 0.0779037006874511 0.0383163059379661 0.0661439395443022 -0.0997108834558527 0.992815551339731 -0.0267573799305332 3.80409738162445e-05 -2.59143486361059e-05 -1.63765382884171e-06 7.40088772837838e-06 -7.65729538044833e-07 9.37895370307415e-06 -2.59143486361059e-05 8.57651835595229e-05 2.49466411823376e-06 3.05882669154346e-05 2.44675284115978e-06 2.676469365676e-05 -1.63765382884171e-06 2.49466411823376e-06 1.01680654582739e-05 -2.07154983699053e-06 2.3510664644207e-06 -1.87776478518795e-06 7.40088772837838e-06 3.05882669154346e-05 -2.07154983699053e-06 9.16010472948399e-05 1.92787706709221e-05 2.65593848183776e-05 -7.65729538044833e-07 2.44675284115978e-06 2.3510664644207e-06 1.92787706709221e-05 2.53692903907e-05 3.36778417024282e-06 9.37895370307415e-06 2.676469365676e-05 -1.87776478518795e-06 2.65593848183776e-05 3.36778417024282e-06 8.21050429265043e-05 1574 1574 0 0 0 1587 1587 0 0 0 0 0 0 0 0 606 603 0 3300 0 0 0 0 0 530 +856 930 0.999423638152286 -0.0291694041935521 0.0173648311665234 0.109830229981988 0.0265999498108781 0.990722978607014 0.133268234512599 -0.0208002704874323 -0.021091092254965 -0.13272952014921 0.990927868368053 0.215494839069322 3.97460340495019e-05 -4.0714578172354e-05 -1.90560333643385e-06 -1.85112781681025e-06 -5.31844100569908e-06 -1.25243118433338e-05 -4.0714578172354e-05 9.82095277469434e-05 3.87879368026785e-07 3.68681931130148e-05 1.05753010354804e-05 4.26522913358447e-05 -1.90560333643385e-06 3.87879368026785e-07 1.09098576163887e-05 -6.863671227198e-06 4.83841205612901e-06 -3.20852895397198e-06 -1.85112781681025e-06 3.68681931130148e-05 -6.863671227198e-06 6.79433506077098e-05 3.5786210673353e-06 2.98407758043416e-05 -5.31844100569908e-06 1.05753010354804e-05 4.83841205612901e-06 3.5786210673353e-06 2.37617906533148e-05 1.05054064335429e-05 -1.25243118433338e-05 4.26522913358447e-05 -3.20852895397198e-06 2.98407758043416e-05 1.05054064335429e-05 8.29846750622833e-05 1134 1134 0 12 0 1139 1152 0 32 0 0 0 0 0 0 21 41 0 3042 0 0 0 0 0 1114 +856 859 0.998164925305851 0.0187214661094215 -0.0575872259783245 0.0785403814630796 -0.0165937946562843 0.99916984152645 0.0372058296898914 -0.0166170518055384 0.0582359671343225 -0.0361819636106433 0.997646950399393 0.139053816168107 2.4294116114258e-05 -1.22717885801291e-05 3.31192870113975e-07 1.70599642320292e-06 -3.29262739366286e-06 6.10450389430561e-06 -1.22717885801291e-05 2.7393139335828e-05 1.11726058735244e-06 -8.74677850399903e-07 -1.1123590638066e-06 -1.21283196637174e-06 3.31192870113975e-07 1.11726058735244e-06 1.25695836856215e-05 -1.1577945974747e-06 2.68914494492161e-06 -1.95675098153945e-06 1.70599642320292e-06 -8.74677850399903e-07 -1.1577945974747e-06 5.87901478512957e-05 1.33880744699957e-05 -1.24705750650697e-06 -3.29262739366286e-06 -1.1123590638066e-06 2.68914494492161e-06 1.33880744699957e-05 2.83121108588934e-05 5.13590656863113e-06 6.10450389430561e-06 -1.21283196637174e-06 -1.95675098153945e-06 -1.24705750650697e-06 5.13590656863113e-06 5.19758680016129e-05 1288 1287 0 50 0 1284 1287 0 64 0 0 0 0 0 0 5 1 0 3128 0 0 0 0 0 2274 +856 898 0.998117329786081 0.0534694580165237 -0.0300468474240307 0.120506220449878 -0.0496686264217246 0.992066044754804 0.115490217741321 -0.0213129682292142 0.0359836564301479 -0.113780402108526 0.992854066097299 0.261838775065234 3.72442364423183e-05 -3.10234712780084e-05 -3.26120645530531e-07 -1.53274485264531e-05 -9.5252197284522e-06 -1.83140692333675e-05 -3.10234712780084e-05 5.67429012199924e-05 3.19522785215118e-06 1.52322263440362e-05 7.04947925123901e-06 3.33865582395798e-05 -3.26120645530531e-07 3.19522785215118e-06 1.06121152357671e-05 -5.54115114268047e-06 3.51802544477427e-06 -2.04360098023813e-06 -1.53274485264531e-05 1.52322263440362e-05 -5.54115114268047e-06 5.19626524739862e-05 9.21726545314175e-06 3.56244982113448e-05 -9.5252197284522e-06 7.04947925123901e-06 3.51802544477427e-06 9.21726545314175e-06 2.52427521274467e-05 1.81495402028469e-05 -1.83140692333675e-05 3.33865582395798e-05 -2.04360098023813e-06 3.56244982113448e-05 1.81495402028469e-05 0.000105435773262978 792 809 0 121 0 792 809 0 138 0 0 0 0 0 0 0 0 0 2740 0 0 0 0 0 1719 +856 895 0.998274106970186 0.0532087096169665 -0.0248523756163216 0.125124871944761 -0.0499715649861747 0.991937132956656 0.116462727748247 -0.0212077960384513 0.0308488256779723 -0.115019813435022 0.992884078063327 0.267178924781709 4.26720718595075e-05 -4.44371990214312e-05 -1.22908538400446e-06 -1.67882859077513e-05 -1.16117619025568e-05 -2.26893610596751e-05 -4.44371990214312e-05 6.87281234317778e-05 2.08978289027812e-06 2.48894473881213e-05 1.23623950274841e-05 4.20607615283735e-05 -1.22908538400446e-06 2.08978289027812e-06 9.87961485549227e-06 -3.69669736406241e-06 3.34022677361036e-06 -3.08598578564796e-06 -1.67882859077513e-05 2.48894473881213e-05 -3.69669736406241e-06 5.70262317343159e-05 1.22296073834641e-05 4.73392963434873e-05 -1.16117619025568e-05 1.23623950274841e-05 3.34022677361036e-06 1.22296073834641e-05 3.11889023208765e-05 3.21362470828925e-05 -2.26893610596751e-05 4.20607615283735e-05 -3.08598578564796e-06 4.73392963434873e-05 3.21362470828925e-05 0.000116810522975985 800 821 0 130 0 800 821 0 150 0 0 0 0 0 0 0 0 0 2648 0 0 0 0 0 1690 +856 894 0.997996878412013 0.0526235370351536 -0.035114014720442 0.111848075369863 -0.0485003380797252 0.992811925344169 0.109417540186918 -0.0298872139147777 0.0406195505394872 -0.107495321964788 0.993375461680857 0.251164893646638 7.80974943038244e-05 -4.58708396087048e-05 4.25108542856913e-06 -2.3936894105347e-05 -2.39638562357924e-05 -7.25059258254657e-05 -4.58708396087048e-05 7.96383839712951e-05 -1.69744802974349e-06 2.26427302332055e-05 1.51297037437647e-05 5.03250871538543e-05 4.25108542856913e-06 -1.69744802974349e-06 1.14812175417219e-05 -4.01770091733976e-06 1.19890593945462e-06 -3.70364929441969e-06 -2.3936894105347e-05 2.26427302332055e-05 -4.01770091733976e-06 6.09160527380227e-05 1.83237792862135e-05 4.97153462377213e-05 -2.39638562357924e-05 1.51297037437647e-05 1.19890593945462e-06 1.83237792862135e-05 3.5849949608258e-05 4.37782544666702e-05 -7.25059258254657e-05 5.03250871538543e-05 -3.70364929441969e-06 4.97153462377213e-05 4.37782544666702e-05 0.000180389589266125 822 841 0 123 0 822 841 0 140 0 0 0 0 0 0 0 0 0 2664 0 0 0 0 0 1082 +856 931 0.994768056825904 -0.101174293464501 -0.0141518712817314 0.117944535464996 0.102115981061077 0.988791338101278 0.108922064375491 -0.0097795286662231 0.00297313483541492 -0.109797322544058 0.993949550244582 0.145137498293728 4.83249005652154e-05 -3.92322971295025e-05 -2.30601898271821e-06 8.77482202739689e-06 -6.80981059810335e-06 -3.62954981442465e-05 -3.92322971295025e-05 7.23279650422974e-05 -8.55072542384047e-07 4.22766435348174e-06 -6.78650425904067e-07 4.97734359313345e-05 -2.30601898271821e-06 -8.55072542384047e-07 1.10023972211924e-05 -2.74598996118534e-06 5.42725009819938e-06 -1.285875189561e-06 8.77482202739689e-06 4.22766435348174e-06 -2.74598996118534e-06 4.75070690363727e-05 -3.53032088555432e-07 -2.15019751778459e-06 -6.80981059810335e-06 -6.78650425904067e-07 5.42725009819938e-06 -3.53032088555432e-07 2.12218369682418e-05 2.70665657651952e-06 -3.62954981442465e-05 4.97734359313345e-05 -1.285875189561e-06 -2.15019751778459e-06 2.70665657651952e-06 0.000107730204480546 1140 1140 0 0 0 1158 1158 0 0 0 0 0 0 0 0 188 198 0 3437 0 0 0 0 0 1351 +856 860 0.999096000928397 0.000523496268105029 -0.0425077273038982 0.0907568638401627 -3.69598471398058e-05 0.999934493842363 0.0114458140028353 -0.0111784885052588 0.0425109346269285 -0.0114338959184996 0.999030573336607 0.165905845439312 2.46173063893381e-05 -1.90865657803038e-05 3.17485914726494e-07 -1.11312494571579e-06 -3.67286994851991e-06 6.99486288159688e-06 -1.90865657803038e-05 7.97507512927489e-05 -1.51540286570687e-06 1.39834331708631e-05 -1.11065819885878e-06 2.31562207558485e-05 3.17485914726494e-07 -1.51540286570687e-06 1.31023666440095e-05 1.55123389303691e-06 2.26424721866126e-06 -6.64452212914309e-07 -1.11312494571579e-06 1.39834331708631e-05 1.55123389303691e-06 6.63443352422887e-05 5.86228405696767e-06 3.50015446226584e-06 -3.67286994851991e-06 -1.11065819885878e-06 2.26424721866126e-06 5.86228405696767e-06 3.08962559553887e-05 4.41969181805742e-06 6.99486288159688e-06 2.31562207558485e-05 -6.64452212914309e-07 3.50015446226584e-06 4.41969181805742e-06 5.9091022830408e-05 1224 1233 0 30 0 1224 1234 0 42 0 0 0 0 0 0 25 22 0 2813 0 0 0 0 0 1691 +856 896 0.998003604459257 0.0528488971184066 -0.0345803348696742 0.113372501612695 -0.0486775090073147 0.992515214699165 0.112000217444045 -0.0261883210071453 0.0402405964564832 -0.110093336147283 0.993106314415928 0.259586594592784 3.89531422322573e-05 -3.42928627184503e-05 -2.12704249822934e-06 -5.50118329166057e-06 -6.44585301900044e-06 -1.70056245323105e-05 -3.42928627184503e-05 6.82934651240866e-05 2.0331781011663e-06 1.41960773168705e-05 8.96431564995809e-06 3.52645575802007e-05 -2.12704249822934e-06 2.0331781011663e-06 1.03215693830233e-05 -3.57913445221711e-06 4.22460904526731e-06 -3.27987148640527e-06 -5.50118329166057e-06 1.41960773168705e-05 -3.57913445221711e-06 4.51498840317963e-05 1.59907601146987e-06 1.82934075466762e-05 -6.44585301900044e-06 8.96431564995809e-06 4.22460904526731e-06 1.59907601146987e-06 2.28755159277214e-05 1.75564487489942e-05 -1.70056245323105e-05 3.52645575802007e-05 -3.27987148640527e-06 1.82934075466762e-05 1.75564487489942e-05 9.65951849870607e-05 818 819 0 105 0 818 819 0 125 0 0 0 0 0 0 0 0 0 2728 0 0 0 0 0 1662 +856 929 0.999072400978258 0.0319980086155906 -0.028817790480458 0.11662135790642 -0.0279659019170868 0.991009647557976 0.130834960071763 -0.0248108677594478 0.0327451665670351 -0.129907682188747 0.99098524114885 0.25029685394318 2.75947917691788e-05 -2.14291924483667e-05 -3.17570747256841e-06 -4.06400387788523e-07 -5.85973509551139e-06 -4.42905753337772e-06 -2.14291924483667e-05 6.12836492415245e-05 3.70023629675587e-06 1.7653204064717e-05 7.72853079034849e-06 1.88515424617405e-05 -3.17570747256841e-06 3.70023629675587e-06 9.59354245795172e-06 -3.3365940220884e-06 3.8403569849064e-06 -4.12991725129278e-06 -4.06400387788523e-07 1.7653204064717e-05 -3.3365940220884e-06 4.67376326531642e-05 4.00073660853528e-06 1.69100426511257e-05 -5.85973509551139e-06 7.72853079034849e-06 3.8403569849064e-06 4.00073660853528e-06 2.46294275167433e-05 5.73047126269253e-06 -4.42905753337772e-06 1.88515424617405e-05 -4.12991725129278e-06 1.69100426511257e-05 5.73047126269253e-06 5.63351446805127e-05 914 933 0 92 0 914 933 0 111 0 0 0 0 0 0 0 0 0 2911 0 0 0 0 0 1543 +856 900 0.99807367074628 0.0528828468371076 -0.0324399795537778 0.11703529266517 -0.0488830218574472 0.992314827034205 0.113673806227117 -0.0264971750758917 0.0382020671839998 -0.111869068819218 0.992988375311811 0.258223782312536 4.24800093556565e-05 -3.66693362841432e-05 3.56109318910516e-06 -1.41260057118639e-05 -1.25126689226094e-05 -2.13656723735634e-05 -3.66693362841432e-05 5.97801015015475e-05 -3.93490365356362e-06 2.17384951899828e-05 1.23871099439792e-05 3.92372100819914e-05 3.56109318910516e-06 -3.93490365356362e-06 1.18993634722534e-05 -6.86362910841683e-06 4.32657638488967e-06 -2.88799071967928e-06 -1.41260057118639e-05 2.17384951899828e-05 -6.86362910841683e-06 4.95319405616963e-05 1.03214693227758e-05 3.26563339214666e-05 -1.25126689226094e-05 1.23871099439792e-05 4.32657638488967e-06 1.03214693227758e-05 2.86408380383284e-05 2.35268487548054e-05 -2.13656723735634e-05 3.92372100819914e-05 -2.88799071967928e-06 3.26563339214666e-05 2.35268487548054e-05 9.9728207081648e-05 893 906 0 122 0 893 906 0 140 0 0 0 0 0 0 0 0 0 2706 0 0 0 0 0 1028 +856 899 0.998200270776464 0.0534585588058102 -0.0271735517038171 0.121866410684857 -0.0499763171953324 0.99201939162427 0.115757912736045 -0.0214670801578341 0.033144941414729 -0.114191545798364 0.992905687226533 0.266262285357852 7.09395985146906e-05 -5.44709694525089e-05 -3.42029733087724e-06 2.40730903731665e-06 -5.3060946101447e-06 -4.94194136132186e-05 -5.44709694525089e-05 0.000159425660216685 4.49275256758652e-06 2.89125240858305e-05 1.04092348107924e-05 0.000104785887528616 -3.42029733087724e-06 4.49275256758652e-06 1.14924183038279e-05 -1.8444370724e-06 3.86925033207703e-06 -1.85196092809001e-06 2.40730903731665e-06 2.89125240858305e-05 -1.8444370724e-06 5.65381542741101e-05 8.49517713488141e-06 2.37317529636814e-05 -5.3060946101447e-06 1.04092348107924e-05 3.86925033207703e-06 8.49517713488141e-06 2.95980637294538e-05 1.66665525787527e-05 -4.94194136132186e-05 0.000104785887528616 -1.85196092809001e-06 2.37317529636814e-05 1.66665525787527e-05 0.000170798045990736 841 863 0 122 0 841 863 0 142 0 0 0 0 0 0 0 0 0 2734 0 0 0 0 0 916 +856 897 0.998034405990524 0.052597752100097 -0.0340705288065652 0.114012332140606 -0.0483950371988069 0.992275910111111 0.114221007646111 -0.0261480864230088 0.0398151332242948 -0.112347651008749 0.992870968695907 0.259018934959512 4.86871946083254e-05 -4.89275252255874e-05 -1.75314190364399e-06 -1.57248954676598e-05 -1.21171542868353e-05 -2.3985471577682e-05 -4.89275252255874e-05 9.76067483705641e-05 1.16505568446749e-07 2.46933548326665e-05 1.29453150837541e-05 5.38898011688018e-05 -1.75314190364399e-06 1.16505568446749e-07 1.06217414236732e-05 -4.85865904388158e-06 3.40713512062475e-06 -6.67015673519957e-06 -1.57248954676598e-05 2.46933548326665e-05 -4.85865904388158e-06 4.78079199715268e-05 1.05988360727278e-05 3.71400369167403e-05 -1.21171542868353e-05 1.29453150837541e-05 3.40713512062475e-06 1.05988360727278e-05 2.6143522681261e-05 2.21635601705252e-05 -2.3985471577682e-05 5.38898011688018e-05 -6.67015673519957e-06 3.71400369167403e-05 2.21635601705252e-05 0.000110514044275234 861 877 0 117 0 861 877 0 137 0 0 0 0 0 0 0 0 0 2686 0 0 0 0 0 1041 +856 901 0.997859162222517 0.0527572669672731 -0.0386492322138627 0.112082269106059 -0.0483784552272119 0.993125233561427 0.106591723568905 -0.0296560096682323 0.0440070157861887 -0.104493737830097 0.993551428621533 0.247689423660162 9.30273601396624e-05 -7.4732715243798e-05 3.05341347020492e-06 -3.35552093896544e-05 -2.32098762248767e-05 -9.54187361815834e-05 -7.4732715243798e-05 0.000126603031470228 -3.76781329359235e-07 4.23398534580824e-05 1.80076217230339e-05 0.000106153078621107 3.05341347020492e-06 -3.76781329359235e-07 1.00911388788282e-05 -3.96860824005493e-06 2.37317198084123e-06 -4.80906762670773e-06 -3.35552093896544e-05 4.23398534580824e-05 -3.96860824005493e-06 6.43225834211385e-05 2.24903279748803e-05 6.89733224221779e-05 -2.32098762248767e-05 1.80076217230339e-05 2.37317198084123e-06 2.24903279748803e-05 3.3727426754137e-05 4.51991387734803e-05 -9.54187361815834e-05 0.000106153078621107 -4.80906762670773e-06 6.89733224221779e-05 4.51991387734803e-05 0.000239080756738349 820 837 0 119 0 820 837 0 135 0 0 0 0 0 0 0 0 0 2681 0 0 0 0 0 1215 +856 892 0.998147987881802 0.0525395120723606 -0.030662582388126 0.118551234262435 -0.0489751457484188 0.993024964039075 0.107251367796008 -0.0271023806440284 0.0360836443064096 -0.105551032521676 0.993759000033296 0.255795727700139 7.03307258687521e-05 -4.28613772567775e-05 1.70951170137837e-06 -1.17831517291043e-05 -1.66266902271843e-05 -6.60842352494433e-05 -4.28613772567775e-05 6.06767246961959e-05 2.46454581823743e-07 7.1598919314659e-06 9.32602547823899e-06 3.71867049955363e-05 1.70951170137837e-06 2.46454581823743e-07 1.00207280677088e-05 -4.8110100085647e-06 4.07729262711447e-06 -5.65779401383121e-06 -1.17831517291043e-05 7.1598919314659e-06 -4.8110100085647e-06 4.31448250617259e-05 7.95777512011164e-06 3.39230901300637e-05 -1.66266902271843e-05 9.32602547823899e-06 4.07729262711447e-06 7.95777512011164e-06 2.68214325532736e-05 3.28518331512552e-05 -6.60842352494433e-05 3.71867049955363e-05 -5.65779401383121e-06 3.39230901300637e-05 3.28518331512552e-05 0.000145286937573332 853 861 0 105 0 853 861 0 124 0 0 0 0 0 0 0 0 0 2731 0 0 0 0 0 1097 +856 891 0.998118459906617 0.052424631605363 -0.0317993395321991 0.119518072445154 -0.048683854860563 0.992874123773606 0.108769741273531 -0.0239320165249562 0.0372749549906871 -0.107016972213931 0.993558224458237 0.261894625833806 5.57006338742402e-05 -7.36338921159944e-05 -1.66125407242626e-06 -3.07482419818376e-05 -2.49621958554949e-05 -3.76339846582575e-05 -7.36338921159944e-05 0.000121409958478789 1.70425330505857e-06 4.92903978421304e-05 3.33072768216445e-05 6.44497650174402e-05 -1.66125407242626e-06 1.70425330505857e-06 1.10000580871129e-05 -8.99001182544179e-06 2.38908326367545e-06 -8.9622299723529e-06 -3.07482419818376e-05 4.92903978421304e-05 -8.99001182544179e-06 8.8721299828766e-05 3.0042299029707e-05 6.84138679772066e-05 -2.49621958554949e-05 3.33072768216445e-05 2.38908326367545e-06 3.0042299029707e-05 4.30072523210371e-05 4.23887114354705e-05 -3.76339846582575e-05 6.44497650174402e-05 -8.9622299723529e-06 6.84138679772066e-05 4.23887114354705e-05 0.000127956139344706 806 826 0 120 0 806 826 0 138 0 0 0 0 0 0 0 0 0 2581 0 0 0 0 0 1692 +856 893 0.998233611729072 0.0526311358825246 -0.0275612037118673 0.119569800380773 -0.0491420845891435 0.992172880241501 0.114795606342391 -0.0232597748879443 0.0333873020258493 -0.113238417725606 0.993006721434672 0.262643280500802 5.23670462755035e-05 -6.7439393352098e-05 -1.53415251592147e-06 -1.76932321934435e-05 -7.85653450369921e-06 -2.76616949612056e-05 -6.7439393352098e-05 0.000127773713616995 1.63174659005863e-06 4.54355327203122e-05 1.47339545318967e-05 5.95021167259034e-05 -1.53415251592147e-06 1.63174659005863e-06 9.72219172117192e-06 -3.87702707063598e-06 3.34768596812898e-06 -3.28244057563247e-06 -1.76932321934435e-05 4.54355327203122e-05 -3.87702707063598e-06 6.15137535498509e-05 1.40853130513056e-05 4.95851761887881e-05 -7.85653450369921e-06 1.47339545318967e-05 3.34768596812898e-06 1.40853130513056e-05 2.62711995547801e-05 2.90302665918143e-05 -2.76616949612056e-05 5.95021167259034e-05 -3.28244057563247e-06 4.95851761887881e-05 2.90302665918143e-05 0.000127645837571927 838 857 0 122 0 838 857 0 140 0 0 0 0 0 0 0 0 0 2672 0 0 0 0 0 1483 +856 925 0.998134785674282 0.0533663270060347 -0.0296476772924895 0.121461259483778 -0.049580537509719 0.991969238280929 0.116356351801698 -0.0198617179690474 0.0356190949801082 -0.114669374491353 0.992764934224895 0.267095795768989 4.11791795078949e-05 -4.51020036609199e-05 2.60321199528884e-06 -2.91888504286144e-05 -1.92157582207285e-05 -3.36906219497154e-05 -4.51020036609199e-05 6.90580934927787e-05 -3.42500268817709e-06 4.09599192183573e-05 2.47094275277852e-05 5.44504183562812e-05 2.60321199528884e-06 -3.42500268817709e-06 1.04034234546506e-05 -6.31710025118711e-06 2.37989916843933e-06 -6.54135610156125e-06 -2.91888504286144e-05 4.09599192183573e-05 -6.31710025118711e-06 7.40029266313432e-05 2.29485118794885e-05 6.75163304889423e-05 -1.92157582207285e-05 2.47094275277852e-05 2.37989916843933e-06 2.29485118794885e-05 3.42221172762829e-05 3.6572491576405e-05 -3.36906219497154e-05 5.44504183562812e-05 -6.54135610156125e-06 6.75163304889423e-05 3.6572491576405e-05 0.000122878899218762 789 811 0 129 0 789 811 0 151 0 0 0 0 0 0 0 0 0 2675 0 0 0 0 0 1642 +856 921 0.998107907031065 0.0526998769448698 -0.0316753672758826 0.11531208040522 -0.0488332302545383 0.992457855634114 0.112439852423611 -0.0273545390368515 0.037362033469469 -0.110680295265831 0.993153538328739 0.260101148655523 4.182656700083e-05 -4.01071747805665e-05 2.33339084550544e-06 -1.30613350310836e-05 -1.208244489247e-05 -2.00553501001266e-05 -4.01071747805665e-05 5.51595910559887e-05 -1.78959540491528e-06 1.62784727326075e-05 9.44044128847272e-06 2.58916506897016e-05 2.33339084550544e-06 -1.78959540491528e-06 9.84045286673319e-06 -2.78120822038504e-06 1.40390238252592e-06 -2.42970518044833e-06 -1.30613350310836e-05 1.62784727326075e-05 -2.78120822038504e-06 5.06609623282443e-05 3.87853104975581e-06 2.786370508931e-05 -1.208244489247e-05 9.44044128847272e-06 1.40390238252592e-06 3.87853104975581e-06 2.71067449833843e-05 2.34074701332135e-05 -2.00553501001266e-05 2.58916506897016e-05 -2.42970518044833e-06 2.786370508931e-05 2.34074701332135e-05 0.000105170190661542 833 850 0 113 0 833 850 0 130 0 0 0 0 0 0 0 0 0 2584 0 0 0 0 0 1610 +856 922 0.99814603262063 0.0521026433127188 -0.0314612797502524 0.11182535476629 -0.0481715069787598 0.99220968928533 0.114888808870594 -0.0267301501981982 0.0372021972347245 -0.113160271509643 0.992880027733851 0.264800716047841 3.76881493908381e-05 -3.58784660612182e-05 -1.88396221161433e-06 -7.9701249402459e-07 -5.19415085983647e-06 -1.5248434412994e-05 -3.58784660612182e-05 6.7376756057601e-05 2.572979400138e-06 1.3742932678419e-05 7.61284584317311e-06 3.47352071291931e-05 -1.88396221161433e-06 2.572979400138e-06 1.10691561066094e-05 -3.3514983030952e-06 2.77643116127177e-06 -4.71835450326813e-06 -7.9701249402459e-07 1.3742932678419e-05 -3.3514983030952e-06 5.72087168509118e-05 6.1767156644458e-06 1.93358013958649e-05 -5.19415085983647e-06 7.61284584317311e-06 2.77643116127177e-06 6.1767156644458e-06 2.5453472136414e-05 1.34581597492139e-05 -1.5248434412994e-05 3.47352071291931e-05 -4.71835450326813e-06 1.93358013958649e-05 1.34581597492139e-05 8.72842942181854e-05 865 874 0 114 0 865 874 0 133 0 0 0 0 0 0 0 0 0 2701 0 0 0 0 0 953 +856 923 0.998146816302454 0.0520830547395975 -0.0314688499037803 0.114586466264737 -0.0482551085603305 0.992523455042124 0.112109926808809 -0.0275092535369408 0.0370725990875375 -0.110383633751738 0.993197400216421 0.25911749841488 6.73364025097047e-05 -6.14499398439339e-05 5.18661066094658e-07 -1.66443573302602e-05 -1.77794104429322e-05 -5.42981029139579e-05 -6.14499398439339e-05 8.88716617606164e-05 9.05966894200267e-08 2.32314468655995e-05 1.63825351111994e-05 6.24848736309499e-05 5.18661066094658e-07 9.05966894200267e-08 1.01568840651967e-05 -4.6922847964614e-06 3.72273269106009e-06 -4.2110258254993e-06 -1.66443573302602e-05 2.32314468655995e-05 -4.6922847964614e-06 5.08319884350995e-05 9.30796945559302e-06 5.32871819521003e-05 -1.77794104429322e-05 1.63825351111994e-05 3.72273269106009e-06 9.30796945559302e-06 2.50162250464305e-05 3.23267507258499e-05 -5.42981029139579e-05 6.24848736309499e-05 -4.2110258254993e-06 5.32871819521003e-05 3.23267507258499e-05 0.000172197330961338 883 905 0 120 0 883 905 0 140 0 0 0 0 0 0 0 0 0 2686 0 0 0 0 0 986 +856 926 0.998022198928686 0.0528484408289756 -0.0340401637407389 0.115281745137039 -0.0487473007900968 0.992541923140384 0.111732857631348 -0.0260489357624534 0.0396911968984292 -0.10985250616501 0.993155091502851 0.260174171557689 2.8027940433963e-05 -2.74669022146044e-05 -2.66114808609876e-06 -3.49845900232635e-06 -6.38514199911641e-06 -1.10269944204473e-05 -2.74669022146044e-05 5.26755062668555e-05 2.36087357296708e-06 6.30602974405491e-06 6.59298246015082e-06 2.71286945273087e-05 -2.66114808609876e-06 2.36087357296708e-06 9.77901224696739e-06 -1.99219531215541e-06 1.58744852812639e-06 -3.79326972192866e-06 -3.49845900232635e-06 6.30602974405491e-06 -1.99219531215541e-06 3.8636498794668e-05 2.27662338547044e-06 2.2407519547374e-05 -6.38514199911641e-06 6.59298246015082e-06 1.58744852812639e-06 2.27662338547044e-06 2.49622506817419e-05 2.03373680994721e-05 -1.10269944204473e-05 2.71286945273087e-05 -3.79326972192866e-06 2.2407519547374e-05 2.03373680994721e-05 9.399949806752e-05 819 838 0 124 0 819 838 0 140 0 0 0 0 0 0 0 0 0 2676 0 0 0 0 0 1519 +856 928 0.998036978353295 0.0524198610133289 -0.0342687614420019 0.117552390193936 -0.0483660682933804 0.992755923631333 0.109983633022098 -0.0281369217321057 0.0397858426738158 -0.108110287513459 0.993342464841049 0.254157419057544 8.51248458294951e-05 -8.68872358772518e-05 -3.22300202084862e-06 -4.01710333439575e-05 -2.50815448755868e-05 -8.86522842725724e-05 -8.68872358772518e-05 0.000116728833688253 4.84646585300062e-06 4.22382102725634e-05 2.43416745713999e-05 9.78352414285591e-05 -3.22300202084862e-06 4.84646585300062e-06 1.03468239650157e-05 -4.94577800275262e-06 3.47475137868008e-06 -5.41411178817766e-06 -4.01710333439575e-05 4.22382102725634e-05 -4.94577800275262e-06 7.17155989294357e-05 1.82627280576206e-05 8.12104232071858e-05 -2.50815448755868e-05 2.43416745713999e-05 3.47475137868008e-06 1.82627280576206e-05 3.1839344279644e-05 4.9779420623062e-05 -8.86522842725724e-05 9.78352414285591e-05 -5.41411178817766e-06 8.12104232071858e-05 4.9779420623062e-05 0.000231233175423879 837 854 0 127 0 837 854 0 147 0 0 0 0 0 0 0 0 0 2671 0 0 0 0 0 1068 +856 890 0.997511599103639 0.0512198897128903 -0.048447214073669 0.119711774874562 -0.0469677730336212 0.995258974037258 0.0851680861271846 -0.0203733082306661 0.0525798245524156 -0.0826806960306011 0.995188054868994 0.26088355979919 5.04455958162927e-05 -6.25389089994299e-05 4.77026211000923e-06 -2.28048904759691e-05 -1.5784144302951e-05 -1.99979920816238e-05 -6.25389089994299e-05 9.61422162591421e-05 -5.11244421820298e-06 3.80040011169671e-05 2.41809115866723e-05 4.30187958485027e-05 4.77026211000923e-06 -5.11244421820298e-06 1.16139374112894e-05 -5.4289095650609e-06 3.78126223783171e-06 -3.55904094744598e-07 -2.28048904759691e-05 3.80040011169671e-05 -5.4289095650609e-06 6.62705365972086e-05 2.21531097700106e-05 5.59489863404497e-05 -1.5784144302951e-05 2.41809115866723e-05 3.78126223783171e-06 2.21531097700106e-05 3.76978829210349e-05 3.78294665381253e-05 -1.99979920816238e-05 4.30187958485027e-05 -3.55904094744598e-07 5.59489863404497e-05 3.78294665381253e-05 0.000110944638436333 825 837 0 106 0 825 837 0 121 0 0 0 0 0 0 0 0 0 2468 0 0 0 0 0 1237 +856 902 0.997950106591943 0.0530983368743837 -0.0357232609696226 0.117990955677629 -0.0489230895821663 0.992833514394311 0.109032765722859 -0.0258006758149856 0.0412567092587937 -0.107061567878557 0.993396046209426 0.253102085362921 6.97317117959817e-05 -3.91655785062361e-05 -1.51812724770002e-06 -5.54373384998903e-06 -5.62527580008703e-06 -4.83755178890781e-05 -3.91655785062361e-05 6.68314442775103e-05 2.85315704379158e-06 7.84679056693249e-06 2.07608642704222e-06 4.55836192457313e-05 -1.51812724770002e-06 2.85315704379158e-06 1.03615734759952e-05 -5.81867033936788e-06 2.7615848862465e-06 -1.58102989517633e-06 -5.54373384998903e-06 7.84679056693249e-06 -5.81867033936788e-06 4.58004779684099e-05 1.03937779979703e-05 2.27620989136325e-05 -5.62527580008703e-06 2.07608642704222e-06 2.7615848862465e-06 1.03937779979703e-05 2.95512923581085e-05 1.67178142992407e-05 -4.83755178890781e-05 4.55836192457313e-05 -1.58102989517633e-06 2.27620989136325e-05 1.67178142992407e-05 0.000138869367168106 858 877 0 120 0 858 877 0 139 0 0 0 0 0 0 0 0 0 2725 0 0 0 0 0 1086 +856 903 0.99810793452383 0.0527984755469076 -0.0315098717943611 0.117205703959111 -0.0489497882100088 0.992452653578049 0.112435086339114 -0.0256496957941962 0.037208457032908 -0.110679950243083 0.993159342371313 0.259248676106523 4.32762528095245e-05 -2.55803039604505e-05 -2.36847604516633e-06 -7.92665800497282e-06 -6.15733830912415e-06 -1.42205445799766e-05 -2.55803039604505e-05 7.50165631101141e-05 4.35483750887895e-06 1.80339038677816e-05 1.74517933207649e-06 4.12499731226415e-05 -2.36847604516633e-06 4.35483750887895e-06 1.06921941996612e-05 -5.17562903646485e-06 2.65288629732272e-06 -5.50320874514352e-06 -7.92665800497282e-06 1.80339038677816e-05 -5.17562903646485e-06 5.37269433628398e-05 7.77965168190384e-06 3.05975665650631e-05 -6.15733830912415e-06 1.74517933207649e-06 2.65288629732272e-06 7.77965168190384e-06 2.43662927988264e-05 1.49510151184846e-05 -1.42205445799766e-05 4.12499731226415e-05 -5.50320874514352e-06 3.05975665650631e-05 1.49510151184846e-05 9.03595614008782e-05 817 838 0 122 0 817 838 0 139 0 0 0 0 0 0 0 0 0 2709 0 0 0 0 0 1523 +856 920 0.998310980365878 0.0517947559770938 -0.0263151996798983 0.115071106526441 -0.0484919654392737 0.992347195335482 0.11355867733308 -0.0307826563730743 0.0319955585785887 -0.112090798744034 0.993182730955472 0.265147453771217 4.8007838456845e-05 -3.63737595484345e-05 -3.73066690270483e-06 6.74927480516883e-06 -6.00882495878158e-06 -1.46688266148924e-05 -3.63737595484345e-05 0.00010052468915164 5.69308692415995e-06 4.65508427978996e-06 5.9406501654386e-07 5.77051007009129e-05 -3.73066690270483e-06 5.69308692415995e-06 1.19863814374472e-05 -2.04945913199404e-06 2.35941207696988e-06 -2.71135315017598e-06 6.74927480516883e-06 4.65508427978996e-06 -2.04945913199404e-06 5.06042763747769e-05 -5.08422397100284e-06 6.59242698778216e-06 -6.00882495878158e-06 5.9406501654386e-07 2.35941207696988e-06 -5.08422397100284e-06 2.64280835935478e-05 6.92934506395664e-06 -1.46688266148924e-05 5.77051007009129e-05 -2.71135315017598e-06 6.59242698778216e-06 6.92934506395664e-06 0.000122264938090399 859 874 0 124 0 859 874 0 143 0 0 0 0 0 0 0 0 0 2498 0 0 0 0 0 1026 +856 924 0.998029960513762 0.0526403162728633 -0.0341349530480297 0.116725273600532 -0.0485925303376525 0.992724569279339 0.110166671659517 -0.0285814130382571 0.0396858150008614 -0.10829093522472 0.993326788844373 0.256473207698002 2.58918910143716e-05 -2.00947897697546e-05 -3.44207469969558e-06 1.14496988213664e-06 -4.03310930250442e-06 1.00923353376499e-06 -2.00947897697546e-05 5.29571133303108e-05 6.28479887129032e-06 5.77125446060363e-07 1.5695091362361e-06 2.49551979781389e-05 -3.44207469969558e-06 6.28479887129032e-06 1.04069107123554e-05 -4.60468949362376e-06 3.72471582298611e-06 5.89402371740121e-08 1.14496988213664e-06 5.77125446060363e-07 -4.60468949362376e-06 4.13181214917458e-05 1.96886354842172e-06 9.75393568182253e-06 -4.03310930250442e-06 1.5695091362361e-06 3.72471582298611e-06 1.96886354842172e-06 2.08745117287522e-05 2.17763478723448e-06 1.00923353376499e-06 2.49551979781389e-05 5.89402371740121e-08 9.75393568182253e-06 2.17763478723448e-06 6.74723186850212e-05 812 830 0 115 0 812 830 0 135 0 0 0 0 0 0 0 0 0 2695 0 0 0 0 0 1491 +856 927 0.998113008276503 0.0529809768962586 -0.0310393105005239 0.120297894418181 -0.0492020259994265 0.992497080910388 0.111931698021205 -0.0251169431752146 0.0367366757720615 -0.110193286871191 0.99323101853584 0.257754231223987 6.49216609414698e-05 -7.67526521629564e-05 -9.47018542392278e-07 -2.90456991780555e-05 -1.82865166927306e-05 -4.81787597628916e-05 -7.67526521629564e-05 0.000128784237145386 8.74966771221351e-07 4.75027414964552e-05 2.40214251934332e-05 8.57757706599771e-05 -9.47018542392278e-07 8.74966771221351e-07 9.71064606667137e-06 -4.05788922493972e-06 3.01967691864961e-06 -4.03464526894811e-06 -2.90456991780555e-05 4.75027414964552e-05 -4.05788922493972e-06 6.70695186382927e-05 2.05914636426393e-05 6.93624497466734e-05 -1.82865166927306e-05 2.40214251934332e-05 3.01967691864961e-06 2.05914636426393e-05 3.13453430469013e-05 3.81923848571339e-05 -4.81787597628916e-05 8.57757706599771e-05 -4.03464526894811e-06 6.93624497466734e-05 3.81923848571339e-05 0.000141543128802875 818 839 0 127 0 818 839 0 145 0 0 0 0 0 0 0 0 0 2682 0 0 0 0 0 1513 +856 918 0.998089796991815 0.0523749739802045 -0.0327661294847484 0.117125726962545 -0.0486692442478766 0.993263109904152 0.105165104325878 -0.0327404254481566 0.0380534072742367 -0.103369514868288 0.993914826124812 0.250164262635614 4.60787321470242e-05 -4.68895632040391e-05 -3.15075072580275e-06 5.4961720188428e-07 -5.7897688750073e-06 -1.90595708550664e-05 -4.68895632040391e-05 0.000102729783164272 7.34356739292102e-06 1.18522340423695e-05 -4.14090182455194e-06 7.03000715940663e-05 -3.15075072580275e-06 7.34356739292102e-06 1.18991439362703e-05 -4.97471813978159e-06 1.28930991715821e-07 -3.01225663202184e-07 5.4961720188428e-07 1.18522340423695e-05 -4.97471813978159e-06 5.30655233619433e-05 6.02614645569813e-06 3.74044293858197e-05 -5.7897688750073e-06 -4.14090182455194e-06 1.28930991715821e-07 6.02614645569813e-06 3.44449441438483e-05 7.774393424909e-06 -1.90595708550664e-05 7.03000715940663e-05 -3.01225663202184e-07 3.74044293858197e-05 7.774393424909e-06 0.000148690873120682 859 880 0 126 0 859 880 0 146 0 0 0 0 0 0 0 0 0 2432 0 0 0 0 0 965 +857 859 0.999819002405235 -0.000514933723680559 -0.0190183404286674 0.027376249335997 0.000646040979146631 0.999976067193037 0.00688822707236152 -0.0121765458303595 0.0190143382859812 -0.00689926694710151 0.999795406598339 0.06486283809551 2.5534085908145e-05 -2.23233791065978e-05 -1.87888046630823e-06 -1.66824743471596e-06 -2.51377573031079e-06 3.48060726184952e-08 -2.23233791065978e-05 5.8153323198105e-05 2.20961328970867e-06 1.5602059491207e-05 6.28885917191075e-06 2.19772275769264e-05 -1.87888046630823e-06 2.20961328970867e-06 1.09098368423516e-05 1.90976364354628e-06 3.54565371783197e-07 -1.95556202724756e-06 -1.66824743471596e-06 1.5602059491207e-05 1.90976364354628e-06 5.69286205219795e-05 1.15191624571065e-05 9.31949444686724e-06 -2.51377573031079e-06 6.28885917191075e-06 3.54565371783197e-07 1.15191624571065e-05 2.94587997953023e-05 6.90113984604136e-06 3.48060726184952e-08 2.19772275769264e-05 -1.95556202724756e-06 9.31949444686724e-06 6.90113984604136e-06 5.53707024756917e-05 1351 1351 0 20 0 1345 1353 0 23 0 0 0 0 0 0 32 27 0 3476 0 0 0 0 0 1856 +857 932 0.979716249725653 -0.200376822400704 -0.00228014650836981 0.0982535349158189 0.199859196720469 0.976231384872584 0.0838366547281431 0.0222291356316446 -0.014572971891552 -0.0825918412093685 0.996476902018253 0.00233437004453012 3.45095525413121e-05 -2.74110772987415e-05 -2.25120649061818e-06 -8.56109678466786e-06 -6.66634267300285e-06 1.31772614720237e-05 -2.74110772987415e-05 4.82715717706083e-05 2.77740832190816e-06 2.26753002395782e-05 2.75748781212331e-06 2.39919556124665e-06 -2.25120649061818e-06 2.77740832190816e-06 1.16792213220807e-05 -1.51605749141071e-06 2.72157985742686e-06 -4.66645852647645e-07 -8.56109678466786e-06 2.26753002395782e-05 -1.51605749141071e-06 7.5262928545354e-05 3.84113925147453e-06 9.8545795773283e-06 -6.66634267300285e-06 2.75748781212331e-06 2.72157985742686e-06 3.84113925147453e-06 2.87262292876975e-05 -3.8816220323346e-06 1.31772614720237e-05 2.39919556124665e-06 -4.66645852647645e-07 9.8545795773283e-06 -3.8816220323346e-06 6.38736728229091e-05 1227 1227 0 0 0 1245 1245 0 0 0 0 0 0 0 0 503 503 0 3135 0 0 0 0 0 668 +857 931 0.990540366573243 -0.124815329037477 0.0570168030164065 0.0830263137204418 0.119086916753174 0.988354197685112 0.0947327091159144 -0.00141514771535758 -0.068176890858765 -0.0870466171398074 0.993868601977821 0.0862956390473234 2.77519250282047e-05 -2.75193274830093e-05 -3.73406628713908e-06 2.3249428126086e-06 -1.36966242953408e-06 4.2339117365042e-06 -2.75193274830093e-05 4.79555300302773e-05 3.75632111571688e-06 5.76449144330837e-06 1.95617290278421e-06 1.05140292070642e-05 -3.73406628713908e-06 3.75632111571688e-06 1.09501821347664e-05 -4.46190619190377e-06 1.76510081987231e-06 -4.51097333821491e-06 2.3249428126086e-06 5.76449144330837e-06 -4.46190619190377e-06 5.26574522522665e-05 6.32201671049774e-06 7.370222875619e-06 -1.36966242953408e-06 1.95617290278421e-06 1.76510081987231e-06 6.32201671049774e-06 2.46285552549537e-05 1.1810701178629e-06 4.2339117365042e-06 1.05140292070642e-05 -4.51097333821491e-06 7.370222875619e-06 1.1810701178629e-06 4.35363708860311e-05 1320 1320 0 0 0 1320 1320 0 0 0 0 0 0 0 0 235 245 0 3351 0 0 0 0 0 599 +857 860 0.999838901869021 -0.0175099317487899 0.0039462133118375 0.0486464068109808 0.0175665564815119 0.999736109970896 -0.0148029224696645 -0.00253844112553763 -0.00368597378336534 0.0148698591255521 0.99988264355716 0.0948674327837799 2.93183377340633e-05 -2.29115620513706e-05 8.28637590678328e-07 -5.05606996392608e-06 -4.3563862154786e-06 -5.45383491388352e-06 -2.29115620513706e-05 6.00508481190389e-05 3.01264926044692e-07 1.56235615088233e-05 5.66651963137315e-06 2.49125178065216e-05 8.28637590678328e-07 3.01264926044692e-07 1.27652851707069e-05 -2.51783272548262e-06 2.05616615136351e-06 8.71306111931537e-07 -5.05606996392608e-06 1.56235615088233e-05 -2.51783272548262e-06 6.53002112126675e-05 1.67347145567466e-05 9.0446488930971e-06 -4.3563862154786e-06 5.66651963137315e-06 2.05616615136351e-06 1.67347145567466e-05 3.57070252709519e-05 7.1813251043554e-06 -5.45383491388352e-06 2.49125178065216e-05 8.71306111931537e-07 9.0446488930971e-06 7.1813251043554e-06 5.498865717784e-05 1289 1281 0 1 0 1291 1292 0 10 0 0 0 0 0 0 48 53 0 3113 0 0 0 0 0 1711 +857 861 0.999491571130595 -0.0205117964012079 -0.0244103553290397 0.0674835569797759 0.019862629401124 0.999450250408283 -0.0265456759585104 0.0119483243625064 0.0249414352467573 0.0260473255290447 0.99934951925771 0.129222617403924 2.30713141668345e-05 -2.56482185713517e-05 -1.21837172122621e-06 -4.16367808979999e-06 -6.9458435706412e-06 -6.87414866156245e-06 -2.56482185713517e-05 8.15705915989516e-05 1.415576507824e-06 2.26353273124184e-05 1.59504990378769e-05 4.02064281903754e-05 -1.21837172122621e-06 1.415576507824e-06 9.46906099969736e-06 3.34900773483856e-06 1.3675294711442e-06 -2.5118445908226e-06 -4.16367808979999e-06 2.26353273124184e-05 3.34900773483856e-06 5.05714881871734e-05 8.06232419214488e-06 1.64774127819792e-05 -6.9458435706412e-06 1.59504990378769e-05 1.3675294711442e-06 8.06232419214488e-06 2.72715778375625e-05 7.44191347545043e-06 -6.87414866156245e-06 4.02064281903754e-05 -2.5118445908226e-06 1.64774127819792e-05 7.44191347545043e-06 6.17446577901648e-05 996 991 0 1 0 995 998 0 8 0 0 0 0 0 0 66 65 0 2742 0 0 0 0 0 2308 +857 933 0.9562763719316 -0.287933726194138 -0.0512803062129753 0.0995865848038897 0.290525929379034 0.955376275183607 0.0533934188336416 0.0541116994642881 0.0336182219010124 -0.0659571234686253 0.997255971664226 -0.0900829033030022 2.13100466922738e-05 -1.78227486540459e-05 -2.45169281378734e-06 -4.54190902700853e-07 -1.28514336562169e-06 1.25123732728831e-05 -1.78227486540459e-05 2.90175999707063e-05 3.14156347919371e-06 4.01421541626703e-06 2.06796679160033e-07 -2.88660802888644e-06 -2.45169281378734e-06 3.14156347919371e-06 1.0438895017602e-05 -2.47879622250218e-06 3.72475480620703e-06 -2.23921415131955e-06 -4.54190902700853e-07 4.01421541626703e-06 -2.47879622250218e-06 5.72099894621661e-05 6.56790698450933e-06 5.95035003128338e-06 -1.28514336562169e-06 2.06796679160033e-07 3.72475480620703e-06 6.56790698450933e-06 1.7522327043659e-05 1.63498772895941e-06 1.25123732728831e-05 -2.88660802888644e-06 -2.23921415131955e-06 5.95035003128338e-06 1.63498772895941e-06 4.64744068326782e-05 1477 1477 0 0 0 1475 1475 0 0 0 0 0 0 0 0 712 709 0 3087 0 0 0 0 0 1368 +857 929 0.999670125332838 0.00830526435253141 0.0243035614892654 0.0853231968237493 -0.0109848132898599 0.993615196871124 0.112286127476838 -0.0158403887869002 -0.0232158220620087 -0.112516057213148 0.993378660167004 0.191098504998535 2.2569005834208e-05 -1.50801935424081e-05 -1.22663680338883e-06 7.85335146329294e-06 -3.98989159487261e-06 5.7402459327944e-06 -1.50801935424081e-05 6.79041636051462e-05 4.76789353070213e-06 9.38066731435741e-06 -1.26839137621895e-07 1.49976081079205e-05 -1.22663680338883e-06 4.76789353070213e-06 1.00763405691821e-05 -7.87804978309689e-07 3.00441311770061e-06 -1.7176558687421e-06 7.85335146329294e-06 9.38066731435741e-06 -7.87804978309689e-07 3.86798296377703e-05 -4.86454563753269e-06 5.70232378250592e-06 -3.98989159487261e-06 -1.26839137621895e-07 3.00441311770061e-06 -4.86454563753269e-06 2.50356073212795e-05 1.80949980172586e-07 5.7402459327944e-06 1.49976081079205e-05 -1.7176558687421e-06 5.70232378250592e-06 1.80949980172586e-07 3.47239306070921e-05 888 907 0 55 0 888 907 0 66 0 0 0 0 0 0 2 4 0 3015 0 0 0 0 0 1427 +857 895 0.999408772350901 0.0299377114114711 0.0169067792174471 0.0797068523086597 -0.0313532621754356 0.99537337495425 0.0908230002980756 -0.0175589350553252 -0.014109525116829 -0.0912993859104721 0.995723527608617 0.193740255962031 4.13001057431879e-05 -4.31072476882773e-05 -3.77574607057645e-06 -9.13804638880943e-06 -4.83906753414837e-06 -2.38727564024351e-05 -4.31072476882773e-05 7.34578620086136e-05 6.55519926289837e-06 1.45635498987336e-05 5.22700060589187e-06 4.29878993269029e-05 -3.77574607057645e-06 6.55519926289837e-06 1.15994334005915e-05 -4.96368800707817e-06 2.36222023430737e-06 1.61852786146965e-06 -9.13804638880943e-06 1.45635498987336e-05 -4.96368800707817e-06 7.03487855212954e-05 2.01346608970844e-05 2.55438471815797e-05 -4.83906753414837e-06 5.22700060589187e-06 2.36222023430737e-06 2.01346608970844e-05 3.10115978382067e-05 1.51353573860984e-05 -2.38727564024351e-05 4.29878993269029e-05 1.61852786146965e-06 2.55438471815797e-05 1.51353573860984e-05 9.1407835614308e-05 866 887 0 80 0 866 887 0 89 0 0 0 0 0 0 2 3 0 2862 0 0 0 0 0 978 +857 894 0.999239852851437 0.0303907026916963 0.0244156028666755 0.090428514297239 -0.0325597070020199 0.995039908099429 0.0939970572381059 -0.0118087593967866 -0.0214378626122313 -0.0947205705186897 0.995273043725807 0.199747392114675 4.29015879688551e-05 -4.92926107799543e-05 2.01976415178574e-06 -2.21321927751134e-05 -1.33512983185848e-05 -2.29322386122318e-05 -4.92926107799543e-05 0.000133498586701502 1.66523806561822e-06 5.16259985850178e-05 2.51611928487058e-05 5.25038713340269e-05 2.01976415178574e-06 1.66523806561822e-06 9.84989615381523e-06 -2.28327044203626e-06 3.66452673969263e-06 1.03444219061516e-06 -2.21321927751134e-05 5.16259985850178e-05 -2.28327044203626e-06 7.19588667828246e-05 1.92401675579098e-05 4.22694121049296e-05 -1.33512983185848e-05 2.51611928487058e-05 3.66452673969263e-06 1.92401675579098e-05 3.22812177948624e-05 2.08940234381188e-05 -2.29322386122318e-05 5.25038713340269e-05 1.03444219061516e-06 4.22694121049296e-05 2.08940234381188e-05 7.48097540268938e-05 852 871 0 81 0 852 871 0 90 0 0 0 0 0 0 0 1 0 2821 0 0 0 0 0 1614 +857 900 0.999346516663219 0.0298253261067516 0.020420322125664 0.0851895143626102 -0.0315537807773694 0.995411342837334 0.0903361360111714 -0.0188653461267491 -0.0176323155525211 -0.0909214412193354 0.995701959913133 0.19425759473728 5.55684091254813e-05 -5.80096122099268e-05 -9.29627888002123e-07 -9.35426509118502e-06 -1.16162784949011e-05 -4.58452151377903e-05 -5.80096122099268e-05 0.000148584804038934 5.97495417866108e-06 3.25432126398669e-05 5.69348565117322e-06 7.81738180437839e-05 -9.29627888002123e-07 5.97495417866108e-06 9.84867424033313e-06 -5.15494431055116e-07 2.06967060077888e-06 1.83306575896666e-06 -9.35426509118502e-06 3.25432126398669e-05 -5.15494431055116e-07 5.28023760601859e-05 8.91400948467049e-06 3.27236122811033e-05 -1.16162784949011e-05 5.69348565117322e-06 2.06967060077888e-06 8.91400948467049e-06 3.19671621789695e-05 1.78826592052024e-05 -4.58452151377903e-05 7.81738180437839e-05 1.83306575896666e-06 3.27236122811033e-05 1.78826592052024e-05 0.000114016535920649 856 874 0 73 0 856 874 0 81 0 0 0 0 0 0 0 0 0 2851 0 0 0 0 0 1398 +857 898 0.999198878853684 0.0308752414548004 0.0254621280070878 0.0943176121628752 -0.0332141497657268 0.994707472342959 0.0972309864211026 -0.00725603003126418 -0.0223253388077632 -0.0979987955547849 0.994936086046199 0.202656161273498 5.71274877434722e-05 -8.3390779310099e-05 -3.28811617355954e-06 -2.81246682219931e-05 -1.21406093694529e-05 -4.51835660711583e-05 -8.3390779310099e-05 0.000167614761407456 7.82219824509873e-06 5.9658134530563e-05 2.32483338555362e-05 0.000106005153574926 -3.28811617355954e-06 7.82219824509873e-06 1.12146782816073e-05 -3.17732346575537e-06 4.53137661820033e-06 8.70576562004961e-07 -2.81246682219931e-05 5.9658134530563e-05 -3.17732346575537e-06 8.68353809929462e-05 2.75201603159387e-05 7.04008167642314e-05 -1.21406093694529e-05 2.32483338555362e-05 4.53137661820033e-06 2.75201603159387e-05 3.56241882555929e-05 3.05857175999915e-05 -4.51835660711583e-05 0.000106005153574926 8.70576562004961e-07 7.04008167642314e-05 3.05857175999915e-05 0.000129897142721053 867 881 0 84 0 867 881 0 87 0 0 0 0 0 0 0 0 0 2913 0 0 0 0 0 928 +857 899 0.999271141076567 0.0302369663768291 0.0233004823096664 0.0896475571876272 -0.0323276341255914 0.99492321958851 0.0953032591020626 -0.0116822145116737 -0.0203005094364271 -0.0959870459382905 0.99517555050788 0.198988140569817 2.95913157791666e-05 -2.03228076668356e-05 -2.78972904669502e-07 -3.62979115113261e-06 -4.90196271542289e-06 1.11849034604028e-06 -2.03228076668356e-05 0.00012252706324332 3.70653296574639e-06 4.39302395224046e-05 1.33949258455904e-05 4.86278040551152e-05 -2.78972904669502e-07 3.70653296574639e-06 1.01103029467695e-05 -2.49826452990539e-06 2.34651577011626e-06 8.00924570231473e-07 -3.62979115113261e-06 4.39302395224046e-05 -2.49826452990539e-06 6.72144259024076e-05 1.95372034913104e-05 2.61777600114202e-05 -4.90196271542289e-06 1.33949258455904e-05 2.34651577011626e-06 1.95372034913104e-05 3.29556230834748e-05 1.12870703711936e-05 1.11849034604028e-06 4.86278040551152e-05 8.00924570231473e-07 2.61777600114202e-05 1.12870703711936e-05 5.3890964790098e-05 856 876 0 85 0 856 876 0 89 0 0 0 0 0 0 0 0 0 2942 0 0 0 0 0 1629 +857 897 0.999396956190432 0.0304380546119751 0.016710738725102 0.0832314456852931 -0.0318263753495428 0.995406057155391 0.0902987442352851 -0.0165853912483167 -0.0138854524380813 -0.0907761323795954 0.995774516645607 0.195728230707372 5.30640715248543e-05 -6.54074468724581e-05 -2.56822668438756e-06 -1.31642258364088e-05 -1.3366744360816e-05 -4.32155425856793e-05 -6.54074468724581e-05 0.000135227998836151 4.83324679213155e-06 2.66047292556994e-05 1.69412922479028e-05 8.50100195578435e-05 -2.56822668438756e-06 4.83324679213155e-06 1.03496028651952e-05 -2.46948570188541e-06 4.24065486643385e-06 6.15803873528753e-07 -1.31642258364088e-05 2.66047292556994e-05 -2.46948570188541e-06 5.48882088676029e-05 7.08259565510955e-06 2.78366582200292e-05 -1.3366744360816e-05 1.69412922479028e-05 4.24065486643385e-06 7.08259565510955e-06 2.83102373826159e-05 1.67754603449185e-05 -4.32155425856793e-05 8.50100195578435e-05 6.15803873528753e-07 2.78366582200292e-05 1.67754603449185e-05 0.000115723244161312 886 893 0 75 0 886 893 0 79 0 0 0 0 0 0 0 0 0 2821 0 0 0 0 0 1348 +857 896 0.999207554751846 0.0302724978502832 0.0258425695460466 0.0904236868482207 -0.0325603842484877 0.995108985959007 0.0932626797879348 -0.0130475304636803 -0.0228928789021496 -0.0940302182148943 0.995306100733855 0.198489759822111 5.24346072572725e-05 -5.07933246019083e-05 -3.03654988993624e-06 -1.10220073247349e-05 -1.31494947441877e-05 -2.84437227400141e-05 -5.07933246019083e-05 8.77608829405833e-05 5.84549707618192e-06 1.27431281323069e-05 1.29633190919203e-05 4.62219818353963e-05 -3.03654988993624e-06 5.84549707618192e-06 1.08546880742207e-05 -1.79746232344873e-06 3.77201021492857e-06 2.02491975262576e-06 -1.10220073247349e-05 1.27431281323069e-05 -1.79746232344873e-06 5.10283102630409e-05 8.02591586227289e-06 2.39702590575329e-05 -1.31494947441877e-05 1.29633190919203e-05 3.77201021492857e-06 8.02591586227289e-06 2.81356827597433e-05 1.63133599893297e-05 -2.84437227400141e-05 4.62219818353963e-05 2.02491975262576e-06 2.39702590575329e-05 1.63133599893297e-05 8.99328445797784e-05 857 874 0 77 0 857 874 0 80 0 0 0 0 0 0 0 0 0 2842 0 0 0 0 0 857 +857 922 0.999346031139958 0.0301085108485991 0.0200246752606358 0.0885359614703236 -0.0318651355145319 0.995050346197088 0.0941245009107439 -0.0124899234764152 -0.0170916114937898 -0.0947010354089959 0.995359026034832 0.200263994789118 2.53315081066178e-05 -2.26030569526118e-05 -9.9758106855284e-07 -1.48615800033616e-06 -3.85362545461735e-06 -6.18584411579708e-06 -2.26030569526118e-05 8.83430155157632e-05 4.43759697826882e-06 1.90365813152773e-05 3.96922246896676e-06 3.6421147763501e-05 -9.9758106855284e-07 4.43759697826882e-06 9.07427046269845e-06 -2.05355152820833e-06 3.3567709204164e-06 -4.98141446314657e-07 -1.48615800033616e-06 1.90365813152773e-05 -2.05355152820833e-06 4.48279162808888e-05 3.24107852794932e-06 1.40943787307008e-05 -3.85362545461735e-06 3.96922246896676e-06 3.3567709204164e-06 3.24107852794932e-06 2.2663042447164e-05 5.55868757755397e-06 -6.18584411579708e-06 3.6421147763501e-05 -4.98141446314657e-07 1.40943787307008e-05 5.55868757755397e-06 5.11855574190204e-05 871 890 0 81 0 871 890 0 88 0 0 0 0 0 0 0 0 0 2896 0 0 0 0 0 1575 +857 930 0.996432161250546 -0.0527364909601052 0.065892416458802 0.0755633627605885 0.0453395668909925 0.992995507834487 0.10910657677091 -0.0128507590802989 -0.0711847715435168 -0.105729768474844 0.991843709643083 0.14398645097616 3.34240188403127e-05 -3.58817201024211e-05 -3.6572543432395e-06 -6.00412469996285e-06 -5.72499235427062e-06 -1.46218240330483e-05 -3.58817201024211e-05 9.12527288967052e-05 1.07979003759175e-05 1.97418059451546e-05 4.76126150952615e-06 4.28777600914005e-05 -3.6572543432395e-06 1.07979003759175e-05 1.33820497907459e-05 -2.30426175630606e-06 3.31901064896381e-06 1.64729002399349e-06 -6.00412469996285e-06 1.97418059451546e-05 -2.30426175630606e-06 5.30975969533801e-05 5.08754148789689e-07 2.33526606555225e-05 -5.72499235427062e-06 4.76126150952615e-06 3.31901064896381e-06 5.08754148789689e-07 2.46770039617223e-05 5.01871699633526e-06 -1.46218240330483e-05 4.28777600914005e-05 1.64729002399349e-06 2.33526606555225e-05 5.01871699633526e-06 6.3489016232399e-05 1141 1141 0 0 0 1148 1148 0 0 0 0 0 0 0 0 70 85 0 3197 0 0 0 0 0 1063 +857 893 0.999290083314932 0.0299072780277775 0.0229103493950825 0.0852445837553277 -0.0318887253528528 0.995279546308389 0.0916609725866849 -0.0147096898345936 -0.0200608719602579 -0.0923264827724737 0.995526685727238 0.196948898450888 3.00788404042353e-05 -2.78270099756722e-05 -1.00000623355383e-06 -5.7270352447566e-06 -5.20421287219161e-06 -1.02830851819673e-05 -2.78270099756722e-05 5.68373814131587e-05 3.25044187453984e-06 1.11035404026123e-05 4.08301886731332e-06 2.801315825822e-05 -1.00000623355383e-06 3.25044187453984e-06 9.52134070750921e-06 -6.97932808027039e-07 2.73441530548306e-06 5.76344313446723e-07 -5.7270352447566e-06 1.11035404026123e-05 -6.97932808027039e-07 6.2989913203195e-05 1.77528574648309e-05 1.67237228858707e-05 -5.20421287219161e-06 4.08301886731332e-06 2.73441530548306e-06 1.77528574648309e-05 3.15368207923651e-05 8.18512239306923e-06 -1.02830851819673e-05 2.801315825822e-05 5.76344313446723e-07 1.67237228858707e-05 8.18512239306923e-06 5.72478237533595e-05 901 918 0 74 0 901 918 0 82 0 0 0 0 0 0 0 0 0 2814 0 0 0 0 0 1522 +857 891 0.999318752840948 0.0292615426903101 0.022489827473676 0.0846042221960443 -0.0310409784390343 0.996037881004857 0.0833366501660656 -0.0231345132766989 -0.0199621611545433 -0.083977983559603 0.996267639943857 0.191008261330452 4.37035825565542e-05 -4.30814472922732e-05 -6.36501745939912e-06 -3.83192986991749e-06 -8.78927553399019e-06 -1.50310263723697e-05 -4.30814472922732e-05 8.23767942035412e-05 1.09710803210526e-05 5.02492609083648e-06 1.82377908571179e-06 3.09043056161508e-05 -6.36501745939912e-06 1.09710803210526e-05 1.39178823891326e-05 -1.03288166238163e-05 -1.98961076867714e-06 -8.2629619629871e-07 -3.83192986991749e-06 5.02492609083648e-06 -1.03288166238163e-05 8.32283452871271e-05 3.33870013153729e-05 1.80186732417417e-05 -8.78927553399019e-06 1.82377908571179e-06 -1.98961076867714e-06 3.33870013153729e-05 5.05255953388252e-05 9.20927950224754e-06 -1.50310263723697e-05 3.09043056161508e-05 -8.2629619629871e-07 1.80186732417417e-05 9.20927950224754e-06 7.58453306269381e-05 893 912 0 82 0 893 912 0 94 0 0 0 0 0 0 0 0 0 2828 0 0 0 0 0 1195 +857 892 0.999035605688438 0.0301461410731458 0.0319228561556289 0.0951929638663142 -0.0331071315140734 0.994762788731228 0.0967001137464704 -0.00825392456837749 -0.0288405341428489 -0.0976637309038952 0.994801497413573 0.204160117279436 3.0210626400078e-05 -3.71534768114469e-05 -1.79328663791496e-06 -5.99023015842586e-06 -4.71573850196759e-06 -3.47563788992929e-06 -3.71534768114469e-05 0.000113836106045156 6.35551163048033e-06 3.19436193517373e-05 1.02705978048009e-05 2.99123446503047e-05 -1.79328663791496e-06 6.35551163048033e-06 1.0518575304987e-05 -3.03260162207763e-06 4.35054400628056e-06 5.51713519377098e-07 -5.99023015842586e-06 3.19436193517373e-05 -3.03260162207763e-06 5.42828631216908e-05 7.73595631379979e-06 1.16417089380203e-05 -4.71573850196759e-06 1.02705978048009e-05 4.35054400628056e-06 7.73595631379979e-06 2.36990735295836e-05 4.04285392097008e-06 -3.47563788992929e-06 2.99123446503047e-05 5.51713519377098e-07 1.16417089380203e-05 4.04285392097008e-06 4.80218542737239e-05 865 887 0 83 0 865 887 0 91 0 0 0 0 0 0 1 0 0 2932 0 0 0 0 0 1590 +857 901 0.999280490650195 0.0308144669362139 0.0221126577629954 0.0913364819200586 -0.0327769506084243 0.994966379006127 0.0946972869529448 -0.00972079575613572 -0.0190833046068886 -0.0953539368608996 0.995260495654484 0.200209413708446 3.3817319293279e-05 -2.91941524582068e-05 -1.59905619737582e-06 2.50158299855194e-06 -2.60445744437271e-06 5.37887677712832e-06 -2.91941524582068e-05 0.000103775706494894 5.46188029430251e-06 2.22607147126631e-05 4.4937861232892e-06 2.26161870454098e-05 -1.59905619737582e-06 5.46188029430251e-06 1.01030937794712e-05 -2.94401864909654e-06 3.68666568702025e-06 -1.08182635869023e-06 2.50158299855194e-06 2.22607147126631e-05 -2.94401864909654e-06 4.98389749766322e-05 4.81812225566118e-06 1.29728665750369e-05 -2.60445744437271e-06 4.4937861232892e-06 3.68666568702025e-06 4.81812225566118e-06 2.26045189933469e-05 9.85248946322487e-07 5.37887677712832e-06 2.26161870454098e-05 -1.08182635869023e-06 1.29728665750369e-05 9.85248946322487e-07 4.71152182491539e-05 885 904 0 77 0 885 904 0 86 0 0 0 0 0 0 0 0 0 2843 0 0 0 0 0 1617 +857 921 0.999356338088556 0.0300024852764502 0.0196662248402592 0.0839579984193691 -0.0316670710535365 0.995378701595252 0.0906555956432958 -0.0188975668089538 -0.0168554481732617 -0.0912200158286922 0.995688105070605 0.194932612714258 4.96740381218428e-05 -6.65262064111872e-05 -1.39210047874314e-08 -2.23718913591086e-05 -1.17022374956977e-05 -4.73541261050493e-05 -6.65262064111872e-05 0.000144776818509914 3.96538354110427e-06 4.0537896281445e-05 1.50978726776549e-05 0.000101068949278538 -1.39210047874314e-08 3.96538354110427e-06 1.05747999423727e-05 -3.13617908661955e-06 2.53989238593829e-06 2.26273140421568e-06 -2.23718913591086e-05 4.0537896281445e-05 -3.13617908661955e-06 6.556808300894e-05 1.79435533330513e-05 5.26323134465599e-05 -1.17022374956977e-05 1.50978726776549e-05 2.53989238593829e-06 1.79435533330513e-05 3.47607459878421e-05 2.53345213479888e-05 -4.73541261050493e-05 0.000101068949278538 2.26273140421568e-06 5.26323134465599e-05 2.53345213479888e-05 0.000135634042640695 853 873 0 79 0 853 873 0 93 0 0 0 0 0 0 0 1 0 2785 0 0 0 0 0 935 +857 902 0.999142239906617 0.0299904167641854 0.0285544976614517 0.0920259032948042 -0.0325732534133376 0.994967056033115 0.0947604377937672 -0.0112108463789743 -0.0255688794525273 -0.0956092689602133 0.995090498443451 0.199500165941577 3.97160924487498e-05 -3.76365705762257e-05 -1.77882951025575e-06 -1.19084801813373e-05 -9.67834060666368e-06 -8.08917814207535e-06 -3.76365705762257e-05 9.92657355541771e-05 6.25375118759271e-06 1.85816172752378e-05 3.54007298221157e-06 3.36039387847212e-05 -1.77882951025575e-06 6.25375118759271e-06 9.68293653822114e-06 -2.54116734766682e-06 2.7365601825236e-06 -1.20484782837966e-06 -1.19084801813373e-05 1.85816172752378e-05 -2.54116734766682e-06 5.34125101454384e-05 1.20215794064908e-05 2.23677596623122e-05 -9.67834060666368e-06 3.54007298221157e-06 2.7365601825236e-06 1.20215794064908e-05 2.69216074813653e-05 7.04277774171034e-06 -8.08917814207535e-06 3.36039387847212e-05 -1.20484782837966e-06 2.23677596623122e-05 7.04277774171034e-06 6.05526461253319e-05 868 879 0 74 0 868 879 0 78 0 0 0 0 0 0 0 0 0 2908 0 0 0 0 0 1662 +857 923 0.999296398096331 0.0301864150236058 0.0222595844462983 0.0906210494809928 -0.032142553868482 0.995099542341674 0.0935080588088663 -0.0122100074604601 -0.0193278292239711 -0.0941577462528352 0.995369656880335 0.200865433107015 3.23391211804793e-05 -3.11670298947662e-05 1.10743715432107e-06 -2.11507386325687e-06 -4.55821601071429e-06 -1.05176672064029e-05 -3.11670298947662e-05 8.30621897246345e-05 7.90761643827563e-07 1.85988444154675e-05 9.24097340708992e-06 3.11127813379372e-05 1.10743715432107e-06 7.90761643827563e-07 8.4392369933735e-06 -6.6430708867733e-07 3.60120268862029e-06 8.26736942479876e-07 -2.11507386325687e-06 1.85988444154675e-05 -6.6430708867733e-07 3.76734102298036e-05 2.00183060478677e-06 1.7268747555314e-05 -4.55821601071429e-06 9.24097340708992e-06 3.60120268862029e-06 2.00183060478677e-06 2.11715661153471e-05 9.16820811740778e-06 -1.05176672064029e-05 3.11127813379372e-05 8.26736942479876e-07 1.7268747555314e-05 9.16820811740778e-06 5.16727432345881e-05 855 875 0 81 0 855 875 0 89 0 0 0 0 0 0 1 1 0 2792 0 0 0 0 0 1616 +857 925 0.999303536172369 0.0300331164592393 0.0221462075567015 0.0897791772157971 -0.0319546429738392 0.995224198715024 0.0922371675868955 -0.0124770110066711 -0.0192702720741873 -0.092880601891807 0.995490758574083 0.198477323075857 3.52001996765496e-05 -2.89871162646875e-05 7.74008626248575e-07 -1.14527984924475e-05 -1.22286272947305e-05 -2.41385008595811e-05 -2.89871162646875e-05 6.49784156933883e-05 2.4372958994476e-06 1.90215207859527e-05 9.45445553568526e-06 3.73960815258332e-05 7.74008626248575e-07 2.4372958994476e-06 1.07549631313762e-05 -2.04732315216238e-06 3.14025927400618e-06 -7.02056837981962e-07 -1.14527984924475e-05 1.90215207859527e-05 -2.04732315216238e-06 4.77167387979607e-05 4.96519903847549e-06 2.85294198768005e-05 -1.22286272947305e-05 9.45445553568526e-06 3.14025927400618e-06 4.96519903847549e-06 2.72888620811338e-05 1.56045994104713e-05 -2.41385008595811e-05 3.73960815258332e-05 -7.02056837981962e-07 2.85294198768005e-05 1.56045994104713e-05 7.34144124204464e-05 844 865 0 81 0 844 865 0 91 0 0 0 0 0 0 1 2 0 2819 0 0 0 0 0 929 +857 927 0.999181232347661 0.0304562728968684 0.0266323180636195 0.0950830336580802 -0.0328497979038794 0.994971997347572 0.0946129762340146 -0.00995487159339658 -0.0236168520739872 -0.0954103764556844 0.995157828870727 0.198531750186533 3.41214506305502e-05 -3.84561429892763e-05 -3.09160690240081e-06 -5.41156648551209e-06 -6.43562392027729e-06 -9.80826555008391e-06 -3.84561429892763e-05 7.52815341481651e-05 4.87908424515895e-06 1.11774894228e-05 9.57583087766377e-06 2.96683398609528e-05 -3.09160690240081e-06 4.87908424515895e-06 1.05221242530699e-05 -3.49490110381548e-06 5.02653846035756e-06 -2.94645190038726e-06 -5.41156648551209e-06 1.11774894228e-05 -3.49490110381548e-06 4.12129223402773e-05 4.56341664117957e-06 2.07467864645255e-05 -6.43562392027729e-06 9.57583087766377e-06 5.02653846035756e-06 4.56341664117957e-06 2.35147768054536e-05 7.58878442737631e-06 -9.80826555008391e-06 2.96683398609528e-05 -2.94645190038726e-06 2.07467864645255e-05 7.58878442737631e-06 7.5769355410104e-05 862 877 0 72 0 862 877 0 79 0 0 0 0 0 0 0 0 0 2885 0 0 0 0 0 1517 +857 926 0.999200306813299 0.0300942297225824 0.0263264923910021 0.0917579772652627 -0.0324319790824209 0.995098813867994 0.0934158304106377 -0.0135233030521864 -0.0233861838914874 -0.0941949466580668 0.995279055555314 0.198049875593342 4.19178542033177e-05 -4.41236871462884e-05 -1.60524974942681e-06 -1.2930301991598e-05 -1.11736294222859e-05 -1.66497321049891e-05 -4.41236871462884e-05 9.00868900654545e-05 5.35752844823423e-06 2.72414712140338e-05 1.64990010278345e-05 3.63146222815591e-05 -1.60524974942681e-06 5.35752844823423e-06 1.02634812615092e-05 -1.81417804377288e-06 3.73959566350337e-06 -8.91429715237743e-09 -1.2930301991598e-05 2.72414712140338e-05 -1.81417804377288e-06 5.53589748924591e-05 1.40842157100884e-05 2.9948354234402e-05 -1.11736294222859e-05 1.64990010278345e-05 3.73959566350337e-06 1.40842157100884e-05 3.08338262213634e-05 1.42892184924197e-05 -1.66497321049891e-05 3.63146222815591e-05 -8.91429715237743e-09 2.9948354234402e-05 1.42892184924197e-05 7.46314007219097e-05 871 885 0 71 0 871 885 0 85 0 0 0 0 0 0 0 0 0 2846 0 0 0 0 0 1539 +857 924 0.999301996507685 0.0301558685005482 0.0220486591595041 0.0908691555015837 -0.0320508920969514 0.995302207679205 0.0913578442427967 -0.014427430155362 -0.0191901040003414 -0.0920007553440686 0.995574005749737 0.19783740511886 4.6475856596056e-05 -6.05331536396003e-05 -2.14926025239411e-06 -1.35128474555215e-05 -8.56141814113364e-06 -2.62202737763159e-05 -6.05331536396003e-05 0.000126698767539466 5.32672694465849e-06 3.57955252990729e-05 1.08985202816794e-05 6.81744249526424e-05 -2.14926025239411e-06 5.32672694465849e-06 1.00450967450633e-05 -2.26398692923478e-06 5.04257024977413e-06 1.31365991407798e-06 -1.35128474555215e-05 3.57955252990729e-05 -2.26398692923478e-06 5.41541015449199e-05 5.72885089365e-06 3.81248364435275e-05 -8.56141814113364e-06 1.08985202816794e-05 5.04257024977413e-06 5.72885089365e-06 2.58128765363e-05 1.39212508634515e-05 -2.62202737763159e-05 6.81744249526424e-05 1.31365991407798e-06 3.81248364435275e-05 1.39212508634515e-05 9.59013283865809e-05 830 847 0 81 0 830 847 0 87 0 0 0 0 0 0 1 1 0 2831 0 0 0 0 0 1489 +857 890 0.999502308662768 0.0305835399783947 0.00773188593987153 0.0955099792338658 -0.0310247722143639 0.997372636425306 0.0654621082694553 -0.0061208716016422 -0.00570950845906053 -0.0656694083453246 0.997825100065503 0.19659701845645 3.55269731546702e-05 -3.41032184212412e-05 1.21380828104813e-06 -8.04027863994141e-06 -8.63179788957125e-06 -1.118632492461e-05 -3.41032184212412e-05 6.18629652973825e-05 1.28405661207551e-06 1.3744762863233e-05 1.22671083254388e-05 2.25135949132782e-05 1.21380828104813e-06 1.28405661207551e-06 1.04103464603734e-05 -3.37633597456729e-06 4.26705982583505e-06 -5.87695469717742e-07 -8.04027863994141e-06 1.3744762863233e-05 -3.37633597456729e-06 5.10945366192342e-05 8.22300091405668e-06 1.82263232034395e-05 -8.63179788957125e-06 1.22671083254388e-05 4.26705982583505e-06 8.22300091405668e-06 2.58839400333708e-05 1.34764575932417e-05 -1.118632492461e-05 2.25135949132782e-05 -5.87695469717742e-07 1.82263232034395e-05 1.34764575932417e-05 5.86117011419389e-05 830 850 0 77 0 830 850 0 81 0 0 0 0 0 0 4 2 0 2659 0 0 0 0 0 1247 +857 918 0.999327113536716 0.029791669212803 0.0213957144281507 0.0869047971672315 -0.031587235494381 0.995515141704963 0.0891731416401314 -0.0195886762070123 -0.0186431409424101 -0.0897889697104457 0.99578630951331 0.195187752995987 7.16906318282788e-05 -9.05841708024222e-05 -4.03836862065935e-06 -2.19027554381788e-05 -1.45968833745677e-05 -6.33173418890658e-05 -9.05841708024222e-05 0.000191004740012053 1.17821625201222e-05 3.92111282841359e-05 1.3078590042336e-05 0.000136583072300053 -4.03836862065935e-06 1.17821625201222e-05 1.11052796943347e-05 -3.83873223889969e-06 8.4736772935962e-07 5.97842435445279e-06 -2.19027554381788e-05 3.92111282841359e-05 -3.83873223889969e-06 6.35630267278429e-05 1.76117573568431e-05 4.39967648619353e-05 -1.45968833745677e-05 1.3078590042336e-05 8.4736772935962e-07 1.76117573568431e-05 3.78499558083501e-05 1.60279690723207e-05 -6.33173418890658e-05 0.000136583072300053 5.97842435445279e-06 4.39967648619353e-05 1.60279690723207e-05 0.000178908914543991 867 888 0 83 0 867 888 0 94 0 0 0 0 0 0 0 1 0 2568 0 0 0 0 0 1563 +857 903 0.999276944301039 0.0306132665163535 0.0225480930807207 0.091378355599995 -0.0325761340194506 0.995174081178191 0.0925599462159004 -0.0126062675035668 -0.0196057155116799 -0.0932275499213741 0.995451776760147 0.197654789720835 5.07679597949794e-05 -5.77681350174009e-05 -4.694745610501e-06 -1.18691568706886e-05 -1.0525394867059e-05 -3.60461311106771e-05 -5.77681350174009e-05 0.000149461516923675 9.65488093195726e-06 3.76513441639297e-05 1.32503240485214e-05 8.51785499620603e-05 -4.694745610501e-06 9.65488093195726e-06 1.07783611512814e-05 -5.66915913314564e-07 3.28750565220968e-06 1.27768383196083e-06 -1.18691568706886e-05 3.76513441639297e-05 -5.66915913314564e-07 5.59509300325775e-05 8.3657444712817e-06 3.16613250165734e-05 -1.0525394867059e-05 1.32503240485214e-05 3.28750565220968e-06 8.3657444712817e-06 2.58940638696398e-05 1.71519211481964e-05 -3.60461311106771e-05 8.51785499620603e-05 1.27768383196083e-06 3.16613250165734e-05 1.71519211481964e-05 0.000102791368668931 847 868 0 83 0 847 868 0 90 0 0 0 0 0 0 1 1 0 2841 0 0 0 0 0 1494 +857 928 0.999274609280214 0.0300658542383533 0.0233730540750166 0.0914282515642743 -0.0321345993668768 0.995066825531282 0.0938582987840032 -0.0134750459218378 -0.0204358207910981 -0.0945412985737714 0.995311167471047 0.200125907000848 2.64044803405557e-05 -2.46421538974573e-05 -9.4864311582531e-07 -1.99139358235005e-06 -3.33800022323796e-06 6.09124409571521e-06 -2.46421538974573e-05 7.52092509948245e-05 4.82258349656862e-06 1.266625161865e-05 -4.21514001313455e-07 5.86245400092524e-06 -9.4864311582531e-07 4.82258349656862e-06 1.02161314064531e-05 -3.47434881139745e-06 2.14418308685852e-06 -2.11239824076296e-06 -1.99139358235005e-06 1.266625161865e-05 -3.47434881139745e-06 4.95100047844585e-05 6.03254120172268e-06 1.61870288990823e-05 -3.33800022323796e-06 -4.21514001313455e-07 2.14418308685852e-06 6.03254120172268e-06 2.62419685534871e-05 6.07306398981038e-06 6.09124409571521e-06 5.86245400092524e-06 -2.11239824076296e-06 1.61870288990823e-05 6.07306398981038e-06 3.60958725044744e-05 897 916 0 73 0 897 916 0 81 0 0 0 0 0 0 1 1 0 2809 0 0 0 0 0 1628 +858 860 0.999064538040144 -0.0283388080916427 0.0326643656999469 0.0228895953053778 0.0288922353782225 0.999444732542784 -0.0165971481686771 0.00155635237965663 -0.0321758848438424 0.0175253687102064 0.999328561528233 0.0531012666052928 2.62922198785721e-05 -2.76688177182051e-05 8.4905280350249e-07 -3.96069564195873e-06 9.05952500227952e-08 7.1199559410839e-06 -2.76688177182051e-05 8.24282107973276e-05 1.85029914658121e-06 1.88668197533729e-05 1.31601234773343e-06 2.32048824004462e-05 8.4905280350249e-07 1.85029914658121e-06 1.06011888391273e-05 9.00737063473787e-07 1.44706744593133e-06 8.96112358352421e-07 -3.96069564195873e-06 1.88668197533729e-05 9.00737063473787e-07 4.78180214278095e-05 5.62294051057062e-06 5.42463376698002e-06 9.05952500227952e-08 1.31601234773343e-06 1.44706744593133e-06 5.62294051057062e-06 3.00854804860486e-05 2.3552052503488e-06 7.1199559410839e-06 2.32048824004462e-05 8.96112358352421e-07 5.42463376698002e-06 2.3552052503488e-06 4.16854048080503e-05 1281 1264 0 0 0 1288 1288 0 3 0 0 0 0 0 0 103 114 0 3009 0 0 0 0 0 2082 +857 920 0.999359531896895 0.0296557942076925 0.0200264793892902 0.0868952444911706 -0.0313533170886169 0.995395551571488 0.090579608186581 -0.0186109743756609 -0.0172480582779428 -0.0911494913952069 0.995687839990042 0.1959911703701 4.44467123901952e-05 -3.94498673326235e-05 -3.9171944554702e-06 -1.19925835857165e-05 -5.31193008103768e-06 -2.52704020595414e-05 -3.94498673326235e-05 7.81520210906422e-05 6.33542140436086e-06 1.36031896677917e-05 3.6745524832113e-06 5.31800512079098e-05 -3.9171944554702e-06 6.33542140436086e-06 1.21595679334712e-05 -3.67156251768727e-06 2.25210283039731e-06 -2.99890004763466e-06 -1.19925835857165e-05 1.36031896677917e-05 -3.67156251768727e-06 4.74394999543228e-05 2.47982010222666e-06 2.75531129380667e-05 -5.31193008103768e-06 3.6745524832113e-06 2.25210283039731e-06 2.47982010222666e-06 2.82358063141864e-05 1.1925492825546e-05 -2.52704020595414e-05 5.31800512079098e-05 -2.99890004763466e-06 2.75531129380667e-05 1.1925492825546e-05 0.000112246410273296 881 893 0 68 0 881 893 0 74 0 0 0 0 0 0 1 1 0 2644 0 0 0 0 0 1342 +858 861 0.999498684230725 -0.031371218920519 -0.00426929086494444 0.0324772814018374 0.0312398673168248 0.999120437998206 -0.027971790509361 0.0120872734911083 0.0051430449225931 0.027824395729526 0.999599595883877 0.0789965644658813 2.95776355246338e-05 -3.90937138384532e-05 -2.4571121259076e-07 -4.95710264678016e-06 -2.1839615996068e-06 -5.05192219762865e-06 -3.90937138384532e-05 0.000123837836010605 1.80313456420354e-07 3.69185600378223e-05 1.18158349810044e-05 4.0340489200433e-05 -2.4571121259076e-07 1.80313456420354e-07 1.14095779329209e-05 9.4816724568614e-07 -2.16379389998215e-06 -2.32545879348458e-06 -4.95710264678016e-06 3.69185600378223e-05 9.4816724568614e-07 6.36200268711757e-05 1.36911168601851e-05 1.04663729179123e-05 -2.1839615996068e-06 1.18158349810044e-05 -2.16379389998215e-06 1.36911168601851e-05 2.81532762836861e-05 6.65360582647164e-06 -5.05192219762865e-06 4.0340489200433e-05 -2.32545879348458e-06 1.04663729179123e-05 6.65360582647164e-06 4.3010542258952e-05 1132 1120 0 0 0 1141 1141 0 2 0 0 0 0 0 0 69 79 0 2719 0 0 0 0 0 1362 +857 919 0.999117827494417 0.0302497912387416 0.0291293136350481 0.0965730143376313 -0.0328638246418538 0.995039554439302 0.0938949100385371 -0.0109033861108574 -0.0261445178334948 -0.0947693791857267 0.995155881737131 0.202898597622348 3.9803920409551e-05 -3.7653523098906e-05 -2.00097805896234e-06 -3.48221319609495e-07 -4.62808391505828e-06 -2.85916739842273e-06 -3.7653523098906e-05 0.000183876907652638 9.48042212307074e-06 4.87838372175776e-05 7.8786936810081e-06 5.64932172735368e-05 -2.00097805896234e-06 9.48042212307074e-06 1.00042899155582e-05 -2.24716754158946e-06 2.30697703041157e-06 3.19632775864438e-07 -3.48221319609495e-07 4.87838372175776e-05 -2.24716754158946e-06 6.30305117637807e-05 9.01778191333842e-06 3.15657962067133e-05 -4.62808391505828e-06 7.8786936810081e-06 2.30697703041157e-06 9.01778191333842e-06 2.93860044663473e-05 8.8121395348562e-06 -2.85916739842273e-06 5.64932172735368e-05 3.19632775864438e-07 3.15657962067133e-05 8.8121395348562e-06 6.57680409349504e-05 874 893 0 77 0 874 893 0 86 0 0 0 0 0 0 0 0 0 2649 0 0 0 0 0 1607 +857 916 0.999256443824259 0.030404627430565 0.0237090300625023 0.092041721199463 -0.032506279043118 0.995043200971415 0.093980689630005 -0.0113311689790427 -0.0207340613114519 -0.0946815020548835 0.995291671757663 0.200975248721255 3.39142570270461e-05 -3.53313550355144e-05 -1.94825750010422e-06 -5.09411609214153e-06 -6.44236511102549e-06 1.68407323086202e-06 -3.53313550355144e-05 0.000116722856761645 6.08863423049976e-06 2.81849719640605e-05 6.47432292144452e-06 3.63785836315039e-05 -1.94825750010422e-06 6.08863423049976e-06 1.03864298608923e-05 -3.35972779841106e-06 2.46682730557484e-06 -3.70922477986878e-07 -5.09411609214153e-06 2.81849719640605e-05 -3.35972779841106e-06 6.91729748982408e-05 1.83999508703412e-05 2.51515957898871e-05 -6.44236511102549e-06 6.47432292144452e-06 2.46682730557484e-06 1.83999508703412e-05 3.39654155792927e-05 8.23777678567507e-06 1.68407323086202e-06 3.63785836315039e-05 -3.70922477986878e-07 2.51515957898871e-05 8.23777678567507e-06 5.1020505308695e-05 874 887 0 70 0 874 887 0 77 0 0 0 0 0 0 0 0 0 2751 0 0 0 0 0 1606 +858 932 0.976785735892392 -0.213353071048691 0.0192378073400031 0.0652330002193501 0.211017403574647 0.973768365978565 0.0851282844185828 0.0313051190443282 -0.0368955491322964 -0.0790925817857055 0.996184261048476 -0.0481930149477321 2.74560271619581e-05 -2.26323203256288e-05 -1.08934591971719e-06 -8.06085693120134e-07 -4.13577532611378e-06 9.88723785523934e-06 -2.26323203256288e-05 5.4499533862419e-05 1.25380697929744e-06 1.4718477770431e-05 2.87190775761405e-06 7.41457399473809e-06 -1.08934591971719e-06 1.25380697929744e-06 1.01207607427959e-05 -7.12891599347509e-07 3.11104566654914e-06 -2.73408127874404e-06 -8.06085693120134e-07 1.4718477770431e-05 -7.12891599347509e-07 5.72852175620638e-05 4.75399924983234e-07 9.85984561432633e-06 -4.13577532611378e-06 2.87190775761405e-06 3.11104566654914e-06 4.75399924983234e-07 2.61054228738194e-05 -1.54139449016274e-07 9.88723785523934e-06 7.41457399473809e-06 -2.73408127874404e-06 9.85984561432633e-06 -1.54139449016274e-07 3.90070500339018e-05 1165 1165 0 0 0 1185 1185 0 0 0 0 0 0 0 0 467 465 0 3035 0 0 0 0 0 1412 +858 896 0.998513578233439 0.0164851305495512 0.05195069349121 0.0681368116707936 -0.0211975956408034 0.995578812666967 0.0915067741081541 -0.00518196783178555 -0.0502125086258632 -0.0924719862412179 0.994448407780968 0.1502391897408 3.10612099630036e-05 -3.22635199601282e-05 -1.89810326577269e-06 -5.0970045679495e-06 -5.79182616425057e-06 -5.22571683137149e-06 -3.22635199601282e-05 7.00653995716651e-05 4.71797698021203e-06 2.6193470254065e-05 1.35204608677936e-05 2.20582445843336e-05 -1.89810326577269e-06 4.71797698021203e-06 1.00945152122643e-05 1.88803073800588e-06 2.27752933924974e-06 9.33360168565533e-07 -5.0970045679495e-06 2.6193470254065e-05 1.88803073800588e-06 5.44036739482551e-05 9.12445339512726e-06 1.2609000768551e-05 -5.79182616425057e-06 1.35204608677936e-05 2.27752933924974e-06 9.12445339512726e-06 3.1931959583363e-05 8.5482823408934e-06 -5.22571683137149e-06 2.20582445843336e-05 9.33360168565533e-07 1.2609000768551e-05 8.5482823408934e-06 4.04035986891623e-05 854 868 0 44 0 854 868 0 62 0 0 0 0 0 0 7 5 0 2841 0 0 0 0 0 2046 +858 930 0.99389677459642 -0.0669806966543945 0.0876515129505773 0.046809162861861 0.0570253107757905 0.992123470544977 0.111530861759041 -0.00397256302578855 -0.0944315380461303 -0.105851809004295 0.989887912418755 0.0983174098876589 2.43719385769284e-05 -2.32825783968166e-05 -1.37235354463088e-06 -2.17621999659248e-06 7.66939087641505e-07 -6.41858266501571e-06 -2.32825783968166e-05 7.94084387779242e-05 5.40729321774493e-06 1.90123176187384e-05 -5.27766256010476e-07 3.0614205089056e-05 -1.37235354463088e-06 5.40729321774493e-06 1.07569195747185e-05 -5.54317182825076e-07 3.72690415700878e-06 8.28702177216827e-07 -2.17621999659248e-06 1.90123176187384e-05 -5.54317182825076e-07 4.85646710714239e-05 -3.52216484385513e-06 1.32633565954448e-05 7.66939087641505e-07 -5.27766256010476e-07 3.72690415700878e-06 -3.52216484385513e-06 2.19305903314161e-05 -1.37771480708458e-06 -6.41858266501571e-06 3.0614205089056e-05 8.28702177216827e-07 1.32633565954448e-05 -1.37771480708458e-06 3.89901545925867e-05 1052 1052 0 0 0 1083 1083 0 0 0 0 0 0 0 0 100 114 0 3087 0 0 0 0 0 1293 +858 929 0.998791287757095 -0.00545459701856184 0.0488488574266448 0.0632149652531132 -2.58512282451211e-06 0.99381758618771 0.111025246576401 -0.00676703096685084 -0.0491524515547365 -0.110891175281889 0.992616332603268 0.140251783327027 2.30240403053603e-05 -2.06163986014984e-05 -1.7914577254807e-06 3.4715513286526e-06 -5.04994529158828e-06 -6.35643144798939e-07 -2.06163986014984e-05 8.0540908762122e-05 5.88893559022942e-06 1.58357439872351e-05 2.33495582901624e-06 2.97961001970394e-05 -1.7914577254807e-06 5.88893559022942e-06 1.08341130894676e-05 -1.10996193557114e-06 3.94367615563974e-06 -2.1497291154104e-07 3.4715513286526e-06 1.58357439872351e-05 -1.10996193557114e-06 4.06352058600732e-05 -7.60539172784692e-06 1.14556563910171e-05 -5.04994529158828e-06 2.33495582901624e-06 3.94367615563974e-06 -7.60539172784692e-06 2.4274054563322e-05 1.27123865719801e-06 -6.35643144798939e-07 2.97961001970394e-05 -2.1497291154104e-07 1.14556563910171e-05 1.27123865719801e-06 3.8766038001986e-05 859 865 0 20 0 859 877 0 45 0 0 0 0 0 0 12 30 0 2985 0 0 0 0 0 1398 +858 862 0.998336631237223 -0.0300788621872801 -0.0491856968989122 0.0223623003560938 0.0296331027906311 0.99951312220397 -0.00976717774343352 0.00585812151100201 0.0494555350685133 0.00829340651304031 0.998741893313531 0.0967920494668171 2.47882951135143e-05 -2.39181196953571e-05 2.38836675557501e-06 -7.81425162569932e-06 -4.67351767304343e-06 2.40999558641844e-06 -2.39181196953571e-05 4.39621346708533e-05 -1.37305273058294e-06 2.39870008871518e-05 1.01018452007359e-05 6.49305089717797e-06 2.38836675557501e-06 -1.37305273058294e-06 1.09160562227783e-05 1.19068405624048e-06 2.18670021712982e-06 4.56255634878696e-07 -7.81425162569932e-06 2.39870008871518e-05 1.19068405624048e-06 6.18803593861244e-05 1.42498981801914e-05 1.21689854309575e-05 -4.67351767304343e-06 1.01018452007359e-05 2.18670021712982e-06 1.42498981801914e-05 2.99376313497502e-05 6.06758145109715e-06 2.40999558641844e-06 6.49305089717797e-06 4.56255634878696e-07 1.21689854309575e-05 6.06758145109715e-06 3.36031942158157e-05 1085 1079 0 0 0 1086 1090 0 8 0 0 0 0 0 0 57 64 0 2705 0 0 0 0 0 2092 +858 897 0.999047600538671 0.01659133961511 0.0403561557596911 0.0585876836218504 -0.0202575229504503 0.99553408601558 0.092203667741773 -0.00865900956557171 -0.0386461462740639 -0.092933368769777 0.994922039331356 0.149113521255862 2.95927412001319e-05 -2.2728017636765e-05 -9.40495303285795e-07 7.4466606406706e-07 -9.07108156179864e-06 -5.69567119482e-06 -2.2728017636765e-05 7.05357045370231e-05 4.60316321959224e-06 9.83237629093954e-06 8.43594977067148e-06 3.31141489402477e-05 -9.40495303285795e-07 4.60316321959224e-06 1.09332665119211e-05 -4.16663804566845e-06 1.33200389547459e-06 -1.40241740262386e-06 7.4466606406706e-07 9.83237629093954e-06 -4.16663804566845e-06 5.48526722288244e-05 4.11692643649392e-06 7.06964221376844e-06 -9.07108156179864e-06 8.43594977067148e-06 1.33200389547459e-06 4.11692643649392e-06 3.31659464703018e-05 8.37760286166242e-06 -5.69567119482e-06 3.31141489402477e-05 -1.40241740262386e-06 7.06964221376844e-06 8.37760286166242e-06 4.50810093136321e-05 890 892 0 28 0 891 893 0 54 0 0 0 0 0 0 8 7 0 2837 0 0 0 0 0 1601 +858 931 0.987176777175504 -0.137631586918466 0.0808675267810925 0.0576568587064304 0.130096017982876 0.98721831560953 0.0920598904522614 0.00949538821132665 -0.0925042523908235 -0.0803588427454496 0.992464316578801 0.0427706991635845 3.22062765796894e-05 -2.9975997365083e-05 -4.5130291974826e-06 7.08578696675754e-06 -2.46328337188081e-06 5.70885853458948e-06 -2.9975997365083e-05 5.62218469411021e-05 4.53523111693425e-06 6.32359242572234e-06 2.82259758110239e-06 1.15361297655073e-05 -4.5130291974826e-06 4.53523111693425e-06 1.05324377286568e-05 -2.68612076870905e-06 4.0141497557679e-06 -4.15613349494947e-06 7.08578696675754e-06 6.32359242572234e-06 -2.68612076870905e-06 4.92057486086614e-05 -5.59153954392032e-06 9.30188567882057e-06 -2.46328337188081e-06 2.82259758110239e-06 4.0141497557679e-06 -5.59153954392032e-06 2.32979588571585e-05 6.54359305214192e-07 5.70885853458948e-06 1.15361297655073e-05 -4.15613349494947e-06 9.30188567882057e-06 6.54359305214192e-07 3.87037597203269e-05 1143 1143 0 0 0 1159 1159 0 0 0 0 0 0 0 0 251 258 0 3148 0 0 0 0 0 1509 +858 899 0.998746788908276 0.0167286278284271 0.0471699550178483 0.0625872342841312 -0.0210820703578043 0.995409122331871 0.0933607277602422 -0.00462451455093664 -0.045391606656258 -0.0942381673711423 0.99451433868783 0.150716038727616 3.27997599983263e-05 -2.58261267142555e-05 -5.34279309153334e-07 -7.30705392920985e-06 -4.87579759907963e-06 -1.56458182585649e-06 -2.58261267142555e-05 8.368846184367e-05 2.54068067610163e-06 2.67437800011532e-05 1.15705451695621e-05 3.79742511494465e-05 -5.34279309153334e-07 2.54068067610163e-06 1.20727269732834e-05 -2.04212475462718e-06 1.18830131618831e-06 -5.08092378747635e-08 -7.30705392920985e-06 2.67437800011532e-05 -2.04212475462718e-06 5.30006870343802e-05 8.81271478211944e-06 1.64791241423055e-05 -4.87579759907963e-06 1.15705451695621e-05 1.18830131618831e-06 8.81271478211944e-06 2.95722919390108e-05 1.36037690244305e-05 -1.56458182585649e-06 3.79742511494465e-05 -5.08092378747635e-08 1.64791241423055e-05 1.36037690244305e-05 5.03915963499975e-05 877 892 0 44 0 878 893 0 66 0 0 0 0 0 0 9 10 0 2953 0 0 0 0 0 775 +858 892 0.998258375504462 0.0163097011210459 0.0566939977822591 0.0695843137861906 -0.0215996279682699 0.995339382850411 0.0939838763756537 -0.00193164729247885 -0.0548969198300322 -0.095044761014503 0.993958158876354 0.154024935201596 2.58226574714919e-05 -3.04192733117613e-05 -1.52467740938488e-06 -1.51710416439672e-06 -3.12473972828963e-06 -7.92286474480916e-07 -3.04192733117613e-05 9.23864568154096e-05 6.38677300402738e-06 6.06872433661345e-06 4.26332826937678e-07 3.25353922299131e-05 -1.52467740938488e-06 6.38677300402738e-06 1.20573834203942e-05 -2.17349280983027e-06 5.2871005084622e-07 -5.52899508710042e-07 -1.51710416439672e-06 6.06872433661345e-06 -2.17349280983027e-06 4.8358026188729e-05 5.78061373096583e-06 5.27403624940634e-06 -3.12473972828963e-06 4.26332826937678e-07 5.2871005084622e-07 5.78061373096583e-06 2.92826979020104e-05 2.07514327498639e-06 -7.92286474480916e-07 3.25353922299131e-05 -5.52899508710042e-07 5.27403624940634e-06 2.07514327498639e-06 3.99856336566611e-05 867 883 0 45 0 867 883 0 58 0 0 0 0 0 0 6 6 0 2940 0 0 0 0 0 933 +858 898 0.998597805523699 0.0168039296527192 0.0502001070863256 0.0671347888920191 -0.0214072659295493 0.995471600259881 0.092617611939913 -0.00314535659772472 -0.0484164410988008 -0.0935623910781315 0.99443548167142 0.149455783782926 3.85889412743612e-05 -3.70362483667893e-05 -4.40394942003115e-06 -7.51102784766124e-07 -3.3806022368769e-06 -2.17956560754258e-06 -3.70362483667893e-05 0.000123556486557593 1.14233616148925e-05 2.13368910766829e-05 4.50568355261748e-06 3.75914546865473e-05 -4.40394942003115e-06 1.14233616148925e-05 1.11139281989255e-05 1.64583013349263e-06 3.54988978624939e-06 8.45231882785458e-08 -7.51102784766124e-07 2.13368910766829e-05 1.64583013349263e-06 4.09198332666046e-05 -2.63806325430149e-06 8.12644816718599e-06 -3.3806022368769e-06 4.50568355261748e-06 3.54988978624939e-06 -2.63806325430149e-06 2.18354749029338e-05 4.58813903461857e-06 -2.17956560754258e-06 3.75914546865473e-05 8.45231882785458e-08 8.12644816718599e-06 4.58813903461857e-06 4.610695913551e-05 860 871 0 36 0 860 871 0 58 0 0 0 0 0 0 7 6 0 2939 0 0 0 0 0 2063 +858 900 0.998628058846639 0.0161182526896376 0.0498217022433678 0.0627093225286096 -0.0207329221574432 0.995399522168409 0.0935410990191806 -0.00865080656362096 -0.0480847795358075 -0.0944457156102686 0.994368071078239 0.151403939234239 3.62717346605447e-05 -3.9525195088152e-05 2.24846427738697e-06 -1.59204339025482e-05 -1.5243860268056e-05 -1.04875640683684e-05 -3.9525195088152e-05 0.000129326506539034 2.63644486350105e-06 4.79936036770939e-05 2.54244987919826e-05 5.775633147719e-05 2.24846427738697e-06 2.63644486350105e-06 1.07143651444112e-05 -1.0756971180458e-06 1.30791138229667e-06 -5.81392921604255e-07 -1.59204339025482e-05 4.79936036770939e-05 -1.0756971180458e-06 6.92889764540048e-05 1.58343495348082e-05 2.93020081619827e-05 -1.5243860268056e-05 2.54244987919826e-05 1.30791138229667e-06 1.58343495348082e-05 3.95571677611456e-05 1.6757319440449e-05 -1.04875640683684e-05 5.775633147719e-05 -5.81392921604255e-07 2.93020081619827e-05 1.6757319440449e-05 6.10713181615791e-05 870 885 0 44 0 870 885 0 59 0 0 0 0 0 0 10 7 0 2846 0 0 0 0 0 1672 +858 933 0.953361677597692 -0.300722422288817 -0.025836726202474 0.0641182717347827 0.301683824433232 0.952067767415384 0.0505354956839717 0.0613220232201028 0.00940115755926195 -0.0559731273150988 0.998388014378735 -0.140837078787095 2.60370173699258e-05 -2.35826331543166e-05 -4.54885868494576e-06 6.38104082465151e-06 1.40790206766751e-06 1.53229147418662e-05 -2.35826331543166e-05 3.49892509071746e-05 4.4803233574083e-06 5.97992747929282e-06 9.45741283701155e-07 -2.21110075450263e-06 -4.54885868494576e-06 4.4803233574083e-06 1.02307875438506e-05 -2.7359838111539e-06 3.12705253174521e-06 -5.40107629367132e-06 6.38104082465151e-06 5.97992747929282e-06 -2.7359838111539e-06 6.55060259333541e-05 5.46769754000529e-06 1.85474830611972e-05 1.40790206766751e-06 9.45741283701155e-07 3.12705253174521e-06 5.46769754000529e-06 2.65667936876635e-05 6.55240360096258e-06 1.53229147418662e-05 -2.21110075450263e-06 -5.40107629367132e-06 1.85474830611972e-05 6.55240360096258e-06 5.48091602206641e-05 1240 1240 0 0 0 1265 1265 0 0 0 0 0 0 0 0 704 701 0 2908 0 0 0 0 0 1309 +858 901 0.998848262466046 0.0171090245701356 0.0448266644623511 0.0616629786957177 -0.0212041975176283 0.995483657935412 0.0925346896637443 -0.00760446611937218 -0.0430410336329778 -0.0933786274357819 0.994699905178448 0.148521765201303 3.62270769663268e-05 -3.28582226595545e-05 -1.81543977486929e-06 -3.84357009153115e-06 -5.0635728004364e-06 -2.66205722819922e-06 -3.28582226595545e-05 8.67593891352948e-05 5.02021821566623e-06 2.06622181327683e-05 5.70072029135448e-06 2.91840534920715e-05 -1.81543977486929e-06 5.02021821566623e-06 1.25067182270988e-05 -3.94144673316029e-06 1.69441375379308e-06 -1.7176213704623e-06 -3.84357009153115e-06 2.06622181327683e-05 -3.94144673316029e-06 5.39574984947825e-05 2.33840166096134e-06 1.30443215494341e-05 -5.0635728004364e-06 5.70072029135448e-06 1.69441375379308e-06 2.33840166096134e-06 3.02701037494072e-05 3.40373316729796e-06 -2.66205722819922e-06 2.91840534920715e-05 -1.7176213704623e-06 1.30443215494341e-05 3.40373316729796e-06 4.87375099928698e-05 864 874 0 42 0 864 874 0 60 0 0 0 0 0 0 4 4 0 2842 0 0 0 0 0 831 +858 895 0.998990771352615 0.0170784061815705 0.0415423494112236 0.0630254068144542 -0.0207898969674182 0.995668707867124 0.0906179030782323 -0.00528629481586083 -0.0398148080039453 -0.0913901100585236 0.995018908788722 0.147581481087409 2.93284752253728e-05 -3.36250951088019e-05 -1.89889528756108e-06 -8.71079717742995e-06 -4.53803241467747e-06 -3.12918096868226e-06 -3.36250951088019e-05 7.8121641823116e-05 3.85665778264747e-06 3.57940684411046e-05 1.30182744830518e-05 3.0136734435764e-05 -1.89889528756108e-06 3.85665778264747e-06 1.01940724614921e-05 -5.79074859702951e-07 2.41528369852977e-06 1.60792753449298e-07 -8.71079717742995e-06 3.57940684411046e-05 -5.79074859702951e-07 6.99297391793929e-05 1.29716341054294e-05 2.15318806857609e-05 -4.53803241467747e-06 1.30182744830518e-05 2.41528369852977e-06 1.29716341054294e-05 2.9989472820054e-05 9.99892998313146e-06 -3.12918096868226e-06 3.0136734435764e-05 1.60792753449298e-07 2.15318806857609e-05 9.99892998313146e-06 4.50258110355616e-05 848 862 0 39 0 850 865 0 61 0 0 0 0 0 0 11 11 0 2876 0 0 0 0 0 2059 +858 894 0.99840012087732 0.0162911297891344 0.0541460776266114 0.0646298592123014 -0.0213510654949589 0.995321816943763 0.0942263907724153 -0.00684406798497476 -0.0523577180020618 -0.0952317163867139 0.994077255327601 0.151765696825694 3.53653070113062e-05 -3.81390061326026e-05 2.98886935533684e-06 -1.03783797471647e-05 -9.9733609510628e-06 -4.01055844067019e-06 -3.81390061326026e-05 0.000119987037861253 3.65325934220618e-06 3.01317741047169e-05 1.28246499323827e-05 4.20653588776987e-05 2.98886935533684e-06 3.65325934220618e-06 1.2650845461418e-05 -5.11692322178406e-08 2.08062513188412e-06 1.19708640757232e-06 -1.03783797471647e-05 3.01317741047169e-05 -5.11692322178406e-08 6.65441451740535e-05 7.42795312236671e-06 1.69358769080998e-05 -9.9733609510628e-06 1.28246499323827e-05 2.08062513188412e-06 7.42795312236671e-06 3.61524699365407e-05 7.23844870681332e-06 -4.01055844067019e-06 4.20653588776987e-05 1.19708640757232e-06 1.69358769080998e-05 7.23844870681332e-06 4.79575186122248e-05 860 874 0 37 0 860 875 0 61 0 0 0 0 0 0 7 6 0 2832 0 0 0 0 0 933 +858 925 0.998761722532788 0.0165957215686883 0.0468999320783331 0.0661002608283016 -0.0208311154828969 0.99560439019577 0.0913124463074291 -0.00378103805723806 -0.045178382342398 -0.0921763540639545 0.994717263105653 0.149861164446904 2.5928764421187e-05 -2.40682119607415e-05 -6.96737321956621e-07 2.83780027774011e-06 -5.47413491420762e-06 -3.53196512548743e-06 -2.40682119607415e-05 6.94636622575944e-05 4.01245334403562e-06 1.06474221469219e-05 9.30999575120975e-06 2.10129095206291e-05 -6.96737321956621e-07 4.01245334403562e-06 1.01839662700384e-05 -3.09585194692155e-07 3.03781203557392e-06 -6.36436761046112e-07 2.83780027774011e-06 1.06474221469219e-05 -3.09585194692155e-07 4.20495608757302e-05 2.57424892853556e-06 7.59002666228447e-06 -5.47413491420762e-06 9.30999575120975e-06 3.03781203557392e-06 2.57424892853556e-06 2.61903050261435e-05 3.69247653168424e-06 -3.53196512548743e-06 2.10129095206291e-05 -6.36436761046112e-07 7.59002666228447e-06 3.69247653168424e-06 3.40340633542815e-05 867 881 0 40 0 867 882 0 64 0 0 0 0 0 0 6 9 0 2832 0 0 0 0 0 2058 +858 893 0.999016732013436 0.0166495272421795 0.041089687268301 0.0574103510451104 -0.0202891113846555 0.995752024400036 0.0898123480510974 -0.0074724430543641 -0.0394198061438143 -0.0905577116862078 0.995110737424605 0.145977601732662 3.41596571275927e-05 -3.14525442678725e-05 -1.04489255125125e-08 -3.97018736680947e-06 -8.13535816741823e-06 -1.06129912417297e-05 -3.14525442678725e-05 7.13754564741801e-05 4.39461346293076e-06 1.39171957500467e-05 6.61242859233472e-06 3.80667686994755e-05 -1.04489255125125e-08 4.39461346293076e-06 1.0687913525663e-05 -3.72547078000958e-07 2.04039875563607e-06 2.50824376068807e-06 -3.97018736680947e-06 1.39171957500467e-05 -3.72547078000958e-07 5.37846524195883e-05 7.73762426757965e-06 1.12966776982654e-05 -8.13535816741823e-06 6.61242859233472e-06 2.04039875563607e-06 7.73762426757965e-06 3.27982620416911e-05 9.90163139479648e-06 -1.06129912417297e-05 3.80667686994755e-05 2.50824376068807e-06 1.12966776982654e-05 9.90163139479648e-06 6.48587897411819e-05 896 905 0 31 0 896 905 0 54 0 0 0 0 0 0 9 6 0 2845 0 0 0 0 0 1604 +858 891 0.998851457255571 0.0167862967836004 0.0448774618122993 0.0656767801931205 -0.0206687469194961 0.99595024447955 0.0874980766754491 -0.00421015620932289 -0.0432269503805129 -0.0883251422949198 0.995153304772377 0.151542533534362 2.13677325165571e-05 -1.92421416566817e-05 -1.2413960280972e-06 7.57148778121878e-07 -4.0253433201971e-07 2.78131308268202e-07 -1.92421416566817e-05 4.21316977789611e-05 2.56442476580215e-06 1.42060452626599e-05 6.15338497894321e-06 9.97134988507143e-06 -1.2413960280972e-06 2.56442476580215e-06 9.93487635553437e-06 -4.37784919667259e-07 1.42289732666069e-06 -2.98388698649798e-06 7.57148778121878e-07 1.42060452626599e-05 -4.37784919667259e-07 5.74214562214536e-05 9.83181907074481e-06 1.18076315680108e-05 -4.0253433201971e-07 6.15338497894321e-06 1.42289732666069e-06 9.83181907074481e-06 2.79330498380819e-05 6.13949931304621e-06 2.78131308268202e-07 9.97134988507143e-06 -2.98388698649798e-06 1.18076315680108e-05 6.13949931304621e-06 2.82601331058114e-05 856 871 0 44 0 856 871 0 69 0 0 0 0 0 0 9 12 0 2840 0 0 0 0 0 2118 +858 890 0.999429621926362 0.0172751717137183 0.0290172234783263 0.0637144558160191 -0.0191423335263795 0.997678622022915 0.0653524156066309 -0.00132319247628012 -0.0278208893332767 -0.0658705973915412 0.997440255111045 0.149992951094888 2.35160486360364e-05 -2.13372249092435e-05 4.87318978614987e-06 -2.40673573057223e-06 -1.65424522966159e-06 -3.4722995745889e-07 -2.13372249092435e-05 5.05601191167879e-05 -2.05328691775967e-06 3.52829159427463e-06 5.60940152329384e-06 1.59056084683588e-05 4.87318978614987e-06 -2.05328691775967e-06 1.04358610192051e-05 -1.02061036768159e-06 1.70049499191413e-06 5.10097830311799e-07 -2.40673573057223e-06 3.52829159427463e-06 -1.02061036768159e-06 5.19320454231193e-05 5.49036472369861e-06 -2.48734664838223e-06 -1.65424522966159e-06 5.60940152329384e-06 1.70049499191413e-06 5.49036472369861e-06 2.67207428566147e-05 4.66188411967758e-06 -3.4722995745889e-07 1.59056084683588e-05 5.10097830311799e-07 -2.48734664838223e-06 4.66188411967758e-06 3.7508591674226e-05 835 850 0 37 0 835 850 0 58 0 0 0 0 0 0 3 2 0 2695 0 0 0 0 0 2108 +858 923 0.998795104211852 0.0163115378668888 0.04628470087245 0.0624158478621534 -0.0205471914210891 0.995494528906946 0.0925659540060139 -0.00647116582534139 -0.0445662734266647 -0.0934054422866003 0.994630218032865 0.151191896926835 4.1005162545487e-05 -4.51209233573947e-05 -1.73156669341251e-06 -8.28539489990782e-06 -1.52041862813433e-05 -7.85457997700776e-06 -4.51209233573947e-05 9.4883178961241e-05 5.37705725324743e-06 2.85644169643899e-05 1.92121376255505e-05 3.24486809970354e-05 -1.73156669341251e-06 5.37705725324743e-06 1.28086805664669e-05 -2.59721116810532e-06 2.13663582223906e-06 -1.08478681551416e-06 -8.28539489990782e-06 2.85644169643899e-05 -2.59721116810532e-06 6.51845351644697e-05 7.48105088879676e-06 2.31396781597612e-05 -1.52041862813433e-05 1.92121376255505e-05 2.13663582223906e-06 7.48105088879676e-06 3.86287926087074e-05 1.16152864068371e-05 -7.85457997700776e-06 3.24486809970354e-05 -1.08478681551416e-06 2.31396781597612e-05 1.16152864068371e-05 4.42624022034579e-05 853 868 0 42 0 854 869 0 61 0 0 0 0 0 0 10 9 0 2804 0 0 0 0 0 811 +858 902 0.998703551003277 0.0164797097350547 0.0481626035477092 0.0598682059632983 -0.0209394704244406 0.995388509548025 0.0936122515384908 -0.00784786647971965 -0.0463977994283074 -0.094499387441454 0.994443115508072 0.150037488786808 2.7125353359435e-05 -2.62300886256805e-05 -2.68777519126025e-06 2.04448600519226e-07 -2.55575278800051e-06 3.90282832857244e-06 -2.62300886256805e-05 7.80063213810564e-05 8.33183284943161e-06 9.8124909880656e-06 4.60987008251855e-06 2.67637780058891e-05 -2.68777519126025e-06 8.33183284943161e-06 1.23219610580573e-05 -9.06756416055205e-07 3.72974981500062e-06 7.54819893177715e-07 2.04448600519226e-07 9.8124909880656e-06 -9.06756416055205e-07 3.809607705601e-05 -3.26167377589386e-06 5.06341200715508e-06 -2.55575278800051e-06 4.60987008251855e-06 3.72974981500062e-06 -3.26167377589386e-06 2.48368299394442e-05 2.2306371742459e-06 3.90282832857244e-06 2.67637780058891e-05 7.54819893177715e-07 5.06341200715508e-06 2.2306371742459e-06 4.40515191187367e-05 854 864 0 34 0 854 864 0 52 0 0 0 0 0 0 9 9 0 2912 0 0 0 0 0 804 +858 928 0.998787960339693 0.0168000168021201 0.046264129905622 0.0660437510099047 -0.0210044671347612 0.995542277671677 0.0919477336788368 -0.00751337371177374 -0.0445131737900199 -0.0928080427750636 0.99468851634841 0.150230203104483 4.68804396951305e-05 -4.74281656726345e-05 -1.91221344730583e-06 -2.7236363836125e-07 -7.64771945602164e-06 -1.06263118120552e-05 -4.74281656726345e-05 0.000107413713837014 6.57952654579741e-06 1.79321489180557e-05 9.25816734416939e-06 3.83530419031469e-05 -1.91221344730583e-06 6.57952654579741e-06 1.20777310546191e-05 -2.30750000401218e-06 2.74643316151679e-06 1.06365484378092e-06 -2.7236363836125e-07 1.79321489180557e-05 -2.30750000401218e-06 4.89840713842453e-05 -3.38087492613053e-06 1.12956680714788e-05 -7.64771945602164e-06 9.25816734416939e-06 2.74643316151679e-06 -3.38087492613053e-06 2.7330842619206e-05 6.21066831357222e-06 -1.06263118120552e-05 3.83530419031469e-05 1.06365484378092e-06 1.12956680714788e-05 6.21066831357222e-06 5.67057650607104e-05 854 867 0 43 0 854 867 0 57 0 0 0 0 0 0 11 10 0 2806 0 0 0 0 0 845 +858 922 0.998904887556647 0.0168660648288965 0.0436412817482608 0.0630505614047525 -0.0208584020380267 0.995475014040973 0.0927061135230279 -0.0066363967522262 -0.0418802182404016 -0.0935148773046939 0.99473665612705 0.147326449272968 4.34903778500931e-05 -6.76957711487041e-05 -5.331503283387e-06 -1.21731763541331e-05 -6.66186211691747e-06 -2.4344568392866e-05 -6.76957711487041e-05 0.000211743669993319 1.82059697232281e-05 4.88496427752849e-05 8.36771536468068e-06 9.69556561387706e-05 -5.331503283387e-06 1.82059697232281e-05 1.27192310538239e-05 2.04465147402488e-06 3.64665783242908e-06 6.49606869062536e-06 -1.21731763541331e-05 4.88496427752849e-05 2.04465147402488e-06 5.52358547373108e-05 2.9381793631843e-06 2.52781175686382e-05 -6.66186211691747e-06 8.36771536468068e-06 3.64665783242908e-06 2.9381793631843e-06 2.76679852954099e-05 6.71037644436969e-06 -2.4344568392866e-05 9.69556561387706e-05 6.49606869062536e-06 2.52781175686382e-05 6.71037644436969e-06 7.89413935913836e-05 882 893 0 38 0 882 893 0 63 0 0 0 0 0 0 6 5 0 2912 0 0 0 0 0 777 +858 916 0.998775530512925 0.0172801831974838 0.046355527364996 0.0657699799498585 -0.0215417611988739 0.995426666999174 0.0930682714536288 -0.00403833114149563 -0.0445352913213351 -0.0939528918957636 0.994580042998726 0.149768991548981 4.02054225918947e-05 -3.75894568213704e-05 -2.49995151606298e-06 -2.39597723032606e-06 -4.94366967448263e-06 -3.97851686478805e-06 -3.75894568213704e-05 0.000142992372663832 1.30430088831213e-05 3.07470260811063e-05 3.5446939994945e-06 5.9612306194409e-05 -2.49995151606298e-06 1.30430088831213e-05 1.41009301907365e-05 -4.1851043803477e-07 1.52981353519172e-06 3.26624859702685e-06 -2.39597723032606e-06 3.07470260811063e-05 -4.1851043803477e-07 4.72719452599448e-05 4.90406582448571e-07 1.47393677665684e-05 -4.94366967448263e-06 3.5446939994945e-06 1.52981353519172e-06 4.90406582448571e-07 2.59260828523305e-05 5.79959435916035e-06 -3.97851686478805e-06 5.9612306194409e-05 3.26624859702685e-06 1.47393677665684e-05 5.79959435916035e-06 6.78129791678215e-05 865 875 0 36 0 865 875 0 54 0 0 0 0 0 0 8 6 0 2753 0 0 0 0 0 783 +858 915 0.998570388156897 0.016580940027709 0.0508158668525999 0.0667375544266005 -0.0213047797133819 0.995355927215772 0.0938758995578454 -0.00335282912955554 -0.0490233236077269 -0.0948243143092947 0.994286207868853 0.15024761040881 3.97431045924622e-05 -4.28565378614511e-05 -8.99796540543151e-07 -6.02977357057395e-07 -5.23820934850605e-06 -1.62286915381231e-05 -4.28565378614511e-05 7.33068222254781e-05 3.30923439095862e-06 1.04991191640439e-05 6.03009224724787e-06 4.23170835499718e-05 -8.99796540543151e-07 3.30923439095862e-06 1.07340613012985e-05 -1.79626173814748e-07 2.7285180038654e-06 1.4494483424941e-06 -6.02977357057395e-07 1.04991191640439e-05 -1.79626173814748e-07 4.46936832796965e-05 -1.12005686045393e-06 1.46210093320005e-05 -5.23820934850605e-06 6.03009224724787e-06 2.7285180038654e-06 -1.12005686045393e-06 2.18359956691423e-05 7.26726920507606e-06 -1.62286915381231e-05 4.23170835499718e-05 1.4494483424941e-06 1.46210093320005e-05 7.26726920507606e-06 7.51522779633833e-05 872 881 0 33 0 872 881 0 51 0 0 0 0 0 0 9 6 0 2902 0 0 0 0 0 1629 +858 924 0.998655954917364 0.0165561284467344 0.0491139320248644 0.0661702761668532 -0.0210445449783183 0.995506353933056 0.0923267372193353 -0.00596763576312155 -0.0473646580769175 -0.0932362262737392 0.994516764703084 0.150905166413701 4.5501307943949e-05 -6.49308464098529e-05 -1.73047538474888e-06 -2.01689723927029e-05 -1.54019743949472e-05 -2.85919977221793e-05 -6.49308464098529e-05 0.00017647910873015 7.9846396911218e-06 7.18526136169212e-05 3.43331092658116e-05 9.85401955613954e-05 -1.73047538474888e-06 7.9846396911218e-06 1.14388074622273e-05 1.46099260657719e-06 4.28825858466707e-06 3.8908190334792e-06 -2.01689723927029e-05 7.18526136169212e-05 1.46099260657719e-06 7.58947696718382e-05 1.35897606449747e-05 5.27680587939751e-05 -1.54019743949472e-05 3.43331092658116e-05 4.28825858466707e-06 1.35897606449747e-05 3.1774389066016e-05 2.63899542807958e-05 -2.85919977221793e-05 9.85401955613954e-05 3.8908190334792e-06 5.27680587939751e-05 2.63899542807958e-05 9.72526432275554e-05 855 864 0 41 0 855 865 0 60 0 0 0 0 0 0 5 6 0 2855 0 0 0 0 0 1585 +858 921 0.998803283691493 0.0168656882634587 0.0459080499094793 0.0670211524667645 -0.0210046840910392 0.995608845292949 0.0912240671132199 -0.00559847585576178 -0.0441679038819713 -0.0920791818699614 0.994771642404844 0.148434593066577 3.59835000113524e-05 -4.78005854577645e-05 1.61004242156633e-06 -4.96822784009651e-06 -4.32410548783612e-06 -1.22824271926951e-05 -4.78005854577645e-05 0.000175590989688314 4.26161204889339e-06 6.95130132091148e-05 2.21919380014392e-05 6.27562938757917e-05 1.61004242156633e-06 4.26161204889339e-06 1.01600931092651e-05 2.22434225310874e-06 3.97721555333941e-06 2.79421037758562e-06 -4.96822784009651e-06 6.95130132091148e-05 2.22434225310874e-06 7.77847842293564e-05 1.51344714703667e-05 2.89875600030422e-05 -4.32410548783612e-06 2.21919380014392e-05 3.97721555333941e-06 1.51344714703667e-05 2.93568537215247e-05 1.23284532394752e-05 -1.22824271926951e-05 6.27562938757917e-05 2.79421037758562e-06 2.89875600030422e-05 1.23284532394752e-05 5.46755267610297e-05 856 865 0 43 0 856 866 0 66 0 0 0 0 0 0 5 4 0 2789 0 0 0 0 0 2023 +858 926 0.998381520898074 0.0169451870813919 0.0542881143900234 0.0724248927741234 -0.0220714118329354 0.995207304055641 0.0952642363849297 -0.00170256249880814 -0.0524136576566509 -0.0963082685395155 0.993970586034603 0.153847078948368 4.3951354181205e-05 -5.54735969876762e-05 -1.2791174027937e-06 -9.68043217430577e-06 -8.87560780967534e-06 -2.4456661272835e-05 -5.54735969876762e-05 9.70923382329315e-05 5.35263036287921e-06 2.41443007363393e-05 1.39251737767262e-05 5.81148908393162e-05 -1.2791174027937e-06 5.35263036287921e-06 1.10669825479638e-05 -7.36675663620421e-07 2.72355629913554e-06 3.02318863380597e-06 -9.68043217430577e-06 2.41443007363393e-05 -7.36675663620421e-07 5.39088488094913e-05 8.05595193761695e-06 2.57768394088377e-05 -8.87560780967534e-06 1.39251737767262e-05 2.72355629913554e-06 8.05595193761695e-06 2.64860831138731e-05 1.27958186715416e-05 -2.4456661272835e-05 5.81148908393162e-05 3.02318863380597e-06 2.57768394088377e-05 1.27958186715416e-05 8.08517515355615e-05 867 877 0 36 0 867 877 0 57 0 0 0 0 0 0 11 9 0 2857 0 0 0 0 0 1616 +858 903 0.998832848997859 0.016801385743869 0.0452841385024147 0.0633970564250973 -0.02089045053065 0.995595699774839 0.0913936084552657 -0.00779095908188781 -0.0435491542908313 -0.0922329443687757 0.994784677773849 0.147354773336398 4.52088673995402e-05 -5.34332222945807e-05 -5.23620128715772e-06 -9.38705247201545e-06 -9.13742603521491e-06 -2.41729843301244e-05 -5.34332222945807e-05 0.000151191157916512 1.08418535947864e-05 4.74485410464412e-05 1.91589500132711e-05 8.27493007465778e-05 -5.23620128715772e-06 1.08418535947864e-05 1.13911626290119e-05 1.41100529801293e-07 4.03505862043321e-06 2.38644077476469e-06 -9.38705247201545e-06 4.74485410464412e-05 1.41100529801293e-07 6.56182783309921e-05 7.71343086372351e-06 3.37592152170496e-05 -9.13742603521491e-06 1.91589500132711e-05 4.03505862043321e-06 7.71343086372351e-06 2.65738581461288e-05 1.74864828644779e-05 -2.41729843301244e-05 8.27493007465778e-05 2.38644077476469e-06 3.37592152170496e-05 1.74864828644779e-05 8.6809320704164e-05 854 866 0 40 0 855 868 0 61 0 0 0 0 0 0 4 5 0 2852 0 0 0 0 0 1640 +858 920 0.998754381121702 0.0157717443082173 0.0473385495308158 0.0618900894027829 -0.0200820558851429 0.995556014906427 0.092005066246701 -0.00914191941945969 -0.0456770973424459 -0.0928411183964845 0.994632660590461 0.154150116454443 3.20189702693843e-05 -3.42321108004662e-05 -2.82431988793014e-06 -1.02496301649011e-06 -2.34406246615456e-06 -6.31270345625856e-06 -3.42321108004662e-05 0.000104241683599523 5.55488378279304e-06 3.11250090053416e-05 7.68764157291426e-06 4.91436794679186e-05 -2.82431988793014e-06 5.55488378279304e-06 1.20612288142182e-05 -2.51075826298062e-06 2.95064632840139e-06 9.30605550377375e-07 -1.02496301649011e-06 3.11250090053416e-05 -2.51075826298062e-06 5.81955190396178e-05 2.95740532759007e-06 2.05938764470972e-05 -2.34406246615456e-06 7.68764157291426e-06 2.95064632840139e-06 2.95740532759007e-06 2.73407329954485e-05 6.01896678465881e-06 -6.31270345625856e-06 4.91436794679186e-05 9.30605550377375e-07 2.05938764470972e-05 6.01896678465881e-06 5.68858892753907e-05 852 860 0 36 0 853 861 0 59 0 0 0 0 0 0 9 8 0 2662 0 0 0 0 0 1631 +858 918 0.998480311898056 0.0161647504668405 0.0526855539432449 0.0651564857646525 -0.0210139069789366 0.995460550694284 0.0928262232610671 -0.00782496703642597 -0.0509458778061816 -0.0937922856837259 0.994287445702087 0.153285828135702 4.20600276879257e-05 -3.32493245789403e-05 -5.12109921281315e-06 5.0064483998291e-06 -1.2067095691808e-06 2.61846157561288e-06 -3.32493245789403e-05 7.56650730098095e-05 9.49019591610621e-06 -2.43209432443164e-06 -6.41253331806053e-06 2.8835785340704e-05 -5.12109921281315e-06 9.49019591610621e-06 1.16420672708586e-05 -3.2352334799724e-06 9.87981078354452e-07 -8.13762092670182e-07 5.0064483998291e-06 -2.43209432443164e-06 -3.2352334799724e-06 4.37178874930817e-05 -3.31917739497165e-07 6.73279630931394e-06 -1.2067095691808e-06 -6.41253331806053e-06 9.87981078354452e-07 -3.31917739497165e-07 2.860236945226e-05 -4.48632107282639e-08 2.61846157561288e-06 2.8835785340704e-05 -8.13762092670182e-07 6.73279630931394e-06 -4.48632107282639e-08 5.95291711957386e-05 877 890 0 39 0 878 892 0 63 0 0 0 0 0 0 9 11 0 2579 0 0 0 0 0 1625 +858 919 0.998602992476995 0.0164447997319153 0.0502158538488438 0.0653216811799529 -0.0210611717586368 0.995459038249273 0.0928317306312153 -0.00709526852825091 -0.0484612263582387 -0.093759648728067 0.994414721235685 0.151101141983141 4.17243212818102e-05 -3.84072408616416e-05 -5.3545550121846e-06 -2.40514528547127e-06 -7.8665309924136e-06 -7.38176474822905e-06 -3.84072408616416e-05 9.63352505657214e-05 9.56880818987364e-06 2.07690309577442e-05 9.19017579057609e-06 3.51229768884498e-05 -5.3545550121846e-06 9.56880818987364e-06 1.22475473571201e-05 -3.50617825709762e-07 1.70407329538863e-06 -9.74399815412957e-07 -2.40514528547127e-06 2.07690309577442e-05 -3.50617825709762e-07 4.96110306139028e-05 3.4844216773126e-07 1.58845201035859e-05 -7.8665309924136e-06 9.19017579057609e-06 1.70407329538863e-06 3.4844216773126e-07 2.99009311764456e-05 6.88454378516307e-06 -7.38176474822905e-06 3.51229768884498e-05 -9.74399815412957e-07 1.58845201035859e-05 6.88454378516307e-06 5.3465369579242e-05 880 892 0 40 0 882 894 0 59 0 0 0 0 0 0 7 9 0 2654 0 0 0 0 0 836 +859 931 0.991224223370125 -0.124715422205436 0.0438246787599396 0.0349712654218308 0.121087987308288 0.989614556722772 0.0774643689190014 0.00519539125789421 -0.0530305415201465 -0.0714779167751207 0.99603145988446 0.0130188118536482 2.9224438952308e-05 -4.29110659120484e-05 -5.9392828492389e-08 -2.66222317830918e-06 -2.60484304751259e-06 -1.82358285201337e-06 -4.29110659120484e-05 0.000146313358319274 6.55865449437051e-07 4.30355281657881e-05 6.78750262631722e-06 3.66150101802049e-05 -5.9392828492389e-08 6.55865449437051e-07 9.701930803694e-06 1.39963443608446e-06 1.98796011441335e-06 -4.0040295513397e-07 -2.66222317830918e-06 4.30355281657881e-05 1.39963443608446e-06 7.00738477083098e-05 8.19300537638152e-06 1.77146716543643e-05 -2.60484304751259e-06 6.78750262631722e-06 1.98796011441335e-06 8.19300537638152e-06 2.34341309772287e-05 2.90772395202131e-06 -1.82358285201337e-06 3.66150101802049e-05 -4.0040295513397e-07 1.77146716543643e-05 2.90772395202131e-06 3.88378814224131e-05 1123 1123 0 0 0 1109 1109 0 0 0 0 0 0 0 0 233 242 0 3306 0 0 0 0 0 1651 +858 927 0.998682786331742 0.0167430836326118 0.0485011488022692 0.0674564251851172 -0.0212074870468905 0.995435832429097 0.0930470096743932 -0.00343809008136761 -0.0467218875670116 -0.093953034366443 0.994479709474011 0.150866320111116 2.49978094407937e-05 -2.62741475040936e-05 -1.94921622346283e-06 -1.0956444289445e-06 -3.20961229788188e-06 -1.74593996201488e-06 -2.62741475040936e-05 6.52493458522268e-05 4.98964007886181e-06 8.73068752486211e-06 3.64095428482995e-06 2.30545682179186e-05 -1.94921622346283e-06 4.98964007886181e-06 1.04902987499444e-05 -1.11606366359385e-06 2.33402962664686e-06 -2.6545562731936e-06 -1.0956444289445e-06 8.73068752486211e-06 -1.11606366359385e-06 4.32951840568162e-05 3.80457695715498e-06 9.03672768075201e-06 -3.20961229788188e-06 3.64095428482995e-06 2.33402962664686e-06 3.80457695715498e-06 2.65442902250825e-05 6.37777211510949e-06 -1.74593996201488e-06 2.30545682179186e-05 -2.6545562731936e-06 9.03672768075201e-06 6.37777211510949e-06 4.49312411321933e-05 856 867 0 37 0 857 868 0 58 0 0 0 0 0 0 9 10 0 2878 0 0 0 0 0 1620 +859 862 0.998186670910171 -0.0171533268146454 -0.057698642934296 0.0211334320535679 0.0164158579504524 0.999777702587378 -0.0132312137332173 0.0104382966762331 0.0579127760085802 0.0122600484621178 0.998246363172282 0.0707199111849234 3.33341563031295e-05 -3.31858137620264e-05 1.74074208016598e-06 1.15436847785877e-07 -3.624367961905e-07 1.3143519659897e-05 -3.31858137620264e-05 5.67576843964047e-05 -2.48285514904525e-06 1.63168816966542e-05 8.20557970859279e-06 -6.59135681224145e-06 1.74074208016598e-06 -2.48285514904525e-06 1.23958495067698e-05 -1.98647208330217e-06 3.00997855902696e-06 -1.53844679389738e-06 1.15436847785877e-07 1.63168816966542e-05 -1.98647208330217e-06 6.6924357615296e-05 1.48155847248077e-05 1.63601600556929e-07 -3.624367961905e-07 8.20557970859279e-06 3.00997855902696e-06 1.48155847248077e-05 3.09352903740986e-05 9.18747192461509e-07 1.3143519659897e-05 -6.59135681224145e-06 -1.53844679389738e-06 1.63601600556929e-07 9.18747192461509e-07 3.10110887872009e-05 1109 1102 0 4 0 1096 1101 0 13 0 0 0 0 0 0 31 38 0 2709 0 0 0 0 0 1276 +859 932 0.979593482398749 -0.200045501580607 -0.0194526743471053 0.0464943662303888 0.200942842000427 0.9768461945491 0.0734403597739918 0.0299427455919118 0.00431085730252428 -0.0758505734474378 0.997109877103327 -0.0787708347009831 2.23814539948848e-05 -1.29948196144219e-05 1.52314139255738e-06 1.53313714151857e-06 -3.15375640556217e-06 6.04497542409312e-06 -1.29948196144219e-05 6.21507683202254e-05 -2.24486017139134e-06 1.43349618730299e-05 1.14309764128379e-06 2.19914747987936e-05 1.52314139255738e-06 -2.24486017139134e-06 9.50810689283364e-06 -6.75244721033318e-08 3.55285961852941e-06 1.39340894132472e-07 1.53313714151857e-06 1.43349618730299e-05 -6.75244721033318e-08 4.42980918496862e-05 -6.42396240550797e-06 3.63156928538826e-06 -3.15375640556217e-06 1.14309764128379e-06 3.55285961852941e-06 -6.42396240550797e-06 2.07687956606565e-05 -1.11427957881695e-06 6.04497542409312e-06 2.19914747987936e-05 1.39340894132472e-07 3.63156928538826e-06 -1.11427957881695e-06 4.68086819788606e-05 1166 1166 0 0 0 1163 1163 0 0 0 0 0 0 0 0 431 431 0 3082 0 0 0 0 0 1615 +859 930 0.995480424494673 -0.0544579915853879 0.0778013598878011 0.0352924265801418 0.0464949218608817 0.993826674292891 0.100731145655564 -0.00676180903423892 -0.0828066826352549 -0.0966585154883821 0.99186701966268 0.0703668192963442 3.2493107136141e-05 -3.02001115697633e-05 -3.30995893278336e-06 3.76609645700505e-06 -1.51252149034945e-06 7.58681793939855e-06 -3.02001115697633e-05 7.16130989581408e-05 7.02551525125168e-06 1.21194461544377e-05 -3.82537979800398e-06 8.37296543098987e-06 -3.30995893278336e-06 7.02551525125168e-06 1.41349819187485e-05 -3.57633462348516e-06 1.45590146057541e-06 -1.42925022198364e-06 3.76609645700505e-06 1.21194461544377e-05 -3.57633462348516e-06 5.13117626160013e-05 -3.67361300298487e-07 1.01253176721135e-05 -1.51252149034945e-06 -3.82537979800398e-06 1.45590146057541e-06 -3.67361300298487e-07 3.06176157015404e-05 1.537774794628e-06 7.58681793939855e-06 8.37296543098987e-06 -1.42925022198364e-06 1.01253176721135e-05 1.537774794628e-06 3.21664987027645e-05 1100 1100 0 0 0 1100 1100 0 0 0 0 0 0 0 0 78 90 0 3109 0 0 0 0 0 1340 +859 863 0.99630516727939 -0.0207735738306713 -0.0833335003626333 0.0137294796284043 0.0191443835733766 0.999610585038417 -0.0203019914478586 0.00522669883838676 0.0837227939690428 0.0186316104901091 0.996314888406553 0.0759912303096512 3.54524823017451e-05 -4.31053599784886e-05 1.32895354025261e-06 -7.38411062863042e-06 -8.64578431481923e-06 6.31820272407883e-06 -4.31053599784886e-05 8.84740238064863e-05 -3.48350490932725e-06 4.17030439953808e-05 2.23812107163339e-05 5.98212706136103e-06 1.32895354025261e-06 -3.48350490932725e-06 9.92137680515849e-06 -4.03442483763414e-06 1.18373283558339e-06 -1.65667584977614e-06 -7.38411062863042e-06 4.17030439953808e-05 -4.03442483763414e-06 8.72626748757074e-05 2.02650921148081e-05 1.91919221251951e-05 -8.64578431481923e-06 2.23812107163339e-05 1.18373283558339e-06 2.02650921148081e-05 3.32724413234063e-05 4.78547026356296e-06 6.31820272407883e-06 5.98212706136103e-06 -1.65667584977614e-06 1.91919221251951e-05 4.78547026356296e-06 3.33635476706712e-05 1051 1042 0 1 0 1045 1045 0 5 0 0 0 0 0 0 27 31 0 2665 0 0 0 0 0 2271 +859 899 0.999206495767744 0.029560019450313 0.0266942702773819 0.0434186379339918 -0.0316847639626708 0.996042738487006 0.0830357684370781 -0.00887888134509392 -0.024134095138924 -0.0838156808562892 0.996188976597524 0.120723093936539 3.56963822687975e-05 -5.37316798486871e-05 -3.37487554009394e-06 -8.71263191263197e-06 -3.44250388887942e-06 -4.05462782720733e-06 -5.37316798486871e-05 0.000194487659296707 1.63581463659838e-05 5.86821432847036e-05 1.11553002845535e-05 4.95442397793387e-05 -3.37487554009394e-06 1.63581463659838e-05 1.21884856660276e-05 1.23602725077709e-07 2.86219309307019e-06 2.72248598176317e-06 -8.71263191263197e-06 5.86821432847036e-05 1.23602725077709e-07 6.63665825990599e-05 9.14622492848587e-06 2.32324792639779e-05 -3.44250388887942e-06 1.11553002845535e-05 2.86219309307019e-06 9.14622492848587e-06 2.7638019268792e-05 7.93869459324434e-06 -4.05462782720733e-06 4.95442397793387e-05 2.72248598176317e-06 2.32324792639779e-05 7.93869459324434e-06 4.63789253328874e-05 897 915 0 72 0 897 915 0 82 0 0 0 0 0 0 0 1 0 2950 0 0 0 0 0 1163 +859 895 0.999193502049878 0.0292258046115647 0.0275353918822157 0.0454395989239191 -0.0314334196647177 0.996013180793594 0.0834846322002345 -0.00717215998749888 -0.0249857077042514 -0.0842828335441645 0.996128565186384 0.121290117473287 3.51245907506247e-05 -3.92876766064315e-05 -9.75793280278297e-07 -6.75222204685805e-06 -5.83263392373095e-06 1.92672807281554e-07 -3.92876766064315e-05 8.68221169790731e-05 4.25033885412232e-06 2.66392335389502e-05 1.51927707841801e-05 1.94222835312193e-05 -9.75793280278297e-07 4.25033885412232e-06 9.38217364075e-06 -7.97654122137196e-08 3.71873141643935e-06 5.34223583378867e-08 -6.75222204685805e-06 2.66392335389502e-05 -7.97654122137196e-08 5.8011760548938e-05 1.36340086954305e-05 1.01586074214058e-05 -5.83263392373095e-06 1.51927707841801e-05 3.71873141643935e-06 1.36340086954305e-05 2.73954027768433e-05 6.41811340413624e-06 1.92672807281554e-07 1.94222835312193e-05 5.34223583378867e-08 1.01586074214058e-05 6.41811340413624e-06 3.31062968873861e-05 886 905 0 73 0 886 905 0 82 0 0 0 0 0 0 0 1 0 2858 0 0 0 0 0 2140 +859 893 0.999244139597565 0.0292673028144808 0.0255846529366232 0.0442114646541391 -0.0312459016074157 0.996248236678382 0.0807040553377169 -0.00817741827314693 -0.0231266753482137 -0.0814424698862888 0.996409695349337 0.12046806454621 5.05364435160116e-05 -7.51714756519334e-05 -5.81583100871545e-06 -1.33853851499113e-05 -5.12035244069365e-06 -1.52489439873785e-05 -7.51714756519334e-05 0.000190285016274661 1.23743317534145e-05 5.96201750469411e-05 2.14059078026746e-05 6.38004355650409e-05 -5.81583100871545e-06 1.23743317534145e-05 1.07650482564454e-05 3.65033743189179e-06 1.79728707824576e-06 1.81328623544489e-06 -1.33853851499113e-05 5.96201750469411e-05 3.65033743189179e-06 7.26884796085246e-05 1.83134710954171e-05 2.21511444064397e-05 -5.12035244069365e-06 2.14059078026746e-05 1.79728707824576e-06 1.83134710954171e-05 3.07447072604939e-05 9.05298123799282e-06 -1.52489439873785e-05 6.38004355650409e-05 1.81328623544489e-06 2.21511444064397e-05 9.05298123799282e-06 5.73556625363359e-05 918 937 0 70 0 917 936 0 85 0 0 0 0 0 0 2 4 0 2823 0 0 0 0 0 1489 +859 894 0.999366352247365 0.029752434512477 0.0195368021020856 0.0431613270064472 -0.031253064010411 0.996172990349209 0.0816248693026588 -0.00864135347872586 -0.0170334959933785 -0.0821837328143213 0.996471622312923 0.119101767725175 3.68570972204767e-05 -4.51663339150769e-05 3.61993193537395e-06 -1.5231334827386e-05 -1.14454764711549e-05 -2.11460516585216e-06 -4.51663339150769e-05 9.94513058934097e-05 -2.21967592979361e-06 4.7947173904943e-05 2.12814799081462e-05 2.50225664714237e-05 3.61993193537395e-06 -2.21967592979361e-06 1.16140775629852e-05 6.33977863908217e-07 1.61085117046025e-06 1.4889698356952e-06 -1.5231334827386e-05 4.7947173904943e-05 6.33977863908217e-07 7.61435695345345e-05 1.76439839284281e-05 2.29224104394387e-05 -1.14454764711549e-05 2.12814799081462e-05 1.61085117046025e-06 1.76439839284281e-05 3.38147108779193e-05 8.35783337442392e-06 -2.11460516585216e-06 2.50225664714237e-05 1.4889698356952e-06 2.29224104394387e-05 8.35783337442392e-06 3.5721237568149e-05 859 875 0 65 0 859 875 0 82 0 0 0 0 0 0 1 1 0 2825 0 0 0 0 0 1081 +859 929 0.999605550482852 0.0081488216327246 0.0268763864734849 0.0426139181544827 -0.0108461435159633 0.994746372522006 0.101793985702206 -0.00906878373853013 -0.0259056869182273 -0.10204533825858 0.994442378584595 0.111207495537406 2.22547100832244e-05 -1.22107968943014e-05 -1.95890300694581e-06 8.45251116474091e-06 -2.92144628606164e-06 4.31900266010132e-06 -1.22107968943014e-05 5.63997739868243e-05 3.83974293769701e-06 8.60952040327548e-06 4.46668532796244e-06 1.99730287649966e-05 -1.95890300694581e-06 3.83974293769701e-06 1.01006847301845e-05 -1.05020516606765e-06 2.70758755789618e-06 -7.31976749809336e-07 8.45251116474091e-06 8.60952040327548e-06 -1.05020516606765e-06 5.48289954596563e-05 2.8604501058076e-06 1.01619712671014e-05 -2.92144628606164e-06 4.46668532796244e-06 2.70758755789618e-06 2.8604501058076e-06 2.70762983189075e-05 1.23256190381387e-06 4.31900266010132e-06 1.99730287649966e-05 -7.31976749809336e-07 1.01619712671014e-05 1.23256190381387e-06 3.39900804210837e-05 919 938 0 48 0 916 938 0 53 0 0 0 0 0 0 4 12 0 3005 0 0 0 0 0 1780 +859 898 0.999319965254934 0.030082481458531 0.0213225550104753 0.0429302904848476 -0.0317388361825666 0.996114419824823 0.082150525834187 -0.00646250241647426 -0.018768412843227 -0.0827714137027656 0.996391810360258 0.120772878768687 3.92704370831947e-05 -4.86118285206664e-05 -3.35925359342089e-06 -9.29176172777343e-06 -6.80135646013729e-06 -4.34454771789374e-06 -4.86118285206664e-05 9.99508246355173e-05 6.63045684367064e-06 2.93233732758506e-05 1.20754097597413e-05 2.96391780271792e-05 -3.35925359342089e-06 6.63045684367064e-06 9.20769675672943e-06 1.50973259698132e-06 2.80176732524512e-06 2.52198082227905e-07 -9.29176172777343e-06 2.93233732758506e-05 1.50973259698132e-06 4.54033810867019e-05 5.62637568999363e-06 1.60856832894958e-05 -6.80135646013729e-06 1.20754097597413e-05 2.80176732524512e-06 5.62637568999363e-06 2.27508572560978e-05 6.11094175109604e-06 -4.34454771789374e-06 2.96391780271792e-05 2.52198082227905e-07 1.60856832894958e-05 6.11094175109604e-06 3.77286254787811e-05 869 887 0 71 0 869 887 0 83 0 0 0 0 0 0 2 5 0 2931 0 0 0 0 0 2150 +859 901 0.999322887189828 0.0297788237536131 0.0216099235176437 0.0424940620556983 -0.0314721781471523 0.996069974100942 0.0827895446129745 -0.00736425223598417 -0.019059620700871 -0.0834135981144623 0.996332726807836 0.121339992404142 3.66803486698468e-05 -5.30208142355542e-05 5.62157802440777e-07 -1.60505342938325e-05 -4.76371333538346e-06 -2.13382515877835e-06 -5.30208142355542e-05 0.000156571071697838 2.5257770205151e-06 6.42593114202913e-05 1.64754144559197e-05 4.01326832878232e-05 5.62157802440777e-07 2.5257770205151e-06 1.09394501182114e-05 -7.94333428779007e-07 5.29412102798502e-07 1.07660477501753e-07 -1.60505342938325e-05 6.42593114202913e-05 -7.94333428779007e-07 8.3827136712744e-05 2.04113049757065e-05 2.85510907970276e-05 -4.76371333538346e-06 1.64754144559197e-05 5.29412102798502e-07 2.04113049757065e-05 3.02919346193682e-05 1.03064008940209e-05 -2.13382515877835e-06 4.01326832878232e-05 1.07660477501753e-07 2.85510907970276e-05 1.03064008940209e-05 4.234273037542e-05 864 876 0 69 0 864 876 0 76 0 0 0 0 0 0 0 1 0 2848 0 0 0 0 0 1122 +859 897 0.999370205937792 0.0295338748597789 0.0196708342380707 0.0402607791837064 -0.0310393508127925 0.996212224376463 0.0812266132743418 -0.0101046183858389 -0.017197388899921 -0.0817860271603041 0.996501528135486 0.119083859927635 4.25642241783257e-05 -5.05954739339019e-05 -1.42981462765843e-06 -6.70659967531199e-06 -6.1838078881253e-06 -7.85304530922168e-06 -5.05954739339019e-05 0.000108542381495479 5.47643802307062e-06 2.41324502446604e-05 7.36295702237746e-06 3.67807297089317e-05 -1.42981462765843e-06 5.47643802307062e-06 1.01493856554502e-05 -1.5892930756245e-07 1.1559614632784e-06 1.39656762002222e-06 -6.70659967531199e-06 2.41324502446604e-05 -1.5892930756245e-07 4.97723867600523e-05 5.57093003474687e-06 1.80032583348017e-05 -6.1838078881253e-06 7.36295702237746e-06 1.1559614632784e-06 5.57093003474687e-06 2.79905459629518e-05 8.57216933364082e-06 -7.85304530922168e-06 3.67807297089317e-05 1.39656762002222e-06 1.80032583348017e-05 8.57216933364082e-06 4.67046387078029e-05 899 916 0 68 0 899 916 0 80 0 0 0 0 0 0 0 4 0 2840 0 0 0 0 0 1699 +859 900 0.999408634413865 0.0294718646807343 0.0177141370451598 0.0372672855054732 -0.0308041448265155 0.996290320371397 0.0803536072355561 -0.0128723016835806 -0.0152802526327699 -0.080851757720531 0.996609004150063 0.118219743073218 3.78349233861084e-05 -4.02045971735983e-05 4.06034101407655e-06 -1.44667279943133e-05 -1.39949652920048e-05 -1.18349034398558e-05 -4.02045971735983e-05 6.85847972339115e-05 -2.72610448628007e-06 2.75149848516712e-05 1.91890267137745e-05 3.04260339302449e-05 4.06034101407655e-06 -2.72610448628007e-06 1.12732931274947e-05 -5.07204533817157e-06 1.37968907333743e-06 -7.7475627966593e-07 -1.44667279943133e-05 2.75149848516712e-05 -5.07204533817157e-06 6.42084919607296e-05 1.71680503279774e-05 2.28855358559095e-05 -1.39949652920048e-05 1.91890267137745e-05 1.37968907333743e-06 1.71680503279774e-05 3.59241987012547e-05 1.51961469076613e-05 -1.18349034398558e-05 3.04260339302449e-05 -7.7475627966593e-07 2.28855358559095e-05 1.51961469076613e-05 4.65611145117268e-05 897 913 0 70 0 897 913 0 83 0 0 0 0 0 0 2 3 0 2860 0 0 0 0 0 1689 +859 923 0.999150582339618 0.0292147527554614 0.029062209686116 0.0500898795984136 -0.0315344182513517 0.996062683363133 0.0828535531946851 -0.00639774201326452 -0.0265272364929205 -0.0836996357989266 0.996137880361537 0.122602935809403 2.12428875023249e-05 -1.84164652279013e-05 5.12333036764682e-07 -4.42555846687759e-07 -3.80754515517485e-06 2.22126582467174e-06 -1.84164652279013e-05 4.27773485454686e-05 1.28947071547808e-06 9.68479573052784e-06 4.49149361524635e-06 6.95367517413348e-06 5.12333036764682e-07 1.28947071547808e-06 1.04570833732666e-05 5.55796594052341e-07 1.00932560418677e-06 -1.26078426188735e-06 -4.42555846687759e-07 9.68479573052784e-06 5.55796594052341e-07 4.91857744550884e-05 9.11860189933482e-06 6.90206370770415e-06 -3.80754515517485e-06 4.49149361524635e-06 1.00932560418677e-06 9.11860189933482e-06 2.66049299550739e-05 2.60585976805774e-06 2.22126582467174e-06 6.95367517413348e-06 -1.26078426188735e-06 6.90206370770415e-06 2.60585976805774e-06 2.67715525466041e-05 885 903 0 67 0 884 902 0 81 0 0 0 0 0 0 0 1 0 2795 0 0 0 0 0 1173 +859 891 0.999304155292559 0.0294313855638984 0.0229128513898512 0.0450308483599047 -0.0311375607756992 0.996462093031922 0.0780624715172446 -0.00954895201033211 -0.0205343011559656 -0.0787216024622857 0.99668513171503 0.122983796898608 3.21049763872783e-05 -4.7783256145844e-05 -3.05779320290333e-06 -1.18438243384276e-05 -9.29577650888147e-06 -5.79917052953796e-06 -4.7783256145844e-05 0.000135242702357054 6.57599063560566e-06 6.27528380873812e-05 2.77573187123484e-05 3.65563926990735e-05 -3.05779320290333e-06 6.57599063560566e-06 9.42236312599343e-06 -6.53073356933877e-07 4.31790892670329e-06 -1.11167279289525e-06 -1.18438243384276e-05 6.27528380873812e-05 -6.53073356933877e-07 8.45085079937197e-05 1.58910470989152e-05 2.81904717811212e-05 -9.29577650888147e-06 2.77573187123484e-05 4.31790892670329e-06 1.58910470989152e-05 3.07160735953343e-05 1.23161960920846e-05 -5.79917052953796e-06 3.65563926990735e-05 -1.11167279289525e-06 2.81904717811212e-05 1.23161960920846e-05 3.8662959281589e-05 854 875 0 74 0 853 874 0 81 0 0 0 0 0 0 5 5 0 2824 0 0 0 0 0 2135 +859 925 0.999264926261156 0.0295599197525691 0.0244093893513919 0.0461597042238336 -0.0314923747729966 0.996051690726257 0.0830015646390064 -0.00585854610025064 -0.0218594939429827 -0.0837092620059913 0.99625043135698 0.12173352563008 2.90682657777408e-05 -3.3742293135982e-05 1.97588396743384e-06 -1.1778868264613e-05 -1.08507315243825e-05 -6.18783588310154e-06 -3.3742293135982e-05 7.56190978404331e-05 -1.72762062034891e-07 3.50934970361007e-05 1.88038710020871e-05 2.41264043667717e-05 1.97588396743384e-06 -1.72762062034891e-07 8.97524476363086e-06 -2.01883493133097e-07 2.51131927309208e-06 1.28210335538105e-07 -1.1778868264613e-05 3.50934970361007e-05 -2.01883493133097e-07 5.93025608483866e-05 1.15793478732244e-05 1.97302484084075e-05 -1.08507315243825e-05 1.88038710020871e-05 2.51131927309208e-06 1.15793478732244e-05 2.6563821860039e-05 9.10551083564679e-06 -6.18783588310154e-06 2.41264043667717e-05 1.28210335538105e-07 1.97302484084075e-05 9.10551083564679e-06 3.19215560999728e-05 887 908 0 69 0 887 908 0 82 0 0 0 0 0 0 0 2 0 2814 0 0 0 0 0 2124 +859 902 0.999466728281887 0.0298027252337084 0.0133437860498927 0.0359813218285647 -0.0307830086836975 0.996274837159449 0.0805534308350284 -0.0107645796693553 -0.0108933665081385 -0.0809212358504144 0.996660969514991 0.117445057296996 3.63837194511103e-05 -3.58945242942587e-05 -1.75935233377501e-06 -6.69839872207818e-06 -4.55682710363812e-06 -2.81791202255551e-06 -3.58945242942587e-05 8.72604603534549e-05 5.71279848368613e-06 2.26567463841628e-05 3.58875782549204e-06 1.91517151140812e-05 -1.75935233377501e-06 5.71279848368613e-06 1.10007636792279e-05 -8.20085598049049e-07 1.45187024899052e-06 2.24741622048008e-07 -6.69839872207818e-06 2.26567463841628e-05 -8.20085598049049e-07 4.6276598459792e-05 5.35589356512027e-06 1.47861471363807e-05 -4.55682710363812e-06 3.58875782549204e-06 1.45187024899052e-06 5.35589356512027e-06 2.6116576268913e-05 4.37018004896191e-06 -2.81791202255551e-06 1.91517151140812e-05 2.24741622048008e-07 1.47861471363807e-05 4.37018004896191e-06 3.31314878328007e-05 869 889 0 74 0 869 889 0 84 0 0 0 0 0 0 2 6 0 2929 0 0 0 0 0 904 +859 892 0.999257619643775 0.0291212833076418 0.0252222212021954 0.0441907767202842 -0.031105282894689 0.996129126402866 0.0822145054592203 -0.00761003588482546 -0.0227303972666072 -0.0829380153510974 0.996295445462702 0.121123417656744 2.37892894261433e-05 -2.5231868226924e-05 -1.56921975127114e-06 5.02058739169971e-06 9.95266161387294e-07 2.991863601813e-06 -2.5231868226924e-05 5.97032135585116e-05 3.84165028684484e-06 -9.60018951329453e-07 -7.59647133067731e-07 1.20041557225444e-05 -1.56921975127114e-06 3.84165028684484e-06 1.101550860864e-05 -3.85378832164918e-06 2.25879796464735e-06 -1.85705311551477e-06 5.02058739169971e-06 -9.60018951329453e-07 -3.85378832164918e-06 5.16046775725518e-05 9.03822856134969e-06 3.53481853638533e-06 9.95266161387294e-07 -7.59647133067731e-07 2.25879796464735e-06 9.03822856134969e-06 2.58461354209243e-05 3.54335566138326e-06 2.991863601813e-06 1.20041557225444e-05 -1.85705311551477e-06 3.53481853638533e-06 3.54335566138326e-06 2.7460434221388e-05 893 910 0 70 0 892 909 0 79 0 0 0 0 0 0 0 0 0 2944 0 0 0 0 0 1129 +859 896 0.999430212169692 0.0300221404767086 0.0154247231301403 0.0400419252423881 -0.0311605218678619 0.996323099884446 0.07980791009399 -0.00897274367326842 -0.0129720036758865 -0.0802430789404586 0.996690912671922 0.119353271180366 3.05290139097328e-05 -3.20387477276365e-05 -5.42375238700167e-07 -4.13338035372724e-06 -6.42189537115582e-06 4.26951108016631e-06 -3.20387477276365e-05 6.36254962661128e-05 1.5622572487434e-06 2.1722454593674e-05 1.10960756119026e-05 7.98313231256029e-06 -5.42375238700167e-07 1.5622572487434e-06 9.0208389681109e-06 -3.78415167437743e-07 2.54313617839367e-06 -1.13465912950989e-06 -4.13338035372724e-06 2.1722454593674e-05 -3.78415167437743e-07 5.69668897875549e-05 1.1262909896111e-05 1.05666544403066e-05 -6.42189537115582e-06 1.10960756119026e-05 2.54313617839367e-06 1.1262909896111e-05 2.78999324727103e-05 4.17376236741939e-06 4.26951108016631e-06 7.98313231256029e-06 -1.13465912950989e-06 1.05666544403066e-05 4.17376236741939e-06 2.81557352770274e-05 840 851 0 65 0 840 851 0 78 0 0 0 0 0 0 1 1 0 2845 0 0 0 0 0 2108 +859 921 0.999420313412673 0.0293633743380716 0.0172287372026425 0.0404561845313062 -0.0306594035826095 0.996280314292354 0.0805328276262927 -0.0108131482821571 -0.0147999361510148 -0.0810143666333927 0.996603047501319 0.118444013025847 2.55185874319854e-05 -2.94335750377304e-05 1.26772337635953e-06 -5.24735736169008e-06 -4.89177795613086e-06 9.94963932210219e-07 -2.94335750377304e-05 5.84834046566659e-05 4.99801579470888e-07 1.89607156139716e-05 9.72519017292378e-06 1.37020092808962e-05 1.26772337635953e-06 4.99801579470888e-07 9.08777027960968e-06 6.34068851732678e-07 2.07503962141148e-06 1.49618670897643e-06 -5.24735736169008e-06 1.89607156139716e-05 6.34068851732678e-07 4.90901170417125e-05 1.20174165840327e-05 1.26997194713367e-05 -4.89177795613086e-06 9.72519017292378e-06 2.07503962141148e-06 1.20174165840327e-05 2.80596100304515e-05 7.46251476445263e-06 9.94963932210219e-07 1.37020092808962e-05 1.49618670897643e-06 1.26997194713367e-05 7.46251476445263e-06 3.42435119272747e-05 871 880 0 62 0 871 880 0 73 0 0 0 0 0 0 0 0 0 2784 0 0 0 0 0 2097 +859 890 0.999543207294849 0.0301264011054984 0.00240347813728405 0.04560857572429 -0.0302122329063892 0.998085714798682 0.0539641260247316 -0.00196431987097764 -0.000773132288725428 -0.0540120900468928 0.998539982371878 0.119594688140481 4.02207502103538e-05 -5.48328498122572e-05 2.68227660337994e-06 -1.67109077991124e-05 -9.92191631114601e-06 5.37777627770929e-07 -5.48328498122572e-05 0.000124356184178016 -7.18133918968424e-07 5.91977272406424e-05 2.50149878096269e-05 2.09275115061104e-05 2.68227660337994e-06 -7.18133918968424e-07 1.01713532460082e-05 1.40154035162336e-06 2.50114606515367e-06 1.74595077847946e-06 -1.67109077991124e-05 5.91977272406424e-05 1.40154035162336e-06 8.04930448556113e-05 1.86904136933186e-05 1.74321687638565e-05 -9.92191631114601e-06 2.50149878096269e-05 2.50114606515367e-06 1.86904136933186e-05 3.06400944935326e-05 8.94016336031953e-06 5.37777627770929e-07 2.09275115061104e-05 1.74595077847946e-06 1.74321687638565e-05 8.94016336031953e-06 3.88280496575326e-05 857 871 0 65 0 855 869 0 68 0 0 0 0 0 0 0 0 0 2670 0 0 0 0 0 1957 +859 920 0.99923634351992 0.028845926832308 0.0263560675011577 0.0438199288529404 -0.0309143456309947 0.99617128982167 0.0817744738242782 -0.0120026115285198 -0.0238962972685696 -0.0825268067976418 0.996302310113068 0.123106373138491 3.04114453709604e-05 -3.03157353505623e-05 -4.36904256519134e-06 7.16063113370257e-07 -7.74313429660663e-07 -2.27258582426068e-06 -3.03157353505623e-05 6.31414643215488e-05 7.27162494586835e-06 5.79770756785442e-06 1.22052888993517e-06 2.37584163049968e-05 -4.36904256519134e-06 7.27162494586835e-06 1.10240411160763e-05 -7.87209425798854e-07 2.36180459668572e-06 -1.42940189967336e-06 7.16063113370257e-07 5.79770756785442e-06 -7.87209425798854e-07 3.60382934143876e-05 -1.92455392832355e-06 6.29351839351418e-06 -7.74313429660663e-07 1.22052888993517e-06 2.36180459668572e-06 -1.92455392832355e-06 2.38831438393647e-05 2.47335661876278e-06 -2.27258582426068e-06 2.37584163049968e-05 -1.42940189967336e-06 6.29351839351418e-06 2.47335661876278e-06 4.04464603598256e-05 908 923 0 73 0 908 923 0 83 0 0 0 0 0 0 0 3 0 2653 0 0 0 0 0 1691 +859 922 0.999397770500605 0.0291801361004247 0.0187780716683206 0.04255578539357 -0.0306404543851149 0.99609000882843 0.0828604662505133 -0.00772537437240395 -0.0162867698913437 -0.0833859338817972 0.996384226670197 0.117960723506223 3.34423726547334e-05 -3.79597583832223e-05 -1.66796231589866e-06 -3.3120506625627e-06 -6.27538137653183e-06 -3.20764227283142e-06 -3.79597583832223e-05 8.03333728440241e-05 4.64276158209975e-06 2.0061310553793e-05 1.30886216483248e-05 2.42979472044451e-05 -1.66796231589866e-06 4.64276158209975e-06 1.13850918135952e-05 -2.2781365671011e-06 3.31461690910494e-06 -5.22384713469809e-07 -3.3120506625627e-06 2.0061310553793e-05 -2.2781365671011e-06 5.08736266401928e-05 8.21653431097368e-06 1.51977946994116e-05 -6.27538137653183e-06 1.30886216483248e-05 3.31461690910494e-06 8.21653431097368e-06 2.80311359487157e-05 7.97766688780044e-06 -3.20764227283142e-06 2.42979472044451e-05 -5.22384713469809e-07 1.51977946994116e-05 7.97766688780044e-06 3.94082106465741e-05 901 910 0 68 0 901 910 0 79 0 0 0 0 0 0 1 1 0 2904 0 0 0 0 0 1069 +859 928 0.999483602736753 0.0295036771737654 0.012730313962651 0.0384046285348822 -0.0304460831680164 0.996199989957708 0.0816003433080288 -0.0103088416869063 -0.0102744284555229 -0.0819457933117263 0.996583826418242 0.11789826687595 3.19403622663984e-05 -3.67157180532828e-05 -1.94973995257977e-06 -2.02615177027863e-06 -4.42653242676923e-06 -4.56219133785493e-07 -3.67157180532828e-05 0.000105069445838078 5.64994243329617e-06 3.68263573628568e-05 1.12828683879197e-05 3.32075799185203e-05 -1.94973995257977e-06 5.64994243329617e-06 1.07521376516508e-05 -1.57660246956753e-06 1.12853755187875e-06 5.84185119299719e-07 -2.02615177027863e-06 3.68263573628568e-05 -1.57660246956753e-06 6.17556880312258e-05 8.39307098832507e-06 1.94556058611441e-05 -4.42653242676923e-06 1.12828683879197e-05 1.12853755187875e-06 8.39307098832507e-06 3.23959431172596e-05 5.47184480392499e-06 -4.56219133785493e-07 3.32075799185203e-05 5.84185119299719e-07 1.94556058611441e-05 5.47184480392499e-06 4.3479931346513e-05 892 908 0 75 0 891 907 0 90 0 0 0 0 0 0 3 4 0 2818 0 0 0 0 0 929 +859 889 0.999510639021873 0.0296484782678879 -0.00997247303761344 0.0437927203696699 -0.0292923808861265 0.998987825347461 0.0341362158062863 -0.00369804141023431 0.0109744660056622 -0.0338273933957354 0.999367434206229 0.118373796458616 3.28113050093961e-05 -3.3716472377211e-05 2.78104125060662e-06 -7.58020532544043e-06 -6.93316357091796e-06 7.58746031157747e-06 -3.3716472377211e-05 8.77888705431432e-05 -5.96119891579464e-07 5.0000267431965e-05 1.55708161339749e-05 4.81462806507818e-06 2.78104125060662e-06 -5.96119891579464e-07 1.24061439855e-05 -9.83981629032918e-07 2.40515408792933e-06 -5.75581130577952e-07 -7.58020532544043e-06 5.0000267431965e-05 -9.83981629032918e-07 9.29122010140727e-05 1.29421168324801e-05 1.44306262601905e-05 -6.93316357091796e-06 1.55708161339749e-05 2.40515408792933e-06 1.29421168324801e-05 3.41676047562691e-05 4.00100596071653e-06 7.58746031157747e-06 4.81462806507818e-06 -5.75581130577952e-07 1.44306262601905e-05 4.00100596071653e-06 2.72931314883403e-05 895 910 0 63 0 894 910 0 70 0 0 0 0 0 0 0 0 0 2585 0 0 0 0 0 1081 +860 931 0.992874226088648 -0.107295468965865 0.0518502990180693 0.0271563304180275 0.101088220113244 0.988742803326341 0.110312468128966 0.000976911938480027 -0.0631026380051143 -0.1042849519814 0.992543553637337 -0.0172879025424492 3.2048334508611e-05 -3.67728992053442e-05 -3.02871373689216e-06 -2.95713646539822e-06 -2.59737345260721e-06 5.30993486538559e-06 -3.67728992053442e-05 9.58806649515553e-05 7.68179986981923e-06 1.61054679891869e-05 -1.08778809792777e-06 1.72757731893565e-05 -3.02871373689216e-06 7.68179986981923e-06 1.00224955159374e-05 -1.97567387899784e-06 3.39832656470383e-06 -2.11885547163725e-06 -2.95713646539822e-06 1.61054679891869e-05 -1.97567387899784e-06 4.71253940317205e-05 -5.87761061221459e-06 6.13029145137982e-06 -2.59737345260721e-06 -1.08778809792777e-06 3.39832656470383e-06 -5.87761061221459e-06 2.15056729079431e-05 -1.40563849533313e-06 5.30993486538559e-06 1.72757731893565e-05 -2.11885547163725e-06 6.13029145137982e-06 -1.40563849533313e-06 4.09774518586566e-05 1276 1276 0 0 0 1243 1243 0 0 0 0 0 0 0 0 174 181 0 3117 0 0 0 0 0 1474 +859 924 0.99937942143642 0.0300619892981445 0.0183588890961333 0.0427659470420134 -0.031427245451717 0.996357964343691 0.0792662294562655 -0.00992241513407658 -0.0159091248258165 -0.0797940078472942 0.996684411465807 0.117794721745117 3.09604785714889e-05 -2.93260110927261e-05 8.64644053779376e-07 -9.85080954976579e-06 -9.86881334171176e-06 -5.73084935514852e-06 -2.93260110927261e-05 7.40719392391636e-05 1.90417997485143e-06 3.78072999441294e-05 1.84349175545377e-05 2.97921251171228e-05 8.64644053779376e-07 1.90417997485143e-06 1.01108830853159e-05 -1.38591040281712e-06 2.19076858298707e-06 -8.73635531175552e-07 -9.85080954976579e-06 3.78072999441294e-05 -1.38591040281712e-06 7.22911618534731e-05 1.63101164660892e-05 2.3903552643136e-05 -9.86881334171176e-06 1.84349175545377e-05 2.19076858298707e-06 1.63101164660892e-05 3.37602986539512e-05 1.41854113608068e-05 -5.73084935514852e-06 2.97921251171228e-05 -8.73635531175552e-07 2.3903552643136e-05 1.41854113608068e-05 4.42538012549257e-05 864 877 0 58 0 864 877 0 73 0 0 0 0 0 0 0 1 0 2835 0 0 0 0 0 1745 +860 863 0.996072015807369 -0.00268823108220685 -0.0885060039720049 0.0131643324237357 0.00354711098013427 0.999948122156001 0.00954835066294451 0.00337889342739422 0.0884757442983019 -0.00982478551097167 0.99602987719271 0.0525570601228782 5.09653803976986e-05 -6.94104822908242e-05 6.97313490522058e-06 -3.26795792466655e-05 -1.88777059544418e-05 1.05320173694874e-06 -6.94104822908242e-05 0.000137941800735255 -9.57766875595262e-06 8.6603424678421e-05 3.94385984539314e-05 1.69872436689314e-05 6.97313490522058e-06 -9.57766875595262e-06 1.07916879952337e-05 -5.97274771620201e-06 -2.67752740117761e-06 -6.44624153827185e-07 -3.26795792466655e-05 8.6603424678421e-05 -5.97274771620201e-06 0.000127843703962262 4.28437442566054e-05 2.12376801468951e-05 -1.88777059544418e-05 3.94385984539314e-05 -2.67752740117761e-06 4.28437442566054e-05 4.28809500462866e-05 8.92895412204873e-06 1.05320173694874e-06 1.69872436689314e-05 -6.44624153827185e-07 2.12376801468951e-05 8.92895412204873e-06 3.375160210274e-05 1010 1001 0 9 0 980 988 0 23 0 0 0 0 0 0 3 12 0 2642 0 0 0 0 0 1865 +859 926 0.999457162606908 0.0299461551237141 0.013733459398709 0.0366003398094652 -0.030938196834885 0.996406423072369 0.0788483863926996 -0.0109876603459214 -0.011322901145707 -0.0792304730102818 0.996792016448874 0.115687640700862 3.17512446975526e-05 -3.64736021228927e-05 1.31418814502988e-06 -1.15025828297126e-05 -4.79100134186242e-06 -8.16372580841263e-06 -3.64736021228927e-05 8.40941432803948e-05 9.72449763226742e-07 3.67707604396867e-05 1.21247215555712e-05 3.14295474129748e-05 1.31418814502988e-06 9.72449763226742e-07 9.25459522756502e-06 1.57957504027401e-07 3.10271375140687e-06 6.36199184875313e-07 -1.15025828297126e-05 3.67707604396867e-05 1.57957504027401e-07 5.51300363891189e-05 9.12027959385347e-06 2.50369020565058e-05 -4.79100134186242e-06 1.21247215555712e-05 3.10271375140687e-06 9.12027959385347e-06 2.37151769940428e-05 1.04702610700131e-05 -8.16372580841263e-06 3.14295474129748e-05 6.36199184875313e-07 2.50369020565058e-05 1.04702610700131e-05 4.46967561321206e-05 877 897 0 67 0 877 897 0 83 0 0 0 0 0 0 1 5 0 2849 0 0 0 0 0 1763 +860 930 0.9971987103286 -0.0360443319683902 0.0655403559032886 0.0200249184997342 0.0275773763681299 0.99167394403189 0.125786632997657 -0.0132917612131775 -0.0695285583888215 -0.123626837139794 0.989889986163706 0.0461731956148529 2.43223016321956e-05 -1.90667408376981e-05 -1.04881601072895e-06 4.6340332396598e-06 8.19091549328718e-08 3.94552418155385e-06 -1.90667408376981e-05 5.17981664432159e-05 4.26460010849729e-06 6.39320927326352e-06 -1.47885418755764e-06 1.39521356746619e-05 -1.04881601072895e-06 4.26460010849729e-06 1.09011189250556e-05 -2.217065618979e-06 3.00781527556725e-06 -1.10681317901886e-06 4.6340332396598e-06 6.39320927326352e-06 -2.217065618979e-06 4.51653957549142e-05 -9.28560857668732e-07 9.31695180063196e-06 8.19091549328718e-08 -1.47885418755764e-06 3.00781527556725e-06 -9.28560857668732e-07 2.29757212682853e-05 1.02441073724013e-06 3.94552418155385e-06 1.39521356746619e-05 -1.10681317901886e-06 9.31695180063196e-06 1.02441073724013e-06 2.70406220203968e-05 1214 1212 0 2 0 1222 1222 0 4 0 0 0 0 0 0 46 60 0 3048 0 0 0 0 0 1298 +859 927 0.999396691210366 0.0305312460468336 0.0165558633903459 0.0427331353774053 -0.0317527913884149 0.996338744402388 0.0793779984738577 -0.00706719861749709 -0.0140717389407242 -0.0798558039061636 0.996707096766991 0.117593419951779 2.87147970748757e-05 -2.79219630613799e-05 -4.06711395777892e-07 -3.89055356069297e-06 -4.60970197094045e-06 3.3122723426849e-07 -2.79219630613799e-05 8.00405228316782e-05 2.02143303435741e-06 3.50210055375101e-05 1.20431723327521e-05 2.63658520203432e-05 -4.06711395777892e-07 2.02143303435741e-06 9.63336201411707e-06 -4.9216797502022e-07 2.50727669502618e-06 -6.36665158508983e-07 -3.89055356069297e-06 3.50210055375101e-05 -4.9216797502022e-07 6.66177840621462e-05 1.16089116792938e-05 2.18731828112546e-05 -4.60970197094045e-06 1.20431723327521e-05 2.50727669502618e-06 1.16089116792938e-05 2.77222055491926e-05 9.44915158285666e-06 3.3122723426849e-07 2.63658520203432e-05 -6.36665158508983e-07 2.18731828112546e-05 9.44915158285666e-06 3.94506220149668e-05 863 884 0 75 0 863 884 0 86 0 0 0 0 0 0 0 4 0 2893 0 0 0 0 0 1748 +859 903 0.999406972016767 0.0300636252481269 0.0167893633356703 0.0387873901088016 -0.0312983820052475 0.996391021825888 0.0789008422554262 -0.0100480945835422 -0.014356725536506 -0.0793795317553728 0.996741076895182 0.117031417153087 3.75464132922225e-05 -4.06081149872892e-05 -1.44823608490861e-06 -5.99834830310427e-06 -6.29139593664642e-06 -4.1528450747818e-06 -4.06081149872892e-05 7.20944263393322e-05 3.83222001610945e-06 1.98104379588725e-05 9.9576166650109e-06 2.24332405912288e-05 -1.44823608490861e-06 3.83222001610945e-06 9.6472526401448e-06 -7.86280218305125e-07 3.11052828014795e-06 -1.01940159735208e-06 -5.99834830310427e-06 1.98104379588725e-05 -7.86280218305125e-07 4.8784110879116e-05 7.96048185507469e-06 1.58370516282503e-05 -6.29139593664642e-06 9.9576166650109e-06 3.11052828014795e-06 7.96048185507469e-06 3.00732922861355e-05 8.35160672564585e-06 -4.1528450747818e-06 2.24332405912288e-05 -1.01940159735208e-06 1.58370516282503e-05 8.35160672564585e-06 4.14144598198086e-05 869 885 0 69 0 869 885 0 80 0 0 0 0 0 0 0 1 0 2851 0 0 0 0 0 1763 +859 919 0.999334108695271 0.0296473040048931 0.0212691458095935 0.0425041074846995 -0.0312650972986752 0.996283095147026 0.0802651108213672 -0.0113019760481188 -0.0188104462768077 -0.0808766448951948 0.996546604741275 0.119995036779637 3.53103679039748e-05 -3.37545645010751e-05 -3.41750353949405e-06 1.65895354962381e-06 -3.11598746376884e-06 -6.13753758683175e-06 -3.37545645010751e-05 8.0149289509902e-05 7.92511966301499e-06 1.77544888991378e-05 2.92110695889754e-06 2.88795480781174e-05 -3.41750353949405e-06 7.92511966301499e-06 1.14429793782905e-05 -2.66540551640302e-06 2.51524294823069e-06 3.32667338516034e-07 1.65895354962381e-06 1.77544888991378e-05 -2.66540551640302e-06 5.46887553273167e-05 5.45533326922279e-06 1.03100103116344e-05 -3.11598746376884e-06 2.92110695889754e-06 2.51524294823069e-06 5.45533326922279e-06 2.99563383686286e-05 1.14781983525307e-06 -6.13753758683175e-06 2.88795480781174e-05 3.32667338516034e-07 1.03100103116344e-05 1.14781983525307e-06 3.75086720867722e-05 896 913 0 73 0 896 913 0 84 0 0 0 0 0 0 0 2 0 2650 0 0 0 0 0 1059 +859 918 0.999315933583114 0.0294669197843297 0.0223464879865745 0.04270843137712 -0.0311704598270294 0.996294072446302 0.0801656013670135 -0.0127118562740872 -0.0199014401760723 -0.0808073130773895 0.996531038569362 0.120509457764646 4.41463549881973e-05 -6.21196251786509e-05 -1.67216784520451e-06 -1.08667748524838e-05 -1.09269481147896e-05 -1.85434380771467e-05 -6.21196251786509e-05 0.000160773626456006 6.75332177533454e-06 4.75890125443606e-05 1.81522717747388e-05 6.64418836301738e-05 -1.67216784520451e-06 6.75332177533454e-06 9.89411057431803e-06 -2.06783696010071e-06 6.35684663198487e-07 8.15291610005554e-07 -1.08667748524838e-05 4.75890125443606e-05 -2.06783696010071e-06 6.67964345994787e-05 1.14061862938443e-05 3.42315754048322e-05 -1.09269481147896e-05 1.81522717747388e-05 6.35684663198487e-07 1.14061862938443e-05 3.26171423952395e-05 1.71211679063845e-05 -1.85434380771467e-05 6.64418836301738e-05 8.15291610005554e-07 3.42315754048322e-05 1.71211679063845e-05 6.50159325016808e-05 885 903 0 63 0 885 903 0 80 0 0 0 0 0 0 0 1 0 2566 0 0 0 0 0 1668 +859 916 0.999350352620917 0.0300034673446854 0.0199665886857274 0.0436930825030099 -0.0315378040319495 0.996167895606197 0.0815775133254453 -0.0090952373703146 -0.0174424663763749 -0.0821542190688783 0.996466981217086 0.118533989358621 2.52127933282538e-05 -2.46451999578112e-05 5.5726172056469e-07 -8.68049743028715e-06 -5.11945577891243e-06 -3.43333424250346e-07 -2.46451999578112e-05 7.35074834829947e-05 5.97302911226037e-06 1.42279603186474e-05 -3.15192901787465e-07 1.84146976473965e-05 5.5726172056469e-07 5.97302911226037e-06 1.12066155330899e-05 -3.55471574945474e-06 5.73364318937252e-07 4.66781970991858e-07 -8.68049743028715e-06 1.42279603186474e-05 -3.55471574945474e-06 4.82023290612618e-05 1.27963273269186e-05 8.77140093421714e-06 -5.11945577891243e-06 -3.15192901787465e-07 5.73364318937252e-07 1.27963273269186e-05 3.44103044766839e-05 5.75919676399633e-06 -3.43333424250346e-07 1.84146976473965e-05 4.66781970991858e-07 8.77140093421714e-06 5.75919676399633e-06 3.03211209752154e-05 865 884 0 73 0 865 884 0 84 0 0 0 0 0 0 2 6 0 2761 0 0 0 0 0 1049 +859 917 0.999280940840987 0.0303629423948851 0.0227088749407779 0.0477404100247193 -0.032128889979675 0.996119619061176 0.0819355780481981 -0.00519333740043081 -0.0201329506189465 -0.082606272464888 0.996378877761282 0.120943456902736 3.88984408236825e-05 -4.36425924490451e-05 -8.78234992596693e-07 -1.22169587201349e-05 -8.85859449934926e-06 -5.25548822848965e-06 -4.36425924490451e-05 0.000110333895159621 6.50923573724437e-06 2.65288872530829e-05 4.21516323341587e-06 4.07087816551346e-05 -8.78234992596693e-07 6.50923573724437e-06 1.02973871527941e-05 -9.83418034692294e-07 -1.14921311979678e-06 2.81465678691589e-06 -1.22169587201349e-05 2.65288872530829e-05 -9.83418034692294e-07 7.78797977182797e-05 2.86117018087736e-05 1.79784521245018e-05 -8.85859449934926e-06 4.21516323341587e-06 -1.14921311979678e-06 2.86117018087736e-05 4.29179868966766e-05 3.31849312129472e-06 -5.25548822848965e-06 4.07087816551346e-05 2.81465678691589e-06 1.79784521245018e-05 3.31849312129472e-06 5.23947355923628e-05 868 884 0 75 0 868 884 0 80 0 0 0 0 0 0 0 2 0 2522 0 0 0 0 0 1397 +859 915 0.999402087627052 0.0298522483493442 0.0174444981349409 0.0383769006294454 -0.0311488453141672 0.996347270580795 0.0795101618775454 -0.010732077095186 -0.0150072210047351 -0.0800059977419723 0.996681405286076 0.11724892181379 2.30916870788439e-05 -2.55669293071974e-05 -7.21299327323057e-07 -3.46741060658152e-06 -1.54781529419705e-06 1.28737616029854e-06 -2.55669293071974e-05 6.51509397859441e-05 2.26631151372962e-06 2.32871563469457e-05 8.16370634505431e-06 1.55615032848318e-05 -7.21299327323057e-07 2.26631151372962e-06 9.79217554660079e-06 -1.62616187391253e-06 1.84110479506794e-06 -5.3806691680436e-07 -3.46741060658152e-06 2.32871563469457e-05 -1.62616187391253e-06 5.6234704437029e-05 1.43514511019545e-05 1.70428793554925e-05 -1.54781529419705e-06 8.16370634505431e-06 1.84110479506794e-06 1.43514511019545e-05 2.63802627033572e-05 6.31165523731911e-06 1.28737616029854e-06 1.55615032848318e-05 -5.3806691680436e-07 1.70428793554925e-05 6.31165523731911e-06 3.19230386594119e-05 866 882 0 72 0 866 882 0 84 0 0 0 0 0 0 2 6 0 2901 0 0 0 0 0 1735 +860 862 0.997376691410098 5.45961094727529e-05 -0.0723859962362229 0.0148054177761499 0.000743476177745327 0.999939241127634 0.010998240598617 0.00531525797281838 0.0723821986058642 -0.0110232060833849 0.997316051336097 0.0416136497539412 2.88081789718912e-05 -2.72663861716692e-05 2.24467460742143e-07 1.48747277532701e-06 -3.10436989986709e-06 7.60642140102041e-06 -2.72663861716692e-05 5.70248021531333e-05 4.0096758549469e-07 1.5828576138132e-05 7.18252725089183e-07 9.72899528524004e-07 2.24467460742143e-07 4.0096758549469e-07 1.05883818384078e-05 -1.86188491957254e-06 3.74082740010855e-06 2.52575323037974e-07 1.48747277532701e-06 1.5828576138132e-05 -1.86188491957254e-06 4.94665678024582e-05 -1.29291981102582e-06 4.66092947870019e-06 -3.10436989986709e-06 7.18252725089183e-07 3.74082740010855e-06 -1.29291981102582e-06 3.18046405598946e-05 -7.79578764531459e-06 7.60642140102041e-06 9.72899528524004e-07 2.52575323037974e-07 4.66092947870019e-06 -7.79578764531459e-06 3.52750562293042e-05 1205 1195 0 11 0 1161 1166 0 23 0 0 0 0 0 0 7 13 0 2677 0 0 0 0 0 2167 +860 929 0.99949022665697 0.0266169024035819 0.0176302956196799 0.0286943754100121 -0.0286232959939651 0.991674976225743 0.125544607427456 -0.018340015219637 -0.0141419144263062 -0.125985245303212 0.991931310233853 0.087922224912897 2.0611156064925e-05 -1.87009122331043e-05 -4.12423487821936e-07 1.02584184597714e-06 -1.27595562845362e-06 5.61580372280133e-06 -1.87009122331043e-05 5.93846492469952e-05 3.28844201431995e-06 8.51322124973761e-06 2.21535237855191e-06 1.24816404060933e-05 -4.12423487821936e-07 3.28844201431995e-06 9.11039133922153e-06 -6.19296658422445e-07 2.94891402531217e-06 -6.96907333086907e-07 1.02584184597714e-06 8.51322124973761e-06 -6.19296658422445e-07 3.73884271561547e-05 -1.87295981389531e-06 5.93922278775067e-06 -1.27595562845362e-06 2.21535237855191e-06 2.94891402531217e-06 -1.87295981389531e-06 1.84639168321433e-05 2.54984666722096e-06 5.61580372280133e-06 1.24816404060933e-05 -6.96907333086907e-07 5.93922278775067e-06 2.54984666722096e-06 2.88395855555301e-05 920 939 0 67 0 919 938 0 86 0 0 0 0 0 0 0 0 0 2902 0 0 0 0 0 1828 +860 864 0.994616116531422 -0.0129929912343872 -0.102810324942271 0.0153109023059227 0.01328699571341 0.999909357730491 0.00217533167795306 0.00272285063455955 0.102772741915665 -0.0035296602924957 0.994698600088165 0.0601637006751977 2.93863181503847e-05 -3.58455912972979e-05 3.04433397689268e-06 -1.06702500364986e-05 -9.4124063130778e-06 5.97707389881017e-06 -3.58455912972979e-05 9.77361843385611e-05 -7.60361386284016e-06 4.95025243162868e-05 2.37883350037968e-05 1.29232127745236e-06 3.04433397689268e-06 -7.60361386284016e-06 1.00813023754082e-05 -2.92930026138431e-06 2.35003871236064e-07 -1.80223097629952e-06 -1.06702500364986e-05 4.95025243162868e-05 -2.92930026138431e-06 7.39209804631907e-05 1.77609227553933e-05 1.39797804044229e-05 -9.4124063130778e-06 2.37883350037968e-05 2.35003871236064e-07 1.77609227553933e-05 3.16865103247386e-05 4.10946769028935e-06 5.97707389881017e-06 1.29232127745236e-06 -1.80223097629952e-06 1.39797804044229e-05 4.10946769028935e-06 3.05076822442988e-05 1002 997 0 3 0 972 979 0 13 0 0 0 0 0 0 4 11 0 2536 0 0 0 0 0 2332 +860 900 0.998792928120875 0.0482601051879767 0.00914598179393753 0.0304644976952431 -0.0489596937700268 0.99313028978559 0.106278765030156 -0.0177979630581425 -0.00395412716978329 -0.106598263389398 0.994294310111795 0.0950572752463419 4.1393879070531e-05 -4.69174484309366e-05 3.54923039043357e-06 -1.6827313796372e-05 -8.68943819097723e-06 -8.84528598422444e-06 -4.69174484309366e-05 9.16451957040196e-05 3.40913846680206e-08 3.15556050761481e-05 1.24105533180942e-05 3.1750801071334e-05 3.54923039043357e-06 3.40913846680206e-08 1.08224487171798e-05 -4.18997191250216e-06 4.38379664789083e-06 3.63133264085932e-07 -1.6827313796372e-05 3.15556050761481e-05 -4.18997191250216e-06 5.79015651609138e-05 9.2620167713754e-06 2.12571446051323e-05 -8.68943819097723e-06 1.24105533180942e-05 4.38379664789083e-06 9.2620167713754e-06 2.4962065453081e-05 1.14454979759804e-05 -8.84528598422444e-06 3.1750801071334e-05 3.63133264085932e-07 2.12571446051323e-05 1.14454979759804e-05 4.6112691417939e-05 935 952 0 93 0 935 952 0 97 0 0 0 0 0 0 0 0 0 2815 0 0 0 0 0 1729 +860 892 0.998719718043517 0.0478600780275938 0.0163810171317211 0.0380152726878936 -0.0493524821650895 0.99293804877253 0.107881248620624 -0.0135105497067698 -0.0111021302109832 -0.108551574060412 0.994028821752058 0.0964691301419404 2.25750870017126e-05 -2.23764240078232e-05 -1.97634181476439e-06 -1.44872818637165e-07 2.51558705140197e-06 6.69959729837225e-06 -2.23764240078232e-05 6.00926823522645e-05 4.97824811217498e-06 2.00410737923445e-06 -3.79856270374862e-06 5.13315714122756e-06 -1.97634181476439e-06 4.97824811217498e-06 9.64761350423566e-06 -1.51192600034738e-06 2.53862914384923e-06 -2.34878830427689e-06 -1.44872818637165e-07 2.00410737923445e-06 -1.51192600034738e-06 4.87767621470441e-05 7.98011141110056e-06 -4.02284587299065e-07 2.51558705140197e-06 -3.79856270374862e-06 2.53862914384923e-06 7.98011141110056e-06 2.30982681506135e-05 2.13479744627003e-06 6.69959729837225e-06 5.13315714122756e-06 -2.34878830427689e-06 -4.02284587299065e-07 2.13479744627003e-06 2.59523656396481e-05 916 937 0 96 0 915 937 0 104 0 0 0 0 0 0 0 0 0 2894 0 0 0 0 0 1732 +860 895 0.998768336123321 0.0474700486502513 0.0144362473862263 0.0324262402302903 -0.0487374751996099 0.993155862875411 0.106141841642992 -0.0166170507800791 -0.00929888534293035 -0.106714696819798 0.99424619899401 0.0945974115862711 3.07757917021602e-05 -2.99536183370757e-05 -1.11003354428145e-06 -3.16719289572217e-06 -1.68239435423264e-06 6.63625454513856e-06 -2.99536183370757e-05 5.1237873761848e-05 2.90285091834228e-06 8.41237994337641e-06 4.04711597929112e-06 4.53467962650582e-06 -1.11003354428145e-06 2.90285091834228e-06 1.1100626580532e-05 -3.54236672442802e-06 4.36635420551302e-06 -1.7412989848851e-06 -3.16719289572217e-06 8.41237994337641e-06 -3.54236672442802e-06 4.59422712475316e-05 6.40839783945018e-06 4.99102601283758e-06 -1.68239435423264e-06 4.04711597929112e-06 4.36635420551302e-06 6.40839783945018e-06 2.68861924189499e-05 6.66223048702627e-06 6.63625454513856e-06 4.53467962650582e-06 -1.7412989848851e-06 4.99102601283758e-06 6.66223048702627e-06 3.39566754132682e-05 922 943 0 99 0 920 941 0 108 0 0 0 0 0 0 0 0 0 2816 0 0 0 0 0 1622 +860 897 0.998714833653284 0.0480272977103683 0.016188258570131 0.0347528243757332 -0.0495121359812622 0.992786726978352 0.109192779643084 -0.0154320374311314 -0.0108272541055786 -0.109853964017006 0.993888764982422 0.0967773107871597 2.83977160158944e-05 -2.10539574081629e-05 6.34329934551025e-08 1.05197529021017e-06 -4.06369945729466e-06 3.67541157802607e-06 -2.10539574081629e-05 3.6196745034045e-05 2.00244212927489e-06 3.09711070875624e-06 4.67194867393705e-06 2.17262071436397e-06 6.34329934551025e-08 2.00244212927489e-06 9.40816270959264e-06 -4.46488081215003e-06 4.46171870578893e-06 -1.34123884199842e-06 1.05197529021017e-06 3.09711070875624e-06 -4.46488081215003e-06 4.34807763107169e-05 -1.57416219202334e-06 5.57875656095327e-06 -4.06369945729466e-06 4.67194867393705e-06 4.46171870578893e-06 -1.57416219202334e-06 2.13835199740477e-05 4.7891409449696e-06 3.67541157802607e-06 2.17262071436397e-06 -1.34123884199842e-06 5.57875656095327e-06 4.7891409449696e-06 2.58663163871514e-05 953 965 0 89 0 951 964 0 98 0 0 0 0 0 0 0 0 0 2750 0 0 0 0 0 1744 +860 898 0.998731036836811 0.048341556206553 0.0141212606518092 0.033239637825781 -0.0495849867347573 0.992938271820153 0.107772526393893 -0.0141942407088412 -0.00881164850533673 -0.108335969549993 0.994075285153132 0.0970016636223362 3.74954509995368e-05 -4.28115809388009e-05 -5.21384996340739e-06 -9.76442111412299e-07 2.28224664526846e-06 4.01600952892928e-06 -4.28115809388009e-05 7.72455650649731e-05 6.32882126969482e-06 1.384645265265e-05 1.24929218002673e-06 1.1215094697716e-05 -5.21384996340739e-06 6.32882126969482e-06 1.16826181267176e-05 -4.00815998039056e-06 3.12524941270736e-06 -2.10877894244672e-06 -9.76442111412299e-07 1.384645265265e-05 -4.00815998039056e-06 4.68395087187687e-05 2.76022995614565e-06 5.31949091766964e-06 2.28224664526846e-06 1.24929218002673e-06 3.12524941270736e-06 2.76022995614565e-06 2.23510396180293e-05 5.23566370277967e-06 4.01600952892928e-06 1.1215094697716e-05 -2.10877894244672e-06 5.31949091766964e-06 5.23566370277967e-06 3.57177718268525e-05 921 936 0 93 0 920 936 0 103 0 0 0 0 0 0 0 0 0 2883 0 0 0 0 0 1558 +860 932 0.983102753184142 -0.182840657738456 -0.00884706502340688 0.0433415564523538 0.182817569399793 0.978224004842594 0.0982625700278031 0.0152868829350802 -0.00931198155665473 -0.098219602053184 0.995121197026775 -0.096543341371251 2.80805057984167e-05 -2.32145107145326e-05 -5.17733054254901e-07 9.19631528728783e-07 -5.45461730556676e-06 1.85973097362531e-05 -2.32145107145326e-05 0.000106906311581124 3.93149775486257e-06 3.51729062091774e-05 2.40615584230231e-06 -2.50056942168483e-06 -5.17733054254901e-07 3.93149775486257e-06 9.65950201176908e-06 -6.30665211637096e-07 2.45496471199923e-06 -1.49568917180694e-06 9.19631528728783e-07 3.51729062091774e-05 -6.30665211637096e-07 6.61487698987136e-05 3.68126733335536e-06 5.91290672852125e-06 -5.45461730556676e-06 2.40615584230231e-06 2.45496471199923e-06 3.68126733335536e-06 2.97243523153745e-05 1.54328651990385e-06 1.85973097362531e-05 -2.50056942168483e-06 -1.49568917180694e-06 5.91290672852125e-06 1.54328651990385e-06 4.57242517927892e-05 1401 1401 0 0 0 1373 1373 0 0 0 0 0 0 0 0 347 347 0 2750 0 0 0 0 0 1994 +860 890 0.998856088041993 0.0478156603963805 0.000421903192768245 0.040031591274658 -0.0476900550876306 0.995510864851795 0.08175436751495 -0.0064118012850178 0.00348912986069929 -0.0816809683028352 0.99665241954752 0.0952826279547019 2.78593817915667e-05 -2.66792107024064e-05 5.04458066111387e-08 -3.99582222480395e-06 -6.73888410178719e-06 6.184010881153e-06 -2.66792107024064e-05 5.03050855835322e-05 2.37779293890693e-06 1.3229888095293e-05 9.04820352131755e-06 3.93490002516332e-06 5.04458066111387e-08 2.37779293890693e-06 1.0858468670949e-05 -2.350634031319e-06 3.91257336744183e-06 -2.53387566123203e-06 -3.99582222480395e-06 1.3229888095293e-05 -2.350634031319e-06 5.10731965820214e-05 7.80198251833615e-06 1.13369792113536e-05 -6.73888410178719e-06 9.04820352131755e-06 3.91257336744183e-06 7.80198251833615e-06 2.66386625395978e-05 8.09003175726708e-07 6.184010881153e-06 3.93490002516332e-06 -2.53387566123203e-06 1.13369792113536e-05 8.09003175726708e-07 2.70468628194933e-05 938 957 0 93 0 932 953 0 95 0 0 0 0 0 0 0 0 0 2634 0 0 0 0 0 2094 +860 893 0.998787181279065 0.0467730704973443 0.0153768133522696 0.0318475015402622 -0.0481279685004533 0.993357274644656 0.104522837497656 -0.0200403999876673 -0.0103858153574697 -0.105136125032229 0.994403605208955 0.0930148067455872 4.52241075038593e-05 -4.94745901933019e-05 -5.13504599321311e-06 -4.29220599106544e-06 -4.5592583905333e-06 -3.00986564403158e-06 -4.94745901933019e-05 7.21570692828364e-05 8.06509345248342e-06 1.1237302224236e-05 6.39705027674264e-06 1.67241519973997e-05 -5.13504599321311e-06 8.06509345248342e-06 1.21197353468818e-05 -1.39765928476894e-06 3.04701676563785e-06 -1.05409587937698e-06 -4.29220599106544e-06 1.1237302224236e-05 -1.39765928476894e-06 5.01451041026128e-05 5.70180728730409e-06 1.25839619779916e-05 -4.5592583905333e-06 6.39705027674264e-06 3.04701676563785e-06 5.70180728730409e-06 2.36469788618509e-05 5.64295697466641e-06 -3.00986564403158e-06 1.67241519973997e-05 -1.05409587937698e-06 1.25839619779916e-05 5.64295697466641e-06 3.89296592563363e-05 990 1005 0 89 0 990 1005 0 95 0 0 0 0 0 0 0 0 0 2763 0 0 0 0 0 1317 +860 894 0.998734768543272 0.0478294033963791 0.0155309456751118 0.0365890813191399 -0.0492307774390534 0.992932855730974 0.107984603359369 -0.0164302356213134 -0.0102563470867181 -0.108612578372306 0.994031244561134 0.094717387038288 3.5012936125584e-05 -3.70954793874166e-05 1.15874537793899e-06 -7.09229546228235e-06 -6.73693065016397e-06 -7.84396839504572e-07 -3.70954793874166e-05 6.59376064572051e-05 2.34689188336137e-06 1.93512304255623e-05 1.14992063308032e-05 1.45621509751267e-05 1.15874537793899e-06 2.34689188336137e-06 1.01163958886517e-05 -1.87495120841394e-06 4.44920842123286e-06 4.72477695639538e-08 -7.09229546228235e-06 1.93512304255623e-05 -1.87495120841394e-06 5.32093796998048e-05 6.98065749421081e-06 1.39471321381968e-05 -6.73693065016397e-06 1.14992063308032e-05 4.44920842123286e-06 6.98065749421081e-06 2.39244975874475e-05 8.20937098625125e-06 -7.84396839504572e-07 1.45621509751267e-05 4.72477695639538e-08 1.39471321381968e-05 8.20937098625125e-06 3.67588326295757e-05 915 934 0 102 0 915 934 0 109 0 0 0 0 0 0 0 0 0 2758 0 0 0 0 0 1729 +860 924 0.998746729966945 0.0474234191356497 0.0159996468029503 0.0345993344686726 -0.0488657085825427 0.993074039781175 0.106846123174509 -0.0189483271512514 -0.0108218254033538 -0.107494050208283 0.994146828825983 0.0959789341783761 3.5748982845988e-05 -4.42239004345225e-05 -2.47400754698558e-06 -1.24117855741216e-05 -5.41920545837832e-06 -4.87285133312886e-06 -4.42239004345225e-05 9.80916967124788e-05 5.55448531549929e-06 4.20135754403236e-05 1.44442101657201e-05 2.82704280374843e-05 -2.47400754698558e-06 5.55448531549929e-06 1.00423514663683e-05 -1.21932246929656e-06 4.15847147637768e-06 -3.28486761632545e-07 -1.24117855741216e-05 4.20135754403236e-05 -1.21932246929656e-06 6.40921442974651e-05 7.72578408895463e-06 1.95460645846007e-05 -5.41920545837832e-06 1.44442101657201e-05 4.15847147637768e-06 7.72578408895463e-06 2.54605410878344e-05 8.83215354317793e-06 -4.87285133312886e-06 2.82704280374843e-05 -3.28486761632545e-07 1.95460645846007e-05 8.83215354317793e-06 3.90065875745965e-05 917 931 0 95 0 916 931 0 101 0 0 0 0 0 0 0 0 0 2791 0 0 0 0 0 1357 +860 896 0.998697035425191 0.048246072547315 0.0166297299044008 0.0392780750470513 -0.0497510632007015 0.993033690823568 0.106812548886924 -0.015413725464021 -0.0113605960818041 -0.107500722663063 0.994140096507321 0.0965924857914868 2.88171039509448e-05 -3.55213837578293e-05 -2.56656685463553e-06 -4.23741337511648e-06 -5.38639265334507e-06 5.88129614269513e-06 -3.55213837578293e-05 9.7651327292086e-05 7.60266528010328e-06 2.78739029729422e-05 1.31912884571705e-05 6.26063933693611e-06 -2.56656685463553e-06 7.60266528010328e-06 9.85171317067205e-06 3.62500057910628e-07 4.23488711681324e-06 -1.02133555178148e-06 -4.23741337511648e-06 2.78739029729422e-05 3.62500057910628e-07 5.5575383918896e-05 5.29074181564547e-06 7.90122656306671e-06 -5.38639265334507e-06 1.31912884571705e-05 4.23488711681324e-06 5.29074181564547e-06 2.4546712127592e-05 6.07185494726742e-06 5.88129614269513e-06 6.26063933693611e-06 -1.02133555178148e-06 7.90122656306671e-06 6.07185494726742e-06 2.79653501648838e-05 898 916 0 96 0 898 916 0 99 0 0 0 0 0 0 0 0 0 2797 0 0 0 0 0 1519 +860 899 0.998572543040443 0.0475365851982374 0.024354657735915 0.0388983471252682 -0.0499502318809784 0.992608625733758 0.110603302183875 -0.0131372700114629 -0.0189169400479925 -0.111661941531713 0.993566183096319 0.0988306116758336 4.39503763295306e-05 -5.13623353674455e-05 -2.06221876270236e-06 -1.61058785529783e-05 -6.58063112951695e-06 -9.70990002843646e-07 -5.13623353674455e-05 0.000104802837696242 4.73106352366487e-06 4.94970693428004e-05 1.91432100884977e-05 2.75287874941594e-05 -2.06221876270236e-06 4.73106352366487e-06 9.57634023123266e-06 -5.26164635447367e-07 3.53626847451202e-06 9.76932314815756e-08 -1.61058785529783e-05 4.94970693428004e-05 -5.26164635447367e-07 6.70658743712852e-05 1.57431350821781e-05 2.6849105970117e-05 -6.58063112951695e-06 1.91432100884977e-05 3.53626847451202e-06 1.57431350821781e-05 2.67241066411492e-05 1.35360107030616e-05 -9.70990002843646e-07 2.75287874941594e-05 9.76932314815756e-08 2.6849105970117e-05 1.35360107030616e-05 4.17459789296682e-05 911 921 0 78 0 910 921 0 85 0 0 0 0 0 0 0 0 0 2891 0 0 0 0 0 1822 +860 901 0.998699829164222 0.0479495627167207 0.0173057985261709 0.0358331673815637 -0.0495465816708824 0.992885967681448 0.108270916805971 -0.0164234811070182 -0.0119911414003726 -0.108987589277633 0.993970783228243 0.0961909773382773 3.52786780521966e-05 -4.75626113163297e-05 -1.17115969381323e-06 -9.88794751248463e-06 -4.98914546961456e-06 5.89731055850069e-06 -4.75626113163297e-05 0.000116196872245875 4.33948979448005e-06 5.37924476291318e-05 2.27413647812301e-05 1.71062759521032e-05 -1.17115969381323e-06 4.33948979448005e-06 9.99576576965218e-06 -2.07856807405036e-06 4.97340757628707e-06 -1.49920019899573e-06 -9.88794751248463e-06 5.37924476291318e-05 -2.07856807405036e-06 7.45564615344831e-05 1.45409324675298e-05 2.81055062013939e-05 -4.98914546961456e-06 2.27413647812301e-05 4.97340757628707e-06 1.45409324675298e-05 2.7218725243158e-05 1.48626070793381e-05 5.89731055850069e-06 1.71062759521032e-05 -1.49920019899573e-06 2.81055062013939e-05 1.48626070793381e-05 4.02068405876731e-05 906 920 0 93 0 906 920 0 101 0 0 0 0 0 0 0 0 0 2760 0 0 0 0 0 1764 +860 891 0.998758500217351 0.0475592513504674 0.0148180921366876 0.0336962517620425 -0.0488419498188868 0.993420265252149 0.103588805014056 -0.0148274860536466 -0.00979398700620091 -0.104183944047698 0.994509820776642 0.097907725266432 4.15962571331419e-05 -5.97090667694632e-05 -5.59275620237571e-06 -1.31144058320569e-05 -9.91992123307845e-06 -4.0581082234557e-06 -5.97090667694632e-05 0.000155740790427757 1.1712409295465e-05 5.73410701031888e-05 2.43986289247417e-05 2.27632237264382e-05 -5.59275620237571e-06 1.1712409295465e-05 1.06223975475813e-05 1.46959773681654e-06 4.62261131981918e-06 -1.94790698933113e-06 -1.31144058320569e-05 5.73410701031888e-05 1.46959773681654e-06 5.97059733518961e-05 1.14009802206904e-05 1.3572720407716e-05 -9.91992123307845e-06 2.43986289247417e-05 4.62261131981918e-06 1.14009802206904e-05 2.69389460956256e-05 6.16377503157495e-06 -4.0581082234557e-06 2.27632237264382e-05 -1.94790698933113e-06 1.3572720407716e-05 6.16377503157495e-06 2.90602394229759e-05 877 894 0 97 0 876 893 0 116 0 0 0 0 0 0 0 0 0 2786 0 0 0 0 0 1971 +860 925 0.998729227721271 0.0480965636367509 0.0150549082232284 0.0353176859500498 -0.049437552920554 0.993001138808596 0.107259809276628 -0.0148436887425474 -0.00979071276778563 -0.107867784306378 0.99411703689874 0.0951747962556619 2.40879825183197e-05 -2.28243480425971e-05 7.00972856466324e-07 -4.60828357703273e-06 -3.42500047420068e-06 3.29268417876496e-06 -2.28243480425971e-05 5.52928423107412e-05 3.02428110175502e-06 7.99524102499964e-06 1.70790798674239e-06 9.3139859531844e-06 7.00972856466324e-07 3.02428110175502e-06 1.10610439155809e-05 -5.76815010275747e-06 4.07254496494556e-06 -1.14425143331449e-06 -4.60828357703273e-06 7.99524102499964e-06 -5.76815010275747e-06 4.54025849221022e-05 5.15066933601736e-07 6.04860563190589e-06 -3.42500047420068e-06 1.70790798674239e-06 4.07254496494556e-06 5.15066933601736e-07 2.30291448201123e-05 4.17104971520384e-06 3.29268417876496e-06 9.3139859531844e-06 -1.14425143331449e-06 6.04860563190589e-06 4.17104971520384e-06 2.67051182021841e-05 929 950 0 98 0 927 949 0 107 0 0 0 0 0 0 0 0 0 2754 0 0 0 0 0 1560 +860 927 0.998712238502497 0.0480337472270394 0.01632861882283 0.0374977565929134 -0.0495144780842084 0.992978578812568 0.10743304184198 -0.0146976573294738 -0.0110535571369963 -0.108103196745984 0.994078225155303 0.0967296551786961 4.18730236704194e-05 -6.06472197904991e-05 -3.75545623576262e-06 -1.1146675124036e-05 -5.00039008086039e-06 -9.82469718789294e-06 -6.06472197904991e-05 0.000145344980863574 8.97081110593149e-06 4.44487445538548e-05 1.47932608305506e-05 4.18841631618861e-05 -3.75545623576262e-06 8.97081110593149e-06 1.05312517189341e-05 -2.67596635137038e-06 4.42613970549188e-06 -8.82447749686672e-07 -1.1146675124036e-05 4.44487445538548e-05 -2.67596635137038e-06 5.69088869486749e-05 5.02761421398117e-06 2.39722130476507e-05 -5.00039008086039e-06 1.47932608305506e-05 4.42613970549188e-06 5.02761421398117e-06 2.36693523341039e-05 1.03607717185189e-05 -9.82469718789294e-06 4.18841631618861e-05 -8.82447749686672e-07 2.39722130476507e-05 1.03607717185189e-05 4.64474438369286e-05 888 904 0 92 0 887 904 0 100 0 0 0 0 0 0 0 0 0 2833 0 0 0 0 0 1360 +860 922 0.998754565944336 0.0482080096219955 0.0128570919583887 0.0366763944846785 -0.0493078011788297 0.99305791184301 0.106792904581296 -0.0154779014415708 -0.00761956352095509 -0.107293855995049 0.994198154654023 0.0946088050958107 3.20602859121113e-05 -3.59979997838063e-05 -1.73633301915907e-06 -3.88653845494926e-06 -3.89840887847189e-06 1.2382078673589e-06 -3.59979997838063e-05 7.8071974826793e-05 4.71502469390746e-06 1.65307105344049e-05 5.90967112625231e-06 1.55948805570367e-05 -1.73633301915907e-06 4.71502469390746e-06 1.06019467697943e-05 -2.0485942615803e-06 4.5632458551329e-06 -1.4295263282952e-06 -3.88653845494926e-06 1.65307105344049e-05 -2.0485942615803e-06 4.26919032451397e-05 7.75620048900328e-07 9.87139671213989e-06 -3.89840887847189e-06 5.90967112625231e-06 4.5632458551329e-06 7.75620048900328e-07 2.21140790914737e-05 4.3514351364786e-06 1.2382078673589e-06 1.55948805570367e-05 -1.4295263282952e-06 9.87139671213989e-06 4.3514351364786e-06 3.21390092903895e-05 950 965 0 100 0 949 964 0 105 0 0 0 0 0 0 0 0 0 2839 0 0 0 0 0 1597 +860 902 0.998803147171229 0.0477789203677326 0.0104617383518142 0.029464245968621 -0.0486253445557744 0.993070008881238 0.106993146170447 -0.0170862604727387 -0.00527722158717837 -0.107373796752804 0.994204716697325 0.0958272206823157 3.98026571165572e-05 -5.43460726685148e-05 -1.07832309355084e-06 -8.45798913847456e-06 -5.75392253730365e-06 3.65943249614264e-07 -5.43460726685148e-05 0.000162520434703529 4.92503679997072e-06 5.33521406836242e-05 2.2659383430422e-05 3.1384897838205e-05 -1.07832309355084e-06 4.92503679997072e-06 9.62735811949112e-06 -1.04744341552644e-06 3.57603447472886e-06 -5.76826464414572e-07 -8.45798913847456e-06 5.33521406836242e-05 -1.04744341552644e-06 5.78218216029999e-05 7.43232936301928e-06 2.28866056589315e-05 -5.75392253730365e-06 2.2659383430422e-05 3.57603447472886e-06 7.43232936301928e-06 2.56801074116614e-05 1.09500416152804e-05 3.65943249614264e-07 3.1384897838205e-05 -5.76826464414572e-07 2.28866056589315e-05 1.09500416152804e-05 4.22515353820951e-05 900 914 0 83 0 899 914 0 92 0 0 0 0 0 0 0 0 0 2873 0 0 0 0 0 1639 +860 923 0.99874546559127 0.0476643637142614 0.0153493775962627 0.0352538454267008 -0.0490433855368277 0.992980463381919 0.107631527337096 -0.016635899036991 -0.0101114438120442 -0.108249285325791 0.994072356989415 0.0951504379667522 2.05428955789302e-05 -1.95549060644106e-05 4.19007207444484e-08 -8.2625716558322e-07 3.44380627229153e-07 4.6056389619012e-06 -1.95549060644106e-05 4.9733568070777e-05 1.62827182215174e-06 1.29276803287774e-05 3.53856598149264e-06 6.65421921986173e-06 4.19007207444484e-08 1.62827182215174e-06 9.76948352936215e-06 -2.54209250751929e-06 3.47613760864919e-06 -1.93307768475786e-06 -8.2625716558322e-07 1.29276803287774e-05 -2.54209250751929e-06 4.83111315669026e-05 3.39795024778777e-06 7.64952847794707e-06 3.44380627229153e-07 3.53856598149264e-06 3.47613760864919e-06 3.39795024778777e-06 2.30956466254217e-05 6.64748075944017e-06 4.6056389619012e-06 6.65421921986173e-06 -1.93307768475786e-06 7.64952847794707e-06 6.64748075944017e-06 2.5365833215703e-05 926 946 0 94 0 925 946 0 101 0 0 0 0 0 0 0 0 0 2725 0 0 0 0 0 1713 +860 921 0.99877950994239 0.0479899098979737 0.011681569553106 0.0346966297431003 -0.0489613862313889 0.99313188276466 0.106263098461426 -0.017776544933775 -0.00650178264327919 -0.106705351244942 0.994269427689574 0.0937408279943591 3.60353152054487e-05 -3.98472866691546e-05 1.49776524163515e-06 -1.01635676365847e-05 -5.97829440207602e-06 4.09948030639389e-08 -3.98472866691546e-05 7.02154323642636e-05 1.23758275279828e-06 2.8154463692239e-05 1.33871184640537e-05 1.36260593107249e-05 1.49776524163515e-06 1.23758275279828e-06 1.03552674346751e-05 -2.68439365898683e-06 4.37421826753859e-06 1.81257650251078e-07 -1.01635676365847e-05 2.8154463692239e-05 -2.68439365898683e-06 6.34477802148689e-05 1.60119408417321e-05 1.7469467648669e-05 -5.97829440207602e-06 1.33871184640537e-05 4.37421826753859e-06 1.60119408417321e-05 3.26444659129433e-05 1.27729056513372e-05 4.09948030639389e-08 1.36260593107249e-05 1.81257650251078e-07 1.7469467648669e-05 1.27729056513372e-05 3.5549767464424e-05 950 964 0 99 0 950 964 0 107 0 0 0 0 0 0 0 0 0 2736 0 0 0 0 0 1648 +860 926 0.998737911874331 0.0479404673487527 0.0149764807375912 0.0356622891888492 -0.0492743190849522 0.993004527345175 0.107303542116279 -0.017503446410305 -0.0097275312188949 -0.107906071480566 0.994113502007702 0.0939097611283403 3.63062432089929e-05 -4.0962729189903e-05 -2.04074344012265e-06 -7.39133664735946e-06 -1.03763538689661e-06 5.23246252013102e-06 -4.0962729189903e-05 9.72668337286444e-05 7.46097694580375e-06 2.9833968994036e-05 4.67502001511847e-06 1.79346269384441e-05 -2.04074344012265e-06 7.46097694580375e-06 1.10433531324896e-05 -2.79189031365408e-06 5.05036808581439e-06 -2.37261810531969e-08 -7.39133664735946e-06 2.9833968994036e-05 -2.79189031365408e-06 5.27728520296309e-05 2.71080156955211e-06 1.67313963049757e-05 -1.03763538689661e-06 4.67502001511847e-06 5.05036808581439e-06 2.71080156955211e-06 2.2935343565032e-05 6.83866873708608e-06 5.23246252013102e-06 1.79346269384441e-05 -2.37261810531969e-08 1.67313963049757e-05 6.83866873708608e-06 3.90440954906619e-05 889 903 0 91 0 886 902 0 103 0 0 0 0 0 0 0 0 0 2803 0 0 0 0 0 1337 +860 889 0.9987812667281 0.0474567004109936 -0.013558864964034 0.0419116564527212 -0.0465284835127956 0.996985456655342 0.0620894470883668 -0.00455287206539059 0.0164645514670524 -0.061382903188435 0.99797848561036 0.0924096258085813 3.10943537473497e-05 -3.20999304234726e-05 4.01360742872626e-06 -1.10858445792568e-05 -1.01220266656876e-05 2.62496231136855e-06 -3.20999304234726e-05 5.68227467215928e-05 -1.07094582620251e-06 2.18884601475299e-05 1.63260137752373e-05 9.13815547657149e-06 4.01360742872626e-06 -1.07094582620251e-06 1.08566476923659e-05 -1.17617400336768e-06 2.30878454892143e-06 -1.23253330225081e-06 -1.10858445792568e-05 2.18884601475299e-05 -1.17617400336768e-06 6.32908892972968e-05 1.50243384536286e-05 1.09364525331141e-05 -1.01220266656876e-05 1.63260137752373e-05 2.30878454892143e-06 1.50243384536286e-05 3.13873105127072e-05 7.14838188826727e-06 2.62496231136855e-06 9.13815547657149e-06 -1.23253330225081e-06 1.09364525331141e-05 7.14838188826727e-06 3.36285657406206e-05 889 906 0 80 0 889 906 0 94 0 0 0 0 0 0 0 0 0 2544 0 0 0 0 0 2052 +860 903 0.998735317845663 0.0480625299662674 0.0147566290515041 0.0350535536916963 -0.0493646658422679 0.993082044708911 0.106541927160392 -0.0171712389106483 -0.00953386878466836 -0.107135641548509 0.994198702300494 0.0956090250612174 3.45101120572501e-05 -3.9155712586843e-05 -2.99470425600656e-06 -7.88379185819811e-06 -3.49718693711882e-06 -3.64737588257458e-06 -3.9155712586843e-05 7.6116949600839e-05 6.09379230914564e-06 2.4610912235295e-05 8.24617476960191e-06 1.90326998261649e-05 -2.99470425600656e-06 6.09379230914564e-06 1.0415417707434e-05 -1.53620106585547e-06 4.12147284226716e-06 -5.40652466490339e-07 -7.88379185819811e-06 2.4610912235295e-05 -1.53620106585547e-06 4.83421393351753e-05 1.36492647023094e-06 1.0387162222939e-05 -3.49718693711882e-06 8.24617476960191e-06 4.12147284226716e-06 1.36492647023094e-06 2.36217937568625e-05 5.9665128760619e-06 -3.64737588257458e-06 1.90326998261649e-05 -5.40652466490339e-07 1.0387162222939e-05 5.9665128760619e-06 3.1950431520518e-05 913 931 0 94 0 911 931 0 105 0 0 0 0 0 0 0 0 0 2795 0 0 0 0 0 1313 +860 928 0.998771026485044 0.0480825327878599 0.0120210937404584 0.0334168959029738 -0.0491025125655778 0.992922503532242 0.108138084128638 -0.0169091911254473 -0.00673646151624014 -0.108595451193729 0.994063201243397 0.0948308180382354 3.15084999335296e-05 -3.5059634671606e-05 -4.93253455860533e-06 2.90571858297492e-06 -1.94777388208612e-06 7.89680855122514e-06 -3.5059634671606e-05 7.41140725889901e-05 6.74646243040512e-06 1.20314567080639e-05 8.01313043217613e-06 8.61822142762957e-06 -4.93253455860533e-06 6.74646243040512e-06 1.14400136062738e-05 -5.7107117834196e-06 2.99641866710438e-06 -2.77814298640611e-06 2.90571858297492e-06 1.20314567080639e-05 -5.7107117834196e-06 4.5977486932412e-05 3.34265100884766e-06 1.55324844145413e-05 -1.94777388208612e-06 8.01313043217613e-06 2.99641866710438e-06 3.34265100884766e-06 2.44803367355116e-05 4.49941760270406e-06 7.89680855122514e-06 8.61822142762957e-06 -2.77814298640611e-06 1.55324844145413e-05 4.49941760270406e-06 3.6951839108686e-05 918 935 0 90 0 915 934 0 96 0 0 0 0 0 0 0 0 0 2739 0 0 0 0 0 1746 +860 917 0.998696774131261 0.0489771230080574 0.0143525176072752 0.0447835237872504 -0.0502559222810771 0.992734261202995 0.109329908576852 -0.00972260355874821 -0.00889357158243316 -0.109908726021177 0.993901894720455 0.0937354373012436 4.8708133969273e-05 -5.06964739592854e-05 -3.45001324845015e-06 -8.6124017435639e-06 -5.96879549162033e-06 5.88956327122689e-06 -5.06964739592854e-05 7.90758251969518e-05 7.4241646343569e-06 9.12652427753434e-06 -4.24340335207562e-07 9.11361950647217e-06 -3.45001324845015e-06 7.4241646343569e-06 1.26810702736252e-05 -9.30367575435562e-06 -1.77139439210615e-06 7.76433084818486e-08 -8.6124017435639e-06 9.12652427753434e-06 -9.30367575435562e-06 8.56100469459957e-05 3.30523554632467e-05 5.76539513108969e-07 -5.96879549162033e-06 -4.24340335207562e-07 -1.77139439210615e-06 3.30523554632467e-05 4.87778108886707e-05 -1.83654458255567e-06 5.88956327122689e-06 9.11361950647217e-06 7.76433084818486e-08 5.76539513108969e-07 -1.83654458255567e-06 4.16134119027456e-05 923 938 0 93 0 922 938 0 100 0 0 0 0 0 0 0 0 0 2445 0 0 0 0 0 1374 +860 920 0.998733312015313 0.0471272147318248 0.0176294385204001 0.0334755158964168 -0.048748218185733 0.993064837466933 0.10698523174013 -0.0194366944645083 -0.0124652595095433 -0.10770911854803 0.994104301915531 0.0976458889953691 3.16242891838628e-05 -3.35322913493428e-05 -6.16420885683036e-06 1.64384181387729e-06 -2.06425866886577e-06 2.05064944016269e-06 -3.35322913493428e-05 6.03749529597185e-05 8.59476653177374e-06 7.74999058889941e-06 3.68906250433506e-06 1.12285682448987e-05 -6.16420885683036e-06 8.59476653177374e-06 1.20574009772062e-05 -4.73312737677767e-06 3.72095695655318e-06 -4.56321601909955e-06 1.64384181387729e-06 7.74999058889941e-06 -4.73312737677767e-06 4.61344537965414e-05 3.39100087972646e-06 1.07947814173519e-05 -2.06425866886577e-06 3.68906250433506e-06 3.72095695655318e-06 3.39100087972646e-06 2.4847707688639e-05 2.20567044926053e-06 2.05064944016269e-06 1.12285682448987e-05 -4.56321601909955e-06 1.07947814173519e-05 2.20567044926053e-06 3.62385510229577e-05 945 959 0 94 0 944 959 0 96 0 0 0 0 0 0 0 0 0 2603 0 0 0 0 0 1740 +860 919 0.998711085076887 0.0478536396882049 0.016917379026844 0.0362659031134613 -0.0494158797515872 0.992826898444538 0.108870659745295 -0.0149439501313131 -0.0115861716249637 -0.109566321894963 0.993911958743573 0.0981665822768999 3.46044674955703e-05 -4.98900567546837e-05 -2.84370405268022e-06 -1.09768880685078e-05 -2.18150151274681e-06 -5.7425893524059e-06 -4.98900567546837e-05 0.000147583820799889 6.69706192744447e-06 6.37039703275467e-05 1.76762107060539e-05 4.79015755791981e-05 -2.84370405268022e-06 6.69706192744447e-06 9.91765586867067e-06 -9.95731449982127e-07 3.70395179794391e-06 6.4579752144738e-07 -1.09768880685078e-05 6.37039703275467e-05 -9.95731449982127e-07 7.38715288015848e-05 1.26575844820805e-05 3.32577304396913e-05 -2.18150151274681e-06 1.76762107060539e-05 3.70395179794391e-06 1.26575844820805e-05 2.70499105374321e-05 1.26481603600678e-05 -5.7425893524059e-06 4.79015755791981e-05 6.4579752144738e-07 3.32577304396913e-05 1.26481603600678e-05 4.84634363849803e-05 939 957 0 93 0 939 957 0 100 0 0 0 0 0 0 0 0 0 2621 0 0 0 0 0 1812 +861 865 0.998245082708448 0.0100520387743497 -0.0583584729485082 0.0277269374142758 -0.00974376355528385 0.999937045135718 0.00556460573880238 0.00032547980173499 0.0584107346314144 -0.00498620915411299 0.998280183013812 0.036332878298621 4.07246047312388e-05 -4.306488033585e-05 6.85252036762308e-07 -8.96980999242756e-06 -6.9275455618218e-06 8.48302276565634e-06 -4.306488033585e-05 6.0321217904698e-05 -1.28769800044852e-06 3.13329314396851e-05 1.8943789907495e-05 1.42497428299921e-06 6.85252036762308e-07 -1.28769800044852e-06 1.05243336571419e-05 -5.13095480163919e-06 2.50432197973006e-06 -9.15662823949595e-07 -8.96980999242756e-06 3.13329314396851e-05 -5.13095480163919e-06 8.76401987226354e-05 2.59614766976501e-05 1.85342855891581e-05 -6.9275455618218e-06 1.8943789907495e-05 2.50432197973006e-06 2.59614766976501e-05 3.49337234724007e-05 1.27109826457007e-05 8.48302276565634e-06 1.42497428299921e-06 -9.15662823949595e-07 1.85342855891581e-05 1.27109826457007e-05 3.82093954906252e-05 912 916 0 22 0 891 902 0 27 0 0 0 0 0 0 0 2 0 2423 0 0 0 0 0 2033 +860 916 0.998665153293455 0.0484645973154788 0.0178632137200578 0.0424075264641999 -0.0501168509563845 0.992879384225025 0.108068633891387 -0.0129847113705307 -0.012498513814671 -0.108819626850966 0.993982935449317 0.0979383439235206 3.77122441112173e-05 -4.64776792321337e-05 -1.84001116068729e-06 -1.15274150852213e-05 -8.93182621913362e-06 4.47185686778242e-07 -4.64776792321337e-05 0.000105919247524847 4.63842074290285e-06 3.92649508652161e-05 1.80634125294106e-05 2.18488196203232e-05 -1.84001116068729e-06 4.63842074290285e-06 1.04722943722823e-05 -2.97570757716097e-06 2.81320145994313e-06 -1.24824060972757e-07 -1.15274150852213e-05 3.92649508652161e-05 -2.97570757716097e-06 6.92746120733128e-05 1.60948456417108e-05 2.17992833893769e-05 -8.93182621913362e-06 1.80634125294106e-05 2.81320145994313e-06 1.60948456417108e-05 3.29591516167748e-05 8.85130067954183e-06 4.47185686778242e-07 2.18488196203232e-05 -1.24824060972757e-07 2.17992833893769e-05 8.85130067954183e-06 3.81570834760467e-05 924 937 0 91 0 923 937 0 98 0 0 0 0 0 0 0 0 0 2680 0 0 0 0 0 1780 +860 915 0.998729977528606 0.0474914498948579 0.0168224306386936 0.0329650620117712 -0.049031519872712 0.992976265688956 0.107675651088761 -0.0189330971468169 -0.0115906015668434 -0.108363729934425 0.994043741487274 0.0949046938476155 4.35304031492187e-05 -6.16227293333229e-05 -3.81263534169166e-06 -2.41572400792247e-05 -1.43213304150755e-05 -5.52000054498454e-06 -6.16227293333229e-05 0.000141752274943852 8.17865658683582e-06 7.10811809033379e-05 3.4645338337958e-05 4.56779392299251e-05 -3.81263534169166e-06 8.17865658683582e-06 1.12881041779929e-05 -2.77998061374894e-06 3.91822945733503e-06 -3.84958963282315e-08 -2.41572400792247e-05 7.10811809033379e-05 -2.77998061374894e-06 0.000104446447704567 3.30018640774578e-05 4.2507603699777e-05 -1.43213304150755e-05 3.4645338337958e-05 3.91822945733503e-06 3.30018640774578e-05 3.8079746972105e-05 2.00693307881557e-05 -5.52000054498454e-06 4.56779392299251e-05 -3.84958963282315e-08 4.2507603699777e-05 2.00693307881557e-05 5.41963214967606e-05 918 928 0 84 0 918 928 0 90 0 0 0 0 0 0 0 0 0 2831 0 0 0 0 0 1378 +861 930 0.993514020980314 -0.0371774997940941 0.107460335122257 0.0151609864037854 0.0220878153939927 0.990138144678456 0.138342267090812 -0.0179649128756637 -0.11154379645076 -0.135071418004568 0.984537299197743 0.0197439862006967 2.54575726964287e-05 -2.60478971230931e-05 1.37630791311016e-07 2.89930739061299e-07 -2.99930722779002e-06 -4.10261127315826e-07 -2.60478971230931e-05 8.14034952085372e-05 5.01936791724212e-06 2.0430587717903e-05 4.73948145547589e-06 1.95861090502881e-05 1.37630791311016e-07 5.01936791724212e-06 1.10788206356742e-05 -3.5200055142681e-06 2.43020677032135e-06 4.38242202689063e-07 2.89930739061299e-07 2.0430587717903e-05 -3.5200055142681e-06 5.42980546044984e-05 2.3942701505355e-06 1.13374880801747e-05 -2.99930722779002e-06 4.73948145547589e-06 2.43020677032135e-06 2.3942701505355e-06 2.71095261633888e-05 2.42140368074064e-06 -4.10261127315826e-07 1.95861090502881e-05 4.38242202689063e-07 1.13374880801747e-05 2.42140368074064e-06 3.24499728442074e-05 1114 1113 0 0 0 1120 1120 0 2 0 0 0 0 0 0 43 56 0 2876 0 0 0 0 0 1421 +860 914 0.998717130638917 0.0478950140440818 0.016436562842795 0.0342831655668245 -0.0494101676096542 0.99276962656903 0.109394258984535 -0.0142711492820239 -0.0110782807851138 -0.110066053766394 0.993862533504075 0.0981628007995906 2.75912665842109e-05 -3.23726309490341e-05 -1.2031459865825e-06 -6.40004943912711e-06 -2.43203529758371e-06 8.93453554252876e-07 -3.23726309490341e-05 7.32871262705662e-05 3.32794417788732e-06 2.45602165057294e-05 1.04168386668677e-05 1.53913724886883e-05 -1.2031459865825e-06 3.32794417788732e-06 9.76373323893374e-06 -2.62363434220405e-06 4.77529112103298e-06 -1.75871663958441e-06 -6.40004943912711e-06 2.45602165057294e-05 -2.62363434220405e-06 5.09869936073097e-05 5.0685289324154e-06 1.51243087976368e-05 -2.43203529758371e-06 1.04168386668677e-05 4.77529112103298e-06 5.0685289324154e-06 2.29589254514706e-05 7.71449162945803e-06 8.93453554252876e-07 1.53913724886883e-05 -1.75871663958441e-06 1.51243087976368e-05 7.71449162945803e-06 3.19193613066941e-05 977 996 0 96 0 976 996 0 103 0 0 0 0 0 0 0 0 0 2894 0 0 0 0 0 1769 +861 863 0.998494672921624 -0.000332074489653724 -0.0548477699972674 -0.0010771381815288 0.00145634756094688 0.999789624549191 0.0204593669396313 -0.00584115336613726 0.0548294373390932 -0.0205084463166295 0.99828509777055 0.0244988534344538 2.11884732142014e-05 -1.7939134006266e-05 2.62855929253504e-07 2.73367819285421e-06 -6.41795983041413e-07 8.99986914083667e-06 -1.7939134006266e-05 2.48085934021847e-05 3.44152457717353e-07 1.01003754554274e-07 1.98275997748005e-06 -3.23151840463233e-06 2.62855929253504e-07 3.44152457717353e-07 9.02781649431942e-06 2.21111190792532e-06 1.57876821312028e-06 -1.34420023575874e-06 2.73367819285421e-06 1.01003754554274e-07 2.21111190792532e-06 3.09474389759189e-05 3.51284899661145e-06 8.79132120711909e-06 -6.41795983041413e-07 1.98275997748005e-06 1.57876821312028e-06 3.51284899661145e-06 2.49928417199371e-05 9.45692244797056e-06 8.99986914083667e-06 -3.23151840463233e-06 -1.34420023575874e-06 8.79132120711909e-06 9.45692244797056e-06 3.49391946986145e-05 1129 1115 0 7 0 1094 1095 0 17 0 0 0 0 0 0 3 9 0 2650 0 0 0 0 0 2292 +861 900 0.997611925333938 0.0466721220202519 0.0509132542432715 0.0236939969610318 -0.0524770260962655 0.991460559022184 0.119382250085643 -0.0220643480209761 -0.0449066605706232 -0.121768932530206 0.991542091344008 0.0689291201316612 3.91153502463332e-05 -4.80862507010461e-05 1.3267787780299e-06 -2.1786082298239e-05 -7.32128900778573e-06 -4.21618995106698e-06 -4.80862507010461e-05 8.82032536771106e-05 4.67897082590708e-07 4.90358517398392e-05 1.83506466667207e-05 2.5095752916431e-05 1.3267787780299e-06 4.67897082590708e-07 1.15343843445469e-05 -3.39018014576307e-06 4.80803757741034e-06 1.06568459521706e-06 -2.1786082298239e-05 4.90358517398392e-05 -3.39018014576307e-06 7.00936984089046e-05 1.40312876613364e-05 2.80300986124413e-05 -7.32128900778573e-06 1.83506466667207e-05 4.80803757741034e-06 1.40312876613364e-05 2.70724063967845e-05 1.44584651242689e-05 -4.21618995106698e-06 2.5095752916431e-05 1.06568459521706e-06 2.80300986124413e-05 1.44584651242689e-05 4.85556847606643e-05 910 920 0 76 0 910 920 0 85 0 0 0 0 0 0 0 0 0 2647 0 0 0 0 0 1701 +861 931 0.992097976747319 -0.106637659626254 0.0661060820447796 0.0088412610817398 0.0985371399960019 0.988396363102561 0.115598708673749 -0.0103001175324228 -0.0776661868208054 -0.108171340728795 0.991093802053898 -0.042457996471407 4.06367689883088e-05 -5.05603831235887e-05 -4.86579697465455e-06 -9.22755459902781e-06 -3.29562195850671e-06 2.15476568192776e-06 -5.05603831235887e-05 9.97367562304246e-05 8.16535708361499e-06 3.18014493584631e-05 3.52295926214637e-06 6.5144570943688e-06 -4.86579697465455e-06 8.16535708361499e-06 1.07942638101828e-05 -2.7493538931485e-06 4.97458642069115e-06 -3.02505650217926e-06 -9.22755459902781e-06 3.18014493584631e-05 -2.7493538931485e-06 6.63283860704211e-05 -3.23105499081547e-07 9.4418615814362e-06 -3.29562195850671e-06 3.52295926214637e-06 4.97458642069115e-06 -3.23105499081547e-07 2.1934681421178e-05 2.71913685712262e-06 2.15476568192776e-06 6.5144570943688e-06 -3.02505650217926e-06 9.4418615814362e-06 2.71913685712262e-06 3.95600659008801e-05 1252 1252 0 0 0 1178 1178 0 0 0 0 0 0 0 0 162 168 0 2868 0 0 0 0 0 1116 +861 864 0.998693705899293 -0.00969177063780512 -0.050169227411236 0.0170007494012579 0.0106708968336337 0.999757070198775 0.0192855528395773 0.00232728688060852 0.0499701286560489 -0.0197957108856025 0.998554513320445 0.0362449248311979 2.14208779706915e-05 -2.08168285666111e-05 2.49235527023387e-06 -2.83893168610462e-06 -1.75434371737413e-06 7.03290847077934e-06 -2.08168285666111e-05 3.52169109082473e-05 -1.69236011070459e-06 9.41019192335835e-06 5.41491225968259e-06 -2.33335803889983e-07 2.49235527023387e-06 -1.69236011070459e-06 8.78321741598928e-06 -1.93471413313474e-06 1.55157169222716e-06 7.21154218701065e-07 -2.83893168610462e-06 9.41019192335835e-06 -1.93471413313474e-06 6.71359314963842e-05 1.99030928585804e-05 1.23476915565006e-05 -1.75434371737413e-06 5.41491225968259e-06 1.55157169222716e-06 1.99030928585804e-05 3.36087348393773e-05 9.00158599948367e-06 7.03290847077934e-06 -2.33335803889983e-07 7.21154218701065e-07 1.23476915565006e-05 9.00158599948367e-06 3.02177137392804e-05 928 924 0 5 0 911 918 0 15 0 0 0 0 0 0 7 17 0 2543 0 0 0 0 0 2176 +861 898 0.997648679196961 0.0471750164142663 0.0497154978137812 0.0248294362003474 -0.0528471224567644 0.991395774544268 0.119756418883541 -0.0210113654593222 -0.0436382234354027 -0.122102154125487 0.991557748904882 0.0670677233849455 2.35640638249019e-05 -2.36106042382525e-05 -2.71000426559366e-07 -2.52227052922439e-06 -9.70994220514591e-08 6.09836439592859e-06 -2.36106042382525e-05 5.23806634979163e-05 4.94878840409857e-06 1.46426067059287e-05 4.13987331856462e-06 3.29191625354386e-06 -2.71000426559366e-07 4.94878840409857e-06 1.16475059364607e-05 -4.88789509752048e-06 4.56200774872071e-06 -1.04976552967878e-08 -2.52227052922439e-06 1.46426067059287e-05 -4.88789509752048e-06 5.06749292911865e-05 3.10245784120447e-06 2.52564997145147e-06 -9.70994220514591e-08 4.13987331856462e-06 4.56200774872071e-06 3.10245784120447e-06 2.43823420658448e-05 1.62714206167169e-06 6.09836439592859e-06 3.29191625354386e-06 -1.04976552967878e-08 2.52564997145147e-06 1.62714206167169e-06 2.69987516570418e-05 870 881 0 76 0 869 881 0 87 0 0 0 0 0 0 0 0 0 2731 0 0 0 0 0 1050 +861 897 0.997453000193474 0.0469185525223443 0.0537230102865133 0.0270111169402876 -0.0531410362998719 0.991233704940783 0.120961863619674 -0.0194234543980505 -0.0475767029754321 -0.123508670216211 0.991202333388804 0.0689983537302629 4.47980063434271e-05 -5.19676274692368e-05 -2.27652697114777e-06 -1.22574401396423e-05 -7.48077961552561e-06 -6.85562437322317e-06 -5.19676274692368e-05 7.99096468258032e-05 4.96568502620796e-06 2.59019621387253e-05 1.40480646407961e-05 2.23097929258053e-05 -2.27652697114777e-06 4.96568502620796e-06 1.00033272268398e-05 -1.75001015053285e-06 3.8765890851544e-06 8.59814770308258e-07 -1.22574401396423e-05 2.59019621387253e-05 -1.75001015053285e-06 5.23877971805374e-05 1.3422036855035e-05 2.41947512459001e-05 -7.48077961552561e-06 1.40480646407961e-05 3.8765890851544e-06 1.3422036855035e-05 2.39706626233427e-05 1.24201825946144e-05 -6.85562437322317e-06 2.23097929258053e-05 8.59814770308258e-07 2.41947512459001e-05 1.24201825946144e-05 4.48446553909526e-05 904 914 0 78 0 902 913 0 86 0 0 0 0 0 0 0 0 0 2650 0 0 0 0 0 1672 +861 929 0.998210752564672 0.0248511816285567 0.0543848530009515 0.0201206210395267 -0.0321807391720575 0.989860943870965 0.138346347350493 -0.0210187805964507 -0.050395371718151 -0.139848956272643 0.988889567109918 0.0597779637204299 2.73200851170485e-05 -2.85492258257462e-05 -3.34905235281965e-06 5.64248994594066e-07 -3.60186136751205e-06 1.49878777454664e-06 -2.85492258257462e-05 6.94265294907979e-05 8.01108129934604e-06 1.96753016440801e-05 9.00675581692717e-06 1.77367222274032e-05 -3.34905235281965e-06 8.01108129934604e-06 1.06027571990647e-05 -2.5398638514656e-06 5.45880834544416e-06 -1.36267156608344e-06 5.64248994594066e-07 1.96753016440801e-05 -2.5398638514656e-06 5.4500163488808e-05 5.82657706236328e-06 1.72139598097006e-05 -3.60186136751205e-06 9.00675581692717e-06 5.45880834544416e-06 5.82657706236328e-06 2.08748621969801e-05 3.2390359303944e-06 1.49878777454664e-06 1.77367222274032e-05 -1.36267156608344e-06 1.72139598097006e-05 3.2390359303944e-06 3.30861593931109e-05 937 951 0 57 0 934 950 0 66 0 0 0 0 0 0 0 0 0 2771 0 0 0 0 0 1408 +861 899 0.99738718632578 0.047412312854115 0.054505716608138 0.0309921638476713 -0.0537320593530936 0.991193367331708 0.121031294941865 -0.0185714088040583 -0.0482873311627258 -0.123643767119304 0.991151124956093 0.0685187262396404 4.46252587918832e-05 -6.76071845494035e-05 -3.68703564218346e-06 -2.25378737159757e-05 -1.27929917475794e-05 -9.22490179507035e-06 -6.76071845494035e-05 0.000163425804215349 1.05365787105523e-05 6.85038686456498e-05 3.51844492108869e-05 4.39237132108887e-05 -3.68703564218346e-06 1.05365787105523e-05 9.56683405531772e-06 1.68468649301971e-07 6.46443086251416e-06 1.60275417805206e-06 -2.25378737159757e-05 6.85038686456498e-05 1.68468649301971e-07 8.04515305925753e-05 2.07621138169225e-05 3.05177121965193e-05 -1.27929917475794e-05 3.51844492108869e-05 6.46443086251416e-06 2.07621138169225e-05 2.91888980001465e-05 1.76189762316077e-05 -9.22490179507035e-06 4.39237132108887e-05 1.60275417805206e-06 3.05177121965193e-05 1.76189762316077e-05 5.24185536186998e-05 910 926 0 79 0 908 925 0 86 0 0 0 0 0 0 0 0 0 2732 0 0 0 0 0 1758 +861 892 0.997808349819951 0.0469059159211871 0.0466726052538421 0.0235431457440526 -0.0520817879310228 0.991801741197739 0.116691017319417 -0.0224863729088428 -0.0408164721098529 -0.118866064159318 0.992071002698788 0.0646057686465336 3.45191590652606e-05 -3.56636750136652e-05 -5.56607514322712e-07 -4.67690316336122e-06 -5.53987478354009e-06 2.26646591801795e-06 -3.56636750136652e-05 5.04296318968614e-05 1.3934396706759e-06 1.63896581506598e-05 8.94898864076284e-06 7.90493412146512e-06 -5.56607514322712e-07 1.3934396706759e-06 9.45050210572288e-06 -2.83688204064757e-06 3.74194793927032e-06 -3.52947908992806e-07 -4.67690316336122e-06 1.63896581506598e-05 -2.83688204064757e-06 6.07697174075001e-05 1.09125477279644e-05 1.57098921232089e-05 -5.53987478354009e-06 8.94898864076284e-06 3.74194793927032e-06 1.09125477279644e-05 2.45461060461134e-05 7.16022603584703e-06 2.26646591801795e-06 7.90493412146512e-06 -3.52947908992806e-07 1.57098921232089e-05 7.16022603584703e-06 4.75436965341946e-05 885 890 0 65 0 884 889 0 78 0 0 0 0 0 0 0 0 0 2769 0 0 0 0 0 1782 +861 895 0.997510547873747 0.0463155322834563 0.0531749786075878 0.02512461226726 -0.0524515816420912 0.991327704525541 0.120491550838074 -0.0246434800007332 -0.0471331991685303 -0.122980704622397 0.991289164586559 0.0664351149009934 2.04193387544116e-05 -1.5410716983666e-05 4.41416766081969e-06 -9.29914767184135e-07 -9.74475148519472e-09 7.61906216553767e-06 -1.5410716983666e-05 4.90375490687886e-05 -3.38233846334419e-07 1.51036065474871e-05 4.40152664160252e-06 3.35161900404077e-06 4.41416766081969e-06 -3.38233846334419e-07 1.0319606058532e-05 -2.18566028005164e-06 2.90329407848396e-06 8.44732452537886e-07 -9.29914767184135e-07 1.51036065474871e-05 -2.18566028005164e-06 5.84468032383726e-05 5.08054389890138e-06 -8.37178503282654e-07 -9.74475148519472e-09 4.40152664160252e-06 2.90329407848396e-06 5.08054389890138e-06 2.52834323549968e-05 4.54214446597382e-06 7.61906216553767e-06 3.35161900404077e-06 8.44732452537886e-07 -8.37178503282654e-07 4.54214446597382e-06 2.5542466919693e-05 886 902 0 77 0 885 901 0 87 0 0 0 0 0 0 0 0 0 2693 0 0 0 0 0 1058 +861 890 0.997980782344902 0.0478942865022541 0.0417192448481283 0.0365972522859297 -0.0516890254684479 0.994113895742799 0.0952145311241852 -0.0133848121070234 -0.036913448990581 -0.0971786993713967 0.994582172408144 0.0721495902055426 3.56390075843228e-05 -3.70801501867903e-05 4.22229968510139e-06 -1.00841561832063e-05 -5.94713926362832e-06 7.35743689798053e-06 -3.70801501867903e-05 5.86235134809981e-05 -8.17091407592983e-07 2.57324121898086e-05 1.38433658797022e-05 -6.34252274227763e-07 4.22229968510139e-06 -8.17091407592983e-07 1.14026225184837e-05 -1.69112556868251e-06 4.94322981800218e-06 2.60177885471056e-06 -1.00841561832063e-05 2.57324121898086e-05 -1.69112556868251e-06 6.55894479395698e-05 1.32352903491935e-05 1.03799909116816e-05 -5.94713926362832e-06 1.38433658797022e-05 4.94322981800218e-06 1.32352903491935e-05 2.69668664499351e-05 6.54241012681993e-06 7.35743689798053e-06 -6.34252274227763e-07 2.60177885471056e-06 1.03799909116816e-05 6.54241012681993e-06 2.76691216365037e-05 854 866 0 74 0 853 865 0 85 0 0 0 0 0 0 0 0 0 2589 0 0 0 0 0 1362 +861 901 0.997891666431938 0.0476564444030686 0.044057750425403 0.0216332668190408 -0.0525979597911876 0.991522547931539 0.118812842610361 -0.0208864399706989 -0.0380220553296962 -0.120879693291334 0.991938719406748 0.0686825004207415 4.06197721097952e-05 -4.30037083288878e-05 1.75671249511065e-07 -1.19287352853192e-05 -7.25767303881494e-06 -4.90355138266893e-06 -4.30037083288878e-05 6.78914837662186e-05 2.24912087401581e-06 2.69536026920157e-05 1.47557226952862e-05 2.12118221731243e-05 1.75671249511065e-07 2.24912087401581e-06 9.26980042570996e-06 -9.67119893171984e-07 3.92638200546628e-06 4.97582314447405e-07 -1.19287352853192e-05 2.69536026920157e-05 -9.67119893171984e-07 5.69648309601179e-05 1.64853700126389e-05 2.22354628335248e-05 -7.25767303881494e-06 1.47557226952862e-05 3.92638200546628e-06 1.64853700126389e-05 2.67156953803485e-05 1.21325480426207e-05 -4.90355138266893e-06 2.12118221731243e-05 4.97582314447405e-07 2.22354628335248e-05 1.21325480426207e-05 4.45239331267693e-05 885 891 0 75 0 885 891 0 84 0 0 0 0 0 0 0 0 0 2671 0 0 0 0 0 1774 +861 894 0.997581821543763 0.0469010381897473 0.0512913437350901 0.0253328803568264 -0.0527950622160423 0.991326050267113 0.12035507246232 -0.0214518809348376 -0.0452016673479146 -0.122771962102632 0.991404990198475 0.0677084791631065 3.797315375101e-05 -5.14636121427049e-05 1.85440530737339e-06 -2.10868354560353e-05 -1.25524686531752e-05 -9.84765570607532e-06 -5.14636121427049e-05 0.000107287004310956 2.27536044969566e-06 5.08682880782416e-05 2.5734141357682e-05 3.6145322044349e-05 1.85440530737339e-06 2.27536044969566e-06 9.91865871784844e-06 -1.18703930477063e-06 3.96155289186209e-06 1.02817750524506e-06 -2.10868354560353e-05 5.08682880782416e-05 -1.18703930477063e-06 7.66520961667811e-05 1.84878474977459e-05 3.19410696175293e-05 -1.25524686531752e-05 2.5734141357682e-05 3.96155289186209e-06 1.84878474977459e-05 2.75193287775435e-05 1.45666785254988e-05 -9.84765570607532e-06 3.6145322044349e-05 1.02817750524506e-06 3.19410696175293e-05 1.45666785254988e-05 4.6365122011213e-05 856 868 0 75 0 856 868 0 87 0 0 0 0 0 0 0 0 0 2667 0 0 0 0 0 1758 +861 896 0.997897107915923 0.0471449889250838 0.0444827161073885 0.0231251500647723 -0.0521126244950314 0.99163613172218 0.118076486360795 -0.0221960206476627 -0.0385439538874341 -0.120146295333335 0.992007677055172 0.0683221119022033 4.56663120073859e-05 -5.59306185847817e-05 -3.60738791900044e-06 -1.55332218180654e-05 -3.75582699310824e-06 2.81654654174266e-06 -5.59306185847817e-05 0.000116282780389233 5.88354418446057e-06 6.37163973412082e-05 1.9704388790715e-05 1.85468361047342e-05 -3.60738791900044e-06 5.88354418446057e-06 1.13538256381556e-05 -1.92298894670894e-06 5.34084195642917e-06 -1.03538551135535e-06 -1.55332218180654e-05 6.37163973412082e-05 -1.92298894670894e-06 9.02663603683081e-05 1.67532172664437e-05 2.83386636688858e-05 -3.75582699310824e-06 1.9704388790715e-05 5.34084195642917e-06 1.67532172664437e-05 2.76982606924669e-05 1.25844858628552e-05 2.81654654174266e-06 1.85468361047342e-05 -1.03538551135535e-06 2.83386636688858e-05 1.25844858628552e-05 4.11566498210664e-05 859 863 0 73 0 859 863 0 81 0 0 0 0 0 0 0 0 0 2681 0 0 0 0 0 1098 +861 902 0.997889889764542 0.0477164912703648 0.0440329917965608 0.0244365748543638 -0.0526501488388783 0.991533776443676 0.11869596454213 -0.0209637119286168 -0.0379964436882552 -0.120763846544352 0.991953811240653 0.0652921991478736 5.17663912698832e-05 -7.37980435854943e-05 -3.3491267139354e-06 -2.48815276805153e-05 -1.25619384434275e-05 -1.41407886343884e-05 -7.37980435854943e-05 0.000154106380339308 8.08732097544262e-06 6.85928641987686e-05 3.32321858928455e-05 5.64978919370184e-05 -3.3491267139354e-06 8.08732097544262e-06 9.52183541954025e-06 -3.81685861724769e-07 5.92162759579884e-06 1.89772697604969e-06 -2.48815276805153e-05 6.85928641987686e-05 -3.81685861724769e-07 7.84330350656246e-05 1.96606526479296e-05 4.05802813989516e-05 -1.25619384434275e-05 3.32321858928455e-05 5.92162759579884e-06 1.96606526479296e-05 2.89514489150456e-05 2.07927430713579e-05 -1.41407886343884e-05 5.64978919370184e-05 1.89772697604969e-06 4.05802813989516e-05 2.07927430713579e-05 6.79054281152344e-05 880 893 0 73 0 879 893 0 85 0 0 0 0 0 0 0 0 0 2728 0 0 0 0 0 1757 +861 923 0.997379260148788 0.0464924464570831 0.0554352220839033 0.0287802119169996 -0.0529191301346349 0.991271390382272 0.120750139856608 -0.0192983452811408 -0.0493373802592923 -0.123367268884546 0.991133865770471 0.0689432986246442 2.94016104796074e-05 -3.68729796230479e-05 1.64846649964653e-06 -1.60560073200298e-05 -8.11610836573228e-06 -5.77768045728791e-06 -3.68729796230479e-05 7.08224192361889e-05 5.77237013232268e-07 3.94286735913136e-05 2.04784505906572e-05 2.61377755233762e-05 1.64846649964653e-06 5.77237013232268e-07 8.94166734560999e-06 6.91167494296228e-07 4.68406199914414e-06 1.48739782927137e-06 -1.60560073200298e-05 3.94286735913136e-05 6.91167494296228e-07 6.06927279497489e-05 1.81162240709674e-05 2.86047486998455e-05 -8.11610836573228e-06 2.04784505906572e-05 4.68406199914414e-06 1.81162240709674e-05 2.58945434543043e-05 1.49539272836759e-05 -5.77768045728791e-06 2.61377755233762e-05 1.48739782927137e-06 2.86047486998455e-05 1.49539272836759e-05 4.40302512698524e-05 917 933 0 84 0 916 933 0 94 0 0 0 0 0 0 0 0 0 2623 0 0 0 0 0 1764 +861 889 0.998614016355005 0.0482187885797598 0.0210948990807432 0.0319955572556205 -0.0496466197345078 0.996064640922379 0.0734196448718581 -0.0108574626983433 -0.0174716767444771 -0.0743651768778438 0.99707801148138 0.0660074238016965 3.7239284510272e-05 -4.34791604629432e-05 5.2876565280317e-06 -2.72882479071166e-05 -1.79648760681403e-05 -3.23621192429781e-06 -4.34791604629432e-05 6.63111618319537e-05 -4.77454716624163e-06 5.34752110962478e-05 3.28932527082412e-05 1.81819663728563e-05 5.2876565280317e-06 -4.77454716624163e-06 9.87861473540802e-06 -2.88106240058049e-06 2.77125305921981e-06 6.57627845091424e-07 -2.72882479071166e-05 5.34752110962478e-05 -2.88106240058049e-06 0.000106729284159894 4.43793013941768e-05 3.59667684579753e-05 -1.79648760681403e-05 3.28932527082412e-05 2.77125305921981e-06 4.43793013941768e-05 4.46557416950226e-05 2.29280701761666e-05 -3.23621192429781e-06 1.81819663728563e-05 6.57627845091424e-07 3.59667684579753e-05 2.29280701761666e-05 4.22301423017372e-05 919 931 0 79 0 919 931 0 82 0 0 0 0 0 0 0 0 0 2538 0 0 0 0 0 2053 +861 922 0.997645474238008 0.0469095703957662 0.0500299903828277 0.0264705453246683 -0.0525886796301619 0.991499453597155 0.119009513448712 -0.0204841749944529 -0.0440220229791564 -0.121360313619517 0.991631854959791 0.0676516105048309 4.97041128021464e-05 -5.7557962278306e-05 -4.84063078652208e-06 -2.22122858562191e-05 -1.33219849788699e-05 -1.78532700517937e-05 -5.7557962278306e-05 9.1074619768249e-05 6.96114474923656e-06 4.29112317211234e-05 2.33763468697128e-05 4.3542046463825e-05 -4.84063078652208e-06 6.96114474923656e-06 9.4069525100483e-06 5.71988107126004e-07 5.02548083877487e-06 3.05910101673036e-07 -2.22122858562191e-05 4.29112317211234e-05 5.71988107126004e-07 6.05917973008413e-05 1.53549242235005e-05 3.76997296026382e-05 -1.33219849788699e-05 2.33763468697128e-05 5.02548083877487e-06 1.53549242235005e-05 3.05589461518899e-05 2.10463253399274e-05 -1.78532700517937e-05 4.3542046463825e-05 3.05910101673036e-07 3.76997296026382e-05 2.10463253399274e-05 6.2869364007585e-05 902 904 0 69 0 902 904 0 77 0 0 0 0 0 0 0 0 0 2744 0 0 0 0 0 1735 +861 891 0.997705640523263 0.0464040330833872 0.0492962532213371 0.0245535778577587 -0.051874499106497 0.991868980927753 0.116210847238071 -0.0228255351729959 -0.0435027724463202 -0.118501436223094 0.992000462904402 0.0718927428801416 5.31813734364331e-05 -6.16581884673897e-05 -7.61903650511384e-06 9.6352491078081e-07 -6.55777731998848e-06 4.8693209522527e-06 -6.16581884673897e-05 0.000155309489261333 1.2062469029613e-05 6.18362370450999e-05 2.47860922010442e-05 2.01072926876025e-05 -7.61903650511384e-06 1.2062469029613e-05 1.33586798189658e-05 -4.2965295526854e-06 5.34102542634664e-06 -2.86217241004918e-06 9.6352491078081e-07 6.18362370450999e-05 -4.2965295526854e-06 9.4771827032879e-05 1.64009570393758e-05 2.37287202249294e-05 -6.55777731998848e-06 2.47860922010442e-05 5.34102542634664e-06 1.64009570393758e-05 2.86426718303694e-05 9.2713063138907e-06 4.8693209522527e-06 2.01072926876025e-05 -2.86217241004918e-06 2.37287202249294e-05 9.2713063138907e-06 3.92895643368892e-05 851 864 0 85 0 849 863 0 88 0 0 0 0 0 0 0 0 0 2674 0 0 0 0 0 1280 +861 925 0.997588273082368 0.0465393661233595 0.0514949008094549 0.0244143131762341 -0.0525027188686912 0.991229827188075 0.121271984415588 -0.0199872039890499 -0.0453993603471997 -0.123683131806788 0.991282694788187 0.0686285656671255 3.35156398466291e-05 -4.07233033337203e-05 4.247419288857e-06 -2.12821762403799e-05 -1.19481485826772e-05 1.6597427402e-06 -4.07233033337203e-05 9.35124268711136e-05 -2.91520673458944e-06 6.58150126636207e-05 2.91744834269721e-05 1.51890369781603e-05 4.247419288857e-06 -2.91520673458944e-06 1.11272824399219e-05 -4.74673702194234e-06 3.15867745228891e-06 3.13365182994577e-07 -2.12821762403799e-05 6.58150126636207e-05 -4.74673702194234e-06 9.48093152294129e-05 2.71923890710958e-05 2.38162682221098e-05 -1.19481485826772e-05 2.91744834269721e-05 3.15867745228891e-06 2.71923890710958e-05 3.28061657137626e-05 9.90066296575634e-06 1.6597427402e-06 1.51890369781603e-05 3.13365182994577e-07 2.38162682221098e-05 9.90066296575634e-06 2.84891743746954e-05 893 909 0 76 0 892 909 0 85 0 0 0 0 0 0 0 0 0 2649 0 0 0 0 0 1081 +861 893 0.997437277942749 0.0466401011651325 0.0542547466445646 0.0282133472593597 -0.0528882901245723 0.991352018635739 0.120099974665043 -0.0203444103501196 -0.0481840776383522 -0.122661632592066 0.991278174152942 0.0693853679690602 3.67960560977877e-05 -4.28171803521835e-05 -2.15330452253987e-07 -8.14409940819127e-06 -7.66262294190052e-06 -2.94136604706365e-06 -4.28171803521835e-05 8.21135297507757e-05 4.90651788186254e-06 1.93034585065883e-05 1.31220919860058e-05 2.03742054464314e-05 -2.15330452253987e-07 4.90651788186254e-06 9.98482551234126e-06 6.41901417259928e-07 3.82065952184587e-06 8.9465467178295e-07 -8.14409940819127e-06 1.93034585065883e-05 6.41901417259928e-07 5.07860922334928e-05 1.1013084331758e-05 1.70121816768431e-05 -7.66262294190052e-06 1.31220919860058e-05 3.82065952184587e-06 1.1013084331758e-05 2.52011585640618e-05 9.32172133684729e-06 -2.94136604706365e-06 2.03742054464314e-05 8.9465467178295e-07 1.70121816768431e-05 9.32172133684729e-06 4.23846095736121e-05 899 910 0 74 0 899 910 0 82 0 0 0 0 0 0 0 0 0 2659 0 0 0 0 0 1728 +861 921 0.99765644229395 0.0463103269855447 0.0503684103766439 0.0258640586051606 -0.0520751962206074 0.991416478926801 0.119923055543836 -0.024870868833797 -0.0443823961494118 -0.122264953796567 0.99150465656252 0.0678966213675162 2.6922403765217e-05 -2.62077055393618e-05 3.6705170966899e-06 -8.78731504423809e-06 -4.81206646376036e-06 4.66888663541259e-06 -2.62077055393618e-05 5.76509085645693e-05 5.26109244928114e-07 2.55616040476995e-05 1.30142467121413e-05 8.01893258356223e-06 3.6705170966899e-06 5.26109244928114e-07 1.12461044037507e-05 -3.30188130226646e-06 3.9938962672429e-06 1.11774183197788e-06 -8.78731504423809e-06 2.55616040476995e-05 -3.30188130226646e-06 5.39352652892056e-05 9.40901122093999e-06 9.90276107960965e-06 -4.81206646376036e-06 1.30142467121413e-05 3.9938962672429e-06 9.40901122093999e-06 2.81871168519623e-05 7.4920641361407e-06 4.66888663541259e-06 8.01893258356223e-06 1.11774183197788e-06 9.90276107960965e-06 7.4920641361407e-06 2.6173030148664e-05 875 882 0 72 0 875 882 0 83 0 0 0 0 0 0 0 0 0 2619 0 0 0 0 0 1021 +861 926 0.998001030130913 0.0477285316312283 0.0414237990286265 0.0216573667781413 -0.0523130651379276 0.991663884788054 0.117754332501782 -0.0223447034411088 -0.0354582440838819 -0.119685951036001 0.992178404346263 0.0658256732490269 4.22435701194437e-05 -5.61899495271636e-05 -1.41793686811707e-06 -2.23337986080763e-05 -8.72577815939306e-06 -1.14368373524868e-05 -5.61899495271636e-05 0.000111926480521306 5.81486646881682e-06 5.13820450726466e-05 2.31734703718772e-05 4.24361374959672e-05 -1.41793686811707e-06 5.81486646881682e-06 9.86462579246861e-06 -8.67989116783163e-07 5.6264118407676e-06 1.71422087470503e-06 -2.23337986080763e-05 5.13820450726466e-05 -8.67989116783163e-07 7.3004487824772e-05 1.77069406354732e-05 3.75341233997553e-05 -8.72577815939306e-06 2.31734703718772e-05 5.6264118407676e-06 1.77069406354732e-05 2.81978716569692e-05 2.05696430453749e-05 -1.14368373524868e-05 4.24361374959672e-05 1.71422087470503e-06 3.75341233997553e-05 2.05696430453749e-05 6.11640587637368e-05 887 900 0 73 0 885 900 0 86 0 0 0 0 0 0 0 0 0 2691 0 0 0 0 0 1720 +861 924 0.997766897679834 0.0473955504066437 0.0470625083905626 0.025087768656214 -0.0526765852203656 0.991594110677528 0.11817908884047 -0.0222067127411575 -0.041065743191644 -0.120394275076905 0.991876415318372 0.0677248525712898 3.76930152841823e-05 -4.47036299905417e-05 -2.88841404682494e-06 -3.60205946146109e-06 -6.23796393644568e-06 -8.65732618981125e-06 -4.47036299905417e-05 8.2240170807791e-05 6.06435634570077e-06 2.47335445695666e-05 1.35545992869555e-05 2.89457589377595e-05 -2.88841404682494e-06 6.06435634570077e-06 1.07681310483419e-05 -1.2181057057199e-06 5.48417053654408e-06 1.38216042232331e-06 -3.60205946146109e-06 2.47335445695666e-05 -1.2181057057199e-06 6.43361245621853e-05 5.5130635336349e-06 2.54251601973186e-05 -6.23796393644568e-06 1.35545992869555e-05 5.48417053654408e-06 5.5130635336349e-06 2.21393227009612e-05 8.44235447051918e-06 -8.65732618981125e-06 2.89457589377595e-05 1.38216042232331e-06 2.54251601973186e-05 8.44235447051918e-06 4.96687775435168e-05 867 875 0 73 0 866 874 0 81 0 0 0 0 0 0 0 0 0 2675 0 0 0 0 0 1741 +861 920 0.997124961711223 0.0457801048158114 0.0603820564029147 0.0296405546339598 -0.0527639001833647 0.991411966731095 0.119659028325579 -0.025117513826773 -0.0543854904347784 -0.122500996834454 0.990977156247677 0.0737598327240757 3.44563962534582e-05 -3.78464743460335e-05 6.12232456607152e-07 -1.03504305298355e-05 -6.45099328722681e-06 -9.89471805991539e-06 -3.78464743460335e-05 7.630888249171e-05 3.20285820965066e-06 2.66592884638389e-05 1.22977277871517e-05 3.37023468077674e-05 6.12232456607152e-07 3.20285820965066e-06 1.01237417948852e-05 6.42803554348161e-07 2.8854817520478e-06 2.34359307288198e-06 -1.03504305298355e-05 2.66592884638389e-05 6.42803554348161e-07 4.88619543380645e-05 6.99501870765035e-06 2.05849517483078e-05 -6.45099328722681e-06 1.22977277871517e-05 2.8854817520478e-06 6.99501870765035e-06 3.00697477988903e-05 1.3200480494446e-05 -9.89471805991539e-06 3.37023468077674e-05 2.34359307288198e-06 2.05849517483078e-05 1.3200480494446e-05 5.11847937588693e-05 901 909 0 71 0 900 909 0 77 0 0 0 0 0 0 0 0 0 2425 0 0 0 0 0 1570 +861 928 0.997193411544391 0.0466519213927907 0.0585567946767953 0.0345143922198903 -0.0536559183876893 0.990782587874319 0.124382096730358 -0.0158076855129984 -0.0522143887681653 -0.127174925969813 0.990505020588053 0.075760808098391 0.000273311356031149 -0.000714966351923772 -4.54547098211648e-05 -0.00040391132948735 -0.000195188309806941 -0.000458223886112989 -0.000714966351923772 0.00209057618562195 0.000146912428529279 0.00114984470759912 0.000544339179191861 0.00132555989325893 -4.54547098211648e-05 0.000146912428529279 2.18192264712834e-05 6.77313339574341e-05 3.40873840817785e-05 8.56660470400332e-05 -0.00040391132948735 0.00114984470759912 6.77313339574341e-05 0.000763496974849829 0.000364799313226508 0.000784057734212514 -0.000195188309806941 0.000544339179191861 3.40873840817785e-05 0.000364799313226508 0.000201374934822472 0.000380548174189223 -0.000458223886112989 0.00132555989325893 8.56660470400332e-05 0.000784057734212514 0.000380548174189223 0.000923934660651875 886 898 0 85 0 885 898 0 94 0 0 0 0 0 0 0 0 0 2644 0 0 0 0 0 1764 +861 927 0.997926854134895 0.0478784017519069 0.0430075858670954 0.0244890055623609 -0.0526803051238602 0.991553709199029 0.11851593658958 -0.0206960991090654 -0.0369699776641747 -0.120535888511809 0.992020322539906 0.0664406975086681 4.07935179160677e-05 -5.23975759473899e-05 -3.22007756143913e-06 -1.9225745379549e-05 -7.69663606781576e-06 -6.86784049016261e-06 -5.23975759473899e-05 0.00011326532102305 6.33821213571542e-06 6.21844251679223e-05 2.50211312840228e-05 3.99783745898502e-05 -3.22007756143913e-06 6.33821213571542e-06 9.9090796729121e-06 -1.46712140698212e-06 4.83897503751617e-06 4.12638132872021e-07 -1.9225745379549e-05 6.21844251679223e-05 -1.46712140698212e-06 8.52298708587962e-05 1.73058478670443e-05 3.27474911466977e-05 -7.69663606781576e-06 2.50211312840228e-05 4.83897503751617e-06 1.73058478670443e-05 2.73690418246515e-05 1.58774845204025e-05 -6.86784049016261e-06 3.99783745898502e-05 4.12638132872021e-07 3.27474911466977e-05 1.58774845204025e-05 5.56451175979931e-05 861 876 0 81 0 858 874 0 87 0 0 0 0 0 0 0 0 0 2719 0 0 0 0 0 1740 +861 918 0.997808255051127 0.0472787264212624 0.0462969564853621 0.0233176249941081 -0.0522953191469864 0.992110556701609 0.113937890433951 -0.0298095500933204 -0.0405448609214402 -0.116109281753043 0.992408559487298 0.0682306505360038 5.46473054521726e-05 -6.71992389873125e-05 -5.94383609485718e-06 -1.13786127350821e-05 -1.37894086996487e-05 -2.12570110328379e-05 -6.71992389873125e-05 0.000159029587512362 9.87681161085279e-06 6.09301208417161e-05 2.22899075706214e-05 6.99231437847525e-05 -5.94383609485718e-06 9.87681161085279e-06 1.03713621526407e-05 -4.62394934143517e-07 4.29996649896216e-06 4.56784727873446e-07 -1.13786127350821e-05 6.09301208417161e-05 -4.62394934143517e-07 7.54927055071112e-05 3.74149687774932e-06 4.76017721987236e-05 -1.37894086996487e-05 2.22899075706214e-05 4.29996649896216e-06 3.74149687774932e-06 3.5156456738748e-05 2.33703740000842e-05 -2.12570110328379e-05 6.99231437847525e-05 4.56784727873446e-07 4.76017721987236e-05 2.33703740000842e-05 8.94174123685821e-05 893 907 0 81 0 891 906 0 90 0 0 0 0 0 0 0 0 0 2420 0 0 0 0 0 1697 +861 903 0.997569278821779 0.0474687869699758 0.0510122359301621 0.027273583984585 -0.0533513948161224 0.99122496273951 0.120940902564975 -0.0180662315787209 -0.0448236837193207 -0.12336850289136 0.991348097225276 0.0691474679018437 3.81439319992322e-05 -4.16414200809786e-05 -1.59261321583153e-06 -1.30959214078358e-05 -7.77545691292187e-06 -2.22122848765168e-06 -4.16414200809786e-05 6.91349082046753e-05 2.84651493365884e-06 3.7193660847739e-05 1.91159687219887e-05 1.86988218335252e-05 -1.59261321583153e-06 2.84651493365884e-06 9.39490730215834e-06 -1.90570093204244e-06 4.31180131207216e-06 -1.64945705179505e-06 -1.30959214078358e-05 3.7193660847739e-05 -1.90570093204244e-06 6.93938200909783e-05 1.92413878982474e-05 2.38455560123826e-05 -7.77545691292187e-06 1.91159687219887e-05 4.31180131207216e-06 1.92413878982474e-05 2.77536692857995e-05 1.08824474797186e-05 -2.22122848765168e-06 1.86988218335252e-05 -1.64945705179505e-06 2.38455560123826e-05 1.08824474797186e-05 4.33668611511204e-05 881 894 0 77 0 880 894 0 88 0 0 0 0 0 0 0 0 0 2680 0 0 0 0 0 1733 +861 915 0.99807512179204 0.0477031167076635 0.0396290791739932 0.0180267135266251 -0.0520337207046182 0.991814463026197 0.116604300271002 -0.0248880669536668 -0.0337423053367337 -0.118441899631977 0.992387511631485 0.0656898336279608 5.18201958063232e-05 -7.0768583738278e-05 -1.82651846589879e-06 -3.74687185672741e-05 -2.09673920593554e-05 -2.4515709687492e-05 -7.0768583738278e-05 0.000126929285254216 3.47597599590944e-06 8.08349804679991e-05 4.04403400772159e-05 5.69852684803469e-05 -1.82651846589879e-06 3.47597599590944e-06 9.60070915150181e-06 -3.1004848320368e-06 3.76440420745658e-06 -2.02416410030511e-06 -3.74687185672741e-05 8.08349804679991e-05 -3.1004848320368e-06 0.000111884704897514 3.83785173816593e-05 6.26917839932853e-05 -2.09673920593554e-05 4.04403400772159e-05 3.76440420745658e-06 3.83785173816593e-05 4.18561961694281e-05 3.34860156240351e-05 -2.4515709687492e-05 5.69852684803469e-05 -2.02416410030511e-06 6.26917839932853e-05 3.34860156240351e-05 7.29658361044662e-05 887 895 0 75 0 887 895 0 84 0 0 0 0 0 0 0 0 0 2742 0 0 0 0 0 1628 +861 888 0.998731354355488 0.0494173729600599 0.0096749716784385 0.0466288114646412 -0.0498655383755669 0.997324809498475 0.0534476607658801 -0.00300532939496333 -0.00700784630019156 -0.0538623022953538 0.998523781630501 0.0629023695509759 2.65943662914322e-05 -3.03225748762059e-05 6.47817854857268e-06 -1.47042575182261e-05 -7.17782028958084e-06 7.68341511543639e-06 -3.03225748762059e-05 5.30773444492856e-05 -4.83583934384645e-06 2.76824122644716e-05 1.61660044792682e-05 2.5171426786206e-06 6.47817854857268e-06 -4.83583934384645e-06 1.15259068193686e-05 -4.90801314475841e-06 3.21424678280139e-06 1.38356746285507e-06 -1.47042575182261e-05 2.76824122644716e-05 -4.90801314475841e-06 7.82362088743245e-05 3.03599769445426e-05 1.80885284553021e-06 -7.17782028958084e-06 1.61660044792682e-05 3.21424678280139e-06 3.03599769445426e-05 3.88851787857706e-05 3.61279118044605e-06 7.68341511543639e-06 2.5171426786206e-06 1.38356746285507e-06 1.80885284553021e-06 3.61279118044605e-06 3.76204594482805e-05 846 856 0 84 0 845 856 0 92 0 0 0 0 0 0 0 0 0 2420 0 0 0 0 0 2048 +861 916 0.997651427655129 0.0476255945956932 0.0492283621207281 0.0299972167889806 -0.0532101428885942 0.991445976639942 0.119178673000866 -0.0185064143755653 -0.0431313063963781 -0.121518221447974 0.991651658731363 0.068460963914934 4.04438773128175e-05 -4.83788961566446e-05 -1.04172955725738e-06 -2.07335934279152e-05 -1.35054694192261e-05 -9.89699190926006e-06 -4.83788961566446e-05 8.57547713023388e-05 4.6452126477039e-06 3.9244607412902e-05 2.27689241242965e-05 3.2546657477066e-05 -1.04172955725738e-06 4.6452126477039e-06 9.56397215323854e-06 -3.09622593944253e-06 3.16181403237696e-06 2.11177988581609e-07 -2.07335934279152e-05 3.9244607412902e-05 -3.09622593944253e-06 7.68673296946394e-05 2.23266934909939e-05 2.69246662031735e-05 -1.35054694192261e-05 2.27689241242965e-05 3.16181403237696e-06 2.23266934909939e-05 3.48637910997055e-05 1.50821901680442e-05 -9.89699190926006e-06 3.2546657477066e-05 2.11177988581609e-07 2.69246662031735e-05 1.50821901680442e-05 4.66672371686011e-05 859 870 0 77 0 858 870 0 85 0 0 0 0 0 0 0 0 0 2598 0 0 0 0 0 1756 +861 919 0.997547653218406 0.047143003240275 0.0517321641141919 0.0280028831520815 -0.0530246439594963 0.991484510484337 0.118940542299941 -0.0227916880279163 -0.0456844250420087 -0.12139193842724 0.991552787598047 0.0702459341505375 3.86518415490255e-05 -4.78049326798849e-05 -3.0328005908646e-06 -1.1820211786995e-05 -1.08598293291159e-05 -9.38158109301047e-06 -4.78049326798849e-05 9.38197219070999e-05 5.93062814835525e-06 3.89497472908088e-05 1.75955442254054e-05 3.94438989592044e-05 -3.0328005908646e-06 5.93062814835525e-06 9.6265390261932e-06 5.06522237192826e-07 3.95072855338483e-06 -2.96316735953085e-07 -1.1820211786995e-05 3.89497472908088e-05 5.06522237192826e-07 6.03684855280808e-05 4.71267205142023e-06 2.96961514259584e-05 -1.08598293291159e-05 1.75955442254054e-05 3.95072855338483e-06 4.71267205142023e-06 2.65429575311181e-05 1.046420410778e-05 -9.38158109301047e-06 3.94438989592044e-05 -2.96316735953085e-07 2.96961514259584e-05 1.046420410778e-05 5.98770921919103e-05 889 901 0 69 0 889 901 0 80 0 0 0 0 0 0 0 0 0 2464 0 0 0 0 0 1764 +862 930 0.990208587772516 -0.0432284513260234 0.132733769996612 0.00787524386111456 0.0281310979140823 0.993130569151454 0.113579548982452 -0.0183901524219136 -0.136731832547173 -0.108733498117473 0.984622482150103 -0.00197251692959342 2.79756718789011e-05 -2.69221360092535e-05 -2.98173847823305e-06 5.74535560537032e-07 -2.35303840729713e-06 4.61441689352371e-06 -2.69221360092535e-05 4.71853108120848e-05 5.21231693425299e-06 1.11308451723418e-05 4.95657339622001e-06 3.66627903938102e-06 -2.98173847823305e-06 5.21231693425299e-06 1.09020665657185e-05 -3.14171632811342e-06 3.74564019118745e-06 -2.53191870460677e-06 5.74535560537032e-07 1.11308451723418e-05 -3.14171632811342e-06 4.93763941755892e-05 6.2150004383343e-06 9.88857834112779e-06 -2.35303840729713e-06 4.95657339622001e-06 3.74564019118745e-06 6.2150004383343e-06 1.89286925285359e-05 2.83995991401609e-06 4.61441689352371e-06 3.66627903938102e-06 -2.53191870460677e-06 9.88857834112779e-06 2.83995991401609e-06 3.08306394632502e-05 1106 1103 0 0 0 1098 1097 0 0 0 0 0 0 0 0 32 44 0 2831 0 0 0 0 0 1772 +861 917 0.997573824598728 0.0488342517356209 0.0496153235693249 0.0424933125059905 -0.0545343046879704 0.991163695811667 0.120915415548044 -0.0129772401138923 -0.0432720936362734 -0.123327790713929 0.991422100797614 0.0698364759180701 3.87393297371359e-05 -4.39545490891533e-05 1.07704838071883e-06 -1.08055785682039e-05 -1.07096303059728e-05 8.11809413744653e-07 -4.39545490891533e-05 0.000118943105012705 6.25547888255199e-06 3.19531688031165e-05 8.61924902156809e-06 3.19687363139624e-05 1.07704838071883e-06 6.25547888255199e-06 1.04582682569633e-05 -2.69724111097555e-06 6.40597753108911e-08 3.40462314661934e-06 -1.08055785682039e-05 3.19531688031165e-05 -2.69724111097555e-06 7.93374420210844e-05 2.65652890519594e-05 1.16596450348816e-05 -1.07096303059728e-05 8.61924902156809e-06 6.40597753108911e-08 2.65652890519594e-05 4.38852891790665e-05 -1.12020619561641e-07 8.11809413744653e-07 3.19687363139624e-05 3.40462314661934e-06 1.16596450348816e-05 -1.12020619561641e-07 4.63510913060343e-05 863 869 0 70 0 862 869 0 80 0 0 0 0 0 0 0 0 0 2361 0 0 0 0 0 1733 +861 914 0.99707888798496 0.0469776718850348 0.0602228318741179 0.0338345341903319 -0.0541595306149203 0.990830524772364 0.123780517137768 -0.017894124991896 -0.0538556995892521 -0.126680580688532 0.990480486480258 0.0716843448483372 3.50401915660942e-05 -3.96408257910313e-05 8.49143390273978e-08 -1.07454462824351e-05 -5.05536914653768e-06 -5.64801237653708e-06 -3.96408257910313e-05 6.51189491897365e-05 2.03438292449976e-06 2.19787207714235e-05 7.87139667202003e-06 1.95192206337635e-05 8.49143390273978e-08 2.03438292449976e-06 9.11018987141657e-06 -3.0937139947428e-06 5.04114161429572e-06 4.36211469331505e-07 -1.07454462824351e-05 2.19787207714235e-05 -3.0937139947428e-06 5.31059502549124e-05 6.44935665980575e-06 1.84903681757239e-05 -5.05536914653768e-06 7.87139667202003e-06 5.04114161429572e-06 6.44935665980575e-06 2.35473364239037e-05 7.02878220553606e-06 -5.64801237653708e-06 1.95192206337635e-05 4.36211469331505e-07 1.84903681757239e-05 7.02878220553606e-06 4.10941345831288e-05 912 927 0 83 0 911 927 0 88 0 0 0 0 0 0 0 0 0 2733 0 0 0 0 0 1203 +862 931 0.986779328766654 -0.113173717059719 0.11600976719966 0.00854067765503633 0.102158073389939 0.990039438868757 0.0968795000280891 -0.00486956944352373 -0.125818457946712 -0.0837473536974342 0.988512061832625 -0.0640602901223411 2.68409746926321e-05 -3.11371684311365e-05 -1.00581994756034e-06 4.0891787345656e-07 -5.01258153729122e-06 -3.87948357885573e-06 -3.11371684311365e-05 0.000109952417144665 7.05944913879477e-06 3.0899402820225e-05 7.99119064071445e-06 4.47602834964807e-05 -1.00581994756034e-06 7.05944913879477e-06 1.09171176271905e-05 -3.06336420527465e-06 6.88645255815123e-06 1.02272019901083e-07 4.0891787345656e-07 3.0899402820225e-05 -3.06336420527465e-06 6.42267642271343e-05 -1.89294828756977e-06 2.1675377254892e-05 -5.01258153729122e-06 7.99119064071445e-06 6.88645255815123e-06 -1.89294828756977e-06 2.53383906273555e-05 2.04358305596704e-06 -3.87948357885573e-06 4.47602834964807e-05 1.02272019901083e-07 2.1675377254892e-05 2.04358305596704e-06 4.7308070525798e-05 1139 1139 0 0 0 1129 1129 0 0 0 0 0 0 0 0 151 154 0 2867 0 0 0 0 0 1537 +862 864 0.999387746236493 -0.0130390394815075 -0.0324671545064104 -0.00894467073912366 0.0125859658113608 0.999821088993492 -0.0141203211175803 -0.0136426651356515 0.0326454611996629 0.0137030454012243 0.999373053674049 0.0115399023405579 2.16745073790665e-05 -1.8031564264539e-05 2.50280851616651e-06 -4.92939171134232e-06 -4.32493525782063e-06 9.44711526669011e-06 -1.8031564264539e-05 2.30642121392417e-05 -1.8136430709569e-06 6.59276719368443e-06 4.73401769866494e-06 -6.11703591851835e-06 2.50280851616651e-06 -1.8136430709569e-06 8.58825390794713e-06 -1.10203873443186e-07 -1.16961318669166e-06 1.18727307473064e-06 -4.92939171134232e-06 6.59276719368443e-06 -1.10203873443186e-07 6.50310681122567e-05 2.93419621533822e-05 7.64891295282078e-06 -4.32493525782063e-06 4.73401769866494e-06 -1.16961318669166e-06 2.93419621533822e-05 3.51175774660538e-05 6.79209990710418e-06 9.44711526669011e-06 -6.11703591851835e-06 1.18727307473064e-06 7.64891295282078e-06 6.79209990710418e-06 2.95192661938551e-05 957 953 0 0 0 937 941 0 7 0 0 0 0 0 0 11 22 0 2529 0 0 0 0 0 2606 +862 898 0.995413064522111 0.0408098800827756 0.0865296750619628 0.0244625373303557 -0.0491249013920842 0.994143982165353 0.0962522040663617 -0.0193411645322127 -0.0820949148359226 -0.100061463171613 0.991588689198318 0.0499106871743686 4.94706336489232e-05 -6.9105644660404e-05 -6.99765709804143e-06 -1.90489709273106e-05 -8.77785237123997e-06 7.45844551880378e-06 -6.9105644660404e-05 0.000195424704895173 1.54217199873091e-05 9.45187889529244e-05 3.49966518845996e-05 2.53846568139465e-05 -6.99765709804143e-06 1.54217199873091e-05 1.29709712731518e-05 -1.6449072667417e-06 5.04871008748666e-06 -3.50050020431314e-06 -1.90489709273106e-05 9.45187889529244e-05 -1.6449072667417e-06 0.000108248000215703 3.0290228573487e-05 3.19247575602146e-05 -8.77785237123997e-06 3.49966518845996e-05 5.04871008748666e-06 3.0290228573487e-05 3.03577988719994e-05 9.88861901738977e-06 7.45844551880378e-06 2.53846568139465e-05 -3.50050020431314e-06 3.19247575602146e-05 9.88861901738977e-06 3.92080647210792e-05 841 852 0 73 0 839 850 0 80 0 0 0 0 0 0 0 0 0 2724 0 0 0 0 0 1524 +862 929 0.996057954941697 0.0185996736516265 0.0867329380190534 0.0198955494819974 -0.0283654089819314 0.993217199578568 0.11276080007961 -0.025224051971567 -0.0840473317283287 -0.114776507184001 0.989829479975207 0.041426833317927 2.16240543271797e-05 -2.41628554877096e-05 -1.71460775963108e-06 -2.05625119305732e-06 -1.90624912648636e-06 3.35138029399905e-06 -2.41628554877096e-05 8.02237602999926e-05 8.49933101656525e-06 3.67231457930791e-05 1.16290744949584e-05 1.52927790290805e-05 -1.71460775963108e-06 8.49933101656525e-06 1.17301569220737e-05 -2.65587974732891e-06 4.40439146604619e-06 -1.75165206484981e-06 -2.05625119305732e-06 3.67231457930791e-05 -2.65587974732891e-06 6.83473699616184e-05 1.02982842265419e-05 1.62187972058312e-05 -1.90624912648636e-06 1.16290744949584e-05 4.40439146604619e-06 1.02982842265419e-05 2.59994889532276e-05 5.01464046272417e-06 3.35138029399905e-06 1.52927790290805e-05 -1.75165206484981e-06 1.62187972058312e-05 5.01464046272417e-06 2.81791382295596e-05 904 917 0 53 0 901 914 0 56 0 0 0 0 0 0 0 2 0 2795 0 0 0 0 0 1466 +862 865 0.999557143980578 0.00810942357753989 -0.0286313319045903 0.0155198976796034 -0.00875725898650977 0.999706810727018 -0.022574388165765 -0.00614979368620757 0.0284398722295647 0.0228151229506982 0.999335100870729 0.0181166846208689 3.50870966036183e-05 -4.18857356865575e-05 2.61904573128393e-06 -1.63907876535183e-05 -1.05875468921343e-05 9.30253073378524e-06 -4.18857356865575e-05 9.03208500912344e-05 -3.58835354063993e-06 6.76399818810108e-05 3.52350895442554e-05 5.18911122408733e-06 2.61904573128393e-06 -3.58835354063993e-06 9.67951878760005e-06 -3.06377937375184e-06 7.4809574637175e-07 -1.66347903213958e-06 -1.63907876535183e-05 6.76399818810108e-05 -3.06377937375184e-06 0.000128153847386325 4.95464484349134e-05 2.47289762621222e-05 -1.05875468921343e-05 3.52350895442554e-05 7.4809574637175e-07 4.95464484349134e-05 5.05048632593336e-05 1.59661871466917e-05 9.30253073378524e-06 5.18911122408733e-06 -1.66347903213958e-06 2.47289762621222e-05 1.59661871466917e-05 4.8951637347546e-05 889 890 0 21 0 869 880 0 27 0 0 0 0 0 0 2 12 0 2428 0 0 0 0 0 1920 +862 866 0.999884970387181 0.0125897580825202 0.00845836776506505 0.0356719678230319 -0.0124329712094452 0.999754503066917 -0.0183399788529718 -0.00100587110815318 -0.00868718715871728 0.0182327065694033 0.999796029793289 0.0198063336701904 3.40382007692506e-05 -4.20901005660985e-05 1.17649864674191e-05 -2.61964496591769e-05 -8.2842728371477e-06 1.33607255579299e-05 -4.20901005660985e-05 7.83073552281351e-05 -1.22299180246009e-05 6.37246475007485e-05 2.66428487881905e-05 -4.63477553546245e-06 1.17649864674191e-05 -1.22299180246009e-05 1.18440493581809e-05 -4.46019429645895e-06 1.47400620099906e-06 5.87938590500352e-06 -2.61964496591769e-05 6.37246475007485e-05 -4.46019429645895e-06 0.00011132102248807 4.34281723990194e-05 9.94404504153182e-06 -8.2842728371477e-06 2.66428487881905e-05 1.47400620099906e-06 4.34281723990194e-05 4.47246015472501e-05 6.66106207435744e-06 1.33607255579299e-05 -4.63477553546245e-06 5.87938590500352e-06 9.94404504153182e-06 6.66106207435744e-06 3.26610984466082e-05 862 864 0 28 0 859 864 0 33 0 0 0 0 0 0 0 7 0 2436 0 0 0 0 0 2096 +862 890 0.996843814569022 0.0424032310142544 0.0671146433726098 0.0228302559230003 -0.0470933082477175 0.996440671337205 0.0699157265809777 -0.0153267420943341 -0.0639111075930177 -0.0728557101716285 0.99529262823635 0.046934823882786 2.96841230581683e-05 -3.04854790321208e-05 4.82765242533036e-06 -1.23509150389727e-05 -8.07177149652283e-06 3.1534781549304e-06 -3.04854790321208e-05 5.73088314342676e-05 2.42852563074452e-08 3.38797910636248e-05 1.64494587178711e-05 3.4040703434051e-06 4.82765242533036e-06 2.42852563074452e-08 1.15338259707027e-05 2.26976593430486e-06 4.30299392872625e-06 1.95373216447586e-06 -1.23509150389727e-05 3.38797910636248e-05 2.26976593430486e-06 6.40715526778575e-05 1.66401648085464e-05 9.7662994728822e-06 -8.07177149652283e-06 1.64494587178711e-05 4.30299392872625e-06 1.66401648085464e-05 2.93951689055306e-05 5.36327822334547e-06 3.1534781549304e-06 3.4040703434051e-06 1.95373216447586e-06 9.7662994728822e-06 5.36327822334547e-06 2.73073648251683e-05 868 881 0 71 0 867 880 0 73 0 0 0 0 0 0 0 0 0 2578 0 0 0 0 0 1137 +862 901 0.994860345319182 0.0405108441199231 0.0927995949349432 0.0274232940328576 -0.0493768784149003 0.994220563370793 0.0953278303994359 -0.0216535134847801 -0.0884014546791986 -0.0994200325857659 0.991110912023093 0.0508148627044432 4.66673780047911e-05 -5.35273508014049e-05 -2.11354535346277e-06 -1.8453151193443e-05 -1.12572607542509e-05 -3.83245742170685e-06 -5.35273508014049e-05 8.63797297703682e-05 5.51898504599032e-06 3.96168779512112e-05 2.30987728198687e-05 1.92946002500444e-05 -2.11354535346277e-06 5.51898504599032e-06 9.5092024603296e-06 3.22944711665522e-07 4.97428258077671e-06 5.00438286468864e-07 -1.8453151193443e-05 3.96168779512112e-05 3.22944711665522e-07 6.25356088300751e-05 1.65183341855936e-05 2.54314907544967e-05 -1.12572607542509e-05 2.30987728198687e-05 4.97428258077671e-06 1.65183341855936e-05 2.89546691553963e-05 1.50502921878804e-05 -3.83245742170685e-06 1.92946002500444e-05 5.00438286468864e-07 2.54314907544967e-05 1.50502921878804e-05 4.83304363112703e-05 859 867 0 71 0 853 865 0 71 0 0 0 0 0 0 0 1 0 2618 0 0 0 0 0 1822 +862 899 0.995717801287929 0.0407247555766036 0.0829912916007352 0.0188369713359688 -0.0485276668298177 0.994361943893997 0.0942835621272641 -0.0228023558908545 -0.0786837070198562 -0.09790719492753 0.992080165828869 0.0468192984730936 2.60824986285429e-05 -3.05707203344114e-05 2.15702970280315e-07 -9.95655065647492e-06 -4.00017805069315e-06 -5.97234119301704e-06 -3.05707203344114e-05 5.73653664847417e-05 3.27686829355415e-06 2.2714546267504e-05 1.34187406826251e-05 2.44446334728419e-05 2.15702970280315e-07 3.27686829355415e-06 9.52225771777802e-06 -8.96650491682487e-07 4.16801518322262e-06 6.10378255678109e-07 -9.95655065647492e-06 2.2714546267504e-05 -8.96650491682487e-07 5.83907361009021e-05 1.69036375708077e-05 2.35896218025894e-05 -4.00017805069315e-06 1.34187406826251e-05 4.16801518322262e-06 1.69036375708077e-05 2.39936108543635e-05 1.26841010099103e-05 -5.97234119301704e-06 2.44446334728419e-05 6.10378255678109e-07 2.35896218025894e-05 1.26841010099103e-05 4.70241870463217e-05 902 918 0 78 0 897 913 0 77 0 0 0 0 0 0 0 0 0 2760 0 0 0 0 0 1806 +862 893 0.995341919823354 0.0401976059180789 0.0876277074949215 0.0226132855774424 -0.0484663975590338 0.994356222484244 0.094375373453638 -0.0229247474692664 -0.0833394921391435 -0.0981827647060256 0.991672664625112 0.0492606380982954 3.20130816396137e-05 -3.50034658427977e-05 -4.8967931132487e-07 -6.04552597550615e-06 -3.82103283458428e-06 1.90397579278087e-06 -3.50034658427977e-05 6.87095099493191e-05 3.42163899304117e-06 2.9509526704058e-05 9.52693061290626e-06 1.21473772480663e-05 -4.8967931132487e-07 3.42163899304117e-06 9.18333057348573e-06 6.31479639178996e-07 2.7986220032881e-06 -5.7815341718526e-07 -6.04552597550615e-06 2.9509526704058e-05 6.31479639178996e-07 6.11945493788495e-05 1.1437483117692e-05 1.42349097992181e-05 -3.82103283458428e-06 9.52693061290626e-06 2.7986220032881e-06 1.1437483117692e-05 2.388927077876e-05 7.14875125485374e-06 1.90397579278087e-06 1.21473772480663e-05 -5.7815341718526e-07 1.42349097992181e-05 7.14875125485374e-06 3.79356762768435e-05 914 923 0 71 0 909 920 0 71 0 0 0 0 0 0 0 0 0 2611 0 0 0 0 0 1872 +862 895 0.995927338842179 0.040521271045256 0.0805404391570616 0.0174397682812358 -0.0480532241901734 0.994421821388142 0.0938942425925044 -0.0239212641259023 -0.0762864561482861 -0.0973820709369442 0.992319055983693 0.0483860508178308 2.84395711768372e-05 -3.1993991750408e-05 -8.21553923992899e-08 -5.00655992071943e-06 -4.56237611531868e-06 3.46642938843252e-06 -3.1993991750408e-05 8.86979761250352e-05 5.55464465285682e-06 2.84355271955136e-05 1.37548421754912e-05 1.59476731431644e-05 -8.21553923992899e-08 5.55464465285682e-06 1.04565275023475e-05 -2.07457385832578e-06 4.42970167030467e-06 -7.88912896617902e-07 -5.00655992071943e-06 2.84355271955136e-05 -2.07457385832578e-06 5.85341871561654e-05 1.2795177846997e-05 1.4005440497996e-05 -4.56237611531868e-06 1.37548421754912e-05 4.42970167030467e-06 1.2795177846997e-05 2.57149225481521e-05 5.89237035340795e-06 3.46642938843252e-06 1.59476731431644e-05 -7.88912896617902e-07 1.4005440497996e-05 5.89237035340795e-06 3.08262083732792e-05 844 859 0 75 0 841 856 0 78 0 0 0 0 0 0 0 1 0 2707 0 0 0 0 0 1473 +862 900 0.995694221685575 0.0407336792281396 0.0832693477727254 0.0192400992205421 -0.048569061221793 0.994353872985396 0.094347345330837 -0.0258714526074672 -0.0789560839580446 -0.0979854206271603 0.992050802202452 0.0499985842931864 4.23731699281108e-05 -6.59065874108555e-05 -1.66841465740945e-06 -1.93575866221173e-05 -9.88989096308125e-06 -5.01463324670772e-06 -6.59065874108555e-05 0.000175299304079494 1.29616951708755e-05 7.39765777263491e-05 2.62536335411889e-05 4.54016054617629e-05 -1.66841465740945e-06 1.29616951708755e-05 1.22303000611115e-05 3.35227352524979e-06 6.69194040006129e-06 3.71395136799952e-06 -1.93575866221173e-05 7.39765777263491e-05 3.35227352524979e-06 7.41625871949814e-05 1.36231723361561e-05 3.39452900456408e-05 -9.88989096308125e-06 2.62536335411889e-05 6.69194040006129e-06 1.36231723361561e-05 2.88895067305339e-05 1.23739364797717e-05 -5.01463324670772e-06 4.54016054617629e-05 3.71395136799952e-06 3.39452900456408e-05 1.23739364797717e-05 5.18635553525525e-05 885 899 0 77 0 883 897 0 79 0 0 0 0 0 0 0 0 0 2654 0 0 0 0 0 1274 +862 892 0.995607775791298 0.0406724993438518 0.084326179689515 0.0213079204971546 -0.0485215639734691 0.99446218215852 0.0932235275350718 -0.0229537408609647 -0.0800675628046249 -0.0969057070230548 0.992067774566279 0.0482653017579126 2.10988164753793e-05 -2.454456136761e-05 1.70545339443024e-07 1.74362702780167e-06 -5.70304633104083e-07 2.19349475818105e-06 -2.454456136761e-05 8.61032667034921e-05 9.54716722220884e-06 6.93911914345997e-06 5.18367871671413e-06 1.64878157019528e-05 1.70545339443024e-07 9.54716722220884e-06 9.89379889986e-06 -6.58224516749531e-07 5.39189117939008e-06 4.35144214192091e-07 1.74362702780167e-06 6.93911914345997e-06 -6.58224516749531e-07 4.01744228418923e-05 3.51788724737461e-06 8.66672486118488e-06 -5.70304633104083e-07 5.18367871671413e-06 5.39189117939008e-06 3.51788724737461e-06 1.93489045164882e-05 9.42401561082944e-07 2.19349475818105e-06 1.64878157019528e-05 4.35144214192091e-07 8.66672486118488e-06 9.42401561082944e-07 3.34541624840994e-05 863 878 0 76 0 861 876 0 76 0 0 0 0 0 0 0 0 0 2753 0 0 0 0 0 1841 +862 896 0.99514676198843 0.0407655132799033 0.0895605662720435 0.026103283772089 -0.0492551433875138 0.994284256068803 0.0947245954521935 -0.0229836626961724 -0.0851871642550597 -0.0986761929785108 0.991466669124812 0.0500723981208297 2.71215828694158e-05 -2.45653630295062e-05 -1.38966761734529e-06 -1.14451896831047e-06 -4.68136900071668e-06 8.86918185937736e-06 -2.45653630295062e-05 5.70367730406148e-05 7.03547033964549e-06 1.4463927916366e-05 9.02510474503409e-06 9.15099109823962e-08 -1.38966761734529e-06 7.03547033964549e-06 9.92401100360687e-06 -8.18792032721819e-07 4.92724837045046e-06 -1.32209213184446e-06 -1.14451896831047e-06 1.4463927916366e-05 -8.18792032721819e-07 4.74978270830781e-05 3.95948446454895e-06 7.61614066835064e-06 -4.68136900071668e-06 9.02510474503409e-06 4.92724837045046e-06 3.95948446454895e-06 2.29109582973627e-05 2.67792046042842e-06 8.86918185937736e-06 9.15099109823962e-08 -1.32209213184446e-06 7.61614066835064e-06 2.67792046042842e-06 2.60188843365845e-05 859 870 0 78 0 858 869 0 78 0 0 0 0 0 0 0 0 0 2634 0 0 0 0 0 1503 +862 894 0.995262898548144 0.0405870849791314 0.0883428056292321 0.0238662170778242 -0.0489367760319498 0.994321395347041 0.0944994958013694 -0.0244029761137345 -0.0840056826955553 -0.0983750541957208 0.991597395108944 0.0499056615362199 4.93136988585889e-05 -7.74782262347774e-05 9.36635954260645e-07 -3.67637398940233e-05 -1.87705951064875e-05 -1.69565877680886e-05 -7.74782262347774e-05 0.000208584288904447 1.0547091542125e-05 0.000109407449009259 4.83767225546221e-05 7.4165686253634e-05 9.36635954260645e-07 1.0547091542125e-05 1.09048226279498e-05 4.03906144888719e-06 6.55191386878322e-06 5.6787656390703e-06 -3.67637398940233e-05 0.000109407449009259 4.03906144888719e-06 0.000116932895281988 3.16893207967759e-05 5.71312209060075e-05 -1.87705951064875e-05 4.83767225546221e-05 6.55191386878322e-06 3.16893207967759e-05 3.41725965342466e-05 2.37158598723566e-05 -1.69565877680886e-05 7.4165686253634e-05 5.6787656390703e-06 5.71312209060075e-05 2.37158598723566e-05 6.58937904227737e-05 847 858 0 71 0 846 857 0 74 0 0 0 0 0 0 0 0 0 2634 0 0 0 0 0 1817 +862 891 0.995495246063816 0.0395891871787911 0.0861505155113104 0.0193860882489335 -0.0474350465700086 0.99471887043055 0.0910180485742901 -0.0255988934327592 -0.0820922129147644 -0.0946945883770206 0.992115821621077 0.0496799389884435 3.36873736211669e-05 -4.18436490080918e-05 -4.79108386374401e-06 -8.45072507191844e-06 -6.28615965499136e-06 1.85461533427587e-06 -4.18436490080918e-05 0.000101459765450384 1.12499652169096e-05 3.29613167110917e-05 1.70198175489359e-05 1.39661251652289e-05 -4.79108386374401e-06 1.12499652169096e-05 1.3912902248227e-05 -3.83609814824058e-06 2.032600131264e-06 -2.42626830435694e-06 -8.45072507191844e-06 3.29613167110917e-05 -3.83609814824058e-06 6.5135067619266e-05 1.57312124339604e-05 1.0745441217264e-05 -6.28615965499136e-06 1.70198175489359e-05 2.032600131264e-06 1.57312124339604e-05 3.11465292782971e-05 4.97420705184395e-06 1.85461533427587e-06 1.39661251652289e-05 -2.42626830435694e-06 1.0745441217264e-05 4.97420705184395e-06 2.81768061703529e-05 839 851 0 72 0 837 849 0 83 0 0 0 0 0 0 0 0 0 2654 0 0 0 0 0 1396 +862 923 0.995668968413528 0.0409170719797196 0.0834811269626083 0.0234845921225223 -0.0486775416046274 0.99446144950985 0.0931499993671407 -0.0236737468227477 -0.0792073372969351 -0.0968102198085253 0.992146148034126 0.0497079524226162 3.03173433838579e-05 -4.01082443727373e-05 7.9699827735524e-07 -1.62092496113324e-05 -8.6186040540549e-06 -2.62046022380486e-06 -4.01082443727373e-05 9.25000458948553e-05 3.30602269364278e-06 4.72770999139176e-05 2.21662708744315e-05 2.78314648505901e-05 7.9699827735524e-07 3.30602269364278e-06 9.89516434138512e-06 -4.07456158627551e-07 4.31659931822385e-06 5.06265914794008e-07 -1.62092496113324e-05 4.72770999139176e-05 -4.07456158627551e-07 7.66851870693806e-05 2.06165749045387e-05 3.03201458877721e-05 -8.6186040540549e-06 2.21662708744315e-05 4.31659931822385e-06 2.06165749045387e-05 2.84882354208973e-05 1.30399728485913e-05 -2.62046022380486e-06 2.78314648505901e-05 5.06265914794008e-07 3.03201458877721e-05 1.30399728485913e-05 4.49545352485357e-05 868 884 0 76 0 865 881 0 78 0 0 0 0 0 0 0 0 0 2593 0 0 0 0 0 1797 +862 922 0.996424223927036 0.0413809341439683 0.0736639956883663 0.0144861248774075 -0.0480215176607003 0.994711890727876 0.0907864983691833 -0.0268847880932363 -0.0695176223195683 -0.0939993230504732 0.99314219900933 0.0444667313564393 4.361527420279e-05 -6.24202417752744e-05 -2.97923051961557e-06 -2.20430109668104e-05 -1.28306270062738e-05 -1.65076848191806e-05 -6.24202417752744e-05 0.000147550780761155 9.88149996331861e-06 7.54319179031848e-05 3.63189607891627e-05 6.08202715065502e-05 -2.97923051961557e-06 9.88149996331861e-06 9.87892326125116e-06 1.96088353362303e-06 5.61752587495756e-06 1.92731627134248e-06 -2.20430109668104e-05 7.54319179031848e-05 1.96088353362303e-06 9.39692649941969e-05 3.09009841288372e-05 4.82789367860398e-05 -1.28306270062738e-05 3.63189607891627e-05 5.61752587495756e-06 3.09009841288372e-05 3.38887346713568e-05 2.47193299141244e-05 -1.65076848191806e-05 6.08202715065502e-05 1.92731627134248e-06 4.82789367860398e-05 2.47193299141244e-05 6.80434372986291e-05 897 906 0 75 0 889 902 0 73 0 0 0 0 0 0 0 0 0 2727 0 0 0 0 0 1793 +862 925 0.995845698042263 0.0410455646274843 0.0812810390874072 0.0214051232380937 -0.0486446241069719 0.994398806754322 0.0938334357842237 -0.0242623063148687 -0.0769743219275689 -0.0973975089516751 0.992264419907214 0.0498273754655618 3.33990694391946e-05 -3.80397950016376e-05 3.77854043098651e-06 -1.66457957235542e-05 -8.08898702286594e-06 5.84819022148579e-06 -3.80397950016376e-05 8.12319753606636e-05 -9.75552945471545e-07 4.72673645876355e-05 1.78710130909375e-05 7.86716987539442e-06 3.77854043098651e-06 -9.75552945471545e-07 9.84219884647073e-06 -2.16046658910529e-06 3.77767416921241e-06 -6.70309925477844e-08 -1.66457957235542e-05 4.72673645876355e-05 -2.16046658910529e-06 8.19185287699142e-05 2.15565363045533e-05 2.04916327126262e-05 -8.08898702286594e-06 1.78710130909375e-05 3.77767416921241e-06 2.15565363045533e-05 3.06784811993459e-05 9.03295241538737e-06 5.84819022148579e-06 7.86716987539442e-06 -6.70309925477844e-08 2.04916327126262e-05 9.03295241538737e-06 3.07660260841337e-05 874 890 0 74 0 872 888 0 73 0 0 0 0 0 0 0 1 0 2607 0 0 0 0 0 1417 +862 889 0.997344446973602 0.0439661150722333 0.0580606132965753 0.0314316894002424 -0.0468469202758458 0.997688464273954 0.0492249359100391 -0.0135276302753571 -0.0557621749180201 -0.0518141774047803 0.997098726740877 0.0464351884115781 3.14580312029734e-05 -3.68308508991628e-05 5.28926362775851e-06 -1.79698315618259e-05 -1.33060259351203e-05 -5.62317808296347e-06 -3.68308508991628e-05 7.53881233517839e-05 -3.39941836196019e-06 5.62327454482083e-05 2.8163278682059e-05 2.36473084577409e-05 5.28926362775851e-06 -3.39941836196019e-06 9.28035513119958e-06 1.04999714992845e-06 2.99865027428588e-06 6.98733196824748e-07 -1.79698315618259e-05 5.62327454482083e-05 1.04999714992845e-06 9.08909266426047e-05 2.75568597792511e-05 3.3889881345667e-05 -1.33060259351203e-05 2.8163278682059e-05 2.99865027428588e-06 2.75568597792511e-05 3.562714387795e-05 1.79922948431211e-05 -5.62317808296347e-06 2.36473084577409e-05 6.98733196824748e-07 3.3889881345667e-05 1.79922948431211e-05 3.93832768929465e-05 836 849 0 71 0 833 846 0 72 0 0 0 0 0 0 0 0 0 2539 0 0 0 0 0 2148 +862 903 0.995297502016187 0.0409081939374857 0.0878032012463755 0.0252069686693293 -0.0492518841199769 0.994251683421252 0.095067565050541 -0.0220550396316983 -0.0834094382607317 -0.0989449831107143 0.991591022511927 0.0493961132571066 2.76676585496436e-05 -3.17108776649493e-05 -7.15490740644242e-07 -4.61366152013845e-06 -3.43231409625135e-06 6.02489154019636e-06 -3.17108776649493e-05 8.12303260359332e-05 6.60234451089394e-06 2.85318737615876e-05 1.35860002477273e-05 8.76615132960767e-06 -7.15490740644242e-07 6.60234451089394e-06 1.05091442759756e-05 -2.16379528869959e-06 5.42149795648709e-06 -7.0716936059506e-07 -4.61366152013845e-06 2.85318737615876e-05 -2.16379528869959e-06 5.93326379629777e-05 8.84546611847202e-06 1.419920232403e-05 -3.43231409625135e-06 1.35860002477273e-05 5.42149795648709e-06 8.84546611847202e-06 2.50638931146437e-05 6.45488887165396e-06 6.02489154019636e-06 8.76615132960767e-06 -7.0716936059506e-07 1.419920232403e-05 6.45488887165396e-06 3.51413562049481e-05 866 879 0 75 0 863 877 0 78 0 0 0 0 0 0 0 1 0 2666 0 0 0 0 0 1843 +862 902 0.995369593004803 0.0405830179869474 0.0871343329149007 0.0231817857078934 -0.0489239161340914 0.994194824912342 0.0958284954886727 -0.0203396623452208 -0.0827394933001045 -0.0996477233487513 0.99157677840894 0.047513648356292 2.33156929074206e-05 -3.12788712519721e-05 9.95841377969975e-07 -1.04572769743831e-05 -3.22066222963596e-06 3.70711927402216e-06 -3.12788712519721e-05 8.56490238022151e-05 6.65451159572599e-06 3.42344990564324e-05 1.66738604873273e-05 1.33971123045103e-05 9.95841377969975e-07 6.65451159572599e-06 1.00761643479957e-05 -1.5969548740462e-06 6.23648106599983e-06 -4.84614873671056e-07 -1.04572769743831e-05 3.42344990564324e-05 -1.5969548740462e-06 6.08472225440919e-05 1.27582795929518e-05 1.90672097173412e-05 -3.22066222963596e-06 1.66738604873273e-05 6.23648106599983e-06 1.27582795929518e-05 2.53132207410897e-05 8.82393488441394e-06 3.70711927402216e-06 1.33971123045103e-05 -4.84614873671056e-07 1.90672097173412e-05 8.82393488441394e-06 3.38119119901661e-05 870 879 0 69 0 868 877 0 69 0 0 0 0 0 0 0 1 0 2723 0 0 0 0 0 1814 +862 920 0.995657376395919 0.0395763680081029 0.084262090667651 0.0183577178281813 -0.0475298515594728 0.994382092182419 0.0945788980568571 -0.0276243081348505 -0.0800456247344645 -0.0981731421632317 0.99194492393412 0.0510568053644946 3.81380970231518e-05 -4.30500158894481e-05 -3.42891871175537e-06 -5.65872005656193e-06 -3.80701732289249e-06 2.81048265458957e-06 -4.30500158894481e-05 9.83985697072153e-05 1.11344134826062e-05 2.67245224019401e-05 5.35994103378154e-06 1.95652240814938e-05 -3.42891871175537e-06 1.11344134826062e-05 1.33246172520312e-05 -1.32729634738224e-06 2.25705925224465e-06 1.87495572982107e-06 -5.65872005656193e-06 2.67245224019401e-05 -1.32729634738224e-06 6.20438443808866e-05 9.37746323512361e-06 2.01552788057474e-05 -3.80701732289249e-06 5.35994103378154e-06 2.25705925224465e-06 9.37746323512361e-06 3.1059236925009e-05 4.63405693018738e-06 2.81048265458957e-06 1.95652240814938e-05 1.87495572982107e-06 2.01552788057474e-05 4.63405693018738e-06 4.20025537771619e-05 889 897 0 73 0 888 896 0 74 0 0 0 0 0 0 0 1 0 2456 0 0 0 0 0 1259 +862 927 0.994773876854513 0.0404944197810752 0.0937290557641326 0.0312180659752745 -0.0496617405582264 0.993982209558929 0.0976374856552433 -0.0175511180224173 -0.0892112406178124 -0.101781968181719 0.990798559496574 0.0497388908100217 3.34767734180054e-05 -3.97543840291212e-05 -1.87206324469635e-06 -1.03703561648663e-05 -7.08494506861673e-06 2.55572919656472e-06 -3.97543840291212e-05 0.000103304639902268 6.78547542998621e-06 5.18234767379827e-05 2.62306870014109e-05 2.41478660031982e-05 -1.87206324469635e-06 6.78547542998621e-06 9.93044871670884e-06 -1.29453100010113e-06 5.44199712171599e-06 -1.41944408354009e-06 -1.03703561648663e-05 5.18234767379827e-05 -1.29453100010113e-06 8.1752493672318e-05 2.46133352821173e-05 3.32973934212198e-05 -7.08494506861673e-06 2.62306870014109e-05 5.44199712171599e-06 2.46133352821173e-05 3.01711000632176e-05 1.62692284628144e-05 2.55572919656472e-06 2.41478660031982e-05 -1.41944408354009e-06 3.32973934212198e-05 1.62692284628144e-05 4.58993598013164e-05 841 855 0 75 0 839 853 0 74 0 0 0 0 0 0 0 1 0 2677 0 0 0 0 0 1855 +862 924 0.995400585946233 0.0404807669473228 0.0868273056431682 0.0240830570705363 -0.0486522575998421 0.994367489776194 0.0941607832732366 -0.0236760658468657 -0.0825265492331663 -0.0979520432841877 0.991763462670469 0.0501429525138544 2.68428282718474e-05 -4.3566929875348e-05 -1.33736917482983e-06 -1.42648758362751e-05 -5.32077458224022e-06 4.09617649050926e-06 -4.3566929875348e-05 0.00018148625104066 1.16902798341011e-05 9.45772607066159e-05 2.82056902215264e-05 3.53497459542019e-05 -1.33736917482983e-06 1.16902798341011e-05 1.0050065121737e-05 3.77716055836298e-06 6.27726318427114e-06 5.14686053019684e-07 -1.42648758362751e-05 9.45772607066159e-05 3.77716055836298e-06 9.74999485136215e-05 1.4581744832997e-05 3.50364483440048e-05 -5.32077458224022e-06 2.82056902215264e-05 6.27726318427114e-06 1.4581744832997e-05 2.71129490801285e-05 1.03445153725865e-05 4.09617649050926e-06 3.53497459542019e-05 5.14686053019684e-07 3.50364483440048e-05 1.03445153725865e-05 4.39143415083709e-05 844 852 0 75 0 838 849 0 75 0 0 0 0 0 0 0 1 0 2647 0 0 0 0 0 1844 +862 921 0.995431117319266 0.040251018888884 0.0865837522340369 0.0245869862232039 -0.0484665895965185 0.994298765171719 0.0949787095662852 -0.0243838029376517 -0.0822671280974426 -0.098741182170363 0.99170676037738 0.0488128918478551 4.26774066206577e-05 -5.83819457935284e-05 2.16307902820787e-06 -1.82613260270193e-05 -6.93383110347577e-06 2.95065971924826e-06 -5.83819457935284e-05 0.000145881491477775 3.96188207586202e-06 6.60778346102518e-05 2.99461875779355e-05 1.85659359084517e-05 2.16307902820787e-06 3.96188207586202e-06 1.21791164845557e-05 -4.13243077262983e-06 2.65279320236805e-06 1.66663057382251e-07 -1.82613260270193e-05 6.60778346102518e-05 -4.13243077262983e-06 9.77829177805232e-05 3.96771766307003e-05 2.13897778566999e-05 -6.93383110347577e-06 2.99461875779355e-05 2.65279320236805e-06 3.96771766307003e-05 4.07913129148851e-05 1.13342311381201e-05 2.95065971924826e-06 1.85659359084517e-05 1.66663057382251e-07 2.13897778566999e-05 1.13342311381201e-05 3.65943002709048e-05 871 879 0 76 0 863 877 0 78 0 0 0 0 0 0 0 0 0 2589 0 0 0 0 0 1453 +862 926 0.995244999645014 0.0406784375508988 0.088502290365919 0.0245085079318014 -0.0490939513411955 0.994257358714111 0.0950898973842558 -0.0215280133606043 -0.0841259450069011 -0.0989826720252469 0.991526729854238 0.0493061054768667 3.1440187911038e-05 -4.61915717257705e-05 -2.06434295790606e-06 -1.34110154835995e-05 -5.80789832027323e-06 -2.18553185733764e-07 -4.61915717257705e-05 0.000133291113341092 9.51303571092488e-06 6.66977461484032e-05 2.54132188643791e-05 3.08601759771512e-05 -2.06434295790606e-06 9.51303571092488e-06 1.00087362230276e-05 -8.91159879172127e-07 4.57233882360554e-06 -1.58022294508533e-06 -1.34110154835995e-05 6.66977461484032e-05 -8.91159879172127e-07 9.26656258968685e-05 2.46512788043369e-05 3.97378041902479e-05 -5.80789832027323e-06 2.54132188643791e-05 4.57233882360554e-06 2.46512788043369e-05 2.81371728840692e-05 1.27381543385753e-05 -2.18553185733764e-07 3.08601759771512e-05 -1.58022294508533e-06 3.97378041902479e-05 1.27381543385753e-05 4.29498462335468e-05 847 855 0 66 0 845 853 0 68 0 0 0 0 0 0 0 1 0 2642 0 0 0 0 0 1867 +862 888 0.998508099511412 0.0443086848948162 0.0319110584750842 0.021887629892226 -0.0451074838608284 0.998675184253346 0.0247626988894894 -0.0121613962017224 -0.0307715795800844 -0.0261651829620642 0.999183913546805 0.0430724656166267 2.77580700013938e-05 -3.6786336257806e-05 6.6413335116633e-06 -1.86502204553596e-05 -1.04837769599726e-05 -3.5311857507315e-07 -3.6786336257806e-05 6.88374728128383e-05 -6.41907873661565e-06 4.57527539301495e-05 2.70778963549562e-05 1.53364261572444e-05 6.6413335116633e-06 -6.41907873661565e-06 1.11892174202517e-05 -2.40399573993321e-06 2.2674241359901e-06 -6.25671801321732e-07 -1.86502204553596e-05 4.57527539301495e-05 -2.40399573993321e-06 9.76512625506111e-05 4.1932339973808e-05 1.9971517626661e-05 -1.04837769599726e-05 2.70778963549562e-05 2.2674241359901e-06 4.1932339973808e-05 3.87778650923145e-05 1.14828936675509e-05 -3.5311857507315e-07 1.53364261572444e-05 -6.25671801321732e-07 1.9971517626661e-05 1.14828936675509e-05 4.11907471915644e-05 879 891 0 78 0 874 886 0 77 0 0 0 0 0 0 0 0 0 2431 0 0 0 0 0 1807 +862 919 0.994961164630653 0.0403909232015726 0.0917652123614325 0.0255938040519175 -0.0491199127410325 0.994269622381436 0.0949481552311057 -0.0226844662948168 -0.0874043193962831 -0.0989772263321289 0.991243660064704 0.052237611763464 3.82748475910576e-05 -5.33103406630145e-05 -4.61735235834918e-06 -6.13635864902851e-06 -5.78346878080178e-06 -3.81471261163931e-06 -5.33103406630145e-05 0.00013221946271578 1.17866458374634e-05 3.97618836909567e-05 1.61793763901006e-05 3.29899255018006e-05 -4.61735235834918e-06 1.17866458374634e-05 1.11553000151666e-05 -2.12986853016969e-06 3.53864889874672e-06 -1.08146405876983e-06 -6.13635864902851e-06 3.97618836909567e-05 -2.12986853016969e-06 6.9942484623592e-05 1.41077457089764e-05 2.96884652480878e-05 -5.78346878080178e-06 1.61793763901006e-05 3.53864889874672e-06 1.41077457089764e-05 3.00004637237171e-05 6.05614654588708e-06 -3.81471261163931e-06 3.29899255018006e-05 -1.08146405876983e-06 2.96884652480878e-05 6.05614654588708e-06 5.15808592017711e-05 866 880 0 74 0 864 878 0 74 0 0 0 0 0 0 0 2 0 2454 0 0 0 0 0 1806 +862 928 0.995354475642633 0.040705686301388 0.0872497273400405 0.0246736781215269 -0.048933575072918 0.994336748429263 0.0943394718752619 -0.023620080990318 -0.0829154572366426 -0.0981706566436898 0.991709407601534 0.0485300458116682 3.73290220847879e-05 -4.0770919107617e-05 -4.18959970493559e-06 -2.795846256498e-06 -5.24161792336847e-06 -5.60275775631628e-07 -4.0770919107617e-05 7.242592367415e-05 7.13799769073337e-06 2.78870490960167e-05 1.62826773206169e-05 2.13025377614032e-05 -4.18959970493559e-06 7.13799769073337e-06 1.06964948549148e-05 -4.56741194703666e-06 4.06964105941482e-06 -1.69284438086778e-06 -2.795846256498e-06 2.78870490960167e-05 -4.56741194703666e-06 7.0408049404126e-05 1.35522552791255e-05 3.07228596787604e-05 -5.24161792336847e-06 1.62826773206169e-05 4.06964105941482e-06 1.35522552791255e-05 2.80874461049622e-05 1.29238523376295e-05 -5.60275775631628e-07 2.13025377614032e-05 -1.69284438086778e-06 3.07228596787604e-05 1.29238523376295e-05 5.16378852945772e-05 870 881 0 75 0 864 877 0 73 0 0 0 0 0 0 0 0 0 2615 0 0 0 0 0 1823 +863 930 0.986815220106915 -0.0428415824391841 0.156077929828172 0.00896629823528946 0.024820521386476 0.992981930579372 0.115632293330912 -0.0157030069301243 -0.159936434508978 -0.110233771399554 0.980953032800035 -0.0111518821554888 1.67814190076471e-05 -1.22196640674369e-05 2.96625070999987e-06 -1.36381316548217e-06 -5.28856798380511e-07 3.57178978600217e-06 -1.22196640674369e-05 3.5068270726912e-05 -4.64280882602496e-07 3.34005911515777e-06 2.80236245091959e-06 -1.31575957593434e-06 2.96625070999987e-06 -4.64280882602496e-07 9.48071707827285e-06 -2.43061493344083e-06 1.77532250929308e-06 -3.81431948245706e-07 -1.36381316548217e-06 3.34005911515777e-06 -2.43061493344083e-06 4.96890327849114e-05 5.65694548007282e-06 6.48976788757435e-06 -5.28856798380511e-07 2.80236245091959e-06 1.77532250929308e-06 5.65694548007282e-06 1.92686379603769e-05 -1.20416597442184e-07 3.57178978600217e-06 -1.31575957593434e-06 -3.81431948245706e-07 6.48976788757435e-06 -1.20416597442184e-07 1.93489731721676e-05 976 973 0 2 0 971 971 0 2 0 0 0 0 0 0 36 48 0 2921 0 0 0 0 0 1592 +863 865 0.999918208353092 0.0103508971969217 -0.00751235856177839 0.0212134375265091 -0.0104834712987641 0.999786106017354 -0.0178280409519245 -0.00221966327501768 0.00732621549437067 0.0179053383624624 0.999812845198868 0.00782811406902473 3.66287488190444e-05 -3.88179704688505e-05 -1.14816112454284e-07 -3.73964753301201e-06 -6.07451280661752e-06 1.3958645829889e-05 -3.88179704688505e-05 5.72058601770735e-05 -1.05829427599128e-06 2.75877892811433e-05 1.90557827161809e-05 -6.91839546891031e-06 -1.14816112454284e-07 -1.05829427599128e-06 1.13153029144088e-05 -5.45258275359595e-06 -2.24812175572648e-07 -2.49635665241903e-06 -3.73964753301201e-06 2.75877892811433e-05 -5.45258275359595e-06 8.68831613189542e-05 3.02931986203556e-05 1.17999655596061e-05 -6.07451280661752e-06 1.90557827161809e-05 -2.24812175572648e-07 3.02931986203556e-05 4.15275735613169e-05 1.01669863970767e-05 1.3958645829889e-05 -6.91839546891031e-06 -2.49635665241903e-06 1.17999655596061e-05 1.01669863970767e-05 3.29376794868552e-05 890 889 0 22 0 883 891 0 26 0 0 0 0 0 0 0 9 0 2435 0 0 0 0 0 1711 +862 914 0.996170339382735 0.0411363820855089 0.0771521419210217 0.0174979484002 -0.0483660092054733 0.994367453323083 0.0943085198977413 -0.0228709819917335 -0.0728380675719951 -0.0976788914795905 0.992548966082629 0.0496507403224649 3.55855987495897e-05 -4.64523717158387e-05 -7.4948390414155e-07 -2.40355514318735e-05 -9.95944535567035e-06 -8.01027830060413e-06 -4.64523717158387e-05 0.000102797426166729 5.29803376187814e-06 6.54137941640083e-05 2.43315551867208e-05 3.09737720165019e-05 -7.4948390414155e-07 5.29803376187814e-06 1.03416796521186e-05 -1.05928774155839e-06 5.57091293415856e-06 5.72065516048499e-07 -2.40355514318735e-05 6.54137941640083e-05 -1.05928774155839e-06 0.000100686450294532 3.04692225278455e-05 3.68385711329993e-05 -9.95944535567035e-06 2.43315551867208e-05 5.57091293415856e-06 3.04692225278455e-05 3.12867398725079e-05 1.79266974264273e-05 -8.01027830060413e-06 3.09737720165019e-05 5.72065516048499e-07 3.68385711329993e-05 1.79266974264273e-05 4.23921906673422e-05 935 950 0 75 0 933 948 0 79 0 0 0 0 0 0 0 0 0 2760 0 0 0 0 0 1313 +862 915 0.995066058988252 0.0406477493419019 0.0905057938644119 0.0258336244462901 -0.0493420736947526 0.994157839390973 0.0959976569556472 -0.021381849982115 -0.0860749557832655 -0.0999897537296219 0.991258367498605 0.0494626891517502 2.53944634018064e-05 -2.69315920259399e-05 -1.21838056606958e-07 -3.86653043355164e-06 -4.2790664032169e-06 7.49510599088943e-06 -2.69315920259399e-05 7.66896127605779e-05 6.82488546651034e-06 2.44261975521275e-05 1.3811272234798e-05 7.36084652960558e-06 -1.21838056606958e-07 6.82488546651034e-06 9.60099111314685e-06 1.00550252269291e-06 5.37440635431301e-06 -4.05323713275419e-07 -3.86653043355164e-06 2.44261975521275e-05 1.00550252269291e-06 4.82844132334816e-05 1.19885064701047e-05 1.82710430229605e-05 -4.2790664032169e-06 1.3811272234798e-05 5.37440635431301e-06 1.19885064701047e-05 2.49232147277074e-05 7.49200797953096e-06 7.49510599088943e-06 7.36084652960558e-06 -4.05323713275419e-07 1.82710430229605e-05 7.49200797953096e-06 3.28616636236783e-05 877 885 0 68 0 874 884 0 71 0 0 0 0 0 0 0 2 0 2688 0 0 0 0 0 1844 +862 918 0.994709383411219 0.03942370843854 0.0948631317563623 0.0249460533205978 -0.0486128343009972 0.994136103732604 0.0965929583177796 -0.0233710939835283 -0.0904988115662065 -0.10069348771549 0.990793008976544 0.0537025542225225 3.07470077188193e-05 -3.19517157129752e-05 -1.59821589364948e-06 -5.85283723238919e-06 -6.26212348638525e-06 3.58140899362665e-06 -3.19517157129752e-05 7.69890168694984e-05 8.30910038314034e-06 2.21539146332751e-05 7.66240477902738e-06 1.90438459849813e-05 -1.59821589364948e-06 8.30910038314034e-06 1.2292633330894e-05 -1.31083043542314e-06 4.01450002332583e-06 -1.05995608219934e-06 -5.85283723238919e-06 2.21539146332751e-05 -1.31083043542314e-06 4.84420740148916e-05 6.73793811837621e-06 2.34499707929948e-05 -6.26212348638525e-06 7.66240477902738e-06 4.01450002332583e-06 6.73793811837621e-06 2.82198063906575e-05 4.86540281579419e-06 3.58140899362665e-06 1.90438459849813e-05 -1.05995608219934e-06 2.34499707929948e-05 4.86540281579419e-06 4.52649735385978e-05 877 889 0 73 0 873 886 0 75 0 0 0 0 0 0 0 1 0 2376 0 0 0 0 0 1306 +862 917 0.994937661411585 0.0416932640903107 0.091436981765267 0.0371026563907936 -0.050603883203683 0.993957548339989 0.0974045127428253 -0.0142986797057471 -0.0868233661496384 -0.101538484465028 0.991035639754187 0.0484784202553368 4.26315645070684e-05 -4.25909795422183e-05 -3.86740532248874e-06 -1.43294373702583e-05 -1.36761033819607e-05 7.18584412488191e-06 -4.25909795422183e-05 9.75212488389928e-05 1.14061456799186e-05 3.18138079947799e-05 1.27646337126922e-05 1.9776854714245e-05 -3.86740532248874e-06 1.14061456799186e-05 1.19319469266499e-05 -3.10900034278407e-06 6.59393637009057e-07 1.13386111190845e-06 -1.43294373702583e-05 3.18138079947799e-05 -3.10900034278407e-06 7.98090809417218e-05 3.27430015854018e-05 1.82054658685341e-05 -1.36761033819607e-05 1.27646337126922e-05 6.59393637009057e-07 3.27430015854018e-05 4.65358573570544e-05 1.4838725240311e-06 7.18584412488191e-06 1.9776854714245e-05 1.13386111190845e-06 1.82054658685341e-05 1.4838725240311e-06 4.4344463814812e-05 858 869 0 74 0 854 866 0 74 0 0 0 0 0 0 0 1 0 2310 0 0 0 0 0 1858 +862 916 0.995535753253791 0.0412896844682846 0.0848747662731217 0.0261536667307802 -0.0493197606763828 0.994273627115118 0.0948025085647563 -0.0202609466299268 -0.080474376047484 -0.0985652899344179 0.991871341666807 0.0489275475220861 3.85247940729924e-05 -6.54148349129731e-05 -3.2701038290389e-06 -2.1671585745429e-05 -1.05795349904627e-05 -1.0189439902203e-05 -6.54148349129731e-05 0.000190698213054085 1.41099004847675e-05 7.39467403841807e-05 2.76101076551213e-05 6.7080657043679e-05 -3.2701038290389e-06 1.41099004847675e-05 1.10226177855995e-05 1.87824138868032e-06 5.03841965348767e-06 1.46563261342802e-06 -2.1671585745429e-05 7.39467403841807e-05 1.87824138868032e-06 8.28035199903801e-05 2.6060633875794e-05 4.51457297877016e-05 -1.05795349904627e-05 2.76101076551213e-05 5.03841965348767e-06 2.6060633875794e-05 3.57323566729326e-05 1.45583851586395e-05 -1.0189439902203e-05 6.7080657043679e-05 1.46563261342802e-06 4.51457297877016e-05 1.45583851586395e-05 6.83408310836131e-05 836 844 0 72 0 835 843 0 74 0 0 0 0 0 0 0 0 0 2561 0 0 0 0 0 1814 +863 866 0.999902917326963 0.0128235023593822 0.00545102818434662 0.0136358982894544 -0.0127024782344595 0.999684148284927 -0.0216852649175261 -0.00625433704395343 -0.00572738751357941 0.0216139180871754 0.999749986535229 0.0122881936565923 2.21456780682272e-05 -2.77664116014814e-05 6.11602779477277e-06 -8.45412014429326e-06 -3.41309375921663e-06 1.90792300129529e-05 -2.77664116014814e-05 0.000101371272845889 -7.21589996234443e-06 5.63018295545282e-05 2.22903216860229e-05 -2.90538460824022e-05 6.11602779477277e-06 -7.21589996234443e-06 9.78747861476483e-06 -3.79619933564342e-06 1.31015308763964e-06 2.10631167999248e-06 -8.45412014429326e-06 5.63018295545282e-05 -3.79619933564342e-06 8.48350633595335e-05 2.18917921449761e-05 -7.76628878758691e-06 -3.41309375921663e-06 2.22903216860229e-05 1.31015308763964e-06 2.18917921449761e-05 3.11298502739394e-05 -7.94884520415396e-06 1.90792300129529e-05 -2.90538460824022e-05 2.10631167999248e-06 -7.76628878758691e-06 -7.94884520415396e-06 3.34574762496235e-05 871 873 0 27 0 862 871 0 26 0 0 0 0 0 0 1 13 0 2449 0 0 0 0 0 2545 +863 929 0.994812902413688 0.0189879637575046 0.099933710146264 0.01463239417177 -0.0304364498618391 0.992978178897185 0.114315172894231 -0.0220274917900378 -0.0970613811516278 -0.116763836295207 0.988405430389051 0.0285712826391768 3.16439369032862e-05 -2.82325685118788e-05 -6.29096567212144e-06 4.54735114026166e-06 -2.84955989493599e-06 1.12355907865124e-05 -2.82325685118788e-05 4.23610441050164e-05 7.64924215128912e-06 1.17462842340685e-06 3.50827394296662e-06 -4.62282779612848e-06 -6.29096567212144e-06 7.64924215128912e-06 1.12947215713642e-05 -3.6612414775645e-06 3.24713456878792e-06 -6.31249007164464e-06 4.54735114026166e-06 1.17462842340685e-06 -3.6612414775645e-06 4.20950819100616e-05 1.42786835933725e-06 6.3490449876178e-06 -2.84955989493599e-06 3.50827394296662e-06 3.24713456878792e-06 1.42786835933725e-06 2.25447526620289e-05 -6.82294029643847e-07 1.12355907865124e-05 -4.62282779612848e-06 -6.31249007164464e-06 6.3490449876178e-06 -6.82294029643847e-07 2.53427856783692e-05 881 894 0 50 0 881 894 0 53 0 0 0 0 0 0 0 0 0 2822 0 0 0 0 0 2018 +862 904 0.995038779233132 0.0408008259434391 0.0907365440413759 0.0277994711673559 -0.0495049166015123 0.994164543886686 0.0958442638390758 -0.0212841081331187 -0.0862965297941735 -0.0998606643324099 0.991252115591474 0.0491730334686964 4.14904340404084e-05 -4.81487016659493e-05 -1.84965563375502e-06 -2.25074332163948e-05 -1.4346130632711e-05 4.34168133371721e-07 -4.81487016659493e-05 8.77576467240504e-05 5.76065096236889e-06 5.35358792456482e-05 2.92301470886292e-05 2.14478473601267e-05 -1.84965563375502e-06 5.76065096236889e-06 9.51251780719376e-06 9.50662142804371e-07 5.17503360970271e-06 4.42217293540424e-07 -2.25074332163948e-05 5.35358792456482e-05 9.50662142804371e-07 9.13860700342763e-05 3.13370989821384e-05 3.52759698370324e-05 -1.4346130632711e-05 2.92301470886292e-05 5.17503360970271e-06 3.13370989821384e-05 3.67417273769267e-05 1.99825856896875e-05 4.34168133371721e-07 2.14478473601267e-05 4.42217293540424e-07 3.52759698370324e-05 1.99825856896875e-05 4.74563576788508e-05 837 849 0 77 0 832 846 0 76 0 0 0 0 0 0 0 1 0 2645 0 0 0 0 0 1861 +863 900 0.994574361100834 0.0410197857801224 0.0955992542618413 0.0142401796768626 -0.0501594675003805 0.994188766596153 0.0952508487841346 -0.0256460798505261 -0.091136535269592 -0.0995292597610003 0.990852187962706 0.0396872541993848 2.43667125868904e-05 -1.95055041620908e-05 4.45216308139438e-06 -1.05017446837717e-05 -7.00678003581556e-06 1.98949937686431e-06 -1.95055041620908e-05 4.08843625083938e-05 3.16527780054376e-06 1.06149138874619e-05 6.21674651260614e-06 6.52319814381471e-06 4.45216308139438e-06 3.16527780054376e-06 1.17698175300985e-05 -2.5797977492214e-06 2.49011531640722e-06 2.03125530021831e-06 -1.05017446837717e-05 1.06149138874619e-05 -2.5797977492214e-06 4.87609027104919e-05 1.50680829634189e-05 6.81997747938485e-06 -7.00678003581556e-06 6.21674651260614e-06 2.49011531640722e-06 1.50680829634189e-05 3.00892716214176e-05 5.00832880732107e-06 1.98949937686431e-06 6.52319814381471e-06 2.03125530021831e-06 6.81997747938485e-06 5.00832880732107e-06 2.42131163800299e-05 854 866 0 72 0 854 866 0 75 0 0 0 0 0 0 0 0 0 2703 0 0 0 0 0 1686 +863 899 0.994521011371116 0.042075631003701 0.0956953458482333 0.0185665491526269 -0.0512989230916692 0.994052800892056 0.0960596144500589 -0.0210425704222728 -0.0910844576808118 -0.100442373101691 0.99076483145835 0.0391387640062374 3.86460965758698e-05 -4.20586706802523e-05 -2.23140064919108e-06 -5.43816027014048e-06 -8.66911293388756e-06 1.0067072036747e-05 -4.20586706802523e-05 0.000132090875203548 1.2941520606681e-05 2.60275454543816e-05 1.33438687850034e-05 5.38189423810481e-06 -2.23140064919108e-06 1.2941520606681e-05 1.00679954415259e-05 1.21694696121879e-06 5.24924740191487e-06 -2.92394138444172e-08 -5.43816027014048e-06 2.60275454543816e-05 1.21694696121879e-06 3.89793707173941e-05 3.2441270298549e-06 6.55870927991741e-06 -8.66911293388756e-06 1.33438687850034e-05 5.24924740191487e-06 3.2441270298549e-06 2.14878324574276e-05 1.02007295967229e-06 1.0067072036747e-05 5.38189423810481e-06 -2.92394138444172e-08 6.55870927991741e-06 1.02007295967229e-06 2.68788974716062e-05 848 863 0 68 0 848 863 0 70 0 0 0 0 0 0 0 0 0 2807 0 0 0 0 0 1927 +863 867 0.999137623501131 0.0296468306955592 0.0290701691467417 0.0357505287079171 -0.0287268928134573 0.999088690926272 -0.0315682323311301 -0.00112457087661158 -0.0299795752771026 0.0307059129963094 0.999078761646582 0.0129712505919761 2.67854134062798e-05 -3.44855188528667e-05 3.96260448623317e-06 -1.53169839637851e-05 -9.34381107244511e-06 5.56833933786008e-06 -3.44855188528667e-05 6.64814749833188e-05 -4.80357422843148e-06 4.53921535791365e-05 2.1772832946805e-05 -2.55462273935812e-06 3.96260448623317e-06 -4.80357422843148e-06 8.83318956111002e-06 -3.36490928235871e-06 -1.39488190387146e-06 -1.00508251967019e-07 -1.53169839637851e-05 4.53921535791365e-05 -3.36490928235871e-06 9.04597626931441e-05 2.7745839535438e-05 7.67197424068995e-06 -9.34381107244511e-06 2.1772832946805e-05 -1.39488190387146e-06 2.7745839535438e-05 3.93760224797952e-05 1.00607080243756e-06 5.56833933786008e-06 -2.55462273935812e-06 -1.00508251967019e-07 7.67197424068995e-06 1.00607080243756e-06 2.1408853525243e-05 801 807 0 41 0 800 807 0 40 0 0 0 0 0 0 0 3 0 2288 0 0 0 0 0 2440 +863 897 0.994447207680785 0.0407860597125484 0.09701158935413 0.0131716114763399 -0.0501812705016177 0.994070406540491 0.0964669214356264 -0.0237514760948517 -0.09250184445044 -0.100799425462392 0.990597236317424 0.038501551738416 2.84635931546427e-05 -2.95076587983519e-05 2.66044958801278e-06 -3.82022532842931e-06 -4.89538586557275e-06 3.1267706487525e-06 -2.95076587983519e-05 5.500311338292e-05 1.78130709820676e-06 1.31129642666572e-05 7.81331605821699e-06 9.74137160538879e-06 2.66044958801278e-06 1.78130709820676e-06 1.10564743134204e-05 -3.22237199854625e-06 5.20609831381159e-06 1.49499356471378e-06 -3.82022532842931e-06 1.31129642666572e-05 -3.22237199854625e-06 4.20667229193437e-05 1.92400123649849e-06 1.07686960774723e-05 -4.89538586557275e-06 7.81331605821699e-06 5.20609831381159e-06 1.92400123649849e-06 2.54101255552122e-05 6.08099726784675e-06 3.1267706487525e-06 9.74137160538879e-06 1.49499356471378e-06 1.07686960774723e-05 6.08099726784675e-06 2.89043751185165e-05 838 848 0 65 0 838 848 0 64 0 0 0 0 0 0 0 0 0 2670 0 0 0 0 0 1684 +863 898 0.994640689094747 0.0425834375339135 0.0942154469549566 0.0178129470007104 -0.051621328324299 0.994073676554484 0.0956700791443541 -0.0204372097060781 -0.0895831349036294 -0.100020879966372 0.990944340269216 0.0364537388287628 3.46920276755647e-05 -3.70131671680964e-05 -3.61779240520625e-06 -3.48756763205175e-06 -3.77036461157042e-06 1.62890932717611e-06 -3.70131671680964e-05 7.20756521206629e-05 7.38588055195589e-06 2.24818758680015e-05 1.2162238109954e-05 1.60668489043439e-05 -3.61779240520625e-06 7.38588055195589e-06 1.02662082636241e-05 1.02266944166464e-06 4.55468314074034e-06 -4.40825461708475e-07 -3.48756763205175e-06 2.24818758680015e-05 1.02266944166464e-06 4.64873685001189e-05 8.83232660790887e-06 1.45355806228505e-05 -3.77036461157042e-06 1.2162238109954e-05 4.55468314074034e-06 8.83232660790887e-06 2.20244789870957e-05 8.80811993167431e-06 1.62890932717611e-06 1.60668489043439e-05 -4.40825461708475e-07 1.45355806228505e-05 8.80811993167431e-06 3.29976158440444e-05 807 819 0 68 0 807 819 0 70 0 0 0 0 0 0 0 0 0 2761 0 0 0 0 0 1969 +863 890 0.9951731683779 0.0431227367572379 0.0881521101009997 0.0252376933252141 -0.0496125805655719 0.996111328791772 0.0728066789677582 -0.0131320521986344 -0.0846696922772101 -0.0768287070518275 0.993442697382404 0.0357061686965467 1.8808074481778e-05 -2.24835568647529e-05 3.05705427563643e-06 -9.46439110147683e-07 -9.22436158811721e-07 4.77975639023908e-06 -2.24835568647529e-05 6.48121008371419e-05 3.40365257308383e-06 1.36036032572064e-05 7.50287349265988e-06 -2.75866095133056e-07 3.05705427563643e-06 3.40365257308383e-06 9.30526094932896e-06 6.60749115667062e-07 5.02821893420713e-06 -1.33823678787206e-06 -9.46439110147683e-07 1.36036032572064e-05 6.60749115667062e-07 4.23501299710284e-05 5.26591129825532e-06 3.2941861386307e-06 -9.22436158811721e-07 7.50287349265988e-06 5.02821893420713e-06 5.26591129825532e-06 2.15267356487654e-05 1.17212576842957e-06 4.77975639023908e-06 -2.75866095133056e-07 -1.33823678787206e-06 3.2941861386307e-06 1.17212576842957e-06 2.4561679557631e-05 790 802 0 63 0 790 802 0 63 0 0 0 0 0 0 0 0 0 2571 0 0 0 0 0 2028 +863 892 0.994364395195628 0.0417692410883838 0.0974411620729859 0.0216035786689061 -0.0511393347333224 0.994092213692547 0.0957362999017846 -0.0202175182676005 -0.0928666679184014 -0.10017984415416 0.990625954038648 0.0383516211072163 3.30715229489016e-05 -3.14998874458482e-05 -6.39565795262819e-07 -6.24811617192264e-06 -5.16007319318577e-06 1.08423445356146e-05 -3.14998874458482e-05 4.5240889558632e-05 2.84056895874053e-06 1.15863974525333e-05 6.60782407079858e-06 -3.16936358567021e-06 -6.39565795262819e-07 2.84056895874053e-06 9.56030916587946e-06 8.60987489046398e-07 4.96923684410893e-06 2.16318501515485e-06 -6.24811617192264e-06 1.15863974525333e-05 8.60987489046398e-07 3.56817136102666e-05 4.80337486605385e-06 4.41250197161505e-06 -5.16007319318577e-06 6.60782407079858e-06 4.96923684410893e-06 4.80337486605385e-06 2.01896807180318e-05 3.57252026961859e-06 1.08423445356146e-05 -3.16936358567021e-06 2.16318501515485e-06 4.41250197161505e-06 3.57252026961859e-06 2.83485310363872e-05 833 846 0 67 0 833 846 0 70 0 0 0 0 0 0 0 0 0 2783 0 0 0 0 0 1953 +863 889 0.996321187797828 0.0451470726543912 0.0728411461734729 0.0304709342943149 -0.0489129980667525 0.99751174437715 0.0507724181990273 -0.0110532029190295 -0.0703676727286613 -0.054148514849386 0.996050364677589 0.0352223043547201 2.91908439531885e-05 -2.91201137046591e-05 3.99307181078965e-06 -1.09867270254288e-05 -7.35162064713503e-06 5.67327216750099e-06 -2.91201137046591e-05 4.24606573918689e-05 -1.68610857337476e-06 2.22601607982068e-05 1.26734477750262e-05 6.50210494919901e-07 3.99307181078965e-06 -1.68610857337476e-06 9.37062392827765e-06 -3.28601628737512e-07 4.24484477545485e-06 1.40004191841736e-06 -1.09867270254288e-05 2.22601607982068e-05 -3.28601628737512e-07 5.15393574181333e-05 8.65322512584697e-06 6.97522093483117e-06 -7.35162064713503e-06 1.26734477750262e-05 4.24484477545485e-06 8.65322512584697e-06 2.61885244839473e-05 4.89111021060723e-06 5.67327216750099e-06 6.50210494919901e-07 1.40004191841736e-06 6.97522093483117e-06 4.89111021060723e-06 2.40244248208084e-05 811 823 0 66 0 811 823 0 65 0 0 0 0 0 0 0 0 0 2538 0 0 0 0 0 2038 +863 891 0.994915621266521 0.0422311799068728 0.0914299404108214 0.016650377910903 -0.0506106203765083 0.994530961072161 0.0913604541034527 -0.0238722873461351 -0.087071646733928 -0.0955232689587069 0.991611735218218 0.037223223206711 3.33666339718001e-05 -4.4738927839537e-05 -3.87397613219923e-06 -4.2661875941241e-06 -5.69842660555275e-06 5.13020380510677e-06 -4.4738927839537e-05 0.00013764045828463 1.031571360736e-05 5.5882776858395e-05 2.43580877215244e-05 1.90482009772146e-05 -3.87397613219923e-06 1.031571360736e-05 9.85576344568601e-06 1.41309282769864e-06 4.95714255535787e-06 -1.48853868224516e-06 -4.2661875941241e-06 5.5882776858395e-05 1.41309282769864e-06 6.70703866177497e-05 1.04523551760429e-05 2.11001990225439e-05 -5.69842660555275e-06 2.43580877215244e-05 4.95714255535787e-06 1.04523551760429e-05 2.20752491372231e-05 7.25159799730755e-06 5.13020380510677e-06 1.90482009772146e-05 -1.48853868224516e-06 2.11001990225439e-05 7.25159799730755e-06 2.87352357851668e-05 808 821 0 73 0 808 821 0 77 0 0 0 0 0 0 0 0 0 2698 0 0 0 0 0 1934 +863 895 0.994380784535536 0.0416076931530602 0.0973429772349949 0.0168896595087164 -0.0509334655546938 0.994138123361755 0.095368620443814 -0.0222632654021869 -0.092804296414987 -0.0997907387949814 0.990671071051169 0.0365635134742256 2.10855396318079e-05 -2.23026244171551e-05 2.8688234793164e-06 -2.39129005426571e-06 -1.97553834609797e-06 1.72765335881464e-06 -2.23026244171551e-05 5.03651911065422e-05 -2.31705539788358e-07 1.41172346934999e-05 6.44341647220895e-06 6.64794233819456e-06 2.8688234793164e-06 -2.31705539788358e-07 8.28254807419739e-06 1.33657509911052e-06 4.07310689161551e-06 1.31881772783121e-06 -2.39129005426571e-06 1.41172346934999e-05 1.33657509911052e-06 4.16228181414392e-05 5.16997830279384e-06 5.06676360693322e-06 -1.97553834609797e-06 6.44341647220895e-06 4.07310689161551e-06 5.16997830279384e-06 2.12371014388704e-05 3.88537162369245e-06 1.72765335881464e-06 6.64794233819456e-06 1.31881772783121e-06 5.06676360693322e-06 3.88537162369245e-06 2.22352871506271e-05 812 825 0 68 0 812 825 0 69 0 0 0 0 0 0 0 0 0 2727 0 0 0 0 0 1973 +863 896 0.99450848830559 0.0419362733856119 0.095886472782442 0.0195385197423217 -0.0510085123987847 0.994244727202359 0.0942101591823826 -0.0231893727089592 -0.0913837969828011 -0.0985838293272992 0.99092392757677 0.0379021606656283 3.2461402513285e-05 -4.21651814502555e-05 -1.3955453070714e-06 -1.03507870235846e-05 -1.02198881002303e-05 2.34202221712952e-06 -4.21651814502555e-05 0.000101218507139025 6.3086802244887e-06 4.37137645985827e-05 2.45068624102155e-05 1.49824920084687e-05 -1.3955453070714e-06 6.3086802244887e-06 9.69450043036689e-06 2.30588354839321e-06 5.09720393349106e-06 9.2032695426697e-08 -1.03507870235846e-05 4.37137645985827e-05 2.30588354839321e-06 6.19254725974606e-05 1.48007841772647e-05 1.69642213291049e-05 -1.02198881002303e-05 2.45068624102155e-05 5.09720393349106e-06 1.48007841772647e-05 2.92019128130996e-05 9.55915066431036e-06 2.34202221712952e-06 1.49824920084687e-05 9.2032695426697e-08 1.69642213291049e-05 9.55915066431036e-06 3.15806169602784e-05 819 828 0 68 0 819 828 0 73 0 0 0 0 0 0 0 0 0 2674 0 0 0 0 0 1912 +863 901 0.994707394333057 0.0423610518419585 0.0936095131168961 0.0183462783263773 -0.051339936848352 0.9940861404218 0.0956919866326161 -0.0223982191520166 -0.0890023063945348 -0.0999914331737097 0.99099964820797 0.0400885695058229 3.17336955781159e-05 -3.53448060107028e-05 -1.25393975095838e-06 -6.82660209410801e-06 -6.40324471922384e-06 6.08869872952067e-06 -3.53448060107028e-05 7.26272266565935e-05 4.12311765926893e-06 2.79587622469018e-05 1.42941219926947e-05 8.01319694322937e-07 -1.25393975095838e-06 4.12311765926893e-06 9.41808384175551e-06 -8.97955020925347e-07 4.3608883929555e-06 -6.65696315880913e-07 -6.82660209410801e-06 2.79587622469018e-05 -8.97955020925347e-07 5.3107581419579e-05 7.64362433122496e-06 1.04674272297485e-05 -6.40324471922384e-06 1.42941219926947e-05 4.3608883929555e-06 7.64362433122496e-06 2.68481102734306e-05 4.3825156266714e-06 6.08869872952067e-06 8.01319694322937e-07 -6.65696315880913e-07 1.04674272297485e-05 4.3825156266714e-06 2.82771472103959e-05 813 821 0 70 0 812 820 0 72 0 0 0 0 0 0 0 0 0 2689 0 0 0 0 0 1935 +863 894 0.994520447201711 0.0418591300287025 0.0957961029006303 0.0176019453882938 -0.0509591794710967 0.994209350189919 0.0946093548364595 -0.0242227910984993 -0.0912811159295313 -0.0989726286817659 0.990894634482638 0.0396085941515445 2.07374469746784e-05 -1.73391455365114e-05 4.12426204846672e-06 -4.06077982272599e-06 -1.75689191343327e-06 3.66198801267404e-06 -1.73391455365114e-05 3.54532861932686e-05 -1.56545735313088e-06 1.04672064953164e-05 4.0633491200806e-06 1.92085333119522e-06 4.12426204846672e-06 -1.56545735313088e-06 8.42685889449349e-06 -2.23799273830116e-09 2.78008032771194e-06 1.38051694588253e-06 -4.06077982272599e-06 1.04672064953164e-05 -2.23799273830116e-09 4.16793623557361e-05 5.48999003746001e-06 1.92921014213953e-06 -1.75689191343327e-06 4.0633491200806e-06 2.78008032771194e-06 5.48999003746001e-06 2.48639270519216e-05 4.3630586075596e-06 3.66198801267404e-06 1.92085333119522e-06 1.38051694588253e-06 1.92921014213953e-06 4.3630586075596e-06 2.15824862294441e-05 831 841 0 66 0 831 841 0 67 0 0 0 0 0 0 0 0 0 2676 0 0 0 0 0 1945 +863 924 0.994498835331849 0.0421558499418959 0.0958903062841763 0.0207357134347306 -0.0512015198288389 0.99426239821494 0.0939185171470088 -0.023635863116571 -0.0913809109760556 -0.0983115853373971 0.99095124062571 0.0378593838215956 2.33698885265337e-05 -2.45864857377744e-05 1.36697062421502e-06 -9.84696995656104e-06 -5.64370294602436e-06 3.08527419924179e-06 -2.45864857377744e-05 6.62138615754311e-05 2.0251378590471e-06 3.20979851611086e-05 1.58496518714137e-05 1.08900078266153e-05 1.36697062421502e-06 2.0251378590471e-06 9.60747330662234e-06 -1.42941315349111e-06 3.36789196829619e-06 8.46503931011775e-07 -9.84696995656104e-06 3.20979851611086e-05 -1.42941315349111e-06 6.14469361113444e-05 1.26303768694938e-05 9.41342841360157e-06 -5.64370294602436e-06 1.58496518714137e-05 3.36789196829619e-06 1.26303768694938e-05 2.73948613123253e-05 7.96412243943717e-06 3.08527419924179e-06 1.08900078266153e-05 8.46503931011775e-07 9.41342841360157e-06 7.96412243943717e-06 2.90692563994588e-05 818 824 0 63 0 818 824 0 68 0 0 0 0 0 0 0 0 0 2681 0 0 0 0 0 1746 +863 923 0.994110604540451 0.041283275429894 0.10019878796671 0.0209505106055645 -0.0509178951787626 0.99411807433772 0.0955856800238854 -0.0215236324197855 -0.0956633361888595 -0.100124649536683 0.990365377355435 0.0394196651826576 2.99164272212499e-05 -2.67537861041286e-05 3.34016453144979e-06 -1.04241373028464e-05 -5.44669142530463e-06 5.21504054805299e-06 -2.67537861041286e-05 4.42844000526365e-05 -2.1528802789292e-07 2.25944646373062e-05 1.09606344586339e-05 1.06198671580553e-06 3.34016453144979e-06 -2.1528802789292e-07 1.01304179344119e-05 1.4136043406776e-07 4.23263366675918e-06 1.39145837023119e-06 -1.04241373028464e-05 2.25944646373062e-05 1.4136043406776e-07 5.28958580860016e-05 1.15087941989116e-05 7.41991443720008e-06 -5.44669142530463e-06 1.09606344586339e-05 4.23263366675918e-06 1.15087941989116e-05 2.81608062866636e-05 5.26251262828532e-06 5.21504054805299e-06 1.06198671580553e-06 1.39145837023119e-06 7.41991443720008e-06 5.26251262828532e-06 2.35415180391384e-05 854 868 0 65 0 854 868 0 71 0 0 0 0 0 0 0 0 0 2617 0 0 0 0 0 1934 +863 893 0.994239329635136 0.0417823962526459 0.098703529673783 0.0194291552334254 -0.0511523740067693 0.994220108083145 0.0943917968713972 -0.0229230529799761 -0.0941891184805764 -0.0988969567101354 0.990630002530372 0.0379195550947648 3.76584358791502e-05 -5.34236943670507e-05 -2.44305921235611e-06 -2.04935505585505e-05 -1.09820189333679e-05 -1.40709170673112e-07 -5.34236943670507e-05 0.000156512896614323 1.06769241268436e-05 8.38517701144595e-05 3.34367275799817e-05 2.84642664939472e-05 -2.44305921235611e-06 1.06769241268436e-05 1.06495998387142e-05 2.2196533267282e-06 4.65937530997453e-06 -9.00263230678535e-07 -2.04935505585505e-05 8.38517701144595e-05 2.2196533267282e-06 0.000104337362029715 2.19289549872721e-05 2.7781404854243e-05 -1.09820189333679e-05 3.34367275799817e-05 4.65937530997453e-06 2.19289549872721e-05 2.89200624227374e-05 1.01295893695961e-05 -1.40709170673112e-07 2.84642664939472e-05 -9.00263230678535e-07 2.7781404854243e-05 1.01295893695961e-05 3.46224974201421e-05 814 825 0 68 0 814 825 0 70 0 0 0 0 0 0 0 0 0 2660 0 0 0 0 0 1771 +863 925 0.994340922150934 0.0415781519243494 0.0977618934891607 0.0179458955470299 -0.0508920836854799 0.994195156676327 0.0947944421339325 -0.0223093864162663 -0.093253023297802 -0.0992332994709391 0.990684927674753 0.037556509986837 3.23804344673668e-05 -2.91438938048127e-05 6.38601136957969e-06 -1.84035376923345e-05 -1.07005715881605e-05 1.08530160413305e-05 -2.91438938048127e-05 4.44669168857962e-05 -2.1670330938061e-06 2.80235328432171e-05 1.60177604574875e-05 -1.53533015496917e-06 6.38601136957969e-06 -2.1670330938061e-06 1.06290755294164e-05 -2.62424026470608e-07 4.03657608273581e-06 4.17146642046058e-06 -1.84035376923345e-05 2.80235328432171e-05 -2.62424026470608e-07 6.4609457307396e-05 2.40537504478652e-05 5.09933089366168e-06 -1.07005715881605e-05 1.60177604574875e-05 4.03657608273581e-06 2.40537504478652e-05 3.30020213326875e-05 4.56190291587639e-06 1.08530160413305e-05 -1.53533015496917e-06 4.17146642046058e-06 5.09933089366168e-06 4.56190291587639e-06 2.99153454000889e-05 850 864 0 63 0 850 864 0 68 0 0 0 0 0 0 0 0 0 2644 0 0 0 0 0 1992 +863 902 0.994807287025507 0.0425100526109559 0.0924735481527756 0.0195624654102069 -0.0514739709077576 0.993970335277395 0.0968163359538611 -0.0197259097091623 -0.087800296126706 -0.101073577237364 0.990997093832522 0.0387934085705786 2.62060003439054e-05 -2.83467669424314e-05 -2.05157725075363e-06 -1.22488278181192e-06 -1.34062436066407e-07 4.27011059579495e-06 -2.83467669424314e-05 7.36105018191001e-05 7.54448516674686e-06 8.4366648157907e-06 2.59248180659024e-06 3.75429537337446e-06 -2.05157725075363e-06 7.54448516674686e-06 9.97463972376962e-06 -9.3919608365764e-07 3.73001786319799e-06 -3.50669022548611e-07 -1.22488278181192e-06 8.4366648157907e-06 -9.3919608365764e-07 4.09064471737043e-05 6.49729659995715e-06 8.61544586754061e-06 -1.34062436066407e-07 2.59248180659024e-06 3.73001786319799e-06 6.49729659995715e-06 2.32102347186122e-05 4.45856497713219e-06 4.27011059579495e-06 3.75429537337446e-06 -3.50669022548611e-07 8.61544586754061e-06 4.45856497713219e-06 2.3368823743819e-05 823 836 0 68 0 823 836 0 73 0 0 0 0 0 0 0 0 0 2764 0 0 0 0 0 1925 +863 922 0.994404350511582 0.0417639446067827 0.0970348422708066 0.0209095190712327 -0.0510963756396014 0.994090904701991 0.0957728227905733 -0.0216197393742394 -0.0924616032747403 -0.10019504039452 0.990662306641474 0.0387471197306339 2.8578305265393e-05 -2.64173533357849e-05 2.46487884692879e-06 -6.73059866510853e-06 -4.62161412327416e-06 7.92526053469595e-06 -2.64173533357849e-05 4.15727629286556e-05 1.38590910768708e-06 1.24624855888409e-05 7.67130448106116e-06 -1.16122790403239e-06 2.46487884692879e-06 1.38590910768708e-06 1.04121645268493e-05 -2.46097635787133e-06 3.63244956556556e-06 1.47197193361449e-06 -6.73059866510853e-06 1.24624855888409e-05 -2.46097635787133e-06 4.91939470407614e-05 1.04888990714384e-05 3.24837780143338e-06 -4.62161412327416e-06 7.67130448106116e-06 3.63244956556556e-06 1.04888990714384e-05 2.91251625536207e-05 6.34566153561112e-06 7.92526053469595e-06 -1.16122790403239e-06 1.47197193361449e-06 3.24837780143338e-06 6.34566153561112e-06 2.26091332731951e-05 825 832 0 69 0 825 832 0 71 0 0 0 0 0 0 0 0 0 2738 0 0 0 0 0 1899 +863 921 0.994715869869177 0.0420610108332355 0.0936547361220653 0.0189995537294145 -0.0509402560162028 0.994217772373334 0.0945310076853637 -0.0240546590494944 -0.0891371333811614 -0.0988022897745443 0.991106794945881 0.0358136099898312 1.81550431201169e-05 -1.55919554888587e-05 5.15740128011944e-06 -3.52419526004313e-06 9.93235296608432e-07 4.11838854974879e-06 -1.55919554888587e-05 3.76321015068124e-05 -2.47062265561997e-06 1.34487887427002e-05 3.49030945935309e-06 2.71038552614345e-06 5.15740128011944e-06 -2.47062265561997e-06 8.47333057907055e-06 1.75104715519126e-06 3.47564404096068e-06 1.24168996121416e-06 -3.52419526004313e-06 1.34487887427002e-05 1.75104715519126e-06 3.77316899782363e-05 4.92018301494807e-06 3.78428491364976e-06 9.93235296608432e-07 3.49030945935309e-06 3.47564404096068e-06 4.92018301494807e-06 2.24047770458834e-05 7.24681853288934e-06 4.11838854974879e-06 2.71038552614345e-06 1.24168996121416e-06 3.78428491364976e-06 7.24681853288934e-06 2.20112763371871e-05 817 824 0 71 0 817 824 0 75 0 0 0 0 0 0 0 0 0 2661 0 0 0 0 0 1917 +863 926 0.995316725830501 0.0430190435947983 0.0865677605707861 0.0148127999509834 -0.0511021046214161 0.994313154277292 0.0934340737333218 -0.0242170572924911 -0.0820560185806864 -0.0974202911067854 0.991854876831966 0.035286970453015 3.27724339500552e-05 -3.67870088775516e-05 -2.06970170556031e-06 -1.12268849587132e-05 -9.95915515965204e-06 4.6668286627081e-06 -3.67870088775516e-05 9.37867417506525e-05 7.73712953382289e-06 4.62734139695366e-05 2.20357220119285e-05 1.74748557649022e-05 -2.06970170556031e-06 7.73712953382289e-06 9.64387173801708e-06 1.19549449651009e-06 5.2330963674077e-06 7.19912585969419e-07 -1.12268849587132e-05 4.62734139695366e-05 1.19549449651009e-06 6.60365587072117e-05 1.32496800809877e-05 2.20528947289925e-05 -9.95915515965204e-06 2.20357220119285e-05 5.2330963674077e-06 1.32496800809877e-05 2.73504300127812e-05 1.00553134565197e-05 4.6668286627081e-06 1.74748557649022e-05 7.19912585969419e-07 2.20528947289925e-05 1.00553134565197e-05 3.88904566180932e-05 835 850 0 72 0 833 848 0 75 0 0 0 0 0 0 0 0 0 2723 0 0 0 0 0 1711 +863 916 0.994792893462525 0.0427182932934032 0.0925324080231146 0.0214316840905771 -0.0515234599778347 0.994146794664188 0.094960432448644 -0.0206030741161634 -0.0879342492341286 -0.0992335531814708 0.991171160665306 0.0389558536498874 1.88875249044484e-05 -1.87471293492111e-05 9.56252420468318e-07 -2.62367996025692e-06 -2.66887260811174e-06 4.86122597029521e-06 -1.87471293492111e-05 5.99536864556862e-05 4.05134732649376e-06 1.37404524878862e-05 3.39287044844472e-06 8.20930383615376e-06 9.56252420468318e-07 4.05134732649376e-06 9.28395426048829e-06 -1.27660302872919e-06 2.35881289892559e-06 -7.2667888866261e-08 -2.62367996025692e-06 1.37404524878862e-05 -1.27660302872919e-06 4.72540010512566e-05 7.59560139732882e-06 4.56575622246613e-06 -2.66887260811174e-06 3.39287044844472e-06 2.35881289892559e-06 7.59560139732882e-06 2.47851705279468e-05 6.48503924446286e-07 4.86122597029521e-06 8.20930383615376e-06 -7.2667888866261e-08 4.56575622246613e-06 6.48503924446286e-07 2.42019359522928e-05 840 852 0 72 0 840 852 0 74 0 0 0 0 0 0 0 0 0 2587 0 0 0 0 0 1935 +863 927 0.995166268916796 0.0429491907608594 0.0883145753724193 0.0157980780521058 -0.0512775045772737 0.994221774175895 0.0943063162193478 -0.021752130801132 -0.0837538938470988 -0.0983790158901951 0.991618300808293 0.0357900225930074 3.60698526668607e-05 -4.29318927311823e-05 -6.67898607966476e-06 -5.59604027836401e-06 -8.28116476545416e-06 1.52507043881875e-06 -4.29318927311823e-05 0.000107814893537948 1.21968025634555e-05 4.44257294860096e-05 2.57390952459302e-05 2.0941431558737e-05 -6.67898607966476e-06 1.21968025634555e-05 1.06583342108471e-05 -5.17788865525245e-07 4.68380211121327e-06 -1.5752349832072e-06 -5.59604027836401e-06 4.44257294860096e-05 -5.17788865525245e-07 7.53145794597843e-05 2.14918210258591e-05 2.02654050679161e-05 -8.28116476545416e-06 2.57390952459302e-05 4.68380211121327e-06 2.14918210258591e-05 2.99602625520269e-05 1.10418576816744e-05 1.52507043881875e-06 2.0941431558737e-05 -1.5752349832072e-06 2.02654050679161e-05 1.10418576816744e-05 3.4092391077596e-05 819 836 0 73 0 819 836 0 69 0 0 0 0 0 0 0 0 0 2754 0 0 0 0 0 1715 +863 917 0.995046204540616 0.043900118719096 0.0891954618002741 0.0264724469907917 -0.0524493115246667 0.994009806570451 0.0958831276208855 -0.016038365276312 -0.0844518830453374 -0.100086382781195 0.991388216306747 0.0341795810399472 3.3679136573503e-05 -4.09091295978545e-05 7.34746973358697e-07 -1.68596385267705e-05 -1.28910350320287e-05 6.18564841499092e-06 -4.09091295978545e-05 0.000113666564326616 6.23637903024608e-06 3.92635660369909e-05 1.19279086702548e-05 1.91943745734983e-05 7.34746973358697e-07 6.23637903024608e-06 1.14246254120644e-05 -7.29058824106402e-06 -2.22912296505198e-06 1.34510972514754e-06 -1.68596385267705e-05 3.92635660369909e-05 -7.29058824106402e-06 0.000124139196252823 5.36391719907789e-05 1.48257791643551e-05 -1.28910350320287e-05 1.19279086702548e-05 -2.22912296505198e-06 5.36391719907789e-05 6.0030519934384e-05 3.71840373899395e-06 6.18564841499092e-06 1.91943745734983e-05 1.34510972514754e-06 1.48257791643551e-05 3.71840373899395e-06 3.97021130403242e-05 791 803 0 73 0 791 803 0 75 0 0 0 0 0 0 0 0 0 2366 0 0 0 0 0 1736 +863 903 0.994201104587757 0.0422387188021502 0.0988941569074542 0.0220946578299252 -0.0516942731451611 0.99412547296387 0.09509072577468 -0.022411414071089 -0.094296690082297 -0.0996515661608727 0.990544143186566 0.0374852310194879 2.68899922863543e-05 -2.29448225760469e-05 -2.53396452609716e-07 -3.07253057573426e-06 -3.45302746224789e-06 5.35711430733828e-06 -2.29448225760469e-05 4.09982124806407e-05 3.4132903061279e-06 1.26576642692279e-05 5.62170432618666e-06 2.7327390075547e-06 -2.53396452609716e-07 3.4132903061279e-06 9.59841820803487e-06 -1.30071395713945e-06 4.27143402157816e-06 7.33378413045602e-07 -3.07253057573426e-06 1.26576642692279e-05 -1.30071395713945e-06 3.95595082572886e-05 -8.64728735165798e-07 3.22822120080557e-06 -3.45302746224789e-06 5.62170432618666e-06 4.27143402157816e-06 -8.64728735165798e-07 2.30609195571896e-05 7.58102049623662e-06 5.35711430733828e-06 2.7327390075547e-06 7.33378413045602e-07 3.22822120080557e-06 7.58102049623662e-06 2.67947417945098e-05 819 830 0 70 0 819 830 0 68 0 0 0 0 0 0 0 0 0 2686 0 0 0 0 0 1792 +863 919 0.994681981576474 0.0420286603414979 0.094028438448154 0.0178241490487339 -0.05097213052197 0.994187699542961 0.0948296366518737 -0.0225347743862371 -0.0894963543232379 -0.0991181607344191 0.991042881400939 0.0406840048872387 2.79087480824015e-05 -2.52237133986765e-05 -4.92290243487773e-07 -4.46511001412107e-06 -4.7263476315549e-06 3.0331975045303e-06 -2.52237133986765e-05 6.29928632252872e-05 3.00038839337422e-06 2.61571395978687e-05 9.05821119945305e-06 1.46897224756758e-05 -4.92290243487773e-07 3.00038839337422e-06 8.96033947999129e-06 4.44352606697854e-07 3.12520191521424e-06 1.74652440317768e-07 -4.46511001412107e-06 2.61571395978687e-05 4.44352606697854e-07 4.57420617552878e-05 1.27034821478806e-06 1.05844497535971e-05 -4.7263476315549e-06 9.05821119945305e-06 3.12520191521424e-06 1.27034821478806e-06 2.34244584612184e-05 3.85581759711561e-06 3.0331975045303e-06 1.46897224756758e-05 1.74652440317768e-07 1.05844497535971e-05 3.85581759711561e-06 2.9033317002035e-05 825 837 0 67 0 825 837 0 71 0 0 0 0 0 0 0 0 0 2524 0 0 0 0 0 1946 +863 913 0.994112417313357 0.0412676500120604 0.100187238737655 0.0183883896744001 -0.0507984462282072 0.994225783586897 0.094523061269837 -0.0228768765513837 -0.0957079913288003 -0.0990559049905836 0.990468529576939 0.0379852512081895 1.50346704601915e-05 -9.17578834792368e-06 3.31712499474651e-06 -6.51692235082722e-07 6.06096470994537e-08 1.53329474818544e-06 -9.17578834792368e-06 2.90125434267393e-05 1.28142255069309e-06 -4.55303439538847e-07 1.54814988112017e-06 -9.73610594357953e-07 3.31712499474651e-06 1.28142255069309e-06 9.18773722490691e-06 -1.12150105394344e-06 3.98489941794799e-06 -7.34412446598914e-07 -6.51692235082722e-07 -4.55303439538847e-07 -1.12150105394344e-06 2.73682847407335e-05 -3.11159922424298e-06 2.9265207344758e-06 6.06096470994537e-08 1.54814988112017e-06 3.98489941794799e-06 -3.11159922424298e-06 2.10204350747976e-05 4.72451769838678e-06 1.53329474818544e-06 -9.73610594357953e-07 -7.34412446598914e-07 2.9265207344758e-06 4.72451769838678e-06 2.14514560158911e-05 859 868 0 72 0 859 868 0 71 0 0 0 0 0 0 0 0 0 2632 0 0 0 0 0 1798 +863 928 0.995052875615129 0.0424846468201347 0.0898043958536063 0.0190353617894124 -0.0510623352306914 0.994120454119514 0.0954838238760825 -0.0217421229757789 -0.0852197902535044 -0.099597075688891 0.991371781857528 0.0395461007010057 3.01124697316657e-05 -3.19780132321838e-05 -9.49210560760319e-07 4.50919628520751e-07 -2.9655164657368e-06 7.46454741611021e-06 -3.19780132321838e-05 7.77795848553128e-05 3.6620026641818e-06 2.26691344827728e-05 7.98797841134744e-06 2.84748129667821e-06 -9.49210560760319e-07 3.6620026641818e-06 9.58420443484326e-06 -7.26579099477364e-07 3.86157544028301e-06 -7.12503478596273e-07 4.50919628520751e-07 2.26691344827728e-05 -7.26579099477364e-07 4.54731041433584e-05 -5.11481233961496e-08 9.6206921680171e-06 -2.9655164657368e-06 7.98797841134744e-06 3.86157544028301e-06 -5.11481233961496e-08 2.09658256034316e-05 4.5925914103898e-06 7.46454741611021e-06 2.84748129667821e-06 -7.12503478596273e-07 9.6206921680171e-06 4.5925914103898e-06 2.4529446800781e-05 807 819 0 77 0 807 819 0 77 0 0 0 0 0 0 0 0 0 2680 0 0 0 0 0 1948 +863 918 0.994917687542193 0.0420790206526932 0.0914775985507156 0.0158690285031256 -0.050818780075172 0.994139816869674 0.095412138148148 -0.0254007700669382 -0.0869266737392325 -0.0995760038123654 0.991225692189923 0.0390123424784733 3.84413396794114e-05 -3.92225106135957e-05 -3.44896020413842e-06 -4.11056208732527e-06 -2.32958306022521e-06 5.1861904130183e-06 -3.92225106135957e-05 8.6378963031949e-05 6.84914334990149e-06 2.49939380223175e-05 8.33569526088311e-06 1.78911032934512e-05 -3.44896020413842e-06 6.84914334990149e-06 9.30984091419371e-06 2.50596414940402e-07 2.91155747173169e-06 -1.69425193440644e-06 -4.11056208732527e-06 2.49939380223175e-05 2.50596414940402e-07 4.14543750088274e-05 3.1797734860348e-06 1.56516048636705e-05 -2.32958306022521e-06 8.33569526088311e-06 2.91155747173169e-06 3.1797734860348e-06 2.38795474666792e-05 6.37996465610006e-06 5.1861904130183e-06 1.78911032934512e-05 -1.69425193440644e-06 1.56516048636705e-05 6.37996465610006e-06 3.69872506335021e-05 819 832 0 71 0 819 832 0 74 0 0 0 0 0 0 0 0 0 2422 0 0 0 0 0 1675 +863 920 0.994308360456117 0.0407402002748724 0.0984434884013718 0.0166472914886594 -0.0501686566955033 0.994185405746953 0.0952810835640284 -0.0269132786011326 -0.0939893090326579 -0.0996775555545475 0.990570741898949 0.0395922801108528 2.82141794583978e-05 -2.84530580843736e-05 -8.35754178289123e-07 -6.06241699602985e-06 -1.32187698477625e-06 4.73603955623443e-06 -2.84530580843736e-05 5.5906766717642e-05 5.21138443185757e-06 1.37204879240657e-05 2.94600876895858e-06 8.8836207516244e-06 -8.35754178289123e-07 5.21138443185757e-06 1.16912614093938e-05 -2.08627405715139e-06 2.8158095917062e-06 4.30251904517175e-07 -6.06241699602985e-06 1.37204879240657e-05 -2.08627405715139e-06 5.55927925579869e-05 1.07721408238663e-05 8.02903082766013e-06 -1.32187698477625e-06 2.94600876895858e-06 2.8158095917062e-06 1.07721408238663e-05 2.69145870409901e-05 4.37328192716251e-06 4.73603955623443e-06 8.8836207516244e-06 4.30251904517175e-07 8.02903082766013e-06 4.37328192716251e-06 2.7205486053039e-05 816 825 0 71 0 816 825 0 69 0 0 0 0 0 0 0 0 0 2497 0 0 0 0 0 1637 +863 904 0.995128290322849 0.0427764943904316 0.0888248688532045 0.0147336980366153 -0.0510704938952381 0.994326821457802 0.093305823949633 -0.0234646883661435 -0.0843296534584369 -0.0973875949866759 0.991667366555082 0.0367093913614877 3.21426260287408e-05 -3.76539065429846e-05 -9.43416172433075e-07 -1.00837018111653e-05 -5.59356532565968e-06 4.03436588417568e-06 -3.76539065429846e-05 8.63362424576823e-05 3.97070048815833e-06 4.61905055208943e-05 2.07999268467807e-05 9.68589152600769e-06 -9.43416172433075e-07 3.97070048815833e-06 9.51702463885051e-06 -9.96213502749781e-08 4.71755896812e-06 1.72311998153597e-08 -1.00837018111653e-05 4.61905055208943e-05 -9.96213502749781e-08 7.9585286872887e-05 1.78176666116376e-05 1.92063627058118e-05 -5.59356532565968e-06 2.07999268467807e-05 4.71755896812e-06 1.78176666116376e-05 2.74246190578708e-05 8.6560984451077e-06 4.03436588417568e-06 9.68589152600769e-06 1.72311998153597e-08 1.92063627058118e-05 8.6560984451077e-06 2.95975823018903e-05 790 802 0 74 0 790 802 0 69 0 0 0 0 0 0 0 0 0 2706 0 0 0 0 0 1726 +863 914 0.9941267278671 0.0413247744846083 0.100021557446626 0.0195263098241653 -0.0511259891234908 0.993921436742391 0.0975003118973785 -0.0207240448011407 -0.0953843916812241 -0.102041367090693 0.990196635636511 0.0400460788833123 1.65115930091777e-05 -1.62468702603796e-05 3.25674019444702e-06 -1.25486839395812e-06 1.39483112303108e-06 4.11129745573171e-06 -1.62468702603796e-05 4.53221596205285e-05 2.15713141851094e-06 4.1495847161762e-06 5.76295509053681e-07 3.6433925186147e-06 3.25674019444702e-06 2.15713141851094e-06 9.0974590819166e-06 -8.56564545755657e-07 4.21265637703664e-06 7.89872978249315e-07 -1.25486839395812e-06 4.1495847161762e-06 -8.56564545755657e-07 3.46981097924965e-05 1.8404187491996e-06 3.75234534692017e-06 1.39483112303108e-06 5.76295509053681e-07 4.21265637703664e-06 1.8404187491996e-06 2.10667666112859e-05 3.9360409442576e-06 4.11129745573171e-06 3.6433925186147e-06 7.89872978249315e-07 3.75234534692017e-06 3.9360409442576e-06 2.19288960314372e-05 857 871 0 65 0 857 871 0 62 0 0 0 0 0 0 0 0 0 2776 0 0 0 0 0 1689 +863 905 0.994554928968332 0.0418402689647855 0.0954457183835436 0.0184711302478777 -0.0510515057943152 0.994051700609887 0.0962027040717895 -0.0221292700635297 -0.0908528316615905 -0.10055152115978 0.990775027224407 0.0395289824496841 1.47655786198708e-05 -1.49221639581638e-05 5.0423804476501e-06 -2.25484312826781e-06 3.90814841781e-06 4.17582283942638e-06 -1.49221639581638e-05 3.05424764978254e-05 -2.50166786548134e-06 7.30229277589141e-06 -5.57915855682266e-07 -1.47912534465798e-07 5.0423804476501e-06 -2.50166786548134e-06 8.49652001061328e-06 3.73998099609873e-07 4.69813579298377e-06 1.79931524473755e-06 -2.25484312826781e-06 7.30229277589141e-06 3.73998099609873e-07 3.18491604562691e-05 6.33328873770456e-07 1.76108116019894e-06 3.90814841781e-06 -5.57915855682266e-07 4.69813579298377e-06 6.33328873770456e-07 1.77202476798128e-05 6.36914041575899e-06 4.17582283942638e-06 -1.47912534465798e-07 1.79931524473755e-06 1.76108116019894e-06 6.36914041575899e-06 1.81955136908724e-05 838 852 0 67 0 838 852 0 71 0 0 0 0 0 0 0 0 0 2777 0 0 0 0 0 1664 +863 915 0.995050164704155 0.0426186415659249 0.089770936907827 0.0151940749213284 -0.0511087549822499 0.99421156958165 0.0945052912495156 -0.0228833497041346 -0.0852236169520995 -0.0986255864421937 0.991468571772467 0.03659818171683 3.33730122234759e-05 -3.78280958041747e-05 2.08367278398127e-07 -1.68561491481752e-05 -1.16446687357859e-05 3.99508311171195e-06 -3.78280958041747e-05 8.88723039309787e-05 3.10289382684763e-06 5.81374591088119e-05 3.12619313273829e-05 1.54540440688634e-05 2.08367278398127e-07 3.10289382684763e-06 9.26852144007187e-06 -7.79509635994306e-07 3.5710751516797e-06 -2.19560276761095e-07 -1.68561491481752e-05 5.81374591088119e-05 -7.79509635994306e-07 9.10711131475552e-05 3.13801865649515e-05 2.683686924694e-05 -1.16446687357859e-05 3.12619313273829e-05 3.5710751516797e-06 3.13801865649515e-05 3.4624249959011e-05 1.28102057247366e-05 3.99508311171195e-06 1.54540440688634e-05 -2.19560276761095e-07 2.683686924694e-05 1.28102057247366e-05 3.49719109055469e-05 828 839 0 69 0 828 839 0 77 0 0 0 0 0 0 0 0 0 2776 0 0 0 0 0 1714 +864 866 0.999138827087744 0.0242007746248447 0.033703511883539 0.0252536292892351 -0.0237635268334514 0.999628945701791 -0.0133141168525074 0.000191506582106607 -0.0340132179918663 0.0125017367866973 0.999343188088634 0.00366467892739912 4.09225131579282e-05 -4.44794660627056e-05 7.54868683658964e-06 -3.29884549451945e-05 -1.52452393504392e-05 2.13098622875372e-06 -4.44794660627056e-05 7.06122364030499e-05 -6.60445629116458e-06 5.81981515558345e-05 2.81429157316775e-05 6.29184946944152e-06 7.54868683658964e-06 -6.60445629116458e-06 1.02261153284912e-05 6.04685985196886e-07 2.78893489957273e-06 4.24781266435651e-06 -3.29884549451945e-05 5.81981515558345e-05 6.04685985196886e-07 9.97525214473725e-05 4.73309620238154e-05 2.23191801478177e-05 -1.52452393504392e-05 2.81429157316775e-05 2.78893489957273e-06 4.73309620238154e-05 4.5271119220678e-05 1.63875702672021e-05 2.13098622875372e-06 6.29184946944152e-06 4.24781266435651e-06 2.23191801478177e-05 1.63875702672021e-05 3.45349621232763e-05 855 858 0 30 0 855 863 0 39 0 0 0 0 0 0 0 5 0 2440 0 0 0 0 0 1523 +864 899 0.992736891374676 0.0491576536258029 0.109804324112262 0.00281223031645205 -0.0602694658579996 0.993131694153939 0.100284742369511 -0.0258995810750618 -0.104120391801686 -0.106174211355363 0.988881176306906 0.0301130267557921 3.40713426801981e-05 -3.81575082275572e-05 -3.03660951160723e-06 -7.8223259595181e-06 -5.66016512204814e-06 4.73405573329033e-06 -3.81575082275572e-05 7.25297490416847e-05 7.82437538073211e-06 1.87860346955537e-05 1.23430985601268e-05 9.53276530540057e-06 -3.03660951160723e-06 7.82437538073211e-06 1.01971659816932e-05 -9.25756397770833e-07 4.55356126881058e-06 1.37948711876049e-06 -7.8223259595181e-06 1.87860346955537e-05 -9.25756397770833e-07 5.29112187441606e-05 1.68502589567393e-05 9.01141912820198e-06 -5.66016512204814e-06 1.23430985601268e-05 4.55356126881058e-06 1.68502589567393e-05 2.59231002392053e-05 6.75096097587444e-06 4.73405573329033e-06 9.53276530540057e-06 1.37948711876049e-06 9.01141912820198e-06 6.75096097587444e-06 3.18346414418098e-05 871 884 0 68 0 871 884 0 72 0 0 0 0 0 0 0 0 0 2718 0 0 0 0 0 1853 +864 929 0.993253365201993 0.026586695778137 0.112875595779236 0.00586052961177957 -0.0400561384359336 0.992110616446229 0.118794067647691 -0.0255811027622704 -0.108826735173477 -0.122513967947674 0.986482168804484 0.0257462941193877 1.78442176282587e-05 -1.62948681135805e-05 9.30042198962939e-07 1.20292527142636e-06 5.89481662062063e-07 2.6849679392239e-06 -1.62948681135805e-05 4.97698909739617e-05 5.88875069663879e-06 6.50308120550365e-06 -1.1280912535675e-06 7.18305167866183e-06 9.30042198962939e-07 5.88875069663879e-06 9.7171746695314e-06 8.04422087693463e-07 3.1093365514141e-06 5.00742570291836e-07 1.20292527142636e-06 6.50308120550365e-06 8.04422087693463e-07 3.42465183210118e-05 2.89308302817768e-06 8.22132729413253e-06 5.89481662062063e-07 -1.1280912535675e-06 3.1093365514141e-06 2.89308302817768e-06 2.02844270483709e-05 2.84731289619415e-06 2.6849679392239e-06 7.18305167866183e-06 5.00742570291836e-07 8.22132729413253e-06 2.84731289619415e-06 2.58810882815663e-05 879 891 0 51 0 879 891 0 60 0 0 0 0 0 0 0 0 0 2742 0 0 0 0 0 1648 +864 890 0.994173434463967 0.0513532701104501 0.0947735398467457 0.0103439531613355 -0.0584223387445895 0.995590913969226 0.0733863908196432 -0.0180972265404118 -0.0905870440059283 -0.0784956920530301 0.992790216403941 0.0281332952735011 3.18735434220698e-05 -3.40211755788072e-05 3.51408719143946e-06 -1.37694304689982e-05 -9.4906646621535e-06 4.02343427639063e-06 -3.40211755788072e-05 5.20748071779074e-05 -1.55962609883903e-07 2.58771729398047e-05 1.74221832728821e-05 5.52875341574547e-06 3.51408719143946e-06 -1.55962609883903e-07 1.11169764004696e-05 2.70695364905914e-06 4.98250213438297e-06 2.83907703833031e-06 -1.37694304689982e-05 2.58771729398047e-05 2.70695364905914e-06 6.27709944069114e-05 1.9522642969997e-05 1.24651599805054e-05 -9.4906646621535e-06 1.74221832728821e-05 4.98250213438297e-06 1.9522642969997e-05 3.1207235014841e-05 1.01735002841944e-05 4.02343427639063e-06 5.52875341574547e-06 2.83907703833031e-06 1.24651599805054e-05 1.01735002841944e-05 3.62063938034697e-05 799 810 0 69 0 799 810 0 67 0 0 0 0 0 0 0 0 0 2537 0 0 0 0 0 1586 +864 868 0.997264231788833 0.0560025862223399 0.0482468893405319 0.0227597126702725 -0.0547308685478673 0.998128162828365 -0.0272892395802741 -0.00829774825678051 -0.049684847012185 0.0245739883877834 0.998462585714704 0.00440809745468868 2.80508701584885e-05 -3.09003328378605e-05 1.31467723889839e-06 -4.12802624667396e-06 -9.39050830126449e-06 5.35706467778397e-06 -3.09003328378605e-05 8.97584286595826e-05 -2.79071167121013e-06 5.25447959154622e-05 3.44133757749728e-05 1.11147542524487e-05 1.31467723889839e-06 -2.79071167121013e-06 8.86193390687891e-06 5.21116723133362e-07 3.41916797009915e-07 -1.18573590189632e-06 -4.12802624667396e-06 5.25447959154622e-05 5.21116723133362e-07 7.84669379359897e-05 2.72500168830709e-05 1.24283394751835e-05 -9.39050830126449e-06 3.44133757749728e-05 3.41916797009915e-07 2.72500168830709e-05 3.76666982879395e-05 6.17468358672848e-06 5.35706467778397e-06 1.11147542524487e-05 -1.18573590189632e-06 1.24283394751835e-05 6.17468358672848e-06 3.84767674665796e-05 868 869 0 64 0 868 869 0 63 0 0 0 0 0 0 0 0 0 2256 0 0 0 0 0 2473 +864 930 0.985395091989956 -0.0356562230033554 0.166508697800566 -0.00202294643810528 0.0155803638278374 0.992608855098886 0.12035328430197 -0.0176454986198837 -0.169569351432084 -0.116001269563801 0.978667431007331 -0.0145286862031943 3.53571011235723e-05 -3.48874643955335e-05 -3.5309855800636e-06 -1.03235185917073e-06 -3.88698681712385e-06 8.10295678837517e-06 -3.48874643955335e-05 5.7595567638843e-05 4.85092600487511e-06 1.10144109916228e-05 6.42983438396823e-06 1.33655161523988e-06 -3.5309855800636e-06 4.85092600487511e-06 1.07096030358487e-05 -9.40736492012166e-07 2.76169326206984e-06 -3.17748277796829e-06 -1.03235185917073e-06 1.10144109916228e-05 -9.40736492012166e-07 4.38683753202708e-05 6.27153933219817e-06 9.83610437889681e-06 -3.88698681712385e-06 6.42983438396823e-06 2.76169326206984e-06 6.27153933219817e-06 2.25509780482318e-05 2.40365374275534e-06 8.10295678837517e-06 1.33655161523988e-06 -3.17748277796829e-06 9.83610437889681e-06 2.40365374275534e-06 2.73801411777326e-05 1043 1041 0 0 0 1049 1049 0 1 0 0 0 0 0 0 27 38 0 2854 0 0 0 0 0 1690 +864 892 0.992717853658245 0.0491265816095459 0.109990190505914 0.00696274682851601 -0.0602639740985955 0.993126638528322 0.100338094815871 -0.0238934751865342 -0.10430492056471 -0.106235864117517 0.988855108052334 0.0305338779013223 2.00952890468344e-05 -2.41449676270072e-05 2.31203095517341e-06 -2.92527922553687e-06 -5.11700565149958e-07 4.89404747630275e-06 -2.41449676270072e-05 7.88579987559443e-05 3.44603162748009e-06 2.26502078420796e-05 9.53913008994762e-06 6.41660006254764e-06 2.31203095517341e-06 3.44603162748009e-06 8.8401459359252e-06 3.13813684616775e-07 5.47498854023065e-06 3.60828269743325e-07 -2.92527922553687e-06 2.26502078420796e-05 3.13813684616775e-07 4.50956284683772e-05 5.994413437467e-06 1.12919079579756e-05 -5.11700565149958e-07 9.53913008994762e-06 5.47498854023065e-06 5.994413437467e-06 2.01660865133393e-05 4.06073233446453e-06 4.89404747630275e-06 6.41660006254764e-06 3.60828269743325e-07 1.12919079579756e-05 4.06073233446453e-06 2.48393677286773e-05 838 852 0 72 0 838 852 0 77 0 0 0 0 0 0 0 0 0 2712 0 0 0 0 0 1874 +864 898 0.993146948542352 0.049274203476677 0.105977315840482 -4.47812689466759e-05 -0.0601213565146905 0.992994383761087 0.101723037261833 -0.0251780413505069 -0.100222557799369 -0.107397424041165 0.989151774106216 0.0323811154645605 3.06715007441437e-05 -3.67287196912443e-05 -2.89878896597633e-06 -6.57773824896508e-06 -4.87824583990726e-06 2.88890362582853e-06 -3.67287196912443e-05 8.78673277244447e-05 8.86726576915101e-06 3.18711691048347e-05 1.47895692926462e-05 1.07137284484786e-05 -2.89878896597633e-06 8.86726576915101e-06 1.23591952738032e-05 -3.57924096351573e-06 3.47054690025255e-06 -7.76305581729373e-07 -6.57773824896508e-06 3.18711691048347e-05 -3.57924096351573e-06 8.1346989954123e-05 2.47186333942683e-05 1.60192738725181e-05 -4.87824583990726e-06 1.47895692926462e-05 3.47054690025255e-06 2.47186333942683e-05 2.88817765938628e-05 6.2435290378279e-06 2.88890362582853e-06 1.07137284484786e-05 -7.76305581729373e-07 1.60192738725181e-05 6.2435290378279e-06 2.86108730388002e-05 829 841 0 67 0 829 841 0 71 0 0 0 0 0 0 0 0 0 2701 0 0 0 0 0 1633 +864 897 0.992818144488821 0.048956453323716 0.109157673352532 0.000918432159282575 -0.0599652793011104 0.993182355744183 0.0999648614102755 -0.0285735664137601 -0.103519550096177 -0.105792598589876 0.988985150966124 0.0311378925771161 3.45085920343008e-05 -3.54839411930762e-05 -6.39534983290365e-07 -1.09101353052576e-05 -8.47270023802412e-06 3.92817580333024e-06 -3.54839411930762e-05 7.40584316028513e-05 5.89292716945971e-06 3.01282069560086e-05 1.9965568118965e-05 1.32339215122868e-05 -6.39534983290365e-07 5.89292716945971e-06 1.02959197719959e-05 -2.65894927732143e-06 4.7289036442478e-06 8.36688527205361e-07 -1.09101353052576e-05 3.01282069560086e-05 -2.65894927732143e-06 7.64509446017295e-05 2.74669417210195e-05 1.84681040545982e-05 -8.47270023802412e-06 1.9965568118965e-05 4.7289036442478e-06 2.74669417210195e-05 3.36655799776963e-05 1.12256731171233e-05 3.92817580333024e-06 1.32339215122868e-05 8.36688527205361e-07 1.84681040545982e-05 1.12256731171233e-05 3.70430848393439e-05 873 882 0 64 0 873 882 0 68 0 0 0 0 0 0 0 0 0 2578 0 0 0 0 0 1568 +864 922 0.992575575919643 0.0487096541623693 0.111449969399598 0.00656345179839132 -0.0600158273641129 0.993130296980757 0.100450553431599 -0.0273393257721456 -0.105791429490248 -0.106393528047039 0.988680226684095 0.0303399723510734 2.69490732344543e-05 -3.17962807669218e-05 -2.247015671605e-06 -9.15779448032358e-07 -1.80381324098521e-06 4.9107514416376e-06 -3.17962807669218e-05 0.000103026079573009 1.00122174482584e-05 3.30970082810881e-05 1.86316217602655e-05 1.74880273737322e-05 -2.247015671605e-06 1.00122174482584e-05 1.10706710649986e-05 -2.15144713177585e-06 5.17359848835868e-06 1.18872674642426e-07 -9.15779448032358e-07 3.30970082810881e-05 -2.15144713177585e-06 6.4333993719744e-05 1.42613990499371e-05 1.49005898299143e-05 -1.80381324098521e-06 1.86316217602655e-05 5.17359848835868e-06 1.42613990499371e-05 2.78204442481564e-05 9.96998813572235e-06 4.9107514416376e-06 1.74880273737322e-05 1.18872674642426e-07 1.49005898299143e-05 9.96998813572235e-06 3.27441534665655e-05 849 857 0 68 0 849 857 0 73 0 0 0 0 0 0 0 0 0 2693 0 0 0 0 0 1859 +864 900 0.992433181951054 0.0485919564787765 0.112761700626012 -0.00105023858973 -0.0601273996763588 0.993041006793546 0.101263293619262 -0.0287265559084011 -0.107056411160963 -0.107277120543134 0.988448554168253 0.0313755465452637 4.84877854825133e-05 -8.32876408358114e-05 1.11691093096511e-07 -2.75541019837132e-05 -1.48291826118197e-05 -1.58399606875711e-05 -8.32876408358114e-05 0.000260152064888945 1.35619363895982e-05 9.20835969321641e-05 3.38468825037467e-05 8.24404927756009e-05 1.11691093096511e-07 1.35619363895982e-05 1.25079334350371e-05 1.46427482280147e-06 4.39259465856443e-06 7.61804925353486e-06 -2.75541019837132e-05 9.20835969321641e-05 1.46427482280147e-06 0.000120016070444213 4.65548939416472e-05 4.31761149644098e-05 -1.48291826118197e-05 3.38468825037467e-05 4.39259465856443e-06 4.65548939416472e-05 4.15218544101791e-05 1.45690337200432e-05 -1.58399606875711e-05 8.24404927756009e-05 7.61804925353486e-06 4.31761149644098e-05 1.45690337200432e-05 6.45571249663481e-05 832 845 0 71 0 832 845 0 73 0 0 0 0 0 0 0 0 0 2617 0 0 0 0 0 1511 +864 901 0.992451070449394 0.0492021398535694 0.112338872157779 0.00652840836482922 -0.0606131382871854 0.99308580059253 0.100531786657114 -0.0258112593941531 -0.106615759767638 -0.106582090875169 0.98857136195312 0.0308726736433234 5.40679375194378e-05 -8.44349565809891e-05 -3.31636681491707e-06 -3.69397401701209e-05 -2.02788493955119e-05 2.2849380549541e-06 -8.44349565809891e-05 0.000294084284376704 1.51814642940319e-05 0.000166707121063834 7.2199879428643e-05 5.92082578799997e-05 -3.31636681491707e-06 1.51814642940319e-05 1.0486252896634e-05 5.8342701794824e-06 7.54442630593704e-06 2.72804835549845e-06 -3.69397401701209e-05 0.000166707121063834 5.8342701794824e-06 0.000151931414913202 5.30306353149523e-05 5.09048879984132e-05 -2.02788493955119e-05 7.2199879428643e-05 7.54442630593704e-06 5.30306353149523e-05 4.51732309984319e-05 2.23078756853873e-05 2.2849380549541e-06 5.92082578799997e-05 2.72804835549845e-06 5.09048879984132e-05 2.23078756853873e-05 5.00469883987679e-05 821 829 0 71 0 821 829 0 72 0 0 0 0 0 0 0 0 0 2588 0 0 0 0 0 1867 +864 891 0.992302501726416 0.0492685550526918 0.113614939820943 0.0123220931491909 -0.0604533772587955 0.993427223973668 0.0971994848030414 -0.0227502876412176 -0.108079296100142 -0.103319698755808 0.988758770177796 0.0320227478373783 3.10113631746264e-05 -3.480565689082e-05 -4.16195880327738e-06 -2.94727688900336e-06 -4.4795906673542e-06 1.25335563014104e-06 -3.480565689082e-05 7.13091432829491e-05 9.58505931255017e-06 2.53155077807278e-05 1.41750683818889e-05 1.4198500207697e-05 -4.16195880327738e-06 9.58505931255017e-06 1.18465798154451e-05 -2.25735726433389e-06 4.6133275830317e-06 -1.25989274631789e-06 -2.94727688900336e-06 2.53155077807278e-05 -2.25735726433389e-06 6.23570964455113e-05 1.20468860487997e-05 2.37974362191911e-05 -4.4795906673542e-06 1.41750683818889e-05 4.6133275830317e-06 1.20468860487997e-05 2.44166740276481e-05 1.14607263625255e-05 1.25335563014104e-06 1.4198500207697e-05 -1.25989274631789e-06 2.37974362191911e-05 1.14607263625255e-05 3.8435042190903e-05 838 850 0 70 0 838 850 0 81 0 0 0 0 0 0 0 0 0 2610 0 0 0 0 0 1591 +864 896 0.992146321662698 0.0481600733124172 0.115439524209523 0.00520643088699146 -0.0599318666087339 0.993102613379447 0.100773859029539 -0.0267701318927335 -0.10979001674092 -0.106900919722213 0.988189427987657 0.0332130570844192 2.5362515894641e-05 -3.01292068078401e-05 6.49379601357805e-07 -5.19456387348451e-06 -2.9193571251113e-07 4.59786254330825e-06 -3.01292068078401e-05 7.04264211622195e-05 6.59544700425171e-06 1.65548567365491e-05 5.68020234829654e-06 5.98875080043599e-06 6.49379601357805e-07 6.59544700425171e-06 1.1377856056485e-05 -2.3647967809806e-06 2.14711125623846e-06 -2.15943607188265e-07 -5.19456387348451e-06 1.65548567365491e-05 -2.3647967809806e-06 7.27246333602494e-05 2.96390325999467e-05 9.61461358170524e-06 -2.9193571251113e-07 5.68020234829654e-06 2.14711125623846e-06 2.96390325999467e-05 3.47731854221246e-05 6.06028992749407e-06 4.59786254330825e-06 5.98875080043599e-06 -2.15943607188265e-07 9.61461358170524e-06 6.06028992749407e-06 3.03855806050257e-05 825 835 0 69 0 825 835 0 69 0 0 0 0 0 0 0 0 0 2595 0 0 0 0 0 1626 +864 925 0.993192904220894 0.0497384699085679 0.10532777229402 0.00453373365342051 -0.0604154338149715 0.993077413320892 0.100733442852085 -0.024477253956571 -0.099588304344512 -0.10641116371434 0.989322411489169 0.0310631655592731 3.17434426046057e-05 -4.07938465153585e-05 1.29634355726281e-06 -1.88991280712638e-05 -8.20383728006374e-06 -3.97867118214442e-06 -4.07938465153585e-05 9.70958089466825e-05 3.91165391667954e-06 5.84862854945813e-05 2.86613277696466e-05 3.18602939424863e-05 1.29634355726281e-06 3.91165391667954e-06 1.08342245132839e-05 -2.76162630132132e-06 5.10524489197254e-06 1.18191253364023e-06 -1.88991280712638e-05 5.84862854945813e-05 -2.76162630132132e-06 0.000112475538619652 3.83439695117793e-05 4.19063603219193e-05 -8.20383728006374e-06 2.86613277696466e-05 5.10524489197254e-06 3.83439695117793e-05 3.37024393150174e-05 1.869664624392e-05 -3.97867118214442e-06 3.18602939424863e-05 1.18191253364023e-06 4.19063603219193e-05 1.869664624392e-05 4.76249258958862e-05 851 865 0 69 0 851 865 0 72 0 0 0 0 0 0 0 0 0 2566 0 0 0 0 0 1619 +864 921 0.992421360834608 0.0484274590871255 0.112936370428443 0.00699634712143537 -0.0599715565658311 0.993060022927622 0.101169181404531 -0.0259159273146282 -0.107253228213686 -0.107175426611497 0.98843824944626 0.0326940437076258 4.50941963618737e-05 -5.54811427487146e-05 -2.07198235458246e-07 -1.81803537829929e-05 -1.20808590349683e-05 1.16850552452216e-06 -5.54811427487146e-05 0.000130659133827961 9.01164769750013e-06 6.22614565018501e-05 2.83091258136222e-05 2.46625731654651e-05 -2.07198235458246e-07 9.01164769750013e-06 1.23110913162885e-05 6.9836793175561e-08 4.01652803909385e-06 3.36879769849933e-06 -1.81803537829929e-05 6.22614565018501e-05 6.9836793175561e-08 0.000113215745550686 4.86041553799569e-05 2.63357810689616e-05 -1.20808590349683e-05 2.83091258136222e-05 4.01652803909385e-06 4.86041553799569e-05 4.88281621145308e-05 1.3162682421843e-05 1.16850552452216e-06 2.46625731654651e-05 3.36879769849933e-06 2.63357810689616e-05 1.3162682421843e-05 3.83929688246223e-05 807 814 0 72 0 807 814 0 75 0 0 0 0 0 0 0 0 0 2542 0 0 0 0 0 1602 +864 928 0.992120227690931 0.0484422741865179 0.115545661442274 0.00797764967597839 -0.0603800290041963 0.992933706307289 0.102161181357316 -0.0249094063779966 -0.109780261905074 -0.108332824898588 0.988034560703999 0.0310919632216682 4.3140144343873e-05 -5.3033858159496e-05 -6.23357852157404e-06 -1.14947066563461e-06 -5.71286885799678e-06 6.78495120103193e-06 -5.3033858159496e-05 0.000149894859837131 1.30530463931468e-05 5.8421945979944e-05 2.97219673755786e-05 2.75308257476523e-05 -6.23357852157404e-06 1.30530463931468e-05 1.14948554518712e-05 -1.74851079995904e-06 3.80264694957632e-06 -1.80423391346594e-06 -1.14947066563461e-06 5.8421945979944e-05 -1.74851079995904e-06 9.37521347147887e-05 2.76791910943559e-05 3.44236044548851e-05 -5.71286885799678e-06 2.97219673755786e-05 3.80264694957632e-06 2.76791910943559e-05 3.31280379430834e-05 1.31284973018097e-05 6.78495120103193e-06 2.75308257476523e-05 -1.80423391346594e-06 3.44236044548851e-05 1.31284973018097e-05 4.55619618815006e-05 829 840 0 77 0 829 840 0 75 0 0 0 0 0 0 0 0 0 2561 0 0 0 0 0 1876 +864 903 0.992635309481809 0.0492796331632588 0.110664629061178 0.00714921078192515 -0.060631311938645 0.992968450407292 0.101673499538176 -0.0249570257304532 -0.10487605247411 -0.107634447325358 0.988643433886258 0.0312259335514127 3.4033729247728e-05 -3.30571885796007e-05 -2.69829860183485e-06 -3.27724244169347e-06 -2.18004340980987e-06 1.158091807302e-05 -3.30571885796007e-05 8.30208727303331e-05 1.02273223874749e-05 1.89511992155337e-05 6.34000192336281e-06 -1.40526377818371e-06 -2.69829860183485e-06 1.02273223874749e-05 1.24431930460534e-05 -1.85811458047778e-06 3.87224318913732e-06 -1.24131251044177e-06 -3.27724244169347e-06 1.89511992155337e-05 -1.85811458047778e-06 5.89845770458716e-05 8.81966197408793e-06 6.82427315228169e-06 -2.18004340980987e-06 6.34000192336281e-06 3.87224318913732e-06 8.81966197408793e-06 2.52265040436032e-05 2.93321847868035e-06 1.158091807302e-05 -1.40526377818371e-06 -1.24131251044177e-06 6.82427315228169e-06 2.93321847868035e-06 2.86879450302785e-05 815 828 0 67 0 815 828 0 72 0 0 0 0 0 0 0 0 0 2631 0 0 0 0 0 1730 +864 895 0.992755073928389 0.0486216806068275 0.109878548244898 0.0021625705737591 -0.0598048357287738 0.993098682263013 0.100888001818456 -0.025943011256654 -0.104214897269504 -0.106728344231671 0.988811567349752 0.0327575648861625 2.7398619604629e-05 -3.19871697929882e-05 6.51328448872311e-07 -3.69596044048685e-06 -1.31735439396666e-06 3.49802867328825e-06 -3.19871697929882e-05 7.31166605722189e-05 5.05865693184483e-06 1.99556560567726e-05 8.37619674716701e-06 1.32652958748639e-05 6.51328448872311e-07 5.05865693184483e-06 1.04526193835483e-05 -1.73144255563283e-06 2.95415907153261e-06 2.02042696575955e-07 -3.69596044048685e-06 1.99556560567726e-05 -1.73144255563283e-06 6.91888818623653e-05 2.03213959985933e-05 1.6117902381908e-05 -1.31735439396666e-06 8.37619674716701e-06 2.95415907153261e-06 2.03213959985933e-05 2.85963061582747e-05 9.72588188465061e-06 3.49802867328825e-06 1.32652958748639e-05 2.02042696575955e-07 1.6117902381908e-05 9.72588188465061e-06 3.56597366868186e-05 821 834 0 69 0 821 834 0 71 0 0 0 0 0 0 0 0 0 2634 0 0 0 0 0 1627 +864 918 0.992462423292398 0.0488798115242194 0.112379279130708 0.00384847662025346 -0.060091036603056 0.993306903319992 0.0986431099307948 -0.0282367798222441 -0.106805457129076 -0.104652567298683 0.988757014885479 0.0313408676532288 4.11547112106192e-05 -5.48242017342587e-05 -1.66695441662724e-06 -1.87032806811214e-05 -1.15307462518706e-05 3.14100105429193e-06 -5.48242017342587e-05 0.000161463790719239 8.77636999535531e-06 7.97380648022976e-05 4.08526248501997e-05 3.99282949069758e-05 -1.66695441662724e-06 8.77636999535531e-06 9.94981873801544e-06 1.86237230881358e-06 3.86750619494236e-06 1.10411710210171e-06 -1.87032806811214e-05 7.97380648022976e-05 1.86237230881358e-06 9.61172236264193e-05 3.35475832250881e-05 3.84330403575798e-05 -1.15307462518706e-05 4.08526248501997e-05 3.86750619494236e-06 3.35475832250881e-05 3.97033898558824e-05 1.73578275522336e-05 3.14100105429193e-06 3.99282949069758e-05 1.10411710210171e-06 3.84330403575798e-05 1.73578275522336e-05 5.08191509066452e-05 828 839 0 68 0 828 839 0 76 0 0 0 0 0 0 0 0 0 2363 0 0 0 0 0 1584 +864 893 0.99253105130901 0.0479298039423005 0.112182200377257 0.00112524337091734 -0.0593162859106493 0.993170498523381 0.10046859752472 -0.0284808555684086 -0.106600611692413 -0.106372434196415 0.988595576982789 0.0305505349819334 3.37268101051433e-05 -4.00125164217851e-05 -6.34953363207506e-07 -1.17076267154319e-05 -8.47620427924384e-06 8.98760146800987e-07 -4.00125164217851e-05 9.50456293743785e-05 5.57058580223265e-06 4.24834093787871e-05 2.13543464805575e-05 1.78758054709788e-05 -6.34953363207506e-07 5.57058580223265e-06 1.00675750137335e-05 1.18849014892132e-06 3.33598090178389e-06 1.59842601193611e-06 -1.17076267154319e-05 4.24834093787871e-05 1.18849014892132e-06 7.98615425813583e-05 2.99360535473499e-05 1.67070964650085e-05 -8.47620427924384e-06 2.13543464805575e-05 3.33598090178389e-06 2.99360535473499e-05 3.47941651434567e-05 1.2358049343022e-05 8.98760146800987e-07 1.78758054709788e-05 1.59842601193611e-06 1.67070964650085e-05 1.2358049343022e-05 3.24038160505307e-05 865 876 0 69 0 865 876 0 75 0 0 0 0 0 0 0 0 0 2593 0 0 0 0 0 1714 +864 894 0.9932713752183 0.0481536254564273 0.105324277957883 -0.00586251843724899 -0.0587320361370206 0.993276814439323 0.0997582970407492 -0.0316046615212094 -0.0998124396212561 -0.105272970190229 0.989421587921034 0.0298954847878776 3.31368779106165e-05 -3.66916980073049e-05 4.35010031314788e-06 -1.84804401955892e-05 -1.04243122137772e-05 1.95394609700259e-06 -3.66916980073049e-05 0.000113548643056523 3.26660994656469e-06 5.52008210862553e-05 2.62967412790096e-05 2.27787832560003e-05 4.35010031314788e-06 3.26660994656469e-06 1.16941018435749e-05 -3.87749270906181e-06 1.97467670931871e-06 1.72838693469291e-06 -1.84804401955892e-05 5.52008210862553e-05 -3.87749270906181e-06 0.000119691729106626 5.17701352517831e-05 2.91224658424633e-05 -1.04243122137772e-05 2.62967412790096e-05 1.97467670931871e-06 5.17701352517831e-05 4.57400777858081e-05 1.46613544047653e-05 1.95394609700259e-06 2.27787832560003e-05 1.72838693469291e-06 2.91224658424633e-05 1.46613544047653e-05 3.75587432172383e-05 821 830 0 69 0 821 830 0 71 0 0 0 0 0 0 0 0 0 2615 0 0 0 0 0 1884 +864 923 0.993560490549745 0.0488673411194647 0.102222965083504 -0.00281530321560172 -0.0590396292901106 0.993336743014635 0.098976952622125 -0.0293737653941135 -0.0967050866905966 -0.104374795563823 0.989825251374794 0.0286503039824022 3.43280284336602e-05 -3.79830571529634e-05 8.64388338579937e-07 -1.0472730274665e-05 -7.9273991977016e-06 4.68366188370866e-06 -3.79830571529634e-05 0.000101439141158089 4.1726746543199e-06 5.8450900569007e-05 2.73589259278099e-05 1.84123096978517e-05 8.64388338579937e-07 4.1726746543199e-06 9.87242839791097e-06 1.04408976331804e-06 4.51532846710619e-06 8.35500647489078e-07 -1.0472730274665e-05 5.8450900569007e-05 1.04408976331804e-06 9.50176515500451e-05 3.43913104280178e-05 2.83067281898213e-05 -7.9273991977016e-06 2.73589259278099e-05 4.51532846710619e-06 3.43913104280178e-05 3.52443951093766e-05 1.34768454202569e-05 4.68366188370866e-06 1.84123096978517e-05 8.35500647489078e-07 2.83067281898213e-05 1.34768454202569e-05 3.81424154824461e-05 852 866 0 76 0 852 866 0 79 0 0 0 0 0 0 0 0 0 2560 0 0 0 0 0 1854 +864 926 0.99236417409493 0.0485743398658862 0.113374950846654 0.00506053711469506 -0.0601263648489699 0.993087781125652 0.100804162756199 -0.026704786359222 -0.107694782709918 -0.106851263378227 0.988425334201598 0.0325196333099721 2.54949438507919e-05 -3.1829145941335e-05 1.62658481285533e-06 -7.17711432244057e-06 -6.9875572489459e-06 4.98854931725877e-06 -3.1829145941335e-05 0.000132030124151114 5.96326084707041e-06 6.43190160085725e-05 3.23789854080238e-05 1.36358492662738e-05 1.62658481285533e-06 5.96326084707041e-06 9.67464204776882e-06 2.22827354576081e-06 5.58501942921339e-06 -5.63227879496223e-07 -7.17711432244057e-06 6.43190160085725e-05 2.22827354576081e-06 8.09612034999215e-05 2.52980243389983e-05 2.07045196912397e-05 -6.9875572489459e-06 3.23789854080238e-05 5.58501942921339e-06 2.52980243389983e-05 3.18997617220934e-05 9.64814476888466e-06 4.98854931725877e-06 1.36358492662738e-05 -5.63227879496223e-07 2.07045196912397e-05 9.64814476888466e-06 3.03795069358318e-05 825 837 0 67 0 825 837 0 71 0 0 0 0 0 0 0 0 0 2608 0 0 0 0 0 1754 +864 902 0.992528066900358 0.048775630044899 0.111843526092308 0.00415964237176855 -0.0602129870325731 0.993034400973489 0.101277216963337 -0.0242829790467947 -0.106124608869257 -0.107254913159943 0.988551440743172 0.030355667779361 2.68091201036127e-05 -3.24998978782662e-05 -1.70823364233298e-06 -3.92096562854222e-06 -4.64193472831485e-06 6.78939621945107e-06 -3.24998978782662e-05 8.75733282277822e-05 7.92778218807597e-06 3.29430286654269e-05 2.381290689463e-05 8.91002555563558e-06 -1.70823364233298e-06 7.92778218807597e-06 1.12866510644768e-05 -3.46024980184747e-06 4.31381247781646e-06 -2.55652834532991e-07 -3.92096562854222e-06 3.29430286654269e-05 -3.46024980184747e-06 8.60865021227416e-05 3.19299940406209e-05 2.00305187938487e-05 -4.64193472831485e-06 2.381290689463e-05 4.31381247781646e-06 3.19299940406209e-05 3.68051872155589e-05 1.33589525618468e-05 6.78939621945107e-06 8.91002555563558e-06 -2.55652834532991e-07 2.00305187938487e-05 1.33589525618468e-05 3.16731244539558e-05 810 822 0 63 0 810 822 0 66 0 0 0 0 0 0 0 0 0 2707 0 0 0 0 0 1851 +864 924 0.993109632285666 0.0488880922270667 0.106504519621595 0.00260458214909208 -0.0597508560685652 0.993058549252183 0.101314130091629 -0.0275983257203166 -0.100812169208398 -0.106979774703202 0.989137116048099 0.0315458752827374 3.30499956160955e-05 -3.14067511527837e-05 -1.85528007923465e-06 2.38489456801749e-06 -2.56659612200834e-06 1.36927672921923e-05 -3.14067511527837e-05 8.51473797664193e-05 7.09914399190926e-06 2.7242103809353e-05 1.40779302810038e-05 -5.8746455428552e-06 -1.85528007923465e-06 7.09914399190926e-06 1.05219742070518e-05 -4.74595429181017e-06 2.43612865030747e-06 -2.80140250615698e-06 2.38489456801749e-06 2.7242103809353e-05 -4.74595429181017e-06 8.0322208988965e-05 2.57936346647308e-05 1.36276132861225e-05 -2.56659612200834e-06 1.40779302810038e-05 2.43612865030747e-06 2.57936346647308e-05 3.26650656100218e-05 5.14051424998411e-06 1.36927672921923e-05 -5.8746455428552e-06 -2.80140250615698e-06 1.36276132861225e-05 5.14051424998411e-06 2.71091280490622e-05 820 826 0 69 0 820 826 0 71 0 0 0 0 0 0 0 0 0 2607 0 0 0 0 0 1730 +864 927 0.992361003896181 0.0493348074097709 0.113073934768385 0.0117946223851717 -0.0609614594777155 0.99293662467071 0.101786835326993 -0.022185785017635 -0.107253617209449 -0.107902438180878 0.988359107526263 0.0306421148990923 2.46526298979399e-05 -2.71503626453392e-05 -8.71612612078021e-07 -2.60914508776877e-06 -1.11605455579705e-06 9.70700528711896e-06 -2.71503626453392e-05 8.5649473061751e-05 9.2341845335661e-06 2.14058601741079e-05 8.95686844484803e-06 -1.25377775792438e-06 -8.71612612078021e-07 9.2341845335661e-06 1.08695345507871e-05 8.96715053084135e-07 5.16108847556756e-06 -8.51873977607765e-07 -2.60914508776877e-06 2.14058601741079e-05 8.96715053084135e-07 4.30727431261512e-05 7.12050126731097e-06 6.48732077901733e-06 -1.11605455579705e-06 8.95686844484803e-06 5.16108847556756e-06 7.12050126731097e-06 2.04829885878071e-05 3.7252458736909e-06 9.70700528711896e-06 -1.25377775792438e-06 -8.51873977607765e-07 6.48732077901733e-06 3.7252458736909e-06 2.79080906098276e-05 825 839 0 69 0 825 839 0 70 0 0 0 0 0 0 0 0 0 2637 0 0 0 0 0 1742 +864 920 0.992586413644684 0.0481603630185811 0.111592073562164 0.00060032598288561 -0.0593103901399185 0.99333276951465 0.0988548766111549 -0.0311201238269294 -0.106087176743637 -0.104740576866248 0.988825021168199 0.0319704647267876 3.61352414272604e-05 -4.21465074405981e-05 -3.83583899421141e-06 -5.50980006371109e-06 -8.3678601798066e-07 1.15125768106022e-07 -4.21465074405981e-05 9.79903933440833e-05 1.05003101849672e-05 3.63054710743157e-05 1.48598958362254e-05 2.89340401718956e-05 -3.83583899421141e-06 1.05003101849672e-05 1.26550591467787e-05 7.0885082412497e-07 4.16085267048564e-06 6.82957592144592e-07 -5.50980006371109e-06 3.63054710743157e-05 7.0885082412497e-07 7.61368735477123e-05 1.89596548476866e-05 2.57904576449991e-05 -8.3678601798066e-07 1.48598958362254e-05 4.16085267048564e-06 1.89596548476866e-05 2.89044368035861e-05 1.1555637437478e-05 1.15125768106022e-07 2.89340401718956e-05 6.82957592144592e-07 2.57904576449991e-05 1.1555637437478e-05 4.42574045385483e-05 837 846 0 68 0 837 846 0 69 0 0 0 0 0 0 0 0 0 2422 0 0 0 0 0 1578 +864 919 0.992716967687471 0.0489149192541024 0.110092473583606 0.00295132922807514 -0.0600769624691337 0.993124808685406 0.100468268393843 -0.0271212438370926 -0.104421169529337 -0.106350576152363 0.988830508381586 0.0328159900411973 3.18098385250636e-05 -4.10480865581461e-05 -3.46419523183824e-06 -1.1057850407228e-07 -5.30267494192282e-07 9.16017812549239e-06 -4.10480865581461e-05 0.000165114847951582 1.53985953959526e-05 3.83460911314691e-05 1.293519659294e-05 2.44557241257023e-05 -3.46419523183824e-06 1.53985953959526e-05 1.15623718276058e-05 -1.32530938478815e-06 3.10926227930328e-06 -1.9234311720086e-07 -1.1057850407228e-07 3.83460911314691e-05 -1.32530938478815e-06 7.48125435234409e-05 1.6935978915512e-05 2.01985657784528e-05 -5.30267494192282e-07 1.293519659294e-05 3.10926227930328e-06 1.6935978915512e-05 2.98957191164586e-05 4.91352422745004e-06 9.16017812549239e-06 2.44557241257023e-05 -1.9234311720086e-07 2.01985657784528e-05 4.91352422745004e-06 3.72935326737197e-05 822 834 0 65 0 822 834 0 73 0 0 0 0 0 0 0 0 0 2436 0 0 0 0 0 1874 +864 916 0.992517237066864 0.0497922723447711 0.111491092648255 0.012630377080822 -0.0612148414831739 0.992951183223582 0.10149231949797 -0.021952893534545 -0.10565167915063 -0.107557786094882 0.988569190974016 0.0310052078784595 3.27786442345804e-05 -3.89869092627233e-05 -2.7859926814463e-06 -4.45551314953806e-06 -6.0102570194856e-06 4.86829519959885e-06 -3.89869092627233e-05 0.000126026446061358 1.383954216888e-05 2.63741778735361e-05 1.41389448576569e-05 2.25402605403278e-05 -2.7859926814463e-06 1.383954216888e-05 1.13627979968195e-05 -2.98308940213836e-07 4.2753415602857e-06 1.92513099328415e-06 -4.45551314953806e-06 2.63741778735361e-05 -2.98308940213836e-07 5.24700667990485e-05 1.27096188824919e-05 1.18824871402837e-05 -6.0102570194856e-06 1.41389448576569e-05 4.2753415602857e-06 1.27096188824919e-05 2.98887764233829e-05 5.0769456032122e-06 4.86829519959885e-06 2.25402605403278e-05 1.92513099328415e-06 1.18824871402837e-05 5.0769456032122e-06 3.78751197452786e-05 806 816 0 66 0 806 816 0 70 0 0 0 0 0 0 0 0 0 2526 0 0 0 0 0 1910 +864 917 0.991492781873217 0.04936505799699 0.120437346957919 0.0218332232076147 -0.0620301057352374 0.992663632633591 0.103784287968646 -0.0180730981670174 -0.114430456941252 -0.110372113759035 0.987280946351432 0.0302653028842349 3.82305372444944e-05 -3.86022380435202e-05 -1.54900436229873e-06 -1.6772637548484e-05 -1.87228816071025e-05 1.21264011343039e-05 -3.86022380435202e-05 0.000120650294265523 9.16959637507098e-06 5.77224250638301e-05 3.13872198278693e-05 9.21008322085615e-06 -1.54900436229873e-06 9.16959637507098e-06 1.25838010784189e-05 -5.30390390984704e-06 -1.10230214626979e-06 4.39538694990734e-07 -1.6772637548484e-05 5.77224250638301e-05 -5.30390390984704e-06 0.000128150154079803 6.49901638451277e-05 1.35609740815603e-05 -1.87228816071025e-05 3.13872198278693e-05 -1.10230214626979e-06 6.49901638451277e-05 6.54977169166732e-05 1.36930406829276e-06 1.21264011343039e-05 9.21008322085615e-06 4.39538694990734e-07 1.35609740815603e-05 1.36930406829276e-06 3.8504015903077e-05 825 836 0 69 0 825 836 0 73 0 0 0 0 0 0 0 0 0 2258 0 0 0 0 0 1774 +865 869 0.998223329579995 0.0463929675491865 0.0373881912401455 -0.00279295263910802 -0.0460800956461743 0.998895498352726 -0.00918739113672234 -0.0135514798161019 -0.0377731262601998 0.00744821674226935 0.999258582650102 0.00301675542019577 3.15703167736137e-05 -4.36276250354286e-05 -3.04562879328779e-07 -9.02955063473109e-06 -9.57356124496249e-06 1.68787903013502e-05 -4.36276250354286e-05 0.000122412321514025 -7.40030492114948e-07 7.1360367884045e-05 4.32112596190204e-05 -1.7382802943088e-05 -3.04562879328779e-07 -7.40030492114948e-07 9.70398510013475e-06 -2.0812938819627e-06 -2.80013089416885e-07 -3.18708496929433e-06 -9.02955063473109e-06 7.1360367884045e-05 -2.0812938819627e-06 0.00010285294057988 3.92531623508035e-05 3.07277739978773e-06 -9.57356124496249e-06 4.32112596190204e-05 -2.80013089416885e-07 3.92531623508035e-05 4.09564166308432e-05 -3.13212738025728e-07 1.68787903013502e-05 -1.7382802943088e-05 -3.18708496929433e-06 3.07277739978773e-06 -3.13212738025728e-07 3.19998044946628e-05 890 896 0 55 0 890 896 0 70 0 0 0 0 0 0 0 0 0 2252 0 0 0 0 0 2486 +865 930 0.985352265750599 -0.0541424551001014 0.161708091745263 -0.0102949273657141 0.0321712768570313 0.990252189883431 0.13551977485392 -0.0147096963642353 -0.167469165297822 -0.128332361416762 0.977489070878876 -0.0194065577444441 2.36885064893774e-05 -2.44705661049754e-05 9.75059889119506e-07 -7.05128291647821e-06 3.09771093877229e-07 1.31414567121667e-06 -2.44705661049754e-05 4.75689282920631e-05 2.59884850199726e-06 1.07429888425906e-05 2.06788040120158e-06 8.43974975410964e-06 9.75059889119506e-07 2.59884850199726e-06 9.89845376930786e-06 8.56379046222594e-07 2.30991516365228e-06 7.80948974372003e-07 -7.05128291647821e-06 1.07429888425906e-05 8.56379046222594e-07 3.9915726009479e-05 5.5140688414242e-06 8.42749013735707e-06 3.09771093877229e-07 2.06788040120158e-06 2.30991516365228e-06 5.5140688414242e-06 1.7727970519749e-05 2.31443834800844e-06 1.31414567121667e-06 8.43974975410964e-06 7.80948974372003e-07 8.42749013735707e-06 2.31443834800844e-06 2.46929603216181e-05 1061 1061 0 0 0 1074 1074 0 0 0 0 0 0 0 0 48 56 0 2817 0 0 0 0 0 1544 +864 915 0.99242448507019 0.048951252889813 0.112682812680935 0.00602167571026003 -0.0605576311564602 0.992939844290715 0.10199626918985 -0.0253577944543824 -0.106894409310718 -0.108047399137822 0.988382185593035 0.0314305947816224 1.98752072876333e-05 -2.00616959739199e-05 4.96494760988236e-08 2.39551837983998e-06 4.71678499301666e-08 8.57146996671985e-06 -2.00616959739199e-05 9.89063748880418e-05 1.01560328094078e-05 3.08424332176315e-05 1.73986270278876e-05 5.24458314783351e-07 4.96494760988236e-08 1.01560328094078e-05 1.14209963507027e-05 -1.3348613286976e-06 3.95234606727515e-06 -8.5837033267467e-07 2.39551837983998e-06 3.08424332176315e-05 -1.3348613286976e-06 6.98189502261765e-05 2.36461834316718e-05 1.00444357780112e-05 4.71678499301666e-08 1.73986270278876e-05 3.95234606727515e-06 2.36461834316718e-05 3.02419629399448e-05 3.74779862059309e-06 8.57146996671985e-06 5.24458314783351e-07 -8.5837033267467e-07 1.00444357780112e-05 3.74779862059309e-06 2.31501895216952e-05 828 835 0 64 0 828 835 0 65 0 0 0 0 0 0 0 0 0 2657 0 0 0 0 0 1749 +865 898 0.994725223940623 0.0312302688551046 0.0977056762092935 -0.00552933382428085 -0.0424470116475182 0.992467758611202 0.114917358651563 -0.0208732008235236 -0.0933808334642227 -0.118458509295425 0.988558345024224 0.0242315595059831 3.89907143578544e-05 -4.28534499019762e-05 -4.06428315887242e-06 -6.06034497126974e-06 -6.96239549790797e-06 4.68988810574723e-06 -4.28534499019762e-05 7.52774046991177e-05 6.63257624130977e-06 2.14163726027635e-05 1.538760886659e-05 8.84542505061372e-06 -4.06428315887242e-06 6.63257624130977e-06 1.00179469966769e-05 2.35679347673004e-07 3.63516211494923e-06 -2.36291049136101e-06 -6.06034497126974e-06 2.14163726027635e-05 2.35679347673004e-07 4.50881082272314e-05 1.00757534047263e-05 1.63317829622798e-05 -6.96239549790797e-06 1.538760886659e-05 3.63516211494923e-06 1.00757534047263e-05 2.16461997126931e-05 6.23328065202924e-06 4.68988810574723e-06 8.84542505061372e-06 -2.36291049136101e-06 1.63317829622798e-05 6.23328065202924e-06 3.32617414281334e-05 855 864 0 42 0 855 864 0 55 0 0 0 0 0 0 0 0 0 2713 0 0 0 0 0 2083 +864 914 0.99246255101714 0.0491269763261816 0.112270321214456 0.00522927822768091 -0.0606563611183598 0.992964258168355 0.101699497816105 -0.0250415403465018 -0.106484227397439 -0.107742852186192 0.988459704347302 0.0315770245666583 3.86344569083796e-05 -4.50025120435484e-05 -2.04074614297128e-06 -6.8197964292452e-06 -4.70473899188585e-06 -4.82654134735013e-06 -4.50025120435484e-05 8.26776555582396e-05 6.76773636191707e-06 2.68892384405588e-05 1.28563076063867e-05 2.39659456597291e-05 -2.04074614297128e-06 6.76773636191707e-06 1.08866506456797e-05 -3.09125717944469e-06 3.05121993152606e-06 1.32979111644281e-06 -6.8197964292452e-06 2.68892384405588e-05 -3.09125717944469e-06 8.55885135779215e-05 2.88695407017829e-05 2.46316906784753e-05 -4.70473899188585e-06 1.28563076063867e-05 3.05121993152606e-06 2.88695407017829e-05 3.23383063081566e-05 1.20997569117154e-05 -4.82654134735013e-06 2.39659456597291e-05 1.32979111644281e-06 2.46316906784753e-05 1.20997569117154e-05 4.2792323315739e-05 887 900 0 68 0 887 900 0 70 0 0 0 0 0 0 0 0 0 2703 0 0 0 0 0 1500 +865 867 0.999263737059734 0.0192710594135647 0.0331754437271538 0.011102026823773 -0.0187307159850216 0.999688044352999 -0.0165219325856696 -0.00104008468794964 -0.0334834896046267 0.0158883682848748 0.999312971834721 -0.000526036067823689 4.7364700651305e-05 -3.93655098108153e-05 -3.63196148016898e-07 -2.51262915255395e-05 -1.28429878125191e-05 -4.76364757768126e-06 -3.93655098108153e-05 6.423847178704e-05 -2.28718215875688e-06 4.41919954214555e-05 2.17791966463738e-05 -3.04353509591066e-06 -3.63196148016898e-07 -2.28718215875688e-06 8.5649858265591e-06 3.56823783184828e-06 -5.95809884077821e-07 2.46565262550853e-06 -2.51262915255395e-05 4.41919954214555e-05 3.56823783184828e-06 7.25558111931135e-05 2.97844649537816e-05 1.00862219623426e-05 -1.28429878125191e-05 2.17791966463738e-05 -5.95809884077821e-07 2.97844649537816e-05 3.66269706142071e-05 8.74204481819263e-06 -4.76364757768126e-06 -3.04353509591066e-06 2.46565262550853e-06 1.00862219623426e-05 8.74204481819263e-06 3.62094381914368e-05 889 889 0 22 0 889 895 0 33 0 0 0 0 0 0 0 9 0 2354 0 0 0 0 0 2045 +864 904 0.991461409488855 0.0482883523621353 0.12113013052302 0.012013492411476 -0.0607900057167555 0.992952683768041 0.101732703703386 -0.0241230377159429 -0.115363983544824 -0.108227551131837 0.98740971662055 0.0329340766914216 3.39624890496393e-05 -3.57055700371528e-05 -1.71240827805342e-06 -1.13108954014375e-05 -8.56352665225836e-06 7.63220180108212e-06 -3.57055700371528e-05 0.000103652648976692 5.70458875449966e-06 5.71786732581774e-05 2.81582772694809e-05 1.23575312380476e-05 -1.71240827805342e-06 5.70458875449966e-06 1.11004462068551e-05 1.45846210547074e-07 4.54720270135931e-06 -5.55825567588599e-07 -1.13108954014375e-05 5.71786732581774e-05 1.45846210547074e-07 8.59377652793841e-05 2.83009511731894e-05 1.95279570126034e-05 -8.56352665225836e-06 2.81582772694809e-05 4.54720270135931e-06 2.83009511731894e-05 3.61007973289655e-05 1.09064001179131e-05 7.63220180108212e-06 1.23575312380476e-05 -5.55825567588599e-07 1.95279570126034e-05 1.09064001179131e-05 3.37462936040138e-05 800 812 0 69 0 800 812 0 75 0 0 0 0 0 0 0 0 0 2599 0 0 0 0 0 1778 +865 868 0.998502257540208 0.0360566804180565 0.0411479949005695 0.00761652487523275 -0.0355990564745418 0.999296477758995 -0.0118007083088154 -0.00393491560035266 -0.0415445407391818 0.0103182040926461 0.999083372796822 0.0011583439184377 2.11352208850497e-05 -2.29130176658363e-05 3.16546860877634e-06 -6.06128828794997e-06 -2.32672395404253e-06 9.49290809781588e-06 -2.29130176658363e-05 4.0524941581606e-05 -2.76386065472341e-06 2.3750971238514e-05 1.1183285428663e-05 -5.93953724405445e-06 3.16546860877634e-06 -2.76386065472341e-06 7.98740256650312e-06 1.7599834217702e-06 8.03028646202634e-07 1.34931109935036e-07 -6.06128828794997e-06 2.3750971238514e-05 1.7599834217702e-06 5.60442107774259e-05 1.70315136100092e-05 -5.06795627864014e-07 -2.32672395404253e-06 1.1183285428663e-05 8.03028646202634e-07 1.70315136100092e-05 2.49388829256383e-05 4.09076976373751e-06 9.49290809781588e-06 -5.93953724405445e-06 1.34931109935036e-07 -5.06795627864014e-07 4.09076976373751e-06 2.5058939778888e-05 901 902 0 37 0 901 902 0 48 0 0 0 0 0 0 0 0 0 2282 0 0 0 0 0 2712 +865 891 0.994609662530447 0.0307639999382909 0.0990211871715738 -0.0043092233093862 -0.0417462029949102 0.99296318781649 0.110821307413428 -0.0208472409471171 -0.0949150869808312 -0.114357701748114 0.988895061325675 0.025005739152173 4.97251691260041e-05 -8.32427975171804e-05 -6.84666296230244e-06 -2.64400205471596e-05 -1.39988339499541e-05 2.81124641186496e-07 -8.32427975171804e-05 0.000247298405191204 1.8670988321225e-05 0.000120534258139542 5.51645018011987e-05 3.23953957775244e-05 -6.84666296230244e-06 1.8670988321225e-05 1.04982021918046e-05 7.49782016311293e-06 5.44260321773937e-06 -1.30247865557746e-06 -2.64400205471596e-05 0.000120534258139542 7.49782016311293e-06 0.000102743220405667 3.25545173803859e-05 2.88794468788732e-05 -1.39988339499541e-05 5.51645018011987e-05 5.44260321773937e-06 3.25545173803859e-05 3.21638791595911e-05 1.24754883356656e-05 2.81124641186496e-07 3.23953957775244e-05 -1.30247865557746e-06 2.88794468788732e-05 1.24754883356656e-05 4.01343229369859e-05 825 837 0 47 0 825 837 0 63 0 0 0 0 0 0 0 0 0 2641 0 0 0 0 0 2097 +865 899 0.994409063040259 0.0302950215453658 0.101157436765474 -0.00496274199484823 -0.0420712534782048 0.99231189186166 0.116392091229201 -0.022402925154421 -0.0968536265411247 -0.119997170547892 0.988038488160422 0.0251030241538568 4.63424138845793e-05 -5.58158426385313e-05 -3.89724141044582e-06 -1.7277308418481e-05 -1.50673973538417e-05 8.25914533944483e-06 -5.58158426385313e-05 0.000120879142232118 7.92668483576614e-06 5.47018030863293e-05 3.41708234144996e-05 7.16433067027424e-06 -3.89724141044582e-06 7.92668483576614e-06 1.01814309268183e-05 -4.91600088372287e-08 4.41706548341845e-06 -1.24068404603993e-06 -1.7277308418481e-05 5.47018030863293e-05 -4.91600088372287e-08 7.96962062051415e-05 3.10661055749266e-05 1.60117742183899e-05 -1.50673973538417e-05 3.41708234144996e-05 4.41706548341845e-06 3.10661055749266e-05 3.27578881375112e-05 8.30652993505035e-06 8.25914533944483e-06 7.16433067027424e-06 -1.24068404603993e-06 1.60117742183899e-05 8.30652993505035e-06 3.41169240887691e-05 864 876 0 48 0 864 876 0 56 0 0 0 0 0 0 0 0 0 2700 0 0 0 0 0 1848 +865 929 0.994626903160127 0.00817066965559711 0.103201568144457 -0.0062357838001272 -0.021946738444258 0.990863930928212 0.133067693514058 -0.0217834534099261 -0.101171459324036 -0.134617645733652 0.985719242622043 0.0182348236792096 3.09251958046273e-05 -2.92146850132758e-05 -4.46741294771063e-06 -7.37870161291389e-07 -2.02389369280251e-06 9.80363849162956e-06 -2.92146850132758e-05 4.89626371909033e-05 6.39185622388481e-06 1.37863330954512e-05 8.23911059725664e-06 -3.6410435782957e-06 -4.46741294771063e-06 6.39185622388481e-06 9.99606394939643e-06 -3.21976601686797e-06 2.49421662406057e-06 -5.00911137324542e-06 -7.37870161291389e-07 1.37863330954512e-05 -3.21976601686797e-06 6.26846547090281e-05 1.26042228727119e-05 1.45863924377778e-05 -2.02389369280251e-06 8.23911059725664e-06 2.49421662406057e-06 1.26042228727119e-05 2.22838012297072e-05 2.92227183585942e-06 9.80363849162956e-06 -3.6410435782957e-06 -5.00911137324542e-06 1.45863924377778e-05 2.92227183585942e-06 2.52157049495354e-05 881 893 0 29 0 880 895 0 43 0 0 0 0 0 0 1 4 0 2669 0 0 0 0 0 2101 +865 900 0.994415152684446 0.0304992232812879 0.101036139528425 -0.00487139681417765 -0.0421638413130754 0.992423067023999 0.115406527217508 -0.0227058937239737 -0.0967507860293392 -0.119022071137742 0.988166500132841 0.0259500582956458 2.57665550884096e-05 -2.68390383973679e-05 2.31745377608916e-06 -1.11395222136498e-05 -4.57753503858988e-06 6.27486933283737e-06 -2.68390383973679e-05 4.87400829463785e-05 1.10576148436655e-06 2.08217887912862e-05 1.16535089309063e-05 2.20979761633956e-06 2.31745377608916e-06 1.10576148436655e-06 9.88190227215001e-06 -1.12116090522706e-06 4.81321736826639e-06 4.2436323942932e-07 -1.11395222136498e-05 2.08217887912862e-05 -1.12116090522706e-06 4.93576169530399e-05 1.40836962580425e-05 9.93711077713179e-06 -4.57753503858988e-06 1.16535089309063e-05 4.81321736826639e-06 1.40836962580425e-05 2.27755652211559e-05 4.94302142342518e-06 6.27486933283737e-06 2.20979761633956e-06 4.2436323942932e-07 9.93711077713179e-06 4.94302142342518e-06 2.52155729437908e-05 893 905 0 47 0 893 905 0 56 0 0 0 0 0 0 0 0 0 2619 0 0 0 0 0 1710 +865 921 0.994429194451126 0.03054700202287 0.100883387585366 -0.00414244092725482 -0.0419692338141926 0.992694936857246 0.113116514050949 -0.0246382715562038 -0.0966910576854658 -0.116720362428342 0.988446860664883 0.0237101079807624 1.82008015558991e-05 -1.47228215932033e-05 2.63099477178259e-06 1.19087274043792e-06 1.16180225218583e-06 3.0264059550245e-06 -1.47228215932033e-05 4.49924594590396e-05 1.57732061415167e-06 6.64314589569733e-06 -1.73265612710392e-06 4.30489724758313e-06 2.63099477178259e-06 1.57732061415167e-06 8.33184418096836e-06 1.27663132479439e-06 1.52574722124381e-06 1.41987692729294e-07 1.19087274043792e-06 6.64314589569733e-06 1.27663132479439e-06 3.81328844406219e-05 5.94200856975111e-06 7.46415165508089e-06 1.16180225218583e-06 -1.73265612710392e-06 1.52574722124381e-06 5.94200856975111e-06 2.3635596661523e-05 2.18916547005531e-06 3.0264059550245e-06 4.30489724758313e-06 1.41987692729294e-07 7.46415165508089e-06 2.18916547005531e-06 2.58891604717711e-05 859 865 0 53 0 859 865 0 63 0 0 0 0 0 0 0 0 0 2552 0 0 0 0 0 2060 +865 925 0.994114264029319 0.0306462605466379 0.103911677726577 -0.00144991747010304 -0.0426760467351454 0.992378675938548 0.115599820836858 -0.0197100617970924 -0.0995770309283421 -0.119353970428141 0.987845658316386 0.0244385023895835 3.59484318204695e-05 -3.85879104700752e-05 6.10139437338845e-06 -2.11885886805059e-05 -1.14545406403935e-05 7.51126087881295e-06 -3.85879104700752e-05 5.48315751873907e-05 -4.22765077764846e-06 3.64099491101543e-05 2.01510863688077e-05 1.69606125011173e-06 6.10139437338845e-06 -4.22765077764846e-06 1.09305192787766e-05 6.29716797654062e-07 4.60245280480201e-06 6.11003081741057e-06 -2.11885886805059e-05 3.64099491101543e-05 6.29716797654062e-07 7.26035049045369e-05 2.62891381369857e-05 1.78683035383735e-05 -1.14545406403935e-05 2.01510863688077e-05 4.60245280480201e-06 2.62891381369857e-05 3.21567480737974e-05 1.22843122572055e-05 7.51126087881295e-06 1.69606125011173e-06 6.11003081741057e-06 1.78683035383735e-05 1.22843122572055e-05 3.44835994639782e-05 867 877 0 42 0 867 877 0 57 0 0 0 0 0 0 0 0 0 2552 0 0 0 0 0 2033 +865 922 0.994084739813058 0.0297871736108454 0.104442588818366 -0.00284738632340504 -0.0419570904816172 0.992323344965551 0.116335641979137 -0.0224026544483519 -0.100175509128341 -0.120029593537002 0.987703277328885 0.0277637360495918 4.18274720293761e-05 -4.56765053413041e-05 -4.45666917502296e-06 -1.59968338928711e-05 -8.64366153163281e-06 1.03238995441644e-05 -4.56765053413041e-05 7.45507879396909e-05 5.87666787534519e-06 4.39980681872782e-05 2.11781844818654e-05 2.53659573611399e-06 -4.45666917502296e-06 5.87666787534519e-06 1.04225275292809e-05 -1.41866035736512e-06 3.13406971663091e-06 -2.49942740116659e-06 -1.59968338928711e-05 4.39980681872782e-05 -1.41866035736512e-06 8.22552423059856e-05 3.05444810131782e-05 1.81831219672224e-05 -8.64366153163281e-06 2.11781844818654e-05 3.13406971663091e-06 3.05444810131782e-05 3.24449922635672e-05 9.94570711624851e-06 1.03238995441644e-05 2.53659573611399e-06 -2.49942740116659e-06 1.81831219672224e-05 9.94570711624851e-06 3.14660116375635e-05 879 887 0 45 0 879 887 0 58 0 0 0 0 0 0 0 0 0 2695 0 0 0 0 0 1820 +865 923 0.994313725465565 0.029887922766316 0.102210211933564 -0.00371360614998203 -0.0417623877820936 0.992360629533158 0.1160873977626 -0.0216791608995143 -0.0979597790806381 -0.119695835454994 0.987965985577036 0.0257994712197884 3.31237653010603e-05 -3.28212619482736e-05 2.07788090471727e-06 -8.54238216914634e-06 -7.72721642889304e-06 1.11236494874484e-05 -3.28212619482736e-05 4.58590825282709e-05 2.05819704547822e-07 2.02372427812628e-05 1.40802382006065e-05 -3.71706336886551e-06 2.07788090471727e-06 2.05819704547822e-07 9.59549537362348e-06 1.02010043632082e-06 4.66853707119997e-06 2.56076333665624e-06 -8.54238216914634e-06 2.02372427812628e-05 1.02010043632082e-06 6.19921389353201e-05 2.04092827144562e-05 1.0125537531909e-05 -7.72721642889304e-06 1.40802382006065e-05 4.66853707119997e-06 2.04092827144562e-05 2.63815962068388e-05 4.99929923687779e-06 1.11236494874484e-05 -3.71706336886551e-06 2.56076333665624e-06 1.0125537531909e-05 4.99929923687779e-06 2.82874147371008e-05 887 899 0 46 0 887 899 0 59 0 0 0 0 0 0 0 0 0 2544 0 0 0 0 0 1844 +865 926 0.994897613599455 0.0310068837240094 0.0960068310894405 -0.00497060291881778 -0.0420550583974996 0.992442056190205 0.115282857217114 -0.022053734719469 -0.0917066547056074 -0.118732212422259 0.988682229645108 0.0269941327406899 4.1147800969813e-05 -5.46502439785775e-05 -3.23486311688991e-06 -1.86288540382328e-05 -1.16408855247529e-05 2.62573494302784e-06 -5.46502439785775e-05 0.000141624640817148 1.10143219164995e-05 6.80867434331597e-05 3.13220373899633e-05 1.9904929618252e-05 -3.23486311688991e-06 1.10143219164995e-05 1.06646976267442e-05 1.59267995578674e-07 5.36841016222708e-06 9.30911875611756e-08 -1.86288540382328e-05 6.80867434331597e-05 1.59267995578674e-07 0.000113842268272966 4.28245729788875e-05 2.92957807143401e-05 -1.16408855247529e-05 3.13220373899633e-05 5.36841016222708e-06 4.28245729788875e-05 3.94770392032976e-05 1.2224518279005e-05 2.62573494302784e-06 1.9904929618252e-05 9.30911875611756e-08 2.92957807143401e-05 1.2224518279005e-05 3.78487190042832e-05 847 855 0 41 0 847 855 0 58 0 0 0 0 0 0 0 0 0 2642 0 0 0 0 0 1709 +865 920 0.994050264726763 0.0296935935301881 0.104796763785515 -0.00359694426750298 -0.0415595314194556 0.992733697529573 0.112927459625447 -0.0266919927852487 -0.100682056717413 -0.116610875532798 0.988061246665725 0.0274333202211604 3.09148897499477e-05 -3.06348374327489e-05 -3.10797938594105e-06 -3.71869193287043e-06 -3.86173443832909e-06 2.43615260193514e-06 -3.06348374327489e-05 6.06262238730129e-05 6.78119691527261e-06 1.70548258360942e-05 8.59265736691452e-06 1.23726406559473e-05 -3.10797938594105e-06 6.78119691527261e-06 1.08888520092451e-05 -2.06017012160901e-06 1.38576599122986e-06 -1.75186288021207e-06 -3.71869193287043e-06 1.70548258360942e-05 -2.06017012160901e-06 5.79396256028684e-05 1.56615834314126e-05 1.59439832527488e-05 -3.86173443832909e-06 8.59265736691452e-06 1.38576599122986e-06 1.56615834314126e-05 3.23911034336515e-05 6.2284613851838e-06 2.43615260193514e-06 1.23726406559473e-05 -1.75186288021207e-06 1.59439832527488e-05 6.2284613851838e-06 3.11490918362528e-05 867 873 0 42 0 867 873 0 55 0 0 0 0 0 0 0 0 0 2418 0 0 0 0 0 1657 +865 901 0.994501841246443 0.0306575341504745 0.10013093107151 -0.00324901316888752 -0.0424355355262568 0.992141876109761 0.117701839382414 -0.0201406471791078 -0.0957356416494649 -0.121303805666666 0.987987891448447 0.0263050226060733 3.59466247663939e-05 -3.67581671422181e-05 -2.60476489401338e-06 -4.75659905645051e-06 -6.63955163380567e-06 1.46927192910314e-05 -3.67581671422181e-05 7.79173083353449e-05 5.76468173567393e-06 3.06555739608872e-05 2.06055036232611e-05 -6.77154945302309e-06 -2.60476489401338e-06 5.76468173567393e-06 9.40764874081693e-06 -8.8305198903819e-07 5.40984598902068e-06 -3.26182769623011e-06 -4.75659905645051e-06 3.06555739608872e-05 -8.8305198903819e-07 5.66040839006117e-05 1.30879465061286e-05 9.21212898243799e-06 -6.63955163380567e-06 2.06055036232611e-05 5.40984598902068e-06 1.30879465061286e-05 2.46831702718412e-05 1.88410685455571e-06 1.46927192910314e-05 -6.77154945302309e-06 -3.26182769623011e-06 9.21212898243799e-06 1.88410685455571e-06 2.9453593467881e-05 842 849 0 47 0 842 849 0 57 0 0 0 0 0 0 0 0 0 2571 0 0 0 0 0 1843 +865 924 0.994712754956295 0.0302884418513583 0.0981282090811523 -0.00568508566431935 -0.0415943603225737 0.992459225690985 0.11530218788126 -0.0232285041131276 -0.0938959227901476 -0.118774137046187 0.988471678932846 0.0268791331722893 4.21561055601091e-05 -4.6151658282234e-05 -2.74383713516952e-06 -1.98655582996781e-05 -1.3293946998067e-05 2.26702776883662e-06 -4.6151658282234e-05 8.42660817276448e-05 7.35317169955155e-06 4.0757095285703e-05 1.96232389317748e-05 1.31271380579562e-05 -2.74383713516952e-06 7.35317169955155e-06 9.4761497847435e-06 1.58912060323427e-06 4.313978023697e-06 1.02228611351804e-06 -1.98655582996781e-05 4.0757095285703e-05 1.58912060323427e-06 6.92525533149761e-05 2.53119802754173e-05 1.57675566828579e-05 -1.3293946998067e-05 1.96232389317748e-05 4.313978023697e-06 2.53119802754173e-05 2.91221401294973e-05 4.26660373060989e-06 2.26702776883662e-06 1.31271380579562e-05 1.02228611351804e-06 1.57675566828579e-05 4.26660373060989e-06 3.42870682366691e-05 851 855 0 43 0 851 855 0 57 0 0 0 0 0 0 0 0 0 2629 0 0 0 0 0 1695 +865 918 0.995056939431238 0.0310344132864716 0.0943321391769695 -0.00808353154342031 -0.0416058136932962 0.992808415699428 0.11225152998205 -0.0282106015414992 -0.0901700812723234 -0.115621429278299 0.989192115584726 0.0257915234597611 4.83034818926897e-05 -5.31950109759744e-05 -7.64035464941702e-06 -5.98397986402681e-06 -1.08876321491417e-05 8.51117683085901e-06 -5.31950109759744e-05 0.000125974116206835 1.06405573136718e-05 5.11402666737795e-05 3.01410091975047e-05 1.64081711777706e-05 -7.64035464941702e-06 1.06405573136718e-05 1.04478484270952e-05 1.45722155413706e-07 4.20012872728521e-06 -4.27968393767155e-06 -5.98397986402681e-06 5.11402666737795e-05 1.45722155413706e-07 6.84534367104408e-05 1.26233091168465e-05 2.4411512527092e-05 -1.08876321491417e-05 3.01410091975047e-05 4.20012872728521e-06 1.26233091168465e-05 3.29721803213708e-05 8.2592072566155e-06 8.51117683085901e-06 1.64081711777706e-05 -4.27968393767155e-06 2.4411512527092e-05 8.2592072566155e-06 3.70132597525941e-05 859 870 0 54 0 859 870 0 70 0 0 0 0 0 0 0 0 0 2372 0 0 0 0 0 1657 +865 896 0.994975198837056 0.031164506258723 0.0951479229873697 -0.00651223063397845 -0.0419489403435694 0.992647831430908 0.11353664236522 -0.0226400794274718 -0.0909100660169823 -0.116957497857838 0.988967291467024 0.0236621259608644 4.20645825433024e-05 -5.272664325722e-05 -2.78152548077807e-06 -2.22629994117253e-05 -1.65629566797105e-05 9.39358782427459e-07 -5.272664325722e-05 0.000110400410178297 7.3879445261692e-06 5.64627518355934e-05 3.24110397391187e-05 1.31213481216749e-05 -2.78152548077807e-06 7.3879445261692e-06 9.73736676652673e-06 2.84888809564075e-06 5.40202673506807e-06 -4.80102445608626e-07 -2.22629994117253e-05 5.64627518355934e-05 2.84888809564075e-06 8.0527520174841e-05 2.72001688729473e-05 1.90363167772203e-05 -1.65629566797105e-05 3.24110397391187e-05 5.40202673506807e-06 2.72001688729473e-05 3.10208938587625e-05 7.19841727851166e-06 9.39358782427459e-07 1.31213481216749e-05 -4.80102445608626e-07 1.90363167772203e-05 7.19841727851166e-06 3.19926182103072e-05 855 866 0 47 0 855 866 0 61 0 0 0 0 0 0 0 0 0 2624 0 0 0 0 0 2075 +865 927 0.994824315055446 0.0307511838373752 0.0968449630443544 -0.00361562705875485 -0.041971939342181 0.992356512605219 0.116047008569223 -0.0218171313689237 -0.0925361468957872 -0.119511156728604 0.98851107476602 0.026936735474733 4.62277290100956e-05 -5.75514543733381e-05 -7.92929212026132e-06 -9.44363077729204e-06 -4.97005055963367e-06 6.67152249223537e-06 -5.75514543733381e-05 0.000136436367728674 1.48776023606387e-05 4.99771731074877e-05 1.87626872204201e-05 1.1385081694001e-05 -7.92929212026132e-06 1.48776023606387e-05 1.13810553808586e-05 2.65473290175575e-06 4.97883160014449e-06 -2.19210726965093e-06 -9.44363077729204e-06 4.99771731074877e-05 2.65473290175575e-06 6.41265861370529e-05 1.29532693467698e-05 1.72596789853056e-05 -4.97005055963367e-06 1.87626872204201e-05 4.97883160014449e-06 1.29532693467698e-05 2.38038687416233e-05 6.72753520645544e-06 6.67152249223537e-06 1.1385081694001e-05 -2.19210726965093e-06 1.72596789853056e-05 6.72753520645544e-06 3.43645472056073e-05 848 858 0 41 0 848 858 0 55 0 0 0 0 0 0 0 0 0 2654 0 0 0 0 0 1691 +865 892 0.994469406230777 0.030464459334153 0.100511276921961 -0.00255365563693432 -0.0420110340900087 0.992495094352964 0.114841458977103 -0.0212295883216925 -0.0962583663153162 -0.118428900200835 0.988285850607772 0.0271708726193034 3.75818226145878e-05 -3.43401027286537e-05 -1.17526326318408e-06 -7.88483382308244e-06 -6.84604807263229e-06 1.15126488690914e-05 -3.43401027286537e-05 4.39197209870508e-05 3.21433147715365e-06 1.39159643357338e-05 9.72682791494553e-06 -4.34409935213254e-06 -1.17526326318408e-06 3.21433147715365e-06 9.45720231193565e-06 8.50240317852414e-07 4.19475080932894e-06 -3.23598457482275e-08 -7.88483382308244e-06 1.39159643357338e-05 8.50240317852414e-07 4.59073779064279e-05 1.27385214825178e-05 9.01277616802085e-06 -6.84604807263229e-06 9.72682791494553e-06 4.19475080932894e-06 1.27385214825178e-05 2.28794707178071e-05 5.40156386309701e-06 1.15126488690914e-05 -4.34409935213254e-06 -3.23598457482275e-08 9.01277616802085e-06 5.40156386309701e-06 2.98159231521986e-05 900 914 0 50 0 900 914 0 62 0 0 0 0 0 0 0 0 0 2709 0 0 0 0 0 1829 +865 928 0.995532447959311 0.0306668852554357 0.0893011041861836 -0.0122804788885435 -0.0409567114496677 0.992430508975701 0.115776649810999 -0.0237175462684134 -0.0850746310445737 -0.118916891159162 0.989252788800552 0.0267609359971814 3.36242359738552e-05 -3.72521619716072e-05 -2.57447594536495e-06 -3.65098254581794e-06 -2.03388423556794e-06 8.18983671463472e-06 -3.72521619716072e-05 9.51023023989358e-05 7.75227629762845e-06 2.8739565232394e-05 1.2403469094547e-05 2.3931894828383e-06 -2.57447594536495e-06 7.75227629762845e-06 9.85325407301373e-06 -6.72456614834693e-07 4.81395840444591e-06 -1.79055719852319e-06 -3.65098254581794e-06 2.8739565232394e-05 -6.72456614834693e-07 5.2756873884203e-05 1.10539887820431e-05 1.28163017243161e-05 -2.03388423556794e-06 1.2403469094547e-05 4.81395840444591e-06 1.10539887820431e-05 2.30650558073173e-05 4.20689095029125e-06 8.18983671463472e-06 2.3931894828383e-06 -1.79055719852319e-06 1.28163017243161e-05 4.20689095029125e-06 3.12985324342023e-05 855 866 0 45 0 855 866 0 59 0 0 0 0 0 0 0 0 0 2584 0 0 0 0 0 1793 +865 919 0.994716516734596 0.0305154023745052 0.0980196998226043 -0.00670211382908456 -0.0418015632288086 0.9924581513267 0.115236483705542 -0.0255159453234841 -0.0937639624110422 -0.118725010352123 0.988490106814362 0.0273201996196238 4.36161776346801e-05 -4.54074416638295e-05 -3.53749652796855e-06 -6.73276205897417e-06 -9.75977553836068e-06 5.38482113480763e-06 -4.54074416638295e-05 8.48486151280178e-05 4.70848930685295e-06 3.106631793674e-05 1.91832748423937e-05 1.63853202090966e-05 -3.53749652796855e-06 4.70848930685295e-06 1.03480067319416e-05 -1.32677829635417e-06 1.89015809603681e-06 -1.30688643178158e-06 -6.73276205897417e-06 3.106631793674e-05 -1.32677829635417e-06 5.75474123944774e-05 1.25932597389216e-05 1.98128577376439e-05 -9.75977553836068e-06 1.91832748423937e-05 1.89015809603681e-06 1.25932597389216e-05 3.44602552328049e-05 7.4403710138089e-06 5.38482113480763e-06 1.63853202090966e-05 -1.30688643178158e-06 1.98128577376439e-05 7.4403710138089e-06 3.89814207911337e-05 876 886 0 40 0 876 886 0 54 0 0 0 0 0 0 0 0 0 2430 0 0 0 0 0 1803 +865 915 0.995120188676939 0.0312403930004906 0.0935940592812827 -0.00652685097783353 -0.0420068441215422 0.992434120637211 0.115368718645891 -0.0224352830881164 -0.0892817738092261 -0.118737332125247 0.988903539697001 0.0262351752622708 4.10435561100778e-05 -4.67770658846202e-05 -2.70323386815833e-06 -2.0064111712007e-05 -1.08233107206674e-05 2.47784649802643e-06 -4.67770658846202e-05 9.33455108585855e-05 8.50059468946844e-06 4.14328005448083e-05 1.77799247239552e-05 1.34528202570358e-05 -2.70323386815833e-06 8.50059468946844e-06 9.76593686959254e-06 7.08224202820084e-07 4.11104182039178e-06 -5.22820376859334e-07 -2.0064111712007e-05 4.14328005448083e-05 7.08224202820084e-07 6.35685795649395e-05 1.75544962739044e-05 2.12379673466123e-05 -1.08233107206674e-05 1.77799247239552e-05 4.11104182039178e-06 1.75544962739044e-05 2.36816413508455e-05 7.2118489066585e-06 2.47784649802643e-06 1.34528202570358e-05 -5.22820376859334e-07 2.12379673466123e-05 7.2118489066585e-06 3.43111925771982e-05 859 863 0 38 0 859 863 0 52 0 0 0 0 0 0 0 0 0 2677 0 0 0 0 0 1679 +865 897 0.994466382519107 0.0303187094179411 0.100585236981336 -0.00567098994077683 -0.0419416381128632 0.992417996377201 0.115531032450469 -0.0221814458713125 -0.0963198475485229 -0.119110437518683 0.988197951142552 0.0252008522380115 3.57210180283848e-05 -3.34653888406325e-05 -2.15998302764969e-07 -7.08774216236137e-06 -4.64129501166849e-06 1.0887987789394e-05 -3.34653888406325e-05 3.96653319415753e-05 1.81812848820798e-06 1.2263673764489e-05 7.49690556254979e-06 -6.24490180573612e-06 -2.15998302764969e-07 1.81812848820798e-06 9.42826288675637e-06 5.32087595095103e-07 4.74396170882912e-06 8.89339639635124e-07 -7.08774216236137e-06 1.2263673764489e-05 5.32087595095103e-07 4.80503349520157e-05 1.68229688633908e-05 1.39211698569434e-05 -4.64129501166849e-06 7.49690556254979e-06 4.74396170882912e-06 1.68229688633908e-05 2.60269192354949e-05 8.33885947472736e-06 1.0887987789394e-05 -6.24490180573612e-06 8.89339639635124e-07 1.39211698569434e-05 8.33885947472736e-06 2.7702484758216e-05 888 893 0 37 0 888 893 0 47 0 0 0 0 0 0 0 0 0 2561 0 0 0 0 0 1687 +865 902 0.994873352956129 0.0311607113283311 0.0962082202690714 -0.00339353236004775 -0.0423539702453056 0.992276790901808 0.116588641994278 -0.0197603296238627 -0.0918321990496226 -0.120065733276079 0.988509517865452 0.0267576815185966 3.64489687684572e-05 -4.26529351602565e-05 -5.09973608804605e-06 -5.34211562394873e-06 -5.08195816583023e-06 8.510877193125e-06 -4.26529351602565e-05 0.00011309747992575 9.22398433211465e-06 5.29952692051959e-05 2.40428285035374e-05 3.22596183453313e-06 -5.09973608804605e-06 9.22398433211465e-06 1.02822083819731e-05 -4.85544362691306e-07 5.63446790526214e-06 -2.25321053004717e-06 -5.34211562394873e-06 5.29952692051959e-05 -4.85544362691306e-07 7.90021537466374e-05 2.21073321175438e-05 1.57357651117557e-05 -5.08195816583023e-06 2.40428285035374e-05 5.63446790526214e-06 2.21073321175438e-05 2.51401946312539e-05 5.30351866415562e-06 8.510877193125e-06 3.22596183453313e-06 -2.25321053004717e-06 1.57357651117557e-05 5.30351866415562e-06 2.97103335833023e-05 859 867 0 42 0 859 867 0 50 0 0 0 0 0 0 0 0 0 2718 0 0 0 0 0 1847 +866 868 0.999151756768901 0.032108400572133 0.0257840562813339 0.00855109625973936 -0.0318363709103322 0.999433739104645 -0.0108925032278628 -0.00361653024217089 -0.0261191966354117 0.0100623929563847 0.999608191150469 0.00251269860276848 4.16369324565926e-05 -5.47473370394328e-05 2.20349078592461e-07 -2.17650088234186e-05 -1.58180398372392e-05 2.45486679063807e-05 -5.47473370394328e-05 0.000110562614711249 -2.54510304306006e-06 8.10093297347868e-05 4.45388273581206e-05 -3.87159184261619e-05 2.20349078592461e-07 -2.54510304306006e-06 9.7335635449196e-06 -6.43842574689438e-06 -9.2207120080722e-07 -1.35260929044665e-06 -2.17650088234186e-05 8.10093297347868e-05 -6.43842574689438e-06 0.000131362255499298 4.87705562052202e-05 -2.08118487075803e-05 -1.58180398372392e-05 4.45388273581206e-05 -9.2207120080722e-07 4.87705562052202e-05 4.43067361192262e-05 -1.28237233536543e-05 2.45486679063807e-05 -3.87159184261619e-05 -1.35260929044665e-06 -2.08118487075803e-05 -1.28237233536543e-05 4.40807360876359e-05 856 857 0 30 0 856 857 0 45 0 0 0 0 0 0 0 0 0 2273 0 0 0 0 0 2032 +865 916 0.994757609556301 0.0316034968263138 0.0972549084529065 0.00107555043544804 -0.0428219946562629 0.992381824856332 0.115518788378669 -0.0182046369793968 -0.0928632058648259 -0.119077842956471 0.98853269663342 0.0266897323185511 2.91256994253648e-05 -2.64579639385999e-05 -1.61354432593593e-06 -6.62982334671019e-06 -8.56288454274461e-07 8.95549765707569e-06 -2.64579639385999e-05 4.84693656097107e-05 4.87587881520873e-06 1.04808544346657e-05 9.78494674919397e-07 3.41467150977509e-06 -1.61354432593593e-06 4.87587881520873e-06 9.4240659647034e-06 -1.90045582478875e-06 2.12952073266574e-06 -1.20161111411453e-06 -6.62982334671019e-06 1.04808544346657e-05 -1.90045582478875e-06 4.84821883900514e-05 1.26502639877915e-05 7.30698151651474e-06 -8.56288454274461e-07 9.78494674919397e-07 2.12952073266574e-06 1.26502639877915e-05 2.65710587096262e-05 4.50741237282013e-06 8.95549765707569e-06 3.41467150977509e-06 -1.20161111411453e-06 7.30698151651474e-06 4.50741237282013e-06 3.07665823988433e-05 872 878 0 40 0 872 878 0 51 0 0 0 0 0 0 0 0 0 2540 0 0 0 0 0 1802 +865 914 0.993940121930947 0.0302295738330045 0.105684468498301 -0.000622900562536831 -0.0425890995529794 0.992251064730035 0.11672186231113 -0.020981715904236 -0.101337074238207 -0.12051554840761 0.987525594593301 0.0249676598045476 2.4630184989574e-05 -2.75733820192354e-05 1.03504099994123e-06 -6.22063575369313e-06 -1.41145187120295e-06 9.48545748355791e-07 -2.75733820192354e-05 6.51608766953753e-05 3.39067674686171e-06 2.19791278034964e-05 1.02662450681778e-05 1.22800045214933e-05 1.03504099994123e-06 3.39067674686171e-06 8.43436641735253e-06 -8.91435988234343e-07 4.1875548749833e-06 5.45194786821823e-07 -6.22063575369313e-06 2.19791278034964e-05 -8.91435988234343e-07 5.42925006351649e-05 1.3365876446268e-05 9.28099554105174e-06 -1.41145187120295e-06 1.02662450681778e-05 4.1875548749833e-06 1.3365876446268e-05 2.21093869847281e-05 6.7197521637967e-06 9.48545748355791e-07 1.22800045214933e-05 5.45194786821823e-07 9.28099554105174e-06 6.7197521637967e-06 2.90862236981452e-05 890 901 0 45 0 890 901 0 59 0 0 0 0 0 0 0 0 0 2719 0 0 0 0 0 1712 +865 917 0.995006088961246 0.0315831343227066 0.0946857357599288 0.00202477717434738 -0.0426373134360601 0.992204749803786 0.117097369610774 -0.0171452879222499 -0.0902493348064148 -0.120549741157586 0.988596387548447 0.0251172040686094 4.77288865197757e-05 -5.73433573712371e-05 -1.10218327251809e-06 -2.76360860237644e-05 -2.22989946218363e-05 4.65138768366106e-06 -5.73433573712371e-05 0.00017119867755834 1.10179713748728e-05 8.60689945514536e-05 3.69008367952039e-05 2.31524675446205e-05 -1.10218327251809e-06 1.10179713748728e-05 1.15178302690279e-05 -1.90780688640168e-06 2.29594594172548e-06 1.83697107314061e-06 -2.76360860237644e-05 8.60689945514536e-05 -1.90780688640168e-06 0.000130385042103559 5.27966840375686e-05 2.00289845713742e-05 -2.22989946218363e-05 3.69008367952039e-05 2.29594594172548e-06 5.27966840375686e-05 5.9951684495419e-05 2.96282770489181e-06 4.65138768366106e-06 2.31524675446205e-05 1.83697107314061e-06 2.00289845713742e-05 2.96282770489181e-06 4.24364849558013e-05 855 864 0 47 0 855 864 0 57 0 0 0 0 0 0 0 0 0 2277 0 0 0 0 0 1700 +866 922 0.995848556479434 0.0286660861366764 0.086393912189642 -0.00258638201808099 -0.0386887467043892 0.992417111385982 0.116668152924215 -0.0193575722251209 -0.0823943774554461 -0.119526283862208 0.989406202744768 0.0254300831876609 2.3590690644333e-05 -2.72761365866333e-05 5.60944358745751e-07 -7.06078379925586e-06 -3.38409611918248e-06 5.66971039863339e-06 -2.72761365866333e-05 7.52371243457953e-05 5.97065670593541e-06 1.77989499024356e-05 7.75487801515337e-06 4.96585565692067e-06 5.60944358745751e-07 5.97065670593541e-06 9.91045081334342e-06 -4.16949355811757e-07 3.98291142371446e-06 -5.64553716486736e-07 -7.06078379925586e-06 1.77989499024356e-05 -4.16949355811757e-07 4.65251833099325e-05 7.31206843874963e-06 2.61702168350388e-06 -3.38409611918248e-06 7.75487801515337e-06 3.98291142371446e-06 7.31206843874963e-06 2.16825657192549e-05 2.35784128481969e-06 5.66971039863339e-06 4.96585565692067e-06 -5.64553716486736e-07 2.61702168350388e-06 2.35784128481969e-06 2.9082345097028e-05 868 875 0 42 0 868 875 0 55 0 0 0 0 0 0 0 0 0 2694 0 0 0 0 0 1981 +865 903 0.994303614543592 0.0306087948928134 0.102095170212686 -0.000860231129492589 -0.0425149702948657 0.992272928910411 0.116562909419682 -0.019874565035174 -0.0977384233880121 -0.120239495286549 0.987921891835008 0.02797166225476 3.85208432711433e-05 -4.00576942454973e-05 -4.97427947769748e-06 -8.18560370819268e-06 -4.26301472146921e-06 7.17702897040607e-06 -4.00576942454973e-05 6.25954802356269e-05 9.19179327223302e-06 2.08221836152162e-05 1.04022951451876e-05 5.94235873554601e-06 -4.97427947769748e-06 9.19179327223302e-06 1.11469986769191e-05 -1.29129927662283e-06 4.29479976233952e-06 -9.01100159966181e-07 -8.18560370819268e-06 2.08221836152162e-05 -1.29129927662283e-06 5.11417138076948e-05 1.34747549964325e-05 1.38126321406818e-05 -4.26301472146921e-06 1.04022951451876e-05 4.29479976233952e-06 1.34747549964325e-05 2.22476044009562e-05 6.75308074099329e-06 7.17702897040607e-06 5.94235873554601e-06 -9.01100159966181e-07 1.38126321406818e-05 6.75308074099329e-06 3.5416909423841e-05 866 878 0 46 0 866 878 0 58 0 0 0 0 0 0 0 0 0 2626 0 0 0 0 0 1726 +866 898 0.995396296794559 0.0286616598862702 0.0914588518419148 -0.0016781089341952 -0.0394963826763072 0.992114541481998 0.11894861216278 -0.0153725253967834 -0.0873283921938578 -0.122013301867167 0.988679172474219 0.0277102514847088 4.23835547504503e-05 -4.57702085032086e-05 -2.76829804314371e-06 -9.78922634654711e-06 -8.23489431742794e-06 1.72064606763863e-06 -4.57702085032086e-05 8.17849423460642e-05 7.14044589534306e-06 2.80609851727882e-05 1.83781359211886e-05 1.57594797385742e-05 -2.76829804314371e-06 7.14044589534306e-06 1.0774235305413e-05 -5.56794560874622e-08 4.62444586820671e-06 -7.29819944786246e-07 -9.78922634654711e-06 2.80609851727882e-05 -5.56794560874622e-08 5.81925572372375e-05 1.70412654468249e-05 1.78394273350231e-05 -8.23489431742794e-06 1.83781359211886e-05 4.62444586820671e-06 1.70412654468249e-05 2.58876241272932e-05 1.17386860306423e-05 1.72064606763863e-06 1.57594797385742e-05 -7.29819944786246e-07 1.78394273350231e-05 1.17386860306423e-05 3.85075315425043e-05 821 830 0 43 0 820 830 0 53 0 0 0 0 0 0 0 0 0 2706 0 0 0 0 0 1649 +866 925 0.995707757654263 0.0293999332329922 0.0877593600308012 -0.00017416195382601 -0.0396694428461999 0.992259892764724 0.117671749008885 -0.0170765122219777 -0.083620551608993 -0.120648038261853 0.989167151806091 0.0284112782287834 3.35899231929867e-05 -4.30078747216891e-05 1.43347274708848e-06 -1.74483064415758e-05 -9.4182525018987e-06 2.83809303386352e-07 -4.30078747216891e-05 8.94700028821977e-05 4.50993812289743e-06 4.34361147121112e-05 2.54528895003783e-05 1.84550239355743e-05 1.43347274708848e-06 4.50993812289743e-06 9.86682265539309e-06 1.6181231439905e-06 6.54651752515544e-06 2.07014365454769e-06 -1.74483064415758e-05 4.34361147121112e-05 1.6181231439905e-06 6.97094877244827e-05 2.04722099447948e-05 1.72074988216911e-05 -9.4182525018987e-06 2.54528895003783e-05 6.54651752515544e-06 2.04722099447948e-05 2.862561184432e-05 1.12463224727852e-05 2.83809303386352e-07 1.84550239355743e-05 2.07014365454769e-06 1.72074988216911e-05 1.12463224727852e-05 3.46047053532032e-05 877 889 0 41 0 876 889 0 56 0 0 0 0 0 0 0 0 0 2562 0 0 0 0 0 1711 +866 930 0.989982894839073 -0.054648172245438 0.130182353628598 -0.0200937940107831 0.0369666670203675 0.990215895611389 0.134558335334309 -0.01805431415972 -0.136262002977549 -0.12839804262047 0.982316959639697 -0.0224961481009744 3.26879774041728e-05 -3.26235906723429e-05 -3.43158555844751e-06 -4.48568900909554e-06 -3.78316404016503e-06 5.60952330786358e-06 -3.26235906723429e-05 4.92653409584418e-05 5.11226182970375e-06 1.5477108121295e-05 7.53209812075548e-06 3.37913942307602e-06 -3.43158555844751e-06 5.11226182970375e-06 9.99998563468944e-06 -7.31336644592954e-08 2.84543755650732e-06 -1.81972494584717e-06 -4.48568900909554e-06 1.5477108121295e-05 -7.31336644592954e-08 4.68847397016671e-05 4.53929890771753e-06 1.45345160876795e-05 -3.78316404016503e-06 7.53209812075548e-06 2.84543755650732e-06 4.53929890771753e-06 1.82982571407627e-05 3.7231196962439e-06 5.60952330786358e-06 3.37913942307602e-06 -1.81972494584717e-06 1.45345160876795e-05 3.7231196962439e-06 3.5423776456553e-05 1036 1036 0 0 0 1042 1042 0 0 0 0 0 0 0 0 63 69 0 2793 0 0 0 0 0 1558 +866 869 0.99848442000185 0.0429579855023362 0.0344016641334544 0.00683953294896126 -0.042845377696245 0.999073690984731 -0.00400419682483415 -0.00672132343642057 -0.034541809790977 0.00252417585104055 0.999400065995914 0.000355651607402754 2.56769487724584e-05 -3.10825006635134e-05 2.06639520374092e-06 -1.24066727917325e-05 -6.55518732781293e-06 1.18720215667234e-05 -3.10825006635134e-05 5.46845903055427e-05 -1.71372805882088e-06 3.36288754656876e-05 1.95790734801916e-05 -1.11880172260552e-05 2.06639520374092e-06 -1.71372805882088e-06 7.86329293218218e-06 1.26879523803357e-07 1.85523990939406e-06 -8.48088799998419e-07 -1.24066727917325e-05 3.36288754656876e-05 1.26879523803357e-07 6.73484503374741e-05 2.62272539098275e-05 1.78118585661383e-06 -6.55518732781293e-06 1.95790734801916e-05 1.85523990939406e-06 2.62272539098275e-05 2.79912379161328e-05 2.55663895454552e-07 1.18720215667234e-05 -1.11880172260552e-05 -8.48088799998419e-07 1.78118585661383e-06 2.55663895454552e-07 2.16184741672023e-05 855 861 0 59 0 855 861 0 63 0 0 0 0 0 0 0 0 0 2250 0 0 0 0 0 2433 +866 870 0.998999418917826 0.043243645889152 0.0114082466689362 0.00338850317342597 -0.0431477989656437 0.99903238651519 -0.00851810649051441 -0.0116295299933366 -0.0117655618763432 0.00801734270048232 0.999898641748131 0.00854270061653989 2.71671971624278e-05 -2.72559119393077e-05 3.16388005458666e-06 -5.34494303359138e-06 -3.06987367689795e-06 1.4506312609811e-05 -2.72559119393077e-05 4.39396585687155e-05 -2.46033870906214e-06 1.884658503503e-05 1.15138025623497e-05 -1.26248103922393e-05 3.16388005458666e-06 -2.46033870906214e-06 8.47714453543356e-06 5.31554931855579e-07 3.60379526012543e-06 1.30277040304287e-06 -5.34494303359138e-06 1.884658503503e-05 5.31554931855579e-07 5.10729549065955e-05 1.33827076275902e-05 -8.46730041519171e-07 -3.06987367689795e-06 1.15138025623497e-05 3.60379526012543e-06 1.33827076275902e-05 2.54226847774367e-05 7.23680882405268e-07 1.4506312609811e-05 -1.26248103922393e-05 1.30277040304287e-06 -8.46730041519171e-07 7.23680882405268e-07 2.71843524622867e-05 885 895 0 45 0 885 895 0 57 0 0 0 0 0 0 0 0 0 2238 0 0 0 0 0 2694 +866 921 0.995649254665395 0.0285552793113892 0.0886969994289146 -0.00248965480892683 -0.0388700625258775 0.992390328681825 0.116835584382555 -0.0196171365784942 -0.084685771670799 -0.119774920422547 0.989182636581483 0.0268875540164248 3.15884664215666e-05 -3.74516751254201e-05 2.10183650257384e-06 -1.01889604232836e-05 -8.6052614948215e-06 1.86595462940229e-06 -3.74516751254201e-05 8.72842036841258e-05 2.58881086120633e-06 3.7988337949621e-05 2.17262204151304e-05 1.70137954600175e-05 2.10183650257384e-06 2.58881086120633e-06 9.53475582506322e-06 1.27510494589914e-06 4.20600180258016e-06 2.24537236021554e-06 -1.01889604232836e-05 3.7988337949621e-05 1.27510494589914e-06 6.59975643445616e-05 1.99096230801613e-05 2.00105780286452e-05 -8.6052614948215e-06 2.17262204151304e-05 4.20600180258016e-06 1.99096230801613e-05 2.97669994220278e-05 1.11785641754907e-05 1.86595462940229e-06 1.70137954600175e-05 2.24537236021554e-06 2.00105780286452e-05 1.11785641754907e-05 3.59664942013768e-05 842 848 0 48 0 842 848 0 57 0 0 0 0 0 0 0 0 0 2556 0 0 0 0 0 1664 +866 929 0.99598482890589 0.00638124973188553 0.0892944580652401 -0.00884623748261616 -0.0184489658769112 0.990676292860558 0.134981918871135 -0.020563880019516 -0.0876005493554588 -0.136087333782099 0.9868162855044 0.0214734117005771 1.87791274868762e-05 -1.57552792250432e-05 9.26425103882596e-07 5.14730464431285e-06 9.54741480936018e-07 2.2090653198561e-06 -1.57552792250432e-05 6.21847485639931e-05 6.83611074399615e-06 4.50223003736628e-06 1.79400765518774e-06 1.01138724493545e-06 9.26425103882596e-07 6.83611074399615e-06 9.57123723284937e-06 1.15842782024579e-06 2.64608126226102e-06 -2.42235153003066e-07 5.14730464431285e-06 4.50223003736628e-06 1.15842782024579e-06 3.28645395706572e-05 4.24122599174037e-07 4.51269749195152e-06 9.54741480936018e-07 1.79400765518774e-06 2.64608126226102e-06 4.24122599174037e-07 2.14211073927263e-05 -1.35382697046217e-06 2.2090653198561e-06 1.01138724493545e-06 -2.42235153003066e-07 4.51269749195152e-06 -1.35382697046217e-06 2.16735116186953e-05 865 876 0 29 0 864 878 0 41 0 0 0 0 0 0 0 7 0 2727 0 0 0 0 0 2109 +866 920 0.995636706076518 0.0280795895176237 0.0889892474719488 -0.00333403511921397 -0.0383487468328115 0.992523028928357 0.115876704575308 -0.0234061684956326 -0.0850701071437842 -0.118783726576505 0.989269176296898 0.0275933071886889 4.21570661562497e-05 -4.76661542574898e-05 -5.01409688734765e-06 -6.15515328017948e-06 -7.74929560249156e-06 -1.13500526145995e-06 -4.76661542574898e-05 9.54444170257883e-05 9.14237696676156e-06 3.01761543571979e-05 2.00890763927827e-05 2.29390151015747e-05 -5.01409688734765e-06 9.14237696676156e-06 1.1912530021282e-05 -5.05527016138244e-07 5.45016811526572e-06 -2.44083645257545e-07 -6.15515328017948e-06 3.01761543571979e-05 -5.05527016138244e-07 6.12898025616357e-05 1.28845679991346e-05 1.64263961731683e-05 -7.74929560249156e-06 2.00890763927827e-05 5.45016811526572e-06 1.28845679991346e-05 2.82458814228843e-05 9.83554571731598e-06 -1.13500526145995e-06 2.29390151015747e-05 -2.44083645257545e-07 1.64263961731683e-05 9.83554571731598e-06 4.20947222100927e-05 826 834 0 41 0 825 834 0 55 0 0 0 0 0 0 0 0 0 2394 0 0 0 0 0 1697 +866 923 0.996287650224426 0.016782676806966 0.0844349440071205 -0.00217911658305269 -0.0266395143995613 0.992774112894063 0.117003833441307 -0.0263684739574247 -0.0818611891121074 -0.118818780193194 0.989535670499327 0.0273147512186943 5.1051379172454e-05 -3.09189490965082e-06 -0.000238159401644214 -5.58267760901494e-05 9.84767861782119e-05 3.33204013044918e-06 -3.09189490965082e-06 8.51673474151628e-05 -0.00021503836712124 -3.26235416165816e-05 8.72580037654059e-05 3.90445921124353e-06 -0.000238159401644214 -0.00021503836712124 0.00233563177433463 0.000452994994562886 -0.000973660611456709 -4.2097914088498e-06 -5.58267760901494e-05 -3.26235416165816e-05 0.000452994994562886 0.000180903027961906 -0.000155746446161268 6.41326497617241e-06 9.84767861782119e-05 8.72580037654059e-05 -0.000973660611456709 -0.000155746446161268 0.000512358721813729 4.60921167470448e-06 3.33204013044918e-06 3.90445921124353e-06 -4.2097914088498e-06 6.41326497617241e-06 4.60921167470448e-06 2.51642317283075e-05 844 856 0 41 0 843 856 0 54 0 0 0 0 0 0 0 0 0 2532 0 0 0 0 0 1975 +866 928 0.995563593891022 0.0285920555942648 0.0896416469933801 -0.00181398970779683 -0.039149272921765 0.992203387513591 0.118320633180576 -0.0188760399635319 -0.0855597156872815 -0.121305120104016 0.988920928531731 0.0285473724049152 2.7489201650211e-05 -2.64719289425197e-05 -2.62927534557428e-06 -7.8962902426174e-07 -1.10686234497788e-06 5.51150849140274e-06 -2.64719289425197e-05 4.49508943919514e-05 5.42735486897654e-06 7.23644823336088e-06 3.5021803715668e-06 4.27085591696121e-06 -2.62927534557428e-06 5.42735486897654e-06 9.66821244763613e-06 -9.71494668138127e-07 4.2928578522999e-06 -5.41723462488437e-07 -7.8962902426174e-07 7.23644823336088e-06 -9.71494668138127e-07 3.71884290838425e-05 4.25864391341586e-06 8.74529513339705e-06 -1.10686234497788e-06 3.5021803715668e-06 4.2928578522999e-06 4.25864391341586e-06 2.20141251517268e-05 3.28828236471357e-06 5.51150849140274e-06 4.27085591696121e-06 -5.41723462488437e-07 8.74529513339705e-06 3.28828236471357e-06 2.94437624168814e-05 850 862 0 47 0 849 862 0 59 0 0 0 0 0 0 1 0 0 2564 0 0 0 0 0 2011 +866 899 0.996033374352483 0.0292083899638805 0.0840499085765318 -0.0054636421196046 -0.039044480526831 0.992260719986229 0.117873627723933 -0.0179618008762486 -0.0799565239139083 -0.120687752187736 0.989465219578473 0.0259390800896444 2.0086497972382e-05 -1.90370732657361e-05 2.02726270383149e-06 1.58327641826376e-06 1.10901227536344e-06 8.65640625024804e-06 -1.90370732657361e-05 4.06094893119527e-05 1.15231391111459e-06 3.38410319257176e-06 1.75448469147982e-06 -1.6517292530594e-06 2.02726270383149e-06 1.15231391111459e-06 8.62284691275437e-06 5.55887161397693e-07 4.65321953225435e-06 7.51744165559522e-07 1.58327641826376e-06 3.38410319257176e-06 5.55887161397693e-07 3.22643572769954e-05 3.69313095559301e-06 2.02780939835708e-06 1.10901227536344e-06 1.75448469147982e-06 4.65321953225435e-06 3.69313095559301e-06 1.69810166344178e-05 3.46438554538678e-06 8.65640625024804e-06 -1.6517292530594e-06 7.51744165559522e-07 2.02780939835708e-06 3.46438554538678e-06 2.41769038097444e-05 884 895 0 47 0 883 895 0 56 0 0 0 0 0 0 0 0 0 2733 0 0 0 0 0 1998 +866 924 0.995536029584211 0.0283316407598795 0.0900296169688558 -0.00203760919378182 -0.0388605431978502 0.992319414655948 0.117439505615633 -0.018922840663197 -0.0860108829281143 -0.120413858956224 0.988990713095526 0.0290362677022841 2.86034373736777e-05 -3.2160922882741e-05 -5.27168322967268e-07 -4.48040973117276e-07 -9.50749531513669e-07 3.66220975962666e-06 -3.2160922882741e-05 7.25144979500336e-05 6.10050537299621e-06 1.54169973484942e-05 9.57133014015999e-06 8.08159536706997e-06 -5.27168322967268e-07 6.10050537299621e-06 1.0319796234499e-05 -4.47419712548817e-07 5.30170769698821e-06 5.6400670647753e-07 -4.48040973117276e-07 1.54169973484942e-05 -4.47419712548817e-07 4.77988875461783e-05 6.27369619179673e-06 1.03602883311537e-05 -9.50749531513669e-07 9.57133014015999e-06 5.30170769698821e-06 6.27369619179673e-06 2.19347699302405e-05 4.95513197521357e-06 3.66220975962666e-06 8.08159536706997e-06 5.6400670647753e-07 1.03602883311537e-05 4.95513197521357e-06 3.2164233917145e-05 825 830 0 38 0 825 830 0 54 0 0 0 0 0 0 1 0 0 2635 0 0 0 0 0 1868 +866 926 0.995339056329246 0.0286996707352492 0.0920678654324849 0.000720185146606712 -0.039553920521803 0.992186553249991 0.118327219697146 -0.0166774096387469 -0.0879525458242157 -0.121417348223349 0.988697212109678 0.0299526243308129 2.58741378031945e-05 -3.06253875008466e-05 3.31262534551209e-07 -5.81181550549396e-06 -2.82501996958692e-06 3.09519345776938e-06 -3.06253875008466e-05 7.25415799197714e-05 4.74665036991597e-06 2.14855719824636e-05 8.42751002329985e-06 1.4741769565375e-05 3.31262534551209e-07 4.74665036991597e-06 9.76771218721011e-06 -2.42932489025211e-07 4.14173581581713e-06 1.64003044859217e-06 -5.81181550549396e-06 2.14855719824636e-05 -2.42932489025211e-07 4.85908514002089e-05 9.95406631143533e-06 1.31577865228996e-05 -2.82501996958692e-06 8.42751002329985e-06 4.14173581581713e-06 9.95406631143533e-06 2.21992983162211e-05 5.6397734884314e-06 3.09519345776938e-06 1.4741769565375e-05 1.64003044859217e-06 1.31577865228996e-05 5.6397734884314e-06 3.25132688354208e-05 856 863 0 39 0 854 863 0 51 0 0 0 0 0 0 0 0 0 2623 0 0 0 0 0 1889 +866 900 0.995798335828155 0.028534194453078 0.0870142178542727 -0.00602049090796183 -0.0386018442009849 0.992462660681602 0.116308919593806 -0.0212244128570059 -0.0830395808404629 -0.119179137854364 0.989394138407 0.0256274891421482 2.67354008213476e-05 -3.03097632010817e-05 1.96044791996435e-06 -9.49431712735736e-06 -6.64362277171873e-06 1.77057671041599e-06 -3.03097632010817e-05 7.9422731379268e-05 4.99225240155394e-06 2.65349329540832e-05 1.52869703262864e-05 1.51352228591319e-05 1.96044791996435e-06 4.99225240155394e-06 1.03742615092628e-05 4.706711476166e-07 5.27925160902274e-06 2.5076877462738e-06 -9.49431712735736e-06 2.65349329540832e-05 4.706711476166e-07 5.17716455358713e-05 1.32722088586304e-05 1.17699722319709e-05 -6.64362277171873e-06 1.52869703262864e-05 5.27925160902274e-06 1.32722088586304e-05 2.38665225379155e-05 8.07767185814967e-06 1.77057671041599e-06 1.51352228591319e-05 2.5076877462738e-06 1.17699722319709e-05 8.07767185814967e-06 3.54180687686555e-05 853 865 0 43 0 853 865 0 54 0 0 0 0 0 0 0 0 0 2631 0 0 0 0 0 1715 +866 892 0.995770816502023 0.0286687901801383 0.0872844858637597 -0.00346621885584489 -0.0387769317707768 0.992444009665893 0.116409781550901 -0.0186390548843237 -0.0832876375300572 -0.11930208777675 0.989358469558315 0.0252453879206531 2.27468210805938e-05 -1.8960476977356e-05 1.32443975547816e-06 -2.22939765991307e-06 -1.56731424016341e-06 4.20067171236038e-06 -1.8960476977356e-05 5.14761008433955e-05 3.79877809234533e-06 6.69848032646279e-06 5.62954339016575e-06 1.3295090242204e-06 1.32443975547816e-06 3.79877809234533e-06 9.24129671128081e-06 -1.27157787531892e-06 4.42651754262252e-06 -4.53176257264545e-08 -2.22939765991307e-06 6.69848032646279e-06 -1.27157787531892e-06 4.06837568327317e-05 7.35563496945361e-06 2.80954684454138e-06 -1.56731424016341e-06 5.62954339016575e-06 4.42651754262252e-06 7.35563496945361e-06 2.1144583628867e-05 3.22999177591357e-06 4.20067171236038e-06 1.3295090242204e-06 -4.53176257264545e-08 2.80954684454138e-06 3.22999177591357e-06 2.87184318878507e-05 858 873 0 45 0 858 873 0 59 0 0 0 0 0 0 1 0 0 2725 0 0 0 0 0 2026 +866 916 0.995170757361908 0.0286832334447708 0.0938745748905337 0.00536049862864879 -0.0397598625330808 0.992176933945291 0.118338857009321 -0.0151976981935558 -0.0897458468291216 -0.121499810148308 0.98852591221012 0.026928150278553 3.30728200807052e-05 -3.43110217306764e-05 -2.80827153706179e-06 -6.66696288856154e-06 -7.25816165568446e-06 6.8768864620508e-06 -3.43110217306764e-05 8.78769711162818e-05 9.58578954957115e-06 2.49655115932109e-05 9.49569106600251e-06 1.04929929103929e-05 -2.80827153706179e-06 9.58578954957115e-06 1.06811026217696e-05 -1.20846436272785e-06 3.3365208090796e-06 -4.02601414665941e-07 -6.66696288856154e-06 2.49655115932109e-05 -1.20846436272785e-06 6.26635153384594e-05 1.69779184543554e-05 1.49040379292863e-05 -7.25816165568446e-06 9.49569106600251e-06 3.3365208090796e-06 1.69779184543554e-05 2.87120097545238e-05 5.91052317361445e-06 6.8768864620508e-06 1.04929929103929e-05 -4.02601414665941e-07 1.49040379292863e-05 5.91052317361445e-06 3.46292273706381e-05 844 851 0 40 0 843 851 0 49 0 0 0 0 0 0 0 0 0 2509 0 0 0 0 0 1999 +866 927 0.995254463274739 0.0286756785754499 0.0929852611436308 0.00238516917600873 -0.0397921308480573 0.991976808921624 0.119994153541922 -0.0148581268881746 -0.0887983088481015 -0.12312479855784 0.98841041289831 0.0304729652768381 3.49472096902641e-05 -4.27958851870984e-05 -1.99628807570495e-06 -1.11281236505164e-05 -3.61057086813641e-06 -1.78278237213926e-06 -4.27958851870984e-05 8.41844013071753e-05 6.80549579436049e-06 2.87794476106277e-05 1.24705349426923e-05 2.21151873810522e-05 -1.99628807570495e-06 6.80549579436049e-06 1.01250470183371e-05 1.46193542953044e-06 4.26825426021816e-06 1.41369561944239e-06 -1.11281236505164e-05 2.87794476106277e-05 1.46193542953044e-06 5.01093905116789e-05 1.0142158896824e-05 2.09333857191728e-05 -3.61057086813641e-06 1.24705349426923e-05 4.26825426021816e-06 1.0142158896824e-05 2.34923605401356e-05 1.1018409514716e-05 -1.78278237213926e-06 2.21151873810522e-05 1.41369561944239e-06 2.09333857191728e-05 1.1018409514716e-05 4.27431837294122e-05 846 855 0 36 0 845 855 0 53 0 0 0 0 0 0 0 0 0 2663 0 0 0 0 0 1915 +866 901 0.995688342069798 0.0292869614078378 0.088017040155825 8.94460449110345e-05 -0.0395906169268635 0.992259635825962 0.117700459480329 -0.0173961717180198 -0.0838886673970128 -0.120677624280668 0.989140840568383 0.0258650871802785 2.99107532712914e-05 -2.80746912848352e-05 -6.51317259685735e-07 -2.33054889071681e-06 -2.08841809215728e-06 4.99851081767054e-06 -2.80746912848352e-05 3.97206053726809e-05 2.56876368764554e-06 9.58548086851779e-06 6.38697299814564e-06 8.65459068658222e-07 -6.51317259685735e-07 2.56876368764554e-06 9.80461579290392e-06 -8.18987595218019e-07 4.87804740837388e-06 7.59706425044736e-08 -2.33054889071681e-06 9.58548086851779e-06 -8.18987595218019e-07 4.16866304711934e-05 6.15735143814862e-06 5.64309761314044e-06 -2.08841809215728e-06 6.38697299814564e-06 4.87804740837388e-06 6.15735143814862e-06 1.99247744430254e-05 6.34984404374395e-06 4.99851081767054e-06 8.65459068658222e-07 7.59706425044736e-08 5.64309761314044e-06 6.34984404374395e-06 2.8762646599639e-05 884 891 0 45 0 884 891 0 54 0 0 0 0 0 0 0 0 0 2593 0 0 0 0 0 2013 +866 914 0.99638710984398 0.0291887719537632 0.0797542658958831 -0.00814462067918227 -0.0383845459106408 0.992469980199951 0.116318377899376 -0.0200709214436112 -0.0757585240880122 -0.118959463657749 0.990004692935476 0.0241463565230878 3.05412437681233e-05 -4.03276983289693e-05 -8.24561036940427e-07 -9.67890661019196e-06 -4.30875788547507e-06 2.92028385865951e-06 -4.03276983289693e-05 9.47933111710029e-05 6.08497194216868e-06 3.63584221338463e-05 1.35032069210835e-05 1.408539248372e-05 -8.24561036940427e-07 6.08497194216868e-06 9.50084435400321e-06 1.12381156101921e-06 4.99323048830231e-06 7.20537949411417e-07 -9.67890661019196e-06 3.63584221338463e-05 1.12381156101921e-06 5.53459860957952e-05 1.01783493683432e-05 1.58288145602184e-05 -4.30875788547507e-06 1.35032069210835e-05 4.99323048830231e-06 1.01783493683432e-05 2.04055745015062e-05 9.09162201133769e-06 2.92028385865951e-06 1.408539248372e-05 7.20537949411417e-07 1.58288145602184e-05 9.09162201133769e-06 3.54603606205023e-05 882 894 0 42 0 881 894 0 60 0 0 0 0 0 0 0 0 0 2720 0 0 0 0 0 1725 +866 919 0.995269050272405 0.0283067749259157 0.0929421543927141 -0.00199864520418091 -0.0391627596798013 0.992342656560474 0.117142350261392 -0.0199890129648309 -0.0889145422533777 -0.120228026947937 0.988756504763472 0.0299653613622939 3.92773306701951e-05 -4.96518821417814e-05 -3.55194175197323e-06 -1.15223625090764e-05 -9.16703242747787e-06 3.70652627226651e-07 -4.96518821417814e-05 0.000122089506619574 1.00486648328412e-05 5.08719930631009e-05 2.08169707853325e-05 2.36453443474344e-05 -3.55194175197323e-06 1.00486648328412e-05 1.09520762164505e-05 1.31299426963123e-06 4.30094210597209e-06 -9.06755183933033e-08 -1.15223625090764e-05 5.08719930631009e-05 1.31299426963123e-06 7.23954357231143e-05 1.57769339474587e-05 2.46583716070364e-05 -9.16703242747787e-06 2.08169707853325e-05 4.30094210597209e-06 1.57769339474587e-05 3.15454154664434e-05 1.25813382138562e-05 3.70652627226651e-07 2.36453443474344e-05 -9.06755183933033e-08 2.46583716070364e-05 1.25813382138562e-05 4.37439685821445e-05 836 846 0 40 0 836 846 0 52 0 0 0 0 0 0 0 0 0 2425 0 0 0 0 0 2004 +866 918 0.995562227768206 0.0287518752162472 0.0896056935286801 -0.00246967798379838 -0.039054734475976 0.992546702673133 0.115437302150138 -0.0223798895697831 -0.0856187967459097 -0.118424544264441 0.989264903329509 0.026923407685517 2.72109757555515e-05 -2.28257209980321e-05 -1.52813620313986e-06 -1.43884903798737e-06 -3.7940926243946e-06 1.90822342976655e-06 -2.28257209980321e-05 5.35500992029232e-05 6.03758741060144e-06 1.28546034982406e-05 7.91844455833464e-06 1.57774460561745e-05 -1.52813620313986e-06 6.03758741060144e-06 9.72258680968185e-06 -7.84758195338976e-07 3.89961793810673e-06 5.01586026485714e-07 -1.43884903798737e-06 1.28546034982406e-05 -7.84758195338976e-07 4.21923093327864e-05 3.01252046929194e-06 1.54303630255877e-05 -3.7940926243946e-06 7.91844455833464e-06 3.89961793810673e-06 3.01252046929194e-06 2.32040949060811e-05 6.26619650442875e-06 1.90822342976655e-06 1.57774460561745e-05 5.01586026485714e-07 1.54303630255877e-05 6.26619650442875e-06 4.05365127434182e-05 850 860 0 43 0 849 860 0 59 0 0 0 0 0 0 0 0 0 2372 0 0 0 0 0 1733 +866 915 0.995976997050587 0.0291301225147261 0.0847422994045625 -0.00970425206395953 -0.0385851439198421 0.992939726103664 0.112169010844648 -0.0264665174692348 -0.0808764985319007 -0.11498754840181 0.990069116626592 0.00117484063322206 0.000417951346552363 -0.000304831384449621 -7.39316057425332e-06 -0.000442881077520741 -0.000376137867720558 -0.00137488593025429 -0.000304831384449621 0.000282847282291395 6.94568555346461e-06 0.000374693028003557 0.000296309883481792 0.00107256057653896 -7.39316057425332e-06 6.94568555346461e-06 1.01096196154932e-05 5.97938648252764e-06 1.05719235106881e-05 2.12867285254827e-05 -0.000442881077520741 0.000374693028003557 5.97938648252764e-06 0.000617525948328199 0.000466193964372543 0.00170930406493008 -0.000376137867720558 0.000296309883481792 1.05719235106881e-05 0.000466193964372543 0.00040015039078182 0.00143029735584918 -0.00137488593025429 0.00107256057653896 2.12867285254827e-05 0.00170930406493008 0.00143029735584918 0.00767934248921454 846 850 0 38 0 846 850 0 50 0 0 0 0 0 0 0 0 0 2640 0 0 0 0 0 1676 +866 917 0.995705113270259 0.0300586520172898 0.0875660027999727 0.00789553093668481 -0.0404324485150974 0.992044738745774 0.119215994874438 -0.0117159176464059 -0.083285920265885 -0.122244483579962 0.988999363862148 0.0259639511953539 2.91525994962707e-05 -2.47959716159449e-05 -7.43767034409105e-07 -5.60797472187499e-06 -7.42351485138791e-06 6.44757648027115e-06 -2.47959716159449e-05 4.10230665557582e-05 5.47865129443531e-06 -5.78998995499481e-06 -3.25973619920634e-06 5.25122984021826e-06 -7.43767034409105e-07 5.47865129443531e-06 1.13798428315922e-05 -7.14259534846469e-06 -8.34724095068651e-07 1.66455030546848e-06 -5.60797472187499e-06 -5.78998995499481e-06 -7.14259534846469e-06 6.37978108423409e-05 2.69669419308173e-05 -4.11167232433936e-06 -7.42351485138791e-06 -3.25973619920634e-06 -8.34724095068651e-07 2.69669419308173e-05 4.05251743032746e-05 -2.73892147349931e-06 6.44757648027115e-06 5.25122984021826e-06 1.66455030546848e-06 -4.11167232433936e-06 -2.73892147349931e-06 3.14264360759347e-05 867 875 0 43 0 866 875 0 49 0 0 0 0 0 0 0 0 0 2287 0 0 0 0 0 1890 +867 923 0.99735719527057 0.015418357462994 0.0709992908074859 -0.00902251744970386 -0.0244760087022158 0.99140358786727 0.128529572324482 -0.0200322606030292 -0.0684072367519086 -0.129927673022526 0.989160881627918 0.0240118305997229 3.89478189968199e-05 -4.52293445706493e-05 -4.18437925968661e-07 -1.7889752506682e-05 -1.14286581360653e-05 -1.13009252063022e-05 -4.52293445706493e-05 7.62549537666826e-05 4.27976456374223e-06 3.16723036885179e-05 1.78041124499149e-05 2.58590597507921e-05 -4.18437925968661e-07 4.27976456374223e-06 9.92082785240557e-06 5.96946576016083e-07 4.1400050881459e-06 8.04820521075653e-07 -1.7889752506682e-05 3.16723036885179e-05 5.96946576016083e-07 6.54489089656262e-05 2.07845553464637e-05 2.63602827811432e-05 -1.14286581360653e-05 1.78041124499149e-05 4.1400050881459e-06 2.07845553464637e-05 2.69676022949291e-05 1.35230594289712e-05 -1.13009252063022e-05 2.58590597507921e-05 8.04820521075653e-07 2.63602827811432e-05 1.35230594289712e-05 4.68374971116193e-05 859 873 0 37 0 858 873 0 48 0 0 0 0 0 0 5 8 0 2560 0 0 0 0 0 1375 +867 870 0.999555761946698 0.0283844308134705 0.00908861081528501 0.00410268230037168 -0.0284383730144639 0.999578359455208 0.00586193220074496 -0.00794292172270189 -0.00891839107948414 -0.00611779341194388 0.999941515741957 0.00570048674334274 2.94514314659616e-05 -2.99157639127347e-05 2.61906172808451e-06 -5.25042460638042e-06 -8.13655233626913e-06 1.14285791124443e-05 -2.99157639127347e-05 6.20478239850232e-05 -3.63488993883123e-06 3.03027881626202e-05 2.16018196092265e-05 -2.18064541278777e-06 2.61906172808451e-06 -3.63488993883123e-06 8.69328522144931e-06 -1.24710071761928e-06 1.59846185598809e-06 -1.05444224264655e-06 -5.25042460638042e-06 3.03027881626202e-05 -1.24710071761928e-06 6.20126583635609e-05 1.97789678631922e-05 1.20351593172112e-05 -8.13655233626913e-06 2.16018196092265e-05 1.59846185598809e-06 1.97789678631922e-05 3.18650701056086e-05 3.36243436899963e-06 1.14285791124443e-05 -2.18064541278777e-06 -1.05444224264655e-06 1.20351593172112e-05 3.36243436899963e-06 3.54971692817425e-05 855 866 0 42 0 855 866 0 49 0 0 0 0 0 0 4 4 0 2250 0 0 0 0 0 2739 +867 871 0.99946609006845 0.0249466369504793 -0.0210997655945538 -0.000946161330551849 -0.0248128911527531 0.99967047745641 0.00657700043440338 -0.0117533221574837 0.0212568867881862 -0.00604994272150537 0.999755741647499 0.0118734541286348 3.21844437491325e-05 -3.54931915702735e-05 4.57293186103303e-06 -9.25335567836395e-06 -4.47101212502227e-06 8.97677694064707e-06 -3.54931915702735e-05 5.46934733101752e-05 -4.12629900918017e-06 1.95757202903427e-05 1.20328033776791e-05 1.5682021194645e-06 4.57293186103303e-06 -4.12629900918017e-06 8.88739020807067e-06 -1.37630012249693e-07 1.43717072950852e-06 4.28637890443252e-07 -9.25335567836395e-06 1.95757202903427e-05 -1.37630012249693e-07 4.93321249350058e-05 1.64582939595793e-05 8.86824935926027e-06 -4.47101212502227e-06 1.20328033776791e-05 1.43717072950852e-06 1.64582939595793e-05 2.45828037624849e-05 8.58884189353564e-06 8.97677694064707e-06 1.5682021194645e-06 4.28637890443252e-07 8.86824935926027e-06 8.58884189353564e-06 3.9425705773654e-05 807 817 0 34 0 803 816 0 45 0 0 0 0 0 0 2 2 0 2309 0 0 0 0 0 2151 +867 925 0.997522511682498 0.0162240980769398 0.068451569216715 -0.00899524197230616 -0.0249932218277678 0.99129498070586 0.129265618360171 -0.0185312887695804 -0.0657584789157176 -0.130656189554721 0.989244551454155 0.0241750899267018 3.47912732416817e-05 -4.18047919051629e-05 3.85361627911262e-06 -2.33554723648017e-05 -1.37672722993914e-05 -1.81897549965241e-06 -4.18047919051629e-05 7.98299343679292e-05 -2.07325605390148e-06 5.01713576446452e-05 2.67131201675245e-05 1.98955254502379e-05 3.85361627911262e-06 -2.07325605390148e-06 8.8504370848188e-06 2.00990069620891e-06 4.46355502366353e-06 2.43619880552866e-06 -2.33554723648017e-05 5.01713576446452e-05 2.00990069620891e-06 7.17411324942895e-05 2.78870992716779e-05 2.27623820237336e-05 -1.37672722993914e-05 2.67131201675245e-05 4.46355502366353e-06 2.78870992716779e-05 2.99508869140767e-05 1.26957089056821e-05 -1.81897549965241e-06 1.98955254502379e-05 2.43619880552866e-06 2.27623820237336e-05 1.26957089056821e-05 3.94860545742467e-05 866 878 0 34 0 865 878 0 48 0 0 0 0 0 0 5 11 0 2594 0 0 0 0 0 2137 +867 869 0.999436805087102 0.0288773852147023 0.0170929593823659 0.000685616115490797 -0.0290113442232858 0.999549872208046 0.00764165395955387 -0.00723998245070012 -0.0168645943812337 -0.00813323994735418 0.999824702567563 0.00112504981341316 3.47041679241528e-05 -4.80028961224328e-05 1.03685248642258e-06 -1.01945214030829e-05 -9.58088818088646e-06 9.4171468449256e-06 -4.80028961224328e-05 9.91734383485176e-05 5.76208219679235e-07 3.56261541249185e-05 2.9897437673479e-05 -9.81138129113808e-06 1.03685248642258e-06 5.76208219679235e-07 8.96776830348308e-06 -5.76910531497659e-07 2.93481392937806e-06 -2.80208109363377e-06 -1.01945214030829e-05 3.56261541249185e-05 -5.76910531497659e-07 6.45879269155887e-05 2.08473846857593e-05 5.75783204703367e-06 -9.58088818088646e-06 2.9897437673479e-05 2.93481392937806e-06 2.08473846857593e-05 3.08750622886032e-05 2.9932730622985e-06 9.4171468449256e-06 -9.81138129113808e-06 -2.80208109363377e-06 5.75783204703367e-06 2.9932730622985e-06 3.29251799209054e-05 853 861 0 45 0 851 861 0 57 0 0 0 0 0 0 0 0 0 2269 0 0 0 0 0 2492 +867 930 0.989365173785826 -0.0689702959434859 0.128061122817231 -0.0208490025676306 0.049518974654275 0.987551396208868 0.149298730721678 -0.0187689418878485 -0.136764118280093 -0.141369509171472 0.980464297069346 -0.0210236866952501 3.33824038128519e-05 -3.16026294160275e-05 -1.63253338063994e-06 -8.52664589290466e-06 -4.19347638989948e-06 3.54313474536285e-06 -3.16026294160275e-05 4.66858777153025e-05 2.23351445463253e-06 2.17663852914325e-05 8.24901044764234e-06 5.30309084096548e-06 -1.63253338063994e-06 2.23351445463253e-06 1.19182246139561e-05 -2.46508213474049e-06 1.66480191862077e-06 -1.05260706589742e-06 -8.52664589290466e-06 2.17663852914325e-05 -2.46508213474049e-06 6.35969850721856e-05 1.36343114950414e-05 1.58654280254255e-05 -4.19347638989948e-06 8.24901044764234e-06 1.66480191862077e-06 1.36343114950414e-05 2.06844607480063e-05 3.67032782929048e-06 3.54313474536285e-06 5.30309084096548e-06 -1.05260706589742e-06 1.58654280254255e-05 3.67032782929048e-06 3.36383254742858e-05 1029 1029 0 0 0 1033 1033 0 0 0 0 0 0 0 0 87 93 0 2738 0 0 0 0 0 1683 +867 929 0.997014355989212 -0.00644040013012771 0.0769473534150546 -0.00948570319758462 -0.00511657064640588 0.988815136823297 0.149058531771733 -0.0177745386995772 -0.0770467043827172 -0.149007202628894 0.985829934070007 0.018516129221473 2.94633927357842e-05 -2.26764974237357e-05 -2.48490041751427e-06 2.82526877282924e-06 1.49900457737013e-06 -1.37899202046843e-06 -2.26764974237357e-05 4.0686844529372e-05 3.53484180682386e-06 4.63892175000237e-06 2.00063752148857e-06 1.84082656094119e-06 -2.48490041751427e-06 3.53484180682386e-06 9.92014532357049e-06 6.84186295195389e-07 2.41246179335982e-06 -1.46483003849111e-06 2.82526877282924e-06 4.63892175000237e-06 6.84186295195389e-07 3.77716659130741e-05 2.13109635365171e-06 3.18548811347949e-06 1.49900457737013e-06 2.00063752148857e-06 2.41246179335982e-06 2.13109635365171e-06 2.08417786214921e-05 3.14523921213044e-06 -1.37899202046843e-06 1.84082656094119e-06 -1.46483003849111e-06 3.18548811347949e-06 3.14523921213044e-06 2.58421955501209e-05 920 925 0 18 0 912 929 0 33 0 0 0 0 0 0 5 19 0 2649 0 0 0 0 0 1827 +867 927 0.997854512938008 0.0167913737759679 0.0632804928549563 -0.0130413758785194 -0.0247906534109043 0.991486416807776 0.127828434978836 -0.0220231481291428 -0.0605953340836641 -0.129122945491472 0.989775464655947 0.0235327975285483 2.97431923886967e-05 -3.44284721707297e-05 -1.25659398963169e-07 -8.55300715137699e-06 -5.1999085941257e-06 5.83440777097263e-06 -3.44284721707297e-05 8.39274894883214e-05 3.98025319770938e-06 3.31034523277302e-05 1.58317066999708e-05 4.40029356840974e-06 -1.25659398963169e-07 3.98025319770938e-06 8.93520983268549e-06 2.80005874173659e-06 3.92929141427246e-06 -8.10811961813641e-07 -8.55300715137699e-06 3.31034523277302e-05 2.80005874173659e-06 5.11987402409594e-05 9.91045708164684e-06 1.62542753127895e-05 -5.1999085941257e-06 1.58317066999708e-05 3.92929141427246e-06 9.91045708164684e-06 2.21484668266002e-05 6.87293145241984e-06 5.83440777097263e-06 4.40029356840974e-06 -8.10811961813641e-07 1.62542753127895e-05 6.87293145241984e-06 3.31162664332257e-05 851 862 0 35 0 850 862 0 48 0 0 0 0 0 0 4 10 0 2673 0 0 0 0 0 1966 +867 898 0.997516485357897 0.0165735318175701 0.0684556753112547 -0.00933408387113057 -0.0253921591096568 0.99118412919319 0.13003561162731 -0.0180206376265652 -0.0656970295749953 -0.131450903681301 0.989143346652239 0.0259124702429612 2.60762692638697e-05 -3.40193543599695e-05 9.78725792951955e-08 -1.42012017799091e-05 -4.86470785741447e-06 -2.95334836988537e-06 -3.40193543599695e-05 7.4496144208758e-05 3.09039958014982e-06 4.10503067560665e-05 1.76070279845673e-05 1.94517454295301e-05 9.78725792951955e-08 3.09039958014982e-06 8.48549258680149e-06 1.77096151422662e-06 4.04136146314384e-06 1.36443785197996e-07 -1.42012017799091e-05 4.10503067560665e-05 1.77096151422662e-06 7.0445680614821e-05 2.17190704987408e-05 1.8294456669604e-05 -4.86470785741447e-06 1.76070279845673e-05 4.04136146314384e-06 2.17190704987408e-05 2.46418672660843e-05 9.91069597757351e-06 -2.95334836988537e-06 1.94517454295301e-05 1.36443785197996e-07 1.8294456669604e-05 9.91069597757351e-06 3.69566843182214e-05 850 860 0 35 0 849 860 0 51 0 0 0 0 0 0 7 13 0 2715 0 0 0 0 0 2167 +867 922 0.997321341032976 0.0155988889508319 0.0714619995780001 -0.00600052048743396 -0.0247544661074783 0.991324649642138 0.129083908445733 -0.0189036366333103 -0.0688284761412032 -0.130507140323403 0.98905537114799 0.0249795812851784 3.65537621679071e-05 -4.30695144593593e-05 -3.70848205582811e-06 -1.01437560492124e-05 -5.23778674918188e-06 -1.33009584949685e-05 -4.30695144593593e-05 6.77870412404185e-05 6.4832393569268e-06 1.8513971685486e-05 1.07171004561365e-05 2.76457792250244e-05 -3.70848205582811e-06 6.4832393569268e-06 1.02966509495635e-05 -7.26445910787267e-07 3.59221808035216e-06 8.3274472669876e-08 -1.01437560492124e-05 1.8513971685486e-05 -7.26445910787267e-07 5.40798662749882e-05 1.43331167332389e-05 1.76611555966371e-05 -5.23778674918188e-06 1.07171004561365e-05 3.59221808035216e-06 1.43331167332389e-05 2.57223923818919e-05 1.14898714096077e-05 -1.33009584949685e-05 2.76457792250244e-05 8.3274472669876e-08 1.76611555966371e-05 1.14898714096077e-05 5.36565789334673e-05 875 884 0 38 0 875 884 0 52 0 0 0 0 0 0 4 6 0 2694 0 0 0 0 0 1364 +867 926 0.997753238994419 0.0166152650826031 0.0649030588060363 -0.0127192015396226 -0.024860291486162 0.991414262070724 0.128373388480578 -0.0214137871771459 -0.0622128602731625 -0.129698473117447 0.9895998514994 0.0237163287493661 3.52111882372825e-05 -4.72288554202217e-05 -1.16232079594981e-06 -2.08630308351884e-05 -1.04011132723035e-05 6.24890189899538e-07 -4.72288554202217e-05 0.000119658268835351 6.67033405346033e-06 6.48841951043947e-05 2.82742417044349e-05 1.75232533597854e-05 -1.16232079594981e-06 6.67033405346033e-06 9.35272628813183e-06 3.25936124015241e-06 4.03060336909067e-06 -5.54121371736309e-07 -2.08630308351884e-05 6.48841951043947e-05 3.25936124015241e-06 8.68927094881921e-05 3.04146795374949e-05 2.8532244469346e-05 -1.04011132723035e-05 2.82742417044349e-05 4.03060336909067e-06 3.04146795374949e-05 3.10887336606256e-05 1.22295837725932e-05 6.24890189899538e-07 1.75232533597854e-05 -5.54121371736309e-07 2.8532244469346e-05 1.22295837725932e-05 3.71564689348642e-05 847 855 0 33 0 845 855 0 44 0 0 0 0 0 0 6 11 0 2621 0 0 0 0 0 1940 +867 921 0.997335139972369 0.0161203666197892 0.0711530207112691 -0.00527082656280864 -0.0252726406454016 0.9912354451883 0.129667211881651 -0.0204474906834877 -0.0684391131671291 -0.131119891635084 0.989001345705101 0.0245393847721721 3.03340352897328e-05 -3.51946570842233e-05 3.12543890953308e-06 -2.14357512184963e-05 -1.37026887988687e-05 2.00752736102806e-06 -3.51946570842233e-05 6.14677443168927e-05 -1.43897520582625e-06 4.28250506147924e-05 2.3284081230847e-05 9.19371894239646e-06 3.12543890953308e-06 -1.43897520582625e-06 8.43084524057001e-06 1.80894984642872e-06 3.17300024767049e-06 7.75752473555203e-07 -2.14357512184963e-05 4.28250506147924e-05 1.80894984642872e-06 7.24036359577655e-05 2.6753809923623e-05 1.9539469176656e-05 -1.37026887988687e-05 2.3284081230847e-05 3.17300024767049e-06 2.6753809923623e-05 3.06781643094384e-05 8.03910656768929e-06 2.00752736102806e-06 9.19371894239646e-06 7.75752473555203e-07 1.9539469176656e-05 8.03910656768929e-06 3.29938309320502e-05 841 847 0 37 0 841 847 0 50 0 0 0 0 0 0 3 7 0 2552 0 0 0 0 0 2097 +867 920 0.996332765229548 0.0141630657793296 0.0843826314935351 -0.00438419857760827 -0.0251661023963376 0.991089791624122 0.130796376970586 -0.0225620486556469 -0.0817782869728904 -0.132440297893749 0.987811661843286 0.0303331182479516 4.25141815253841e-05 -4.64198640741621e-05 -3.85193132478289e-06 -2.9778867663281e-06 -5.14116295319416e-06 6.15595976011128e-06 -4.64198640741621e-05 9.66242053189783e-05 8.32950339770129e-06 2.50622289627915e-05 1.21763011151864e-05 1.20375196741217e-05 -3.85193132478289e-06 8.32950339770129e-06 1.10395930105863e-05 -1.03995071428683e-06 3.09077385173014e-06 -1.46243422341933e-06 -2.9778867663281e-06 2.50622289627915e-05 -1.03995071428683e-06 6.72238887272568e-05 1.49296751281271e-05 1.38863080055673e-05 -5.14116295319416e-06 1.21763011151864e-05 3.09077385173014e-06 1.49296751281271e-05 3.05356512276742e-05 3.90762963109285e-06 6.15595976011128e-06 1.20375196741217e-05 -1.46243422341933e-06 1.38863080055673e-05 3.90762963109285e-06 3.36112957709882e-05 839 846 0 35 0 838 846 0 49 0 0 0 0 0 0 4 8 0 2394 0 0 0 0 0 1651 +867 928 0.997541689547072 0.0160514615490467 0.0682123756932218 -0.0099029634479067 -0.0248615313175719 0.991157431617867 0.130341282827882 -0.0191708061993007 -0.0655170350070816 -0.131716727604401 0.989119922857218 0.0257674891220754 5.32193518709916e-05 -6.55884808227284e-05 -5.77846733831593e-06 -1.66790963604632e-05 -1.08856254112603e-05 -6.73155208420802e-06 -6.55884808227284e-05 0.000120473430541343 1.19224963934578e-05 4.14210912212286e-05 2.1095031644556e-05 2.62872396709625e-05 -5.77846733831593e-06 1.19224963934578e-05 1.10545019164881e-05 -2.86323975418454e-08 5.45862376006868e-06 1.81284351983047e-07 -1.66790963604632e-05 4.14210912212286e-05 -2.86323975418454e-08 5.91459459973898e-05 1.38115221589811e-05 2.88868621483274e-05 -1.08856254112603e-05 2.1095031644556e-05 5.45862376006868e-06 1.38115221589811e-05 2.53538344485332e-05 1.17480832963465e-05 -6.73155208420802e-06 2.62872396709625e-05 1.81284351983047e-07 2.88868621483274e-05 1.17480832963465e-05 4.53326322754908e-05 820 830 0 35 0 819 830 0 47 0 0 0 0 0 0 1 4 0 2586 0 0 0 0 0 1374 +867 919 0.997630650832209 0.01655403290436 0.0667761073641268 -0.0114066536774891 -0.0249685835788611 0.991560508017074 0.127217643332153 -0.0230237491075834 -0.0641065858876407 -0.128583525132587 0.989624485706729 0.024542667550869 4.31055588385013e-05 -3.87417533246743e-05 -2.57862379503138e-06 -1.2584650748038e-05 -1.48275166730859e-05 -1.11188326225217e-05 -3.87417533246743e-05 6.33339232825284e-05 5.55420376715388e-06 1.95736631518396e-05 1.35462042505514e-05 2.92757625728446e-05 -2.57862379503138e-06 5.55420376715388e-06 1.06169840796138e-05 5.10801574357267e-07 1.21633493662882e-06 -1.30111016708951e-06 -1.2584650748038e-05 1.95736631518396e-05 5.10801574357267e-07 5.95122903981615e-05 1.46003526979648e-05 2.90700325277288e-05 -1.48275166730859e-05 1.35462042505514e-05 1.21633493662882e-06 1.46003526979648e-05 3.40679876815842e-05 1.71653186495204e-05 -1.11188326225217e-05 2.92757625728446e-05 -1.30111016708951e-06 2.90700325277288e-05 1.71653186495204e-05 6.33637390373273e-05 859 871 0 39 0 859 871 0 52 0 0 0 0 0 0 8 12 0 2431 0 0 0 0 0 1333 +867 899 0.997131900333703 0.015490324884971 0.0740811931049716 -0.0101712369278287 -0.0250816742373802 0.991150726032639 0.130350097439256 -0.0204122108696442 -0.071406462973235 -0.131834320720864 0.98869653024865 0.0250011355843865 3.62742883845416e-05 -4.42343447983767e-05 -1.91540640929269e-06 -1.4547096681445e-05 -1.12890381919059e-05 -1.16864070202493e-05 -4.42343447983767e-05 8.46989054773382e-05 7.11356442257616e-06 2.88818800192492e-05 2.06953233072359e-05 3.29149714005745e-05 -1.91540640929269e-06 7.11356442257616e-06 1.00671680273635e-05 1.97409561470764e-06 5.59067594963606e-06 1.22004695110264e-06 -1.4547096681445e-05 2.88818800192492e-05 1.97409561470764e-06 5.23129817450229e-05 1.51691569241288e-05 2.73285803081732e-05 -1.12890381919059e-05 2.06953233072359e-05 5.59067594963606e-06 1.51691569241288e-05 2.53881482418085e-05 1.41302171239192e-05 -1.16864070202493e-05 3.29149714005745e-05 1.22004695110264e-06 2.73285803081732e-05 1.41302171239192e-05 5.12572320486926e-05 873 884 0 32 0 872 884 0 47 0 0 0 0 0 0 7 11 0 2710 0 0 0 0 0 1450 +867 924 0.997618938884204 0.0165014415183512 0.0669638350706599 -0.00891982515392935 -0.0249894048242926 0.991463225116791 0.127969538904927 -0.0205350850774264 -0.0642804980229753 -0.129338221995002 0.98951485178601 0.0226366265756009 2.48081687031339e-05 -2.5852522748221e-05 8.09489515628686e-07 -1.3335730238778e-05 -7.49490126728791e-06 -2.03584864198496e-06 -2.5852522748221e-05 5.81143794964809e-05 1.55633073401765e-06 3.61927386769911e-05 1.76576203475881e-05 1.70790607234683e-05 8.09489515628686e-07 1.55633073401765e-06 8.62958911403548e-06 2.23227972172069e-06 3.47311737326248e-06 3.21316083890958e-07 -1.3335730238778e-05 3.61927386769911e-05 2.23227972172069e-06 6.83644328729568e-05 2.01138199649297e-05 2.15599577639287e-05 -7.49490126728791e-06 1.76576203475881e-05 3.47311737326248e-06 2.01138199649297e-05 2.55954605336656e-05 1.21753609104218e-05 -2.03584864198496e-06 1.70790607234683e-05 3.21316083890958e-07 2.15599577639287e-05 1.21753609104218e-05 4.08768567726099e-05 831 837 0 34 0 831 837 0 49 0 0 0 0 0 0 3 6 0 2642 0 0 0 0 0 1957 +867 918 0.997432411980309 0.015931855150729 0.0698194781031716 -0.007456691542667 -0.024899969855013 0.991263463517949 0.129525045437627 -0.0231104364917194 -0.0671459234232616 -0.130930981382773 0.98911501003765 0.027540644679108 3.73895856507338e-05 -5.0532613010949e-05 -3.76210715573244e-06 -4.77689867517551e-06 -4.82763004406834e-06 5.37389272831761e-06 -5.0532613010949e-05 0.000144066264728619 1.01395641615428e-05 3.94859511225827e-05 1.61228138286187e-05 2.09686505916236e-05 -3.76210715573244e-06 1.01395641615428e-05 1.01258567656618e-05 7.01932892412123e-07 3.06956923436152e-06 -1.20633010351998e-06 -4.77689867517551e-06 3.94859511225827e-05 7.01932892412123e-07 5.49705910889391e-05 9.22329666402823e-06 1.99721893393054e-05 -4.82763004406834e-06 1.61228138286187e-05 3.06956923436152e-06 9.22329666402823e-06 2.75589199151732e-05 7.09558688778465e-06 5.37389272831761e-06 2.09686505916236e-05 -1.20633010351998e-06 1.99721893393054e-05 7.09558688778465e-06 3.93233250070188e-05 848 859 0 39 0 847 859 0 58 0 0 0 0 0 0 5 9 0 2374 0 0 0 0 0 1617 +867 917 0.997145468210063 0.0171558806041373 0.073529524606321 0.00280256925502276 -0.026760210868727 0.990928845446153 0.131696295988218 -0.0139887450269139 -0.0706031609943652 -0.133288030308245 0.988559302537866 0.0255201102373549 5.41814527953117e-05 -7.57877357607692e-05 -4.48817834328854e-06 -2.72450878763712e-05 -1.32634510825478e-05 -7.3292400268409e-06 -7.57877357607692e-05 0.00022196916425449 1.56391056170486e-05 0.000102315257768397 2.33306802750134e-05 5.34136869473526e-05 -4.48817834328854e-06 1.56391056170486e-05 1.16500077688813e-05 3.37244849782514e-06 1.88568652906148e-06 4.67225112392273e-06 -2.72450878763712e-05 0.000102315257768397 3.37244849782514e-06 0.000123002357523888 3.34678737616277e-05 2.58767381267824e-05 -1.32634510825478e-05 2.33306802750134e-05 1.88568652906148e-06 3.34678737616277e-05 4.62718899992791e-05 -1.50205687572701e-07 -7.3292400268409e-06 5.34136869473526e-05 4.67225112392273e-06 2.58767381267824e-05 -1.50205687572701e-07 5.48178816370541e-05 818 830 0 43 0 817 830 0 52 0 0 0 0 0 0 5 9 0 2300 0 0 0 0 0 1978 +867 914 0.997429699356377 0.0158622972569897 0.0698740464520145 -0.00890159234957086 -0.0249312165267582 0.991082466072192 0.130896829169995 -0.0181818595751672 -0.0671746178578135 -0.132302429947427 0.988930552539289 0.0263032727826036 3.16759316286971e-05 -3.76346754729982e-05 -1.93639216746605e-07 -1.20601628098194e-05 -4.91179756400691e-06 3.47066341268578e-06 -3.76346754729982e-05 7.20232812842461e-05 1.89563055084421e-06 3.55997004489064e-05 1.41143736223103e-05 7.52799874175245e-06 -1.93639216746605e-07 1.89563055084421e-06 9.12209203771975e-06 3.10587610003537e-07 3.79995601117156e-06 -8.63032677782875e-07 -1.20601628098194e-05 3.55997004489064e-05 3.10587610003537e-07 5.80984089014344e-05 1.59970314532586e-05 1.29402662120793e-05 -4.91179756400691e-06 1.41143736223103e-05 3.79995601117156e-06 1.59970314532586e-05 2.44815409197317e-05 6.65928767142854e-06 3.47066341268578e-06 7.52799874175245e-06 -8.63032677782875e-07 1.29402662120793e-05 6.65928767142854e-06 3.03497626771391e-05 905 917 0 33 0 904 917 0 47 0 0 0 0 0 0 5 10 0 2712 0 0 0 0 0 1644 +867 900 0.997677251230646 0.0162542940738564 0.0661505880625614 -0.0103830939074554 -0.0248163964218361 0.991105023685038 0.130747766691879 -0.0195490701538995 -0.0634369674992143 -0.132085691694598 0.989206308716267 0.0250076687578643 4.44395409468439e-05 -5.46448759728375e-05 3.82882553649875e-06 -2.50436937886716e-05 -1.39595811767557e-05 -4.18844719501833e-06 -5.46448759728375e-05 9.32595248586655e-05 -2.30669201953161e-06 4.91322122956923e-05 2.61289132638046e-05 2.16505665930245e-05 3.82882553649875e-06 -2.30669201953161e-06 1.1247976816944e-05 -2.60534958417645e-06 3.25685187730998e-06 1.05562600019344e-06 -2.50436937886716e-05 4.91322122956923e-05 -2.60534958417645e-06 7.05061277512474e-05 2.80657329545305e-05 2.3614833555634e-05 -1.39595811767557e-05 2.61289132638046e-05 3.25685187730998e-06 2.80657329545305e-05 3.15434623896601e-05 1.49120975053037e-05 -4.18844719501833e-06 2.16505665930245e-05 1.05562600019344e-06 2.3614833555634e-05 1.49120975053037e-05 4.00254623082044e-05 882 896 0 38 0 882 896 0 50 0 0 0 0 0 0 2 5 0 2616 0 0 0 0 0 1609 +868 930 0.98998711842361 -0.0839904034357858 0.113450947488379 -0.020657587576206 0.0664659053717014 0.986408042024763 0.150271281527753 -0.0141239605324737 -0.124530272538194 -0.141226013041391 0.982113753320865 -0.0210918951512557 3.2918336547807e-05 -3.87563561301019e-05 -6.016917764469e-07 -6.49890978851364e-06 -2.61784228142437e-06 -2.37109564088199e-06 -3.87563561301019e-05 7.8131787383133e-05 4.14683697792242e-06 1.43676662411381e-05 5.90453072516938e-06 1.85860143157597e-05 -6.016917764469e-07 4.14683697792242e-06 1.08358069163228e-05 -2.98373425166499e-06 3.77336177107186e-06 2.51665468089085e-08 -6.49890978851364e-06 1.43676662411381e-05 -2.98373425166499e-06 4.92116058966126e-05 6.32150277376216e-06 1.52399222869477e-05 -2.61784228142437e-06 5.90453072516938e-06 3.77336177107186e-06 6.32150277376216e-06 2.00496804756428e-05 3.774387183546e-06 -2.37109564088199e-06 1.85860143157597e-05 2.51665468089085e-08 1.52399222869477e-05 3.774387183546e-06 3.18969334051281e-05 1036 1035 0 0 0 1023 1022 0 0 0 0 0 0 0 0 93 100 0 2699 0 0 0 0 0 1401 +868 929 0.997674846476378 -0.0223069165583845 0.0643995511008711 -0.0144556939857543 0.0124466711882673 0.988663261820601 0.149633001381985 -0.0177670955242235 -0.0670073211273783 -0.148483521644347 0.986642114809329 0.0176791079223028 2.10951882772488e-05 -2.01117722672872e-05 -4.07056581463494e-07 -2.09722806250517e-07 -1.14601446411409e-06 3.1798849386122e-06 -2.01117722672872e-05 4.25773556017747e-05 3.15958604066465e-06 5.05010917677592e-06 3.98338822714742e-06 -6.40019936970631e-07 -4.07056581463494e-07 3.15958604066465e-06 8.7829064049161e-06 1.56447902859414e-06 3.073865641625e-06 -4.00716375802274e-07 -2.09722806250517e-07 5.05010917677592e-06 1.56447902859414e-06 3.20633289196239e-05 3.30001286488506e-06 2.4020398133314e-06 -1.14601446411409e-06 3.98338822714742e-06 3.073865641625e-06 3.30001286488506e-06 1.96949820559493e-05 -7.64277955045269e-07 3.1798849386122e-06 -6.40019936970631e-07 -4.00716375802274e-07 2.4020398133314e-06 -7.64277955045269e-07 1.9111894153537e-05 896 895 0 2 0 897 901 0 13 0 0 0 0 0 0 28 43 0 2638 0 0 0 0 0 1882 +868 921 0.998484140870863 0.000506539576583887 0.0550378401377717 -0.00844011046184649 -0.00745955634527177 0.991976776526596 0.126199959790153 -0.0203660511010955 -0.0545323339726559 -0.126419216298638 0.990476858034519 0.0203444651326515 4.68970162107357e-05 -4.70260095027999e-05 4.52390566882527e-06 -3.20025016000172e-05 -1.66329827924233e-05 -1.1224194816553e-05 -4.70260095027999e-05 7.90259920979682e-05 4.79876433890842e-07 5.10035567291596e-05 2.40386973256624e-05 2.7975503059698e-05 4.52390566882527e-06 4.79876433890842e-07 1.14409720506669e-05 -3.56357497141909e-06 2.92875538045007e-06 2.89038188619097e-06 -3.20025016000172e-05 5.10035567291596e-05 -3.56357497141909e-06 0.000114850868047495 4.49706635608768e-05 4.14410836637655e-05 -1.66329827924233e-05 2.40386973256624e-05 2.92875538045007e-06 4.49706635608768e-05 4.10156502439161e-05 2.24093130203824e-05 -1.1224194816553e-05 2.7975503059698e-05 2.89038188619097e-06 4.14410836637655e-05 2.24093130203824e-05 5.58881668426075e-05 874 877 0 32 0 869 882 0 42 0 0 0 0 0 0 2 16 0 2557 0 0 0 0 0 2013 +868 870 0.999888142942538 0.0107485685428566 -0.0104004748546557 -0.00347192640645385 -0.0107282718923495 0.999940439621894 0.00200534061354023 -0.00839844667789412 0.0104214099394773 -0.0018935371799897 0.999943902792462 0.00325320421520291 3.7088017452532e-05 -4.51676967099982e-05 4.0226323831302e-06 -1.81980974751675e-05 -1.02105622677626e-05 1.41746611972706e-05 -4.51676967099982e-05 8.09225428644725e-05 -3.86155061176888e-06 4.70625300180805e-05 2.67499513239884e-05 -1.85657349786799e-05 4.0226323831302e-06 -3.86155061176888e-06 9.24132419797602e-06 -1.66776123003782e-06 3.45616282691286e-06 1.2244905631376e-07 -1.81980974751675e-05 4.70625300180805e-05 -1.66776123003782e-06 7.04617876060202e-05 2.32937071861401e-05 -6.40147918199555e-06 -1.02105622677626e-05 2.67499513239884e-05 3.45616282691286e-06 2.32937071861401e-05 2.99515634175836e-05 -6.50601019753823e-07 1.41746611972706e-05 -1.85657349786799e-05 1.2244905631376e-07 -6.40147918199555e-06 -6.50601019753823e-07 3.61712929207456e-05 850 857 0 30 0 849 859 0 34 0 0 0 0 0 0 0 9 0 2254 0 0 0 0 0 1970 +867 901 0.997685110061365 0.0168437934134779 0.0658840480335359 -0.00973785498670513 -0.0252704041123979 0.991291404757605 0.129239148595503 -0.0186611236784452 -0.0631334130064049 -0.13060489070911 0.989422323724821 0.0240854438470683 6.02646681380452e-05 -8.17779140684699e-05 -2.55665770000401e-06 -3.90053155718981e-05 -1.90035494939552e-05 -1.42448921946481e-05 -8.17779140684699e-05 0.000162906279435076 6.40023048470599e-06 9.37886730014753e-05 4.26384969461438e-05 4.53435268134911e-05 -2.55665770000401e-06 6.40023048470599e-06 1.00096287475375e-05 6.68823499083677e-07 6.08831500599171e-06 6.90062846601851e-07 -3.90053155718981e-05 9.37886730014753e-05 6.68823499083677e-07 0.000121327533456143 3.90114846032577e-05 4.29254838155337e-05 -1.90035494939552e-05 4.26384969461438e-05 6.08831500599171e-06 3.90114846032577e-05 3.5259065607019e-05 2.07964161445791e-05 -1.42448921946481e-05 4.53435268134911e-05 6.90062846601851e-07 4.29254838155337e-05 2.07964161445791e-05 6.00397828034634e-05 813 822 0 38 0 813 822 0 50 0 0 0 0 0 0 5 7 0 2611 0 0 0 0 0 1334 +868 922 0.998471873423641 0.000815320617060083 0.055256250634433 -0.00635235467862693 -0.00796985367106385 0.991562633501304 0.129383249597546 -0.0157954396931511 -0.0546845445655873 -0.129625919847268 0.990053898274939 0.0248212190040669 2.64348585410212e-05 -2.51525270781627e-05 -4.98163575794535e-07 -8.58384862115721e-07 2.09125201782175e-07 8.98345163990318e-06 -2.51525270781627e-05 4.5098847999498e-05 2.48935567966971e-06 3.06428028706924e-06 8.47591713060611e-07 -2.85349610289236e-07 -4.98163575794535e-07 2.48935567966971e-06 9.98921185078336e-06 -3.2587031032148e-06 2.29262964468786e-06 -8.35211943163666e-07 -8.58384862115721e-07 3.06428028706924e-06 -3.2587031032148e-06 5.0254950935435e-05 1.45650269648184e-05 -6.59981706708581e-08 2.09125201782175e-07 8.47591713060611e-07 2.29262964468786e-06 1.45650269648184e-05 2.43480755307752e-05 2.0899398329289e-06 8.98345163990318e-06 -2.85349610289236e-07 -8.35211943163666e-07 -6.59981706708581e-08 2.0899398329289e-06 2.55184900140557e-05 900 902 0 25 0 896 908 0 35 0 0 0 0 0 0 1 14 0 2683 0 0 0 0 0 1964 +867 915 0.99785902399033 0.0168518916989101 0.063193211559749 -0.0126472481491064 -0.0248390566574098 0.99148607964791 0.127821653599021 -0.0221878208007282 -0.0605011529265103 -0.129117650267446 0.989781916830155 0.0223173808056203 2.76820032241026e-05 -3.51889619494784e-05 2.37741000145126e-07 -1.32587794342787e-05 -7.71636757821763e-06 1.52916054214629e-06 -3.51889619494784e-05 9.16196807762748e-05 5.00547716945231e-06 4.19348293313255e-05 2.04083473297727e-05 1.65636239390046e-05 2.37741000145126e-07 5.00547716945231e-06 9.40251604836962e-06 3.5062299001119e-07 3.19628389727351e-06 6.00712746648833e-07 -1.32587794342787e-05 4.19348293313255e-05 3.5062299001119e-07 6.78822108046431e-05 1.92985110041936e-05 2.15048526237421e-05 -7.71636757821763e-06 2.04083473297727e-05 3.19628389727351e-06 1.92985110041936e-05 2.5377140654228e-05 9.39895239933526e-06 1.52916054214629e-06 1.65636239390046e-05 6.00712746648833e-07 2.15048526237421e-05 9.39895239933526e-06 3.44192893104867e-05 846 849 0 31 0 845 849 0 46 0 0 0 0 0 0 4 9 0 2667 0 0 0 0 0 1945 +867 916 0.997540066349928 0.0168770778848756 0.0680366097674595 -0.00326668528278396 -0.0255983591547188 0.99125834586703 0.129428033120901 -0.0174093055134628 -0.0652574902610248 -0.130851274319461 0.989251941607296 0.0233658367990382 3.55390431949314e-05 -3.19313283051733e-05 9.45301607086746e-09 -1.78670361684596e-05 -1.01813459271182e-05 -3.37033042293691e-06 -3.19313283051733e-05 5.55653584214962e-05 3.75355347303649e-06 1.50204625470865e-05 7.47084436421047e-06 1.70029329907824e-05 9.45301607086746e-09 3.75355347303649e-06 1.01955584540433e-05 -3.12840755021692e-06 1.58886540360315e-06 -1.1105151259977e-06 -1.78670361684596e-05 1.50204625470865e-05 -3.12840755021692e-06 7.20969956669697e-05 2.75761696284019e-05 1.86363522798887e-05 -1.01813459271182e-05 7.47084436421047e-06 1.58886540360315e-06 2.75761696284019e-05 3.62435901619698e-05 9.4362101152066e-06 -3.37033042293691e-06 1.70029329907824e-05 -1.1105151259977e-06 1.86363522798887e-05 9.4362101152066e-06 4.04509435424305e-05 851 857 0 32 0 850 857 0 44 0 0 0 0 0 0 7 12 0 2557 0 0 0 0 0 1332 +868 926 0.998322959894212 0.000677803046577641 0.0578861670098251 -0.00750342937020699 -0.00835171507250151 0.991157094524444 0.132430596272957 -0.0158348015649223 -0.057284523245001 -0.132691953625279 0.98950054514371 0.0280674039746036 4.95070940666547e-05 -6.67956038903775e-05 -6.51132365987084e-06 -1.69235019009383e-05 -1.12261564749716e-05 3.54831232153548e-07 -6.67956038903775e-05 0.000169509889170728 1.63267284817397e-05 6.26469577573185e-05 2.7452239795657e-05 2.78256819552667e-05 -6.51132365987084e-06 1.63267284817397e-05 1.26260750698308e-05 -5.14368898573276e-07 5.36179488738302e-06 3.57895573380146e-07 -1.69235019009383e-05 6.26469577573185e-05 -5.14368898573276e-07 7.9244013942034e-05 2.45583019130328e-05 2.39034540535052e-05 -1.12261564749716e-05 2.7452239795657e-05 5.36179488738302e-06 2.45583019130328e-05 3.22063757553547e-05 7.64163072444251e-06 3.54831232153548e-07 2.78256819552667e-05 3.57895573380146e-07 2.39034540535052e-05 7.64163072444251e-06 3.539186074579e-05 869 874 0 20 0 867 879 0 29 0 0 0 0 0 0 2 9 0 2602 0 0 0 0 0 1456 +868 920 0.9979373201913 -0.000381224916951108 0.0641947010038137 -0.00738035279156232 -0.00786521381078437 0.991722584378714 0.128157926188414 -0.0200436263038204 -0.0637121917776888 -0.128398482470655 0.989673979812603 0.0246063421723863 3.60351120815154e-05 -4.0041400607564e-05 -4.40954135109029e-06 -4.06743838524423e-06 -6.60575701634118e-06 6.26984518370193e-06 -4.0041400607564e-05 7.59853355905513e-05 7.95482056476745e-06 1.56106814789841e-05 1.28706027726161e-05 3.61689287872851e-06 -4.40954135109029e-06 7.95482056476745e-06 1.05128419185377e-05 -9.46545236392903e-07 3.77938675546317e-06 -2.71679314151671e-06 -4.06743838524423e-06 1.56106814789841e-05 -9.46545236392903e-07 4.64677782095235e-05 1.17085881273708e-05 1.08067001681981e-05 -6.60575701634118e-06 1.28706027726161e-05 3.77938675546317e-06 1.17085881273708e-05 2.7178058411858e-05 5.48437035801264e-06 6.26984518370193e-06 3.61689287872851e-06 -2.71679314151671e-06 1.08067001681981e-05 5.48437035801264e-06 3.14332008065339e-05 884 887 0 20 0 881 891 0 29 0 0 0 0 0 0 2 8 0 2384 0 0 0 0 0 2040 +868 872 0.999293472166287 -0.00290147389116851 -0.0374718285530019 -0.00132125689117364 0.00285219893870235 0.999994996240143 -0.00136837710101419 0.00056477262814818 0.0374756113634023 0.0012605331948752 0.999296747522478 0.0147672435492485 1.95238362735714e-05 -2.09273081957053e-05 3.52702074534831e-06 -2.85157380436302e-06 1.98245943586879e-06 8.22190249493924e-06 -2.09273081957053e-05 3.64590172755219e-05 -3.61210662756075e-06 1.29048408477635e-05 4.18969233888243e-06 -6.64310726978322e-06 3.52702074534831e-06 -3.61210662756075e-06 8.73724148602356e-06 2.23990044650581e-06 4.64669445271826e-07 1.00461961592334e-06 -2.85157380436302e-06 1.29048408477635e-05 2.23990044650581e-06 3.86439799788019e-05 6.93216006235759e-06 -7.42934014029473e-07 1.98245943586879e-06 4.18969233888243e-06 4.64669445271826e-07 6.93216006235759e-06 2.16526574750157e-05 3.35659072769763e-06 8.22190249493924e-06 -6.64310726978322e-06 1.00461961592334e-06 -7.42934014029473e-07 3.35659072769763e-06 2.62988663357059e-05 802 801 0 6 0 800 811 0 21 0 0 0 0 0 0 15 24 0 2230 0 0 0 0 0 2362 +868 871 0.999529999186224 0.00851129711893673 -0.0294506120163915 0.00299058684989162 -0.00835031342216295 0.999949539278869 0.00558490480929759 -0.00748744095811892 0.0294966607014843 -0.00533635805868097 0.999550634180246 0.0116737044870281 3.15535400741331e-05 -3.65085029281717e-05 3.40733594006077e-06 -1.43896004108089e-05 -8.61662133824995e-06 1.19435739349031e-05 -3.65085029281717e-05 6.02226499090221e-05 -2.88771049925637e-06 3.25349225653405e-05 2.11817394494059e-05 -7.60070358413913e-06 3.40733594006077e-06 -2.88771049925637e-06 8.21788120118078e-06 4.43285331076188e-07 2.1518529891446e-06 5.90186578574313e-07 -1.43896004108089e-05 3.25349225653405e-05 4.43285331076188e-07 6.50526197741341e-05 2.8323540569727e-05 3.73997443369521e-06 -8.61662133824995e-06 2.11817394494059e-05 2.1518529891446e-06 2.8323540569727e-05 3.23162844749944e-05 4.7859926134877e-06 1.19435739349031e-05 -7.60070358413913e-06 5.90186578574313e-07 3.73997443369521e-06 4.7859926134877e-06 2.89817865889938e-05 793 799 0 28 0 790 800 0 34 0 0 0 0 0 0 0 10 0 2278 0 0 0 0 0 2726 +868 925 0.998223085517768 0.000739630821363802 0.0595829210901512 -0.00561268691339743 -0.00849673965149373 0.99147199942492 0.130042607524023 -0.0137653922713837 -0.0589786143842141 -0.130317793499585 0.989716522920941 0.0237116280210159 2.76810817599875e-05 -2.84463553592491e-05 1.08919505055236e-06 -9.62555847634571e-06 -5.87612215540893e-06 -9.10693873838463e-08 -2.84463553592491e-05 5.22617787333266e-05 1.63846890207841e-06 1.92135254954667e-05 1.03805779356934e-05 9.73945819982954e-06 1.08919505055236e-06 1.63846890207841e-06 9.2031692187378e-06 -1.15736321620211e-06 3.26866365845265e-06 4.88265559059388e-07 -9.62555847634571e-06 1.92135254954667e-05 -1.15736321620211e-06 6.51602641687917e-05 1.83807259376363e-05 2.07983498433315e-05 -5.87612215540893e-06 1.03805779356934e-05 3.26866365845265e-06 1.83807259376363e-05 2.49959793055756e-05 7.41840587286773e-06 -9.10693873838463e-08 9.73945819982954e-06 4.88265559059388e-07 2.07983498433315e-05 7.41840587286773e-06 3.14294548981119e-05 880 886 0 20 0 879 890 0 28 0 0 0 0 0 0 4 14 0 2551 0 0 0 0 0 1801 +868 923 0.998110078898767 0.000567557645534566 0.0614487451378448 -0.00229406043077763 -0.00867907974260704 0.991235847232631 0.131818696457786 -0.013378951837958 -0.0608353842390946 -0.132102888080948 0.989367415566712 0.0231949907586398 2.8334287305588e-05 -3.5703786039522e-05 5.5162759539509e-07 -1.4855705009716e-05 -7.81001050469647e-06 6.34307079746337e-06 -3.5703786039522e-05 9.40311740535904e-05 4.93450214453597e-06 4.63662759704963e-05 2.18638727105787e-05 1.09495248569246e-06 5.5162759539509e-07 4.93450214453597e-06 1.02319933847103e-05 1.47168851404965e-06 5.16694389571177e-06 -8.15290792741684e-07 -1.4855705009716e-05 4.63662759704963e-05 1.47168851404965e-06 7.12808179526053e-05 2.30806665425215e-05 6.85593181055174e-06 -7.81001050469647e-06 2.18638727105787e-05 5.16694389571177e-06 2.30806665425215e-05 2.6991688121023e-05 2.08378079211062e-06 6.34307079746337e-06 1.09495248569246e-06 -8.15290792741684e-07 6.85593181055174e-06 2.08378079211062e-06 2.46315783242156e-05 891 896 0 24 0 890 903 0 35 0 0 0 0 0 0 2 14 0 2528 0 0 0 0 0 2006 +868 928 0.998259325184186 0.000588014515236919 0.0589743496932688 -0.00518965759749978 -0.00840211826421964 0.991168755829491 0.132340099274912 -0.014280799739942 -0.058375714912009 -0.13260524765766 0.989448393905494 0.0246987642786286 3.72453415194149e-05 -4.2860017337745e-05 -4.48372086357241e-06 -8.44056829687086e-06 -6.90918279048735e-06 1.51250121621398e-05 -4.2860017337745e-05 0.000108584492425576 9.03675113864145e-06 4.17515850369911e-05 2.00575512417324e-05 -8.21075398663312e-06 -4.48372086357241e-06 9.03675113864145e-06 1.09887678422514e-05 -7.10459137849677e-07 5.66765013855565e-06 -3.56815852869783e-06 -8.44056829687086e-06 4.17515850369911e-05 -7.10459137849677e-07 6.16308431752132e-05 1.43453181963574e-05 7.38619636863158e-06 -6.90918279048735e-06 2.00575512417324e-05 5.66765013855565e-06 1.43453181963574e-05 2.46092617196526e-05 -9.31043715086923e-07 1.51250121621398e-05 -8.21075398663312e-06 -3.56815852869783e-06 7.38619636863158e-06 -9.31043715086923e-07 2.9447664902682e-05 881 883 0 23 0 875 890 0 36 0 0 0 0 0 0 0 13 0 2572 0 0 0 0 0 2026 +868 927 0.998336340260314 0.000158922596898906 0.0576587067081013 -0.00890054017097703 -0.00780191142487237 0.991171686301355 0.132354895839353 -0.0165244516783653 -0.0571286433740649 -0.132584550450404 0.989523953771763 0.0286106843869045 4.59085907244027e-05 -6.78999336868273e-05 -5.17139555364211e-06 -1.43546069374195e-05 -6.73475827215145e-06 6.49044351155502e-07 -6.78999336868273e-05 0.000166640427624289 1.25763496498171e-05 6.01878650349437e-05 2.73711271415809e-05 2.31240957203676e-05 -5.17139555364211e-06 1.25763496498171e-05 1.15460954665312e-05 1.90307973594438e-07 4.27678580699413e-06 -3.3608629277059e-07 -1.43546069374195e-05 6.01878650349437e-05 1.90307973594438e-07 7.30811126843742e-05 2.10458609196698e-05 2.57804591162384e-05 -6.73475827215145e-06 2.73711271415809e-05 4.27678580699413e-06 2.10458609196698e-05 2.7019235456297e-05 1.09077380208014e-05 6.49044351155502e-07 2.31240957203676e-05 -3.3608629277059e-07 2.57804591162384e-05 1.09077380208014e-05 3.38383732695666e-05 853 858 0 20 0 852 863 0 29 0 0 0 0 0 0 5 12 0 2639 0 0 0 0 0 1464 +868 924 0.998398763835065 0.00109693074810781 0.056557096067137 -0.00483760406698098 -0.00858497607758713 0.991169044375322 0.132326201705701 -0.014669330828336 -0.0559124901820761 -0.132599857522715 0.989591365780136 0.0265852857508111 3.75135968603588e-05 -4.13779211574287e-05 -1.36161459461047e-06 -1.91256239900408e-05 -9.4881904000594e-06 1.89271145728081e-06 -4.13779211574287e-05 7.59756678618422e-05 4.87288037310413e-06 3.85347892214849e-05 1.92260569400377e-05 1.16991213997119e-05 -1.36161459461047e-06 4.87288037310413e-06 1.08415667862032e-05 -2.83106588727313e-06 3.75284552555679e-06 1.17963544146916e-07 -1.91256239900408e-05 3.85347892214849e-05 -2.83106588727313e-06 8.37766997832681e-05 3.11320480490711e-05 1.5757306241945e-05 -9.4881904000594e-06 1.92260569400377e-05 3.75284552555679e-06 3.11320480490711e-05 3.31785340715913e-05 9.20383241106296e-06 1.89271145728081e-06 1.16991213997119e-05 1.17963544146916e-07 1.5757306241945e-05 9.20383241106296e-06 3.30970624145472e-05 870 871 0 26 0 866 874 0 32 0 0 0 0 0 0 3 13 0 2613 0 0 0 0 0 1461 +868 916 0.998374063966542 0.000845395472939299 0.056995734098484 -0.00502341705882652 -0.0082828249305172 0.991429258567944 0.130381824141969 -0.0154068448470434 -0.0563970141949125 -0.130641917323312 0.989824260274514 0.0249322684992373 3.39373103888456e-05 -3.71817351955327e-05 -2.26939324960476e-06 -3.44346869415273e-06 -4.29195875377333e-06 8.25915290434502e-06 -3.71817351955327e-05 9.19307562309477e-05 7.30793939444346e-06 1.89686219200983e-05 6.99704563928629e-06 1.19522626772677e-05 -2.26939324960476e-06 7.30793939444346e-06 1.01553787426435e-05 2.81451838479266e-08 2.78556989585025e-06 3.80718696884965e-07 -3.44346869415273e-06 1.89686219200983e-05 2.81451838479266e-08 5.07519275664039e-05 4.52072459738259e-06 2.42479383890504e-06 -4.29195875377333e-06 6.99704563928629e-06 2.78556989585025e-06 4.52072459738259e-06 2.38807714508744e-05 1.97323500808228e-06 8.25915290434502e-06 1.19522626772677e-05 3.80718696884965e-07 2.42479383890504e-06 1.97323500808228e-06 3.24184034736039e-05 874 877 0 19 0 871 880 0 27 0 0 0 0 0 0 1 6 0 2505 0 0 0 0 0 2025 +868 898 0.998375368216777 0.000657543784196349 0.0569753611150153 -0.00898974699081334 -0.0080090784389152 0.991625469920299 0.128898340051006 -0.0166969648437034 -0.0564134629372621 -0.129145247847211 0.990019709984558 0.024100391711292 3.54317515883908e-05 -4.20138142981205e-05 -3.38678133779547e-06 -4.71018476746237e-06 -3.79117011303864e-06 -7.3116242077305e-06 -4.20138142981205e-05 7.10515315700574e-05 5.76902871615506e-06 1.87734024428099e-05 1.36807064292679e-05 2.86395924306219e-05 -3.38678133779547e-06 5.76902871615506e-06 1.17738134586542e-05 -2.51868046810354e-06 2.52210141145069e-06 -9.03080239713846e-07 -4.71018476746237e-06 1.87734024428099e-05 -2.51868046810354e-06 6.13725798201121e-05 1.70094104064438e-05 1.91284228277367e-05 -3.79117011303864e-06 1.36807064292679e-05 2.52210141145069e-06 1.70094104064438e-05 2.52620694790654e-05 1.5319676724892e-05 -7.3116242077305e-06 2.86395924306219e-05 -9.03080239713846e-07 1.91284228277367e-05 1.5319676724892e-05 5.51097719841229e-05 884 888 0 21 0 882 893 0 30 0 0 0 0 0 0 2 10 0 2699 0 0 0 0 0 1845 +868 900 0.998630152936522 0.000332813562890603 0.052323100836159 -0.0134391629138714 -0.00702653593847092 0.99177521167211 0.127798893991484 -0.0194653002516664 -0.05185022120188 -0.127991479200271 0.990418969837231 0.0220345488051713 3.61553145657707e-05 -3.57009660502647e-05 5.51469860780493e-06 -2.32691266219263e-05 -1.23836184987013e-05 1.76873137321929e-06 -3.57009660502647e-05 6.87816533908051e-05 -8.70849205931604e-08 3.67673775706433e-05 1.92533214261415e-05 8.87325560649206e-06 5.51469860780493e-06 -8.70849205931604e-08 1.07449193387115e-05 -3.26642368822721e-06 3.11491068671564e-06 1.55246284398059e-06 -2.32691266219263e-05 3.67673775706433e-05 -3.26642368822721e-06 8.27931116138403e-05 3.34027719323765e-05 1.23857173751357e-05 -1.23836184987013e-05 1.92533214261415e-05 3.11491068671564e-06 3.34027719323765e-05 3.61668417633481e-05 8.77858098418385e-06 1.76873137321929e-06 8.87325560649206e-06 1.55246284398059e-06 1.23857173751357e-05 8.77858098418385e-06 2.96795013893162e-05 908 914 0 25 0 905 920 0 36 0 0 0 0 0 0 1 14 0 2602 0 0 0 0 0 2083 +868 915 0.998277207012744 0.0010529462216071 0.0586643781445804 -0.00245793517417053 -0.00886553074095228 0.991066419880222 0.133074241498802 -0.0130062693733706 -0.0580001752024694 -0.133365072976603 0.989368352529243 0.0279647252396369 4.21170596874008e-05 -5.63569193480548e-05 -2.36629205511137e-06 -1.13609748862606e-05 -7.43820751834329e-06 3.2010086819199e-06 -5.63569193480548e-05 0.000139917845161995 1.03103680613437e-05 5.58351726276736e-05 2.67405400009229e-05 1.58637357703326e-05 -2.36629205511137e-06 1.03103680613437e-05 1.2342122188595e-05 6.30875106341906e-07 5.22123829932272e-06 1.73145489936677e-06 -1.13609748862606e-05 5.58351726276736e-05 6.30875106341906e-07 8.4077452195578e-05 2.56741348895958e-05 1.55333278749766e-05 -7.43820751834329e-06 2.67405400009229e-05 5.22123829932272e-06 2.56741348895958e-05 3.05942006980547e-05 7.97681113404419e-06 3.2010086819199e-06 1.58637357703326e-05 1.73145489936677e-06 1.55333278749766e-05 7.97681113404419e-06 3.27805141076815e-05 872 872 0 20 0 866 875 0 28 0 0 0 0 0 0 0 6 0 2629 0 0 0 0 0 1459 +868 914 0.998394710892641 -4.2116895606542e-06 0.0566392200145899 -0.0108290413384359 -0.00726529635090126 0.991729338794222 0.128141070869992 -0.0181663018708591 -0.0561713159053002 -0.128346868123209 0.990137295890035 0.0216268802042362 3.58182438836828e-05 -3.49109819158998e-05 2.03745934961577e-06 -1.32882818008465e-05 -9.61385959218997e-06 3.45375052139421e-06 -3.49109819158998e-05 6.78705163510857e-05 2.22520096296166e-06 3.06073583704448e-05 2.00018921581296e-05 5.83438933268796e-06 2.03745934961577e-06 2.22520096296166e-06 9.64791872886608e-06 -2.32057525088183e-06 3.89820463648559e-06 4.427356368013e-07 -1.32882818008465e-05 3.06073583704448e-05 -2.32057525088183e-06 7.09472424678573e-05 2.40545470010303e-05 8.42892414368559e-06 -9.61385959218997e-06 2.00018921581296e-05 3.89820463648559e-06 2.40545470010303e-05 3.11160537883394e-05 5.96867070357836e-06 3.45375052139421e-06 5.83438933268796e-06 4.427356368013e-07 8.42892414368559e-06 5.96867070357836e-06 2.94345358829241e-05 911 919 0 26 0 909 924 0 35 0 0 0 0 0 0 0 14 0 2693 0 0 0 0 0 2079 +868 918 0.998158421307746 0.000384741581367923 0.0606598544866662 -0.00563315096042951 -0.00819107524672926 0.991676406662936 0.128494399700494 -0.0204841356987346 -0.060105509387496 -0.128754636584487 0.989853307970058 0.0246798644510871 4.38908353056827e-05 -5.95482998738071e-05 -3.94081728987716e-06 -1.80325119011127e-05 -1.28696382576682e-05 4.75121461299637e-06 -5.95482998738071e-05 0.000153585024354209 1.06810961311454e-05 6.82569170924854e-05 2.99947531677766e-05 1.57105502740281e-05 -3.94081728987716e-06 1.06810961311454e-05 1.05449008223673e-05 8.07781010035894e-07 4.56454108058373e-06 7.27826882522017e-08 -1.80325119011127e-05 6.82569170924854e-05 8.07781010035894e-07 8.4196899902177e-05 1.99957435963498e-05 2.07181768097155e-05 -1.28696382576682e-05 2.99947531677766e-05 4.56454108058373e-06 1.99957435963498e-05 3.52337917831144e-05 8.11827427432376e-06 4.75121461299637e-06 1.57105502740281e-05 7.27826882522017e-08 2.07181768097155e-05 8.11827427432376e-06 3.59207092262819e-05 883 887 0 26 0 881 892 0 34 0 0 0 0 0 0 1 14 0 2352 0 0 0 0 0 2081 +868 901 0.998350712024537 0.000715699206793651 0.0574050831786237 -0.00611777108625443 -0.00828972402040956 0.991240201892032 0.131811011029844 -0.0146937860853616 -0.0568078892035671 -0.132069489011239 0.989611294295162 0.0226633140238149 4.97722532062283e-05 -5.68123428385068e-05 -2.98592127813545e-06 -7.4550424427379e-06 -1.04618786747982e-05 2.08356009073401e-05 -5.68123428385068e-05 0.000123664610734419 5.79083246740908e-06 4.67967962589958e-05 2.93367060056438e-05 -1.06100829731342e-05 -2.98592127813545e-06 5.79083246740908e-06 1.00131957519044e-05 -1.99653993687584e-06 4.82512497869524e-06 -2.62496424473125e-06 -7.4550424427379e-06 4.67967962589958e-05 -1.99653993687584e-06 7.61490615320033e-05 1.97845930398317e-05 1.48452201308782e-05 -1.04618786747982e-05 2.93367060056438e-05 4.82512497869524e-06 1.97845930398317e-05 2.67088425886687e-05 3.38599590476719e-06 2.08356009073401e-05 -1.06100829731342e-05 -2.62496424473125e-06 1.48452201308782e-05 3.38599590476719e-06 3.56817801553913e-05 857 856 0 26 0 856 864 0 41 0 0 0 0 0 0 3 14 0 2571 0 0 0 0 0 2030 +868 899 0.997813981740875 0.000372715168541562 0.0660841806018959 -0.00246213920462721 -0.00911303871935498 0.99120668074911 0.13200859276438 -0.01351739272566 -0.0654538796995288 -0.132322247266798 0.989043281414188 0.0254318554239893 3.81382986979826e-05 -5.08782873023392e-05 -2.18593524147872e-06 -1.40423128029411e-05 -1.12907385818852e-05 8.46358119269533e-06 -5.08782873023392e-05 0.000121626647307065 6.70807307663984e-06 5.66958883659351e-05 3.27161549493277e-05 2.4444413989016e-06 -2.18593524147872e-06 6.70807307663984e-06 9.9979505610554e-06 1.18934718715042e-06 5.95750046126083e-06 -7.23466700747892e-07 -1.40423128029411e-05 5.66958883659351e-05 1.18934718715042e-06 7.9277054365265e-05 2.46553768489893e-05 1.5247065583202e-05 -1.12907385818852e-05 3.27161549493277e-05 5.95750046126083e-06 2.46553768489893e-05 3.1011369235712e-05 3.10213071646305e-06 8.46358119269533e-06 2.4444413989016e-06 -7.23466700747892e-07 1.5247065583202e-05 3.10213071646305e-06 3.19239189297006e-05 894 901 0 26 0 893 905 0 33 0 0 0 0 0 0 2 12 0 2673 0 0 0 0 0 1998 +868 919 0.998384410217917 0.00085787166740727 0.0568140254692777 -0.0071161173427753 -0.00826407316598698 0.99144636932607 0.130252838145128 -0.0165174779979974 -0.0562163190588702 -0.130511918254065 0.98985168821653 0.0258410690367599 2.98340124253985e-05 -2.64104363128898e-05 -2.0229633844742e-06 3.35232848641086e-06 -5.16367604510325e-06 6.05419769135727e-06 -2.64104363128898e-05 6.72207508199678e-05 5.52228197773383e-06 8.83101733111139e-06 3.18677996054197e-06 1.05146393415248e-05 -2.0229633844742e-06 5.52228197773383e-06 1.04813714720221e-05 -2.84293817890449e-06 2.25306369748987e-06 -7.65657195798609e-07 3.35232848641086e-06 8.83101733111139e-06 -2.84293817890449e-06 5.28053115667843e-05 6.78034063300573e-06 1.18426979954237e-05 -5.16367604510325e-06 3.18677996054197e-06 2.25306369748987e-06 6.78034063300573e-06 2.60560610115937e-05 1.94897368494427e-06 6.05419769135727e-06 1.05146393415248e-05 -7.65657195798609e-07 1.18426979954237e-05 1.94897368494427e-06 3.53905231930369e-05 889 895 0 23 0 887 898 0 32 0 0 0 0 0 0 5 13 0 2398 0 0 0 0 0 1988 +869 872 0.999428715969392 -0.0138364182021755 -0.0308349676034652 0.00953616522388804 0.0136528755338578 0.999887850919971 -0.00615504445960257 0.00751943776362453 0.0309166732594118 0.00573054220621447 0.99950553785389 0.0143902342091085 5.33739272905948e-05 -5.92757912151478e-05 3.95450225194426e-06 -1.92602407522566e-05 -1.91111900927713e-05 1.32795579960578e-05 -5.92757912151478e-05 8.80418363849231e-05 -4.37001809256436e-06 4.83149079011499e-05 3.38730935794499e-05 -3.21250368224874e-07 3.95450225194426e-06 -4.37001809256436e-06 1.02996945329091e-05 -4.1660523444111e-06 -2.08894234322936e-06 -1.15973574039423e-06 -1.92602407522566e-05 4.83149079011499e-05 -4.1660523444111e-06 0.000105356526532088 3.34282044064891e-05 1.85674427921698e-05 -1.91111900927713e-05 3.38730935794499e-05 -2.08894234322936e-06 3.34282044064891e-05 4.16554991899608e-05 8.91559446119312e-06 1.32795579960578e-05 -3.21250368224874e-07 -1.15973574039423e-06 1.85674427921698e-05 8.91559446119312e-06 4.35777255415224e-05 800 800 0 2 0 808 814 0 13 0 0 0 0 0 0 27 35 0 2199 0 0 0 0 0 1927 +869 871 0.999638924278373 -0.00335749325939944 -0.0266598632140095 0.00667031607969137 0.00337897434057162 0.999994001887542 0.000760737368873123 -0.000273581936477642 0.0266571491345636 -0.000850545678801977 0.99964427321526 0.007993547885994 2.86087096401124e-05 -2.79024671919239e-05 7.73339998312521e-08 -1.52629071017871e-06 -4.72612600748552e-06 1.87640844392473e-05 -2.79024671919239e-05 4.57453750171966e-05 3.23566553033369e-07 1.26301723945441e-05 1.05759588106703e-05 -1.45687252037208e-05 7.73339998312521e-08 3.23566553033369e-07 8.67640069702968e-06 2.78534835042108e-07 9.95441249293963e-07 -1.2351374330052e-06 -1.52629071017871e-06 1.26301723945441e-05 2.78534835042108e-07 4.865942457264e-05 1.2281392904997e-05 2.09027040477263e-06 -4.72612600748552e-06 1.05759588106703e-05 9.95441249293963e-07 1.2281392904997e-05 2.73972281448692e-05 -4.35423149305821e-07 1.87640844392473e-05 -1.45687252037208e-05 -1.2351374330052e-06 2.09027040477263e-06 -4.35423149305821e-07 3.06582919525274e-05 803 805 0 12 0 804 817 0 23 0 0 0 0 0 0 18 29 0 2338 0 0 0 0 0 2935 +868 917 0.998319177177786 0.00148125880747629 0.0579363991926774 0.00296492907664909 -0.0092610251402681 0.990904895103864 0.134245008371081 -0.010108136669061 -0.0572106099637062 -0.134555916746703 0.989253077516585 0.0253118929512944 4.05307242499728e-05 -4.06515737055815e-05 -4.03535646300178e-06 -3.6097215784147e-06 -4.98231561342086e-06 9.16795215168861e-06 -4.06515737055815e-05 6.98813953487266e-05 1.00107564883988e-05 -7.61704558181047e-07 -3.62925815355782e-06 2.16548338853116e-06 -4.03535646300178e-06 1.00107564883988e-05 1.35782953282565e-05 -9.18172740072176e-06 -3.07548847950497e-06 4.74812987013875e-07 -3.6097215784147e-06 -7.61704558181047e-07 -9.18172740072176e-06 8.01946485171384e-05 3.58350464042077e-05 -3.00398258453636e-06 -4.98231561342086e-06 -3.62925815355782e-06 -3.07548847950497e-06 3.58350464042077e-05 5.00487839076847e-05 -5.55232391122829e-06 9.16795215168861e-06 2.16548338853116e-06 4.74812987013875e-07 -3.00398258453636e-06 -5.55232391122829e-06 3.26441709266717e-05 859 863 0 26 0 857 868 0 35 0 0 0 0 0 0 2 11 0 2285 0 0 0 0 0 1489 +869 922 0.998488648721314 -0.0105733120712631 0.0539316553290227 -0.00429681195892907 0.00374302198634793 0.992123473318961 0.125207841112014 -0.00953882597832439 -0.0548307227847175 -0.124816740709591 0.990663602378497 0.0228876960732181 3.49961369977307e-05 -4.14179724025855e-05 -1.10261891759052e-06 -9.85074574107014e-06 -5.56894763280376e-06 6.67389598109946e-06 -4.14179724025855e-05 9.19965000124632e-05 4.91860131461726e-06 3.15617038063104e-05 1.61534896951702e-05 2.16534100792949e-06 -1.10261891759052e-06 4.91860131461726e-06 9.16415349531211e-06 -1.59864559558828e-07 3.07637693655392e-06 -1.16422672585021e-06 -9.85074574107014e-06 3.15617038063104e-05 -1.59864559558828e-07 6.06055895117709e-05 1.96524441048608e-05 7.70798005692353e-06 -5.56894763280376e-06 1.61534896951702e-05 3.07637693655392e-06 1.96524441048608e-05 3.07771432400804e-05 3.06477132533777e-06 6.67389598109946e-06 2.16534100792949e-06 -1.16422672585021e-06 7.70798005692353e-06 3.06477132533777e-06 2.93662144977925e-05 881 877 0 10 0 875 888 0 22 0 0 0 0 0 0 15 29 0 2659 0 0 0 0 0 1740 +868 913 0.998271271028436 0.000305462127067134 0.0587739409275901 -0.00504498071558166 -0.00810970079558101 0.991137589264096 0.132591522733402 -0.0131490658913522 -0.0582125604339568 -0.132838947002169 0.989426658205184 0.0255079031829551 3.2491114643278e-05 -3.55096188851155e-05 2.45614059452764e-06 -9.16947555071645e-06 -5.20358879814786e-06 -1.51682295113386e-07 -3.55096188851155e-05 6.64442225058918e-05 1.43787427110931e-06 2.26286762881751e-05 1.21440248258328e-05 1.03382725533993e-05 2.45614059452764e-06 1.43787427110931e-06 1.07187495075148e-05 -3.65982545059131e-06 3.26976467119848e-06 -1.22895380550583e-07 -9.16947555071645e-06 2.26286762881751e-05 -3.65982545059131e-06 6.59152189152974e-05 2.00581861480068e-05 1.45859676993638e-05 -5.20358879814786e-06 1.21440248258328e-05 3.26976467119848e-06 2.00581861480068e-05 2.88826571329986e-05 8.29916507361197e-06 -1.51682295113386e-07 1.03382725533993e-05 -1.22895380550583e-07 1.45859676993638e-05 8.29916507361197e-06 3.44652302515453e-05 911 913 0 25 0 909 922 0 39 0 0 0 0 0 0 3 16 0 2550 0 0 0 0 0 1464 +869 925 0.998683854493852 -0.0100354715529393 0.0502975952110237 -0.00736726918615892 0.00382850716119303 0.992521145361706 0.122012780243726 -0.0117688142540605 -0.0511458825930156 -0.121659628967859 0.991253263991188 0.0210931069269713 3.2400382226413e-05 -3.60901293492968e-05 1.38357126585699e-06 -1.22525803699007e-05 -8.58899503520893e-06 -1.70600978289328e-06 -3.60901293492968e-05 7.93804827328705e-05 3.18230339245383e-06 2.85133783586155e-05 1.3403211099832e-05 1.10644294612781e-05 1.38357126585699e-06 3.18230339245383e-06 9.1583430722817e-06 1.36905168082166e-06 3.10130514026233e-06 7.16691205283057e-07 -1.22525803699007e-05 2.85133783586155e-05 1.36905168082166e-06 5.48348947546067e-05 1.37513654804211e-05 1.37547859248687e-05 -8.58899503520893e-06 1.3403211099832e-05 3.10130514026233e-06 1.37513654804211e-05 2.58473414013003e-05 6.19597610995355e-06 -1.70600978289328e-06 1.10644294612781e-05 7.16691205283057e-07 1.37547859248687e-05 6.19597610995355e-06 2.9771934628053e-05 856 856 0 5 0 860 872 0 24 0 0 0 0 0 0 14 29 0 2573 0 0 0 0 0 2223 +869 926 0.99862642330251 -0.0107975100230059 0.0512706588541539 -0.00945897018656144 0.0043372722979037 0.992212781410799 0.124478851513256 -0.0118899688804066 -0.0522154646733109 -0.124085495455143 0.990896732796411 0.0249133581056905 3.52922767379132e-05 -3.44149010955188e-05 -2.3633059036096e-06 -1.24029068745115e-05 -6.96569286214328e-06 6.08065267265652e-06 -3.44149010955188e-05 4.34723846116711e-05 4.04928140512682e-06 1.49502740277347e-05 7.80155189060362e-06 -1.4853370531029e-07 -2.3633059036096e-06 4.04928140512682e-06 1.12516020671928e-05 -1.82116397225166e-06 3.02581614973924e-06 -6.74413074146998e-07 -1.24029068745115e-05 1.49502740277347e-05 -1.82116397225166e-06 5.07427401766505e-05 1.21667320914088e-05 3.85562474097122e-06 -6.96569286214328e-06 7.80155189060362e-06 3.02581614973924e-06 1.21667320914088e-05 2.69160630573837e-05 5.75323971602991e-06 6.08065267265652e-06 -1.4853370531029e-07 -6.74413074146998e-07 3.85562474097122e-06 5.75323971602991e-06 3.3365258352976e-05 894 894 0 9 0 896 906 0 22 0 0 0 0 0 0 13 28 0 2607 0 0 0 0 0 1304 +869 929 0.997606696720414 -0.03303642559039 0.0607410342585124 -0.00942166721675548 0.0240611383294781 0.989435209038279 0.142965131195218 -0.0146447543349093 -0.0648223748475237 -0.141161473850293 0.987862084513592 0.0178548001371883 3.76748306745569e-05 -3.8689147488105e-05 -5.77721264796718e-06 2.22032737971704e-06 -4.48037834594325e-06 1.12085138287128e-05 -3.8689147488105e-05 8.09263019971055e-05 9.2726902243564e-06 1.08074668517717e-05 1.21843619513195e-05 -9.60370562635503e-06 -5.77721264796718e-06 9.2726902243564e-06 1.14502311537882e-05 -1.26056355987064e-06 3.00968110478538e-06 -3.53131644321339e-06 2.22032737971704e-06 1.08074668517717e-05 -1.26056355987064e-06 3.93112942871233e-05 2.35294467114741e-06 2.26789863157786e-06 -4.48037834594325e-06 1.21843619513195e-05 3.00968110478538e-06 2.35294467114741e-06 2.5859113886359e-05 -1.36462816931738e-06 1.12085138287128e-05 -9.60370562635503e-06 -3.53131644321339e-06 2.26789863157786e-06 -1.36462816931738e-06 2.52370352654835e-05 867 867 0 0 0 885 885 0 5 0 0 0 0 0 0 43 56 0 2632 0 0 0 0 0 2183 +869 873 0.99902846228908 -0.0255807676115125 -0.0358853154468756 0.00531996892051866 0.0249712436773881 0.999537912810272 -0.0173319890401861 0.0133209307283088 0.0363120988861905 0.0164190494027645 0.999205607615965 0.0162045343106814 4.80674752540898e-05 -5.94291653187158e-05 8.42531263126751e-06 -3.87337673365832e-05 -2.24216308204206e-05 2.13128556643102e-05 -5.94291653187158e-05 9.76889259784952e-05 -1.19763765016657e-05 7.62537970328084e-05 4.18811208439844e-05 -2.05068044374949e-05 8.42531263126751e-06 -1.19763765016657e-05 9.35585963385021e-06 -8.41358556003294e-06 -5.55518908599482e-06 3.23714980624363e-06 -3.87337673365832e-05 7.62537970328084e-05 -8.41358556003294e-06 0.000124885986157062 5.55148622538956e-05 1.74071727325516e-06 -2.24216308204206e-05 4.18811208439844e-05 -5.55518908599482e-06 5.55148622538956e-05 5.14533681547471e-05 -4.89032596111975e-06 2.13128556643102e-05 -2.05068044374949e-05 3.23714980624363e-06 1.74071727325516e-06 -4.89032596111975e-06 3.57820768768689e-05 751 750 0 1 0 758 758 0 2 0 0 0 0 0 0 27 32 0 2115 0 0 0 0 0 2499 +869 930 0.990695734152295 -0.0936445440305748 0.0987555654419105 -0.0208074558954349 0.07890886086006 0.986455133914001 0.143804243513459 -0.00903644050365245 -0.110884417346232 -0.134673561429169 0.984666277396444 -0.0264969292046974 2.02767358016661e-05 -1.58408666977691e-05 3.2993501462651e-06 1.06535072042556e-06 1.6586314926562e-06 3.50707885020356e-06 -1.58408666977691e-05 3.94018988072824e-05 -3.86421339198132e-07 2.97379410959512e-06 -2.18957168452094e-06 -1.32237991259274e-06 3.2993501462651e-06 -3.86421339198132e-07 9.52125025606763e-06 -9.60590692284928e-07 4.07621011100836e-06 5.8156494007085e-07 1.06535072042556e-06 2.97379410959512e-06 -9.60590692284928e-07 3.85094580926807e-05 -1.70583910003936e-07 5.96113110627728e-06 1.6586314926562e-06 -2.18957168452094e-06 4.07621011100836e-06 -1.70583910003936e-07 2.07474064258593e-05 1.00180628504925e-06 3.50707885020356e-06 -1.32237991259274e-06 5.8156494007085e-07 5.96113110627728e-06 1.00180628504925e-06 2.13190363692072e-05 999 999 0 0 0 1011 1011 0 0 0 0 0 0 0 0 129 136 0 2687 0 0 0 0 0 1606 +869 920 0.998797307911195 -0.0103512231476785 0.0479248358233708 -0.00856638593370407 0.00440481936264365 0.992451592834428 0.122557877946664 -0.0142459274906185 -0.0488317035923647 -0.12219937831165 0.991303574423352 0.0222083014765637 3.31128129429341e-05 -3.57251646554426e-05 -4.53082379884226e-06 6.64187889056761e-07 -3.61078676519122e-06 1.22411680653615e-05 -3.57251646554426e-05 8.63807416247277e-05 7.23934993396685e-06 2.40167042177738e-05 7.62015343382342e-06 -2.55674763160665e-06 -4.53082379884226e-06 7.23934993396685e-06 1.07562777299057e-05 -2.73910041693191e-06 3.44349586671203e-06 -3.05550021774814e-06 6.64187889056761e-07 2.40167042177738e-05 -2.73910041693191e-06 6.59272870702352e-05 1.09534993738311e-05 6.38543334107682e-06 -3.61078676519122e-06 7.62015343382342e-06 3.44349586671203e-06 1.09534993738311e-05 2.68302888572233e-05 -4.17930719237659e-07 1.22411680653615e-05 -2.55674763160665e-06 -3.05550021774814e-06 6.38543334107682e-06 -4.17930719237659e-07 2.68403715586436e-05 871 870 0 5 0 875 887 0 22 0 0 0 0 0 0 14 29 0 2416 0 0 0 0 0 2143 +869 923 0.998655138520567 -0.0101388053895381 0.0508440648624872 -0.00436228870973347 0.00370391136090908 0.992138279559873 0.125091627508026 -0.00960335538321951 -0.0517126227056631 -0.124735074687312 0.99084154424189 0.0242576466802758 2.98955099145533e-05 -3.51466737897794e-05 1.74248154167822e-06 -9.04965398089257e-06 -4.86353977383559e-06 5.86699752854262e-06 -3.51466737897794e-05 8.21251937783699e-05 2.70482983455183e-06 2.56672097266965e-05 1.55623413716873e-05 -2.0938434107646e-06 1.74248154167822e-06 2.70482983455183e-06 8.83878939443748e-06 7.36667344485488e-07 3.90539609561862e-06 3.33779484657991e-07 -9.04965398089257e-06 2.56672097266965e-05 7.36667344485488e-07 5.08453946587667e-05 1.74250625959385e-05 4.85147512229681e-06 -4.86353977383559e-06 1.55623413716873e-05 3.90539609561862e-06 1.74250625959385e-05 2.82873803867237e-05 4.33412892648917e-06 5.86699752854262e-06 -2.0938434107646e-06 3.33779484657991e-07 4.85147512229681e-06 4.33412892648917e-06 2.58805074544616e-05 866 866 0 8 0 867 882 0 30 0 0 0 0 0 0 12 28 0 2583 0 0 0 0 0 1771 +869 924 0.99844282975679 -0.0111076264754826 0.0546675071805465 -0.0039242921675209 0.00418668296912813 0.992132606037912 0.125121395940649 -0.0105670716722149 -0.0556272180948316 -0.124697685104824 0.990634190777064 0.0255570338603492 4.72202537949609e-05 -5.47399925504549e-05 -1.26997729116609e-06 -2.1360475901783e-05 -9.14064788583181e-06 3.37884793491211e-06 -5.47399925504549e-05 8.41613518377379e-05 4.33591507588159e-06 3.8869957397779e-05 1.4260837077142e-05 1.14368734323573e-06 -1.26997729116609e-06 4.33591507588159e-06 1.18698593123436e-05 -5.0252784181783e-07 2.43460732869682e-06 -1.52111208517857e-06 -2.1360475901783e-05 3.8869957397779e-05 -5.0252784181783e-07 7.74946322829624e-05 2.05991655891824e-05 1.39231290106578e-05 -9.14064788583181e-06 1.4260837077142e-05 2.43460732869682e-06 2.05991655891824e-05 3.27447556308912e-05 7.67607565598942e-06 3.37884793491211e-06 1.14368734323573e-06 -1.52111208517857e-06 1.39231290106578e-05 7.67607565598942e-06 3.52649670780333e-05 865 859 0 14 0 860 867 0 23 0 0 0 0 0 0 14 27 0 2635 0 0 0 0 0 1346 +869 921 0.998568015912881 -0.0106412354089862 0.0524278714500498 -0.00786980101659446 0.00419950640405225 0.992585223505106 0.121478138878077 -0.0141042383615331 -0.0533318079739918 -0.121084012934366 0.991208545196184 0.0189437839300049 3.72835202336606e-05 -3.9406794911628e-05 1.04270967035186e-06 -1.47978139890408e-05 -9.24091524607704e-06 -2.44949132462133e-06 -3.9406794911628e-05 6.89269297300758e-05 1.34927703131456e-06 2.85821870714917e-05 1.67932586446484e-05 9.26574186408017e-06 1.04270967035186e-06 1.34927703131456e-06 9.12724946624941e-06 9.83051576803268e-08 1.94022933267907e-06 1.81379496646676e-06 -1.47978139890408e-05 2.85821870714917e-05 9.83051576803268e-08 6.81399821996536e-05 2.19985651879947e-05 9.7698861672656e-06 -9.24091524607704e-06 1.67932586446484e-05 1.94022933267907e-06 2.19985651879947e-05 3.13364145282502e-05 7.63577766735895e-06 -2.44949132462133e-06 9.26574186408017e-06 1.81379496646676e-06 9.7698861672656e-06 7.63577766735895e-06 3.20787844626857e-05 847 839 0 11 0 843 854 0 28 0 0 0 0 0 0 15 30 0 2521 0 0 0 0 0 2162 +869 918 0.998585288674703 -0.0103630824324564 0.0521538854253327 -0.00697574157858591 0.00383241821077973 0.992300636859406 0.12379320926075 -0.0138636368325469 -0.0530352129543976 -0.123418202105347 0.990936533576175 0.0218171506632328 3.25504109890371e-05 -2.95266597562275e-05 -3.31129286223132e-06 -2.56744726201029e-06 -3.6773250493895e-06 1.23814672021141e-05 -2.95266597562275e-05 4.57448003524573e-05 5.16821730731314e-06 8.21061497305189e-06 5.21056073034436e-06 -4.71125464896127e-06 -3.31129286223132e-06 5.16821730731314e-06 1.01641778294796e-05 -3.92103689571133e-06 1.42165194582007e-06 -3.34720267386901e-06 -2.56744726201029e-06 8.21061497305189e-06 -3.92103689571133e-06 6.59397902627621e-05 1.50964299117302e-05 7.01164098761899e-06 -3.6773250493895e-06 5.21056073034436e-06 1.42165194582007e-06 1.50964299117302e-05 3.0046999738585e-05 2.74302020542899e-06 1.23814672021141e-05 -4.71125464896127e-06 -3.34720267386901e-06 7.01164098761899e-06 2.74302020542899e-06 2.84390899643959e-05 894 891 0 9 0 895 908 0 27 0 0 0 0 0 0 13 29 0 2384 0 0 0 0 0 2177 +869 898 0.998668037640017 -0.00990716848760555 0.0506359418673691 -0.00725231816177607 0.00362628367704676 0.992442524191997 0.122656782291528 -0.00965341672460132 -0.0514684433700007 -0.122309787784853 0.991156554308699 0.0185572709237022 4.73579344439335e-05 -5.14928574001801e-05 -5.516616708356e-06 -1.05222469920285e-05 -1.26258334409955e-05 5.22109517904489e-06 -5.14928574001801e-05 8.53398393243449e-05 7.90562178416222e-06 2.51183727987418e-05 2.02103345286672e-05 4.98102298037317e-06 -5.516616708356e-06 7.90562178416222e-06 1.00844964958552e-05 -2.91995192967845e-06 3.52176737611343e-06 -3.85233443404566e-06 -1.05222469920285e-05 2.51183727987418e-05 -2.91995192967845e-06 7.59770804516156e-05 2.49490867351082e-05 2.46583075772175e-05 -1.26258334409955e-05 2.02103345286672e-05 3.52176737611343e-06 2.49490867351082e-05 2.92587696491592e-05 1.01339879716737e-05 5.22109517904489e-06 4.98102298037317e-06 -3.85233443404566e-06 2.46583075772175e-05 1.01339879716737e-05 3.77435386770748e-05 881 881 0 9 0 883 894 0 23 0 0 0 0 0 0 15 31 0 2676 0 0 0 0 0 2237 +869 927 0.998725490652499 -0.0106736554401945 0.0493301875170759 -0.0123007650813422 0.00450449994091604 0.992332388423247 0.12351574946741 -0.0124785646073387 -0.0502703073514391 -0.123136119663395 0.991115730998673 0.0251425569203034 4.26807165444833e-05 -4.28339186108709e-05 -4.29800413955594e-06 -1.19561728785525e-05 -7.83671422707763e-06 2.43111722109214e-06 -4.28339186108709e-05 6.07358299249377e-05 6.79681015491575e-06 1.79519051758674e-05 8.20794122307028e-06 5.11735156481438e-06 -4.29800413955594e-06 6.79681015491575e-06 1.11969474932797e-05 5.56061180203034e-07 2.29573786121497e-06 -2.2187342339245e-06 -1.19561728785525e-05 1.79519051758674e-05 5.56061180203034e-07 4.95524791319548e-05 9.0837233714598e-06 1.39782863896951e-05 -7.83671422707763e-06 8.20794122307028e-06 2.29573786121497e-06 9.0837233714598e-06 2.62879353303325e-05 6.37273722884098e-06 2.43111722109214e-06 5.11735156481438e-06 -2.2187342339245e-06 1.39782863896951e-05 6.37273722884098e-06 3.13696008920431e-05 882 883 0 5 0 889 901 0 24 0 0 0 0 0 0 13 30 0 2642 0 0 0 0 0 1309 +869 914 0.998952734598419 -0.0100367202977843 0.0446396492370222 -0.00992621589682492 0.00445749863754238 0.992350940543742 0.123368316466781 -0.0108941150568339 -0.0455364111918873 -0.12304013592164 0.991356424404537 0.0219215220995548 3.0900555416184e-05 -3.80581383559931e-05 -9.00911015592267e-07 -8.24998425850783e-06 -5.63933585765094e-06 1.15071081478485e-05 -3.80581383559931e-05 8.74588490582309e-05 3.8134974147889e-06 3.53358661541897e-05 1.76761377561592e-05 -7.58819991490739e-06 -9.00911015592267e-07 3.8134974147889e-06 8.86333476232078e-06 -4.67661736970321e-08 4.5404492230361e-06 -1.29583328753215e-06 -8.24998425850783e-06 3.53358661541897e-05 -4.67661736970321e-08 6.75055249363018e-05 2.02094014095579e-05 5.6096427162035e-06 -5.63933585765094e-06 1.76761377561592e-05 4.5404492230361e-06 2.02094014095579e-05 2.70027324106485e-05 1.29393822117438e-06 1.15071081478485e-05 -7.58819991490739e-06 -1.29583328753215e-06 5.6096427162035e-06 1.29393822117438e-06 2.51007078354746e-05 882 883 0 10 0 883 897 0 26 0 0 0 0 0 0 13 29 0 2687 0 0 0 0 0 2177 +869 916 0.998647935571665 -0.0102662357462574 0.0509598389131462 -0.00507516429849237 0.00387113291972971 0.992269865915482 0.124038411494141 -0.0107225187469944 -0.0518393200994123 -0.123673431260211 0.990967995089628 0.0241938155110174 4.30230894147803e-05 -4.84221623501561e-05 -4.35032074325214e-06 -5.10558338175123e-06 -6.61666024828696e-06 8.21794045616883e-06 -4.84221623501561e-05 8.48880370232801e-05 7.85566215829063e-06 1.83657813148951e-05 1.1095546526192e-05 9.66981322407986e-07 -4.35032074325214e-06 7.85566215829063e-06 1.14766289388747e-05 -3.03362526215305e-06 2.82123112701984e-06 -2.83294465357656e-06 -5.10558338175123e-06 1.83657813148951e-05 -3.03362526215305e-06 6.71707950376582e-05 1.67164750756395e-05 7.01623734284545e-06 -6.61666024828696e-06 1.1095546526192e-05 2.82123112701984e-06 1.67164750756395e-05 3.24517265792601e-05 3.22521041022214e-06 8.21794045616883e-06 9.66981322407986e-07 -2.83294465357656e-06 7.01623734284545e-06 3.22521041022214e-06 3.33854879619201e-05 886 884 0 9 0 886 893 0 17 0 0 0 0 0 0 13 27 0 2530 0 0 0 0 0 1752 +869 899 0.998740085661453 -0.0099526044814122 0.0491852310860691 -0.00764922567449556 0.00368719305830925 0.992040173555545 0.125867782451412 -0.00877043204488829 -0.0500464374386849 -0.125527844384908 0.990826985090623 0.0238408496076817 2.89698556773044e-05 -2.98567802959209e-05 -1.45673282180869e-06 -4.41014065940113e-06 -1.58867955083552e-06 4.54283215137927e-06 -2.98567802959209e-05 4.26668764591928e-05 3.06769322231222e-06 1.16477008883016e-05 5.63585573563671e-06 1.59795105293217e-08 -1.45673282180869e-06 3.06769322231222e-06 9.81600251387468e-06 -2.57362163844928e-06 2.57083556731536e-06 -1.36615044976586e-06 -4.41014065940113e-06 1.16477008883016e-05 -2.57362163844928e-06 5.7536739211136e-05 1.58648878794261e-05 1.07935846788421e-05 -1.58867955083552e-06 5.63585573563671e-06 2.57083556731536e-06 1.58648878794261e-05 2.31676664185833e-05 5.23773528725422e-06 4.54283215137927e-06 1.59795105293217e-08 -1.36615044976586e-06 1.07935846788421e-05 5.23773528725422e-06 2.9462710193446e-05 902 903 0 6 0 906 918 0 26 0 0 0 0 0 0 13 27 0 2684 0 0 0 0 0 1807 +869 919 0.998598564294527 -0.0101017451271045 0.0519505739554017 -0.00578034177363911 0.00352339495715069 0.992126387176951 0.125191124107053 -0.00975309723487671 -0.0528061840780468 -0.124832634405426 0.990771578271459 0.0251889180936397 4.49699941436135e-05 -4.78309892858454e-05 -4.60041207793899e-06 -5.26349275316422e-06 -1.11864537433343e-05 1.33179780819271e-05 -4.78309892858454e-05 7.62691241116131e-05 6.93817595054376e-06 1.50922285117119e-05 1.37628537821677e-05 -4.23816423673442e-06 -4.60041207793899e-06 6.93817595054376e-06 1.07465550820006e-05 -1.23910670108592e-06 3.08769862455353e-06 -2.9479824942999e-06 -5.26349275316422e-06 1.50922285117119e-05 -1.23910670108592e-06 5.39485790809855e-05 1.08566046936073e-05 5.22142636832988e-06 -1.11864537433343e-05 1.37628537821677e-05 3.08769862455353e-06 1.08566046936073e-05 3.39554496275126e-05 -5.32220905296661e-06 1.33179780819271e-05 -4.23816423673442e-06 -2.9479824942999e-06 5.22142636832988e-06 -5.32220905296661e-06 3.4215409479043e-05 901 900 0 7 0 907 917 0 23 0 0 0 0 0 0 14 29 0 2404 0 0 0 0 0 1771 +869 928 0.998921983171062 -0.0102805567731905 0.0452678880667786 -0.0116241353328327 0.00460911241979181 0.992315096127048 0.123650742339339 -0.0129131388120806 -0.0461912071751206 -0.123308799973081 0.991292747995719 0.024288422993161 3.99071380460615e-05 -4.69141393642836e-05 -1.19327830403021e-06 -1.35402472213778e-05 -9.30080528140553e-06 3.85386782496658e-06 -4.69141393642836e-05 8.67915533596511e-05 3.47453853558086e-06 3.70081204995473e-05 2.18082378105852e-05 7.32446820008915e-06 -1.19327830403021e-06 3.47453853558086e-06 9.84595078413221e-06 1.324862847197e-08 4.13854243871446e-06 -1.10287820805794e-06 -1.35402472213778e-05 3.70081204995473e-05 1.324862847197e-08 5.62129339515859e-05 1.57398638108919e-05 1.23419212833784e-05 -9.30080528140553e-06 2.18082378105852e-05 4.13854243871446e-06 1.57398638108919e-05 2.86959007265281e-05 5.16171894604487e-06 3.85386782496658e-06 7.32446820008915e-06 -1.10287820805794e-06 1.23419212833784e-05 5.16171894604487e-06 3.52838047062517e-05 878 874 0 11 0 873 887 0 28 0 0 0 0 0 0 16 34 0 2596 0 0 0 0 0 1686 +869 900 0.998441683175426 -0.0104668820672712 0.0548146848719521 -0.00705660869946649 0.00355713505560318 0.992192295767704 0.124666735777469 -0.0115431510678703 -0.0556915800459798 -0.124277482268522 0.990683377933121 0.0208789732988706 3.10657934712688e-05 -3.14014896156443e-05 2.9902724048408e-06 -1.34220361600082e-05 -7.61871781471687e-06 9.16508482870838e-06 -3.14014896156443e-05 6.06635009105761e-05 -5.24791245740452e-07 3.12023240274078e-05 1.70308517050622e-05 -6.03927234042264e-06 2.9902724048408e-06 -5.24791245740452e-07 9.00805483609325e-06 -2.59585345239009e-06 2.73561918707506e-06 4.03686530751384e-07 -1.34220361600082e-05 3.12023240274078e-05 -2.59585345239009e-06 8.43995820231543e-05 2.92407759649129e-05 4.81871859015847e-06 -7.61871781471687e-06 1.70308517050622e-05 2.73561918707506e-06 2.92407759649129e-05 3.11309664507497e-05 1.93346256490457e-06 9.16508482870838e-06 -6.03927234042264e-06 4.03686530751384e-07 4.81871859015847e-06 1.93346256490457e-06 2.3802620658193e-05 867 866 0 9 0 865 879 0 25 0 0 0 0 0 0 10 26 0 2627 0 0 0 0 0 2184 +869 913 0.998735625734918 -0.0101737658943731 0.0492305228025116 -0.00509831515060423 0.00397955634292526 0.992234456650988 0.12431792375129 -0.00876498713490015 -0.0501130024963143 -0.123964823728527 0.991020388013667 0.0251970747556848 3.66075342540557e-05 -4.12388829696502e-05 1.13653791555954e-06 -1.80622445924071e-05 -8.84831603914179e-06 1.51364561061752e-06 -4.12388829696502e-05 8.53035187937591e-05 3.14083797421279e-06 4.08918069190744e-05 1.66755136775552e-05 3.22223229004894e-06 1.13653791555954e-06 3.14083797421279e-06 9.97869053200592e-06 -1.89379528129366e-06 3.5492929299633e-06 1.22494014125602e-07 -1.80622445924071e-05 4.08918069190744e-05 -1.89379528129366e-06 9.22956235834911e-05 2.94299670663164e-05 6.42306362090956e-06 -8.84831603914179e-06 1.66755136775552e-05 3.5492929299633e-06 2.94299670663164e-05 3.54929493832703e-05 3.25227935872388e-06 1.51364561061752e-06 3.22223229004894e-06 1.22494014125602e-07 6.42306362090956e-06 3.25227935872388e-06 2.795815033842e-05 880 877 0 9 0 878 890 0 26 0 0 0 0 0 0 10 26 0 2582 0 0 0 0 0 1285 +869 903 0.998127607542285 -0.0107247837196213 0.0602184197408175 0.000544150679659887 0.00293706362913391 0.991776113850559 0.127951215909511 -0.00748013727481721 -0.0610954394300618 -0.127534775687462 0.989950619107436 0.0254713258007456 3.79097498850858e-05 -4.30423524707508e-05 -8.00216745523313e-07 -1.61304480025194e-05 -8.21842620473695e-06 2.16948247422794e-06 -4.30423524707508e-05 7.26992510500282e-05 4.28865344663722e-06 2.67121190761365e-05 1.30217197224529e-05 7.76774109354931e-06 -8.00216745523313e-07 4.28865344663722e-06 1.01825256232542e-05 -1.51680336980765e-06 2.90705118746362e-06 -7.76527119632951e-07 -1.61304480025194e-05 2.67121190761365e-05 -1.51680336980765e-06 6.5295881856597e-05 1.76650618925866e-05 7.65103679126502e-06 -8.21842620473695e-06 1.30217197224529e-05 2.90705118746362e-06 1.76650618925866e-05 3.02180150307771e-05 5.99807815422226e-06 2.16948247422794e-06 7.76774109354931e-06 -7.76527119632951e-07 7.65103679126502e-06 5.99807815422226e-06 2.97898705113367e-05 844 842 0 11 0 845 856 0 25 0 0 0 0 0 0 11 25 0 2620 0 0 0 0 0 1510 +870 872 0.999749695378739 -0.013239392974469 -0.0180351064256794 0.0106356808773766 0.0131660420943051 0.999904587737399 -0.00417980349687933 0.0119626077841111 0.0180887237164204 0.00394130630237233 0.999828617403474 0.0106234019161198 4.89507691514534e-05 -7.51003148538757e-05 3.31883463356122e-06 -3.57477999785283e-05 -1.94223567922719e-05 1.35957925661868e-05 -7.51003148538757e-05 0.000168630967849439 -5.35127658595975e-06 0.000118054941963241 5.55870264453986e-05 -1.20566298482696e-05 3.31883463356122e-06 -5.35127658595975e-06 9.51046848950395e-06 -3.55544992668166e-06 -2.62303429132801e-07 -3.8514036717546e-07 -3.57477999785283e-05 0.000118054941963241 -3.55544992668166e-06 0.000147451787855961 5.20823543427622e-05 7.96674835011595e-06 -1.94223567922719e-05 5.55870264453986e-05 -2.62303429132801e-07 5.20823543427622e-05 4.68708626305885e-05 6.12267854913168e-06 1.35957925661868e-05 -1.20566298482696e-05 -3.8514036717546e-07 7.96674835011595e-06 6.12267854913168e-06 4.27193832573107e-05 776 773 0 5 0 781 785 0 15 0 0 0 0 0 0 14 26 0 2229 0 0 0 0 0 1620 +869 917 0.998680306864771 -0.00989261354315996 0.0503962387264426 -0.00271724556602286 0.00353592117436123 0.992188998180789 0.124693581031468 -0.00818607163269034 -0.051236139022526 -0.124350826640953 0.990914592672737 0.0246043715415802 4.00452090274995e-05 -4.33289968808032e-05 -4.38594758579227e-07 -1.77782806003847e-05 -1.22580223157981e-05 4.66425111919135e-06 -4.33289968808032e-05 7.98002619587678e-05 5.76129429691657e-06 2.52284555294561e-05 7.74980308591734e-06 7.73998550423131e-06 -4.38594758579227e-07 5.76129429691657e-06 1.07354470691451e-05 -2.21636258273059e-06 1.32663000311542e-06 1.23449007906539e-06 -1.77782806003847e-05 2.52284555294561e-05 -2.21636258273059e-06 7.32912946029347e-05 2.9003362968825e-05 7.73674497794462e-06 -1.22580223157981e-05 7.74980308591734e-06 1.32663000311542e-06 2.9003362968825e-05 4.51229511010313e-05 2.59739026590628e-06 4.66425111919135e-06 7.73998550423131e-06 1.23449007906539e-06 7.73674497794462e-06 2.59739026590628e-06 3.7042953926803e-05 849 847 0 9 0 848 859 0 24 0 0 0 0 0 0 12 27 0 2339 0 0 0 0 0 1294 +869 915 0.99854826928326 -0.0103150747019968 0.0528673164185435 -0.00342709434126287 0.00357156242506528 0.992011756628642 0.126094879564554 -0.00882274702143503 -0.0537456775308492 -0.125723004833832 0.990608463623394 0.0246175661498791 4.10390166023832e-05 -4.75276028812547e-05 -9.0972207992878e-07 -1.96935501624546e-05 -7.96901960811315e-06 -4.70487838473201e-07 -4.75276028812547e-05 7.43485386354433e-05 3.75805498332721e-06 3.10725226683119e-05 1.11370167814672e-05 1.1622817673037e-05 -9.0972207992878e-07 3.75805498332721e-06 1.07174598432393e-05 -1.47594805988023e-06 2.95379606310737e-06 5.98294676129016e-07 -1.96935501624546e-05 3.10725226683119e-05 -1.47594805988023e-06 7.26325015785046e-05 2.08072292216546e-05 1.58773591448518e-05 -7.96901960811315e-06 1.11370167814672e-05 2.95379606310737e-06 2.08072292216546e-05 2.99089612431647e-05 7.17280759585691e-06 -4.70487838473201e-07 1.1622817673037e-05 5.98294676129016e-07 1.58773591448518e-05 7.17280759585691e-06 3.30305236778396e-05 892 887 0 7 0 887 896 0 17 0 0 0 0 0 0 13 28 0 2643 0 0 0 0 0 1304 +869 902 0.998751320306468 -0.0104034007636995 0.0488627612670002 -0.00895909155206739 0.00420098290405878 0.992102258636359 0.125361318401151 -0.010194140065408 -0.049781039851793 -0.124999510643782 0.990907145200845 0.0234617916934304 3.01248696409003e-05 -2.80028429516098e-05 -9.84474498747427e-07 -1.80364991194469e-06 -2.48800732215221e-06 7.39504649290203e-06 -2.80028429516098e-05 3.67552048291681e-05 2.98034270115308e-06 4.3593611841208e-06 4.26727083675132e-06 -2.64416613210456e-06 -9.84474498747427e-07 2.98034270115308e-06 9.08650302791727e-06 -6.33751467865601e-07 2.37781048727492e-06 -2.58668503579986e-07 -1.80364991194469e-06 4.3593611841208e-06 -6.33751467865601e-07 4.43094095423641e-05 7.14220290366472e-06 4.41671407037852e-06 -2.48800732215221e-06 4.26727083675132e-06 2.37781048727492e-06 7.14220290366472e-06 2.3290146952683e-05 4.63808076977318e-06 7.39504649290203e-06 -2.64416613210456e-06 -2.58668503579986e-07 4.41671407037852e-06 4.63808076977318e-06 2.44438635552769e-05 886 886 0 11 0 885 896 0 22 0 0 0 0 0 0 16 32 0 2661 0 0 0 0 0 1775 +869 901 0.998735813487992 -0.0102212581327326 0.0492168745316441 -0.00691895000798285 0.00400553879111889 0.992177509468899 0.124770771269095 -0.0100862982647962 -0.0501071902572115 -0.12441589764285 0.990964153689855 0.0230551870678346 5.03684096170934e-05 -6.77985132868431e-05 6.01672065666896e-07 -3.32881442318036e-05 -1.75290460487945e-05 -4.87338062790072e-06 -6.77985132868431e-05 0.000127919408667934 1.22208400369353e-06 7.48369570964589e-05 3.71152634429731e-05 2.28925987006468e-05 6.01672065666896e-07 1.22208400369353e-06 9.37161646896183e-06 -2.00189104683958e-08 3.93682024526294e-06 -7.59129045924975e-07 -3.32881442318036e-05 7.48369570964589e-05 -2.00189104683958e-08 9.14988514744204e-05 3.27300270936927e-05 2.48167324910165e-05 -1.75290460487945e-05 3.71152634429731e-05 3.93682024526294e-06 3.27300270936927e-05 3.39573119876923e-05 1.26914248461633e-05 -4.87338062790072e-06 2.28925987006468e-05 -7.59129045924975e-07 2.48167324910165e-05 1.26914248461633e-05 3.73519007799603e-05 872 864 0 11 0 869 879 0 27 0 0 0 0 0 0 11 28 0 2622 0 0 0 0 0 1759 +870 929 0.997090710224363 -0.0338666591738796 0.068287370579596 -0.0129408793945373 0.0236408411755168 0.989098204032166 0.145347354323555 -0.012065939640595 -0.0724653449090583 -0.143310125869539 0.98702126705075 0.0114654447556858 2.16515690148194e-05 -2.2350534116572e-05 1.29026277569834e-06 -3.04773644352833e-06 2.0309679348292e-06 3.69510172316359e-06 -2.2350534116572e-05 5.80133102580477e-05 3.16651333181883e-06 1.51531400190452e-05 3.35133737519601e-06 -1.4899615048743e-06 1.29026277569834e-06 3.16651333181883e-06 9.35709092958843e-06 8.34999228631956e-07 4.72355708020804e-06 2.33958928246193e-07 -3.04773644352833e-06 1.51531400190452e-05 8.34999228631956e-07 4.11286112645941e-05 4.75564342743587e-06 4.42924500389596e-06 2.0309679348292e-06 3.35133737519601e-06 4.72355708020804e-06 4.75564342743587e-06 2.04394826628538e-05 8.46587429092825e-07 3.69510172316359e-06 -1.4899615048743e-06 2.33958928246193e-07 4.42924500389596e-06 8.46587429092825e-07 2.2961815927739e-05 896 895 0 0 0 912 911 0 6 0 0 0 0 0 0 34 48 0 2644 0 0 0 0 0 2076 +870 922 0.998483176056049 -0.0105700079615842 0.0540335272281679 -0.0097251151754651 0.00389599714727127 0.992502909447452 0.122158896297286 -0.010742593646978 -0.0549196534881055 -0.121763088290478 0.991038637990826 0.0146356534141263 6.39808788034223e-05 -7.74400658772284e-05 -5.80391346198208e-06 -2.8352614990668e-05 -2.04609758213848e-05 -1.18728479536351e-05 -7.74400658772284e-05 0.000149426291392741 1.02949991764129e-05 7.029312450442e-05 3.56167342300402e-05 3.32566407638826e-05 -5.80391346198208e-06 1.02949991764129e-05 1.07375616755558e-05 -4.73526332245929e-07 5.73352300192702e-06 -1.1827816605475e-06 -2.8352614990668e-05 7.029312450442e-05 -4.73526332245929e-07 9.82907178305635e-05 3.34519715449601e-05 3.31975171655683e-05 -2.04609758213848e-05 3.56167342300402e-05 5.73352300192702e-06 3.34519715449601e-05 3.57852966683534e-05 1.48458169294378e-05 -1.18728479536351e-05 3.32566407638826e-05 -1.1827816605475e-06 3.31975171655683e-05 1.48458169294378e-05 4.80592984516814e-05 929 926 0 8 0 932 941 0 24 0 0 0 0 0 0 12 26 0 2721 0 0 0 0 0 1643 +869 897 0.99870762469158 -0.00995569791475444 0.0498393866528413 -0.00731581267127145 0.00372967013078221 0.992339028174702 0.123488229082788 -0.0119482647528617 -0.05068698002068 -0.123142751472905 0.991093685186252 0.0219985268155468 2.49091759486699e-05 -2.73092418780275e-05 4.93398965859916e-07 -1.7291097328019e-06 -2.63081226330648e-06 9.80163054633334e-06 -2.73092418780275e-05 8.30829292617596e-05 5.61214383662252e-06 1.64110307577169e-05 7.57738027237334e-06 -5.53847501372987e-06 4.93398965859916e-07 5.61214383662252e-06 8.97361076766139e-06 -6.57489856956732e-07 3.34092600797404e-06 -1.12118511199216e-06 -1.7291097328019e-06 1.64110307577169e-05 -6.57489856956732e-07 5.07873226968663e-05 1.00595940060739e-05 3.32350548711803e-06 -2.63081226330648e-06 7.57738027237334e-06 3.34092600797404e-06 1.00595940060739e-05 2.43183609223783e-05 8.43790314735063e-07 9.80163054633334e-06 -5.53847501372987e-06 -1.12118511199216e-06 3.32350548711803e-06 8.43790314735063e-07 2.50567078292098e-05 877 876 0 6 0 880 888 0 21 0 0 0 0 0 0 12 26 0 2608 0 0 0 0 0 2176 +869 912 0.998547022433529 -0.0103387822090855 0.0528862323442212 -0.0049041659383685 0.00379249675606603 0.992471994597504 0.122413058568145 -0.0115237989166316 -0.0537537064535003 -0.122034624275596 0.991069164851992 0.0199022559915998 3.01560540538184e-05 -3.38925413187126e-05 2.75866946833322e-07 -1.09772981823575e-05 -6.4222295742042e-06 -3.03483800016497e-06 -3.38925413187126e-05 6.85762985449122e-05 2.05251990655642e-06 2.40379284689687e-05 1.07399224806122e-05 5.31290693715001e-06 2.75866946833322e-07 2.05251990655642e-06 8.00320753494226e-06 2.28711742803853e-07 2.62741721553743e-06 7.20703463387471e-07 -1.09772981823575e-05 2.40379284689687e-05 2.28711742803853e-07 6.10097333981628e-05 1.6320063798617e-05 5.96227778871926e-06 -6.4222295742042e-06 1.07399224806122e-05 2.62741721553743e-06 1.6320063798617e-05 2.79253291361868e-05 8.74232484951961e-06 -3.03483800016497e-06 5.31290693715001e-06 7.20703463387471e-07 5.96227778871926e-06 8.74232484951961e-06 2.73668177130513e-05 861 860 0 8 0 862 873 0 22 0 0 0 0 0 0 14 28 0 2609 0 0 0 0 0 2214 +870 923 0.998381108594266 -0.0110951078822096 0.055785845724229 -0.0111395208261379 0.00414850616046848 0.992382133347659 0.123127946904776 -0.0108062874136459 -0.0567269944446372 -0.122697188205073 0.990821602564179 0.0154771669397165 5.04560083012326e-05 -5.77397924537749e-05 -4.13918569731145e-07 -2.25806544011985e-05 -1.51881122189296e-05 -8.45532636581761e-06 -5.77397924537749e-05 9.48189147419615e-05 3.24609593980782e-06 3.86972085029071e-05 2.29345392783711e-05 2.04963141841395e-05 -4.13918569731145e-07 3.24609593980782e-06 9.76339618225392e-06 -1.91434821029301e-06 3.24814153842161e-06 1.01897968402789e-06 -2.25806544011985e-05 3.86972085029071e-05 -1.91434821029301e-06 9.09921728184851e-05 3.93356290043939e-05 2.92910774698211e-05 -1.51881122189296e-05 2.29345392783711e-05 3.24814153842161e-06 3.93356290043939e-05 4.0218845250538e-05 1.77532159914858e-05 -8.45532636581761e-06 2.04963141841395e-05 1.01897968402789e-06 2.92910774698211e-05 1.77532159914858e-05 4.8124655862437e-05 913 914 0 5 0 917 930 0 22 0 0 0 0 0 0 14 27 0 2605 0 0 0 0 0 1765 +870 925 0.998331942247509 -0.0111079669817483 0.0566563867348442 -0.0117755855589801 0.00394772463006515 0.992154162160175 0.124958128901187 -0.0103245733869079 -0.0575999006818677 -0.124526027712173 0.990543042913162 0.0168254380652755 4.09304612394731e-05 -5.03420503277704e-05 1.14380769621975e-06 -2.3275876452789e-05 -1.56594997438299e-05 3.51866435322176e-06 -5.03420503277704e-05 9.24150573583898e-05 1.74857374233288e-06 5.56619843604296e-05 3.19121841357911e-05 8.69498949320674e-06 1.14380769621975e-06 1.74857374233288e-06 8.86458156670173e-06 2.16701390265425e-06 5.326287968341e-06 9.42206780351704e-07 -2.3275876452789e-05 5.56619843604296e-05 2.16701390265425e-06 8.62730203424278e-05 3.18016393968509e-05 1.99492719027923e-05 -1.56594997438299e-05 3.19121841357911e-05 5.326287968341e-06 3.18016393968509e-05 3.42849998407336e-05 1.0990811297684e-05 3.51866435322176e-06 8.69498949320674e-06 9.42206780351704e-07 1.99492719027923e-05 1.0990811297684e-05 3.39320836559598e-05 916 918 0 12 0 919 928 0 23 0 0 0 0 0 0 10 22 0 2609 0 0 0 0 0 2294 +870 873 0.999489370738606 -0.024990003697128 -0.0199122448700271 0.00563271213219747 0.0247290818236564 0.999606459108157 -0.013243844661279 0.0156522752587752 0.0202353723144719 0.012744670433978 0.999714010646457 0.0107187051167056 3.4287805595977e-05 -3.53232556091842e-05 6.53917835033778e-06 -1.77116428965885e-05 -1.12503991636631e-05 1.5117271838651e-05 -3.53232556091842e-05 5.48612530288365e-05 -6.10040573577668e-06 3.85822254380008e-05 1.60045907407083e-05 -9.79355689544253e-06 6.53917835033778e-06 -6.10040573577668e-06 8.60703449549606e-06 4.50324301535761e-07 -5.82850012980029e-07 2.96453907782951e-06 -1.77116428965885e-05 3.85822254380008e-05 4.50324301535761e-07 7.17601916654514e-05 2.10882051093664e-05 3.32921896059627e-06 -1.12503991636631e-05 1.60045907407083e-05 -5.82850012980029e-07 2.10882051093664e-05 3.69422331796684e-05 -1.13161164340368e-06 1.5117271838651e-05 -9.79355689544253e-06 2.96453907782951e-06 3.32921896059627e-06 -1.13161164340368e-06 3.02327752215313e-05 796 796 0 0 0 805 805 0 1 0 0 0 0 0 0 32 36 0 2117 0 0 0 0 0 2759 +870 874 0.999214898355651 -0.0213163289812687 -0.0333946256584534 0.00993202172683874 0.0210299637323776 0.999739203446234 -0.00890312968025208 0.0185203896902427 0.0335756984963945 0.00819385205204666 0.999402588179072 0.0141049102800491 4.94986470490158e-05 -7.48518010749747e-05 4.03755889004067e-06 -3.66902567486109e-05 -1.77444855503314e-05 2.89427897505239e-05 -7.48518010749747e-05 0.000170542076590206 -7.22004922414833e-06 0.000113649477138916 5.02926736926851e-05 -4.64426218726687e-05 4.03755889004067e-06 -7.22004922414833e-06 9.18856009681894e-06 -5.5070269891295e-06 2.1727449062007e-06 1.49965333168942e-08 -3.66902567486109e-05 0.000113649477138916 -5.5070269891295e-06 0.000134568512991067 4.68898571908275e-05 -1.69344462078084e-05 -1.77444855503314e-05 5.02926736926851e-05 2.1727449062007e-06 4.68898571908275e-05 3.94580613631944e-05 -8.68902811024112e-06 2.89427897505239e-05 -4.64426218726687e-05 1.49965333168942e-08 -1.69344462078084e-05 -8.68902811024112e-06 4.46923712123694e-05 721 720 0 1 0 729 729 0 7 0 0 0 0 0 0 21 28 0 2079 0 0 0 0 0 1905 +870 927 0.997539023986765 -0.01186144433272 0.069102834687689 -0.00846890945397483 0.00300199276988623 0.991907816518302 0.126924668876089 -0.010079150431852 -0.0700491517646135 -0.126404864100386 0.989502363144637 0.019860208904118 2.27595261725275e-05 -2.2680209670608e-05 9.46714545569509e-07 -5.26101193653013e-06 -1.4655799797771e-06 8.02197637015949e-06 -2.2680209670608e-05 4.52097298667705e-05 2.70292909278523e-06 7.51943023921544e-06 5.95099552136843e-06 -5.32366957140754e-06 9.46714545569509e-07 2.70292909278523e-06 9.59602492520648e-06 -1.54045273493699e-06 3.82785022218947e-06 -1.04743748302466e-06 -5.26101193653013e-06 7.51943023921544e-06 -1.54045273493699e-06 3.96513861470587e-05 2.77730563661931e-06 7.21752856273719e-06 -1.4655799797771e-06 5.95099552136843e-06 3.82785022218947e-06 2.77730563661931e-06 2.10862658909987e-05 3.14045114628255e-06 8.02197637015949e-06 -5.32366957140754e-06 -1.04743748302466e-06 7.21752856273719e-06 3.14045114628255e-06 2.67394234435823e-05 875 875 0 6 0 877 886 0 17 0 0 0 0 0 0 13 24 0 2646 0 0 0 0 0 1638 +870 919 0.99792087019906 -0.0111399970592625 0.0634809994145481 -0.00444188137310598 0.00307333023652978 0.992053610956189 0.12577832734634 -0.00883385364279094 -0.0643777248930674 -0.125321719802696 0.990025239619318 0.0170524111552562 5.64412244716005e-05 -8.22554874935613e-05 -2.9038542408996e-06 -3.0464522966058e-05 -1.95978649725995e-05 -6.18081521384465e-06 -8.22554874935613e-05 0.000192222296483027 9.80164589855429e-06 8.08516485726351e-05 3.94015950197556e-05 3.77359764946856e-05 -2.9038542408996e-06 9.80164589855429e-06 1.01894485850734e-05 -1.8055242774494e-06 4.39397056051024e-06 -4.472414967527e-08 -3.0464522966058e-05 8.08516485726351e-05 -1.8055242774494e-06 0.000111502044055884 3.21721926525021e-05 3.57986377990648e-05 -1.95978649725995e-05 3.94015950197556e-05 4.39397056051024e-06 3.21721926525021e-05 3.92175764763667e-05 1.56331707951403e-05 -6.18081521384465e-06 3.77359764946856e-05 -4.472414967527e-08 3.57986377990648e-05 1.56331707951403e-05 4.94444927243905e-05 892 891 0 7 0 893 901 0 18 0 0 0 0 0 0 9 21 0 2451 0 0 0 0 0 1798 +870 921 0.99781176886665 -0.0111662603990655 0.0651689231145299 -0.00395066170989892 0.0027989332217229 0.991886193368345 0.127098172205873 -0.00832503529995665 -0.0660593663610815 -0.126637648564531 0.98974697073647 0.0184353452360661 4.58283350380675e-05 -6.14215298169117e-05 -1.4198916753758e-06 -2.16605054349654e-05 -1.39412758359224e-05 7.90672264774535e-06 -6.14215298169117e-05 0.00015611504218755 6.77248970171993e-06 8.53747529698186e-05 4.23490551477087e-05 5.32906197412076e-06 -1.4198916753758e-06 6.77248970171993e-06 9.57603793062796e-06 1.18429323227196e-06 5.62197642678831e-06 1.29738856792645e-07 -2.16605054349654e-05 8.53747529698186e-05 1.18429323227196e-06 0.000112785435853765 3.5007880705515e-05 1.73857004930847e-05 -1.39412758359224e-05 4.23490551477087e-05 5.62197642678831e-06 3.5007880705515e-05 3.58163813357548e-05 9.65391882791408e-06 7.90672264774535e-06 5.32906197412076e-06 1.29738856792645e-07 1.73857004930847e-05 9.65391882791408e-06 3.17160291064034e-05 892 890 0 12 0 895 902 0 24 0 0 0 0 0 0 14 24 0 2545 0 0 0 0 0 2196 +870 920 0.998298676870883 -0.0113478276343251 0.0571924694852883 -0.00832640505060572 0.00421414140732671 0.992355548177473 0.123339803038539 -0.0126773767785369 -0.0581549032330297 -0.122888945025044 0.990715052081368 0.0165913319471231 4.57758495591325e-05 -5.26909839628674e-05 -2.97506207505599e-06 -5.62451468227132e-06 -4.11561478402282e-06 3.05503954920297e-06 -5.26909839628674e-05 9.64098002215674e-05 6.78516839750635e-06 2.92248683962416e-05 1.2511461085323e-05 1.16789853956786e-05 -2.97506207505599e-06 6.78516839750635e-06 1.11371364129969e-05 -2.76600912791598e-06 3.84888826544641e-06 -5.5698715318872e-08 -5.62451468227132e-06 2.92248683962416e-05 -2.76600912791598e-06 6.79469686316139e-05 1.70532457326674e-05 1.33733908779454e-05 -4.11561478402282e-06 1.2511461085323e-05 3.84888826544641e-06 1.70532457326674e-05 2.93656848974726e-05 5.99372059981858e-06 3.05503954920297e-06 1.16789853956786e-05 -5.5698715318872e-08 1.33733908779454e-05 5.99372059981858e-06 3.58147784852893e-05 911 911 0 7 0 914 922 0 19 0 0 0 0 0 0 13 22 0 2460 0 0 0 0 0 1557 +870 928 0.997398199293793 -0.0120401958621532 0.0710764780296554 -0.00482853911175032 0.00279571340817568 0.991672422510941 0.12875554519251 -0.00772125690929662 -0.0720348251336702 -0.128221839461467 0.989125949438735 0.0202126403281022 4.11754936389988e-05 -4.98776742803932e-05 -3.57336355169107e-06 -6.27967507316489e-06 -5.30324290203907e-06 1.88261056891978e-06 -4.98776742803932e-05 9.17338649048565e-05 7.82751713077529e-06 2.47626532064644e-05 1.23749555415427e-05 1.24289717933431e-05 -3.57336355169107e-06 7.82751713077529e-06 1.03742379817338e-05 -1.68452803879099e-06 4.48344948740318e-06 -9.21632604661107e-07 -6.27967507316489e-06 2.47626532064644e-05 -1.68452803879099e-06 5.04631527253896e-05 9.53547201144087e-06 1.88643628528756e-05 -5.30324290203907e-06 1.23749555415427e-05 4.48344948740318e-06 9.53547201144087e-06 2.33863392380063e-05 6.80919690304106e-06 1.88261056891978e-06 1.24289717933431e-05 -9.21632604661107e-07 1.88643628528756e-05 6.80919690304106e-06 4.07643242343802e-05 897 896 0 5 0 899 911 0 21 0 0 0 0 0 0 13 25 0 2592 0 0 0 0 0 1760 +870 926 0.997442150637607 -0.0115267638927277 0.070542822778699 -0.00466089114617863 0.00239724574106225 0.991750978960014 0.128157126000514 -0.00792053397948848 -0.071438150481956 -0.127660210896019 0.989241861836478 0.0193154910329155 2.81459323124273e-05 -2.92795815864594e-05 5.04834004953215e-07 -1.1266532614636e-05 -4.7063850226449e-06 7.72024951964622e-06 -2.92795815864594e-05 6.20959171475758e-05 3.56851417504023e-06 2.48262805625905e-05 1.19752716826018e-05 -1.45382389061501e-06 5.04834004953215e-07 3.56851417504023e-06 9.34820563642862e-06 -2.09729176138105e-06 3.82724032396394e-06 -8.60143188559922e-07 -1.1266532614636e-05 2.48262805625905e-05 -2.09729176138105e-06 6.70452783510518e-05 1.36000801318322e-05 8.90732746551894e-06 -4.7063850226449e-06 1.19752716826018e-05 3.82724032396394e-06 1.36000801318322e-05 2.45022008282237e-05 2.86211711282986e-06 7.72024951964622e-06 -1.45382389061501e-06 -8.60143188559922e-07 8.90732746551894e-06 2.86211711282986e-06 2.58958950305017e-05 886 887 0 7 0 886 895 0 18 0 0 0 0 0 0 14 23 0 2615 0 0 0 0 0 1647 +870 918 0.997607406816093 -0.0113576991212965 0.0681943145455688 -0.00254129218076772 0.00258600317180205 0.991852953473896 0.127361812458463 -0.00944667978418422 -0.0690852694375965 -0.126880736740371 0.989509223903929 0.0164532124286993 2.36415076716857e-05 -2.14510214479518e-05 -4.34349760267719e-07 -1.08505580163294e-06 -2.28452705119339e-06 2.25944741248185e-06 -2.14510214479518e-05 4.27196984771285e-05 5.04836587453227e-06 9.87236713386151e-07 3.87611471733891e-07 3.11489416720149e-06 -4.34349760267719e-07 5.04836587453227e-06 1.01654716813374e-05 -3.30609680068298e-06 3.59048162279143e-06 -5.3067682989082e-07 -1.08505580163294e-06 9.87236713386151e-07 -3.30609680068298e-06 4.35946392191711e-05 6.05671490170693e-06 3.35988932930556e-06 -2.28452705119339e-06 3.87611471733891e-07 3.59048162279143e-06 6.05671490170693e-06 2.30968779094446e-05 -1.76679968223525e-07 2.25944741248185e-06 3.11489416720149e-06 -5.3067682989082e-07 3.35988932930556e-06 -1.76679968223525e-07 2.87239479374824e-05 894 895 0 7 0 898 909 0 21 0 0 0 0 0 0 13 25 0 2389 0 0 0 0 0 1671 +870 914 0.998423979778478 -0.0109749902514852 0.0550373163615815 -0.0116516447288771 0.00398353426557116 0.992077345707405 0.125565407612545 -0.0105505960972439 -0.055979353855328 -0.125148270955412 0.990557530998988 0.0151712206050302 3.0869921142832e-05 -3.00412183445709e-05 -2.19788239425694e-07 -7.73227566092156e-06 -4.69547658172124e-06 2.90460002786148e-06 -3.00412183445709e-05 4.31660590005295e-05 1.80427336911389e-06 1.3188332784796e-05 7.02559811683567e-06 3.45208396621839e-06 -2.19788239425694e-07 1.80427336911389e-06 8.86853993042568e-06 -1.47791983841998e-06 4.11247091933252e-06 -1.24845107975301e-06 -7.73227566092156e-06 1.3188332784796e-05 -1.47791983841998e-06 4.46760755444938e-05 1.33937679685679e-05 1.06545177828584e-05 -4.69547658172124e-06 7.02559811683567e-06 4.11247091933252e-06 1.33937679685679e-05 2.6773573312472e-05 7.61421763602236e-06 2.90460002786148e-06 3.45208396621839e-06 -1.24845107975301e-06 1.06545177828584e-05 7.61421763602236e-06 3.42148375193997e-05 949 951 0 6 0 954 964 0 20 0 0 0 0 0 0 11 22 0 2714 0 0 0 0 0 1594 +870 916 0.99798995330635 -0.011322221817416 0.0623527095859196 -0.00600255292512724 0.00342937873291291 0.992117638281994 0.125263047908247 -0.00868284275577477 -0.0632794789888084 -0.124797432276769 0.990162263690164 0.0163484497768782 7.6502432651121e-05 -9.91201267408741e-05 -4.889020745253e-06 -4.47432579792985e-05 -2.7629044657574e-05 -1.0359095279032e-05 -9.91201267408741e-05 0.000201609902430017 1.14992281132811e-05 9.90462674700533e-05 4.29391360340701e-05 3.8214589412743e-05 -4.889020745253e-06 1.14992281132811e-05 1.09641433059491e-05 9.87190412011296e-07 4.25036700692403e-06 1.29764057405469e-06 -4.47432579792985e-05 9.90462674700533e-05 9.87190412011296e-07 0.000125562258034499 3.98315960560796e-05 2.6560532528437e-05 -2.7629044657574e-05 4.29391360340701e-05 4.25036700692403e-06 3.98315960560796e-05 4.24627094483242e-05 1.33029212675868e-05 -1.0359095279032e-05 3.8214589412743e-05 1.29764057405469e-06 2.6560532528437e-05 1.33029212675868e-05 5.02836532768465e-05 870 871 0 8 0 872 878 0 16 0 0 0 0 0 0 12 19 0 2576 0 0 0 0 0 1830 +870 924 0.998008279885687 -0.0109847188192493 0.0621193144849079 -0.00443042832120862 0.00307370792322736 0.992020476785636 0.126039382565932 -0.00767723312053235 -0.0630081391505538 -0.125597410763362 0.990078413465481 0.0183456319174165 3.74666153631597e-05 -5.27303099681537e-05 -4.39361752388678e-06 -1.19784139455289e-05 -9.55742357154592e-06 2.94859921716382e-06 -5.27303099681537e-05 0.000133302742385758 1.00737665387861e-05 6.0948714384715e-05 3.07162594009307e-05 9.96804323576499e-06 -4.39361752388678e-06 1.00737665387861e-05 1.05784876478768e-05 -1.88541643754435e-06 4.74578487736055e-06 -1.16730025882339e-06 -1.19784139455289e-05 6.0948714384715e-05 -1.88541643754435e-06 0.00010671840585882 2.94221283539066e-05 2.20348000529965e-05 -9.55742357154592e-06 3.07162594009307e-05 4.74578487736055e-06 2.94221283539066e-05 3.15787487692517e-05 6.49560353876235e-06 2.94859921716382e-06 9.96804323576499e-06 -1.16730025882339e-06 2.20348000529965e-05 6.49560353876235e-06 3.36774208539525e-05 868 867 0 7 0 872 878 0 19 0 0 0 0 0 0 13 20 0 2648 0 0 0 0 0 1632 +870 901 0.998062773365353 -0.0110860285619909 0.0612192812190973 -0.00755668290290891 0.0033615684090036 0.992168043133909 0.124865023291797 -0.00908309404072556 -0.0621240716638227 -0.124417338641172 0.9902832552181 0.0141194290848516 7.17945919867572e-05 -0.000106443348576574 -3.93539986444852e-06 -5.17749354686955e-05 -3.16695635997961e-05 -1.5464701237535e-05 -0.000106443348576574 0.000218805339780279 1.03066354813853e-05 0.000129355255508899 6.39964239281954e-05 4.8527832329801e-05 -3.93539986444852e-06 1.03066354813853e-05 1.0256294805525e-05 4.15042320308165e-06 7.40032256323446e-06 1.83798747255901e-06 -5.17749354686955e-05 0.000129355255508899 4.15042320308165e-06 0.000135615940438631 5.22033242412503e-05 4.81353772975986e-05 -3.16695635997961e-05 6.39964239281954e-05 7.40032256323446e-06 5.22033242412503e-05 4.54514351102044e-05 2.51622449382975e-05 -1.5464701237535e-05 4.8527832329801e-05 1.83798747255901e-06 4.81353772975986e-05 2.51622449382975e-05 5.85366741543038e-05 908 904 0 4 0 913 920 0 20 0 0 0 0 0 0 12 23 0 2635 0 0 0 0 0 1835 +870 898 0.998214551080145 -0.0109076750544042 0.0587259111191313 -0.0110389629732842 0.00342267186203117 0.992014501476957 0.126077413428215 -0.00881766890751404 -0.0596321668999999 -0.125651309123032 0.990280643649304 0.0158814704926722 4.31245468563198e-05 -6.17861952370092e-05 -2.21578441165118e-06 -2.44648271582836e-05 -1.3237783356397e-05 6.51435175506096e-06 -6.17861952370092e-05 0.000154907701432581 7.96287210864265e-06 8.13752335394215e-05 3.77692915212129e-05 9.60584431605275e-06 -2.21578441165118e-06 7.96287210864265e-06 9.83080773145505e-06 -1.63979167605403e-07 4.97834958143912e-06 -1.27662021862612e-06 -2.44648271582836e-05 8.13752335394215e-05 -1.63979167605403e-07 0.000110944360712728 3.94938331006726e-05 1.93295140597533e-05 -1.3237783356397e-05 3.77692915212129e-05 4.97834958143912e-06 3.94938331006726e-05 3.67207936564315e-05 8.5816066879559e-06 6.51435175506096e-06 9.60584431605275e-06 -1.27662021862612e-06 1.93295140597533e-05 8.5816066879559e-06 3.3405044265561e-05 888 889 0 8 0 889 898 0 18 0 0 0 0 0 0 12 22 0 2700 0 0 0 0 0 2297 +870 913 0.998313888599142 -0.0107500094058489 0.0570422398563867 -0.00820462991614317 0.00348262387457904 0.992023704987973 0.126003333578455 -0.0075898863774843 -0.0579417911442821 -0.125592221254779 0.99038848074848 0.0175490852625763 3.88333437589125e-05 -3.83734635928075e-05 -2.17421519366243e-06 -8.97870380499808e-06 -9.27902356442141e-06 7.5802918389906e-06 -3.83734635928075e-05 5.48378453546445e-05 3.49648639480857e-06 2.22392458559742e-05 1.56734281622967e-05 1.72783617346887e-06 -2.17421519366243e-06 3.49648639480857e-06 9.37168658389809e-06 -1.42810388947222e-06 4.63736244289981e-06 -7.60531271895373e-07 -8.97870380499808e-06 2.22392458559742e-05 -1.42810388947222e-06 7.32575136473983e-05 2.56968105207972e-05 1.809086857479e-05 -9.27902356442141e-06 1.56734281622967e-05 4.63736244289981e-06 2.56968105207972e-05 3.08990590417607e-05 1.16933517819691e-05 7.5802918389906e-06 1.72783617346887e-06 -7.60531271895373e-07 1.809086857479e-05 1.16933517819691e-05 3.90056547318794e-05 947 948 0 7 0 950 963 0 24 0 0 0 0 0 0 15 26 0 2621 0 0 0 0 0 1682 +870 915 0.99752341173735 -0.0112853367441297 0.0694239455119641 0.000267572128872588 0.00230485407891562 0.991758621676563 0.128099664237964 -0.00486686265472273 -0.0702974443600297 -0.127622402049075 0.989328454969164 0.0163517073180232 2.04979135681622e-05 -1.65458879697145e-05 1.47164751813828e-06 -1.74802561855048e-06 -1.58162653122417e-06 8.62753562765165e-06 -1.65458879697145e-05 3.49216793336632e-05 1.53088356254197e-06 2.02486681389783e-06 2.50844336880135e-06 -6.5419489929541e-06 1.47164751813828e-06 1.53088356254197e-06 8.98554932518058e-06 -2.76984095770234e-06 3.13703683503746e-06 -3.21915406814728e-07 -1.74802561855048e-06 2.02486681389783e-06 -2.76984095770234e-06 4.94311239778473e-05 8.76213424264314e-06 5.00904528550921e-06 -1.58162653122417e-06 2.50844336880135e-06 3.13703683503746e-06 8.76213424264314e-06 2.40366052814274e-05 1.14049410632347e-06 8.62753562765165e-06 -6.5419489929541e-06 -3.21915406814728e-07 5.00904528550921e-06 1.14049410632347e-06 2.6585428125805e-05 886 886 0 6 0 889 896 0 16 0 0 0 0 0 0 11 16 0 2677 0 0 0 0 0 1627 +870 908 0.998265121780266 -0.0104398309248968 0.0579461523079056 -0.00439064094589809 0.00300575640356514 0.991907779646031 0.126924867957872 -0.00695886972975489 -0.0588023134364104 -0.126530496750548 0.990218320031793 0.0165701596345028 3.69663433953926e-05 -4.15115203103129e-05 3.2288715225678e-06 -2.42946186333964e-05 -1.35815833853449e-05 -1.2779521072288e-06 -4.15115203103129e-05 6.85524500074899e-05 -1.86590504629914e-06 4.28807153287555e-05 2.14336569978739e-05 1.02369996748073e-05 3.2288715225678e-06 -1.86590504629914e-06 9.443589471546e-06 -2.32092733493112e-06 3.31487926066453e-06 4.05612415754251e-07 -2.42946186333964e-05 4.28807153287555e-05 -2.32092733493112e-06 9.55650359587989e-05 3.42419573621664e-05 1.90886349974672e-05 -1.35815833853449e-05 2.14336569978739e-05 3.31487926066453e-06 3.42419573621664e-05 3.5672130619528e-05 1.11728868851206e-05 -1.2779521072288e-06 1.02369996748073e-05 4.05612415754251e-07 1.90886349974672e-05 1.11728868851206e-05 3.55186500556799e-05 909 906 0 4 0 914 921 0 20 0 0 0 0 0 0 13 22 0 2676 0 0 0 0 0 1796 +870 911 0.997745718214765 -0.0112512508818394 0.0661580768893476 -0.00597061411306862 0.00264842648833388 0.991678808232632 0.128709467947945 -0.00690169479337119 -0.0670557053593415 -0.128244105735512 0.989473082869292 0.0168359354800627 5.48100765300337e-05 -0.000103418577034481 -4.30674255618641e-06 -4.04862676927478e-05 -1.964115711233e-05 -6.56064017566179e-06 -0.000103418577034481 0.000289855192428017 1.46306120235089e-05 0.000132840988315718 6.04485530160451e-05 3.62898874866045e-05 -4.30674255618641e-06 1.46306120235089e-05 1.00489392957889e-05 2.04446341201299e-06 5.87599156936354e-06 -3.87773928525102e-07 -4.04862676927478e-05 0.000132840988315718 2.04446341201299e-06 0.000126644914701748 4.38365766799793e-05 2.71761051822931e-05 -1.964115711233e-05 6.04485530160451e-05 5.87599156936354e-06 4.38365766799793e-05 4.00738433558207e-05 1.39337855511635e-05 -6.56064017566179e-06 3.62898874866045e-05 -3.87773928525102e-07 2.71761051822931e-05 1.39337855511635e-05 4.34811935310135e-05 886 887 0 8 0 888 898 0 20 0 0 0 0 0 0 14 24 0 2703 0 0 0 0 0 1721 +870 899 0.998207408683948 -0.0109354224565541 0.0588420409586135 -0.00975802786416867 0.00349858310860781 0.992146348674525 0.125033526416078 -0.00865814147844434 -0.0597472105182378 -0.124603528631835 0.99040609422993 0.0152401631647388 2.75019632292924e-05 -2.95918746089756e-05 3.63546789203099e-07 -8.27801150714686e-06 -2.66263018953853e-06 -4.01983939602128e-06 -2.95918746089756e-05 5.12659264901313e-05 2.14195435591123e-06 1.56011090372776e-05 7.05233494129132e-06 1.28244800435405e-05 3.63546789203099e-07 2.14195435591123e-06 9.09694301846262e-06 -8.0720392361023e-07 3.12745516048932e-06 -2.99517350837251e-08 -8.27801150714686e-06 1.56011090372776e-05 -8.0720392361023e-07 4.9503640348628e-05 1.35409397883046e-05 1.14605609400989e-05 -2.66263018953853e-06 7.05233494129132e-06 3.12745516048932e-06 1.35409397883046e-05 2.5456135206628e-05 8.26684327624626e-06 -4.01983939602128e-06 1.28244800435405e-05 -2.99517350837251e-08 1.14605609400989e-05 8.26684327624626e-06 3.42451157595265e-05 932 934 0 12 0 936 946 0 25 0 0 0 0 0 0 10 23 0 2711 0 0 0 0 0 1820 +870 917 0.997406697723247 -0.0108815041102938 0.0711440243808629 0.00696224236364713 0.00152958114185188 0.991486030373767 0.130204116506354 0.0001223269518577 -0.0719551229471373 -0.129757637316527 0.988931451537312 0.0175809572006215 3.68389534612746e-05 -3.83078448838836e-05 -1.83692220144621e-06 -9.07703272158991e-06 -1.00146403222788e-05 6.08856814441896e-06 -3.83078448838836e-05 5.96823070647082e-05 4.33733870328557e-06 1.79149406022209e-05 1.35505088827551e-05 2.19997494213737e-06 -1.83692220144621e-06 4.33733870328557e-06 1.04558842236246e-05 -4.85159961423484e-06 1.08902298348495e-06 -1.53472777038286e-06 -9.07703272158991e-06 1.79149406022209e-05 -4.85159961423484e-06 8.01454099155045e-05 3.49220681913955e-05 1.52184479462916e-05 -1.00146403222788e-05 1.35505088827551e-05 1.08902298348495e-06 3.49220681913955e-05 4.22130972240613e-05 6.53228847409799e-06 6.08856814441896e-06 2.19997494213737e-06 -1.53472777038286e-06 1.52184479462916e-05 6.53228847409799e-06 3.38170551268864e-05 896 896 0 8 0 899 911 0 23 0 0 0 0 0 0 10 23 0 2330 0 0 0 0 0 1629 +870 900 0.998241192975747 -0.0111702685403751 0.0582215230571366 -0.0098653468307114 0.00374430807960059 0.992007129254138 0.126126268738791 -0.00950817886497991 -0.0591650302405215 -0.125686437652201 0.990304205073844 0.0154901558462677 6.70290929325372e-05 -8.60020876181835e-05 1.60404856559197e-06 -3.47458507016369e-05 -2.42493195333024e-05 -2.61069528527702e-06 -8.60020876181835e-05 0.000179292124905495 3.64422141806449e-06 8.36068270340572e-05 4.93557223157087e-05 2.32117197654396e-05 1.60404856559197e-06 3.64422141806449e-06 1.06575431934506e-05 -7.60159943937264e-07 5.57736169614997e-06 9.27267904419041e-07 -3.47458507016369e-05 8.36068270340572e-05 -7.60159943937264e-07 8.77631741341299e-05 3.42916095868652e-05 2.09338519865792e-05 -2.42493195333024e-05 4.93557223157087e-05 5.57736169614997e-06 3.42916095868652e-05 3.76440096842219e-05 1.20587064216369e-05 -2.61069528527702e-06 2.32117197654396e-05 9.27267904419041e-07 2.09338519865792e-05 1.20587064216369e-05 3.8105588872077e-05 920 922 0 7 0 921 934 0 21 0 0 0 0 0 0 14 25 0 2645 0 0 0 0 0 1599 +870 912 0.997857076074531 -0.0112130001154365 0.0644633566950968 -0.00469471540784332 0.00287391011543665 0.991766760968233 0.12802512440622 -0.00765296267588225 -0.0653681602053818 -0.127565514411187 0.989673705402125 0.0152598147887817 3.53280385540542e-05 -4.93940821452478e-05 -2.33225501408178e-06 -1.62654458990313e-05 -1.29173587857432e-05 4.2800580615922e-06 -4.93940821452478e-05 0.000110717876328685 7.22121469476294e-06 4.59345036274029e-05 3.18393085506025e-05 2.87393336623105e-06 -2.33225501408178e-06 7.22121469476294e-06 9.02803520591293e-06 -9.40304098950439e-07 4.79849737893723e-06 -1.39083824104309e-06 -1.62654458990313e-05 4.59345036274029e-05 -9.40304098950439e-07 8.49843569619159e-05 2.7080275349176e-05 9.35361303132273e-06 -1.29173587857432e-05 3.18393085506025e-05 4.79849737893723e-06 2.7080275349176e-05 3.2289807216631e-05 5.92419087640763e-06 4.2800580615922e-06 2.87393336623105e-06 -1.39083824104309e-06 9.35361303132273e-06 5.92419087640763e-06 2.9494873294627e-05 914 913 0 4 0 916 924 0 16 0 0 0 0 0 0 11 21 0 2594 0 0 0 0 0 2263 +870 902 0.997705886799232 -0.0113779909235422 0.0667345845023584 -0.00394436914707741 0.00279994033465045 0.991866803313519 0.127249380425776 -0.00629971006009055 -0.0676396612963209 -0.126770603087487 0.989623206282348 0.0167565622303174 4.64742744635792e-05 -5.37589897425166e-05 -7.78557481185999e-07 -2.03870873768305e-05 -1.37475982957111e-05 -8.1777412968122e-06 -5.37589897425166e-05 0.000105242919276288 5.42409953216977e-06 4.36915350656915e-05 2.42496220337326e-05 2.18507094572582e-05 -7.78557481185999e-07 5.42409953216977e-06 9.0529992151999e-06 -1.59127635745008e-07 3.77007220489732e-06 7.1679656284956e-07 -2.03870873768305e-05 4.36915350656915e-05 -1.59127635745008e-07 7.96028636237979e-05 2.1826043658549e-05 2.63480126754533e-05 -1.37475982957111e-05 2.42496220337326e-05 3.77007220489732e-06 2.1826043658549e-05 3.10745419232552e-05 1.23513967768415e-05 -8.1777412968122e-06 2.18507094572582e-05 7.1679656284956e-07 2.63480126754533e-05 1.23513967768415e-05 4.27822994669739e-05 898 899 0 7 0 899 907 0 17 0 0 0 0 0 0 14 22 0 2693 0 0 0 0 0 1785 +870 903 0.998162517984387 -0.0106420364493868 0.0596517791124266 -0.00632679976184364 0.00303927023555751 0.992010249017115 0.126120690933073 -0.00740376197250211 -0.0605173572415639 -0.125707648554933 0.990219792049869 0.0182481345459484 2.96319151110866e-05 -4.22992744592084e-05 -3.35608156362896e-06 -8.21500949778942e-06 -7.13765179959552e-06 6.06750630920985e-06 -4.22992744592084e-05 0.000119344743769246 1.07304216980125e-05 4.6775581362157e-05 2.81690779975558e-05 9.55492378457126e-06 -3.35608156362896e-06 1.07304216980125e-05 1.03420972795606e-05 -7.72244831348525e-07 5.52522832732678e-06 -1.20719851747293e-06 -8.21500949778942e-06 4.6775581362157e-05 -7.72244831348525e-07 9.51549863062216e-05 2.74614284643173e-05 2.00510228946646e-05 -7.13765179959552e-06 2.81690779975558e-05 5.52522832732678e-06 2.74614284643173e-05 3.27805713133389e-05 8.25920011303776e-06 6.06750630920985e-06 9.55492378457126e-06 -1.20719851747293e-06 2.00510228946646e-05 8.25920011303776e-06 3.25914568796279e-05 898 901 0 9 0 901 913 0 21 0 0 0 0 0 0 13 23 0 2664 0 0 0 0 0 1654 +871 929 0.995042220428616 -0.0344072842078752 0.0933119411325651 -0.0132749141566553 0.0208718967801092 0.989599306163185 0.142329115665573 -0.012064133682898 -0.0972385905352872 -0.139675882079842 0.985411236223704 0.00434837167962589 3.020855973818e-05 -2.68849384183951e-05 -4.59805090878417e-06 7.83934068318616e-07 -4.36272904643136e-06 1.19240533247274e-05 -2.68849384183951e-05 4.39381129389112e-05 5.8512036127454e-06 1.16172207016041e-05 5.40278216938222e-06 -7.23995311913825e-06 -4.59805090878417e-06 5.8512036127454e-06 9.41621751908857e-06 -8.83179591196333e-07 4.01621514361268e-06 -4.4112786027557e-06 7.83934068318616e-07 1.16172207016041e-05 -8.83179591196333e-07 4.43576934674302e-05 -4.26554872042445e-06 6.25621389904265e-06 -4.36272904643136e-06 5.40278216938222e-06 4.01621514361268e-06 -4.26554872042445e-06 2.35039469185849e-05 -2.07050788246336e-06 1.19240533247274e-05 -7.23995311913825e-06 -4.4112786027557e-06 6.25621389904265e-06 -2.07050788246336e-06 2.65067681127678e-05 905 904 0 0 0 913 913 0 3 0 0 0 0 0 0 29 44 0 2674 0 0 0 0 0 2237 +871 921 0.996451453560016 -0.0104321908040376 0.0835204770889136 -0.00527728954998671 0.000216637063915212 0.992603966040775 0.121397362691722 -0.00969693381439559 -0.0841691972547803 -0.120948484881585 0.989083924769953 0.0050581986656436 1.67331757202394e-05 -1.26677450973599e-05 4.16753257986863e-06 -3.26112686207125e-06 -3.51973025337897e-07 -2.03794371955279e-07 -1.26677450973599e-05 3.28032089969643e-05 -1.7050693375585e-06 8.51680282569096e-06 4.25529947855327e-06 5.01195950982298e-06 4.16753257986863e-06 -1.7050693375585e-06 8.43442539359202e-06 1.00284512624987e-06 1.61865626127103e-06 1.08007008339347e-06 -3.26112686207125e-06 8.51680282569096e-06 1.00284512624987e-06 5.09472599062811e-05 1.52148046760302e-05 2.74707343216282e-06 -3.51973025337897e-07 4.25529947855327e-06 1.61865626127103e-06 1.52148046760302e-05 2.5397942061811e-05 5.11057135237822e-06 -2.03794371955279e-07 5.01195950982298e-06 1.08007008339347e-06 2.74707343216282e-06 5.11057135237822e-06 2.43580856983401e-05 849 846 0 9 0 846 858 0 23 0 0 0 0 0 0 18 31 0 2560 0 0 0 0 0 2241 +871 873 0.999751602421588 -0.0222841497564883 0.000387459800543192 0.00127703799276361 0.0222875171820684 0.999595979780365 -0.017639268261232 0.0135430339568334 5.77283657868721e-06 0.0176435222266729 0.999844340930183 -0.000984907107081938 3.04407684239599e-05 -4.15913253605574e-05 3.6654601993546e-06 -1.29836845040623e-05 -8.18960135377343e-06 2.68051926418968e-05 -4.15913253605574e-05 9.10342828952713e-05 -4.8038222041778e-06 5.14139279990507e-05 2.86288428249735e-05 -4.561512101584e-05 3.6654601993546e-06 -4.8038222041778e-06 8.65668831809406e-06 -1.20983067775765e-06 1.72695657468549e-06 1.20300746517379e-06 -1.29836845040623e-05 5.14139279990507e-05 -1.20983067775765e-06 8.00660921036601e-05 2.47753935046241e-05 -1.52595286312035e-05 -8.18960135377343e-06 2.86288428249735e-05 1.72695657468549e-06 2.47753935046241e-05 4.05384295631925e-05 -8.32785413586077e-06 2.68051926418968e-05 -4.561512101584e-05 1.20300746517379e-06 -1.52595286312035e-05 -8.32785413586077e-06 5.42083789504076e-05 768 768 0 0 0 780 780 0 2 0 0 0 0 0 0 39 42 0 2099 0 0 0 0 0 2503 +870 897 0.998511610191942 -0.0108222885833764 0.0534550501048599 -0.0130020044234105 0.00403115481108559 0.992078803417244 0.125552369954132 -0.0106509040897772 -0.0543903861246086 -0.125150013503908 0.990645829758137 0.0153072923655565 4.27460191433437e-05 -4.47513219113466e-05 7.58918149828809e-07 -2.11049720925577e-05 -1.20241476319125e-05 5.96244629854781e-07 -4.47513219113466e-05 7.05024081220024e-05 1.2895171082501e-06 3.76099180716131e-05 2.06837973577081e-05 1.00506406688988e-05 7.58918149828809e-07 1.2895171082501e-06 9.54751330237136e-06 -5.28906549572211e-06 2.47662300159668e-06 -1.98804186183083e-06 -2.11049720925577e-05 3.76099180716131e-05 -5.28906549572211e-06 7.92049153703159e-05 3.05991825014219e-05 1.32298699593446e-05 -1.20241476319125e-05 2.06837973577081e-05 2.47662300159668e-06 3.05991825014219e-05 3.44244366541203e-05 9.52807063067363e-06 5.96244629854781e-07 1.00506406688988e-05 -1.98804186183083e-06 1.32298699593446e-05 9.52807063067363e-06 3.35025059416666e-05 953 953 0 8 0 955 959 0 15 0 0 0 0 0 0 11 18 0 2623 0 0 0 0 0 1585 +870 910 0.998005243146372 -0.0112219159155591 0.0621257052719389 -0.0068045884908183 0.0032354698540893 0.991873231430512 0.127188932326745 -0.00906564234301377 -0.0630481275469381 -0.126734215485709 0.989930993674835 0.015129260131342 2.90371436528792e-05 -3.28003041289911e-05 1.66485648724935e-06 -8.89427290350994e-06 -1.19233277230155e-06 5.82151632578694e-07 -3.28003041289911e-05 7.14017671782395e-05 7.02301605625973e-07 2.78441721393142e-05 7.60964663673926e-06 1.30630614840763e-05 1.66485648724935e-06 7.02301605625973e-07 9.41979817284461e-06 -1.26371621801892e-06 5.16980183307791e-06 1.52101785147025e-06 -8.89427290350994e-06 2.78441721393142e-05 -1.26371621801892e-06 5.73187154373514e-05 1.27780313366975e-05 8.37073220878657e-06 -1.19233277230155e-06 7.60964663673926e-06 5.16980183307791e-06 1.27780313366975e-05 2.16364272623549e-05 6.94950056398424e-06 5.82151632578694e-07 1.30630614840763e-05 1.52101785147025e-06 8.37073220878657e-06 6.94950056398424e-06 3.29654472674967e-05 931 933 0 9 0 933 943 0 21 0 0 0 0 0 0 10 20 0 2653 0 0 0 0 0 1623 +871 922 0.99603963731936 -0.0109048684621615 0.0882390204645412 -0.000543782431132649 -0.000417287189120716 0.991865667380893 0.127288348808745 -0.00478580603914503 -0.0889093176226236 -0.126821061795262 0.987932969145681 0.0104650390980348 3.45901692651205e-05 -3.39620988931724e-05 -2.72025030209393e-06 -6.36345131244275e-06 -4.99171380793818e-06 7.41574232785637e-06 -3.39620988931724e-05 4.83242850572456e-05 4.05829801370205e-06 1.86217756571477e-05 1.25194822975519e-05 -2.83916754661498e-06 -2.72025030209393e-06 4.05829801370205e-06 9.50944252561337e-06 -2.28524281095233e-06 1.97084501932242e-06 -2.9784212726077e-06 -6.36345131244275e-06 1.86217756571477e-05 -2.28524281095233e-06 6.58334937527036e-05 2.29629098940612e-05 5.34307588346566e-06 -4.99171380793818e-06 1.25194822975519e-05 1.97084501932242e-06 2.29629098940612e-05 2.88927769413922e-05 6.68144158213424e-06 7.41574232785637e-06 -2.83916754661498e-06 -2.9784212726077e-06 5.34307588346566e-06 6.68144158213424e-06 2.92664948262076e-05 870 866 0 6 0 865 877 0 22 0 0 0 0 0 0 15 28 0 2687 0 0 0 0 0 1855 +871 920 0.996196954630222 -0.010830862701291 0.086454149689977 -0.00307707440929855 0.00014692559439111 0.992451213616845 0.122639989413409 -0.0101372855212161 -0.0871298226690545 -0.12216088164219 0.988678467955109 0.00923839260789592 3.7287311824702e-05 -4.64649804469727e-05 -3.56071721681234e-06 -1.03385498461022e-05 -5.10811785304714e-06 9.22413978868653e-06 -4.64649804469727e-05 0.000104976615395837 8.1557624393594e-06 4.37613658076551e-05 1.58930022190932e-05 2.40033854823506e-06 -3.56071721681234e-06 8.1557624393594e-06 1.07113046076128e-05 -2.83994610268956e-06 2.65014007255442e-06 -2.35958680261744e-06 -1.03385498461022e-05 4.37613658076551e-05 -2.83994610268956e-06 8.60593214976575e-05 2.22300836525709e-05 1.19951438054569e-05 -5.10811785304714e-06 1.58930022190932e-05 2.65014007255442e-06 2.22300836525709e-05 3.18371501877557e-05 2.83748716303609e-06 9.22413978868653e-06 2.40033854823506e-06 -2.35958680261744e-06 1.19951438054569e-05 2.83748716303609e-06 2.97801889501169e-05 856 857 0 8 0 857 865 0 19 0 0 0 0 0 0 17 28 0 2422 0 0 0 0 0 2129 +871 925 0.995765293018079 -0.0112279235044368 0.0912437118622363 -0.00371062050214837 -0.000134031100229587 0.992335379785851 0.123573767689323 -0.008021427315 -0.0919318402746538 -0.123062698487596 0.988131625333724 0.00641546847649227 3.40444308983151e-05 -3.32887096037441e-05 2.8679484741923e-06 -1.19896579850051e-05 -5.06559280894941e-06 6.60159066258139e-06 -3.32887096037441e-05 5.22901161654078e-05 -1.14500536878138e-07 2.10449785739464e-05 8.68253218531532e-06 -1.61110502412772e-06 2.8679484741923e-06 -1.14500536878138e-07 9.65386843660553e-06 3.61129212034931e-07 3.9632122083797e-06 3.52004871311838e-06 -1.19896579850051e-05 2.10449785739464e-05 3.61129212034931e-07 6.0465007169148e-05 1.54738289712452e-05 8.06884561489171e-06 -5.06559280894941e-06 8.68253218531532e-06 3.9632122083797e-06 1.54738289712452e-05 2.5812113356388e-05 6.28418363967048e-06 6.60159066258139e-06 -1.61110502412772e-06 3.52004871311838e-06 8.06884561489171e-06 6.28418363967048e-06 3.14255371812706e-05 855 858 0 7 0 860 872 0 22 0 0 0 0 0 0 19 31 0 2539 0 0 0 0 0 2283 +871 924 0.99648301058563 -0.0106916664152069 0.0831101551163593 -0.00369033915717644 0.000332535999561623 0.992323358289283 0.123669891296502 -0.0078570841544962 -0.083794385456356 -0.123207308479431 0.988836922906526 0.010953765270781 3.47615784938975e-05 -4.20713833193729e-05 -1.66861333383376e-06 -9.86870035930968e-06 -6.53354451827052e-06 -5.40638334098993e-06 -4.20713833193729e-05 6.87452478007213e-05 4.63392315388079e-06 2.29781577830509e-05 1.28298826710314e-05 1.46565479922384e-05 -1.66861333383376e-06 4.63392315388079e-06 1.06669513733307e-05 -2.79199456385233e-06 2.81848524564466e-06 1.65108461460714e-06 -9.86870035930968e-06 2.29781577830509e-05 -2.79199456385233e-06 6.19016254346753e-05 1.77403653292151e-05 9.10426107088472e-06 -6.53354451827052e-06 1.28298826710314e-05 2.81848524564466e-06 1.77403653292151e-05 2.92895079415634e-05 9.8174764772833e-06 -5.40638334098993e-06 1.46565479922384e-05 1.65108461460714e-06 9.10426107088472e-06 9.8174764772833e-06 3.53194070313825e-05 860 859 0 9 0 858 866 0 19 0 0 0 0 0 0 17 26 0 2627 0 0 0 0 0 1491 +871 875 0.999920320731063 -0.00980233502034869 -0.00795401893622932 0.0146619180017461 0.009691049480656 0.999856272626483 -0.0139110621248011 0.0183143598209963 0.00808923661741489 0.0138328709104598 0.999871599723345 0.00810199161023573 4.3570689830011e-05 -5.13808842213128e-05 1.55287279198929e-06 -2.31170640055012e-05 -1.60755399049838e-05 1.65435827598862e-05 -5.13808842213128e-05 7.88186267302249e-05 -2.42590097932981e-06 5.3061894033562e-05 2.96698885263117e-05 -1.40227752148492e-05 1.55287279198929e-06 -2.42590097932981e-06 9.51319016621146e-06 -4.50540202093405e-06 7.53088957843194e-07 -1.89353783558934e-06 -2.31170640055012e-05 5.3061894033562e-05 -4.50540202093405e-06 0.0001001269078799 3.61384417978944e-05 3.26874964948921e-06 -1.60755399049838e-05 2.96698885263117e-05 7.53088957843194e-07 3.61384417978944e-05 4.07048220074467e-05 -5.1621692687624e-07 1.65435827598862e-05 -1.40227752148492e-05 -1.89353783558934e-06 3.26874964948921e-06 -5.1621692687624e-07 3.41488533404795e-05 754 753 0 7 0 761 766 0 15 0 0 0 0 0 0 19 27 0 2081 0 0 0 0 0 2124 +871 874 0.999749853847615 -0.018524719336099 -0.0125325378591388 0.0072744466558069 0.0183670376206184 0.999752141623534 -0.0125820208313187 0.0150131451738233 0.0127625099692331 0.0123486878928779 0.999842301688926 0.00639230657476671 3.52673060141199e-05 -3.96362946171148e-05 -5.2122956519588e-08 -1.13381797267577e-05 -1.00704247890811e-05 1.76845209091296e-05 -3.96362946171148e-05 5.66214872811909e-05 -8.38549367924632e-07 3.11889588609259e-05 2.16511349758e-05 -1.60653068883929e-05 -5.2122956519588e-08 -8.38549367924632e-07 8.51435233550657e-06 -1.89311733605856e-06 -5.84630240028438e-07 -1.55223694909933e-06 -1.13381797267577e-05 3.11889588609259e-05 -1.89311733605856e-06 7.46769524059809e-05 2.80129154372485e-05 2.86118725810008e-07 -1.00704247890811e-05 2.16511349758e-05 -5.84630240028438e-07 2.80129154372485e-05 3.65278215241996e-05 1.80336971218954e-06 1.76845209091296e-05 -1.60653068883929e-05 -1.55223694909933e-06 2.86118725810008e-07 1.80336971218954e-06 3.15696166578835e-05 744 740 0 7 0 753 753 0 6 0 0 0 0 0 0 19 29 0 2070 0 0 0 0 0 2491 +871 919 0.996806551197723 -0.0103864863910742 0.0791758826269026 -0.00738906116756946 0.000522924300600481 0.992332836595811 0.123593155004178 -0.00910762198316693 -0.0798525268196121 -0.123157063598313 0.989169303833456 0.0121197256720232 3.53785088361392e-05 -3.53938141591018e-05 -3.33176315152928e-06 -2.59993972402705e-06 -4.54303000263678e-07 9.4707713008155e-06 -3.53938141591018e-05 5.57085910060343e-05 5.11494948268291e-06 1.34120692736265e-05 1.92345671027586e-06 -5.86442631468285e-06 -3.33176315152928e-06 5.11494948268291e-06 1.08140741450793e-05 -3.63062063481954e-06 7.71223533642021e-07 -2.86372284914586e-06 -2.59993972402705e-06 1.34120692736265e-05 -3.63062063481954e-06 6.86175081412577e-05 1.76774480347811e-05 5.54928442135847e-06 -4.54303000263678e-07 1.92345671027586e-06 7.71223533642021e-07 1.76774480347811e-05 3.12461414056038e-05 4.31885548170494e-06 9.4707713008155e-06 -5.86442631468285e-06 -2.86372284914586e-06 5.54928442135847e-06 4.31885548170494e-06 3.06881954430991e-05 891 892 0 8 0 892 903 0 21 0 0 0 0 0 0 11 25 0 2448 0 0 0 0 0 1777 +871 923 0.995893182225332 -0.0112511415251949 0.0898341884333625 -0.00264784196081782 -0.000252224049228403 0.99189948103791 0.127025020762662 -0.00480074545599322 -0.0905356613723555 -0.126526010492332 0.987823092810026 0.0107697243160363 3.02491138521801e-05 -3.21419415008938e-05 1.77665238799778e-06 -8.55817741557159e-06 -5.45802673102001e-06 8.08543165337768e-06 -3.21419415008938e-05 5.81332223890691e-05 1.46861999778279e-06 1.98849507628759e-05 1.1172510940193e-05 -2.46200086510956e-06 1.77665238799778e-06 1.46861999778279e-06 9.84988009165159e-06 1.2732290254336e-07 3.25159651575922e-06 1.05846524769612e-06 -8.55817741557159e-06 1.98849507628759e-05 1.2732290254336e-07 5.23349512526217e-05 1.6436107560338e-05 4.97903014137723e-06 -5.45802673102001e-06 1.1172510940193e-05 3.25159651575922e-06 1.6436107560338e-05 2.65892577331419e-05 4.94481488462571e-06 8.08543165337768e-06 -2.46200086510956e-06 1.05846524769612e-06 4.97903014137723e-06 4.94481488462571e-06 2.90486454778371e-05 863 864 0 7 0 860 869 0 19 0 0 0 0 0 0 21 32 0 2527 0 0 0 0 0 1870 +871 926 0.997026921990651 -0.010805009422011 0.0762926510041323 -0.0167687415345279 0.00138155052608527 0.992467029539633 0.122504230926612 -0.0127453236660032 -0.0770416000871733 -0.12203461413946 0.989531275305557 0.0127747959966285 4.33455708076374e-05 -4.84935549433714e-05 -4.2819736358019e-06 -2.00206135304019e-05 -1.07703840685685e-05 3.65353400809388e-06 -4.84935549433714e-05 7.93318710275729e-05 7.64108889946735e-06 3.9807944177345e-05 1.89407056210958e-05 6.65184784538731e-06 -4.2819736358019e-06 7.64108889946735e-06 1.11289124700561e-05 -7.16023142699068e-07 4.1884875540608e-06 -4.82720920730431e-07 -2.00206135304019e-05 3.9807944177345e-05 -7.16023142699068e-07 7.40276669215132e-05 2.12615303686066e-05 1.80846611842205e-05 -1.07703840685685e-05 1.89407056210958e-05 4.1884875540608e-06 2.12615303686066e-05 2.94820908882237e-05 9.42121937350461e-06 3.65353400809388e-06 6.65184784538731e-06 -4.82720920730431e-07 1.80846611842205e-05 9.42121937350461e-06 4.2922656116125e-05 870 871 0 6 0 869 878 0 18 0 0 0 0 0 0 20 33 0 2612 0 0 0 0 0 1346 +871 916 0.996822947196342 -0.0108170493717226 0.0789113641099147 -0.00867047148518974 0.000916239324259355 0.992226857077228 0.124438838792984 -0.0106334420885508 -0.079644035861441 -0.123971188336385 0.989084410965094 0.0109665179833051 4.32760735752818e-05 -5.23330150986536e-05 -2.30773419376034e-06 -1.33301138450936e-05 -1.12425941754495e-05 6.83438427281427e-06 -5.23330150986536e-05 8.99340383548479e-05 3.74522002645743e-06 3.69486345641916e-05 2.39198677913557e-05 4.11853597351598e-06 -2.30773419376034e-06 3.74522002645743e-06 9.62143757131282e-06 -6.66219605487306e-07 1.14280042777386e-06 -2.11237810841799e-06 -1.33301138450936e-05 3.69486345641916e-05 -6.66219605487306e-07 7.28066286999902e-05 2.05015252534999e-05 7.42649910035735e-06 -1.12425941754495e-05 2.39198677913557e-05 1.14280042777386e-06 2.05015252534999e-05 3.42962533698972e-05 8.95796520207446e-06 6.83438427281427e-06 4.11853597351598e-06 -2.11237810841799e-06 7.42649910035735e-06 8.95796520207446e-06 2.8993025545243e-05 867 867 0 4 0 869 876 0 15 0 0 0 0 0 0 14 28 0 2562 0 0 0 0 0 1819 +871 927 0.996849789162581 -0.0110319284501099 0.0785416730226031 -0.0161484069083107 0.00132831702079744 0.99246245744514 0.122541854628716 -0.0137524579679194 -0.0793015347922731 -0.12205149370911 0.989350645354298 0.0130464917369528 5.13302955924903e-05 -5.58413573856144e-05 -7.3560809319478e-06 -1.84443736412466e-05 -9.01807050332522e-06 2.87249253823649e-06 -5.58413573856144e-05 8.22753310849145e-05 1.09800726963005e-05 3.34438893499297e-05 1.53221477693232e-05 7.22651622450322e-06 -7.3560809319478e-06 1.09800726963005e-05 1.08208732907851e-05 3.04957825298409e-06 4.45058417195089e-06 -1.31238417893649e-06 -1.84443736412466e-05 3.34438893499297e-05 3.04957825298409e-06 5.25623435361268e-05 1.10505997764666e-05 1.59520026959019e-05 -9.01807050332522e-06 1.53221477693232e-05 4.45058417195089e-06 1.10505997764666e-05 2.59480811869899e-05 9.30729951102753e-06 2.87249253823649e-06 7.22651622450322e-06 -1.31238417893649e-06 1.59520026959019e-05 9.30729951102753e-06 4.2044745700875e-05 861 862 0 7 0 860 869 0 19 0 0 0 0 0 0 18 32 0 2655 0 0 0 0 0 1347 +871 915 0.996874457201581 -0.010147952245645 0.0783475311945021 -0.00637903421882127 0.000406576705715598 0.992361615251421 0.123362308956071 -0.00795468525019141 -0.0790009574273359 -0.122944880498582 0.989264072472438 0.0115247334686109 5.44827760198591e-05 -5.87862660063451e-05 -4.38823484218117e-06 -2.44408636921046e-05 -1.39681965546234e-05 -4.43271495925968e-06 -5.87862660063451e-05 8.06983594261247e-05 7.56459207350186e-06 3.5089314268335e-05 1.79262127821942e-05 1.20655533179593e-05 -4.38823484218117e-06 7.56459207350186e-06 1.05182533882323e-05 -2.58281288905791e-07 1.86349638187761e-06 -1.05735634817131e-07 -2.44408636921046e-05 3.5089314268335e-05 -2.58281288905791e-07 8.64480398226772e-05 2.96537972288439e-05 1.75042243825155e-05 -1.39681965546234e-05 1.79262127821942e-05 1.86349638187761e-06 2.96537972288439e-05 3.46908794216673e-05 1.13487933593063e-05 -4.43271495925968e-06 1.20655533179593e-05 -1.05735634817131e-07 1.75042243825155e-05 1.13487933593063e-05 4.4982973632862e-05 875 874 0 7 0 875 883 0 17 0 0 0 0 0 0 15 28 0 2672 0 0 0 0 0 1361 +871 928 0.997015255309541 -0.0109232075821928 0.0764281637628954 -0.0123998044822556 0.00142334257905725 0.992372958218298 0.123263481587073 -0.0124014206348049 -0.0771916755612565 -0.122786788105156 0.989426525766752 0.0152455196920117 3.60320147786298e-05 -4.59518276567997e-05 -3.22887940612604e-06 -6.25813694751401e-06 -4.88718850960302e-06 8.91586591551358e-06 -4.59518276567997e-05 0.000114121286970932 8.69632214087818e-06 4.19980008526762e-05 1.37309301964292e-05 5.14205325157957e-07 -3.22887940612604e-06 8.69632214087818e-06 1.02683438308787e-05 1.57448884912247e-06 2.22850687007328e-06 -9.30151049868036e-07 -6.25813694751401e-06 4.19980008526762e-05 1.57448884912247e-06 6.50606147058448e-05 9.8724347107646e-06 8.4246118039209e-06 -4.88718850960302e-06 1.37309301964292e-05 2.22850687007328e-06 9.8724347107646e-06 2.9026678727809e-05 4.42542168506828e-06 8.91586591551358e-06 5.14205325157957e-07 -9.30151049868036e-07 8.4246118039209e-06 4.42542168506828e-06 2.9901177835455e-05 847 846 0 5 0 843 855 0 20 0 0 0 0 0 0 22 35 0 2600 0 0 0 0 0 1764 +871 912 0.997164077447167 -0.00985022618449324 0.0746108282560555 -0.0103077791453873 0.00082592356593059 0.992770098104084 0.120028538942495 -0.0113438807170484 -0.075253707544569 -0.119626524460594 0.989962814527028 0.00458601430769205 3.00071235892838e-05 -2.71107280762753e-05 -1.36590881766339e-06 -3.96151403861069e-07 -5.57233218884215e-06 4.89157052463788e-06 -2.71107280762753e-05 4.87169505098774e-05 4.54831280592539e-06 3.1793852472422e-06 6.56103796213086e-06 1.64930386428906e-06 -1.36590881766339e-06 4.54831280592539e-06 9.27493852545737e-06 -1.94822802753784e-06 2.35149402447218e-06 -1.14309058822315e-06 -3.96151403861069e-07 3.1793852472422e-06 -1.94822802753784e-06 5.14556754997959e-05 1.05153525138959e-05 3.73346595826316e-06 -5.57233218884215e-06 6.56103796213086e-06 2.35149402447218e-06 1.05153525138959e-05 2.767479783168e-05 3.7803711072162e-06 4.89157052463788e-06 1.64930386428906e-06 -1.14309058822315e-06 3.73346595826316e-06 3.7803711072162e-06 2.96076973202261e-05 871 872 0 6 0 868 876 0 16 0 0 0 0 0 0 18 31 0 2592 0 0 0 0 0 2299 +871 917 0.997261566704089 -0.00952496787882755 0.0733392293510981 -0.00614820916460025 0.000543291018141325 0.992588193071383 0.121525239395593 -0.00758014228180758 -0.0739531771445641 -0.121152606089155 0.989875231343845 0.00974043655093099 6.69356360184037e-05 -8.21576744932987e-05 -2.83837507756154e-06 -4.49520782092423e-05 -2.8967695094573e-05 -4.02842127974232e-06 -8.21576744932987e-05 0.000150350061227333 8.63820202791526e-06 9.55255545170826e-05 5.10080186307334e-05 2.94378682376295e-05 -2.83837507756154e-06 8.63820202791526e-06 1.12266925943549e-05 -1.33101932343304e-06 3.2974638361165e-06 1.79582807084852e-06 -4.49520782092423e-05 9.55255545170826e-05 -1.33101932343304e-06 0.000147490467845526 6.42466117096843e-05 3.67932881551092e-05 -2.8967695094573e-05 5.10080186307334e-05 3.2974638361165e-06 6.42466117096843e-05 5.94576523023887e-05 1.96659659070958e-05 -4.02842127974232e-06 2.94378682376295e-05 1.79582807084852e-06 3.67932881551092e-05 1.96659659070958e-05 5.67836204650956e-05 841 840 0 8 0 840 851 0 22 0 0 0 0 0 0 18 33 0 2355 0 0 0 0 0 1373 +871 918 0.997071877072933 -0.0104361862039607 0.0757545904072727 -0.010028344743388 0.00118879699386538 0.992639323855286 0.12110226875591 -0.0136715959427981 -0.0764608312272681 -0.120657609596899 0.989745160399584 0.0095094780765095 4.18668734689221e-05 -4.07106685717386e-05 -5.53379401843033e-06 -3.55172227881927e-06 -5.84397391632643e-06 1.36034813934557e-05 -4.07106685717386e-05 6.90370709617084e-05 5.99509114409818e-06 2.5402429528124e-05 1.05356373124061e-05 -3.46992965190188e-06 -5.53379401843033e-06 5.99509114409818e-06 9.24526714402313e-06 -2.31330076045643e-06 2.36151163817808e-06 -3.34493404594431e-06 -3.55172227881927e-06 2.5402429528124e-05 -2.31330076045643e-06 6.85182604266981e-05 1.39670192977832e-05 8.85149630264024e-06 -5.84397391632643e-06 1.05356373124061e-05 2.36151163817808e-06 1.39670192977832e-05 2.72062709412725e-05 1.31018321367785e-06 1.36034813934557e-05 -3.46992965190188e-06 -3.34493404594431e-06 8.85149630264024e-06 1.31018321367785e-06 3.63721056171687e-05 880 883 0 12 0 879 892 0 24 0 0 0 0 0 0 20 32 0 2397 0 0 0 0 0 2156 +871 913 0.995970433750733 -0.0110654424841983 0.0889969161095241 -0.000169394172807866 -0.000272957396635154 0.991980250959256 0.126392670677817 -0.00451008456558237 -0.0896817740047352 -0.125907655404429 0.987979980425678 0.0104253608583154 2.64223914144606e-05 -2.24065538408574e-05 3.5294766419762e-06 -6.75776420375723e-06 -4.34308395620411e-06 8.75638237992809e-07 -2.24065538408574e-05 4.11478968216097e-05 1.58975582310817e-07 5.28171145999385e-06 2.80224399926324e-06 3.75094533286415e-06 3.5294766419762e-06 1.58975582310817e-07 9.69638472174581e-06 -2.30804096066489e-06 3.11008265950622e-06 3.15434437090281e-07 -6.75776420375723e-06 5.28171145999385e-06 -2.30804096066489e-06 5.88471847839984e-05 1.57449797037776e-05 4.00215354393572e-06 -4.34308395620411e-06 2.80224399926324e-06 3.11008265950622e-06 1.57449797037776e-05 3.04942184438273e-05 3.9451030280522e-06 8.75638237992809e-07 3.75094533286415e-06 3.15434437090281e-07 4.00215354393572e-06 3.9451030280522e-06 2.86150833820304e-05 872 871 0 7 0 869 881 0 22 0 0 0 0 0 0 17 30 0 2529 0 0 0 0 0 1587 +871 914 0.996237635644022 -0.0106573582695054 0.0860057791146839 -0.00426591367335997 -0.000163095170729304 0.992177587021202 0.124834327060908 -0.00712023678959922 -0.0866634105397063 -0.1243786819656 0.988442915269327 0.00686298605863313 2.26604513995624e-05 -2.30378209465294e-05 2.11133463642774e-06 -3.32799421017858e-06 -1.71013706082439e-06 9.95335024263559e-06 -2.30378209465294e-05 6.03304269533811e-05 2.16508570155544e-06 1.53173963166028e-05 7.6333103278857e-06 -4.4958120275017e-06 2.11133463642774e-06 2.16508570155544e-06 8.84989951664945e-06 -8.61164067438457e-07 2.67417352775608e-06 -9.76530827084642e-07 -3.32799421017858e-06 1.53173963166028e-05 -8.61164067438457e-07 5.40967591272059e-05 1.44630657216008e-05 -2.88921487413463e-06 -1.71013706082439e-06 7.6333103278857e-06 2.67417352775608e-06 1.44630657216008e-05 2.53414400171632e-05 4.66817893918336e-07 9.95335024263559e-06 -4.4958120275017e-06 -9.76530827084642e-07 -2.88921487413463e-06 4.66817893918336e-07 2.69801810322946e-05 881 882 0 8 0 880 889 0 20 0 0 0 0 0 0 19 31 0 2703 0 0 0 0 0 2182 +871 901 0.996998277076936 -0.0101794479553158 0.0767516406661538 -0.00638088816453354 0.000439818054122451 0.992047849347629 0.125860522662282 -0.00633470886142803 -0.0774224906968294 -0.125448967489049 0.989074473682458 0.0111220749576097 4.39728493679814e-05 -5.66345008546388e-05 -1.35258952388177e-06 -1.9991526897493e-05 -1.42470514067548e-05 9.05087994724223e-06 -5.66345008546388e-05 0.000131505874216367 4.51538963862614e-06 7.64347294683032e-05 3.86719496442782e-05 -3.02567440626111e-06 -1.35258952388177e-06 4.51538963862614e-06 9.73568822125179e-06 -1.68363159515219e-06 3.72279958427381e-06 -1.59282156021553e-06 -1.9991526897493e-05 7.64347294683032e-05 -1.68363159515219e-06 0.000119594473163434 4.14680110267566e-05 7.87162045147926e-06 -1.42470514067548e-05 3.86719496442782e-05 3.72279958427381e-06 4.14680110267566e-05 3.77516098304918e-05 3.96570774919103e-06 9.05087994724223e-06 -3.02567440626111e-06 -1.59282156021553e-06 7.87162045147926e-06 3.96570774919103e-06 2.82862739731462e-05 852 850 0 9 0 850 863 0 23 0 0 0 0 0 0 16 28 0 2609 0 0 0 0 0 1849 +871 910 0.996627888521993 -0.0103337590467441 0.081400646460316 -0.00528095756709724 0.000174140941209129 0.992302180993286 0.123840022896075 -0.00978673245242272 -0.0820537719737863 -0.123408245348241 0.988957826949634 0.00831663554768725 4.56100101023202e-05 -5.91063747326325e-05 -2.37553978039606e-06 -1.22835128417446e-05 -9.69630101598604e-06 1.89858066698275e-05 -5.91063747326325e-05 0.000155510952454862 9.3481192732073e-06 6.2530363236316e-05 2.64535051957329e-05 -1.80370604660303e-05 -2.37553978039606e-06 9.3481192732073e-06 1.02512633489848e-05 -5.60662711798394e-09 3.95900836462243e-06 -2.09217272611121e-06 -1.22835128417446e-05 6.2530363236316e-05 -5.60662711798394e-09 9.36121432357151e-05 2.27681110139542e-05 -3.54443038789683e-07 -9.69630101598604e-06 2.64535051957329e-05 3.95900836462243e-06 2.27681110139542e-05 3.0888436050746e-05 1.21393073291662e-06 1.89858066698275e-05 -1.80370604660303e-05 -2.09217272611121e-06 -3.54443038789683e-07 1.21393073291662e-06 3.19349405591378e-05 855 857 0 8 0 856 865 0 19 0 0 0 0 0 0 17 28 0 2629 0 0 0 0 0 2175 +871 908 0.995845862379074 -0.0109680639650136 0.0903920348002915 0.00170157400336415 -0.000723845286167467 0.99173379374126 0.128310398641615 -0.00437032230209909 -0.0910521522561627 -0.127842809435759 0.987606055897336 0.00841267474238217 2.78303266942226e-05 -2.43085396448629e-05 2.88317409900837e-06 -1.03489731718795e-05 -6.71557885489669e-06 1.18095536909316e-05 -2.43085396448629e-05 4.07923928225035e-05 1.07230771059117e-07 1.95380868066291e-05 8.68743885191493e-06 -5.50578235004561e-06 2.88317409900837e-06 1.07230771059117e-07 9.59633602504408e-06 -2.42859322507718e-07 2.86897933993843e-06 2.207927639245e-06 -1.03489731718795e-05 1.95380868066291e-05 -2.42859322507718e-07 6.78490753536026e-05 1.51597140836142e-05 -2.75841272916591e-06 -6.71557885489669e-06 8.68743885191493e-06 2.86897933993843e-06 1.51597140836142e-05 2.99570573905734e-05 -1.85064095088059e-06 1.18095536909316e-05 -5.50578235004561e-06 2.207927639245e-06 -2.75841272916591e-06 -1.85064095088059e-06 2.95658790634763e-05 868 866 0 9 0 865 877 0 23 0 0 0 0 0 0 17 29 0 2610 0 0 0 0 0 1914 +871 900 0.996494129402807 -0.0105553514835393 0.0829941842589029 -0.00645441910298315 0.000183411133518802 0.992282437464211 0.123998107487337 -0.00930339746213409 -0.0836625150596005 -0.123548164110779 0.988805559611574 0.0076112606392045 2.39425762249483e-05 -2.58916205703021e-05 3.92546197925477e-06 -1.19055909855006e-05 -6.30617530433761e-06 3.13100286119969e-06 -2.58916205703021e-05 6.11646643690379e-05 -1.2598585095176e-06 2.5834639654031e-05 1.06295135361661e-05 7.08317186924975e-06 3.92546197925477e-06 -1.2598585095176e-06 8.63295606876286e-06 -1.29485397628827e-06 2.7895879254841e-06 2.09785057451441e-06 -1.19055909855006e-05 2.5834639654031e-05 -1.29485397628827e-06 5.95846854502318e-05 1.43600761932573e-05 4.13821641531864e-06 -6.30617530433761e-06 1.06295135361661e-05 2.7895879254841e-06 1.43600761932573e-05 2.74687001285238e-05 5.58728067220467e-06 3.13100286119969e-06 7.08317186924975e-06 2.09785057451441e-06 4.13821641531864e-06 5.58728067220467e-06 2.58793893419102e-05 874 874 0 4 0 874 885 0 19 0 0 0 0 0 0 17 32 0 2613 0 0 0 0 0 2174 +871 903 0.996139331891801 -0.01062128734138 0.087141377733938 0.0014082989530043 -0.000483764193810228 0.99197445136209 0.126437549078923 -0.00456589175723139 -0.0877849499080669 -0.125991571543863 0.98813962903506 0.0100195479950008 4.44955907242998e-05 -4.20170410111675e-05 -1.64143236613713e-06 -1.1044218407745e-05 -7.63310297230203e-06 -3.87128254957773e-06 -4.20170410111675e-05 5.82603126342392e-05 4.16338112797076e-06 1.63498772945965e-05 9.08892510831479e-06 1.12750178777302e-05 -1.64143236613713e-06 4.16338112797076e-06 1.00926251029217e-05 -9.62459074612813e-07 2.41980490300063e-06 -4.23305362581418e-07 -1.1044218407745e-05 1.63498772945965e-05 -9.62459074612813e-07 6.48970623505013e-05 2.02394240164946e-05 1.08124023081498e-05 -7.63310297230203e-06 9.08892510831479e-06 2.41980490300063e-06 2.02394240164946e-05 2.91075247292835e-05 1.05401133270994e-05 -3.87128254957773e-06 1.12750178777302e-05 -4.23305362581418e-07 1.08124023081498e-05 1.05401133270994e-05 3.51423327024102e-05 846 849 0 9 0 847 859 0 21 0 0 0 0 0 0 16 26 0 2643 0 0 0 0 0 1569 +871 911 0.996521979520698 -0.0104275160036001 0.0826753363594238 -0.00619311960915487 8.96004614653056e-05 0.99227327087426 0.124071543394348 -0.00762943297865303 -0.083330284434331 -0.123632612277235 0.988823058427341 0.00972341144307732 3.84100803594277e-05 -4.36940767732218e-05 -2.68588721690622e-06 -1.4757281122699e-05 -8.66881153498119e-06 7.93600239884923e-06 -4.36940767732218e-05 7.42979173572014e-05 4.73733897121135e-06 3.62830664272401e-05 1.75185108786204e-05 3.01051102881274e-06 -2.68588721690622e-06 4.73733897121135e-06 9.18748147080802e-06 -1.83978614357168e-06 2.48231868614293e-06 -1.39206393380622e-06 -1.4757281122699e-05 3.62830664272401e-05 -1.83978614357168e-06 7.99053137476244e-05 2.61743070470414e-05 7.70169956139858e-06 -8.66881153498119e-06 1.75185108786204e-05 2.48231868614293e-06 2.61743070470414e-05 2.84863284316453e-05 4.90685071532833e-06 7.93600239884923e-06 3.01051102881274e-06 -1.39206393380622e-06 7.70169956139858e-06 4.90685071532833e-06 2.78419715664048e-05 890 894 0 11 0 886 897 0 22 0 0 0 0 0 0 17 29 0 2743 0 0 0 0 0 2183 +871 898 0.996944882550781 -0.0097940975426911 0.0774917854300334 -0.00979760918869263 0.000392936547559022 0.992723683687408 0.120414008516334 -0.00949741936826523 -0.0781072772325324 -0.120015680223154 0.989694644697997 0.0038582547685679 4.80312555335601e-05 -5.52437853384388e-05 -4.63178626421338e-06 -2.34831959941006e-05 -1.5505233211591e-05 2.50542262167858e-06 -5.52437853384388e-05 8.7509103624209e-05 6.91922931676102e-06 4.77030312992654e-05 2.84685039354631e-05 1.05291025832808e-05 -4.63178626421338e-06 6.91922931676102e-06 9.95939662647061e-06 -1.19133377512613e-06 3.84039428041184e-06 -3.36430771506845e-06 -2.34831959941006e-05 4.77030312992654e-05 -1.19133377512613e-06 9.27068268845901e-05 3.37805606298987e-05 2.50585219002657e-05 -1.5505233211591e-05 2.84685039354631e-05 3.84039428041184e-06 3.37805606298987e-05 3.22781793366408e-05 1.07145662331253e-05 2.50542262167858e-06 1.05291025832808e-05 -3.36430771506845e-06 2.50585219002657e-05 1.07145662331253e-05 3.62368415580932e-05 860 862 0 8 0 864 872 0 18 0 0 0 0 0 0 18 29 0 2704 0 0 0 0 0 2302 +871 909 0.997505077106705 -0.010083796895691 0.0698708679387387 -0.0142769944564977 0.00159094833213271 0.992705412481231 0.120554688477356 -0.0116448249660245 -0.0705768377709762 -0.120142752884368 0.990244731821187 0.00932317148993252 3.43421560562221e-05 -3.75108897012811e-05 -1.0010305056399e-06 -9.38563098590688e-06 -6.77620063566695e-06 3.19396691304664e-06 -3.75108897012811e-05 7.50093930739902e-05 4.62132729861859e-06 2.10320115445979e-05 1.09658611627412e-05 7.30049559318985e-06 -1.0010305056399e-06 4.62132729861859e-06 8.67196926801205e-06 5.66297315196733e-07 3.17234618958059e-06 -2.16767467641763e-07 -9.38563098590688e-06 2.10320115445979e-05 5.66297315196733e-07 5.26912795465606e-05 1.141691404828e-05 7.42019483061785e-06 -6.77620063566695e-06 1.09658611627412e-05 3.17234618958059e-06 1.141691404828e-05 2.48160176429142e-05 4.66257625725319e-06 3.19396691304664e-06 7.30049559318985e-06 -2.16767467641763e-07 7.42019483061785e-06 4.66257625725319e-06 3.23054352311188e-05 848 848 0 14 0 845 856 0 25 0 0 0 0 0 0 18 31 0 2596 0 0 0 0 0 2181 +871 899 0.996723456167466 -0.00995949253043539 0.0802692994495251 -0.00540238791656978 -0.000113921987784708 0.99221648451155 0.124524836419574 -0.00586668111742979 -0.0808847262921871 -0.124125969772957 0.988964309103499 0.0113278703523481 4.86621581131369e-05 -5.88742652455948e-05 -2.01973172021156e-06 -1.91984879471835e-05 -1.41697430115871e-05 1.74920461432039e-05 -5.88742652455948e-05 0.000153748841504666 9.97272156078005e-06 6.27188545371677e-05 2.81078465075071e-05 -1.8579831620268e-05 -2.01973172021156e-06 9.97272156078005e-06 1.04662519678194e-05 4.94988769473975e-07 3.92861635835574e-06 -3.11382788365465e-06 -1.91984879471835e-05 6.27188545371677e-05 4.94988769473975e-07 7.73531851129577e-05 2.54299762563092e-05 -4.671668296087e-07 -1.41697430115871e-05 2.81078465075071e-05 3.92861635835574e-06 2.54299762563092e-05 2.94478251357837e-05 1.13282353945489e-06 1.74920461432039e-05 -1.8579831620268e-05 -3.11382788365465e-06 -4.671668296087e-07 1.13282353945489e-06 3.32129794925729e-05 873 875 0 11 0 868 876 0 22 0 0 0 0 0 0 17 28 0 2721 0 0 0 0 0 1821 +871 902 0.997154150686719 -0.0103010714886743 0.0746825795914516 -0.00877064944816616 0.0009133894674513 0.992199108989114 0.124659912726138 -0.00890754370742424 -0.0753841196004107 -0.124236935117511 0.989384868726361 0.0117527365473893 3.12418098247848e-05 -2.98999328764458e-05 -7.44565438410113e-07 -4.38540308179314e-06 -2.72367728817064e-06 6.17206743003308e-06 -2.98999328764458e-05 4.53041019669617e-05 2.60192858533879e-06 1.01586348601241e-05 7.21807921437143e-06 -5.33698775466279e-07 -7.44565438410113e-07 2.60192858533879e-06 9.68423572373932e-06 -5.46843060989857e-07 8.45522839429619e-07 -1.49000230566645e-06 -4.38540308179314e-06 1.01586348601241e-05 -5.46843060989857e-07 5.01723954504012e-05 1.08396440316833e-05 3.33767038413323e-06 -2.72367728817064e-06 7.21807921437143e-06 8.45522839429619e-07 1.08396440316833e-05 2.48359295312224e-05 5.14596634408342e-06 6.17206743003308e-06 -5.33698775466279e-07 -1.49000230566645e-06 3.33767038413323e-06 5.14596634408342e-06 3.16875161304809e-05 870 870 0 6 0 870 878 0 18 0 0 0 0 0 0 19 34 0 2702 0 0 0 0 0 1804 +872 921 0.995564160182433 -0.000407951368333427 0.094084199183118 -0.000841722157988535 -0.0120328957864425 0.991226464020252 0.131625629893652 -0.01463947470297 -0.093312444932282 -0.132173865047478 0.986824633366624 0.00702552624337629 1.4718806713499e-05 -1.09284016107763e-05 4.8102307558423e-06 -3.54513774443493e-06 5.2219387891882e-07 2.86378287018603e-06 -1.09284016107763e-05 2.86956175946791e-05 -1.71198294139568e-06 5.08746498401606e-06 1.59352726727556e-06 3.79719237114224e-07 4.8102307558423e-06 -1.71198294139568e-06 8.49229945790557e-06 -3.79092889511483e-07 2.85601393277151e-06 1.02939385537633e-06 -3.54513774443493e-06 5.08746498401606e-06 -3.79092889511483e-07 4.654949128501e-05 1.64179607962763e-05 4.11149120117717e-06 5.2219387891882e-07 1.59352726727556e-06 2.85601393277151e-06 1.64179607962763e-05 2.80387546767272e-05 6.9057036207395e-06 2.86378287018603e-06 3.79719237114224e-07 1.02939385537633e-06 4.11149120117717e-06 6.9057036207395e-06 2.60826117200586e-05 861 862 0 20 0 861 868 0 33 0 0 0 0 0 0 7 16 0 2524 0 0 0 0 0 1960 +872 875 0.999978910023701 0.00019506095156673 -0.00649164532586502 0.0069313595187118 -0.00023787245254975 0.999978226154783 -0.00659474283276501 0.00731729430178824 0.00649021760097219 0.00659614793338971 0.99995718303732 0.00509626781944495 3.51179996510336e-05 -4.23860334038853e-05 -9.50115941888494e-07 -1.7597875565984e-05 -1.45347827225736e-05 1.39964339422985e-05 -4.23860334038853e-05 7.27348632071606e-05 -1.83124447677946e-08 5.57767483979337e-05 3.70930828107852e-05 -7.80162133647233e-06 -9.50115941888494e-07 -1.83124447677946e-08 9.13504573842448e-06 -2.1076377230852e-06 2.03182098175116e-06 -3.28073212580483e-06 -1.7597875565984e-05 5.57767483979337e-05 -2.1076377230852e-06 0.00010452491154188 4.58960966560177e-05 1.34898557949805e-05 -1.45347827225736e-05 3.70930828107852e-05 2.03182098175116e-06 4.58960966560177e-05 4.5070865659722e-05 5.20739096991945e-06 1.39964339422985e-05 -7.80162133647233e-06 -3.28073212580483e-06 1.34898557949805e-05 5.20739096991945e-06 3.19029019613943e-05 808 805 0 6 0 803 813 0 18 0 0 0 0 0 0 6 16 0 2094 0 0 0 0 0 2568 +871 906 0.997091300098548 -0.0102489050560449 0.0755241631065203 -0.0103601622302948 0.000884769026117763 0.992407228234554 0.122992318994237 -0.0090909200071982 -0.0762112619732709 -0.122567749807859 0.989529681341333 0.00833874380311725 4.22302476229728e-05 -5.91722441830943e-05 -2.79397642336918e-06 -1.73731736552118e-05 -1.11770500649695e-05 1.14307289067929e-05 -5.91722441830943e-05 0.000170239647206758 9.67800108452868e-06 7.96051378805509e-05 3.57488228767328e-05 -1.30426907441223e-05 -2.79397642336918e-06 9.67800108452868e-06 9.34506582342641e-06 3.35491279007378e-06 5.09542447116757e-06 -1.05669971047234e-06 -1.73731736552118e-05 7.96051378805509e-05 3.35491279007378e-06 8.34715651138961e-05 2.62955097022344e-05 -1.62904156952885e-06 -1.11770500649695e-05 3.57488228767328e-05 5.09542447116757e-06 2.62955097022344e-05 2.9243649067886e-05 -6.95153615997701e-09 1.14307289067929e-05 -1.30426907441223e-05 -1.05669971047234e-06 -1.62904156952885e-06 -6.95153615997701e-09 2.8224379579135e-05 863 863 0 6 0 861 871 0 20 0 0 0 0 0 0 20 33 0 2708 0 0 0 0 0 2188 +872 927 0.996237544995579 -0.00133200705425262 0.0866543691823407 -0.0173501538826219 -0.00998888298040426 0.991453300905347 0.130079108010068 -0.0221788562488498 -0.0860870266531826 -0.130455271572668 0.987709697209112 0.00985150475206035 3.86304892669052e-05 -3.93394744002368e-05 -4.90568185740732e-06 -8.7807548978798e-06 -7.8393867358967e-06 6.99352660678451e-06 -3.93394744002368e-05 5.92185380898432e-05 6.68784694075996e-06 2.22948353117799e-05 1.31846864896825e-05 3.51882899572174e-07 -4.90568185740732e-06 6.68784694075996e-06 1.03836689194389e-05 -1.00342851582195e-06 3.07636785138827e-06 -2.32321764614518e-06 -8.7807548978798e-06 2.22948353117799e-05 -1.00342851582195e-06 5.72959432949667e-05 1.55468163599044e-05 1.18968321415543e-05 -7.8393867358967e-06 1.31846864896825e-05 3.07636785138827e-06 1.55468163599044e-05 2.61537721770662e-05 7.1238516435791e-06 6.99352660678451e-06 3.51882899572174e-07 -2.32321764614518e-06 1.18968321415543e-05 7.1238516435791e-06 2.75050506672994e-05 882 888 0 14 0 882 892 0 24 0 0 0 0 0 0 4 9 0 2611 0 0 0 0 0 1812 +872 928 0.996564681308726 -0.000557891391490106 0.0828162105220548 -0.0137825011337929 -0.0102362246146297 0.991479998804775 0.129856196139122 -0.0187260805333774 -0.0821830619633806 -0.130257824053984 0.988068238331263 0.00903397874308243 4.63311373244552e-05 -4.48924025322765e-05 -4.11368146174472e-06 -1.38836243637111e-05 -1.19415105946013e-05 6.1088620362174e-06 -4.48924025322765e-05 6.57808658225842e-05 5.73210767037947e-06 3.29152415038303e-05 2.10540151381451e-05 7.96918116080647e-06 -4.11368146174472e-06 5.73210767037947e-06 9.99195623222703e-06 5.5063578219762e-07 4.89058005090082e-06 -2.04016766611209e-06 -1.38836243637111e-05 3.29152415038303e-05 5.5063578219762e-07 6.23090479877629e-05 1.78324381074628e-05 2.41306223710831e-05 -1.19415105946013e-05 2.10540151381451e-05 4.89058005090082e-06 1.78324381074628e-05 2.84205626966964e-05 1.08070057137043e-05 6.1088620362174e-06 7.96918116080647e-06 -2.04016766611209e-06 2.41306223710831e-05 1.08070057137043e-05 4.09436408091843e-05 865 868 0 17 0 865 875 0 30 0 0 0 0 0 0 3 12 0 2546 0 0 0 0 0 2084 +872 925 0.995795615650043 -0.00128188880204706 0.0915939332775424 -0.00801651549357343 -0.0107283732779557 0.991388668615587 0.130512105750469 -0.0159822864626305 -0.0909724895721808 -0.130946036601769 0.987206737030966 0.00820183024253157 3.8649051382029e-05 -4.61466169039439e-05 -8.57107056373286e-10 -1.96388007346749e-05 -1.1412410498375e-05 9.180265423933e-06 -4.61466169039439e-05 8.10792647666654e-05 5.60823550912227e-06 3.93706481058255e-05 2.17478218681349e-05 -8.46680083184458e-07 -8.57107056373286e-10 5.60823550912227e-06 1.06752068690171e-05 3.14740005658728e-06 7.32841064545385e-06 2.77950188056068e-06 -1.96388007346749e-05 3.93706481058255e-05 3.14740005658728e-06 7.03911214455824e-05 2.20793485503456e-05 1.2607461306886e-05 -1.1412410498375e-05 2.17478218681349e-05 7.32841064545385e-06 2.20793485503456e-05 2.97862841160813e-05 5.16147555472233e-06 9.180265423933e-06 -8.46680083184458e-07 2.77950188056068e-06 1.2607461306886e-05 5.16147555472233e-06 3.30216563804578e-05 890 896 0 16 0 890 900 0 28 0 0 0 0 0 0 4 9 0 2496 0 0 0 0 0 2041 +872 922 0.995708040045814 -0.000661726120680825 0.0925476153483409 -0.00247064799242123 -0.0115041350370595 0.991334150869348 0.130859681327739 -0.0133075292170966 -0.0918322049456091 -0.131362717080188 0.98707177180595 0.00794596201656421 4.56562765393012e-05 -4.7649101469604e-05 -2.4928208239359e-06 -2.39308914681241e-05 -1.38098960964634e-05 7.77788242915011e-06 -4.7649101469604e-05 7.27018885463314e-05 5.00497178769452e-06 4.31696989714312e-05 2.20982168362731e-05 3.60571687936925e-06 -2.4928208239359e-06 5.00497178769452e-06 1.0852989710436e-05 -4.14622123979188e-07 4.41699165975079e-06 -1.48007379081357e-07 -2.39308914681241e-05 4.31696989714312e-05 -4.14622123979188e-07 8.3151610219195e-05 3.07313016120189e-05 1.24864740529301e-05 -1.38098960964634e-05 2.20982168362731e-05 4.41699165975079e-06 3.07313016120189e-05 3.36654315201648e-05 7.86905052163764e-06 7.77788242915011e-06 3.60571687936925e-06 -1.48007379081357e-07 1.24864740529301e-05 7.86905052163764e-06 3.42950448979059e-05 907 909 0 17 0 907 916 0 31 0 0 0 0 0 0 6 17 0 2672 0 0 0 0 0 1796 +872 923 0.995320306477786 -0.00104399569736708 0.0966250360204369 -0.000875691312480365 -0.0117909405921879 0.991157490374552 0.132165816285346 -0.011976337544792 -0.0959086087529078 -0.132686620830452 0.986506867396106 0.00818869492034278 4.54997170563086e-05 -5.59199646474361e-05 -9.03798919435348e-08 -2.26030190344278e-05 -1.70488975571184e-05 3.81810308287451e-06 -5.59199646474361e-05 0.000111782451122386 3.27385444841614e-06 6.68242615279171e-05 4.07334893766127e-05 1.65295379993321e-05 -9.03798919435348e-08 3.27385444841614e-06 9.85172250018139e-06 1.37196040298049e-07 5.78588275994037e-06 8.37624261520533e-07 -2.26030190344278e-05 6.68242615279171e-05 1.37196040298049e-07 0.000108397491888063 4.37803559906306e-05 2.77863436919982e-05 -1.70488975571184e-05 4.07334893766127e-05 5.78588275994037e-06 4.37803559906306e-05 4.28028094652075e-05 1.28848422633167e-05 3.81810308287451e-06 1.65295379993321e-05 8.37624261520533e-07 2.77863436919982e-05 1.28848422633167e-05 4.04760115341916e-05 888 893 0 14 0 888 900 0 29 0 0 0 0 0 0 4 13 0 2496 0 0 0 0 0 1704 +871 905 0.996669008891075 -0.0105233978470146 0.080871161818263 -0.00683609089660933 0.000447151103191476 0.992329948493617 0.123616638760911 -0.00888267166302643 -0.0815517429119276 -0.12316871120706 0.989029211807022 0.00842927605220084 1.69289313594423e-05 -1.42276892231143e-05 3.00172581215074e-06 -2.91138165800326e-06 1.45317994337463e-06 3.09098760103217e-06 -1.42276892231143e-05 3.08526323741605e-05 -3.26280411845196e-07 5.21044947956359e-06 3.06515617038306e-06 2.0971205731692e-06 3.00172581215074e-06 -3.26280411845196e-07 8.02009599325106e-06 -1.53363216291786e-07 2.13290896949087e-06 -8.75990933665438e-09 -2.91138165800326e-06 5.21044947956359e-06 -1.53363216291786e-07 5.34301602013352e-05 1.27575160997744e-05 -1.71915733794359e-06 1.45317994337463e-06 3.06515617038306e-06 2.13290896949087e-06 1.27575160997744e-05 2.26736195230594e-05 3.8928910803637e-06 3.09098760103217e-06 2.0971205731692e-06 -8.75990933665438e-09 -1.71915733794359e-06 3.8928910803637e-06 2.10205438114898e-05 871 873 0 7 0 872 883 0 20 0 0 0 0 0 0 15 28 0 2697 0 0 0 0 0 2199 +872 929 0.994964577947879 -0.0246450417378135 0.097149938480375 -0.0158776998068825 0.00979720319696705 0.988570207816729 0.150442543938561 -0.0194611290266407 -0.0997471976474354 -0.148733204547371 0.983833792073922 0.00110813500608198 4.37686762179376e-05 -5.62519009782211e-05 -9.77781553243317e-06 -1.52667763212819e-05 -1.23853788728806e-05 1.08429103053185e-05 -5.62519009782211e-05 0.000119101640056084 1.54554106409067e-05 6.24263005964003e-05 3.02825864152353e-05 4.27224599732365e-06 -9.77781553243317e-06 1.54554106409067e-05 1.17181455553739e-05 1.86066816357853e-06 7.00999476751121e-06 -5.14309168118917e-06 -1.52667763212819e-05 6.24263005964003e-05 1.86066816357853e-06 8.84764259890288e-05 1.96054117563083e-05 1.80197270994875e-05 -1.23853788728806e-05 3.02825864152353e-05 7.00999476751121e-06 1.96054117563083e-05 2.73630849724824e-05 6.41520736049998e-07 1.08429103053185e-05 4.27224599732365e-06 -5.14309168118917e-06 1.80197270994875e-05 6.41520736049998e-07 3.19648051896608e-05 876 876 0 0 0 882 887 0 12 0 0 0 0 0 0 22 32 0 2583 0 0 0 0 0 1465 +872 874 0.999934836225896 -0.00756851400415008 -0.00854639676466766 0.00733917441272673 0.00752840710412667 0.999960543721582 -0.00471530343806967 0.00815529975754147 0.00858174739576229 0.00465065541698379 0.999952361373195 0.000436408656204849 3.44773159376203e-05 -4.14229616290973e-05 -1.02278227604118e-06 -9.15863354314364e-06 -1.16075768194001e-05 1.87874307627835e-05 -4.14229616290973e-05 7.66948134120734e-05 1.88827072795136e-08 4.91873211325604e-05 3.22028176949263e-05 -1.76234826787786e-05 -1.02278227604118e-06 1.88827072795136e-08 8.55399885514686e-06 -1.38276457625152e-06 1.02852571832461e-06 -2.25775664322442e-06 -9.15863354314364e-06 4.91873211325604e-05 -1.38276457625152e-06 9.15956571430573e-05 3.46686627777135e-05 4.50927899903954e-06 -1.16075768194001e-05 3.22028176949263e-05 1.02852571832461e-06 3.46686627777135e-05 3.61417013600402e-05 -3.04420374957898e-06 1.87874307627835e-05 -1.76234826787786e-05 -2.25775664322442e-06 4.50927899903954e-06 -3.04420374957898e-06 3.26918885093615e-05 764 762 0 9 0 764 770 0 17 0 0 0 0 0 0 11 22 0 2064 0 0 0 0 0 2684 +872 876 0.999994888551211 -0.000714330493461629 0.0031165049971826 0.0185203174238569 0.000725100068240082 0.999993765481585 -0.00345589754643093 0.0143485835870922 -0.00311401691427511 0.00345813965977373 0.999989172025753 0.00744055876221216 4.03534311894774e-05 -4.3379875157915e-05 -1.95015053999887e-07 -1.88221805350514e-05 -1.32433333929777e-05 1.90765684714633e-05 -4.3379875157915e-05 6.06197448232721e-05 3.12563338682805e-07 4.00703116684219e-05 2.40923052334405e-05 -1.24516965799509e-05 -1.95015053999887e-07 3.12563338682805e-07 9.46825796130063e-06 -2.13293261211451e-06 3.2916095191428e-06 -2.48937565471936e-06 -1.88221805350514e-05 4.00703116684219e-05 -2.13293261211451e-06 8.75815615817821e-05 3.10420072594051e-05 8.19819848572398e-06 -1.32433333929777e-05 2.40923052334405e-05 3.2916095191428e-06 3.10420072594051e-05 3.42943382564451e-05 9.9928293888613e-07 1.90765684714633e-05 -1.24516965799509e-05 -2.48937565471936e-06 8.19819848572398e-06 9.9928293888613e-07 4.02884653563307e-05 773 772 0 9 0 771 781 0 18 0 0 0 0 0 0 4 13 0 2114 0 0 0 0 0 1573 +872 920 0.995719383001125 -0.000825691957145431 0.0924241772949584 -0.00117981124763696 -0.0110420210745077 0.991735962655167 0.127819615658239 -0.0161235798104056 -0.0917659200708418 -0.128293018552147 0.987481603527038 0.00724514242641872 5.32166653773971e-05 -6.79381490361682e-05 -9.68091505475826e-06 -1.1423000549753e-05 -1.58322512288237e-05 7.96854655021346e-06 -6.79381490361682e-05 0.000131881293861451 1.48847043723323e-05 4.48252887066387e-05 3.17214873793197e-05 8.1457583939265e-06 -9.68091505475826e-06 1.48847043723323e-05 1.31148088731223e-05 -2.24550657677275e-06 6.20548776526949e-06 -3.83467726831611e-06 -1.1423000549753e-05 4.48252887066387e-05 -2.24550657677275e-06 8.13891220586803e-05 2.08428267701062e-05 2.06185287645857e-05 -1.58322512288237e-05 3.17214873793197e-05 6.20548776526949e-06 2.08428267701062e-05 3.05997684570697e-05 4.51280426069968e-06 7.96854655021346e-06 8.1457583939265e-06 -3.83467726831611e-06 2.06185287645857e-05 4.51280426069968e-06 3.92688703171494e-05 860 864 0 17 0 860 868 0 27 0 0 0 0 0 0 7 13 0 2383 0 0 0 0 0 1647 +872 926 0.996209106911225 -0.00110033254215872 0.0869839328579473 -0.0149573211128294 -0.0103055784785323 0.991385722839378 0.13056853986496 -0.0205611145198823 -0.0863782979651836 -0.130969988236014 0.98761614599099 0.010115887945616 4.16932927743881e-05 -4.48768108635256e-05 -2.19629837422112e-06 -2.30304324841539e-05 -1.38461278477785e-05 9.25795491964271e-06 -4.48768108635256e-05 6.76844747404807e-05 3.81064195083921e-06 4.40666212228471e-05 2.38841653951556e-05 -9.03348959609698e-08 -2.19629837422112e-06 3.81064195083921e-06 9.7546868053103e-06 -9.79445957307763e-07 3.7636745563975e-06 3.21250214137401e-07 -2.30304324841539e-05 4.40666212228471e-05 -9.79445957307763e-07 8.22393417137236e-05 3.0996414288104e-05 1.20576868018416e-05 -1.38461278477785e-05 2.38841653951556e-05 3.7636745563975e-06 3.0996414288104e-05 3.47872789463701e-05 8.32073447974629e-06 9.25795491964271e-06 -9.03348959609698e-08 3.21250214137401e-07 1.20576868018416e-05 8.32073447974629e-06 3.29638929645793e-05 892 897 0 17 0 892 901 0 27 0 0 0 0 0 0 6 11 0 2558 0 0 0 0 0 1805 +872 913 0.99531775800749 -0.000989377318920364 0.0966518583756332 -0.000587302094486312 -0.0119379215963143 0.991033258314892 0.133081054029977 -0.0121541011970232 -0.0959168735046285 -0.133611758637816 0.986381189667974 0.0060103209324369 2.06591972465053e-05 -2.69139294035413e-05 1.76609449404758e-06 -1.08711139814889e-05 -4.07619282267731e-06 4.52363688110355e-06 -2.69139294035413e-05 8.49202242765147e-05 3.25076364611892e-06 4.75167224887247e-05 2.08613351970279e-05 6.31435959360538e-06 1.76609449404758e-06 3.25076364611892e-06 8.96004139674363e-06 1.13121104236402e-06 5.29078418539385e-06 -4.05524245032282e-08 -1.08711139814889e-05 4.75167224887247e-05 1.13121104236402e-06 8.96888108569579e-05 3.0263849273407e-05 1.75767216217533e-05 -4.07619282267731e-06 2.08613351970279e-05 5.29078418539385e-06 3.0263849273407e-05 3.0844130303127e-05 7.84608357864642e-06 4.52363688110355e-06 6.31435959360538e-06 -4.05524245032282e-08 1.75767216217533e-05 7.84608357864642e-06 3.45118046927668e-05 885 890 0 17 0 885 896 0 28 0 0 0 0 0 0 7 15 0 2502 0 0 0 0 0 1838 +872 919 0.995937616233211 -0.00045710072119584 0.090044742381993 -0.00382289769678314 -0.0113344620711945 0.99139704006909 0.130397235061958 -0.0151774930451093 -0.0893296957414804 -0.130888120168247 0.987364423836284 0.00759383776288482 4.20694658397315e-05 -4.63765192053044e-05 -3.45938301438874e-06 -1.43754420146746e-05 -1.23078554154195e-05 9.08568517135617e-08 -4.63765192053044e-05 7.45826167102086e-05 5.44628373373803e-06 3.3827720078998e-05 2.07135102909933e-05 1.7509361280654e-05 -3.45938301438874e-06 5.44628373373803e-06 1.00037950743329e-05 -4.4960006177961e-07 1.7857276632479e-06 -5.40764318437489e-07 -1.43754420146746e-05 3.3827720078998e-05 -4.4960006177961e-07 7.37849273182974e-05 2.20841216197303e-05 1.96234602141152e-05 -1.23078554154195e-05 2.07135102909933e-05 1.7857276632479e-06 2.20841216197303e-05 3.24192491095983e-05 1.14461546306095e-05 9.08568517135617e-08 1.7509361280654e-05 -5.40764318437489e-07 1.96234602141152e-05 1.14461546306095e-05 4.59180695889267e-05 892 898 0 16 0 892 902 0 28 0 0 0 0 0 0 4 11 0 2393 0 0 0 0 0 2076 +872 918 0.99616579932149 -0.000331033740750137 0.0874848025592975 -0.00485730272723613 -0.0109255206697649 0.991693527478388 0.128158419760725 -0.0197391428673344 -0.0868005372118821 -0.128622851679374 0.987887558766479 0.00664951510942743 4.49325905657929e-05 -5.30866770762653e-05 -5.97142525490067e-06 -1.35710221640399e-05 -1.10872180228833e-05 9.30381725015337e-07 -5.30866770762653e-05 0.000101394450260493 8.48901876440363e-06 4.70244746572588e-05 2.47001493665087e-05 2.54847374852857e-05 -5.97142525490067e-06 8.48901876440363e-06 1.06641119158615e-05 -1.5237561205393e-07 3.31486238635139e-06 -1.41242834597376e-06 -1.35710221640399e-05 4.70244746572588e-05 -1.5237561205393e-07 9.21315905080471e-05 2.78361334754571e-05 2.61738089000887e-05 -1.10872180228833e-05 2.47001493665087e-05 3.31486238635139e-06 2.78361334754571e-05 3.6863630101842e-05 1.09538905994866e-05 9.30381725015337e-07 2.54847374852857e-05 -1.41242834597376e-06 2.61738089000887e-05 1.09538905994866e-05 5.0053410147132e-05 882 887 0 18 0 882 892 0 31 0 0 0 0 0 0 7 14 0 2346 0 0 0 0 0 1624 +872 914 0.995440569313465 -0.000821027325725038 0.095380285588874 -0.000131838027894054 -0.0118474200567303 0.991155202394832 0.132177923283956 -0.0129010412895324 -0.094645187954191 -0.132705277512955 0.986626371894308 0.0058249593285942 3.23851974886884e-05 -4.6728295245183e-05 5.28099638319966e-07 -1.6639436161218e-05 -7.62108241199235e-06 2.62781573581922e-06 -4.6728295245183e-05 0.000122324661437028 6.40555697511228e-06 4.75290652195123e-05 2.51375637957581e-05 1.4958674726342e-05 5.28099638319966e-07 6.40555697511228e-06 9.68380195424369e-06 -3.78288677478415e-07 3.554670409713e-06 1.86935379567015e-07 -1.6639436161218e-05 4.75290652195123e-05 -3.78288677478415e-07 7.69471405234584e-05 2.52143567007184e-05 1.18249146067346e-05 -7.62108241199235e-06 2.51375637957581e-05 3.554670409713e-06 2.52143567007184e-05 2.90853988490517e-05 5.90292170692651e-06 2.62781573581922e-06 1.4958674726342e-05 1.86935379567015e-07 1.18249146067346e-05 5.90292170692651e-06 3.21659866505246e-05 895 900 0 14 0 895 906 0 26 0 0 0 0 0 0 7 15 0 2644 0 0 0 0 0 1728 +872 924 0.996102604407001 -0.000337590906044854 0.0882014031972779 -0.00598501040413889 -0.0112092371651461 0.991399926923111 0.130386110836335 -0.0163469406104242 -0.0874868818495901 -0.130866615029311 0.987532265080491 0.00660364715773923 3.57011533753678e-05 -3.85059629864892e-05 -2.82592537715902e-06 -1.38004470495026e-05 -8.35960692350147e-06 6.1057853843919e-06 -3.85059629864892e-05 6.11226555803686e-05 4.49301510424207e-06 3.29885126798136e-05 1.61948303814732e-05 5.72620470608954e-06 -2.82592537715902e-06 4.49301510424207e-06 1.04446923144991e-05 -2.48813587819905e-06 3.29712113495538e-06 -9.86850998597126e-07 -1.38004470495026e-05 3.29885126798136e-05 -2.48813587819905e-06 7.26806214649635e-05 2.56516055177781e-05 1.84302601827761e-05 -8.35960692350147e-06 1.61948303814732e-05 3.29712113495538e-06 2.56516055177781e-05 2.7911969104422e-05 9.19957382109248e-06 6.1057853843919e-06 5.72620470608954e-06 -9.86850998597126e-07 1.84302601827761e-05 9.19957382109248e-06 3.64449619913672e-05 870 871 0 18 0 870 876 0 28 0 0 0 0 0 0 7 14 0 2595 0 0 0 0 0 1807 +872 917 0.996430153842868 0.000518335721320172 0.0844196650121234 -0.00239153761079415 -0.0116282484118473 0.991292336433366 0.131165115664763 -0.0142673540526904 -0.0836165794059497 -0.131678529216264 0.987759602632083 0.00667561999403062 4.04971247097466e-05 -3.61596790823295e-05 7.79658793073269e-08 -1.8974711154919e-05 -1.62147337732603e-05 5.7468402083261e-06 -3.61596790823295e-05 6.79961383741393e-05 4.77090765879067e-06 2.40678010628328e-05 1.27303478807299e-05 7.04714590177411e-06 7.79658793073269e-08 4.77090765879067e-06 1.07151723284771e-05 -5.37542197473798e-06 -5.31793760612194e-07 1.14935917962749e-06 -1.8974711154919e-05 2.40678010628328e-05 -5.37542197473798e-06 9.25480972312364e-05 3.94118684022342e-05 3.21718094413581e-06 -1.62147337732603e-05 1.27303478807299e-05 -5.31793760612194e-07 3.94118684022342e-05 5.21856381097269e-05 8.72226210088283e-07 5.7468402083261e-06 7.04714590177411e-06 1.14935917962749e-06 3.21718094413581e-06 8.72226210088283e-07 3.48328716913801e-05 867 869 0 17 0 867 877 0 33 0 0 0 0 0 0 9 20 0 2277 0 0 0 0 0 1797 +872 910 0.996700041432579 -0.000253961279492381 0.0811724270424669 -0.00954154651169258 -0.0102594245212529 0.991581662818229 0.129075753614417 -0.0182161334028747 -0.0805218704253 -0.12948259136388 0.988306878918135 0.00522054296835441 5.06656286752376e-05 -6.49332997819963e-05 -2.91040720560637e-06 -2.41434049185805e-05 -1.57185310410574e-05 4.10432468871076e-06 -6.49332997819963e-05 0.00015606903664641 9.09387820857932e-06 8.83511908108395e-05 4.62972390822276e-05 1.94547469256784e-05 -2.91040720560637e-06 9.09387820857932e-06 1.05617480796326e-05 3.64009623751134e-06 6.35005583167648e-06 -2.4250179591225e-07 -2.41434049185805e-05 8.83511908108395e-05 3.64009623751134e-06 0.00012285908188049 4.8734136073652e-05 2.65441606635486e-05 -1.57185310410574e-05 4.62972390822276e-05 6.35005583167648e-06 4.8734136073652e-05 4.20444607360488e-05 1.36948680807256e-05 4.10432468871076e-06 1.94547469256784e-05 -2.4250179591225e-07 2.65441606635486e-05 1.36948680807256e-05 4.32220100329128e-05 902 907 0 17 0 902 912 0 27 0 0 0 0 0 0 6 11 0 2606 0 0 0 0 0 1547 +872 905 0.995965941082162 -0.000912613695722434 0.0897274280282531 -0.00519560261454877 -0.0108365263302457 0.991406457124655 0.130367965653502 -0.0158443443104974 -0.0890753271193367 -0.130814387235431 0.987397175502747 0.00562403807746941 2.30381506085187e-05 -2.06939199697449e-05 3.02620542446748e-06 -6.71306223511762e-06 -2.01810250013718e-06 1.46182557639034e-06 -2.06939199697449e-05 3.97559580054365e-05 2.43833499076441e-07 9.65965061891553e-06 7.43703541468144e-06 6.17162403188647e-06 3.02620542446748e-06 2.43833499076441e-07 9.1658929622555e-06 -5.46447560205831e-07 3.0590242049964e-06 1.62746824768475e-06 -6.71306223511762e-06 9.65965061891553e-06 -5.46447560205831e-07 5.7069835196485e-05 1.42444935739628e-05 2.85067508677321e-06 -2.01810250013718e-06 7.43703541468144e-06 3.0590242049964e-06 1.42444935739628e-05 2.48173483441047e-05 5.42402239177755e-06 1.46182557639034e-06 6.17162403188647e-06 1.62746824768475e-06 2.85067508677321e-06 5.42402239177755e-06 2.73665143629993e-05 888 893 0 14 0 888 899 0 26 0 0 0 0 0 0 4 13 0 2659 0 0 0 0 0 1693 +872 916 0.995682576304762 -0.00103686931326611 0.092817736156076 -0.00558508663759898 -0.0111584874770738 0.991349316337383 0.130774696155744 -0.0174249453007978 -0.0921503955517052 -0.131245791930372 0.987057671415523 0.00914325399041795 3.3867223607915e-05 -3.25367686007125e-05 -6.43671059190118e-07 -1.32763237393196e-05 -1.0003307298988e-05 5.72777562180092e-06 -3.25367686007125e-05 5.16460262693941e-05 3.35082864091718e-06 2.25706489758013e-05 1.30513511652589e-05 4.41403393433095e-06 -6.43671059190118e-07 3.35082864091718e-06 9.63192089045133e-06 1.11705160945012e-06 5.83230204280035e-07 -2.67357869059054e-07 -1.32763237393196e-05 2.25706489758013e-05 1.11705160945012e-06 6.95462803140718e-05 1.91428061767767e-05 9.49698176771284e-06 -1.0003307298988e-05 1.30513511652589e-05 5.83230204280035e-07 1.91428061767767e-05 3.70175661471297e-05 8.18210327831485e-06 5.72777562180092e-06 4.41403393433095e-06 -2.67357869059054e-07 9.49698176771284e-06 8.18210327831485e-06 3.38851881179626e-05 896 899 0 12 0 896 904 0 22 0 0 0 0 0 0 10 17 0 2503 0 0 0 0 0 1822 +872 911 0.996165251000767 -0.000307631192231045 0.087491131331288 -0.00640429955283796 -0.0111134512782749 0.991448730131284 0.130022716175869 -0.0157485566254945 -0.0867829700993491 -0.130496440120468 0.987643354261355 0.00561627656147448 5.47767605460477e-05 -5.66885702673488e-05 -4.16911590402318e-06 -2.45879799940712e-05 -1.61468442014311e-05 8.92239477163142e-06 -5.66885702673488e-05 7.39008909032305e-05 5.8295330051218e-06 3.74681455969939e-05 2.49651894864804e-05 6.37535871938157e-07 -4.16911590402318e-06 5.8295330051218e-06 1.01131128800716e-05 2.67310810691239e-07 3.84613834272608e-06 -2.88430770879151e-06 -2.45879799940712e-05 3.74681455969939e-05 2.67310810691239e-07 6.91399243970491e-05 2.76170085587072e-05 1.60274946479699e-05 -1.61468442014311e-05 2.49651894864804e-05 3.84613834272608e-06 2.76170085587072e-05 3.28067340016461e-05 1.07581424390201e-05 8.92239477163142e-06 6.37535871938157e-07 -2.88430770879151e-06 1.60274946479699e-05 1.07581424390201e-05 4.02892756021381e-05 896 902 0 21 0 896 908 0 33 0 0 0 0 0 0 7 17 0 2690 0 0 0 0 0 1655 +872 912 0.99581218007609 -0.000890347583455506 0.091418320337263 -0.00382356185688198 -0.0113607319008528 0.990996744872804 0.133403093750421 -0.0140406076016644 -0.0907140329981131 -0.13388300464468 0.986836513959901 0.00804362312875231 6.54025456429176e-05 -7.87828453046742e-05 -9.00758464400521e-06 -3.01888074796623e-05 -2.22451928288476e-05 -4.41183796994162e-07 -7.87828453046742e-05 0.000134402075037216 1.25592114865408e-05 7.15052157480972e-05 4.04123956058353e-05 2.23148356905727e-05 -9.00758464400521e-06 1.25592114865408e-05 1.03622322855681e-05 2.20615434685906e-06 5.83012102518941e-06 -2.678392817529e-06 -3.01888074796623e-05 7.15052157480972e-05 2.20615434685906e-06 0.000103447677191179 3.79405686512099e-05 3.35238656389643e-05 -2.22451928288476e-05 4.04123956058353e-05 5.83012102518941e-06 3.79405686512099e-05 3.94344788866129e-05 1.72189945068037e-05 -4.41183796994162e-07 2.23148356905727e-05 -2.678392817529e-06 3.35238656389643e-05 1.72189945068037e-05 5.25309387147124e-05 891 896 0 16 0 891 900 0 27 0 0 0 0 0 0 9 14 0 2528 0 0 0 0 0 1996 +872 904 0.996464382052841 -0.000221059481817808 0.0840159891494141 -0.00773830205405375 -0.0108756397793211 0.991243544332892 0.131597706202487 -0.0158439448880245 -0.0833093977858406 -0.132046154624325 0.98773648170425 0.00660689205135929 4.39817354133223e-05 -4.62696337221954e-05 -2.14978756239929e-06 -1.54478456869575e-05 -1.04161254681091e-05 4.41585024332657e-06 -4.62696337221954e-05 8.12517761629305e-05 5.77195658219654e-06 3.77997512879234e-05 2.16410741290593e-05 9.40843176917184e-06 -2.14978756239929e-06 5.77195658219654e-06 9.97438630389444e-06 9.79035465209614e-07 4.62983955722143e-06 1.89174820701077e-07 -1.54478456869575e-05 3.77997512879234e-05 9.79035465209614e-07 8.26762524511368e-05 2.69459754049756e-05 1.71800910388442e-05 -1.04161254681091e-05 2.16410741290593e-05 4.62983955722143e-06 2.69459754049756e-05 3.209089412011e-05 1.08629896670849e-05 4.41585024332657e-06 9.40843176917184e-06 1.89174820701077e-07 1.71800910388442e-05 1.08629896670849e-05 3.9383614915402e-05 846 853 0 21 0 846 860 0 35 0 0 0 0 0 0 7 16 0 2574 0 0 0 0 0 1798 +873 921 0.995654259172413 0.0107976724831432 0.0924986835624129 -0.00346912178470486 -0.0236301531599082 0.990040730400513 0.138783889589742 -0.0230315970859742 -0.0900789212494905 -0.14036652883421 0.985993420631985 0.00768636568429673 5.23752605928403e-05 -6.72490408782357e-05 5.86507461402426e-08 -3.71870940649068e-05 -2.39664715829038e-05 -1.33295346816885e-05 -6.72490408782357e-05 0.000130758370930781 5.41329191405177e-06 8.13821530637888e-05 4.78175164293361e-05 4.42625062980702e-05 5.86507461402426e-08 5.41329191405177e-06 9.38160368239709e-06 4.9664213194092e-06 5.99622340468562e-06 4.63260611265878e-06 -3.71870940649068e-05 8.13821530637888e-05 4.9664213194092e-06 0.000102840240351367 4.55523150792748e-05 4.19653937973187e-05 -2.39664715829038e-05 4.78175164293361e-05 5.99622340468562e-06 4.55523150792748e-05 4.87076717308672e-05 2.55710211561036e-05 -1.33295346816885e-05 4.42625062980702e-05 4.63260611265878e-06 4.19653937973187e-05 2.55710211561036e-05 5.37445538539905e-05 846 850 0 35 0 845 850 0 37 0 0 0 0 0 0 0 5 0 2432 0 0 0 0 0 2166 +872 903 0.995434837314705 -0.00078348075213253 0.0954404045368564 0.00039093818141807 -0.0119628176311291 0.991056341919727 0.13290680244071 -0.0131034932544439 -0.0946909481131756 -0.133441797419701 0.986522635851214 0.00678008744421666 3.713613428874e-05 -4.162769864404e-05 -2.33472874317833e-06 -1.84584320498129e-05 -1.07115006779687e-05 4.68084115965134e-06 -4.162769864404e-05 9.05751130524783e-05 7.17376494213246e-06 5.35756774034747e-05 2.68076492464708e-05 1.54826532773062e-05 -2.33472874317833e-06 7.17376494213246e-06 1.0589981235976e-05 -7.98301343509941e-08 4.89660219901279e-06 -5.30300936201184e-07 -1.84584320498129e-05 5.35756774034747e-05 -7.98301343509941e-08 0.000105619891327713 4.0487582311393e-05 2.18253991008345e-05 -1.07115006779687e-05 2.68076492464708e-05 4.89660219901279e-06 4.0487582311393e-05 3.57924634879445e-05 1.25156993623463e-05 4.68084115965134e-06 1.54826532773062e-05 -5.30300936201184e-07 2.18253991008345e-05 1.25156993623463e-05 3.84865018144222e-05 878 883 0 16 0 878 888 0 28 0 0 0 0 0 0 7 14 0 2564 0 0 0 0 0 1831 +872 908 0.995645814965985 -0.000976488898940674 0.0932118962909193 -0.00155126900966041 -0.0114052492871536 0.99115625830894 0.132208894949314 -0.0142856002174014 -0.0925166548758478 -0.132696337871289 0.986829443463323 0.00532327745219431 3.77965090541219e-05 -4.21237993804479e-05 2.47400540393154e-06 -2.48806229442913e-05 -1.57239544949126e-05 7.72672689250511e-06 -4.21237993804479e-05 8.77202238437616e-05 3.17527791955597e-06 5.82643587601188e-05 3.3109456744267e-05 8.13341930677487e-06 2.47400540393154e-06 3.17527791955597e-06 1.01563603317629e-05 8.65676175908392e-07 4.56164036698556e-06 5.93443528885439e-07 -2.48806229442913e-05 5.82643587601188e-05 8.65676175908392e-07 0.000121816408603266 4.74306488920603e-05 1.58404209470997e-05 -1.57239544949126e-05 3.3109456744267e-05 4.56164036698556e-06 4.74306488920603e-05 4.27187954479356e-05 7.70032012545328e-06 7.72672689250511e-06 8.13341930677487e-06 5.93443528885439e-07 1.58404209470997e-05 7.70032012545328e-06 4.14832596077519e-05 894 897 0 20 0 894 902 0 30 0 0 0 0 0 0 7 16 0 2593 0 0 0 0 0 1774 +873 875 0.999774205499575 0.012168042139449 -0.0174205846109155 0.00364335353065691 -0.0121725062542496 0.99992590101438 -0.000150240044745585 -0.00261393932787676 0.0174174656360714 0.00036225829649879 0.999848238814143 0.00824885356956844 3.0026042262196e-05 -3.38078436079828e-05 2.98121189163904e-06 -1.50586520255649e-05 -9.06154625888741e-06 1.5717709666564e-05 -3.38078436079828e-05 5.42882291665617e-05 -2.38760492035695e-06 3.68194202968996e-05 2.37411129743766e-05 -1.39474950361869e-05 2.98121189163904e-06 -2.38760492035695e-06 8.17852826212215e-06 6.05239257249851e-07 1.64975582950444e-06 -2.07496178328293e-06 -1.50586520255649e-05 3.68194202968996e-05 6.05239257249851e-07 8.23173477923505e-05 4.09406882871374e-05 1.13391101725937e-05 -9.06154625888741e-06 2.37411129743766e-05 1.64975582950444e-06 4.09406882871374e-05 3.8963944547266e-05 3.75835456054538e-06 1.5717709666564e-05 -1.39474950361869e-05 -2.07496178328293e-06 1.13391101725937e-05 3.75835456054538e-06 3.75761515665191e-05 749 753 0 24 0 748 755 0 27 0 0 0 0 0 0 1 8 0 2075 0 0 0 0 0 2136 +873 918 0.99567497374246 0.0105797345920758 0.0923006818984216 -0.00377024238125421 -0.0233967537448799 0.990028842670131 0.138908180448247 -0.0249610471206201 -0.0899107255957476 -0.140466935245283 0.985994473374797 0.00627884532484233 2.49584059657954e-05 -2.64250792972151e-05 1.03861299916707e-06 -3.81642002441746e-06 -2.95801842705427e-06 7.27972263751277e-06 -2.64250792972151e-05 6.78771860453399e-05 4.13405629348727e-06 1.92984950242505e-05 8.44918535699507e-06 6.86939967635725e-06 1.03861299916707e-06 4.13405629348727e-06 8.89562072865853e-06 1.01833731352829e-06 3.16163056480687e-06 2.57257966835937e-07 -3.81642002441746e-06 1.92984950242505e-05 1.01833731352829e-06 4.93367536361151e-05 7.7483556470652e-06 1.04620895326191e-05 -2.95801842705427e-06 8.44918535699507e-06 3.16163056480687e-06 7.7483556470652e-06 2.74950014794928e-05 2.74140830423554e-06 7.27972263751277e-06 6.86939967635725e-06 2.57257966835937e-07 1.04620895326191e-05 2.74140830423554e-06 3.40526019629622e-05 841 848 0 32 0 840 850 0 35 0 0 0 0 0 0 0 4 0 2269 0 0 0 0 0 1902 +873 877 0.99983760862971 0.00914709002746729 -0.0155269801845505 0.00323440098681811 -0.00922739299351819 0.999944379748273 -0.00510809439863292 -0.00106707300641307 0.015479392370671 0.00525053843634938 0.999866401204663 0.00739593714373054 2.50624205948016e-05 -2.91783747740021e-05 9.86021652948556e-07 -2.87717132792119e-06 -5.91355841334512e-06 1.74762429471436e-05 -2.91783747740021e-05 5.88721505133781e-05 -1.19699580510848e-06 2.43957220579327e-05 1.84661699280325e-05 -1.92177815539265e-05 9.86021652948556e-07 -1.19699580510848e-06 7.93811933708009e-06 2.19065458565592e-06 -4.49472735639306e-07 -1.91907667586422e-06 -2.87717132792119e-06 2.43957220579327e-05 2.19065458565592e-06 5.63324803080427e-05 1.60062061268521e-05 2.41164718234044e-06 -5.91355841334512e-06 1.84661699280325e-05 -4.49472735639306e-07 1.60062061268521e-05 2.67026284049999e-05 -7.10251184617619e-06 1.74762429471436e-05 -1.92177815539265e-05 -1.91907667586422e-06 2.41164718234044e-06 -7.10251184617619e-06 3.50978946724276e-05 696 703 0 17 0 695 707 0 21 0 0 0 0 0 0 4 11 0 2044 0 0 0 0 0 2858 +873 928 0.99473266758559 0.00969831379171109 0.102043435593151 -0.00157307523301936 -0.0242668805206895 0.989495257203459 0.142514050120175 -0.0211892858755551 -0.0995893495703768 -0.144239657103928 0.984518604583321 0.0137221637363539 4.51226990321828e-05 -5.5598738590391e-05 -3.98035526152824e-06 -1.9078236048049e-05 -9.88765143140662e-06 -7.9791021575807e-06 -5.5598738590391e-05 9.09598293583476e-05 7.28354297400048e-06 4.19896691408315e-05 2.11498431570602e-05 2.85954554669447e-05 -3.98035526152824e-06 7.28354297400048e-06 1.03558459215304e-05 1.62600975783399e-06 4.29063479379606e-06 9.37237518102432e-07 -1.9078236048049e-05 4.19896691408315e-05 1.62600975783399e-06 6.51990907124276e-05 1.92536815096955e-05 3.16668277838849e-05 -9.88765143140662e-06 2.11498431570602e-05 4.29063479379606e-06 1.92536815096955e-05 2.93800880991147e-05 1.81924036549529e-05 -7.9791021575807e-06 2.85954554669447e-05 9.37237518102432e-07 3.16668277838849e-05 1.81924036549529e-05 5.10719156022831e-05 833 839 0 32 0 833 841 0 40 0 0 0 0 0 0 0 3 0 2497 0 0 0 0 0 1708 +873 925 0.996312136966854 0.0108267714669091 0.0851170179937281 -0.0124541499957856 -0.022415685507816 0.990399845696629 0.136402649121298 -0.0252051568096779 -0.0828230811776283 -0.137807571140691 0.986990076221918 0.00537023108680296 4.81289642295239e-05 -6.06310097984744e-05 3.43068241997736e-06 -4.8071188111288e-05 -2.69157235085432e-05 -1.18772441934191e-05 -6.06310097984744e-05 0.000116593677725163 -9.05234556017475e-07 9.87437270327029e-05 5.07845163395943e-05 4.29853109404292e-05 3.43068241997736e-06 -9.05234556017475e-07 8.74844050135904e-06 2.49351790684864e-06 2.69920738188711e-06 3.53200422583013e-06 -4.8071188111288e-05 9.87437270327029e-05 2.49351790684864e-06 0.000139926271256204 5.97451383020131e-05 5.13018884621298e-05 -2.69157235085432e-05 5.07845163395943e-05 2.69920738188711e-06 5.97451383020131e-05 5.0487125023274e-05 2.89380378817684e-05 -1.18772441934191e-05 4.29853109404292e-05 3.53200422583013e-06 5.13018884621298e-05 2.89380378817684e-05 5.70653166415011e-05 829 842 0 32 0 829 843 0 36 0 0 0 0 0 0 0 5 0 2515 0 0 0 0 0 2186 +873 923 0.996208835665621 0.0106943020079356 0.0863341626837895 -0.00910001687945527 -0.0224197523359813 0.990453372660196 0.136012761501396 -0.024625858470416 -0.0840554010575241 -0.137432705316477 0.986938164761326 0.00414439103998342 6.37261605725573e-05 -7.37313560348119e-05 -2.08621377544374e-08 -4.36921864581791e-05 -2.64805201494088e-05 -3.14286324489446e-05 -7.37313560348119e-05 0.000116495057064069 3.7855359504377e-06 6.34282507634268e-05 3.7304964879717e-05 5.48609476513352e-05 -2.08621377544374e-08 3.7855359504377e-06 9.75625501839001e-06 9.77464345301393e-07 4.84563511968339e-06 4.12888096705921e-06 -4.36921864581791e-05 6.34282507634268e-05 9.77464345301393e-07 8.84345494985766e-05 3.69482897446458e-05 3.89385684593803e-05 -2.64805201494088e-05 3.7304964879717e-05 4.84563511968339e-06 3.69482897446458e-05 3.93947642171507e-05 2.81903215774829e-05 -3.14286324489446e-05 5.48609476513352e-05 4.12888096705921e-06 3.89385684593803e-05 2.81903215774829e-05 7.50554199907089e-05 860 870 0 31 0 859 871 0 37 0 0 0 0 0 0 0 3 0 2497 0 0 0 0 0 1584 +873 926 0.995476819639645 0.00990085519792162 0.0944874310503112 -0.0104133602608311 -0.0228911116089272 0.990250106650987 0.137407144235724 -0.0262847829873579 -0.0922057404365106 -0.138948549269358 0.985997668398103 0.00721814917364642 3.10967071100442e-05 -3.48358163737625e-05 1.18076910664064e-06 -1.90767278483905e-05 -1.07169446204701e-05 -2.65578593234934e-06 -3.48358163737625e-05 7.25552295086818e-05 2.14134242762226e-06 3.81732264688578e-05 2.07309622065744e-05 1.46021811673e-05 1.18076910664064e-06 2.14134242762226e-06 9.33379064446619e-06 -7.34908909708981e-07 2.85666843054542e-06 2.23180071587253e-07 -1.90767278483905e-05 3.81732264688578e-05 -7.34908909708981e-07 8.10464593897353e-05 2.45611595675314e-05 2.93021570072594e-05 -1.07169446204701e-05 2.07309622065744e-05 2.85666843054542e-06 2.45611595675314e-05 3.15622768727398e-05 1.58610565906328e-05 -2.65578593234934e-06 1.46021811673e-05 2.23180071587253e-07 2.93021570072594e-05 1.58610565906328e-05 4.00479351691529e-05 838 849 0 30 0 836 849 0 37 0 0 0 0 0 0 0 5 0 2544 0 0 0 0 0 1511 +873 929 0.995566462870729 -0.0121900549359124 0.0932674678959646 -0.0147710980222509 -0.00259958651978556 0.987622036537448 0.156830976199059 -0.0268654108347939 -0.0940247848016229 -0.156378117095338 0.983211688466286 0.00199622614135453 2.13531155093703e-05 -1.58846156952299e-05 1.40881191464655e-06 1.55102002574181e-06 2.66454164511232e-06 2.96843999556469e-06 -1.58846156952299e-05 4.48473475999637e-05 2.99275568591348e-06 -2.33076505513277e-07 -1.52801746217619e-06 -2.56978138830689e-06 1.40881191464655e-06 2.99275568591348e-06 9.18289219212335e-06 6.73910232799978e-07 2.07675914908537e-06 -6.83490587251279e-07 1.55102002574181e-06 -2.33076505513277e-07 6.73910232799978e-07 3.06357136649957e-05 -4.27410943357203e-07 5.45198641132557e-06 2.66454164511232e-06 -1.52801746217619e-06 2.07675914908537e-06 -4.27410943357203e-07 2.05331470072039e-05 8.30128574139565e-07 2.96843999556469e-06 -2.56978138830689e-06 -6.83490587251279e-07 5.45198641132557e-06 8.30128574139565e-07 2.60189404631844e-05 875 873 0 13 0 874 881 0 17 0 0 0 0 0 0 5 19 0 2548 0 0 0 0 0 2106 +873 876 0.999884676288004 0.0101927623495789 -0.0112579625207777 0.00624533766438578 -0.0101831762345864 0.999947737415722 0.000908492682895521 -0.0011855160099757 0.0112666342005757 -0.000793746095755561 0.999936214426163 0.010770307966374 2.82136066467869e-05 -3.67343838209885e-05 1.60765447003119e-06 -1.69803067703163e-05 -1.19183401172623e-05 1.98808242895035e-05 -3.67343838209885e-05 7.65418658610323e-05 -2.68892879642827e-06 5.63966388449829e-05 3.45763917263853e-05 -2.72789298498219e-05 1.60765447003119e-06 -2.68892879642827e-06 7.52317742601537e-06 -1.70432563992011e-07 -5.16147559011332e-07 -1.12030293404378e-06 -1.69803067703163e-05 5.63966388449829e-05 -1.70432563992011e-07 9.07867811748761e-05 3.97938545476608e-05 -1.03988535476036e-05 -1.19183401172623e-05 3.45763917263853e-05 -5.16147559011332e-07 3.97938545476608e-05 3.99732875532767e-05 -1.1359900715647e-05 1.98808242895035e-05 -2.72789298498219e-05 -1.12030293404378e-06 -1.03988535476036e-05 -1.1359900715647e-05 4.59899833418552e-05 712 718 0 21 0 711 719 0 23 0 0 0 0 0 0 1 9 0 2102 0 0 0 0 0 2628 +873 922 0.996142240743535 0.0109200845256215 0.0870711660677785 -0.00536907076454721 -0.0228768511328113 0.990232945803886 0.13753313319635 -0.022890320045522 -0.084718863830298 -0.138994477582784 0.986662682639205 0.00447626343254931 4.67130150630281e-05 -5.90972237365837e-05 -2.34902690959953e-06 -1.23281923791729e-05 -1.1190887707434e-05 -1.37383840084048e-05 -5.90972237365837e-05 0.000117747432687583 6.8091081279197e-06 3.80607849414246e-05 2.79682228469172e-05 4.18840362160489e-05 -2.34902690959953e-06 6.8091081279197e-06 9.94553817781993e-06 -9.34161090824885e-07 3.39335983165741e-06 5.37993691655268e-07 -1.23281923791729e-05 3.80607849414246e-05 -9.34161090824885e-07 7.36739493823957e-05 2.66686508723252e-05 2.68035742883288e-05 -1.1190887707434e-05 2.79682228469172e-05 3.39335983165741e-06 2.66686508723252e-05 3.58913215602202e-05 1.77990770290656e-05 -1.37383840084048e-05 4.18840362160489e-05 5.37993691655268e-07 2.68035742883288e-05 1.77990770290656e-05 5.72638569105015e-05 849 855 0 30 0 849 855 0 32 0 0 0 0 0 0 0 2 0 2563 0 0 0 0 0 1569 +873 920 0.995682917897322 0.0103949670828589 0.0922359564747951 -0.0037427464063104 -0.0231769856855585 0.990075344079519 0.138613276349536 -0.0237109785557118 -0.0898796658983857 -0.140152622897924 0.986042031534573 0.00914424956376719 2.78342549952423e-05 -3.9279243607583e-05 -1.58508336214825e-06 -7.44616294134251e-06 -3.41733609848925e-06 -1.11342575512161e-06 -3.9279243607583e-05 0.000144486757591993 9.61345585345567e-06 6.12747766577052e-05 2.28730150594937e-05 3.79405358118756e-05 -1.58508336214825e-06 9.61345585345567e-06 1.03312747306195e-05 1.72375217200317e-06 4.31276324162178e-06 9.57639278666862e-07 -7.44616294134251e-06 6.12747766577052e-05 1.72375217200317e-06 8.28588274635676e-05 2.41673310026418e-05 2.99522638619372e-05 -3.41733609848925e-06 2.28730150594937e-05 4.31276324162178e-06 2.41673310026418e-05 3.08524012774695e-05 1.24197396532838e-05 -1.11342575512161e-06 3.79405358118756e-05 9.57639278666862e-07 2.99522638619372e-05 1.24197396532838e-05 4.61305836908534e-05 841 848 0 29 0 840 849 0 32 0 0 0 0 0 0 0 2 0 2304 0 0 0 0 0 1879 +873 919 0.996117560375046 0.0113040064819108 0.0873042115245526 -0.00524423659847374 -0.0233051224202503 0.990200373119183 0.137695651142683 -0.0229188430080991 -0.0848921502934402 -0.139195691427886 0.986619421208841 0.00477409939203167 5.62895801430826e-05 -7.22448928618882e-05 -2.89501192298909e-06 -2.79441432103089e-05 -1.91554337097188e-05 -1.55140650491475e-05 -7.22448928618882e-05 0.000149200924214114 8.50862969728905e-06 6.63305906539924e-05 3.63225725644619e-05 4.56093344488023e-05 -2.89501192298909e-06 8.50862969728905e-06 9.67275505339096e-06 1.94685449382057e-06 3.49147861286296e-06 1.23448186700579e-07 -2.79441432103089e-05 6.63305906539924e-05 1.94685449382057e-06 9.66366331077735e-05 3.00748081026493e-05 3.52673237553488e-05 -1.91554337097188e-05 3.63225725644619e-05 3.49147861286296e-06 3.00748081026493e-05 3.70388125831504e-05 1.84971383301395e-05 -1.55140650491475e-05 4.56093344488023e-05 1.23448186700579e-07 3.52673237553488e-05 1.84971383301395e-05 6.49964796944563e-05 833 843 0 30 0 833 844 0 36 0 0 0 0 0 0 0 3 0 2324 0 0 0 0 0 1578 +873 927 0.995713209207371 0.00985633714129377 0.0919676988301551 -0.0148267165508068 -0.0224872212203461 0.990269352618005 0.13733511622052 -0.0274824557030372 -0.0897191723754972 -0.138814487297521 0.986245916708699 0.00788101179285257 3.11746187998345e-05 -4.10989536398646e-05 -9.32036716603961e-07 -1.56467337214289e-05 -8.07568443606195e-06 -1.9887651138518e-06 -4.10989536398646e-05 8.73254968673765e-05 4.23153066694261e-06 4.13898054576861e-05 2.4059479232067e-05 1.86279702747157e-05 -9.32036716603961e-07 4.23153066694261e-06 9.29420938068266e-06 2.05798191625381e-06 2.07118494449197e-06 -3.5173213623683e-07 -1.56467337214289e-05 4.13898054576861e-05 2.05798191625381e-06 7.41981190284221e-05 2.12756615568076e-05 3.22581183067877e-05 -8.07568443606195e-06 2.4059479232067e-05 2.07118494449197e-06 2.12756615568076e-05 2.88073590846471e-05 1.62446254166116e-05 -1.9887651138518e-06 1.86279702747157e-05 -3.5173213623683e-07 3.22581183067877e-05 1.62446254166116e-05 4.48862551693312e-05 827 839 0 27 0 826 839 0 33 0 0 0 0 0 0 0 5 0 2539 0 0 0 0 0 1519 +873 916 0.99573117090401 0.0106149645721395 0.09168837340286 -0.00353780177874062 -0.0233488912953572 0.990024028526236 0.138950538739367 -0.0229467237722985 -0.0892987377593192 -0.140498204500324 0.986045632801433 0.0054624924397504 5.00072233936616e-05 -6.16651554156135e-05 -5.70701226500701e-06 -1.23553927650978e-05 -1.39608117920955e-05 -3.14095976066023e-06 -6.16651554156135e-05 0.000138305533076107 1.40547922998731e-05 3.35608912599086e-05 2.1729365042934e-05 3.9498680459639e-05 -5.70701226500701e-06 1.40547922998731e-05 1.11265179307431e-05 1.0431569291361e-06 3.00435278836131e-06 -1.44238038397603e-07 -1.23553927650978e-05 3.35608912599086e-05 1.0431569291361e-06 6.18545131838234e-05 1.39927445685913e-05 2.53465984687087e-05 -1.39608117920955e-05 2.1729365042934e-05 3.00435278836131e-06 1.39927445685913e-05 3.26289659038487e-05 1.23528731963072e-05 -3.14095976066023e-06 3.9498680459639e-05 -1.44238038397603e-07 2.53465984687087e-05 1.23528731963072e-05 6.51171689442401e-05 819 828 0 29 0 818 828 0 35 0 0 0 0 0 0 0 4 0 2404 0 0 0 0 0 1621 +873 915 0.995619760702523 0.0105735300216831 0.0928950620944497 -0.002549745168376 -0.0234678410733653 0.990037778094069 0.138832483165553 -0.0219497203973577 -0.0905016714431638 -0.140404410220758 0.985949313634608 0.00363885060738823 3.05475712612732e-05 -3.64931977067525e-05 1.17086743683375e-06 -1.29907578134047e-05 -4.39402150325958e-06 -5.17669254952715e-06 -3.64931977067525e-05 7.70364926488852e-05 3.33069819857121e-06 2.79921921690196e-05 1.67197178062133e-05 2.55985636751351e-05 1.17086743683375e-06 3.33069819857121e-06 9.70136780172057e-06 8.61195625753455e-07 3.58707819077094e-06 2.66238255706415e-06 -1.29907578134047e-05 2.79921921690196e-05 8.61195625753455e-07 7.6683600390722e-05 2.28472188169794e-05 2.67727517697146e-05 -4.39402150325958e-06 1.67197178062133e-05 3.58707819077094e-06 2.28472188169794e-05 2.84639583846084e-05 1.26532297641854e-05 -5.17669254952715e-06 2.55985636751351e-05 2.66238255706415e-06 2.67727517697146e-05 1.26532297641854e-05 4.90455451435596e-05 832 836 0 27 0 830 838 0 34 0 0 0 0 0 0 0 4 0 2572 0 0 0 0 0 1496 +873 917 0.995098826183188 0.0111570663566724 0.0982539871921476 0.00991260090335183 -0.0251581284831104 0.989483971603211 0.142437840869491 -0.013426297572584 -0.0956315570304552 -0.144211614687057 0.98491502957833 0.00712626625848542 5.38017877324977e-05 -5.22146182663987e-05 -2.16976976584448e-06 -1.84895724356319e-05 -1.54052956423174e-05 4.83585594382054e-07 -5.22146182663987e-05 7.79176427613936e-05 7.1711635198972e-06 1.50076410764467e-05 8.54525575480995e-06 2.02538486686869e-05 -2.16976976584448e-06 7.1711635198972e-06 1.12812670644564e-05 -5.58855763504989e-06 -1.48188907541441e-06 5.82205499991088e-08 -1.84895724356319e-05 1.50076410764467e-05 -5.58855763504989e-06 8.8376963601471e-05 4.30970257339547e-05 1.65091733428004e-05 -1.54052956423174e-05 8.54525575480995e-06 -1.48188907541441e-06 4.30970257339547e-05 5.11271812572459e-05 7.86569683306198e-06 4.83585594382054e-07 2.02538486686869e-05 5.82205499991088e-08 1.65091733428004e-05 7.86569683306198e-06 6.92636431723482e-05 812 821 0 32 0 811 821 0 36 0 0 0 0 0 0 0 2 0 2203 0 0 0 0 0 1590 +873 913 0.996390917590461 0.0115483956344285 0.0840938398547154 -0.00758762763489688 -0.0229847025800708 0.990397237812424 0.136326867421012 -0.023811088413037 -0.0817119501085704 -0.137767724419732 0.987088249001913 0.00303634402151935 4.65662115267046e-05 -4.28785828820216e-05 -2.12683014921271e-06 -9.47738849301552e-06 -1.28871001570714e-05 -2.83030977619404e-06 -4.28785828820216e-05 5.55666295122388e-05 3.96784865709177e-06 1.43643368972223e-05 1.41947194063406e-05 1.54810212511264e-05 -2.12683014921271e-06 3.96784865709177e-06 1.04456356237852e-05 5.18826540663434e-08 6.1529571400496e-06 3.67827755046777e-06 -9.47738849301552e-06 1.43643368972223e-05 5.18826540663434e-08 6.52802846823978e-05 2.23400008574603e-05 1.45931929589912e-05 -1.28871001570714e-05 1.41947194063406e-05 6.1529571400496e-06 2.23400008574603e-05 3.45873810371581e-05 1.33405227558414e-05 -2.83030977619404e-06 1.54810212511264e-05 3.67827755046777e-06 1.45931929589912e-05 1.33405227558414e-05 5.1059642770546e-05 885 892 0 32 0 884 893 0 36 0 0 0 0 0 0 0 3 0 2513 0 0 0 0 0 1548 +873 914 0.996257216079405 0.0112085748001895 0.0857083850078996 -0.00662074719519935 -0.0231520440782942 0.989929378201883 0.13965603827916 -0.0216988448795114 -0.0832799031262075 -0.141117660212257 0.986483787860453 0.00592393499851033 4.25165309932645e-05 -4.78126631300129e-05 -1.9485779567038e-06 -1.32059162252829e-05 -9.5368555427751e-06 2.55438140507683e-06 -4.78126631300129e-05 7.99173234690862e-05 4.85965261652325e-06 3.22202178521356e-05 1.95128615083692e-05 1.04815360713833e-05 -1.9485779567038e-06 4.85965261652325e-06 9.28327453941986e-06 -7.58257243286255e-07 3.35129244530607e-06 2.91528474319656e-07 -1.32059162252829e-05 3.22202178521356e-05 -7.58257243286255e-07 6.92504640773386e-05 2.17025799153389e-05 9.88931761692845e-06 -9.5368555427751e-06 1.95128615083692e-05 3.35129244530607e-06 2.17025799153389e-05 2.93669164359219e-05 9.07839994778448e-06 2.55438140507683e-06 1.04815360713833e-05 2.91528474319656e-07 9.88931761692845e-06 9.07839994778448e-06 3.52748046164664e-05 887 898 0 32 0 886 898 0 39 0 0 0 0 0 0 0 4 0 2570 0 0 0 0 0 1902 +873 912 0.995778833757722 0.0106909107639114 0.0911604007623336 -0.00491997946880114 -0.0233931895131354 0.989954909263206 0.13943470267505 -0.0221771390338859 -0.088754002301382 -0.140978658146242 0.986026239520415 0.00468426147824909 3.06444729781357e-05 -3.62949128570929e-05 -1.40943569534931e-06 -7.19037184930744e-06 -6.65173973351157e-06 -1.08916165702909e-06 -3.62949128570929e-05 7.31360090154124e-05 5.1912597530148e-06 2.55337050117372e-05 1.99881826851739e-05 1.78149147622947e-05 -1.40943569534931e-06 5.1912597530148e-06 8.66488038784845e-06 8.30755355279775e-07 3.42881910485657e-06 2.25573662675539e-07 -7.19037184930744e-06 2.55337050117372e-05 8.30755355279775e-07 6.68392783437225e-05 2.14554744837751e-05 2.22510554944339e-05 -6.65173973351157e-06 1.99881826851739e-05 3.42881910485657e-06 2.14554744837751e-05 2.91344947458287e-05 1.24487412580106e-05 -1.08916165702909e-06 1.78149147622947e-05 2.25573662675539e-07 2.22510554944339e-05 1.24487412580106e-05 4.28992442194955e-05 856 864 0 29 0 854 864 0 33 0 0 0 0 0 0 0 5 0 2508 0 0 0 0 0 2198 +873 904 0.99560293501129 0.0107234302941244 0.0930580670314586 -0.00209387866243687 -0.0235991838150788 0.990096789538092 0.138388676811456 -0.0221303428363162 -0.0906524920791839 -0.139976267235166 0.985996333812019 0.00539356601427894 6.50525223894274e-05 -8.05239264038073e-05 -6.12239155334116e-06 -4.00751491493696e-05 -2.70175515554805e-05 -1.315914385827e-05 -8.05239264038073e-05 0.000134959966343229 1.07281786450953e-05 8.62829734663084e-05 5.24816989871876e-05 4.51513826239708e-05 -6.12239155334116e-06 1.07281786450953e-05 1.08528603473254e-05 4.09238025147832e-06 7.62049178387033e-06 3.22608087179328e-06 -4.00751491493696e-05 8.62829734663084e-05 4.09238025147832e-06 0.000120256545364768 4.81129592221228e-05 4.80805534270523e-05 -2.70175515554805e-05 5.24816989871876e-05 7.62049178387033e-06 4.81129592221228e-05 4.64510618345464e-05 3.1630080389377e-05 -1.315914385827e-05 4.51513826239708e-05 3.22608087179328e-06 4.80805534270523e-05 3.1630080389377e-05 6.37275750074846e-05 808 818 0 34 0 808 818 0 37 0 0 0 0 0 0 0 3 0 2551 0 0 0 0 0 1507 +873 910 0.995501639508598 0.0104064687941547 0.0941710738121274 -0.00345218403664141 -0.0237080579342539 0.989689160558401 0.141256127166911 -0.0220850262718408 -0.091730113510662 -0.142853319458964 0.985483899104839 0.00771260739577467 3.67342488425213e-05 -4.44246550779325e-05 1.06171333112873e-06 -1.46206534900738e-05 -8.59090259968824e-06 -9.0833496118069e-07 -4.44246550779325e-05 9.06032359033549e-05 2.24037190766606e-06 3.90788520284809e-05 2.01463213604621e-05 2.34481175502129e-05 1.06171333112873e-06 2.24037190766606e-06 8.87459447470332e-06 -7.42951748395709e-07 3.96544404249542e-06 1.81522338426432e-06 -1.46206534900738e-05 3.90788520284809e-05 -7.42951748395709e-07 7.00898756824233e-05 2.10438585003917e-05 2.05775360437085e-05 -8.59090259968824e-06 2.01463213604621e-05 3.96544404249542e-06 2.10438585003917e-05 2.59216034349575e-05 1.10680388853277e-05 -9.0833496118069e-07 2.34481175502129e-05 1.81522338426432e-06 2.05775360437085e-05 1.10680388853277e-05 3.78632412682434e-05 861 870 0 30 0 860 870 0 33 0 0 0 0 0 0 0 4 0 2560 0 0 0 0 0 1920 +874 921 0.99465953027675 0.00560166788388194 0.103058430739819 -0.00878550843597139 -0.0194144125686191 0.990856039676997 0.133519246628467 -0.0244601968685676 -0.101368138062464 -0.134807010027433 0.985673156088372 -0.000189263558280028 2.49315668336321e-05 -1.96361568628441e-05 3.42267028706497e-06 -1.06532173735285e-05 -5.79487817921901e-06 -3.60062439797178e-07 -1.96361568628441e-05 3.60405486100555e-05 -6.31386019084272e-07 1.228180890611e-05 5.56477206592115e-06 5.243356789487e-06 3.42267028706497e-06 -6.31386019084272e-07 8.6989118700526e-06 3.98694552002013e-08 2.47796343385204e-06 2.30216108704014e-06 -1.06532173735285e-05 1.228180890611e-05 3.98694552002013e-08 4.90763222772365e-05 1.29957536721287e-05 9.67972295718083e-06 -5.79487817921901e-06 5.56477206592115e-06 2.47796343385204e-06 1.29957536721287e-05 3.00006563950307e-05 1.32570203439905e-05 -3.60062439797178e-07 5.243356789487e-06 2.30216108704014e-06 9.67972295718083e-06 1.32570203439905e-05 3.79345558725067e-05 876 876 0 29 0 876 880 0 42 0 0 0 0 0 0 0 9 0 2397 0 0 0 0 0 1698 +873 924 0.995674720045592 0.0106224708933778 0.0922985101410134 -0.00418593412141549 -0.0233263865311007 0.990202902871408 0.137673856764593 -0.0230442303688621 -0.0899318161360766 -0.139231369515477 0.986167781966797 0.00676005669956622 5.00977477420776e-05 -6.90537609412741e-05 -2.80271478825928e-06 -3.5857732453947e-05 -1.78004856622426e-05 -1.64544276793896e-05 -6.90537609412741e-05 0.00014405284608058 1.09998323267729e-05 7.02990823656555e-05 3.55850845714947e-05 4.66563721921657e-05 -2.80271478825928e-06 1.09998323267729e-05 1.037299088719e-05 3.64214698591186e-06 5.61067408584886e-06 2.689430318225e-06 -3.5857732453947e-05 7.02990823656555e-05 3.64214698591186e-06 9.1444100295785e-05 3.12831901328195e-05 4.10453874187865e-05 -1.78004856622426e-05 3.55850845714947e-05 5.61067408584886e-06 3.12831901328195e-05 3.4855413505092e-05 2.0018222857208e-05 -1.64544276793896e-05 4.66563721921657e-05 2.689430318225e-06 4.10453874187865e-05 2.0018222857208e-05 6.16528649748774e-05 821 824 0 30 0 821 824 0 35 0 0 0 0 0 0 0 4 0 2531 0 0 0 0 0 1505 +874 926 0.995296448237317 0.00536857216658317 0.0967272379377947 -0.0178133111347743 -0.0184720423037336 0.990661358170361 0.135088330662516 -0.0272659527031436 -0.0950987054554984 -0.13623968533782 0.986100899685088 0.00572616127577464 4.05626317823964e-05 -5.22312197144281e-05 -2.53785124745308e-06 -2.2547763601594e-05 -1.16676582681249e-05 2.43892467713585e-06 -5.22312197144281e-05 0.000107837030376171 7.09630844330783e-06 5.50719814923808e-05 2.39991918078737e-05 1.63675395311331e-05 -2.53785124745308e-06 7.09630844330783e-06 9.83778638574296e-06 1.82163437629816e-06 5.03007166224132e-06 4.80777948210657e-07 -2.2547763601594e-05 5.50719814923808e-05 1.82163437629816e-06 7.62615357212285e-05 1.80409811800428e-05 1.95489835980356e-05 -1.16676582681249e-05 2.39991918078737e-05 5.03007166224132e-06 1.80409811800428e-05 2.77636593906831e-05 1.02856757240534e-05 2.43892467713585e-06 1.63675395311331e-05 4.80777948210657e-07 1.95489835980356e-05 1.02856757240534e-05 4.12260900393754e-05 880 886 0 22 0 880 889 0 33 0 0 0 0 0 0 1 8 0 2493 0 0 0 0 0 1699 +874 922 0.993939454276988 0.0052606620435407 0.109802944707446 -0.00200883444315495 -0.0203799234096168 0.990357001881073 0.137031629731789 -0.0206677050160075 -0.108023238024885 -0.138438918877589 0.984462109878599 0.0037004993525014 3.33432589851368e-05 -3.34629405212393e-05 -3.19166616896118e-06 -4.88424036730304e-06 -4.75791882678916e-06 1.06526244114468e-05 -3.34629405212393e-05 5.91906258526315e-05 5.71509177165018e-06 2.5332104297915e-05 1.20057412199059e-05 1.58636923318361e-07 -3.19166616896118e-06 5.71509177165018e-06 9.53604281801159e-06 9.87952930990715e-08 2.83908203419406e-06 -7.96382215309988e-07 -4.88424036730304e-06 2.5332104297915e-05 9.87952930990715e-08 6.42664353082027e-05 1.63091377925202e-05 5.99798133856889e-06 -4.75791882678916e-06 1.20057412199059e-05 2.83908203419406e-06 1.63091377925202e-05 2.79685101587353e-05 6.2846048250136e-06 1.06526244114468e-05 1.58636923318361e-07 -7.96382215309988e-07 5.99798133856889e-06 6.2846048250136e-06 3.19558492644923e-05 883 887 0 26 0 883 889 0 36 0 0 0 0 0 0 0 6 0 2526 0 0 0 0 0 2033 +873 905 0.996070598897294 0.0107541712076255 0.0879073933979532 -0.00697146002443237 -0.022998754777193 0.989956327092048 0.139490242415448 -0.023594909500358 -0.0855243783437446 -0.140963889886945 0.986313724155178 0.00601529558497998 4.00897741053702e-05 -4.75691103463166e-05 -1.62063573128658e-06 -9.72748608860833e-06 -1.08830607123214e-05 3.21879577293044e-06 -4.75691103463166e-05 0.000100604100790098 6.79888131898693e-06 3.31193282727064e-05 2.44381722725237e-05 1.13494365370758e-05 -1.62063573128658e-06 6.79888131898693e-06 9.30988587908686e-06 1.87733076419975e-06 5.40347128097576e-06 2.18150847255295e-06 -9.72748608860833e-06 3.31193282727064e-05 1.87733076419975e-06 5.74422177474843e-05 1.4553664953248e-05 6.92732254121418e-06 -1.08830607123214e-05 2.44381722725237e-05 5.40347128097576e-06 1.4553664953248e-05 2.69537680272674e-05 7.91352636758684e-06 3.21879577293044e-06 1.13494365370758e-05 2.18150847255295e-06 6.92732254121418e-06 7.91352636758684e-06 3.78601545005395e-05 856 868 0 30 0 854 869 0 36 0 0 0 0 0 0 0 3 0 2576 0 0 0 0 0 1915 +874 877 0.999938675031074 0.00567672052031743 0.00950899685738169 0.00748321345239692 -0.00560532393407052 0.999956027403197 -0.00751821811413008 0.00148825012753863 -0.00955125754514158 0.00746445605196417 0.999926524988289 0.000160554936143415 2.33607109571901e-05 -2.18573065081758e-05 -2.54727371953609e-07 -6.34252254820112e-06 -6.06457251912248e-06 1.2830677173667e-05 -2.18573065081758e-05 2.86871707935859e-05 1.63572497431611e-06 8.4157499527954e-06 8.52420844194207e-06 -9.29906143917547e-06 -2.54727371953609e-07 1.63572497431611e-06 8.88016804127704e-06 7.02072149461693e-08 -5.22686787398676e-08 -2.04336504558515e-06 -6.34252254820112e-06 8.4157499527954e-06 7.02072149461693e-08 4.7795828256148e-05 1.41076786935303e-05 4.88783927912173e-06 -6.06457251912248e-06 8.52420844194207e-06 -5.22686787398676e-08 1.41076786935303e-05 2.80787286057328e-05 3.97249640925683e-06 1.2830677173667e-05 -9.29906143917547e-06 -2.04336504558515e-06 4.88783927912173e-06 3.97249640925683e-06 2.93777794641944e-05 797 798 0 10 0 795 806 0 21 0 0 0 0 0 0 4 15 0 2050 0 0 0 0 0 2427 +873 908 0.996030275096367 0.0108735158259876 0.0883485016570022 -0.00509102354677552 -0.0231572225142157 0.989989480130366 0.139228489457561 -0.0228198580632423 -0.0859501840421673 -0.140721696567335 0.986311294662252 0.00514103812197302 7.66033479808712e-05 -9.54806419496841e-05 3.85907296830732e-06 -7.0990752821445e-05 -3.66479843681965e-05 -4.42669784067114e-05 -9.54806419496841e-05 0.000154102641853784 -9.5514111418494e-07 0.000108414665928203 5.82376731616572e-05 7.62629066181839e-05 3.85907296830732e-06 -9.5514111418494e-07 1.07526162489196e-05 1.65301207157621e-07 4.5928644667436e-06 5.68739119961615e-06 -7.0990752821445e-05 0.000108414665928203 1.65301207157621e-07 0.000141194490691116 6.18609083907426e-05 6.98639629140786e-05 -3.66479843681965e-05 5.82376731616572e-05 4.5928644667436e-06 6.18609083907426e-05 5.21006975203778e-05 4.37255431713755e-05 -4.42669784067114e-05 7.62629066181839e-05 5.68739119961615e-06 6.98639629140786e-05 4.37255431713755e-05 9.1292893274334e-05 839 842 0 30 0 839 843 0 36 0 0 0 0 0 0 0 4 0 2536 0 0 0 0 0 1606 +874 927 0.995289050756524 0.00506601643703865 0.0968196308691465 -0.0197602491103613 -0.0182367428611702 0.990590521737184 0.135638635551487 -0.0274150030266659 -0.0952214610998681 -0.136765323536024 0.986016287707304 0.00575731966401637 5.36065432756417e-05 -6.10730973152791e-05 -8.07380429120688e-06 -1.20165926000594e-05 -1.06095696088516e-05 8.78739503063799e-06 -6.10730973152791e-05 9.57199088252393e-05 1.0782700898999e-05 3.75299696077549e-05 2.2764071439625e-05 5.38080222906057e-06 -8.07380429120688e-06 1.0782700898999e-05 1.08900214536384e-05 1.23809723173995e-06 4.76967369246672e-06 -3.36315194916639e-06 -1.20165926000594e-05 3.75299696077549e-05 1.23809723173995e-06 6.36046263344287e-05 1.28135061493203e-05 2.25646580294955e-05 -1.06095696088516e-05 2.2764071439625e-05 4.76967369246672e-06 1.28135061493203e-05 2.57372150435615e-05 9.85247746355634e-06 8.78739503063799e-06 5.38080222906057e-06 -3.36315194916639e-06 2.25646580294955e-05 9.85247746355634e-06 4.13279140101115e-05 872 880 0 21 0 872 882 0 30 0 0 0 0 0 0 2 8 0 2490 0 0 0 0 0 1715 +873 906 0.995915459093056 0.0104505030808754 0.0896838074839788 -0.00866322142855651 -0.0230002845869979 0.989875001199131 0.140065944861473 -0.0215900670280584 -0.0873119994524456 -0.141556592874993 0.98607218080891 0.00716807040760885 4.47371118045666e-05 -5.44049318098816e-05 -8.86755524836267e-07 -2.40609033436875e-05 -1.46193383125467e-05 -2.93161630891488e-06 -5.44049318098816e-05 0.0001020880748387 3.33899224118333e-06 5.5688366482073e-05 2.96372482555085e-05 2.7220205275071e-05 -8.86755524836267e-07 3.33899224118333e-06 8.42264082450472e-06 1.14047924750254e-06 4.95468443752961e-06 1.46198988923653e-06 -2.40609033436875e-05 5.5688366482073e-05 1.14047924750254e-06 8.10340660959218e-05 2.77916624431965e-05 2.2571862870077e-05 -1.46193383125467e-05 2.96372482555085e-05 4.95468443752961e-06 2.77916624431965e-05 3.06807683716069e-05 1.48118037919228e-05 -2.93161630891488e-06 2.7220205275071e-05 1.46198988923653e-06 2.2571862870077e-05 1.48118037919228e-05 4.44296471097196e-05 864 874 0 33 0 862 875 0 38 0 0 0 0 0 0 0 3 0 2557 0 0 0 0 0 1933 +873 903 0.996640953733003 0.011587514472623 0.0810711961828412 -0.0127327560965264 -0.0224976064987747 0.990591961903927 0.134986750139245 -0.0268243992111129 -0.078744314359808 -0.136357231270202 0.987525209013081 0.00288629025539632 5.35385680057969e-05 -7.31373506927525e-05 -6.79533042116959e-06 -3.84967604790867e-05 -2.46567196471949e-05 -2.22478516614413e-05 -7.31373506927525e-05 0.00014994747220505 1.41837062216414e-05 8.94686791771823e-05 4.94891428924414e-05 5.92494453069677e-05 -6.79533042116959e-06 1.41837062216414e-05 1.08545980831691e-05 6.59399689687472e-06 7.14966223639634e-06 3.94226954167821e-06 -3.84967604790867e-05 8.94686791771823e-05 6.59399689687472e-06 0.000120304934833583 4.81437341547834e-05 5.30809738088501e-05 -2.46567196471949e-05 4.94891428924414e-05 7.14966223639634e-06 4.81437341547834e-05 4.46778135964637e-05 3.25048663815386e-05 -2.22478516614413e-05 5.92494453069677e-05 3.94226954167821e-06 5.30809738088501e-05 3.25048663815386e-05 6.77680089522431e-05 834 846 0 32 0 833 846 0 39 0 0 0 0 0 0 0 3 0 2548 0 0 0 0 0 1580 +874 920 0.994113766461693 0.00497745528610443 0.108226818627459 -0.00728928119746535 -0.0195773036990005 0.990752600001507 0.134260994969245 -0.0241450828194828 -0.106557723845919 -0.135589492694417 0.985018243972997 0.000564198600357037 3.30092166540032e-05 -3.38101707690968e-05 -1.01480059176318e-06 -4.54375863796557e-06 -4.96064394984617e-06 7.41373475272276e-06 -3.38101707690968e-05 6.23474358250816e-05 3.5429278604884e-06 2.06554088909431e-05 1.40160336508299e-05 8.50943544762336e-06 -1.01480059176318e-06 3.5429278604884e-06 1.05596348355807e-05 -2.94357896769941e-06 3.00259443738788e-06 -1.20314453064115e-06 -4.54375863796557e-06 2.06554088909431e-05 -2.94357896769941e-06 7.31598322336417e-05 2.05700937313668e-05 1.8505269995663e-05 -4.96064394984617e-06 1.40160336508299e-05 3.00259443738788e-06 2.05700937313668e-05 2.97231352998919e-05 9.76151045366176e-06 7.41373475272276e-06 8.50943544762336e-06 -1.20314453064115e-06 1.8505269995663e-05 9.76151045366176e-06 3.91244150555341e-05 872 877 0 22 0 872 879 0 30 0 0 0 0 0 0 1 5 0 2287 0 0 0 0 0 2023 +874 876 0.999943540400861 0.00707868926555929 0.00792516049507761 0.00828228312397117 -0.00706477017720422 0.999973454727835 -0.00178293634847199 0.00196568753745232 -0.00793757097192642 0.00172684624708528 0.999967005940248 -0.00060171753171219 3.59922195757548e-05 -3.91302909459739e-05 1.13431741643817e-06 -1.08763458223641e-05 -9.48103045658007e-06 9.54455016224908e-07 -3.91302909459739e-05 5.54492237626237e-05 -1.64950753167579e-07 2.74825952719418e-05 1.85306200122568e-05 6.34731343158607e-06 1.13431741643817e-06 -1.64950753167579e-07 8.22335702287135e-06 2.27221716964551e-06 2.12258366361704e-06 -6.24015929138776e-08 -1.08763458223641e-05 2.74825952719418e-05 2.27221716964551e-06 6.35922935368435e-05 2.77056808164451e-05 1.58652719980356e-05 -9.48103045658007e-06 1.85306200122568e-05 2.12258366361704e-06 2.77056808164451e-05 3.45860593598328e-05 1.43703841598417e-05 9.54455016224908e-07 6.34731343158607e-06 -6.24015929138776e-08 1.58652719980356e-05 1.43703841598417e-05 4.24129750423526e-05 772 775 0 10 0 770 782 0 21 0 0 0 0 0 0 5 13 0 2119 0 0 0 0 0 2044 +874 878 0.99993418551352 0.00945978284378959 0.00649131342351554 -0.00322986911804076 -0.00939037761150673 0.999899295553495 -0.0106404680318873 -0.000528099157263567 -0.00659131623632807 0.0105788118507065 0.999922318627852 -0.000457692961334725 4.51487664727664e-05 -5.73829616718825e-05 3.94090466090814e-06 -3.22305697086379e-05 -2.23959860527215e-05 3.93610940114398e-06 -5.73829616718825e-05 0.00010448775652184 -4.49428730162146e-06 8.31632393061161e-05 5.22175590959738e-05 8.37283870452712e-06 3.94090466090814e-06 -4.49428730162146e-06 9.53410002995521e-06 -5.13088075541774e-06 -5.91195278000125e-07 -1.0146743830188e-06 -3.22305697086379e-05 8.31632393061161e-05 -5.13088075541774e-06 0.000150251855628578 7.19967534393022e-05 2.23541693382129e-05 -2.23959860527215e-05 5.22175590959738e-05 -5.91195278000125e-07 7.19967534393022e-05 6.40903670556532e-05 1.88200446206629e-05 3.93610940114398e-06 8.37283870452712e-06 -1.0146743830188e-06 2.23541693382129e-05 1.88200446206629e-05 4.84681785508888e-05 729 730 0 10 0 728 737 0 19 0 0 0 0 0 0 2 12 0 2037 0 0 0 0 0 1768 +874 913 0.994340319560383 0.00477475473437108 0.106134493044354 -0.00931498933542908 -0.0196217851925103 0.990057240191738 0.139289793918213 -0.0212373079438003 -0.104414148669682 -0.140584006420168 0.984547521807069 0.00207081168224037 1.66319379692904e-05 -1.22785160499313e-05 5.17122005442063e-06 -4.45967819000817e-06 1.66019784025693e-06 5.14300519401256e-06 -1.22785160499313e-05 3.11846896836386e-05 -1.18189814449983e-06 3.93906148537571e-06 2.71033524806601e-07 -1.08999127826738e-06 5.17122005442063e-06 -1.18189814449983e-06 9.07177073496904e-06 -2.35702107773245e-06 2.32583129310508e-06 1.00621567916355e-07 -4.45967819000817e-06 3.93906148537571e-06 -2.35702107773245e-06 5.98277502212252e-05 1.87674488434901e-05 5.13664278966392e-06 1.66019784025693e-06 2.71033524806601e-07 2.32583129310508e-06 1.87674488434901e-05 2.59483476685395e-05 7.21055439870369e-06 5.14300519401256e-06 -1.08999127826738e-06 1.00621567916355e-07 5.13664278966392e-06 7.21055439870369e-06 2.5287958090672e-05 908 913 0 28 0 907 916 0 37 0 0 0 0 0 0 0 7 0 2461 0 0 0 0 0 1825 +874 925 0.99408530170523 0.00467572383791083 0.108501384969106 -0.00936339601237197 -0.0194013199659031 0.990646982281367 0.135063486110797 -0.0232748011394412 -0.106855050031354 -0.136369696426341 0.9848783194788 0.00172656240099678 3.07996088642242e-05 -3.14615400602065e-05 3.19413666330225e-06 -1.64864225356496e-05 -7.56752755140692e-06 1.66661979511515e-06 -3.14615400602065e-05 5.38464539058591e-05 1.08990030766358e-06 2.4350002827989e-05 1.2389060388799e-05 8.89226725873979e-06 3.19413666330225e-06 1.08990030766358e-06 1.05510571488206e-05 2.30630216395696e-07 4.82175857415568e-06 4.87350132014553e-06 -1.64864225356496e-05 2.4350002827989e-05 2.30630216395696e-07 6.28130647737928e-05 1.56382694459243e-05 1.24485085320068e-05 -7.56752755140692e-06 1.2389060388799e-05 4.82175857415568e-06 1.56382694459243e-05 2.61543542119005e-05 1.10947818528164e-05 1.66661979511515e-06 8.89226725873979e-06 4.87350132014553e-06 1.24485085320068e-05 1.10947818528164e-05 3.63757977533826e-05 888 897 0 22 0 888 899 0 32 0 0 0 0 0 0 0 7 0 2470 0 0 0 0 0 1739 +874 914 0.994313859928878 0.00536856325022014 0.106353779819822 -0.00852247143268479 -0.0197825780997063 0.990655868389095 0.134942951019969 -0.0226307778820644 -0.104635546336147 -0.136279598454344 0.985129064380936 -0.00177751395739612 1.77827674427992e-05 -1.48937755414969e-05 3.01927569683696e-06 -4.26947029775139e-06 2.25857949283354e-07 5.63018284931322e-06 -1.48937755414969e-05 3.83143728007491e-05 1.27363275314551e-06 4.06792985762628e-06 3.0952692963616e-06 1.39779699683145e-06 3.01927569683696e-06 1.27363275314551e-06 8.65699803408652e-06 -8.6094844754914e-07 4.25828711275904e-06 4.99111034344416e-07 -4.26947029775139e-06 4.06792985762628e-06 -8.6094844754914e-07 4.46744235819259e-05 6.93803861013429e-06 2.07569505341149e-06 2.25857949283354e-07 3.0952692963616e-06 4.25828711275904e-06 6.93803861013429e-06 2.54577297459463e-05 3.4887262835027e-06 5.63018284931322e-06 1.39779699683145e-06 4.99111034344416e-07 2.07569505341149e-06 3.4887262835027e-06 2.75120116667475e-05 908 915 0 25 0 908 919 0 35 0 0 0 0 0 0 1 8 0 2538 0 0 0 0 0 2043 +874 919 0.994986833860999 0.00605342150309661 0.0998226253480151 -0.0119739821557705 -0.0196119076587656 0.990595370393235 0.135411171006953 -0.0228902187076392 -0.0980641296359091 -0.1366900444202 0.985748070368467 0.0038728179094992 3.72241059791748e-05 -4.18557069968663e-05 -3.45460157878314e-06 -1.67797294991081e-05 -1.38490450997258e-05 3.4762550900037e-06 -4.18557069968663e-05 7.30329036793628e-05 4.53783045769985e-06 4.82730744070542e-05 2.7852369031596e-05 1.07651570603938e-05 -3.45460157878314e-06 4.53783045769985e-06 9.72701999097616e-06 6.09711412202678e-07 1.00865083168053e-06 -1.57379918801782e-06 -1.67797294991081e-05 4.82730744070542e-05 6.09711412202678e-07 9.19777942686774e-05 2.96351038199918e-05 2.1160393718059e-05 -1.38490450997258e-05 2.7852369031596e-05 1.00865083168053e-06 2.96351038199918e-05 3.8176490595904e-05 1.17518645107024e-05 3.4762550900037e-06 1.07651570603938e-05 -1.57379918801782e-06 2.1160393718059e-05 1.17518645107024e-05 3.61031385351859e-05 881 888 0 23 0 881 890 0 32 0 0 0 0 0 0 1 8 0 2322 0 0 0 0 0 2117 +874 923 0.993881899498875 0.00473817871123346 0.110346361566702 -0.00604805582090711 -0.0198693183297713 0.990450095792996 0.136432466564066 -0.0216176603650833 -0.108646122975554 -0.137790266006511 0.984484566946702 0.00272012932114632 2.89028900861455e-05 -2.47282682579135e-05 1.47024304210958e-06 -9.91436374277737e-06 -6.17587111173855e-06 9.06114979893419e-06 -2.47282682579135e-05 3.58413946235326e-05 6.06961156298892e-07 1.78309745047448e-05 1.00622654310013e-05 -1.90343902657234e-06 1.47024304210958e-06 6.06961156298892e-07 8.81791651481387e-06 1.6206533770379e-06 3.53201605933235e-06 2.01886191711928e-06 -9.91436374277737e-06 1.78309745047448e-05 1.6206533770379e-06 5.96608557660981e-05 1.8183236747706e-05 9.69121805524322e-06 -6.17587111173855e-06 1.00622654310013e-05 3.53201605933235e-06 1.8183236747706e-05 2.93471348888472e-05 8.69620167830164e-06 9.06114979893419e-06 -1.90343902657234e-06 2.01886191711928e-06 9.69121805524322e-06 8.69620167830164e-06 2.94409789700126e-05 878 886 0 25 0 878 889 0 35 0 0 0 0 0 0 0 8 0 2452 0 0 0 0 0 2053 +874 916 0.994912326457058 0.00587728928598947 0.100572959260694 -0.00928240450001186 -0.0195279759964638 0.990613604117455 0.135289857309808 -0.0235417641044051 -0.0988338040211243 -0.136565533016481 0.985688457056609 0.00259732476980048 3.66895517801148e-05 -3.96382560227684e-05 -2.2234684004308e-06 -8.8983058549697e-06 -4.91612603164849e-06 7.83568690862088e-06 -3.96382560227684e-05 8.4153200407206e-05 5.11790988988427e-06 3.88895373789318e-05 1.84746522607444e-05 9.49782004672547e-06 -2.2234684004308e-06 5.11790988988427e-06 9.61482497839222e-06 6.27719814426635e-07 3.66599680875742e-06 -1.8749134822643e-07 -8.8983058549697e-06 3.88895373789318e-05 6.27719814426635e-07 7.15052037972655e-05 1.72627930466499e-05 8.99157237149595e-06 -4.91612603164849e-06 1.84746522607444e-05 3.66599680875742e-06 1.72627930466499e-05 3.33286527183222e-05 7.71483900110924e-06 7.83568690862088e-06 9.49782004672547e-06 -1.8749134822643e-07 8.99157237149595e-06 7.71483900110924e-06 3.27319796333994e-05 883 886 0 20 0 883 888 0 28 0 0 0 0 0 0 0 5 0 2398 0 0 0 0 0 2121 +874 917 0.995681798942483 0.00678869749471583 0.0925833075720828 -0.00877599212797386 -0.019575367735187 0.990251061416198 0.137911712128179 -0.0189736665929446 -0.0907444776980608 -0.139128533918887 0.986107849485485 0.000959336146703446 5.10026981486659e-05 -6.35352339927628e-05 -3.37674815922839e-07 -3.42650799080118e-05 -1.63243132510123e-05 -2.92886492067898e-06 -6.35352339927628e-05 0.000157428183084356 8.8317575479709e-06 7.79229919242679e-05 2.6131082510369e-05 3.31777116199763e-05 -3.37674815922839e-07 8.8317575479709e-06 1.11835595907855e-05 -2.69804036209415e-06 -1.21257333145887e-06 2.16070080375137e-06 -3.42650799080118e-05 7.79229919242679e-05 -2.69804036209415e-06 0.0001402055365996 5.90951423916441e-05 3.31980162455288e-05 -1.63243132510123e-05 2.6131082510369e-05 -1.21257333145887e-06 5.90951423916441e-05 5.84511086895906e-05 1.36000645126197e-05 -2.92886492067898e-06 3.31777116199763e-05 2.16070080375137e-06 3.31980162455288e-05 1.36000645126197e-05 5.2800153189638e-05 861 868 0 29 0 861 870 0 39 0 0 0 0 0 0 0 8 0 2218 0 0 0 0 0 1743 +874 928 0.995619012540629 0.00568812512581209 0.0933296689171003 -0.0192406517008369 -0.0183175342291901 0.990672307769251 0.135029058201961 -0.0260168532191518 -0.0916910563107705 -0.136147066996316 0.98643637723926 0.00372396602434186 3.88088135938459e-05 -4.66954753172488e-05 -4.11017448037014e-06 -1.40620094281723e-05 -9.38943654071379e-06 1.20171839246072e-05 -4.66954753172488e-05 0.000115742747740058 8.97579810669653e-06 5.63853229042493e-05 2.50032846200447e-05 6.4096155516433e-06 -4.11017448037014e-06 8.97579810669653e-06 9.50941257405815e-06 2.68996809424001e-06 5.03979121037668e-06 -1.8924251597673e-06 -1.40620094281723e-05 5.63853229042493e-05 2.68996809424001e-06 7.14724769725538e-05 1.56319452633865e-05 1.99049305594436e-05 -9.38943654071379e-06 2.50032846200447e-05 5.03979121037668e-06 1.56319452633865e-05 2.7234328282344e-05 6.93593226441613e-06 1.20171839246072e-05 6.4096155516433e-06 -1.8924251597673e-06 1.99049305594436e-05 6.93593226441613e-06 4.00748754745236e-05 857 862 0 26 0 857 864 0 35 0 0 0 0 0 0 0 7 0 2499 0 0 0 0 0 2123 +874 929 0.993772693583467 -0.0185354326983832 0.109873887810272 -0.0194229379608801 0.00148391793079081 0.988181369207855 0.153282026141566 -0.0282992683334021 -0.111416477575964 -0.152164448164388 0.982055166087625 -0.00338696790482158 3.21928118803527e-05 -3.26924241867886e-05 -7.63655145521824e-06 1.07107252672362e-06 -1.50707816727303e-06 8.68736897474102e-06 -3.26924241867886e-05 5.161005406349e-05 1.03878239091091e-05 9.02630586999553e-06 4.63248508362578e-06 -1.62636901240399e-06 -7.63655145521824e-06 1.03878239091091e-05 1.08834972784222e-05 -1.60703466566352e-07 2.95366456196607e-06 -4.0016672312766e-06 1.07107252672362e-06 9.02630586999553e-06 -1.60703466566352e-07 3.72254985032017e-05 2.66918995658891e-06 9.24706047215136e-06 -1.50707816727303e-06 4.63248508362578e-06 2.95366456196607e-06 2.66918995658891e-06 1.98423329896476e-05 3.67874306093687e-06 8.68736897474102e-06 -1.62636901240399e-06 -4.0016672312766e-06 9.24706047215136e-06 3.67874306093687e-06 3.1638045828138e-05 895 895 0 3 0 895 903 0 15 0 0 0 0 0 0 16 27 0 2514 0 0 0 0 0 1887 +874 918 0.995390053059149 0.00583778099098348 0.0957317219316916 -0.0150755173232692 -0.0185822258946253 0.990971001512499 0.132782434990909 -0.029554145434621 -0.0940922055842381 -0.13394922349314 0.986511156740702 -0.000737329230187063 4.47885571009366e-05 -5.05103294013119e-05 -5.29693454369455e-06 -1.54442762194818e-05 -1.25595338627941e-05 9.52414414862395e-06 -5.05103294013119e-05 9.2584001002076e-05 7.92217326993059e-06 4.2264180739327e-05 2.47852576746784e-05 4.67382576575998e-06 -5.29693454369455e-06 7.92217326993059e-06 1.04823820310078e-05 -1.80550180440623e-07 3.7141701332149e-06 -2.0033718273305e-06 -1.54442762194818e-05 4.2264180739327e-05 -1.80550180440623e-07 7.3524530645513e-05 1.9764892588864e-05 1.53989955347755e-05 -1.25595338627941e-05 2.47852576746784e-05 3.7141701332149e-06 1.9764892588864e-05 3.43486488396732e-05 8.08667959243526e-06 9.52414414862395e-06 4.67382576575998e-06 -2.0033718273305e-06 1.53989955347755e-05 8.08667959243526e-06 3.71025000261328e-05 874 881 0 28 0 874 883 0 39 0 0 0 0 0 0 0 9 0 2265 0 0 0 0 0 1985 +874 912 0.994915976057779 0.00531008985707386 0.100568402247954 -0.0124536249249936 -0.0189354921571517 0.990661958807558 0.135019741180091 -0.0239355006387857 -0.0989123234069596 -0.136237609775282 0.985725958855175 -0.00065306622098185 6.07134220857432e-05 -7.35758603545184e-05 -6.56262642811807e-06 -3.11754810291833e-05 -2.39402950275961e-05 -6.94454730939804e-06 -7.35758603545184e-05 0.000121081993810288 1.11744003030461e-05 6.10573309907533e-05 4.08292834384543e-05 2.96909623571263e-05 -6.56262642811807e-06 1.11744003030461e-05 1.09430519723988e-05 1.15047415552936e-06 5.86274660507639e-06 4.17924004035436e-07 -3.11754810291833e-05 6.10573309907533e-05 1.15047415552936e-06 9.66304450678735e-05 3.68680608485457e-05 3.40714685135674e-05 -2.39402950275961e-05 4.08292834384543e-05 5.86274660507639e-06 3.68680608485457e-05 3.95576126452758e-05 1.91596255787792e-05 -6.94454730939804e-06 2.96909623571263e-05 4.17924004035436e-07 3.40714685135674e-05 1.91596255787792e-05 5.18395482251866e-05 885 889 0 22 0 885 892 0 33 0 0 0 0 0 0 1 7 0 2492 0 0 0 0 0 1719 +874 905 0.995050775569014 0.00590157675892719 0.0991923657912398 -0.011783755899861 -0.0192500581543524 0.99077267066303 0.134160166697497 -0.0253649937136473 -0.0974853286426151 -0.135405636732762 0.985982720051643 -0.00155504245433138 3.26327361574881e-05 -3.40151940851378e-05 2.68498866510984e-06 -1.27638191130529e-05 -4.29254552806432e-06 1.88268880425722e-07 -3.40151940851378e-05 5.51547555220635e-05 -3.89628151985828e-07 2.08893356963435e-05 1.06306190576798e-05 7.97050030279099e-06 2.68498866510984e-06 -3.89628151985828e-07 8.8485445739323e-06 -7.54412737366395e-07 4.3255476076498e-06 2.70509189598032e-06 -1.27638191130529e-05 2.08893356963435e-05 -7.54412737366395e-07 5.71953742824496e-05 1.58069247274371e-05 7.47163984234337e-06 -4.29254552806432e-06 1.06306190576798e-05 4.3255476076498e-06 1.58069247274371e-05 2.73720314797238e-05 9.6870721845818e-06 1.88268880425722e-07 7.97050030279099e-06 2.70509189598032e-06 7.47163984234337e-06 9.6870721845818e-06 3.38320272737104e-05 890 899 0 26 0 890 901 0 35 0 0 0 0 0 0 2 9 0 2538 0 0 0 0 0 2005 +874 915 0.995238452757965 0.00594139402401806 0.0972888585038525 -0.0117296321164175 -0.0192942489133546 0.990398104898713 0.136891657057347 -0.0228072631472233 -0.0955413738167962 -0.138116956417697 0.985796912269008 0.00274354899287562 5.72415965986291e-05 -6.14500449802261e-05 -3.72892783001398e-06 -2.33854672398701e-05 -1.97030617976566e-05 4.36471121222359e-06 -6.14500449802261e-05 9.49621084145533e-05 6.45256285342207e-06 5.39834149287828e-05 3.71798622739724e-05 1.05818754500151e-05 -3.72892783001398e-06 6.45256285342207e-06 1.03303252969194e-05 1.05546553407568e-06 6.18613481961173e-06 -5.70487896761859e-07 -2.33854672398701e-05 5.39834149287828e-05 1.05546553407568e-06 9.16339329513166e-05 3.42043904552272e-05 2.34308491853056e-05 -1.97030617976566e-05 3.71798622739724e-05 6.18613481961173e-06 3.42043904552272e-05 3.90957765255739e-05 1.43216986353907e-05 4.36471121222359e-06 1.05818754500151e-05 -5.70487896761859e-07 2.34308491853056e-05 1.43216986353907e-05 4.29432052594978e-05 871 872 0 22 0 871 874 0 28 0 0 0 0 0 0 0 5 0 2535 0 0 0 0 0 1736 +874 924 0.995009744550211 0.0053079287278008 0.0996365100891428 -0.0120046369650099 -0.0188154906529378 0.990650012063828 0.135124131484447 -0.025366125875786 -0.0979876806624816 -0.136324537375182 0.985806286725658 0.00276286053005368 4.32280485920216e-05 -4.06680808120518e-05 -1.7173646574258e-07 -2.11787056007803e-05 -1.26522982836262e-05 1.6465696198544e-06 -4.06680808120518e-05 5.69292933358926e-05 2.22897348992828e-06 3.44249605148961e-05 1.6533024438778e-05 7.24727900390986e-06 -1.7173646574258e-07 2.22897348992828e-06 1.00763933222127e-05 -1.74473659064461e-06 2.62183166927676e-06 -9.38757256484069e-08 -2.11787056007803e-05 3.44249605148961e-05 -1.74473659064461e-06 8.26408873119233e-05 2.61162213870388e-05 1.27112786677919e-05 -1.26522982836262e-05 1.6533024438778e-05 2.62183166927676e-06 2.61162213870388e-05 3.46686976199327e-05 8.42744845337525e-06 1.6465696198544e-06 7.24727900390986e-06 -9.38757256484069e-08 1.27112786677919e-05 8.42744845337525e-06 3.75169457605906e-05 874 874 0 25 0 874 876 0 36 0 0 0 0 0 0 0 6 0 2487 0 0 0 0 0 1702 +875 877 0.999997315730575 -0.00230875965868526 0.000195347082004935 0.00354602036845517 0.00230979478476426 0.999982339567622 -0.00547589270509215 0.00315466245390762 -0.000182701111918197 0.00547632921799202 0.999984988106622 -0.00234315278023037 3.46826702560521e-05 -3.65085929030498e-05 7.19527342795042e-07 -7.73407521245173e-06 -6.60968630586805e-06 1.44474574624588e-05 -3.65085929030498e-05 4.67276622818531e-05 -1.07075022385947e-07 1.81045767887988e-05 1.33071332904842e-05 -9.60613149249765e-06 7.19527342795042e-07 -1.07075022385947e-07 8.35971008927449e-06 1.84420504479255e-06 3.18907761716163e-06 -2.33491445255064e-06 -7.73407521245173e-06 1.81045767887988e-05 1.84420504479255e-06 5.13440788477547e-05 2.46137919974176e-05 1.00349778141918e-05 -6.60968630586805e-06 1.33071332904842e-05 3.18907761716163e-06 2.46137919974176e-05 2.83054682573773e-05 8.1945579875913e-06 1.44474574624588e-05 -9.60613149249765e-06 -2.33491445255064e-06 1.00349778141918e-05 8.1945579875913e-06 3.64837862901951e-05 761 758 0 8 0 759 769 0 19 0 0 0 0 0 0 6 18 0 2053 0 0 0 0 0 2132 +875 878 0.999974278576882 0.00201426824968714 0.00688366966536167 -0.00121172757006789 -0.00196767065524308 0.999975151595605 -0.00676937689441913 0.00320706995892561 -0.0068971339581027 0.00675565798161087 0.999953394228151 -0.00179945910962781 3.44688690367102e-05 -4.29181817457578e-05 3.46989355247489e-06 -1.5831999424873e-05 -8.96663483448369e-06 2.22572373119199e-05 -4.29181817457578e-05 9.6139557396672e-05 -3.91658231795713e-06 6.76419821943348e-05 3.91088159753381e-05 -2.42591982454697e-05 3.46989355247489e-06 -3.91658231795713e-06 8.71116215731115e-06 -1.28402859171757e-06 9.9664691655194e-07 -7.74035705611817e-07 -1.5831999424873e-05 6.76419821943348e-05 -1.28402859171757e-06 0.000106360306334377 4.60197527405046e-05 8.00501726166398e-08 -8.96663483448369e-06 3.91088159753381e-05 9.9664691655194e-07 4.60197527405046e-05 4.31996010960696e-05 -4.63262037932047e-07 2.22572373119199e-05 -2.42591982454697e-05 -7.74035705611817e-07 8.00501726166398e-08 -4.63262037932047e-07 4.46633510172901e-05 709 708 0 8 0 707 717 0 20 0 0 0 0 0 0 7 17 0 2033 0 0 0 0 0 2665 +875 879 0.99976609864062 0.00465247613949625 0.0211211381010709 0.00871567528531623 -0.00466102031302426 0.999989074258588 0.000355321112716754 0.00662311321314674 -0.0211192542139789 -0.000453684056348756 0.999776860740547 -0.00120972165058874 2.41663889318163e-05 -2.46963751231071e-05 3.51328038090389e-06 -8.33318073327302e-06 -4.17369310913299e-06 1.26132065059656e-05 -2.46963751231071e-05 3.2641472624653e-05 -2.27850675430401e-06 1.67073417027261e-05 1.07555978941992e-05 -8.9103577016359e-06 3.51328038090389e-06 -2.27850675430401e-06 8.01287737490645e-06 3.7250574806171e-06 3.96102015283136e-06 1.21672108986038e-06 -8.33318073327302e-06 1.67073417027261e-05 3.7250574806171e-06 4.78590783669744e-05 2.23109393097134e-05 5.62897783968288e-06 -4.17369310913299e-06 1.07555978941992e-05 3.96102015283136e-06 2.23109393097134e-05 2.73379158431845e-05 6.39030863054731e-06 1.26132065059656e-05 -8.9103577016359e-06 1.21672108986038e-06 5.62897783968288e-06 6.39030863054731e-06 3.02495394838896e-05 732 733 0 16 0 732 742 0 27 0 0 0 0 0 0 6 16 0 2046 0 0 0 0 0 2552 +875 922 0.994913608510837 -0.0021816485938673 0.100708251942713 -0.00659195984139619 -0.0119062916239065 0.990210241949421 0.139075220504 -0.0188422845468655 -0.100025755781751 -0.139566891302638 0.985147669657908 0.000973319298268287 3.83155570238459e-05 -4.16826493780945e-05 -2.52247129307867e-07 -1.02335065646328e-05 -7.64902359493523e-06 5.46191814375385e-06 -4.16826493780945e-05 6.28165607467644e-05 2.58387185933141e-06 2.54453847480103e-05 1.62323527839758e-05 9.23767860217016e-06 -2.52247129307867e-07 2.58387185933141e-06 1.04966934863204e-05 -2.21134524752297e-06 4.11682681118969e-06 8.97913169166433e-07 -1.02335065646328e-05 2.54453847480103e-05 -2.21134524752297e-06 7.18082955403936e-05 2.40360497195238e-05 2.01049754899127e-05 -7.64902359493523e-06 1.62323527839758e-05 4.11682681118969e-06 2.40360497195238e-05 3.09276000762027e-05 1.18959150419652e-05 5.46191814375385e-06 9.23767860217016e-06 8.97913169166433e-07 2.01049754899127e-05 1.18959150419652e-05 4.04273234875765e-05 858 859 0 15 0 855 863 0 23 0 0 0 0 0 0 6 14 0 2557 0 0 0 0 0 1793 +874 908 0.994216679887396 0.00484481629576851 0.10728336864931 -0.00802616236307521 -0.0195596474158587 0.99044202348884 0.136535776631251 -0.0221333183005711 -0.105596465976144 -0.137844571392536 0.984808743112569 0.0017773771393211 3.19864299712226e-05 -3.18436627305626e-05 2.80799653441241e-06 -1.67443762653706e-05 -8.51447400224395e-06 5.9411731087874e-06 -3.18436627305626e-05 5.03198181086962e-05 -1.6070659434107e-07 2.77320451541797e-05 1.58628111322463e-05 2.89951457271276e-06 2.80799653441241e-06 -1.6070659434107e-07 9.31984545962092e-06 2.44463773993102e-07 4.19953565617136e-06 2.37577548964283e-06 -1.67443762653706e-05 2.77320451541797e-05 2.44463773993102e-07 6.63813868968734e-05 2.29825827105688e-05 4.9084837144786e-06 -8.51447400224395e-06 1.58628111322463e-05 4.19953565617136e-06 2.29825827105688e-05 3.10118768874477e-05 6.79888979645138e-06 5.9411731087874e-06 2.89951457271276e-06 2.37577548964283e-06 4.9084837144786e-06 6.79888979645138e-06 2.99483319303118e-05 902 903 0 27 0 902 906 0 38 0 0 0 0 0 0 1 8 0 2485 0 0 0 0 0 2054 +874 910 0.994391845134459 0.0051981071186601 0.105630667954289 -0.00922995570947622 -0.0195659475958988 0.990591821966845 0.135443774117086 -0.0233662908928889 -0.103932824577998 -0.136750948569977 0.985138135512198 -0.000688285771144229 4.64103790314594e-05 -5.74534176143e-05 -3.11949018249073e-06 -1.64697725453612e-05 -1.48353023850176e-05 1.23415624129635e-05 -5.74534176143e-05 0.000140940094395699 1.12499579708238e-05 5.4686147262594e-05 3.17513501667069e-05 4.67142858510239e-06 -3.11949018249073e-06 1.12499579708238e-05 1.05948772403214e-05 2.39612784767215e-06 6.62735183274487e-06 1.41567067478731e-06 -1.64697725453612e-05 5.4686147262594e-05 2.39612784767215e-06 7.77906814174959e-05 2.81799219377048e-05 1.3331725757893e-05 -1.48353023850176e-05 3.17513501667069e-05 6.62735183274487e-06 2.81799219377048e-05 3.79747942648575e-05 6.76512540147566e-06 1.23415624129635e-05 4.67142858510239e-06 1.41567067478731e-06 1.3331725757893e-05 6.76512540147566e-06 3.78787051138325e-05 889 895 0 24 0 889 898 0 34 0 0 0 0 0 0 1 7 0 2519 0 0 0 0 0 2028 +875 920 0.994834093361629 -0.00302041022259907 0.101469225913246 -0.0110122807136049 -0.0109535101739897 0.990527596005833 0.136876229367172 -0.0234845565769375 -0.100921490774832 -0.137280583743636 0.985377538828033 0.00214167941272053 4.32366729184845e-05 -5.59331095385014e-05 -3.49510060616152e-06 -1.8133858166633e-05 -1.08974090035176e-05 7.37729417891116e-07 -5.59331095385014e-05 0.000132391104783652 1.12725606963058e-05 5.11885797137117e-05 2.57572796386308e-05 3.24859114582631e-05 -3.49510060616152e-06 1.12725606963058e-05 1.15969579682652e-05 9.31143547344837e-07 6.12680561286956e-06 2.10727623190738e-06 -1.8133858166633e-05 5.11885797137117e-05 9.31143547344837e-07 7.87734203565214e-05 2.66974538548493e-05 1.95675155455591e-05 -1.08974090035176e-05 2.57572796386308e-05 6.12680561286956e-06 2.66974538548493e-05 3.36137261052699e-05 9.18592220307592e-06 7.37729417891116e-07 3.24859114582631e-05 2.10727623190738e-06 1.95675155455591e-05 9.18592220307592e-06 4.97932449750969e-05 839 841 0 13 0 834 843 0 20 0 0 0 0 0 0 8 16 0 2310 0 0 0 0 0 1844 +874 909 0.99555680627243 0.00550852528169429 0.0940016044217303 -0.0178584215437244 -0.0181854232900341 0.990741098742053 0.134541315747806 -0.0253859975634405 -0.0923901286090717 -0.135652981583928 0.986439218970429 -0.00136711931176899 5.05177003242266e-05 -6.72167420437507e-05 -3.51150307476987e-06 -3.1919319549562e-05 -2.08396819333609e-05 1.42555795494881e-06 -6.72167420437507e-05 0.000154691480019641 8.02732834695813e-06 8.99801754467991e-05 4.68552867059438e-05 2.47407759958266e-05 -3.51150307476987e-06 8.02732834695813e-06 9.82580459154698e-06 1.05256559186295e-06 6.21028699165599e-06 -5.72273018038815e-07 -3.1919319549562e-05 8.99801754467991e-05 1.05256559186295e-06 0.000116343160629843 4.09212580861743e-05 2.82953439648729e-05 -2.08396819333609e-05 4.68552867059438e-05 6.21028699165599e-06 4.09212580861743e-05 3.96437075242128e-05 1.21540129097303e-05 1.42555795494881e-06 2.47407759958266e-05 -5.72273018038815e-07 2.82953439648729e-05 1.21540129097303e-05 4.34748500705087e-05 856 860 0 22 0 855 862 0 33 0 0 0 0 0 0 1 10 0 2505 0 0 0 0 0 1987 +874 904 0.995794461584723 0.00624673756902913 0.0914022349121513 -0.0153480417005569 -0.0186680466032194 0.990576506932155 0.135682305221094 -0.0242468226205184 -0.089693334831594 -0.136817989255192 0.986527213767037 0.00285700809376521 3.45634250563465e-05 -4.07760738261356e-05 -9.66038362091297e-07 -1.20407711697212e-05 -1.93037745696879e-06 1.97702214104473e-08 -4.07760738261356e-05 8.17300607664622e-05 4.41941481043464e-06 3.18789296423773e-05 1.22147292399476e-05 1.63911724791503e-05 -9.66038362091297e-07 4.41941481043464e-06 1.0464858910316e-05 -7.12334791493856e-07 4.55704621762669e-06 1.31705043160724e-06 -1.20407711697212e-05 3.18789296423773e-05 -7.12334791493856e-07 6.51166532352912e-05 1.21854335021684e-05 1.34721490626606e-05 -1.93037745696879e-06 1.22147292399476e-05 4.55704621762669e-06 1.21854335021684e-05 2.71366742309477e-05 1.1185911547923e-05 1.97702214104473e-08 1.63911724791503e-05 1.31705043160724e-06 1.34721490626606e-05 1.1185911547923e-05 4.20527419696986e-05 849 856 0 29 0 849 858 0 38 0 0 0 0 0 0 0 9 0 2521 0 0 0 0 0 1681 +874 911 0.99505013599039 0.00584854477124119 0.0992019223078117 -0.0151595926622599 -0.0191870939149544 0.99078958695155 0.134044208436905 -0.0248348658295906 -0.0975042680737876 -0.135284104433731 0.985997529811793 -0.000243738503233193 4.72382994983986e-05 -5.39188754846216e-05 -4.17499302234905e-06 -2.66856285138047e-05 -1.73578832400285e-05 3.9052449660254e-06 -5.39188754846216e-05 9.67775352319977e-05 6.164470513542e-06 6.0203850901828e-05 3.20346231221066e-05 1.76636396730551e-05 -4.17499302234905e-06 6.164470513542e-06 9.28685854350929e-06 6.30756034271835e-07 4.61220049626012e-06 -1.00146265425435e-06 -2.66856285138047e-05 6.0203850901828e-05 6.30756034271835e-07 9.28007259733656e-05 3.14468216777616e-05 2.45839648583181e-05 -1.73578832400285e-05 3.20346231221066e-05 4.61220049626012e-06 3.14468216777616e-05 3.53750144231617e-05 1.44747577984661e-05 3.9052449660254e-06 1.76636396730551e-05 -1.00146265425435e-06 2.45839648583181e-05 1.44747577984661e-05 4.2891360706278e-05 883 891 0 27 0 883 893 0 34 0 0 0 0 0 0 0 7 0 2545 0 0 0 0 0 1987 +875 926 0.995742614191787 -0.00208969398902112 0.0921535645622983 -0.0207261695495801 -0.0105194116328094 0.990635301664975 0.136128766519216 -0.0255459037973588 -0.0915750416948032 -0.136518615119609 0.986395802639295 0.00257249101164193 4.32048753732625e-05 -6.3445736819581e-05 -3.66486531140392e-06 -2.10473918824688e-05 -1.27411585672647e-05 1.39160104681021e-06 -6.3445736819581e-05 0.000172161688432987 1.31247857487839e-05 8.91157956394165e-05 4.41711354387006e-05 1.76816165991755e-05 -3.66486531140392e-06 1.31247857487839e-05 1.11152459154719e-05 4.49534395386301e-06 6.33128064746873e-06 -4.00584666268651e-07 -2.10473918824688e-05 8.91157956394165e-05 4.49534395386301e-06 0.000110215810212328 3.85231568642053e-05 2.96708598192554e-05 -1.27411585672647e-05 4.41711354387006e-05 6.33128064746873e-06 3.85231568642053e-05 3.64155193893859e-05 1.24491690098904e-05 1.39160104681021e-06 1.76816165991755e-05 -4.00584666268651e-07 2.96708598192554e-05 1.24491690098904e-05 4.28172232049242e-05 824 826 0 11 0 820 831 0 24 0 0 0 0 0 0 8 18 0 2503 0 0 0 0 0 2104 +874 906 0.995008636068592 0.00564929839389463 0.0996288089689801 -0.0146030218579133 -0.0190958175030464 0.990724770569783 0.134535418137164 -0.0241194675199054 -0.0979446981863293 -0.135766396457695 0.985887580655158 -0.000937480293564154 5.17528042822581e-05 -7.56422896980979e-05 -3.77828714370244e-06 -2.74973624809103e-05 -1.81443655714775e-05 1.55138403752772e-06 -7.56422896980979e-05 0.000195432201808766 1.41634242566127e-05 8.52754202974344e-05 4.4636741669318e-05 1.8263537024283e-05 -3.77828714370244e-06 1.41634242566127e-05 1.07090148687521e-05 2.83803106031432e-06 7.39810978466089e-06 1.18598140440934e-06 -2.74973624809103e-05 8.52754202974344e-05 2.83803106031432e-06 9.96362397762518e-05 3.34194274818931e-05 1.54886891021167e-05 -1.81443655714775e-05 4.4636741669318e-05 7.39810978466089e-06 3.34194274818931e-05 3.6620363318603e-05 1.05007008378509e-05 1.55138403752772e-06 1.8263537024283e-05 1.18598140440934e-06 1.54886891021167e-05 1.05007008378509e-05 3.78097997643577e-05 895 903 0 27 0 895 906 0 35 0 0 0 0 0 0 2 7 0 2532 0 0 0 0 0 2000 +875 913 0.994762878263137 -0.00271451297105206 0.102173614250304 -0.0100438557751952 -0.0115733490803962 0.990226689666088 0.138986188752711 -0.0191342351231035 -0.101552319622465 -0.139440792066995 0.985009335939018 0.000216991613653736 1.66947428028149e-05 -1.24276136192044e-05 5.58663334367526e-06 -4.98729452500148e-06 1.85006135914722e-06 3.72055704354898e-06 -1.24276136192044e-05 3.65476942584666e-05 -6.13558859503647e-07 1.08286473286473e-05 5.19635648483671e-06 4.64029416087267e-06 5.58663334367526e-06 -6.13558859503647e-07 1.02841419420569e-05 -1.16514683335804e-07 2.81775441365815e-06 1.46306709577191e-06 -4.98729452500148e-06 1.08286473286473e-05 -1.16514683335804e-07 6.21123532886968e-05 2.10644351842706e-05 6.40375659031992e-06 1.85006135914722e-06 5.19635648483671e-06 2.81775441365815e-06 2.10644351842706e-05 2.69172499968732e-05 7.70785191498506e-06 3.72055704354898e-06 4.64029416087267e-06 1.46306709577191e-06 6.40375659031992e-06 7.70785191498506e-06 2.64605248468206e-05 860 862 0 13 0 855 868 0 25 0 0 0 0 0 0 4 12 0 2470 0 0 0 0 0 1899 +875 921 0.995216409398478 -0.00229357391648247 0.0976679987646404 -0.0120966536708525 -0.0111666136820811 0.990501773523497 0.137045771133888 -0.0237125295477932 -0.0970546505989039 -0.137480821082421 0.985738007095003 0.00111618887350738 2.95274511980057e-05 -3.18461973454155e-05 2.17748534632248e-06 -1.44279755556833e-05 -6.25937413771683e-06 3.19124502008484e-06 -3.18461973454155e-05 6.594947884487e-05 9.15154308669217e-07 3.63856963388212e-05 1.44967621506151e-05 3.64422598132195e-06 2.17748534632248e-06 9.15154308669217e-07 9.59023101898456e-06 -1.64474929096951e-07 2.84306030647553e-06 1.59352892751411e-06 -1.44279755556833e-05 3.63856963388212e-05 -1.64474929096951e-07 7.89330205644004e-05 2.77327558723489e-05 1.00816249676876e-05 -6.25937413771683e-06 1.44967621506151e-05 2.84306030647553e-06 2.77327558723489e-05 3.10397324439847e-05 7.67283692739936e-06 3.19124502008484e-06 3.64422598132195e-06 1.59352892751411e-06 1.00816249676876e-05 7.67283692739936e-06 2.76836425677951e-05 822 819 0 15 0 818 826 0 27 0 0 0 0 0 0 6 15 0 2435 0 0 0 0 0 1945 +875 919 0.995319616223684 -0.00223593370518746 0.0966119152113513 -0.0119886200075681 -0.0111322274981736 0.990424100741313 0.137608772182919 -0.0216082038978839 -0.0959944533359518 -0.138040216137282 0.985763644925854 7.57228262911165e-05 5.56573780924729e-05 -6.22305157006603e-05 -4.04133838009132e-06 -2.75445341338846e-05 -1.95647188333918e-05 -5.9541448638574e-06 -6.22305157006603e-05 0.000116061282059606 7.70610229554313e-06 6.42165401050711e-05 3.72739052578992e-05 3.88382411092117e-05 -4.04133838009132e-06 7.70610229554313e-06 1.06041275265331e-05 2.28072074553909e-06 3.47659294284889e-06 -7.51184064688471e-08 -2.75445341338846e-05 6.42165401050711e-05 2.28072074553909e-06 9.96332117601859e-05 3.57299840262848e-05 4.09127218961058e-05 -1.95647188333918e-05 3.72739052578992e-05 3.47659294284889e-06 3.57299840262848e-05 4.33639364492635e-05 2.13532381850811e-05 -5.9541448638574e-06 3.88382411092117e-05 -7.51184064688471e-08 4.09127218961058e-05 2.13532381850811e-05 6.11795841420521e-05 833 837 0 13 0 831 840 0 23 0 0 0 0 0 0 8 18 0 2330 0 0 0 0 0 1765 +875 916 0.995584135217918 -0.00203337489640054 0.0938514522472631 -0.0141035982447315 -0.0108211691290011 0.99061477596357 0.136254423566089 -0.0236150211104523 -0.093247691666181 -0.136668324893431 0.986218351568126 -0.00163267420993556 3.89830630186683e-05 -4.32909751362157e-05 -2.40722433587889e-06 -1.25793625004077e-05 -6.86900062734685e-06 6.30147216865475e-07 -4.32909751362157e-05 7.9384113506055e-05 4.73473754948545e-06 3.36768949687233e-05 1.49887397874727e-05 2.105750941465e-05 -2.40722433587889e-06 4.73473754948545e-06 1.06237174541517e-05 -8.83257333188537e-07 3.18125584346566e-06 1.01773121715453e-07 -1.25793625004077e-05 3.36768949687233e-05 -8.83257333188537e-07 7.68867732153137e-05 1.66754325286578e-05 1.46313532543063e-05 -6.86900062734685e-06 1.49887397874727e-05 3.18125584346566e-06 1.66754325286578e-05 2.88506180930693e-05 8.57407314211033e-06 6.30147216865475e-07 2.105750941465e-05 1.01773121715453e-07 1.46313532543063e-05 8.57407314211033e-06 4.23187179954917e-05 843 843 0 11 0 838 846 0 19 0 0 0 0 0 0 4 11 0 2424 0 0 0 0 0 1732 +875 928 0.995488422931901 -0.00258398813984091 0.0948478930385402 -0.0170543840380467 -0.0105332399165507 0.990440751856162 0.137536060433111 -0.0227611575121946 -0.0942966100420242 -0.137914611509778 0.985945084305759 0.00165641024131461 5.21249219346344e-05 -6.63057317739397e-05 -5.66339684790805e-06 -1.91926303899059e-05 -1.55065455886853e-05 5.14507800240035e-06 -6.63057317739397e-05 0.00015196029660713 1.23209214714929e-05 6.59635472137038e-05 3.78808908249276e-05 1.45890337931758e-05 -5.66339684790805e-06 1.23209214714929e-05 1.13887598115468e-05 3.45805960210601e-06 7.81474006817518e-06 -1.15151052298224e-06 -1.91926303899059e-05 6.59635472137038e-05 3.45805960210601e-06 8.04453446532407e-05 2.41926454533889e-05 2.28872225840405e-05 -1.55065455886853e-05 3.78808908249276e-05 7.81474006817518e-06 2.41926454533889e-05 3.29231675220856e-05 8.08729739073764e-06 5.14507800240035e-06 1.45890337931758e-05 -1.15151052298224e-06 2.28872225840405e-05 8.08729739073764e-06 4.15115788171368e-05 822 823 0 13 0 816 827 0 24 0 0 0 0 0 0 6 15 0 2479 0 0 0 0 0 1776 +875 923 0.994991808662563 -0.00306661825241169 0.0999094417304737 -0.0113961490945355 -0.0107523708200696 0.990445777502249 0.137482902026811 -0.0208748465751786 -0.0993764922713045 -0.137868624713747 0.985452462122548 7.71043487629614e-05 3.73620541181411e-05 -3.71054284229479e-05 3.14504020858708e-06 -1.35053623888097e-05 -6.2803206222261e-06 7.33823323962535e-06 -3.71054284229479e-05 4.71756028422981e-05 -3.85327522761766e-07 1.93940814790867e-05 1.02390030473534e-05 5.81646637048117e-08 3.14504020858708e-06 -3.85327522761766e-07 1.15272493684628e-05 -8.01684368949474e-07 3.89590604882679e-06 3.59902684801087e-06 -1.35053623888097e-05 1.93940814790867e-05 -8.01684368949474e-07 7.07999601013608e-05 2.67286742620802e-05 9.65670909277176e-06 -6.2803206222261e-06 1.02390030473534e-05 3.89590604882679e-06 2.67286742620802e-05 3.22482726528146e-05 8.76112858580365e-06 7.33823323962535e-06 5.81646637048117e-08 3.59902684801087e-06 9.65670909277176e-06 8.76112858580365e-06 3.83676570263455e-05 861 863 0 12 0 853 865 0 25 0 0 0 0 0 0 6 16 0 2450 0 0 0 0 0 1799 +875 925 0.994894274911137 -0.00280284623434127 0.100883724168123 -0.0132015759435708 -0.0111685478889082 0.990416770224383 0.137658580540246 -0.0217091073242157 -0.100302768092892 -0.138082458376467 0.985328670749824 0.00120196648085915 3.24857340248017e-05 -3.22901896040986e-05 3.90348504753602e-06 -1.73037414813879e-05 -8.62739918184924e-06 1.02923867859683e-05 -3.22901896040986e-05 4.36007512060868e-05 -1.47956528823981e-06 2.5177221384181e-05 1.33488214971963e-05 -3.95623812078462e-06 3.90348504753602e-06 -1.47956528823981e-06 9.60987836246818e-06 1.71595442637801e-06 4.558020643699e-06 4.13530660065354e-06 -1.73037414813879e-05 2.5177221384181e-05 1.71595442637801e-06 6.2803922381022e-05 2.59238093996449e-05 7.43519848287324e-06 -8.62739918184924e-06 1.33488214971963e-05 4.558020643699e-06 2.59238093996449e-05 2.91105392451584e-05 7.17050663400748e-06 1.02923867859683e-05 -3.95623812078462e-06 4.13530660065354e-06 7.43519848287324e-06 7.17050663400748e-06 3.48212340310171e-05 850 853 0 12 0 848 858 0 22 0 0 0 0 0 0 9 18 0 2461 0 0 0 0 0 1992 +875 912 0.994949371211296 -0.00221614792288424 0.100353562042565 -0.00940366755784991 -0.011857096100284 0.990161978967985 0.139422611789742 -0.0210306004695048 -0.0996752627200734 -0.139908341761985 0.985134761292635 -0.000810327259380721 5.64440452383812e-05 -5.80063965673899e-05 -7.39806666629523e-06 -1.75576062317082e-05 -2.13887838346255e-05 1.22580822105204e-05 -5.80063965673899e-05 7.68063554415598e-05 9.38894421442445e-06 3.38873200695861e-05 3.22080023371686e-05 -2.26600264844538e-06 -7.39806666629523e-06 9.38894421442445e-06 1.05457992339292e-05 1.03060680304379e-06 7.6980426629229e-06 -2.94923847496921e-06 -1.75576062317082e-05 3.38873200695861e-05 1.03060680304379e-06 7.12597582282675e-05 3.09161484734174e-05 1.43740832838899e-05 -2.13887838346255e-05 3.22080023371686e-05 7.6980426629229e-06 3.09161484734174e-05 3.88070205299352e-05 8.33934501983835e-06 1.22580822105204e-05 -2.26600264844538e-06 -2.94923847496921e-06 1.43740832838899e-05 8.33934501983835e-06 3.79886764252459e-05 844 845 0 12 0 836 846 0 22 0 0 0 0 0 0 8 16 0 2488 0 0 0 0 0 2003 +875 927 0.995415015169578 -0.00285691637777855 0.0956074557958678 -0.021664804581384 -0.0102839624637268 0.990563111451771 0.136671000387907 -0.0262484626257506 -0.095095676510518 -0.137027589411027 0.985992014191398 0.0035227874572982 4.51323022349365e-05 -6.27585301162389e-05 -5.96817055792209e-06 -1.65260018636172e-05 -1.08536222286046e-05 1.04502383325202e-05 -6.27585301162389e-05 0.000142900302171155 1.30046258766369e-05 5.78350728082776e-05 3.01872881465387e-05 -6.78326382627141e-08 -5.96817055792209e-06 1.30046258766369e-05 1.04411782677106e-05 4.7127634516357e-06 4.46950051033124e-06 -1.82025427386644e-06 -1.65260018636172e-05 5.78350728082776e-05 4.7127634516357e-06 7.39343549213634e-05 2.0946493581543e-05 1.26373865458778e-05 -1.08536222286046e-05 3.01872881465387e-05 4.46950051033124e-06 2.0946493581543e-05 2.76200027976548e-05 5.02648715402342e-06 1.04502383325202e-05 -6.78326382627141e-08 -1.82025427386644e-06 1.26373865458778e-05 5.02648715402342e-06 4.23140983069438e-05 826 829 0 11 0 823 834 0 21 0 0 0 0 0 0 7 16 0 2545 0 0 0 0 0 2077 +875 917 0.995920022526563 -0.000758467043354261 0.0902370958000846 -0.00922197617146845 -0.0117686212596942 0.990332912049897 0.138210791418095 -0.0183419864584202 -0.0894695941889499 -0.13870886070657 0.98628344996616 -0.0018300585802386 4.37488211624863e-05 -5.10692459763876e-05 -1.61874858676603e-06 -1.689011523586e-05 -1.61060379867043e-05 6.96068154834928e-06 -5.10692459763876e-05 0.000139946976178072 1.2382682530576e-05 5.10575849838118e-05 2.27663070012152e-05 1.37610999612033e-05 -1.61874858676603e-06 1.2382682530576e-05 1.26123720585902e-05 -1.12938828538163e-06 2.28484855385344e-06 1.7381425647699e-06 -1.689011523586e-05 5.10575849838118e-05 -1.12938828538163e-06 0.000115585826827769 5.05333574882081e-05 1.88746513144258e-05 -1.61060379867043e-05 2.27663070012152e-05 2.28484855385344e-06 5.05333574882081e-05 5.37515096607051e-05 5.7833839547551e-06 6.96068154834928e-06 1.37610999612033e-05 1.7381425647699e-06 1.88746513144258e-05 5.7833839547551e-06 4.34142941829148e-05 826 828 0 16 0 822 833 0 26 0 0 0 0 0 0 8 19 0 2218 0 0 0 0 0 2136 +875 918 0.995135066124442 -0.00221454632337246 0.0984951570082734 -0.0100490597561744 -0.0113320317277417 0.99053897317258 0.136763034783278 -0.0240234804025386 -0.0978661597612998 -0.137213841906684 0.985694971257733 0.00109452794225722 5.76689917689556e-05 -6.95580887467432e-05 -5.10036930052048e-06 -1.99967453207204e-05 -1.61327030905938e-05 1.24449709531648e-05 -6.95580887467432e-05 0.000146226581140655 1.03861917664937e-05 6.52626837952613e-05 3.92975042299044e-05 1.54144065444637e-06 -5.10036930052048e-06 1.03861917664937e-05 1.12931661831263e-05 7.83563594717994e-07 5.89078038769056e-06 -2.02972003269222e-06 -1.99967453207204e-05 6.52626837952613e-05 7.83563594717994e-07 8.54928473100563e-05 2.97373477811254e-05 1.79793013993217e-05 -1.61327030905938e-05 3.92975042299044e-05 5.89078038769056e-06 2.97373477811254e-05 4.00036892292051e-05 8.75763846684033e-06 1.24449709531648e-05 1.54144065444637e-06 -2.02972003269222e-06 1.79793013993217e-05 8.75763846684033e-06 4.06319580345556e-05 837 838 0 13 0 832 843 0 25 0 0 0 0 0 0 8 19 0 2274 0 0 0 0 0 1864 +875 915 0.995747984754111 -0.00133482055932611 0.0921095495168753 -0.0137485053306231 -0.0113922356733358 0.990435066520913 0.13750853054294 -0.0219489935572952 -0.0914120770166092 -0.137973175870492 0.986208514927609 -4.32826717423568e-05 5.62890225474788e-05 -6.23362338919177e-05 -3.55123250728467e-06 -3.36143800445428e-05 -2.3110345026261e-05 6.6804055369375e-06 -6.23362338919177e-05 9.89746624353715e-05 7.38234837366293e-06 5.86666072029603e-05 3.82706152089237e-05 1.08806209361297e-05 -3.55123250728467e-06 7.38234837366293e-06 1.09598203082107e-05 2.69730934185684e-07 6.23301007147283e-06 -2.37189748638953e-07 -3.36143800445428e-05 5.86666072029603e-05 2.69730934185684e-07 0.000117500177579436 4.82350988715433e-05 2.69492522495851e-05 -2.3110345026261e-05 3.82706152089237e-05 6.23301007147283e-06 4.82350988715433e-05 4.57464980036117e-05 1.44521352305427e-05 6.6804055369375e-06 1.08806209361297e-05 -2.37189748638953e-07 2.69492522495851e-05 1.44521352305427e-05 4.71498175296922e-05 831 829 0 12 0 826 833 0 20 0 0 0 0 0 0 7 15 0 2575 0 0 0 0 0 2109 +875 908 0.995069911438288 -0.00297569427563522 0.0991313098560431 -0.0103790322607984 -0.0107498848553518 0.990424470331191 0.137636508764123 -0.0215206182534902 -0.0985916392286565 -0.138023598753104 0.985509601607944 -0.00170940386916533 3.61092165448652e-05 -3.4003081294268e-05 5.62749030575964e-06 -1.47102498888282e-05 -8.27924569686307e-06 1.4277837934818e-06 -3.4003081294268e-05 5.7601902548767e-05 1.10914976693345e-07 2.3245874449529e-05 1.39823240676664e-05 1.14663494677278e-05 5.62749030575964e-06 1.10914976693345e-07 1.22018018098509e-05 7.31991466601816e-07 4.70752852520947e-06 3.42745186123289e-06 -1.47102498888282e-05 2.3245874449529e-05 7.31991466601816e-07 6.15384105555982e-05 1.73710044169944e-05 5.69716813842556e-06 -8.27924569686307e-06 1.39823240676664e-05 4.70752852520947e-06 1.73710044169944e-05 2.74503132825712e-05 9.49606391047229e-06 1.4277837934818e-06 1.14663494677278e-05 3.42745186123289e-06 5.69716813842556e-06 9.49606391047229e-06 3.66235194662273e-05 848 847 0 13 0 845 853 0 24 0 0 0 0 0 0 8 17 0 2519 0 0 0 0 0 1807 +875 906 0.995252430604031 -0.00285677482671171 0.0972853442937698 -0.0160244157134156 -0.0105874414377322 0.990459499888616 0.137396816426707 -0.0226868863954608 -0.0967497052221373 -0.137774518391396 0.98572697874282 9.90248114375663e-05 3.93434090736033e-05 -4.71996746093861e-05 -9.43568438323941e-07 -1.57741171895406e-05 -1.08246927316052e-05 1.23846385006086e-05 -4.71996746093861e-05 8.61727544283971e-05 4.80015410084936e-06 3.77084223127766e-05 2.41586234842924e-05 -7.29607373915095e-06 -9.43568438323941e-07 4.80015410084936e-06 1.01784506342003e-05 7.39633639682445e-07 4.96038157783252e-06 -3.0772638691298e-07 -1.57741171895406e-05 3.77084223127766e-05 7.39633639682445e-07 7.17906159790861e-05 2.82701748144881e-05 9.04215224245026e-06 -1.08246927316052e-05 2.41586234842924e-05 4.96038157783252e-06 2.82701748144881e-05 3.26252449640921e-05 6.19619785538003e-06 1.23846385006086e-05 -7.29607373915095e-06 -3.0772638691298e-07 9.04215224245026e-06 6.19619785538003e-06 3.53905061489912e-05 846 850 0 12 0 842 854 0 24 0 0 0 0 0 0 7 17 0 2570 0 0 0 0 0 1881 +875 924 0.995810933145723 -0.0017802016285192 0.0914189056465174 -0.0160297229459116 -0.0106883883534191 0.99068977631657 0.135718552365661 -0.0234938355667582 -0.0908093815739956 -0.13612713904283 0.986520683125378 -0.000627807437648159 3.45560222242332e-05 -4.16497525863586e-05 1.50950527699977e-07 -2.85371972160043e-05 -1.52470278110037e-05 -4.42214048675154e-06 -4.16497525863586e-05 7.59223626834803e-05 1.56758531135224e-06 6.4839564561802e-05 3.10078589920372e-05 1.89010095531998e-05 1.50950527699977e-07 1.56758531135224e-06 9.84715608095032e-06 -2.65374292259147e-06 4.41111910459932e-06 -5.1946433216899e-07 -2.85371972160043e-05 6.4839564561802e-05 -2.65374292259147e-06 0.000132233218358082 5.01214489031659e-05 3.53735175079024e-05 -1.52470278110037e-05 3.10078589920372e-05 4.41111910459932e-06 5.01214489031659e-05 4.30812544011316e-05 1.8913588205825e-05 -4.42214048675154e-06 1.89010095531998e-05 -5.1946433216899e-07 3.53735175079024e-05 1.8913588205825e-05 4.66420824829234e-05 831 831 0 14 0 829 835 0 23 0 0 0 0 0 0 8 13 0 2527 0 0 0 0 0 2091 +875 910 0.995095550041741 -0.00204090972893909 0.0988973254168374 -0.00965045274305497 -0.011853567567274 0.990122599539489 0.139702293528393 -0.0205036093375847 -0.098205596699239 -0.14018941674978 0.985242400736135 -0.00183594112152403 4.70723109318801e-05 -6.13898964566916e-05 4.81705788129519e-07 -3.1637242914459e-05 -1.87623480884454e-05 7.36274057949737e-06 -6.13898964566916e-05 0.000124099727831641 4.37346128759192e-06 7.13836272329376e-05 4.2781537578553e-05 5.82215789290669e-06 4.81705788129519e-07 4.37346128759192e-06 9.90296760230379e-06 2.28242464228614e-06 6.14784399238842e-06 9.41332319980169e-07 -3.1637242914459e-05 7.13836272329376e-05 2.28242464228614e-06 9.85522603381344e-05 3.90926142993646e-05 1.34044792073283e-05 -1.87623480884454e-05 4.2781537578553e-05 6.14784399238842e-06 3.90926142993646e-05 3.78412840889243e-05 8.07518316507728e-06 7.36274057949737e-06 5.82215789290669e-06 9.41332319980169e-07 1.34044792073283e-05 8.07518316507728e-06 3.34649851498615e-05 841 845 0 12 0 839 851 0 23 0 0 0 0 0 0 7 15 0 2534 0 0 0 0 0 1863 +875 911 0.995384828488892 -0.00189155774504455 0.0959451156830594 -0.0128737507786752 -0.0114746686471782 0.990286484399911 0.138567711947273 -0.020986978413765 -0.0952752601338666 -0.139029136601513 0.985694437430922 0.000936542867309305 4.9433623246519e-05 -5.39760319338192e-05 -2.28354107033006e-06 -2.11372284713075e-05 -1.48284902628531e-05 3.47756369894298e-06 -5.39760319338192e-05 7.71556490164995e-05 4.61663706030003e-06 3.52721738729314e-05 2.42530575178e-05 9.48744430316502e-06 -2.28354107033006e-06 4.61663706030003e-06 1.03635463418794e-05 -9.45487255482597e-08 4.68672874507996e-06 2.11939486662005e-07 -2.11372284713075e-05 3.52721738729314e-05 -9.45487255482597e-08 6.94806940789557e-05 2.21343979198826e-05 1.41633446612224e-05 -1.48284902628531e-05 2.42530575178e-05 4.68672874507996e-06 2.21343979198826e-05 2.97185634437832e-05 9.17158755248556e-06 3.47756369894298e-06 9.48744430316502e-06 2.11939486662005e-07 1.41633446612224e-05 9.17158755248556e-06 4.24773456062028e-05 854 858 0 14 0 849 861 0 24 0 0 0 0 0 0 8 18 0 2592 0 0 0 0 0 1867 +875 909 0.996190324942063 -0.00201014091824961 0.0871825431225529 -0.018121810781094 -0.0098924523632365 0.99067622753163 0.135877708215654 -0.0231728987775023 -0.0866428062684266 -0.136222507454481 0.986882187793835 2.73523632459732e-05 4.5056746147231e-05 -5.07694112979935e-05 -1.80796320703833e-06 -8.49241875077405e-06 -5.93702831125822e-06 7.15868957085013e-06 -5.07694112979935e-05 0.000100685731948858 7.20357387177236e-06 2.7946752257624e-05 1.41330337411993e-05 6.04736121439438e-06 -1.80796320703833e-06 7.20357387177236e-06 1.05517741934554e-05 -7.57296521270281e-07 5.05150670554893e-06 -6.79153456882681e-08 -8.49241875077405e-06 2.7946752257624e-05 -7.57296521270281e-07 7.23110056504187e-05 2.14310358194376e-05 1.38325104464685e-05 -5.93702831125822e-06 1.41330337411993e-05 5.05150670554893e-06 2.14310358194376e-05 2.70993969634728e-05 6.51678859062902e-06 7.15868957085013e-06 6.04736121439438e-06 -6.79153456882681e-08 1.38325104464685e-05 6.51678859062902e-06 3.69011091776101e-05 830 829 0 12 0 825 832 0 22 0 0 0 0 0 0 6 17 0 2493 0 0 0 0 0 1859 +875 904 0.995690403657618 -0.00126414683297905 0.0927309117657881 -0.0122622053885364 -0.0116626011864051 0.990262144813182 0.138725874600105 -0.0205441437773981 -0.0920032814506992 -0.13920950571991 0.985979771455541 -0.000206212097719798 4.57164900202426e-05 -5.92112476739193e-05 -4.5745668831261e-06 -1.90059394704558e-05 -1.24330173114551e-05 7.71448670362722e-06 -5.92112476739193e-05 0.000140536882676669 1.41533436846391e-05 6.25596642133277e-05 3.34535462571043e-05 9.70712013999947e-06 -4.5745668831261e-06 1.41533436846391e-05 1.23321838212035e-05 2.44812499987757e-06 6.50942890042256e-06 -2.09823489064782e-07 -1.90059394704558e-05 6.25596642133277e-05 2.44812499987757e-06 0.000109458749195228 3.48032108291118e-05 1.99627229581635e-05 -1.24330173114551e-05 3.34535462571043e-05 6.50942890042256e-06 3.48032108291118e-05 3.49074414837645e-05 9.18881275064746e-06 7.71448670362722e-06 9.70712013999947e-06 -2.09823489064782e-07 1.99627229581635e-05 9.18881275064746e-06 4.63995489190891e-05 792 797 0 15 0 792 804 0 25 0 0 0 0 0 0 8 17 0 2515 0 0 0 0 0 2083 +875 929 0.994278987432312 -0.0260733465972955 0.103583182746011 -0.01901823140163 0.00954683523817722 0.987561281463789 0.156944491112413 -0.0242424275893853 -0.106386808804058 -0.155057718127207 0.982160348905245 -0.00553197455438393 3.90802233731961e-05 -3.80355562510138e-05 -7.13256141564919e-06 -3.24374811514864e-06 -7.09842064028183e-06 1.2445944469092e-05 -3.80355562510138e-05 5.84636364319686e-05 7.37617408550459e-06 2.30408796009966e-05 1.63615721060964e-05 -5.76463838463752e-06 -7.13256141564919e-06 7.37617408550459e-06 1.17297684608625e-05 -1.69710444845135e-06 3.23991086952838e-06 -7.43160095193349e-06 -3.24374811514864e-06 2.30408796009966e-05 -1.69710444845135e-06 6.62950494020327e-05 2.16405432383395e-05 1.00684759424493e-05 -7.09842064028183e-06 1.63615721060964e-05 3.23991086952838e-06 2.16405432383395e-05 2.61191708907953e-05 1.05582205758633e-06 1.2445944469092e-05 -5.76463838463752e-06 -7.43160095193349e-06 1.00684759424493e-05 1.05582205758633e-06 3.26190367259589e-05 888 886 0 1 0 892 896 0 11 0 0 0 0 0 0 18 30 0 2504 0 0 0 0 0 1760 +875 905 0.995377613842473 -0.00192199763976473 0.0960193302743668 -0.0120628632016435 -0.0114098694007743 0.990352110677623 0.138103264829742 -0.0217331270170978 -0.0953583805521175 -0.138560466228464 0.985752391048091 0.000671087248823652 2.2455842375524e-05 -2.15088019256889e-05 4.40649617567666e-06 -5.16770487899662e-06 2.90484480895759e-07 4.77895580002477e-06 -2.15088019256889e-05 4.32092250820153e-05 -5.59051306929397e-07 6.90953943211356e-06 3.10236396756646e-06 9.03489010743403e-07 4.40649617567666e-06 -5.59051306929397e-07 9.584655237637e-06 -1.0746235339576e-06 3.63839379666187e-06 6.5499574029995e-07 -5.16770487899662e-06 6.90953943211356e-06 -1.0746235339576e-06 5.29377074643176e-05 1.49925978136184e-05 3.14090250733716e-07 2.90484480895759e-07 3.10236396756646e-06 3.63839379666187e-06 1.49925978136184e-05 2.37913391541707e-05 2.68863840571992e-06 4.77895580002477e-06 9.03489010743403e-07 6.5499574029995e-07 3.14090250733716e-07 2.68863840571992e-06 2.65943161471684e-05 850 854 0 13 0 844 856 0 23 0 0 0 0 0 0 6 16 0 2574 0 0 0 0 0 1891 +876 880 0.99985556371684 0.00554184717103076 0.0160667244456444 0.00202944654644807 -0.00559539892085151 0.999978933320538 0.00329004954896884 0.0031441824172872 -0.016048153021325 -0.00337947407906536 0.999865508925852 -0.00169724193981485 4.71219641106131e-05 -7.23775093360253e-05 5.61476348933748e-06 -4.31708130270289e-05 -2.39496309456951e-05 2.59280368608583e-05 -7.23775093360253e-05 0.000153702319010003 -9.28294368427555e-06 0.00012797112816244 6.68695761807202e-05 -3.83663555989289e-05 5.61476348933748e-06 -9.28294368427555e-06 9.55808714488788e-06 -9.21134292682309e-06 -6.90994157109909e-07 5.4827996016977e-07 -4.31708130270289e-05 0.00012797112816244 -9.21134292682309e-06 0.000185474658078141 8.00825510000289e-05 -1.38826793756174e-05 -2.39496309456951e-05 6.68695761807202e-05 -6.90994157109909e-07 8.00825510000289e-05 5.79891650578748e-05 -6.62854056201479e-06 2.59280368608583e-05 -3.83663555989289e-05 5.4827996016977e-07 -1.38826793756174e-05 -6.62854056201479e-06 4.46938081417334e-05 712 709 0 9 0 708 719 0 19 0 0 0 0 0 0 4 16 0 2089 0 0 0 0 0 2118 +876 878 0.99998201628005 0.00382349202403588 0.00462039232397683 -0.00117928036521531 -0.00378876434381269 0.999964684273879 -0.00750169779373375 0.00174534839708136 -0.00464891183314801 0.00748405730760997 0.999961187499287 -0.00348113014686799 3.57713003165618e-05 -4.05089913237154e-05 2.87425797737998e-06 -2.02255588292492e-05 -1.10613800257715e-05 1.92307285614435e-05 -4.05089913237154e-05 6.51716141566637e-05 -2.32790059749063e-06 4.73278143328031e-05 2.75481027453633e-05 -2.30142980095704e-05 2.87425797737998e-06 -2.32790059749063e-06 9.15356478918896e-06 -5.68227857870635e-07 1.85880508099568e-06 1.54958902302027e-06 -2.02255588292492e-05 4.73278143328031e-05 -5.68227857870635e-07 0.000106539565661692 4.78622821487178e-05 -4.19941808564359e-06 -1.10613800257715e-05 2.75481027453633e-05 1.85880508099568e-06 4.78622821487178e-05 4.65820944170053e-05 8.86429842245474e-07 1.92307285614435e-05 -2.30142980095704e-05 1.54958902302027e-06 -4.19941808564359e-06 8.86429842245474e-07 4.15823750753862e-05 736 733 0 9 0 732 739 0 15 0 0 0 0 0 0 7 18 0 2048 0 0 0 0 0 2151 +875 907 0.996006286989438 -0.00144938265130671 0.0892713591665517 -0.0141773227649076 -0.0108450514770893 0.990500554432986 0.137080401686043 -0.0213677189470132 -0.0886220127054936 -0.137501094387927 0.986529060852315 0.000516573826318698 4.77377117201029e-05 -5.73252310020794e-05 -1.14019701443555e-06 -1.49141007626997e-05 -8.52678465726959e-06 8.33858119551245e-06 -5.73252310020794e-05 0.000103527084996411 4.50297245072222e-06 3.87428109311367e-05 2.19481235334768e-05 3.83738852733212e-06 -1.14019701443555e-06 4.50297245072222e-06 1.13703417312718e-05 -2.37802456328853e-06 4.08074687809239e-06 -3.27883620529322e-06 -1.49141007626997e-05 3.87428109311367e-05 -2.37802456328853e-06 8.21655932076046e-05 2.78119531150161e-05 1.71017802074236e-05 -8.52678465726959e-06 2.19481235334768e-05 4.08074687809239e-06 2.78119531150161e-05 3.17208234984422e-05 7.50306490032964e-06 8.33858119551245e-06 3.83738852733212e-06 -3.27883620529322e-06 1.71017802074236e-05 7.50306490032964e-06 4.34565342759558e-05 834 835 0 11 0 828 837 0 22 0 0 0 0 0 0 4 15 0 2583 0 0 0 0 0 1871 +876 879 0.999847816053074 0.00611634917023686 0.0163381457554587 0.00340795654942439 -0.00608808382553614 0.999979884639922 -0.00177919950009486 0.00297333862756165 -0.0163486993131599 0.0016794607335795 0.999864940600685 -0.00156938146992652 3.72305097284159e-05 -4.07632652711532e-05 5.05362293110359e-06 -2.4015906625311e-05 -1.18995688939341e-05 2.3545830441546e-05 -4.07632652711532e-05 5.88957213760307e-05 -4.9305792423397e-06 4.55538998972604e-05 2.60860228351859e-05 -1.96424639481786e-05 5.05362293110359e-06 -4.9305792423397e-06 8.489819695641e-06 -1.82023690749004e-07 -3.1723604254449e-07 2.04252229215773e-06 -2.4015906625311e-05 4.55538998972604e-05 -1.82023690749004e-07 9.57773434503226e-05 4.66225229604231e-05 -2.68779612711974e-06 -1.18995688939341e-05 2.60860228351859e-05 -3.1723604254449e-07 4.66225229604231e-05 4.24120383284449e-05 1.39243663005918e-06 2.3545830441546e-05 -1.96424639481786e-05 2.04252229215773e-06 -2.68779612711974e-06 1.39243663005918e-06 3.95197697399451e-05 729 727 0 11 0 729 735 0 21 0 0 0 0 0 0 5 16 0 2048 0 0 0 0 0 2538 +876 920 0.995092075177596 -0.00101878824278595 0.0989480873451457 -0.0127675295949324 -0.0125225225983909 0.990611165315002 0.136134880104354 -0.0268582769854543 -0.0981577727259487 -0.136705820006942 0.985736562388608 0.00155967820773753 4.1499807059611e-05 -4.66021372086436e-05 -5.73567245773156e-06 4.27797209204308e-07 -3.90561238871804e-06 3.93381876056038e-06 -4.66021372086436e-05 7.90696538426988e-05 9.45143172796849e-06 1.5152021281666e-05 7.58322545673242e-06 7.01281059908668e-06 -5.73567245773156e-06 9.45143172796849e-06 1.23411613983831e-05 -3.18298067843184e-06 2.37900981323137e-06 -1.11803852442751e-06 4.27797209204308e-07 1.5152021281666e-05 -3.18298067843184e-06 6.43440555398375e-05 1.12703223600434e-05 1.35404427977243e-05 -3.90561238871804e-06 7.58322545673242e-06 2.37900981323137e-06 1.12703223600434e-05 2.91542145069092e-05 5.81759924841789e-06 3.93381876056038e-06 7.01281059908668e-06 -1.11803852442751e-06 1.35404427977243e-05 5.81759924841789e-06 3.69281438577007e-05 845 847 0 16 0 841 848 0 20 0 0 0 0 0 0 2 9 0 2314 0 0 0 0 0 1651 +876 921 0.995214889763302 -0.000506472344633273 0.0977090921009045 -0.0134667511958519 -0.0131174534465221 0.990241882927167 0.138740569812647 -0.0242823476998315 -0.0968259036027924 -0.139358375358727 0.985496822728962 0.00156193107893022 2.79402074846696e-05 -2.4848830255445e-05 4.2216206512071e-06 -1.61189757329805e-05 -8.0904748429802e-06 -3.46528894086203e-06 -2.4848830255445e-05 3.95639110682224e-05 -2.37489633096304e-06 2.15725139283446e-05 1.14766110432665e-05 9.39864335901803e-06 4.2216206512071e-06 -2.37489633096304e-06 8.53165736692479e-06 5.51597499090097e-07 1.43642457783251e-06 2.01622621209435e-06 -1.61189757329805e-05 2.15725139283446e-05 5.51597499090097e-07 6.78350937076572e-05 2.30491877640562e-05 1.49992217330666e-05 -8.0904748429802e-06 1.14766110432665e-05 1.43642457783251e-06 2.30491877640562e-05 3.2677738040736e-05 1.01317662655672e-05 -3.46528894086203e-06 9.39864335901803e-06 2.01622621209435e-06 1.49992217330666e-05 1.01317662655672e-05 3.35601312394458e-05 843 842 0 17 0 839 845 0 23 0 0 0 0 0 0 2 12 0 2448 0 0 0 0 0 1955 +875 903 0.99507648271085 -0.00182323164923179 0.0990932358042512 -0.00886487940268719 -0.0120958835705234 0.990122516926061 0.139682107217244 -0.018737863367496 -0.0983691168835627 -0.140193000190289 0.985225577997848 0.00130523732202465 3.58178606610507e-05 -3.42321110721053e-05 -3.2728468619541e-07 -5.21445330430998e-06 -4.09622069309857e-06 4.26090337521278e-06 -3.42321110721053e-05 5.77349301096648e-05 5.14249276291663e-06 1.50088809270637e-05 9.25647513827881e-06 7.02643457267863e-06 -3.2728468619541e-07 5.14249276291663e-06 1.13797257282616e-05 -1.76529004891768e-06 4.29614490065615e-06 1.63343512092171e-06 -5.21445330430998e-06 1.50088809270637e-05 -1.76529004891768e-06 7.19907659514481e-05 2.2565367060204e-05 1.49334173714207e-05 -4.09622069309857e-06 9.25647513827881e-06 4.29614490065615e-06 2.2565367060204e-05 2.93239845006507e-05 1.01952506895815e-05 4.26090337521278e-06 7.02643457267863e-06 1.63343512092171e-06 1.49334173714207e-05 1.01952506895815e-05 3.4573573815981e-05 842 844 0 12 0 840 850 0 25 0 0 0 0 0 0 6 15 0 2490 0 0 0 0 0 1918 +876 927 0.995854288523736 -0.000633802003999576 0.0909606196323639 -0.0239397570679999 -0.0118234720692081 0.990590451879192 0.136347945177064 -0.0282273946742072 -0.0901911389057291 -0.1368581562816 0.986476255934267 0.000327911606996734 4.31442128224984e-05 -5.01675733232552e-05 -4.78087070175218e-06 -1.16891461471395e-05 -9.44073423066388e-06 1.1449825934242e-05 -5.01675733232552e-05 0.000108584602190847 9.16314079751979e-06 4.16483359289711e-05 2.13269875331599e-05 3.55224205341187e-06 -4.78087070175218e-06 9.16314079751979e-06 1.09258074139647e-05 2.57486873648958e-06 3.29551996005879e-06 -1.55255457553451e-06 -1.16891461471395e-05 4.16483359289711e-05 2.57486873648958e-06 5.80610379439587e-05 1.10081762842023e-05 1.56744737227553e-05 -9.44073423066388e-06 2.13269875331599e-05 3.29551996005879e-06 1.10081762842023e-05 2.60883391201153e-05 5.80952615456481e-06 1.1449825934242e-05 3.55224205341187e-06 -1.55255457553451e-06 1.56744737227553e-05 5.80952615456481e-06 4.31806822037867e-05 844 849 0 15 0 841 851 0 21 0 0 0 0 0 0 4 14 0 2565 0 0 0 0 0 1759 +876 926 0.996111617403973 -0.000201939665948074 0.088099971017095 -0.0250010296638724 -0.0117949129338442 0.990689176234258 0.135631250533092 -0.0287851685852459 -0.0873070770426126 -0.136142995826662 0.986834615822538 1.53439501471091e-05 4.1464621930745e-05 -4.92440605610768e-05 -7.7675168816872e-07 -2.11391630336902e-05 -1.47826681497396e-05 3.81890173114695e-06 -4.92440605610768e-05 9.83521431837391e-05 4.43664273063983e-06 5.69533973657441e-05 2.97313238183024e-05 9.69389603111743e-06 -7.7675168816872e-07 4.43664273063983e-06 1.01751834309409e-05 2.64964487288037e-06 4.05246251565576e-06 1.5401451867182e-06 -2.11391630336902e-05 5.69533973657441e-05 2.64964487288037e-06 8.72263966507186e-05 2.78288062268593e-05 2.13893048949432e-05 -1.47826681497396e-05 2.97313238183024e-05 4.05246251565576e-06 2.78288062268593e-05 3.23424631990281e-05 1.12985659164925e-05 3.81890173114695e-06 9.69389603111743e-06 1.5401451867182e-06 2.13893048949432e-05 1.12985659164925e-05 4.52755900334995e-05 849 854 0 15 0 849 858 0 22 0 0 0 0 0 0 4 14 0 2521 0 0 0 0 0 1742 +876 922 0.995051926931418 -0.000490951723024227 0.0993550284408306 -0.0111778370756857 -0.0133321922517698 0.990284323482237 0.138416802863996 -0.02338620434273 -0.098457683091948 -0.139056526749858 0.985377778828218 0.0015384242617303 4.22729409942567e-05 -4.57692805815578e-05 -2.54537758039623e-06 -2.2295168026341e-05 -1.14625555839107e-05 1.55101651254688e-06 -4.57692805815578e-05 6.26628882972593e-05 4.31636202930621e-06 3.55588510465078e-05 1.83663446189624e-05 1.08027809300545e-05 -2.54537758039623e-06 4.31636202930621e-06 1.08385650723328e-05 -1.37994247061672e-06 2.09736236230319e-06 -2.02051105550208e-07 -2.2295168026341e-05 3.55588510465078e-05 -1.37994247061672e-06 8.50713826538406e-05 3.0005109749268e-05 2.318037584018e-05 -1.14625555839107e-05 1.83663446189624e-05 2.09736236230319e-06 3.0005109749268e-05 3.32125841697817e-05 1.57118933881994e-05 1.55101651254688e-06 1.08027809300545e-05 -2.02051105550208e-07 2.318037584018e-05 1.57118933881994e-05 4.41597275848795e-05 865 864 0 15 0 862 868 0 21 0 0 0 0 0 0 3 12 0 2564 0 0 0 0 0 1883 +876 913 0.995204603109346 -0.000489964627296385 0.0978138941287605 -0.011800521036875 -0.0132235926660077 0.990133379716939 0.139502784801289 -0.0212429952219263 -0.0969171530069464 -0.140127264673851 0.98537881809386 -0.00250643406796204 2.77672329391837e-05 -2.31502503454079e-05 6.76450885014365e-06 -3.00693921566053e-05 -1.91600699701509e-05 -4.19255413209023e-06 -2.31502503454079e-05 4.96783013316505e-05 -2.29052124906846e-06 2.35655395680943e-05 1.27808920568568e-05 8.32929420974773e-06 6.76450885014365e-06 -2.29052124906846e-06 1.0958794288919e-05 -8.56152260545306e-06 -5.07637941772956e-06 2.10214894379816e-07 -3.00693921566053e-05 2.35655395680943e-05 -8.56152260545306e-06 0.000130416503140629 7.32903083439591e-05 1.90013895988092e-05 -1.91600699701509e-05 1.27808920568568e-05 -5.07637941772956e-06 7.32903083439591e-05 6.93579791047243e-05 1.77757105500576e-05 -4.19255413209023e-06 8.32929420974773e-06 2.10214894379816e-07 1.90013895988092e-05 1.77757105500576e-05 3.02792755647098e-05 885 887 0 15 0 881 891 0 23 0 0 0 0 0 0 1 11 0 2478 0 0 0 0 0 1835 +876 919 0.99582466294898 -0.000109510312285299 0.0912865196512752 -0.0194599887044702 -0.0122538269180991 0.990788495281169 0.13486289832396 -0.027869322951551 -0.090460402322853 -0.135418409479542 0.986650277446684 -0.00325874045591572 4.28780485170048e-05 -4.50658628493752e-05 -6.10942411500799e-07 -1.86553585735673e-05 -1.23030070506727e-05 -8.78511633294002e-06 -4.50658628493752e-05 7.76038652390108e-05 3.39122810958964e-06 4.11046324843063e-05 2.20632874904931e-05 2.87861834835398e-05 -6.10942411500799e-07 3.39122810958964e-06 1.01276397994954e-05 2.02115382755034e-07 1.75996115215815e-06 2.41765172376813e-07 -1.86553585735673e-05 4.11046324843063e-05 2.02115382755034e-07 8.90084475752438e-05 2.22520094048559e-05 3.15153773462654e-05 -1.23030070506727e-05 2.20632874904931e-05 1.75996115215815e-06 2.22520094048559e-05 3.62252189769112e-05 1.34250692806953e-05 -8.78511633294002e-06 2.87861834835398e-05 2.41765172376813e-07 3.15153773462654e-05 1.34250692806953e-05 5.65141241695259e-05 857 861 0 14 0 856 865 0 21 0 0 0 0 0 0 4 13 0 2351 0 0 0 0 0 1904 +876 912 0.995138170402278 -2.2410760385069e-05 0.098488686183564 -0.0100480125855187 -0.0139087875405699 0.989945922641358 0.140760846384575 -0.0215616991923146 -0.0975016278713234 -0.141446349346699 0.985132662548011 0.0003749291527016 4.71267856106624e-05 -5.57637949361553e-05 -6.1760169066887e-06 -1.45419629789891e-05 -1.61010017793024e-05 1.03204721672526e-05 -5.57637949361553e-05 9.10197719074523e-05 1.14094002445896e-05 3.21514956439912e-05 2.84805998242083e-05 -1.79826377156137e-07 -6.1760169066887e-06 1.14094002445896e-05 1.25064503526315e-05 -1.25346266771486e-06 6.66107736509573e-06 -1.64043272173685e-06 -1.45419629789891e-05 3.21514956439912e-05 -1.25346266771486e-06 7.95118890733378e-05 2.40702591881885e-05 1.74160669375484e-05 -1.61010017793024e-05 2.84805998242083e-05 6.66107736509573e-06 2.40702591881885e-05 3.61526479921355e-05 6.0323411982552e-06 1.03204721672526e-05 -1.79826377156137e-07 -1.64043272173685e-06 1.74160669375484e-05 6.0323411982552e-06 4.13343835792833e-05 850 850 0 14 0 847 855 0 23 0 0 0 0 0 0 2 12 0 2491 0 0 0 0 0 1920 +876 925 0.995077272555953 -0.000904342803792286 0.0990979505676054 -0.0155249478258317 -0.0129276707014088 0.99022934106445 0.138847857114544 -0.0236333442463252 -0.0982552643518009 -0.139445452629901 0.985343020865323 0.00183583980291699 3.44493187099355e-05 -3.33274299217389e-05 4.99227508173947e-06 -2.08932771723269e-05 -8.62414459915676e-06 6.9298472764257e-06 -3.33274299217389e-05 4.53112443153745e-05 -2.87439135826699e-06 2.90693596217396e-05 1.30183024908901e-05 -7.5033135051789e-08 4.99227508173947e-06 -2.87439135826699e-06 1.0795496302893e-05 1.76176451952633e-06 4.55796374092526e-06 6.36161761997665e-06 -2.08932771723269e-05 2.90693596217396e-05 1.76176451952633e-06 7.39346659867e-05 2.51655984357765e-05 8.58680986846543e-06 -8.62414459915676e-06 1.30183024908901e-05 4.55796374092526e-06 2.51655984357765e-05 3.0116878931734e-05 9.45220908548534e-06 6.9298472764257e-06 -7.5033135051789e-08 6.36161761997665e-06 8.58680986846543e-06 9.45220908548534e-06 3.14578485341272e-05 862 867 0 14 0 861 871 0 23 0 0 0 0 0 0 4 15 0 2485 0 0 0 0 0 1993 +876 908 0.995145958633187 -0.000667095132916365 0.0984077029511358 -0.0128502124588453 -0.0131109325340631 0.990163953649105 0.139296261048389 -0.0234481361370889 -0.0975326840814022 -0.139910327989243 0.985348910618883 -0.00197488983750066 4.05639933533706e-05 -3.92422345764978e-05 2.79644836448953e-06 -1.94905443345283e-05 -1.11855367653994e-05 -5.98162193090407e-06 -3.92422345764978e-05 6.124209751097e-05 2.19728256849063e-06 2.57855253869524e-05 1.35415198992681e-05 1.70187385504222e-05 2.79644836448953e-06 2.19728256849063e-06 1.0932593240878e-05 2.21386227749352e-06 4.76362857079938e-06 4.40920522691447e-06 -1.94905443345283e-05 2.57855253869524e-05 2.21386227749352e-06 6.11573569808743e-05 2.18320443655325e-05 1.4488777779832e-05 -1.11855367653994e-05 1.35415198992681e-05 4.76362857079938e-06 2.18320443655325e-05 3.14819104008134e-05 1.33943066934445e-05 -5.98162193090407e-06 1.70187385504222e-05 4.40920522691447e-06 1.4488777779832e-05 1.33943066934445e-05 4.09601850721858e-05 855 854 0 14 0 852 858 0 23 0 0 0 0 0 0 4 14 0 2510 0 0 0 0 0 1917 +876 909 0.996208030246756 -0.000212541325609494 0.0870029614327184 -0.0221702592808635 -0.0117192285073749 0.990555824608823 0.136608264818519 -0.0263862142462556 -0.0862103251070897 -0.137109857996132 0.986797176062645 -0.00189407824487425 4.15470636556356e-05 -5.74337948737233e-05 -1.65584612482256e-06 -2.02194921660446e-05 -1.21427019200524e-05 1.02634197562081e-05 -5.74337948737233e-05 0.000131387354291757 5.02061877799924e-06 7.11441188991816e-05 3.55166915709824e-05 5.62986466082219e-06 -1.65584612482256e-06 5.02061877799924e-06 9.97025701827803e-06 1.4191850272145e-07 3.77801836175734e-06 -2.55919242265838e-06 -2.02194921660446e-05 7.11441188991816e-05 1.4191850272145e-07 0.000101662611735618 3.76657651312005e-05 2.17241691602239e-05 -1.21427019200524e-05 3.55166915709824e-05 3.77801836175734e-06 3.76657651312005e-05 3.52100798148182e-05 6.27616786140443e-06 1.02634197562081e-05 5.62986466082219e-06 -2.55919242265838e-06 2.17241691602239e-05 6.27616786140443e-06 4.70845774450065e-05 827 830 0 17 0 827 833 0 21 0 0 0 0 0 0 3 13 0 2502 0 0 0 0 0 1741 +876 911 0.995535265686047 5.39651574457478e-05 0.094390316575236 -0.0167045917696354 -0.0132027471768904 0.990248770326002 0.13868330950343 -0.0241772679872156 -0.093462410852677 -0.139310336858407 0.985828285150108 -0.00151893901828128 4.83281228476222e-05 -5.28697386694887e-05 -3.22195216506836e-06 -2.89391978962299e-05 -2.02147380789615e-05 1.44490024469555e-06 -5.28697386694887e-05 8.00197745728378e-05 4.33986457513624e-06 5.34015924410464e-05 3.15061074638557e-05 1.22099559136822e-05 -3.22195216506836e-06 4.33986457513624e-06 1.02196140162326e-05 -4.41496645145387e-07 2.2119332427486e-06 -2.6321673558112e-06 -2.89391978962299e-05 5.34015924410464e-05 -4.41496645145387e-07 9.31066767325749e-05 3.63849610845542e-05 1.94461997677905e-05 -2.02147380789615e-05 3.15061074638557e-05 2.2119332427486e-06 3.63849610845542e-05 3.9571100236968e-05 1.18016946584463e-05 1.44490024469555e-06 1.22099559136822e-05 -2.6321673558112e-06 1.94461997677905e-05 1.18016946584463e-05 3.56023387403064e-05 846 851 0 18 0 843 853 0 23 0 0 0 0 0 0 1 10 0 2606 0 0 0 0 0 1690 +876 924 0.995810327902827 -0.000248747232956885 0.0914424899424666 -0.0179662726691992 -0.0122687959927513 0.990591349901496 0.13630206948253 -0.0255380544891951 -0.090616044313092 -0.136852897759406 0.986438045134058 -0.00195377554413661 4.22746352378211e-05 -4.42078700459059e-05 -3.05186002981116e-06 -2.04050379608921e-05 -1.3728418128189e-05 3.06260140082322e-06 -4.42078700459059e-05 6.84363247196449e-05 5.93509407572824e-06 3.72515951074207e-05 2.30224987784144e-05 7.50107388045807e-06 -3.05186002981116e-06 5.93509407572824e-06 1.05728726127735e-05 1.27319883554352e-06 3.89301022099214e-06 2.34163775306205e-07 -2.04050379608921e-05 3.72515951074207e-05 1.27319883554352e-06 7.42841164341748e-05 2.72821768579942e-05 1.99463508004994e-05 -1.3728418128189e-05 2.30224987784144e-05 3.89301022099214e-06 2.72821768579942e-05 3.71828560515034e-05 1.12690531744444e-05 3.06260140082322e-06 7.50107388045807e-06 2.34163775306205e-07 1.99463508004994e-05 1.12690531744444e-05 3.93383105767814e-05 830 831 0 17 0 829 833 0 21 0 0 0 0 0 0 2 9 0 2508 0 0 0 0 0 1741 +876 917 0.996244175827563 0.00107959397698445 0.0865816181790638 -0.012696216658295 -0.0129108992136593 0.990596355026183 0.136206351138021 -0.023644307989782 -0.0856203878241337 -0.136812630578043 0.986889787819876 -0.00308903935201955 4.42332827074834e-05 -4.48857815076831e-05 -2.08047920164935e-06 -1.94094588974143e-05 -1.84347101768481e-05 4.77411687442464e-06 -4.48857815076831e-05 0.000102299056685604 1.04658059782836e-05 2.93842541905654e-05 1.03520290371179e-05 8.84909064418278e-06 -2.08047920164935e-06 1.04658059782836e-05 1.28670001214213e-05 -4.50032801473151e-06 -2.41315872161497e-07 2.09309103891931e-07 -1.94094588974143e-05 2.93842541905654e-05 -4.50032801473151e-06 0.000113437037894065 4.76373956848933e-05 1.51336623433885e-05 -1.84347101768481e-05 1.03520290371179e-05 -2.41315872161497e-07 4.76373956848933e-05 5.97697533227269e-05 2.49751464155354e-06 4.77411687442464e-06 8.84909064418278e-06 2.09309103891931e-07 1.51336623433885e-05 2.49751464155354e-06 3.99423319256086e-05 833 832 0 12 0 831 840 0 23 0 0 0 0 0 0 2 13 0 2230 0 0 0 0 0 1739 +876 923 0.995170337685787 -0.00104416097796873 0.0981575708654641 -0.0155519656109203 -0.0125171203146748 0.990430916886101 0.13744060744622 -0.0245106781294513 -0.0973618030306777 -0.138005465848314 0.985634400123395 -0.00118904954497473 4.29498992954716e-05 -3.77011330881147e-05 2.02851400949437e-06 -2.15105025568942e-05 -1.6203497698696e-05 -1.71243020068151e-07 -3.77011330881147e-05 4.71236885798117e-05 1.16066999283479e-06 2.1009301293669e-05 1.49319129478585e-05 3.30995507698778e-06 2.02851400949437e-06 1.16066999283479e-06 1.00651333802602e-05 2.58640660271911e-07 2.15509063999341e-06 2.48577251263351e-06 -2.15105025568942e-05 2.1009301293669e-05 2.58640660271911e-07 6.64790319719476e-05 3.11717667303923e-05 1.48970710034843e-05 -1.6203497698696e-05 1.49319129478585e-05 2.15509063999341e-06 3.11717667303923e-05 3.93977079547306e-05 1.59346334483705e-05 -1.71243020068151e-07 3.30995507698778e-06 2.48577251263351e-06 1.48970710034843e-05 1.59346334483705e-05 4.24571348516425e-05 867 871 0 14 0 863 874 0 21 0 0 0 0 0 0 4 13 0 2462 0 0 0 0 0 1935 +876 914 0.995241178665978 -0.000385077718139397 0.0974415106754077 -0.0145514855953505 -0.0132287108228476 0.990200141799311 0.13902762455926 -0.0242751334470102 -0.0965401341283514 -0.139655042500355 0.985482862157787 -0.00237071773017417 2.36269892137297e-05 -2.2172233365613e-05 3.31856083260332e-06 -8.47724474924522e-06 -3.30845418720687e-06 -2.79577129420025e-06 -2.2172233365613e-05 4.13538339403582e-05 1.95956064355396e-07 1.12135278481659e-05 5.34679841825004e-06 1.03813453707001e-05 3.31856083260332e-06 1.95956064355396e-07 1.00944964114279e-05 -1.74532323245345e-07 2.58832859791751e-06 9.77906625629645e-07 -8.47724474924522e-06 1.12135278481659e-05 -1.74532323245345e-07 4.93759716197654e-05 1.47800409553994e-05 6.39083179299055e-06 -3.30845418720687e-06 5.34679841825004e-06 2.58832859791751e-06 1.47800409553994e-05 2.7766684672467e-05 1.04899029590698e-05 -2.79577129420025e-06 1.03813453707001e-05 9.77906625629645e-07 6.39083179299055e-06 1.04899029590698e-05 3.20058928784987e-05 885 889 0 16 0 882 893 0 21 0 0 0 0 0 0 3 12 0 2587 0 0 0 0 0 1684 +876 918 0.996025661245819 8.55847455755643e-05 0.0890666874599097 -0.0171081405336476 -0.0120553286966731 0.990926709394391 0.133861591424948 -0.0314512587875334 -0.0882471030110625 -0.134403308307704 0.986989462722931 -0.00118760518345422 4.99425760226771e-05 -5.2384060531381e-05 -8.23480955578577e-06 -9.91877730899576e-07 -1.27956922281137e-05 9.76471250224499e-06 -5.2384060531381e-05 0.000103649408978336 1.31573702444678e-05 2.4180093143685e-05 1.95185466098463e-05 9.90622511042121e-06 -8.23480955578577e-06 1.31573702444678e-05 1.23250833610586e-05 -8.03108649441439e-07 5.41284912110443e-06 -1.94596049558993e-06 -9.91877730899576e-07 2.4180093143685e-05 -8.03108649441439e-07 6.62547602999963e-05 6.64647428104351e-06 1.34566161386555e-05 -1.27956922281137e-05 1.95185466098463e-05 5.41284912110443e-06 6.64647428104351e-06 3.2800217575136e-05 4.91182197585975e-06 9.76471250224499e-06 9.90622511042121e-06 -1.94596049558993e-06 1.34566161386555e-05 4.91182197585975e-06 4.33745924241285e-05 854 858 0 17 0 850 861 0 23 0 0 0 0 0 0 1 12 0 2292 0 0 0 0 0 1767 +876 928 0.995614935984495 -0.000660061144318452 0.0935439124896776 -0.0193132471041992 -0.0123976957498347 0.990223272150146 0.138939441600834 -0.025198376952647 -0.0927210676420695 -0.139489912221432 0.985872896474881 0.00109638809813493 3.73591566415011e-05 -4.31583171133606e-05 -3.13603955105808e-06 -1.15758251964736e-05 -6.80902218491852e-06 7.10120614603477e-06 -4.31583171133606e-05 8.04095753711124e-05 7.92027201511376e-06 2.95063919552302e-05 1.35517393866717e-05 2.15053393133514e-06 -3.13603955105808e-06 7.92027201511376e-06 1.07383645185442e-05 2.43267726379193e-07 4.37647051531526e-06 -1.48880199165338e-06 -1.15758251964736e-05 2.95063919552302e-05 2.43267726379193e-07 5.61662751736432e-05 1.16258911475036e-05 1.40735001471935e-05 -6.80902218491852e-06 1.35517393866717e-05 4.37647051531526e-06 1.16258911475036e-05 2.60337776685611e-05 4.83634289276417e-06 7.10120614603477e-06 2.15053393133514e-06 -1.48880199165338e-06 1.40735001471935e-05 4.83634289276417e-06 3.20144754641708e-05 841 841 0 13 0 837 846 0 23 0 0 0 0 0 0 2 12 0 2475 0 0 0 0 0 1927 +876 916 0.995578726936467 -0.000357588533600053 0.0939301368145758 -0.0184171566406402 -0.012460018092974 0.990652862916405 0.135836862245318 -0.0274238070668131 -0.0931007326538683 -0.136406661589423 0.986268460538682 -0.000837186815393122 5.19164019109111e-05 -4.88731224364893e-05 -1.64852986461718e-06 -1.60700396493593e-05 -1.3654287399119e-05 -1.22240650086967e-05 -4.88731224364893e-05 7.3712775106135e-05 5.30329226142592e-06 2.48493757479386e-05 1.45769919391124e-05 2.26074047351561e-05 -1.64852986461718e-06 5.30329226142592e-06 9.69036004693917e-06 2.86516516859487e-06 2.11769910966069e-06 1.17014229310272e-06 -1.60700396493593e-05 2.48493757479386e-05 2.86516516859487e-06 5.04864922782999e-05 9.96352813248649e-06 1.88515114565674e-05 -1.3654287399119e-05 1.45769919391124e-05 2.11769910966069e-06 9.96352813248649e-06 2.92673734321406e-05 1.49923998282023e-05 -1.22240650086967e-05 2.26074047351561e-05 1.17014229310272e-06 1.88515114565674e-05 1.49923998282023e-05 5.14853869418075e-05 848 849 0 15 0 843 851 0 20 0 0 0 0 0 0 1 10 0 2433 0 0 0 0 0 1925 +876 915 0.995905612476692 0.000167955605726032 0.0903990200629412 -0.0183735613826231 -0.0125145093078644 0.990625810492221 0.136029006625106 -0.0256410648669925 -0.0895287556833496 -0.136603350535571 0.986571906415466 -0.00108421848623812 4.30872718917542e-05 -5.09230022480658e-05 -3.2130092790874e-06 -2.18193446523438e-05 -1.44772011155725e-05 7.98428150689354e-06 -5.09230022480658e-05 0.000103893014510306 8.09054510768649e-06 5.9117670388628e-05 3.18148693967729e-05 5.28175341445188e-06 -3.2130092790874e-06 8.09054510768649e-06 1.09065993115129e-05 2.00559408844397e-06 5.68097505127596e-06 -1.168546375991e-06 -2.18193446523438e-05 5.9117670388628e-05 2.00559408844397e-06 0.000104169813105888 3.21257466442558e-05 2.06821492027867e-05 -1.44772011155725e-05 3.18148693967729e-05 5.68097505127596e-06 3.21257466442558e-05 3.61456705959538e-05 6.34069579342379e-06 7.98428150689354e-06 5.28175341445188e-06 -1.168546375991e-06 2.06821492027867e-05 6.34069579342379e-06 4.41387898229973e-05 838 835 0 12 0 836 840 0 19 0 0 0 0 0 0 4 12 0 2587 0 0 0 0 0 1740 +876 910 0.995481680309972 -0.000405707517458715 0.0949529334388668 -0.0163041427580948 -0.0128169835716717 0.990264980853133 0.138603725159419 -0.024933709929969 -0.0940847973870332 -0.139194479406888 0.985785447145212 -0.00175750303186943 3.38482036472479e-05 -4.3805283487674e-05 5.75048443363626e-07 -1.61952384577405e-05 -7.59494152208929e-06 3.17475433045921e-06 -4.3805283487674e-05 9.44609435807933e-05 5.36647944565375e-06 4.69010743397818e-05 2.44243957910722e-05 3.46818827046321e-06 5.75048443363626e-07 5.36647944565375e-06 1.07392817614347e-05 5.127823526462e-07 4.9827574603283e-06 2.15109003090381e-06 -1.61952384577405e-05 4.69010743397818e-05 5.127823526462e-07 8.70418070558197e-05 2.76653503449829e-05 5.28071191444482e-06 -7.59494152208929e-06 2.44243957910722e-05 4.9827574603283e-06 2.76653503449829e-05 2.98129411027355e-05 5.49865217656157e-06 3.17475433045921e-06 3.46818827046321e-06 2.15109003090381e-06 5.28071191444482e-06 5.49865217656157e-06 3.65784884027637e-05 867 871 0 14 0 865 875 0 21 0 0 0 0 0 0 3 11 0 2538 0 0 0 0 0 1679 +876 906 0.9953821938596 -0.000548222703684464 0.0959895181731697 -0.0168319228473099 -0.012784241580457 0.990318382173353 0.138224690619173 -0.0245388110488606 -0.0951359622564602 -0.138813548983594 0.985738275255717 -0.00161849971683459 4.15679534212862e-05 -5.30848575815013e-05 -2.86348319717689e-06 -1.9314454517255e-05 -1.06603215988239e-05 -7.16547513182693e-07 -5.30848575815013e-05 0.000111332996979149 8.65619252149174e-06 4.34758114293178e-05 1.86270551822473e-05 1.61224976170706e-05 -2.86348319717689e-06 8.65619252149174e-06 1.045016021517e-05 2.22127466437861e-06 4.19174953296393e-06 6.88910550389744e-07 -1.9314454517255e-05 4.34758114293178e-05 2.22127466437861e-06 6.74395915008515e-05 1.99383773367027e-05 1.65044821903212e-05 -1.06603215988239e-05 1.86270551822473e-05 4.19174953296393e-06 1.99383773367027e-05 2.84494777503468e-05 8.87011627200386e-06 -7.16547513182693e-07 1.61224976170706e-05 6.88910550389744e-07 1.65044821903212e-05 8.87011627200386e-06 3.96570509334828e-05 861 863 0 14 0 857 867 0 22 0 0 0 0 0 0 4 13 0 2585 0 0 0 0 0 1678 +876 907 0.995943798407582 -6.01384341142626e-06 0.0899774992834918 -0.0194628859873577 -0.0124131557129146 0.990428832721627 0.137465053300547 -0.024830870667807 -0.0891171362798649 -0.138024372041712 0.986411379062391 -0.00061740142829266 3.78939127830755e-05 -4.65743299365029e-05 -1.34853341948543e-06 -1.46168610725685e-05 -7.01065429607604e-06 5.55578423855492e-06 -4.65743299365029e-05 0.000103510449006259 5.57075174461808e-06 5.12682547306345e-05 2.53438043320138e-05 9.81779236541367e-06 -1.34853341948543e-06 5.57075174461808e-06 1.0738384590085e-05 -5.36852742407369e-07 3.62085874844248e-06 -2.33951763931064e-07 -1.46168610725685e-05 5.12682547306345e-05 -5.36852742407369e-07 8.39435448328533e-05 3.07394586604249e-05 1.5683348939909e-05 -7.01065429607604e-06 2.53438043320138e-05 3.62085874844248e-06 3.07394586604249e-05 3.39965270092582e-05 7.01395421792662e-06 5.55578423855492e-06 9.81779236541367e-06 -2.33951763931064e-07 1.5683348939909e-05 7.01395421792662e-06 3.58002275379553e-05 843 846 0 15 0 840 848 0 22 0 0 0 0 0 0 1 10 0 2596 0 0 0 0 0 1728 +876 904 0.99635058877565 0.000318649301667456 0.0853545705222516 -0.0213042166766757 -0.0119648334803821 0.990640958579727 0.135968135767272 -0.0257616571353815 -0.0845124074098129 -0.136493185349537 0.987029514932018 -0.00244499706843321 5.08441714791927e-05 -7.05171822807147e-05 -2.81647243357758e-06 -4.24019370296623e-05 -1.95853031022297e-05 2.5347066332619e-06 -7.05171822807147e-05 0.000154903270848264 8.03473381341818e-06 0.000117346559227376 5.09508594752223e-05 2.29631954850497e-05 -2.81647243357758e-06 8.03473381341818e-06 1.08497573591514e-05 5.47866353934931e-06 5.50380069094386e-06 4.73237483089963e-07 -4.24019370296623e-05 0.000117346559227376 5.47866353934931e-06 0.000156911439508807 5.52370684249632e-05 3.54396285892357e-05 -1.95853031022297e-05 5.09508594752223e-05 5.50380069094386e-06 5.52370684249632e-05 4.44031069622576e-05 1.99997590535755e-05 2.5347066332619e-06 2.29631954850497e-05 4.73237483089963e-07 3.54396285892357e-05 1.99997590535755e-05 5.46393210779555e-05 816 818 0 12 0 817 827 0 23 0 0 0 0 0 0 5 14 0 2537 0 0 0 0 0 1746 +876 905 0.995597290881246 -0.000192614356931986 0.0937336507857967 -0.0163485189415499 -0.0127585844731139 0.99041247729339 0.137551238975925 -0.0256110738412025 -0.092861471623955 -0.138141549583314 0.986049521761739 0.00028325263667058 1.77046702482211e-05 -1.80880010970927e-05 4.89619925472231e-06 -6.55632298307553e-06 1.76334176782756e-06 2.91720922020675e-06 -1.80880010970927e-05 3.80698243359515e-05 -1.23521036942292e-06 1.12907715979742e-05 2.46843740023098e-06 2.82392351146614e-06 4.89619925472231e-06 -1.23521036942292e-06 9.57564033476283e-06 7.10782881713439e-07 3.33988071627739e-06 3.10441870192743e-06 -6.55632298307553e-06 1.12907715979742e-05 7.10782881713439e-07 5.12004660806583e-05 1.23838646708801e-05 -5.78694661808169e-07 1.76334176782756e-06 2.46843740023098e-06 3.33988071627739e-06 1.23838646708801e-05 2.36972892529304e-05 5.7084164042714e-06 2.91720922020675e-06 2.82392351146614e-06 3.10441870192743e-06 -5.78694661808169e-07 5.7084164042714e-06 2.57959535681892e-05 858 862 0 16 0 856 867 0 24 0 0 0 0 0 0 3 14 0 2589 0 0 0 0 0 1706 +877 880 0.999911086208674 0.00605540858425769 0.0118807282549003 -0.00526042365200782 -0.00613707161274301 0.999957711541447 0.00684919563259705 -0.000519896754548988 -0.011838751159187 -0.00692149952475769 0.999905963986274 -0.00180687052978761 4.96014319592614e-05 -6.98704516577604e-05 4.24453116509062e-06 -4.16460781511187e-05 -2.66906643697185e-05 1.12320237505075e-05 -6.98704516577604e-05 0.000137855750181752 -4.96715898203726e-06 9.92668849669535e-05 6.11732478370278e-05 -3.5224681490963e-06 4.24453116509062e-06 -4.96715898203726e-06 8.9197122160862e-06 -3.06751520419377e-06 -4.16876872349844e-07 -1.17434323617441e-06 -4.16460781511187e-05 9.92668849669535e-05 -3.06751520419377e-06 0.000138775137132463 6.46314725452728e-05 2.66641179896964e-05 -2.66906643697185e-05 6.11732478370278e-05 -4.16876872349844e-07 6.46314725452728e-05 5.75004030261137e-05 1.1420932616676e-05 1.12320237505075e-05 -3.5224681490963e-06 -1.17434323617441e-06 2.66641179896964e-05 1.1420932616676e-05 4.48847047927803e-05 719 719 0 8 0 713 724 0 20 0 0 0 0 0 0 4 15 0 2078 0 0 0 0 0 2462 +877 881 0.999817809443372 0.00598975469171301 0.0181237622636591 -0.00819217678887133 -0.00604094814145994 0.999977913367056 0.00277123142673794 -0.00942425940041301 -0.0181067629743343 -0.00288021124250467 0.999831910631877 -0.00524934418627824 3.94828743770797e-05 -3.40850214217329e-05 1.74599104542902e-07 -1.76287443319819e-05 -1.67585163558696e-05 -5.03519786251972e-06 -3.40850214217329e-05 6.70747974226503e-05 -1.7677156245661e-06 4.28591352287215e-05 2.01052137372957e-05 -1.99696589748276e-06 1.74599104542902e-07 -1.7677156245661e-06 9.07148005447001e-06 -1.39290061675918e-06 1.16977251449055e-07 1.10552723893729e-06 -1.76287443319819e-05 4.28591352287215e-05 -1.39290061675918e-06 9.2596601744071e-05 3.84741110438725e-05 1.91888409495639e-05 -1.67585163558696e-05 2.01052137372957e-05 1.16977251449055e-07 3.84741110438725e-05 5.35987211831232e-05 1.79757834955326e-05 -5.03519786251972e-06 -1.99696589748276e-06 1.10552723893729e-06 1.91888409495639e-05 1.79757834955326e-05 4.55975212335747e-05 786 785 0 8 0 783 796 0 24 0 0 0 0 0 0 6 21 0 2075 0 0 0 0 0 2578 +877 913 0.995320122497342 0.000311598087383957 0.0966320684788844 -0.0162488503329737 -0.0142524046791632 0.989531669518151 0.143610389531827 -0.0241208320330164 -0.0955757433281961 -0.144315549845654 0.984905223541844 -0.000168925383261246 2.4163164288663e-05 -1.87763291237297e-05 4.63352440812576e-06 -5.92677958107601e-06 -1.75209026864998e-06 -2.35346792064445e-06 -1.87763291237297e-05 3.86386774149409e-05 -1.11687079012664e-06 8.54883384523317e-06 3.25661452545712e-06 6.57662489005911e-06 4.63352440812576e-06 -1.11687079012664e-06 9.53008195738094e-06 -1.95779894199223e-07 2.61490321107085e-06 1.04396216866689e-06 -5.92677958107601e-06 8.54883384523317e-06 -1.95779894199223e-07 4.62603448759879e-05 1.02590717834717e-05 9.45279902473915e-06 -1.75209026864998e-06 3.25661452545712e-06 2.61490321107085e-06 1.02590717834717e-05 2.33924810534287e-05 8.14658676800088e-06 -2.35346792064445e-06 6.57662489005911e-06 1.04396216866689e-06 9.45279902473915e-06 8.14658676800088e-06 3.18661220057167e-05 869 872 0 14 0 869 881 0 29 0 0 0 0 0 0 1 9 0 2444 0 0 0 0 0 1591 +877 919 0.996047381700362 0.00128712106584857 0.0888141696308345 -0.0197480650931067 -0.0139982237247139 0.989674654230506 0.142646866443959 -0.026230808010016 -0.0877135288333884 -0.143326278445683 0.985780865490148 0.000852875276439081 4.2910794309562e-05 -4.43339288616805e-05 -2.6968344128274e-06 -1.63968147078637e-05 -8.83659420732771e-06 -3.16570344153149e-06 -4.43339288616805e-05 6.99295841748625e-05 5.00151761741803e-06 3.48505789547071e-05 1.27461500854827e-05 1.82821364870464e-05 -2.6968344128274e-06 5.00151761741803e-06 1.12075512170797e-05 -1.24126836424749e-06 2.21291060678979e-07 -2.12199148391629e-06 -1.63968147078637e-05 3.48505789547071e-05 -1.24126836424749e-06 7.66831423578679e-05 2.07170644080386e-05 2.23576540531941e-05 -8.83659420732771e-06 1.27461500854827e-05 2.21291060678979e-07 2.07170644080386e-05 3.44259571032448e-05 1.02836957972448e-05 -3.16570344153149e-06 1.82821364870464e-05 -2.12199148391629e-06 2.23576540531941e-05 1.02836957972448e-05 4.5767209957772e-05 859 863 0 13 0 859 868 0 28 0 0 0 0 0 0 1 9 0 2288 0 0 0 0 0 1638 +877 920 0.995265442691613 -5.80420872112497e-06 0.0971941281671795 -0.0163199513483481 -0.0138451213720727 0.989793800777741 0.141832804936468 -0.0287998149124206 -0.0962029687590748 -0.142506953894415 0.985107484944499 0.00120391459739974 2.84606463376294e-05 -2.61830567338647e-05 -1.43701078552238e-07 -8.98654855499392e-07 -1.99795438845646e-06 2.86417515190738e-06 -2.61830567338647e-05 5.66144034075461e-05 4.170522255123e-06 1.08602167204865e-05 4.69152640621793e-06 6.01492158132533e-06 -1.43701078552238e-07 4.170522255123e-06 1.03144352493551e-05 -6.27705410768132e-07 2.05323368030999e-06 7.64449407656035e-07 -8.98654855499392e-07 1.08602167204865e-05 -6.27705410768132e-07 4.83068918799929e-05 7.95833162871179e-06 6.42089446044383e-06 -1.99795438845646e-06 4.69152640621793e-06 2.05323368030999e-06 7.95833162871179e-06 2.86196273152336e-05 7.46411054438626e-06 2.86417515190738e-06 6.01492158132533e-06 7.64449407656035e-07 6.42089446044383e-06 7.46411054438626e-06 3.4403961833902e-05 847 849 0 12 0 846 854 0 23 0 0 0 0 0 0 2 7 0 2258 0 0 0 0 0 1847 +877 921 0.995653876002256 0.000759630431364546 0.0931277733186664 -0.0176480931861559 -0.0140588051540926 0.989733314047741 0.142233319098287 -0.0271054511971439 -0.0920636149590294 -0.142924420676397 0.985442489836414 0.000386079140913103 2.21237425765796e-05 -2.14242997528941e-05 3.17944456042759e-06 -5.24152939461392e-06 -2.10303387764172e-06 2.36567693747604e-06 -2.14242997528941e-05 3.89339754042417e-05 -8.56073080178259e-07 1.00539044763615e-05 2.89167382921291e-06 2.6875563180927e-06 3.17944456042759e-06 -8.56073080178259e-07 8.28514916263393e-06 1.73082933423634e-06 1.19241988708812e-06 3.29084076293532e-07 -5.24152939461392e-06 1.00539044763615e-05 1.73082933423634e-06 4.67413983156601e-05 1.21831646140002e-05 1.30144773341671e-05 -2.10303387764172e-06 2.89167382921291e-06 1.19241988708812e-06 1.21831646140002e-05 2.79519507737212e-05 7.643479330555e-06 2.36567693747604e-06 2.6875563180927e-06 3.29084076293532e-07 1.30144773341671e-05 7.643479330555e-06 2.87303235905763e-05 851 851 0 16 0 851 859 0 30 0 0 0 0 0 0 1 11 0 2390 0 0 0 0 0 2180 +877 922 0.99527410400652 0.000487911822336675 0.0971041700241184 -0.0135129985951135 -0.0146975730930704 0.989223607532595 0.145673043646971 -0.0223956656102059 -0.0959866617775257 -0.146411803630213 0.984555810768772 0.00255384760276438 3.73808898155869e-05 -3.95468323545534e-05 -3.2608739170609e-06 -8.92502384800862e-06 -6.94081215428911e-06 2.8900017464954e-06 -3.95468323545534e-05 5.60459386844344e-05 4.89407585746537e-06 2.00891713821797e-05 1.19667448675484e-05 5.94336253403039e-06 -3.2608739170609e-06 4.89407585746537e-06 9.35421204922302e-06 -1.35082957800486e-07 2.77411986765999e-06 -1.72364989072458e-06 -8.92502384800862e-06 2.00891713821797e-05 -1.35082957800486e-07 5.69354859656613e-05 1.90192605539737e-05 1.89374758725565e-05 -6.94081215428911e-06 1.19667448675484e-05 2.77411986765999e-06 1.90192605539737e-05 2.80830091466455e-05 9.45848097085814e-06 2.8900017464954e-06 5.94336253403039e-06 -1.72364989072458e-06 1.89374758725565e-05 9.45848097085814e-06 4.18233991832203e-05 864 865 0 13 0 864 872 0 27 0 0 0 0 0 0 2 10 0 2501 0 0 0 0 0 1693 +877 926 0.996188378096641 0.000859039114961887 0.0872237203803076 -0.0273298396620833 -0.0132779475046901 0.989791906131489 0.141900241954186 -0.029884912065414 -0.0862114345968434 -0.142517523864235 0.986030599898584 -0.000768144753419214 5.03955320261845e-05 -6.28543492661347e-05 -3.1520719971073e-06 -3.38213173560553e-05 -1.65715506199393e-05 -1.24589976251699e-05 -6.28543492661347e-05 0.000111503408831247 8.11635956731923e-06 6.88772479684064e-05 3.31988550611748e-05 4.00270676589301e-05 -3.1520719971073e-06 8.11635956731923e-06 1.06313331808524e-05 3.19784681845828e-06 5.54772050096561e-06 1.95129315077043e-06 -3.38213173560553e-05 6.88772479684064e-05 3.19784681845828e-06 0.000101469884671532 3.57837165125794e-05 5.17284334045823e-05 -1.65715506199393e-05 3.31988550611748e-05 5.54772050096561e-06 3.57837165125794e-05 3.72148902654975e-05 2.46647124315155e-05 -1.24589976251699e-05 4.00270676589301e-05 1.95129315077043e-06 5.17284334045823e-05 2.46647124315155e-05 6.32765575701288e-05 866 870 0 14 0 864 875 0 26 0 0 0 0 0 0 2 11 0 2490 0 0 0 0 0 1469 +876 903 0.995305839163213 -0.000144466617645505 0.0967794691916033 -0.0127554496571212 -0.0134146720228662 0.990139923376567 0.139438081994718 -0.0226098550723293 -0.0958453603578756 -0.140081802048815 0.985490109353019 -0.00154113168220532 3.55374513212212e-05 -3.40687916710356e-05 2.31745861243109e-07 -7.72648573087052e-06 -8.55147668990239e-06 5.65684716767495e-06 -3.40687916710356e-05 5.1930558954838e-05 2.03244331707134e-06 2.30866446603372e-05 1.6728959918183e-05 5.27768266492491e-06 2.31745861243109e-07 2.03244331707134e-06 1.04588780853943e-05 -1.03252768025117e-06 3.12166586071769e-06 -8.68016455739911e-07 -7.72648573087052e-06 2.30866446603372e-05 -1.03252768025117e-06 6.6874764215668e-05 1.90793159381105e-05 1.5905139915239e-05 -8.55147668990239e-06 1.6728959918183e-05 3.12166586071769e-06 1.90793159381105e-05 2.90750844088896e-05 7.42700317761018e-06 5.65684716767495e-06 5.27768266492491e-06 -8.68016455739911e-07 1.5905139915239e-05 7.42700317761018e-06 3.45614838347656e-05 843 847 0 16 0 842 850 0 20 0 0 0 0 0 0 3 13 0 2500 0 0 0 0 0 1824 +877 879 0.999791493742519 0.00808955535866675 0.0187490835563106 0.00833250738877931 -0.00819792500504249 0.999950091647307 0.00571036252381312 0.00524583288421822 -0.0187019535266814 -0.00586287545840233 0.999807913364185 -0.00236670597098068 2.78900224447623e-05 -2.88772491537777e-05 6.34456201084245e-06 -1.32708787937477e-05 -7.28257471452813e-06 1.02096277800719e-05 -2.88772491537777e-05 4.27240394037876e-05 -5.73020680994916e-06 2.34568808471385e-05 1.33394280966484e-05 -3.58806587176094e-06 6.34456201084245e-06 -5.73020680994916e-06 9.14059762070857e-06 4.73808147691862e-07 -2.50408632557916e-06 2.67139608182227e-06 -1.32708787937477e-05 2.34568808471385e-05 4.73808147691862e-07 6.49449347445561e-05 3.3812063367797e-05 1.02792533983359e-05 -7.28257471452813e-06 1.33394280966484e-05 -2.50408632557916e-06 3.3812063367797e-05 4.3541599571376e-05 1.03047165501302e-05 1.02096277800719e-05 -3.58806587176094e-06 2.67139608182227e-06 1.02792533983359e-05 1.03047165501302e-05 3.85864564045947e-05 739 737 0 9 0 738 746 0 22 0 0 0 0 0 0 2 13 0 2049 0 0 0 0 0 2648 +877 927 0.99603571223455 0.000547348903737917 0.0889525736704181 -0.0275459763816396 -0.0131689351914791 0.989869716098159 0.141366630778528 -0.0307954923035928 -0.0879740819749556 -0.141977623451471 0.985952795695482 -6.36521901299955e-05 4.75661226588942e-05 -6.16747814415416e-05 -6.26130869425864e-06 -2.17273519496912e-05 -1.3807069866335e-05 -6.55814269377663e-06 -6.16747814415416e-05 0.000113872189426552 1.27406770339709e-05 4.96714209168132e-05 2.80548977988737e-05 3.50245960614981e-05 -6.26130869425864e-06 1.27406770339709e-05 1.15873254304466e-05 2.38873261221378e-06 6.03784397403734e-06 1.51829358252884e-06 -2.17273519496912e-05 4.96714209168132e-05 2.38873261221378e-06 7.23402799180396e-05 1.88463167490804e-05 3.12587701696667e-05 -1.3807069866335e-05 2.80548977988737e-05 6.03784397403734e-06 1.88463167490804e-05 2.98918009734849e-05 1.22582907505341e-05 -6.55814269377663e-06 3.50245960614981e-05 1.51829358252884e-06 3.12587701696667e-05 1.22582907505341e-05 5.75139029000562e-05 853 860 0 14 0 853 864 0 23 0 0 0 0 0 0 2 10 0 2499 0 0 0 0 0 1491 +877 912 0.996005522781129 0.000934099080976205 0.0892867630077187 -0.0213632912879605 -0.0137179594322567 0.989674975400131 0.142671863574308 -0.0275175074513696 -0.0882316053265754 -0.143326796258264 0.985734555190107 -0.00179939301776746 4.4431328700828e-05 -5.68081345994158e-05 -3.94165799580365e-06 -2.0053443279991e-05 -1.77024245268827e-05 1.58394960223027e-06 -5.68081345994158e-05 0.000102793164616832 7.27965722927958e-06 5.57658867014861e-05 3.59621998362007e-05 1.86458264269291e-05 -3.94165799580365e-06 7.27965722927958e-06 9.23192650422423e-06 3.44629266233361e-06 4.11939270901202e-06 9.43067024479051e-09 -2.0053443279991e-05 5.57658867014861e-05 3.44629266233361e-06 8.11991184838286e-05 2.68052248306767e-05 2.85059746219883e-05 -1.77024245268827e-05 3.59621998362007e-05 4.11939270901202e-06 2.68052248306767e-05 3.70322294313781e-05 1.25214237663446e-05 1.58394960223027e-06 1.86458264269291e-05 9.43067024479051e-09 2.85059746219883e-05 1.25214237663446e-05 4.76830118021307e-05 868 872 0 15 0 867 876 0 27 0 0 0 0 0 0 0 9 0 2470 0 0 0 0 0 2232 +877 914 0.995392487292856 0.000269277882897387 0.0958839075672359 -0.0177114956032958 -0.0141880274841089 0.989401543099639 0.144510506151504 -0.0253853606607422 -0.0948287726222934 -0.145205075673943 0.984846683439343 -0.000453022188727935 1.78190750496633e-05 -1.69726127375726e-05 4.29818555924998e-06 -5.50251897732761e-06 1.9029079952835e-07 4.83334104647874e-07 -1.69726127375726e-05 3.76934717876175e-05 -1.04477938012058e-06 1.22084689126992e-05 8.08198561659925e-06 1.08145530203247e-05 4.29818555924998e-06 -1.04477938012058e-06 8.75528067276381e-06 1.13006973526478e-06 2.97936115436708e-06 9.64586301434467e-07 -5.50251897732761e-06 1.22084689126992e-05 1.13006973526478e-06 4.96219517411159e-05 1.3741723417076e-05 7.45254553163628e-06 1.9029079952835e-07 8.08198561659925e-06 2.97936115436708e-06 1.3741723417076e-05 2.40879330789278e-05 9.2340211309408e-06 4.83334104647874e-07 1.08145530203247e-05 9.64586301434467e-07 7.45254553163628e-06 9.2340211309408e-06 3.22452549910087e-05 868 874 0 14 0 868 879 0 25 0 0 0 0 0 0 2 10 0 2520 0 0 0 0 0 1906 +877 918 0.995992952001786 0.000473832322111621 0.0894305040000235 -0.0221139347451468 -0.0131763566054447 0.989850371208567 0.141501329480922 -0.0313785191962966 -0.0884557696782627 -0.14211269507399 0.985890236643732 0.000652125090208974 5.20988131145034e-05 -5.26468783036344e-05 -5.60632539576692e-06 -9.03884080205783e-06 -1.1204839469872e-05 1.31799130392399e-05 -5.26468783036344e-05 9.95018726353362e-05 8.33339440037347e-06 3.83117282451561e-05 1.88074286102054e-05 4.84026988635774e-06 -5.60632539576692e-06 8.33339440037347e-06 1.00363014053326e-05 -2.35909088022332e-07 2.33025877078212e-06 -1.85184231345597e-06 -9.03884080205783e-06 3.83117282451561e-05 -2.35909088022332e-07 7.13624450622602e-05 1.37575071873837e-05 1.79343963877189e-05 -1.1204839469872e-05 1.88074286102054e-05 2.33025877078212e-06 1.37575071873837e-05 3.26016619796349e-05 2.51967865407577e-06 1.31799130392399e-05 4.84026988635774e-06 -1.85184231345597e-06 1.79343963877189e-05 2.51967865407577e-06 4.27832971586869e-05 850 854 0 15 0 849 860 0 27 0 0 0 0 0 0 1 10 0 2251 0 0 0 0 0 1862 +877 916 0.995946789517001 0.00100011922878151 0.0899388248328044 -0.0196238686119387 -0.0138758214184889 0.989675906214627 0.142650139285662 -0.0262303050501036 -0.0888676208229963 -0.143319923317677 0.985678418932603 0.00074584855811136 4.43634754580158e-05 -5.1712640248767e-05 -3.42894016938294e-06 -1.45360993616686e-05 -1.11779861768008e-05 -7.3105315796752e-06 -5.1712640248767e-05 8.71724261370642e-05 5.86937667765287e-06 3.65186603339918e-05 2.14471969864843e-05 3.1007577410888e-05 -3.42894016938294e-06 5.86937667765287e-06 1.02655405414473e-05 6.85097806095833e-07 2.9674255279635e-06 -1.74052075640314e-07 -1.45360993616686e-05 3.65186603339918e-05 6.85097806095833e-07 6.53049742534567e-05 1.42608287368021e-05 2.62770853626809e-05 -1.11779861768008e-05 2.14471969864843e-05 2.9674255279635e-06 1.42608287368021e-05 3.00265765048283e-05 1.60537907528096e-05 -7.3105315796752e-06 3.1007577410888e-05 -1.74052075640314e-07 2.62770853626809e-05 1.60537907528096e-05 5.89243425140978e-05 862 867 0 13 0 861 870 0 23 0 0 0 0 0 0 3 8 0 2371 0 0 0 0 0 1660 +877 928 0.996222233512191 0.000206057402017962 0.0868401922863462 -0.0264740768429791 -0.0125923544464228 0.989770814449395 0.142109702250327 -0.0296302090949308 -0.0859226050901517 -0.142666367461038 0.986034286183799 0.00251439869451722 4.90090090061772e-05 -7.19148287299283e-05 -5.70196566440688e-06 -1.90407633697569e-05 -1.28360424150516e-05 -3.74124410324365e-06 -7.19148287299283e-05 0.00015200806951431 1.41084919036128e-05 5.89378256152676e-05 3.24608751385984e-05 3.44207605111614e-05 -5.70196566440688e-06 1.41084919036128e-05 1.13022979809724e-05 3.34477308098261e-06 5.36647318583536e-06 2.01014820995064e-06 -1.90407633697569e-05 5.89378256152676e-05 3.34477308098261e-06 7.14078788625092e-05 1.48047867170967e-05 2.90812410752991e-05 -1.28360424150516e-05 3.24608751385984e-05 5.36647318583536e-06 1.48047867170967e-05 3.20328760621321e-05 1.42086703740646e-05 -3.74124410324365e-06 3.44207605111614e-05 2.01014820995064e-06 2.90812410752991e-05 1.42086703740646e-05 5.74687809199192e-05 842 844 0 15 0 841 851 0 29 0 0 0 0 0 0 3 12 0 2457 0 0 0 0 0 1645 +877 908 0.995200133568605 0.000328130740587007 0.0978600351279753 -0.0137032001978345 -0.0147019459969558 0.989146294683234 0.146196650092717 -0.0235439739081975 -0.0967499195293415 -0.146933658651266 0.984403348748073 0.000738748946411527 3.1356562437457e-05 -3.07215050191068e-05 4.40322340376476e-06 -1.57490588355526e-05 -7.51342909624729e-06 2.09266951748476e-06 -3.07215050191068e-05 4.17575985776542e-05 -2.7055744976733e-06 2.4799709632168e-05 1.2269547365433e-05 6.12024818769797e-06 4.40322340376476e-06 -2.7055744976733e-06 9.47098235264304e-06 8.08720238060497e-07 2.88254665382302e-06 4.03478762553003e-06 -1.57490588355526e-05 2.4799709632168e-05 8.08720238060497e-07 6.94400425888591e-05 2.06574120051388e-05 1.30593814873645e-05 -7.51342909624729e-06 1.2269547365433e-05 2.88254665382302e-06 2.06574120051388e-05 2.67739036888853e-05 9.39093906042512e-06 2.09266951748476e-06 6.12024818769797e-06 4.03478762553003e-06 1.30593814873645e-05 9.39093906042512e-06 3.6719442779622e-05 855 854 0 15 0 855 862 0 29 0 0 0 0 0 0 1 11 0 2491 0 0 0 0 0 1721 +877 917 0.996957384336725 0.00201023604966872 0.0779226075507001 -0.0252865587529866 -0.0127902496161519 0.990336754341345 0.138092441919919 -0.0290578035838355 -0.0768920238466405 -0.138668929294468 0.987349251641532 -0.00802918422121768 4.709057164984e-05 -4.6527531436937e-05 -1.29851972408463e-06 -3.94645532522093e-05 -2.20342768991947e-05 -1.21069843353419e-05 -4.6527531436937e-05 8.33721026168948e-05 6.1548311797187e-06 6.47893206800629e-05 2.99225821244238e-05 3.28718273767453e-05 -1.29851972408463e-06 6.1548311797187e-06 1.20321719443502e-05 -2.23894792335083e-06 1.05077540248474e-06 1.16533809984479e-06 -3.94645532522093e-05 6.47893206800629e-05 -2.23894792335083e-06 0.000158414123480284 7.16518304624401e-05 5.50036391602618e-05 -2.20342768991947e-05 2.99225821244238e-05 1.05077540248474e-06 7.16518304624401e-05 6.78950321530814e-05 3.12772842144874e-05 -1.21069843353419e-05 3.28718273767453e-05 1.16533809984479e-06 5.50036391602618e-05 3.12772842144874e-05 7.48779265582667e-05 847 853 0 20 0 847 858 0 32 0 0 0 0 0 0 5 14 0 2216 0 0 0 0 0 1468 +877 909 0.996177698345494 0.000641203439701406 0.0873474795127035 -0.0236971805069697 -0.013185797888092 0.989618031791698 0.143116336896876 -0.0270602884559012 -0.0863488740698315 -0.143721049296457 0.985843867930413 0.00148801725864348 4.23671654099056e-05 -4.91044979012934e-05 -2.96265880843552e-06 -1.51517448825203e-05 -1.12502885915318e-05 7.03439217450797e-07 -4.91044979012934e-05 9.76870744153181e-05 6.72837151615856e-06 4.29237514897621e-05 2.30730946513087e-05 1.52274846311559e-05 -2.96265880843552e-06 6.72837151615856e-06 9.67403469026851e-06 1.65144480276172e-06 4.74533746110551e-06 1.61471298084522e-07 -1.51517448825203e-05 4.29237514897621e-05 1.65144480276172e-06 7.18938085657912e-05 1.89212621775498e-05 1.85219753279654e-05 -1.12502885915318e-05 2.30730946513087e-05 4.74533746110551e-06 1.89212621775498e-05 3.09564610020621e-05 1.13217430738866e-05 7.03439217450797e-07 1.52274846311559e-05 1.61471298084522e-07 1.85219753279654e-05 1.13217430738866e-05 4.07361347209026e-05 845 846 0 14 0 845 851 0 25 0 0 0 0 0 0 2 11 0 2459 0 0 0 0 0 1900 +877 915 0.996386128577326 0.00112227298026541 0.0849318743584895 -0.0255747799404158 -0.0130574594485298 0.990050910271074 0.140102454739976 -0.029331515209708 -0.0839296463202275 -0.140705136987868 0.986487647613383 -0.00395551649663359 5.70406691083795e-05 -6.99678871084403e-05 -7.61159049271638e-06 -2.87551770811967e-05 -1.72764232917391e-05 -8.28968095315259e-06 -6.99678871084403e-05 0.000106627395553957 1.1674418888086e-05 5.5975068287726e-05 3.14084448492093e-05 2.9226551744226e-05 -7.61159049271638e-06 1.1674418888086e-05 1.20696195638372e-05 4.81358914985665e-06 5.96966613680074e-06 2.15203726496826e-06 -2.87551770811967e-05 5.5975068287726e-05 4.81358914985665e-06 0.000106148057096938 3.60242572215274e-05 4.11342553115095e-05 -1.72764232917391e-05 3.14084448492093e-05 5.96966613680074e-06 3.60242572215274e-05 3.86851573223726e-05 1.88278338556102e-05 -8.28968095315259e-06 2.9226551744226e-05 2.15203726496826e-06 4.11342553115095e-05 1.88278338556102e-05 6.46865636403872e-05 867 869 0 14 0 867 872 0 23 0 0 0 0 0 0 3 8 0 2524 0 0 0 0 0 1414 +877 911 0.99578991474947 0.00062023421836959 0.0916627568468058 -0.0204084798213914 -0.0138931285278344 0.989445974327789 0.144234686765154 -0.0252782900660631 -0.0906058864696514 -0.144900928899878 0.985288939418788 -6.66277264069501e-05 3.83201637948293e-05 -4.28650167639788e-05 -2.87487601833756e-06 -1.17035737476e-05 -9.90793803013855e-06 2.76337496464894e-06 -4.28650167639788e-05 6.30409893211332e-05 3.66890672857278e-06 2.99431534389631e-05 1.95775727419312e-05 9.97428753278688e-06 -2.87487601833756e-06 3.66890672857278e-06 1.00350635705854e-05 -2.61989970930447e-06 2.42576808207098e-06 -1.52771943305822e-06 -1.17035737476e-05 2.99431534389631e-05 -2.61989970930447e-06 7.69855093984886e-05 2.38029593118738e-05 2.01311508613181e-05 -9.90793803013855e-06 1.95775727419312e-05 2.42576808207098e-06 2.38029593118738e-05 2.88697524807538e-05 1.14937660554205e-05 2.76337496464894e-06 9.97428753278688e-06 -1.52771943305822e-06 2.01311508613181e-05 1.14937660554205e-05 3.93218549439576e-05 878 885 0 17 0 878 889 0 28 0 0 0 0 0 0 1 9 0 2555 0 0 0 0 0 1902 +877 923 0.995209490289061 -1.30684455436203e-05 0.0977653837910038 -0.0164462991827656 -0.0142128715863539 0.98935693424115 0.144813158760598 -0.0244967879940268 -0.0967267528652562 -0.145508956762696 0.984617224499945 0.00208268833674482 3.03912670910074e-05 -3.10612263371507e-05 2.94537914000575e-06 -1.42780786807155e-05 -9.3058478696715e-06 3.23686897629805e-06 -3.10612263371507e-05 4.26871733952863e-05 -1.39186331884186e-06 1.98065032634516e-05 1.30220331036124e-05 4.46629039409715e-06 2.94537914000575e-06 -1.39186331884186e-06 9.42495552307439e-06 2.54572434094575e-06 3.35936992049092e-06 2.7504706771007e-06 -1.42780786807155e-05 1.98065032634516e-05 2.54572434094575e-06 5.00409116316278e-05 1.95557191654445e-05 1.23069431708028e-05 -9.3058478696715e-06 1.30220331036124e-05 3.35936992049092e-06 1.95557191654445e-05 3.047281197168e-05 1.18060337516021e-05 3.23686897629805e-06 4.46629039409715e-06 2.7504706771007e-06 1.23069431708028e-05 1.18060337516021e-05 3.98850425355587e-05 861 865 0 14 0 860 872 0 31 0 0 0 0 0 0 1 10 0 2425 0 0 0 0 0 1705 +877 910 0.995752821152902 0.000371854760094301 0.092066176688693 -0.0204849928274784 -0.0136236948863654 0.989578017499776 0.143351812750508 -0.0280222748057673 -0.0910533585524415 -0.143997253464262 0.985380168712091 -0.00119913107475881 4.9707178506873e-05 -7.43687434432879e-05 -1.00503714171506e-06 -2.78264115401355e-05 -1.56019219371526e-05 1.94158278769145e-06 -7.43687434432879e-05 0.000196865013150405 5.51990925087596e-06 0.000110880309816404 4.7759437358072e-05 3.16758351957828e-05 -1.00503714171506e-06 5.51990925087596e-06 9.39609082667084e-06 1.96704094781755e-06 4.89085406272447e-06 1.4913861617233e-06 -2.78264115401355e-05 0.000110880309816404 1.96704094781755e-06 0.000125718136892719 3.68982040792629e-05 3.21325842485517e-05 -1.56019219371526e-05 4.7759437358072e-05 4.89085406272447e-06 3.68982040792629e-05 3.65706833083021e-05 1.36516334550092e-05 1.94158278769145e-06 3.16758351957828e-05 1.4913861617233e-06 3.21325842485517e-05 1.36516334550092e-05 4.37493201079094e-05 857 863 0 15 0 856 867 0 26 0 0 0 0 0 0 2 11 0 2534 0 0 0 0 0 1892 +877 906 0.99549597152376 0.000162970241368047 0.0948037136438537 -0.0200017854077996 -0.0138861154546259 0.98946400163808 0.144111641653055 -0.0258758513426511 -0.093781375963174 -0.144779014028478 0.985009690622075 -0.000391092599040976 4.42007348051972e-05 -5.8676688785043e-05 -1.79280049375142e-06 -2.53336091760976e-05 -1.85003956584327e-05 2.66897775035427e-06 -5.8676688785043e-05 0.000125234323281166 7.48291228909439e-06 5.92386619326937e-05 3.30273824260587e-05 1.50918961784697e-05 -1.79280049375142e-06 7.48291228909439e-06 9.75025794679716e-06 3.15581312051361e-06 3.98196943834049e-06 6.78003485729062e-07 -2.53336091760976e-05 5.92386619326937e-05 3.15581312051361e-06 8.32767054539908e-05 3.0260941464502e-05 1.76834256576378e-05 -1.85003956584327e-05 3.30273824260587e-05 3.98196943834049e-06 3.0260941464502e-05 3.71011169177709e-05 8.06010999619855e-06 2.66897775035427e-06 1.50918961784697e-05 6.78003485729062e-07 1.76834256576378e-05 8.06010999619855e-06 3.80541974834037e-05 856 861 0 13 0 855 867 0 27 0 0 0 0 0 0 2 10 0 2539 0 0 0 0 0 1905 +877 905 0.995953036049212 0.000916912238679275 0.08987051383131 -0.0204461817690061 -0.0138161722195416 0.989624035520278 0.14301531982889 -0.0270165727878227 -0.0888068880749522 -0.143678208481684 0.985631730941094 0.000738616629285733 2.09314352408562e-05 -2.28438915355982e-05 3.77904433481341e-06 -1.10665813370766e-05 -8.45223665161449e-07 2.56117414209244e-06 -2.28438915355982e-05 4.33768145838189e-05 -1.45229325655639e-06 1.7792757580244e-05 5.85856025592907e-06 3.8871028968978e-06 3.77904433481341e-06 -1.45229325655639e-06 8.43387523120043e-06 1.42592424960896e-07 1.99754483244516e-06 1.34303825308036e-06 -1.10665813370766e-05 1.7792757580244e-05 1.42592424960896e-07 5.75534419059383e-05 1.48900027410027e-05 4.07269918799791e-06 -8.45223665161449e-07 5.85856025592907e-06 1.99754483244516e-06 1.48900027410027e-05 2.24636645209003e-05 7.92376805565655e-06 2.56117414209244e-06 3.8871028968978e-06 1.34303825308036e-06 4.07269918799791e-06 7.92376805565655e-06 2.85329209534028e-05 865 870 0 15 0 864 875 0 26 0 0 0 0 0 0 2 10 0 2521 0 0 0 0 0 1903 +877 925 0.99528318562693 0.000179469576119234 0.0970121033633469 -0.0189313966149694 -0.0141826152550051 0.989523420137253 0.143674125800024 -0.0252657921530784 -0.0959699631803511 -0.144372326955494 0.984858567194609 0.00159982111886753 2.55394795232996e-05 -2.59844237710283e-05 3.43473147255534e-06 -1.14088413616896e-05 -4.69466664420401e-06 1.77190588943979e-06 -2.59844237710283e-05 3.94893584954645e-05 -9.87905304511652e-07 2.19582666507415e-05 9.27817175047416e-06 5.69038599437567e-06 3.43473147255534e-06 -9.87905304511652e-07 9.67209857130403e-06 3.45215517615027e-06 2.37701852818955e-06 4.09950910586018e-06 -1.14088413616896e-05 2.19582666507415e-05 3.45215517615027e-06 5.95304466904444e-05 1.48806657291025e-05 1.47840227823771e-05 -4.69466664420401e-06 9.27817175047416e-06 2.37701852818955e-06 1.48806657291025e-05 2.51142066460589e-05 1.07336876536475e-05 1.77190588943979e-06 5.69038599437567e-06 4.09950910586018e-06 1.47840227823771e-05 1.07336876536475e-05 3.70178236800979e-05 857 864 0 16 0 856 867 0 26 0 0 0 0 0 0 1 9 0 2437 0 0 0 0 0 1887 +877 924 0.996086315891687 0.000590902103491344 0.0883838340876309 -0.0213886278967936 -0.0129579460990323 0.990149065918637 0.13941635088233 -0.0283225091355351 -0.087430789349178 -0.140015992283576 0.986281592132098 -0.00328995944867936 4.43485743426228e-05 -4.65391889379028e-05 -2.80421922363315e-06 -2.49536567233386e-05 -1.33757902867396e-05 -1.17964948924368e-05 -4.65391889379028e-05 6.87212406896961e-05 5.38137471056453e-06 3.85847315110718e-05 2.08994770317749e-05 2.73635590907433e-05 -2.80421922363315e-06 5.38137471056453e-06 1.00893479955469e-05 3.41376687203661e-06 3.46179947395803e-06 1.83226619075809e-06 -2.49536567233386e-05 3.85847315110718e-05 3.41376687203661e-06 7.63395783599728e-05 2.80966787982274e-05 2.94056577489819e-05 -1.33757902867396e-05 2.08994770317749e-05 3.46179947395803e-06 2.80966787982274e-05 3.36163715178708e-05 1.77688254214963e-05 -1.17964948924368e-05 2.73635590907433e-05 1.83226619075809e-06 2.94056577489819e-05 1.77688254214963e-05 5.39300693960801e-05 862 863 0 18 0 862 866 0 28 0 0 0 0 0 0 4 9 0 2506 0 0 0 0 0 1449 +877 907 0.996628461152014 0.00107446121665576 0.0820399655952048 -0.0261415060098487 -0.0128219502765617 0.98966841545095 0.142800647932389 -0.026912321442396 -0.0810389289963401 -0.14337110235992 0.986345486629927 -0.000156433983694792 4.7085420722522e-05 -6.26770110567358e-05 -5.06249020205826e-06 -2.17453281289774e-05 -1.22800815744736e-05 1.36243095330997e-06 -6.26770110567358e-05 0.000142735141467846 9.98208925897302e-06 7.76667978975071e-05 3.15987472016664e-05 1.99520908501793e-05 -5.06249020205826e-06 9.98208925897302e-06 1.0701170036315e-05 2.59518248464795e-06 4.63290016494908e-06 -3.44124938365615e-07 -2.17453281289774e-05 7.76667978975071e-05 2.59518248464795e-06 0.000103113722059428 3.27822108379524e-05 2.59820078005036e-05 -1.22800815744736e-05 3.15987472016664e-05 4.63290016494908e-06 3.27822108379524e-05 3.37867141480464e-05 1.03701657018338e-05 1.36243095330997e-06 1.99520908501793e-05 -3.44124938365615e-07 2.59820078005036e-05 1.03701657018338e-05 4.50188533742494e-05 856 859 0 12 0 855 864 0 25 0 0 0 0 0 0 2 9 0 2538 0 0 0 0 0 1892 +878 880 0.999998495181657 0.00162102556525986 0.000617989108386863 -0.00838536889988497 -0.00162519049698253 0.999975561549261 0.00679963676154523 -0.0048320929536732 -0.000606951620665535 -0.00680063087935329 0.999976691243037 -0.00264145215466616 4.00543894960341e-05 -4.65585700166843e-05 2.82992080176787e-06 -2.52567780535812e-05 -1.74106760292661e-05 7.71852068715064e-06 -4.65585700166843e-05 7.28633160333876e-05 -2.62336227487058e-06 5.75494939353525e-05 3.84212313910624e-05 4.08671070008177e-06 2.82992080176787e-06 -2.62336227487058e-06 8.65324552480294e-06 1.21495463070679e-06 2.6475158767638e-06 1.51594336234672e-06 -2.52567780535812e-05 5.75494939353525e-05 1.21495463070679e-06 9.85900265346265e-05 5.17477888404532e-05 1.9909689275507e-05 -1.74106760292661e-05 3.84212313910624e-05 2.6475158767638e-06 5.17477888404532e-05 5.08873894805213e-05 1.64403460381261e-05 7.71852068715064e-06 4.08671070008177e-06 1.51594336234672e-06 1.9909689275507e-05 1.64403460381261e-05 4.03709596875754e-05 730 727 0 6 0 728 738 0 19 0 0 0 0 0 0 10 21 0 2080 0 0 0 0 0 2514 +878 919 0.995765337238814 -0.00315846839377741 0.0918771855853025 -0.0143236685019904 -0.0101193501264002 0.989570704243272 0.143692101580056 -0.0267308220677706 -0.0913728182048137 -0.144013351397984 0.985348244384913 0.000994160850509357 4.01602517518366e-05 -4.3162480629153e-05 -3.28254668435215e-06 -1.5073594694461e-05 -1.19496166091903e-05 9.32519946116331e-07 -4.3162480629153e-05 6.51480384271416e-05 4.39444551398536e-06 3.38800422101548e-05 2.18923635243817e-05 1.5451477380676e-05 -3.28254668435215e-06 4.39444551398536e-06 1.02184325202263e-05 2.25878602373985e-06 3.34614608378616e-06 -2.12795397156779e-06 -1.5073594694461e-05 3.38800422101548e-05 2.25878602373985e-06 7.51849219746694e-05 2.52455885059503e-05 2.55211216053101e-05 -1.19496166091903e-05 2.18923635243817e-05 3.34614608378616e-06 2.52455885059503e-05 3.7633937618569e-05 1.27560377891185e-05 9.32519946116331e-07 1.5451477380676e-05 -2.12795397156779e-06 2.55211216053101e-05 1.27560377891185e-05 4.94022428434616e-05 844 848 0 12 0 844 855 0 23 0 0 0 0 0 0 5 13 0 2310 0 0 0 0 0 1718 +877 904 0.996631656750176 0.0013075762149328 0.0819977500169463 -0.0270464269565699 -0.0127758615795835 0.990140582212065 0.139493386286418 -0.0288909394565947 -0.08100690170781 -0.140071116584378 0.986822154278321 -0.00546546824132521 5.48827699656092e-05 -7.13725478351971e-05 -2.95354086785127e-06 -4.10342037776214e-05 -2.07209933814026e-05 -1.3000465676656e-05 -7.13725478351971e-05 0.000120794157425409 5.72522195627766e-06 8.83408020436539e-05 4.24203592471781e-05 4.1755780205593e-05 -2.95354086785127e-06 5.72522195627766e-06 1.10278082548481e-05 1.66516795206296e-06 4.8206796373175e-06 9.9354602304473e-07 -4.10342037776214e-05 8.83408020436539e-05 1.66516795206296e-06 0.000146352377101877 5.26310399089113e-05 6.06983848225535e-05 -2.07209933814026e-05 4.24203592471781e-05 4.8206796373175e-06 5.26310399089113e-05 4.42784881673078e-05 2.68037818621125e-05 -1.3000465676656e-05 4.1755780205593e-05 9.9354602304473e-07 6.06983848225535e-05 2.68037818621125e-05 6.57606842812619e-05 824 828 0 18 0 824 834 0 30 0 0 0 0 0 0 3 14 0 2515 0 0 0 0 0 1422 +878 882 0.999986978768818 0.00156408012404754 0.00485756586951652 -0.00974039401916138 -0.0016285270911832 0.999910333371952 0.0132918439467419 -0.00696074619982188 -0.00483634079903544 -0.0132995815481847 0.999899860455195 -0.000524604514128896 4.28434200755981e-05 -5.12917029252441e-05 6.74968439376635e-06 -2.82769704317557e-05 -1.46293579051072e-05 7.74993438006965e-06 -5.12917029252441e-05 7.76048462377589e-05 -7.66260094009849e-06 6.25870242700521e-05 3.36083634790494e-05 5.12842728067171e-08 6.74968439376635e-06 -7.66260094009849e-06 9.52363070671839e-06 -5.79407916068975e-06 4.25579767011371e-07 1.02919740526501e-06 -2.82769704317557e-05 6.25870242700521e-05 -5.79407916068975e-06 0.000132960497741295 5.01141893919368e-05 1.19699047740082e-05 -1.46293579051072e-05 3.36083634790494e-05 4.25579767011371e-07 5.01141893919368e-05 4.55711943402732e-05 1.29821689253972e-05 7.74993438006965e-06 5.12842728067171e-08 1.02919740526501e-06 1.19699047740082e-05 1.29821689253972e-05 3.9407808031288e-05 809 807 0 10 0 805 817 0 25 0 0 0 0 0 0 6 18 0 2101 0 0 0 0 0 1542 +878 922 0.99556365884403 -0.00353165322297827 0.0940240852898863 -0.0111763993521503 -0.0102988997597605 0.989200807981362 0.146204289105207 -0.0235554805290378 -0.0935250439872956 -0.146524021629674 0.984776003582866 -0.00185315875024327 2.62192002549511e-05 -2.76427440447805e-05 -1.81175459553321e-07 -8.04233319502762e-06 -1.33325955477785e-07 2.75563220815093e-06 -2.76427440447805e-05 6.25731724211704e-05 3.87034394026309e-06 2.80726092626325e-05 9.07020486882386e-06 9.7529468932921e-06 -1.81175459553321e-07 3.87034394026309e-06 1.0117444242541e-05 1.80330108203649e-06 2.50770465709066e-06 1.50369385829356e-06 -8.04233319502762e-06 2.80726092626325e-05 1.80330108203649e-06 7.7460274970168e-05 2.46342813917486e-05 1.61688536124789e-05 -1.33325955477785e-07 9.07020486882386e-06 2.50770465709066e-06 2.46342813917486e-05 3.04887842193372e-05 8.89196698408588e-06 2.75563220815093e-06 9.7529468932921e-06 1.50369385829356e-06 1.61688536124789e-05 8.89196698408588e-06 3.65101272283045e-05 854 855 0 14 0 850 859 0 23 0 0 0 0 0 0 5 12 0 2527 0 0 0 0 0 1613 +877 903 0.995656668908261 0.000833789083723684 0.0930972741505905 -0.0166266765656252 -0.0142462964624599 0.989547948058649 0.143498785813754 -0.0250103802022844 -0.0920045688844312 -0.144201814443099 0.985261892095553 -0.000317831090003092 4.0980695012671e-05 -4.05412447911191e-05 -3.67061839321264e-06 -1.07472933060127e-05 -6.29875156797625e-06 -9.51878163430486e-06 -4.05412447911191e-05 5.73477939324758e-05 6.28667044709259e-06 1.35751401012112e-05 8.14807878733356e-06 2.08800502429675e-05 -3.67061839321264e-06 6.28667044709259e-06 1.05261920183624e-05 3.32795986074087e-07 2.96432346894412e-06 2.8079224416655e-07 -1.07472933060127e-05 1.35751401012112e-05 3.32795986074087e-07 5.09580815160632e-05 9.67163721285574e-06 1.82082631172465e-05 -6.29875156797625e-06 8.14807878733356e-06 2.96432346894412e-06 9.67163721285574e-06 2.33559345590557e-05 8.53861497880254e-06 -9.51878163430486e-06 2.08800502429675e-05 2.8079224416655e-07 1.82082631172465e-05 8.53861497880254e-06 5.1181490816953e-05 865 865 0 12 0 864 873 0 27 0 0 0 0 0 0 0 9 0 2483 0 0 0 0 0 1560 +878 926 0.995897469490518 -0.00366472429839046 0.0904146009126773 -0.0179910729355302 -0.00962693678242951 0.989217952485866 0.146134063680783 -0.0263211264990731 -0.0899752874436587 -0.146404959873253 0.98512437558612 0.0010456788974491 3.77936286001894e-05 -3.93057676139212e-05 -1.91292323585493e-06 -1.80104685943713e-05 -1.41381691854727e-05 1.17899100700855e-05 -3.93057676139212e-05 6.33906873996707e-05 3.9965326958488e-06 3.79779191206199e-05 2.52345469098191e-05 -1.09483782250743e-06 -1.91292323585493e-06 3.9965326958488e-06 9.16203656992798e-06 3.26348171174745e-06 5.00995311037562e-06 2.44285341097182e-07 -1.80104685943713e-05 3.79779191206199e-05 3.26348171174745e-06 6.93385492023835e-05 2.6422280522986e-05 9.48065345702653e-06 -1.41381691854727e-05 2.52345469098191e-05 5.00995311037562e-06 2.6422280522986e-05 3.46163199718437e-05 8.17177699343851e-06 1.17899100700855e-05 -1.09483782250743e-06 2.44285341097182e-07 9.48065345702653e-06 8.17177699343851e-06 3.70017420890955e-05 848 851 0 13 0 846 857 0 24 0 0 0 0 0 0 3 11 0 2456 0 0 0 0 0 2095 +878 914 0.995803914629309 -0.00408532506904201 0.0914214073837443 -0.0166719347525307 -0.00934003175448215 0.989249022975241 0.145942229492891 -0.0252238856371617 -0.0910347593821697 -0.146183722286753 0.985059892556092 -0.00218155918664134 2.56105686290023e-05 -3.02798810226172e-05 3.49189261451373e-07 -4.994240533901e-07 -2.21904402928365e-06 1.89902374245939e-06 -3.02798810226172e-05 8.45195191717534e-05 5.62383161337165e-06 1.86130955668664e-05 1.32104147060346e-05 1.31855386592028e-05 3.49189261451373e-07 5.62383161337165e-06 1.00752303181574e-05 1.36149143569703e-06 4.25515674699823e-06 7.60626443400271e-07 -4.994240533901e-07 1.86130955668664e-05 1.36149143569703e-06 4.56215995584004e-05 9.3713518224589e-06 8.31535985808311e-06 -2.21904402928365e-06 1.32104147060346e-05 4.25515674699823e-06 9.3713518224589e-06 2.27864484231109e-05 3.24907693988684e-06 1.89902374245939e-06 1.31855386592028e-05 7.60626443400271e-07 8.31535985808311e-06 3.24907693988684e-06 3.67871901616906e-05 875 879 0 12 0 873 885 0 26 0 0 0 0 0 0 5 14 0 2518 0 0 0 0 0 1531 +878 916 0.995700816594959 -0.00345178038836571 0.0925633245096725 -0.0129617103673431 -0.0100902755876129 0.98931658822988 0.1454334025998 -0.0257120991829746 -0.0920764365660318 -0.145742147182413 0.985028505356044 -0.000649060257773894 5.86569861852246e-05 -6.21089916591393e-05 -7.28009184859782e-06 -1.65877626832372e-05 -1.22682316283655e-05 2.56625290289598e-06 -6.21089916591393e-05 9.41511613858299e-05 1.11974458286805e-05 4.25248192560953e-05 2.66353809986273e-05 1.59954186819304e-05 -7.28009184859782e-06 1.11974458286805e-05 1.16085475672823e-05 1.72541614728168e-06 4.21496704821064e-06 5.50231381850398e-07 -1.65877626832372e-05 4.25248192560953e-05 1.72541614728168e-06 9.72478315057336e-05 3.09711389950903e-05 2.74277271582402e-05 -1.22682316283655e-05 2.66353809986273e-05 4.21496704821064e-06 3.09711389950903e-05 3.45546036634255e-05 1.53001367956838e-05 2.56625290289598e-06 1.59954186819304e-05 5.50231381850398e-07 2.74277271582402e-05 1.53001367956838e-05 4.71056403573502e-05 835 839 0 12 0 835 844 0 20 0 0 0 0 0 0 6 11 0 2391 0 0 0 0 0 1681 +878 920 0.995087908492829 -0.00447213526322596 0.0988941574490365 -0.00781360463182264 -0.0100307124238739 0.989282778683551 0.145667321690286 -0.0250421575590793 -0.0984857308427823 -0.145943769330311 0.984378472445443 0.00151127334038629 4.81655320853838e-05 -5.53821516279321e-05 -3.73778906998332e-06 -1.86286482934468e-05 -1.10883012647597e-05 -7.75855956398084e-06 -5.53821516279321e-05 9.04312546798603e-05 6.88265234433006e-06 3.68045006443243e-05 2.05087551866154e-05 3.07640965169956e-05 -3.73778906998332e-06 6.88265234433006e-06 1.11878701557048e-05 6.78621431665724e-07 3.74196431876382e-06 -2.87186584955838e-07 -1.86286482934468e-05 3.68045006443243e-05 6.78621431665724e-07 7.5367767961416e-05 2.76286756307972e-05 2.9016788471682e-05 -1.10883012647597e-05 2.05087551866154e-05 3.74196431876382e-06 2.76286756307972e-05 3.55611614144876e-05 1.56818120137568e-05 -7.75855956398084e-06 3.07640965169956e-05 -2.87186584955838e-07 2.9016788471682e-05 1.56818120137568e-05 6.24025701807379e-05 843 843 0 9 0 841 846 0 17 0 0 0 0 0 0 5 9 0 2287 0 0 0 0 0 1522 +878 881 0.999980350936123 0.00210074718793549 0.0059063188976704 -0.00293558382608597 -0.00216964382437466 0.999929399971469 0.0116827958286662 -0.00195436712095956 -0.00588135931090341 -0.0116953808809859 0.999914310167979 0.00253626212083069 3.79132001534816e-05 -4.50431148713863e-05 1.77240575001177e-06 -2.09505096716104e-05 -1.65388562421457e-05 1.86194845271447e-05 -4.50431148713863e-05 9.06385017288672e-05 -1.53151059926873e-06 6.08471068165853e-05 3.64914901719028e-05 -1.44524539821067e-05 1.77240575001177e-06 -1.53151059926873e-06 8.87980169040732e-06 -4.75484655742024e-08 7.11007570789836e-07 -1.57208357310605e-06 -2.09505096716104e-05 6.08471068165853e-05 -4.75484655742024e-08 0.000102626890555198 4.54791030757774e-05 7.92149733726629e-06 -1.65388562421457e-05 3.64914901719028e-05 7.11007570789836e-07 4.54791030757774e-05 4.50696182272557e-05 -3.38073768472515e-07 1.86194845271447e-05 -1.44524539821067e-05 -1.57208357310605e-06 7.92149733726629e-06 -3.38073768472515e-07 4.49134446968753e-05 792 792 0 8 0 792 803 0 18 0 0 0 0 0 0 8 19 0 2072 0 0 0 0 0 2616 +878 921 0.995735573359563 -0.00407792513334927 0.0921631079820407 -0.0141626349105276 -0.00944356667176937 0.989268886804473 0.1458008527038 -0.0258308512981904 -0.0917686601995384 -0.146049444118238 0.985011712051149 0.00189332199179826 2.62590627284555e-05 -2.61622413022402e-05 3.19914385901474e-06 -9.35022134049004e-06 -4.78651851648794e-06 -8.50520729002383e-07 -2.61622413022402e-05 4.87231198445308e-05 -7.35888443585386e-07 2.59170609997993e-05 1.02654214312087e-05 8.71447159944399e-06 3.19914385901474e-06 -7.35888443585386e-07 8.63356650243566e-06 3.27157031500537e-06 3.10710418942133e-06 1.36950243541613e-06 -9.35022134049004e-06 2.59170609997993e-05 3.27157031500537e-06 5.78376731488186e-05 1.45367471737805e-05 7.30730021548676e-06 -4.78651851648794e-06 1.02654214312087e-05 3.10710418942133e-06 1.45367471737805e-05 2.60686679048688e-05 5.77323767178225e-06 -8.50520729002383e-07 8.71447159944399e-06 1.36950243541613e-06 7.30730021548676e-06 5.77323767178225e-06 2.93253394958085e-05 844 842 0 13 0 837 848 0 25 0 0 0 0 0 0 7 15 0 2402 0 0 0 0 0 1783 +878 913 0.995795046873665 -0.00364103577830467 0.0915367001826926 -0.0170711081977183 -0.00984275134496743 0.989173263459975 0.146421907861848 -0.0247383335002874 -0.091078783851324 -0.146707183581458 0.984977998443498 -0.00175678684348671 2.02482453072248e-05 -1.80025215052862e-05 2.14836843057792e-06 -6.0003818171344e-07 -2.9415059098921e-07 7.78904947522711e-06 -1.80025215052862e-05 4.88138972415651e-05 2.0622265255265e-06 1.29921956329449e-05 1.02707911897322e-05 -4.82380427918075e-06 2.14836843057792e-06 2.0622265255265e-06 8.86363896034572e-06 1.12055575183538e-06 4.23208280134577e-06 -1.04416577292879e-06 -6.0003818171344e-07 1.29921956329449e-05 1.12055575183538e-06 4.77522580454209e-05 9.28749875864308e-06 3.80767024024059e-06 -2.9415059098921e-07 1.02707911897322e-05 4.23208280134577e-06 9.28749875864308e-06 2.33348764613936e-05 2.40968158576037e-06 7.78904947522711e-06 -4.82380427918075e-06 -1.04416577292879e-06 3.80767024024059e-06 2.40968158576037e-06 2.75223080767836e-05 876 880 0 13 0 873 885 0 23 0 0 0 0 0 0 7 14 0 2436 0 0 0 0 0 2094 +878 927 0.995882313185071 -0.00378945307811342 0.0905762569911169 -0.01949610612635 -0.00948172403999793 0.989292164230074 0.145640347095868 -0.0271598137165223 -0.0901582785682014 -0.145899464832275 0.985182638380963 0.00198936434863334 3.74477809617317e-05 -3.60788260488513e-05 -4.2863726792436e-06 -5.68744327484929e-06 -8.13166699858024e-06 1.23503662698341e-05 -3.60788260488513e-05 6.21016327458605e-05 5.72475516213621e-06 2.67872105119832e-05 1.68984024093197e-05 -3.16515297031689e-06 -4.2863726792436e-06 5.72475516213621e-06 1.00439611417692e-05 9.08938170292111e-07 2.95251252295435e-06 -1.98512297788123e-06 -5.68744327484929e-06 2.67872105119832e-05 9.08938170292111e-07 6.93615326248098e-05 1.94081517171728e-05 7.63780936302191e-06 -8.13166699858024e-06 1.68984024093197e-05 2.95251252295435e-06 1.94081517171728e-05 2.75485222537703e-05 4.29546373316163e-06 1.23503662698341e-05 -3.16515297031689e-06 -1.98512297788123e-06 7.63780936302191e-06 4.29546373316163e-06 2.99016352382645e-05 845 850 0 13 0 844 856 0 24 0 0 0 0 0 0 5 13 0 2518 0 0 0 0 0 2097 +878 918 0.995635298403781 -0.00397509342480732 0.0932445773473035 -0.0123504818428281 -0.00971250509693421 0.989254656446752 0.145879717381004 -0.026592271016018 -0.0928225178346033 -0.146148634378443 0.984898246953542 0.00210939264361941 4.3685040507142e-05 -4.70005864144487e-05 -5.21227905833754e-06 -8.14608721513874e-06 -7.92855798014714e-06 3.18761113921765e-07 -4.70005864144487e-05 7.63651518513267e-05 7.74699269784541e-06 2.08228192354389e-05 1.50214912156899e-05 1.52532269199326e-05 -5.21227905833754e-06 7.74699269784541e-06 1.12485817098692e-05 2.45749291414413e-07 2.84556082147683e-06 -1.24607881749236e-06 -8.14608721513874e-06 2.08228192354389e-05 2.45749291414413e-07 6.05178589996409e-05 1.93551042288762e-05 2.12935749472786e-05 -7.92855798014714e-06 1.50214912156899e-05 2.84556082147683e-06 1.93551042288762e-05 3.17472576305803e-05 1.27157829980714e-05 3.18761113921765e-07 1.52532269199326e-05 -1.24607881749236e-06 2.12935749472786e-05 1.27157829980714e-05 4.96122907741942e-05 842 845 0 11 0 840 850 0 24 0 0 0 0 0 0 4 11 0 2220 0 0 0 0 0 1537 +878 912 0.996206771912363 -0.00329800087325517 0.0869551078786578 -0.0161392675051504 -0.00964778111551915 0.988934559547988 0.148038364119485 -0.0239912389645918 -0.0864811419645696 -0.148315744686349 0.985151486809332 0.00202873489804353 2.6083461645317e-05 -2.9224201395834e-05 1.92740561373875e-06 -1.37808277253809e-05 -5.94095436580338e-06 1.16378622130247e-06 -2.9224201395834e-05 6.16852413062911e-05 6.33543831176467e-07 3.70951581861766e-05 1.58179976751947e-05 1.48353364668692e-05 1.92740561373875e-06 6.33543831176467e-07 9.22712413357638e-06 1.02567256556705e-06 3.79715085428588e-06 6.07162752868822e-07 -1.37808277253809e-05 3.70951581861766e-05 1.02567256556705e-06 7.50144673894232e-05 2.30017294331561e-05 1.64563241963819e-05 -5.94095436580338e-06 1.58179976751947e-05 3.79715085428588e-06 2.30017294331561e-05 2.71362384807165e-05 8.1558092676741e-06 1.16378622130247e-06 1.48353364668692e-05 6.07162752868822e-07 1.64563241963819e-05 8.1558092676741e-06 3.09495916244598e-05 850 851 0 11 0 846 858 0 24 0 0 0 0 0 0 3 14 0 2469 0 0 0 0 0 1832 +878 928 0.996460460898369 -0.00331083454265309 0.0839975490168704 -0.0220188767212545 -0.00886610608089657 0.989511642293446 0.144180795977442 -0.0282935249853507 -0.083593911436017 -0.144415193592494 0.985979872933758 1.54213171381075e-05 3.89696936054185e-05 -4.17891810214545e-05 -3.53214711389871e-06 -8.42661560423229e-06 -8.47188614076771e-06 7.98768432368404e-06 -4.17891810214545e-05 7.12454045974503e-05 5.3462981676505e-06 3.11622655573345e-05 1.98772252313155e-05 6.47166305920781e-06 -3.53214711389871e-06 5.3462981676505e-06 9.59953061615791e-06 8.36157557473706e-07 5.20143771574674e-06 -1.11255690496517e-06 -8.42661560423229e-06 3.11622655573345e-05 8.36157557473706e-07 6.4464445696504e-05 1.91446244066283e-05 1.6098544194689e-05 -8.47188614076771e-06 1.98772252313155e-05 5.20143771574674e-06 1.91446244066283e-05 2.79260293890174e-05 6.0820389915727e-06 7.98768432368404e-06 6.47166305920781e-06 -1.11255690496517e-06 1.6098544194689e-05 6.0820389915727e-06 3.65442559468788e-05 857 858 0 11 0 853 864 0 23 0 0 0 0 0 0 5 12 0 2442 0 0 0 0 0 1835 +878 917 0.996620107281438 -0.00224168550705347 0.0821178215031419 -0.0158997284177763 -0.00982711253454543 0.989195910523184 0.146269882284228 -0.0239352202050024 -0.0815585042872157 -0.146582486847154 0.985830505172231 -0.00083945572094717 4.40919804448373e-05 -4.18618820700108e-05 -2.56710558872535e-06 -2.37055133261315e-05 -2.03276173431363e-05 1.19549831553753e-05 -4.18618820700108e-05 7.68303375237889e-05 7.06787027522038e-06 4.30683964777963e-05 2.71729870127212e-05 2.5012375501227e-06 -2.56710558872535e-06 7.06787027522038e-06 1.07667449404668e-05 -3.34348472672734e-07 1.18494861717445e-06 -8.66424720889921e-09 -2.37055133261315e-05 4.30683964777963e-05 -3.34348472672734e-07 0.000103045241389126 4.8729746548512e-05 1.15151679901068e-05 -2.03276173431363e-05 2.71729870127212e-05 1.18494861717445e-06 4.8729746548512e-05 4.96364972980259e-05 2.82381829750387e-06 1.19549831553753e-05 2.5012375501227e-06 -8.66424720889921e-09 1.15151679901068e-05 2.82381829750387e-06 3.65186831472808e-05 845 846 0 9 0 843 854 0 22 0 0 0 0 0 0 7 15 0 2186 0 0 0 0 0 2107 +878 923 0.995633035263759 -0.0042478518646462 0.0932567147502503 -0.0156331439464998 -0.00940301176663959 0.989320529582773 0.145452649050397 -0.0250209769375784 -0.0928786437303537 -0.145694356447316 0.98496025911618 -0.000481427261942907 3.12318645482187e-05 -3.78836019989199e-05 3.24225025514994e-07 -1.66247884735895e-05 -1.12684764906452e-05 3.68119166559884e-06 -3.78836019989199e-05 9.05050192443223e-05 4.88311268563117e-06 5.27947788853513e-05 2.92087588600258e-05 9.53423403577366e-06 3.24225025514994e-07 4.88311268563117e-06 9.99650629989525e-06 1.46760686039593e-06 5.09088775498859e-06 4.31899919697266e-07 -1.66247884735895e-05 5.27947788853513e-05 1.46760686039593e-06 9.40453675066218e-05 3.16160823395824e-05 2.0036875460526e-05 -1.12684764906452e-05 2.92087588600258e-05 5.09088775498859e-06 3.16160823395824e-05 3.62238327713048e-05 9.4787996952879e-06 3.68119166559884e-06 9.53423403577366e-06 4.31899919697266e-07 2.0036875460526e-05 9.4787996952879e-06 3.52140012538415e-05 861 865 0 13 0 859 871 0 25 0 0 0 0 0 0 4 13 0 2429 0 0 0 0 0 1669 +878 915 0.995901461011384 -0.00311895703952432 0.09039110610218 -0.013741839550115 -0.0102230452537232 0.989118700761746 0.146764045832541 -0.0249153341512806 -0.0898652841821039 -0.147086600036786 0.985032873963346 0.000615313579257351 3.36571112943778e-05 -3.49867357278724e-05 -2.4531325633776e-06 -9.95473837313155e-06 -8.46855109960706e-06 1.28684767397145e-05 -3.49867357278724e-05 5.49567357075154e-05 3.88180430578348e-06 2.75022899060779e-05 1.73580724567389e-05 -4.86726011968657e-06 -2.4531325633776e-06 3.88180430578348e-06 9.32036859988168e-06 1.56914540421995e-06 3.21957539916537e-06 -1.79813652802681e-06 -9.95473837313155e-06 2.75022899060779e-05 1.56914540421995e-06 6.19109488964598e-05 2.04085662736021e-05 1.12981260125014e-05 -8.46855109960706e-06 1.73580724567389e-05 3.21957539916537e-06 2.04085662736021e-05 2.89353249745423e-05 4.80705235128641e-06 1.28684767397145e-05 -4.86726011968657e-06 -1.79813652802681e-06 1.12981260125014e-05 4.80705235128641e-06 3.61291315808138e-05 844 842 0 11 0 842 848 0 21 0 0 0 0 0 0 3 9 0 2538 0 0 0 0 0 2102 +878 910 0.996341156991219 -0.00323361639308707 0.085403996454621 -0.0164115703903875 -0.00928517391755666 0.989273566998558 0.145779268701936 -0.0267781417110102 -0.0849593104416419 -0.146038876204156 0.985623945633581 -0.00120327900855898 6.68692536528496e-05 -8.94966545773361e-05 -3.38919279061363e-06 -4.03130775666263e-05 -2.24671269510381e-05 -2.89100141541164e-06 -8.94966545773361e-05 0.000162244550561699 9.68999404827143e-06 8.48946004672443e-05 4.34679683189609e-05 2.55868082173911e-05 -3.38919279061363e-06 9.68999404827143e-06 1.12246229132951e-05 6.52223878990762e-06 7.81332885561868e-06 2.71712044481706e-06 -4.03130775666263e-05 8.48946004672443e-05 6.52223878990762e-06 9.56572113107166e-05 3.65318737534674e-05 3.22065342252524e-05 -2.24671269510381e-05 4.34679683189609e-05 7.81332885561868e-06 3.65318737534674e-05 3.69575150057482e-05 1.87917547767521e-05 -2.89100141541164e-06 2.55868082173911e-05 2.71712044481706e-06 3.22065342252524e-05 1.87917547767521e-05 5.39343054325828e-05 867 872 0 13 0 867 880 0 28 0 0 0 0 0 0 6 15 0 2506 0 0 0 0 0 1499 +878 909 0.996581775912592 -0.0033257111253807 0.0825451607570987 -0.0199165835643404 -0.00861285493970317 0.989561514118803 0.14385349667175 -0.0268458703200652 -0.0821619294362807 -0.144072722679945 0.986150327247776 -0.00173901640469442 4.74561669042639e-05 -5.5629852838487e-05 -3.56824072181998e-06 -3.04135210926676e-05 -1.88829603255722e-05 -5.83534142061481e-06 -5.5629852838487e-05 8.27720268910837e-05 5.52369484226856e-06 5.20478088892046e-05 3.2333829309477e-05 2.37005152376897e-05 -3.56824072181998e-06 5.52369484226856e-06 1.12773643923294e-05 1.70318587077018e-06 5.84467168341681e-06 -1.05386640449566e-07 -3.04135210926676e-05 5.20478088892046e-05 1.70318587077018e-06 8.20818979307614e-05 3.16207470788994e-05 3.20333691881938e-05 -1.88829603255722e-05 3.2333829309477e-05 5.84467168341681e-06 3.16207470788994e-05 3.6456496553635e-05 1.8649584357106e-05 -5.83534142061481e-06 2.37005152376897e-05 -1.05386640449566e-07 3.20333691881938e-05 1.8649584357106e-05 5.76977970134156e-05 844 846 0 14 0 842 851 0 22 0 0 0 0 0 0 5 13 0 2461 0 0 0 0 0 1491 +878 911 0.995425640598559 -0.00372125742864293 0.0954669905365107 -0.0110637870262631 -0.0104537561796364 0.988999190027922 0.1475510796499 -0.0226617956100174 -0.0949658518662639 -0.147874116623783 0.984436251167159 0.00134218372978419 5.43683377153379e-05 -6.01290655370147e-05 -2.91145616023841e-06 -2.27222192001059e-05 -1.58993055687538e-05 -9.49927411664625e-06 -6.01290655370147e-05 8.43501063509148e-05 4.07405089559636e-06 4.59980995134616e-05 2.75088016945947e-05 2.68936739697378e-05 -2.91145616023841e-06 4.07405089559636e-06 1.09345690575458e-05 -6.17694632392834e-08 3.82241991451917e-06 9.69988834128553e-07 -2.27222192001059e-05 4.59980995134616e-05 -6.17694632392834e-08 8.43714024828149e-05 3.0715360604942e-05 3.37320906200231e-05 -1.58993055687538e-05 2.75088016945947e-05 3.82241991451917e-06 3.0715360604942e-05 3.47420321006655e-05 1.94057859736908e-05 -9.49927411664625e-06 2.68936739697378e-05 9.69988834128553e-07 3.37320906200231e-05 1.94057859736908e-05 5.54095525835447e-05 844 849 0 15 0 843 852 0 20 0 0 0 0 0 0 6 10 0 2532 0 0 0 0 0 1548 +878 907 0.996292519211472 -0.00297993130167338 0.0859786960397481 -0.0150399880158969 -0.00964394086949972 0.989232190823513 0.14603652640014 -0.0241336485364407 -0.0854880726637563 -0.146324272244732 0.985535893199373 -0.00091976967687545 4.32043688466518e-05 -4.57263229248823e-05 -8.26746209588141e-07 -1.70992136026303e-05 -8.71497292787989e-06 -1.03709158571291e-06 -4.57263229248823e-05 6.66778218301092e-05 1.94210198294989e-06 3.5315514140136e-05 1.87458033583103e-05 1.52945060471547e-05 -8.26746209588141e-07 1.94210198294989e-06 1.10771895900739e-05 -1.49826930169083e-06 3.4898000157251e-06 -1.61595067914546e-06 -1.70992136026303e-05 3.5315514140136e-05 -1.49826930169083e-06 8.53370145047306e-05 3.3844886747523e-05 2.46786859625508e-05 -8.71497292787989e-06 1.87458033583103e-05 3.4898000157251e-06 3.3844886747523e-05 3.52973940416646e-05 1.43659391018144e-05 -1.03709158571291e-06 1.52945060471547e-05 -1.61595067914546e-06 2.46786859625508e-05 1.43659391018144e-05 4.91480225253001e-05 852 856 0 12 0 851 863 0 25 0 0 0 0 0 0 5 14 0 2545 0 0 0 0 0 1517 +878 908 0.995374009993306 -0.00400296041816309 0.0959924816729729 -0.0104929131306487 -0.0102780292484418 0.988961421836414 0.147816332771678 -0.0226680014181895 -0.0955245640901522 -0.148119149427716 0.984345353637734 -0.00103182152594473 3.4878383506513e-05 -4.15677039660417e-05 1.68502932707322e-06 -2.80423853880437e-05 -1.12835293785952e-05 -9.52286166816034e-07 -4.15677039660417e-05 9.08752272014491e-05 3.16326740692028e-06 6.87920149878617e-05 2.8952203679492e-05 1.77167543943045e-05 1.68502932707322e-06 3.16326740692028e-06 1.03310887640995e-05 1.85484882054208e-06 4.80021498597684e-06 1.91371257459043e-06 -2.80423853880437e-05 6.87920149878617e-05 1.85484882054208e-06 0.000124476130252905 4.17807542873471e-05 2.51803829578886e-05 -1.12835293785952e-05 2.8952203679492e-05 4.80021498597684e-06 4.17807542873471e-05 3.54638291126483e-05 9.68083147981628e-06 -9.52286166816034e-07 1.77167543943045e-05 1.91371257459043e-06 2.51803829578886e-05 9.68083147981628e-06 4.18800516149081e-05 849 852 0 15 0 843 855 0 24 0 0 0 0 0 0 7 13 0 2466 0 0 0 0 0 1633 +878 906 0.996365725101724 -0.00315745393663472 0.0851197528612147 -0.0178206263199137 -0.00930621170216145 0.989295258971875 0.145630645811677 -0.0256534520686343 -0.0846683900063701 -0.145893526451346 0.985670504110435 -0.000981982998278668 3.79598232645841e-05 -4.5835400411171e-05 8.23226336600072e-09 -1.81733337330477e-05 -1.10596977222384e-05 -1.85240927636984e-06 -4.5835400411171e-05 9.06837638724788e-05 4.09534879842857e-06 4.79299103446854e-05 2.51126352353467e-05 2.16035161848921e-05 8.23226336600072e-09 4.09534879842857e-06 1.02296641744449e-05 1.22174503891902e-06 5.74074722380524e-06 1.14135399418371e-06 -1.81733337330477e-05 4.79299103446854e-05 1.22174503891902e-06 8.12463267315922e-05 2.5419113042568e-05 2.54923922489486e-05 -1.10596977222384e-05 2.51126352353467e-05 5.74074722380524e-06 2.5419113042568e-05 3.15400354571965e-05 1.19419404356302e-05 -1.85240927636984e-06 2.16035161848921e-05 1.14135399418371e-06 2.54923922489486e-05 1.19419404356302e-05 4.3010247371288e-05 883 885 0 9 0 881 892 0 23 0 0 0 0 0 0 5 14 0 2540 0 0 0 0 0 1516 +878 905 0.99586945436107 -0.00359745758227192 0.0907253446922541 -0.0135548175994785 -0.00975411742114197 0.989193335305279 0.146292182227735 -0.0249215099049168 -0.0902711862330342 -0.146572861357626 0.9850723370644 -0.00154820302457585 3.62063371933581e-05 -4.16200664215052e-05 2.96697506484421e-06 -1.75475858858148e-05 -7.40135072393076e-06 -2.49898743411739e-06 -4.16200664215052e-05 6.60318100666606e-05 -9.49369092713907e-08 3.53860929845915e-05 1.90011605304173e-05 1.01906520797672e-05 2.96697506484421e-06 -9.49369092713907e-08 1.04644515911981e-05 3.83647598797743e-06 5.06951780118012e-06 2.12191317550247e-06 -1.75475858858148e-05 3.53860929845915e-05 3.83647598797743e-06 7.52644528432667e-05 2.93291900587762e-05 1.48071875954229e-05 -7.40135072393076e-06 1.90011605304173e-05 5.06951780118012e-06 2.93291900587762e-05 3.19616804485673e-05 1.06018349037599e-05 -2.49898743411739e-06 1.01906520797672e-05 2.12191317550247e-06 1.48071875954229e-05 1.06018349037599e-05 3.39527424563519e-05 853 856 0 10 0 853 863 0 24 0 0 0 0 0 0 6 13 0 2555 0 0 0 0 0 1546 +878 924 0.995529720980076 -0.00358019467930168 0.0943809135969223 -0.010916374181954 -0.0103473567037449 0.989132083864375 0.146665104504665 -0.0237049122946092 -0.0938802793699341 -0.146986063544055 0.984673341910527 -0.000181526945806287 3.19045507576025e-05 -3.18886579599029e-05 -2.01008870513942e-07 -1.0433226226332e-05 -6.4262686217624e-06 8.68556486330221e-06 -3.18886579599029e-05 5.36569223099968e-05 2.93527804965013e-06 2.42050017287444e-05 1.33442117815264e-05 -1.31494482553634e-07 -2.01008870513942e-07 2.93527804965013e-06 9.66547775455285e-06 4.91694915232285e-07 3.23578722159879e-06 1.51391618096375e-06 -1.0433226226332e-05 2.42050017287444e-05 4.91694915232285e-07 6.35727505549694e-05 2.06589598118758e-05 9.15800720665069e-06 -6.4262686217624e-06 1.33442117815264e-05 3.23578722159879e-06 2.06589598118758e-05 2.87762099372832e-05 5.77017085356136e-06 8.68556486330221e-06 -1.31494482553634e-07 1.51391618096375e-06 9.15800720665069e-06 5.77017085356136e-06 3.32729964026399e-05 822 824 0 12 0 820 828 0 24 0 0 0 0 0 0 5 10 0 2448 0 0 0 0 0 2097 +879 921 0.996630088470748 -0.00476735151421423 0.0818885774350077 -0.0157789335090406 -0.006800329293003 0.990071037244949 0.140403335894195 -0.0280458182176968 -0.0817448608555673 -0.140487058365713 0.986702165881606 0.00100518257170767 3.36605480693773e-05 -4.40509843995829e-05 -6.13843704867912e-08 -1.74011012901376e-05 -1.29243532341804e-05 3.81890717379556e-06 -4.40509843995829e-05 0.000110153582748782 5.55716648441682e-06 5.42952665537876e-05 2.95088677629192e-05 1.02152591990801e-05 -6.13843704867912e-08 5.55716648441682e-06 9.15489055672162e-06 3.57415367963123e-06 3.90434891730294e-06 9.19865927211633e-07 -1.74011012901376e-05 5.42952665537876e-05 3.57415367963123e-06 7.47535221610654e-05 2.28510709867479e-05 1.02239535973867e-05 -1.29243532341804e-05 2.95088677629192e-05 3.90434891730294e-06 2.28510709867479e-05 3.40419764636536e-05 7.21312736543582e-06 3.81890717379556e-06 1.02152591990801e-05 9.19865927211633e-07 1.02239535973867e-05 7.21312736543582e-06 3.24632756301966e-05 854 851 0 23 0 853 859 0 32 0 0 0 0 0 0 4 15 0 2401 0 0 0 0 0 2165 +879 920 0.996141426603279 -0.00558592480622705 0.0875845628455361 -0.0146133229268222 -0.00678095470465758 0.990090274801135 0.140268550992394 -0.0284678311258765 -0.0875001534745961 -0.140321221446621 0.986232060903341 0.00501738657058818 4.2199623050523e-05 -4.52343263732079e-05 -4.79781524827837e-07 -7.87034903314366e-06 -9.32108447044332e-06 -7.71608045838396e-06 -4.52343263732079e-05 7.06651739485639e-05 2.41257170478619e-06 2.41154934735215e-05 1.77919938687162e-05 2.16674723573324e-05 -4.79781524827837e-07 2.41257170478619e-06 9.92483893362863e-06 -8.93372762437329e-07 3.03839711994218e-06 2.4449062054816e-07 -7.87034903314366e-06 2.41154934735215e-05 -8.93372762437329e-07 5.81917766725758e-05 1.43586578203578e-05 1.9728980860125e-05 -9.32108447044332e-06 1.77919938687162e-05 3.03839711994218e-06 1.43586578203578e-05 2.89415240902485e-05 1.35478114380983e-05 -7.71608045838396e-06 2.16674723573324e-05 2.4449062054816e-07 1.9728980860125e-05 1.35478114380983e-05 4.3280466685156e-05 857 860 0 23 0 856 864 0 23 0 0 0 0 0 0 2 10 0 2278 0 0 0 0 0 1663 +878 925 0.995144632694658 -0.00423289205842966 0.0983323072231931 -0.010092390150257 -0.0105153504608763 0.988784046861841 0.148981663556984 -0.02062031943649 -0.0978600399739327 -0.149292301530732 0.983938626785206 0.00239731662978208 2.67941545417626e-05 -3.56620322668065e-05 2.05440899136185e-06 -1.44573390955781e-05 -6.95248058915141e-06 3.92667266599081e-06 -3.56620322668065e-05 8.0906335017875e-05 1.95926286184261e-06 4.46339059179196e-05 2.07414237035419e-05 7.70935138582673e-06 2.05440899136185e-06 1.95926286184261e-06 1.02600007706941e-05 2.61876269907588e-06 5.72703864468666e-06 5.66812099721281e-07 -1.44573390955781e-05 4.46339059179196e-05 2.61876269907588e-06 8.35288305830944e-05 2.65519027858677e-05 1.8641024634225e-05 -6.95248058915141e-06 2.07414237035419e-05 5.72703864468666e-06 2.65519027858677e-05 3.05212546092716e-05 7.49755374541911e-06 3.92667266599081e-06 7.70935138582673e-06 5.66812099721281e-07 1.8641024634225e-05 7.49755374541911e-06 3.81958514240394e-05 855 859 0 13 0 855 864 0 23 0 0 0 0 0 0 3 11 0 2418 0 0 0 0 0 1872 +879 926 0.996761567681602 -0.00475173501125728 0.0802732720604889 -0.0219466561737692 -0.00640878541337067 0.99038307992774 0.138203771520065 -0.0310915954267843 -0.080157998118964 -0.138270662134914 0.987145338504079 0.000905475155095345 4.98204641747127e-05 -6.99855720134032e-05 -5.947656413468e-06 -2.77218604388578e-05 -2.09990492756885e-05 7.36389811620081e-06 -6.99855720134032e-05 0.000204423680749914 1.8818348376089e-05 0.000106918414197646 5.45777337944967e-05 2.82277638933817e-05 -5.947656413468e-06 1.8818348376089e-05 1.08747503329065e-05 9.09390414928015e-06 9.5842457131964e-06 1.83691348017866e-06 -2.77218604388578e-05 0.000106918414197646 9.09390414928015e-06 9.99418732460687e-05 3.14655159759886e-05 2.84833521941811e-05 -2.09990492756885e-05 5.45777337944967e-05 9.5842457131964e-06 3.14655159759886e-05 3.71208436031779e-05 1.08673115562978e-05 7.36389811620081e-06 2.82277638933817e-05 1.83691348017866e-06 2.84833521941811e-05 1.08673115562978e-05 5.03757948863916e-05 865 871 0 22 0 863 878 0 33 0 0 0 0 0 0 4 15 0 2499 0 0 0 0 0 2033 +879 922 0.996905044097448 -0.00474409561563778 0.078471820482608 -0.0175919616321207 -0.00618010611892451 0.990359200377437 0.138385188933361 -0.0286103715182866 -0.0783718019534054 -0.138441857053974 0.987264763310239 -0.000802476243288917 5.71630119573247e-05 -5.87656458008696e-05 -7.49023829928152e-06 -1.31599450135802e-05 -1.40423000873206e-05 -1.71823113481749e-05 -5.87656458008696e-05 7.70686847444982e-05 9.46206622964545e-06 2.32589422095276e-05 1.79387215944838e-05 2.90637332539691e-05 -7.49023829928152e-06 9.46206622964545e-06 1.14458403463151e-05 -6.90132887106993e-07 2.61317094301965e-06 -6.63124333507243e-07 -1.31599450135802e-05 2.32589422095276e-05 -6.90132887106993e-07 5.91749261938284e-05 1.74260714352282e-05 2.79547874418866e-05 -1.40423000873206e-05 1.79387215944838e-05 2.61317094301965e-06 1.74260714352282e-05 3.12706105465684e-05 1.7302879051762e-05 -1.71823113481749e-05 2.90637332539691e-05 -6.63124333507243e-07 2.79547874418866e-05 1.7302879051762e-05 7.22023255003675e-05 883 883 0 20 0 882 887 0 26 0 0 0 0 0 0 4 15 0 2556 0 0 0 0 0 1459 +878 904 0.996575882578639 -0.00306882158761708 0.0826262222098427 -0.0223382070417277 -0.00898745612215792 0.989369401795783 0.145146176052648 -0.0274241753339329 -0.082193283758828 -0.145391778049232 0.985954103891567 -0.000148773462190251 3.3918770423271e-05 -3.80754247604666e-05 -1.32021616468742e-06 -1.48197334406486e-05 -1.01268565036402e-05 7.16332307759798e-06 -3.80754247604666e-05 7.92027787842398e-05 5.32403398291157e-06 4.62885075635121e-05 2.501945383924e-05 3.28184622276143e-06 -1.32021616468742e-06 5.32403398291157e-06 9.54874594431218e-06 2.73271204139698e-06 5.02669152624096e-06 -3.29911988959931e-08 -1.48197334406486e-05 4.62885075635121e-05 2.73271204139698e-06 8.97375131392069e-05 2.84842063054077e-05 1.36276632918993e-05 -1.01268565036402e-05 2.501945383924e-05 5.02669152624096e-06 2.84842063054077e-05 3.08323196037007e-05 7.64554050795786e-06 7.16332307759798e-06 3.28184622276143e-06 -3.29911988959931e-08 1.36276632918993e-05 7.64554050795786e-06 3.09139363783682e-05 832 834 0 10 0 830 842 0 24 0 0 0 0 0 0 7 15 0 2479 0 0 0 0 0 2092 +879 927 0.997402320771324 -0.00443958142129097 0.0718950668459291 -0.0278863607155801 -0.00540240224465054 0.990677236073456 0.13612284149196 -0.0323294783731467 -0.0718291345483424 -0.136157644084576 0.98807978999035 -0.000271179728475897 5.24202918232888e-05 -7.40057035373141e-05 -7.10771590483481e-06 -2.2155838392086e-05 -1.92270071320579e-05 3.40581833105018e-06 -7.40057035373141e-05 0.000200168495232944 1.75597682741773e-05 8.92070317586913e-05 4.65608568210774e-05 3.47414251273572e-05 -7.10771590483481e-06 1.75597682741773e-05 1.08257038345524e-05 6.73225519137763e-06 7.67582850564684e-06 9.53920159870971e-07 -2.2155838392086e-05 8.92070317586913e-05 6.73225519137763e-06 7.95530194041737e-05 2.25802894244467e-05 3.64155775397261e-05 -1.92270071320579e-05 4.65608568210774e-05 7.67582850564684e-06 2.25802894244467e-05 3.31325119820109e-05 1.51222309259719e-05 3.40581833105018e-06 3.47414251273572e-05 9.53920159870971e-07 3.64155775397261e-05 1.51222309259719e-05 6.05004513381195e-05 857 862 0 19 0 856 867 0 26 0 0 0 0 0 0 3 14 0 2518 0 0 0 0 0 2032 +879 916 0.99710261903325 -0.00464697663118018 0.0759261004215408 -0.0240117922227533 -0.00552147100515522 0.99107798778163 0.133168823275773 -0.033789911108486 -0.0758675192356509 -0.133202206223861 0.988180799136537 -0.0041412231839422 7.06774148743278e-05 -6.53008976754268e-05 -3.33231087673512e-06 -4.49699617146599e-05 -3.32210778312312e-05 -3.48708668238483e-05 -6.53008976754268e-05 9.68115649438484e-05 6.75478656791071e-06 4.87585563550759e-05 3.15608488922943e-05 3.5660503244913e-05 -3.33231087673512e-06 6.75478656791071e-06 1.01239034607088e-05 1.43736804534209e-06 3.36208080691777e-06 -7.56977023559511e-07 -4.49699617146599e-05 4.87585563550759e-05 1.43736804534209e-06 9.57513005068813e-05 3.91155234727498e-05 4.72492159098111e-05 -3.32210778312312e-05 3.15608488922943e-05 3.36208080691777e-06 3.91155234727498e-05 5.05576259441114e-05 3.72086741834514e-05 -3.48708668238483e-05 3.5660503244913e-05 -7.56977023559511e-07 4.72492159098111e-05 3.72086741834514e-05 8.56235230491153e-05 866 871 0 25 0 865 876 0 29 0 0 0 0 0 0 3 14 0 2428 0 0 0 0 0 1484 +879 881 0.999951290556661 0.000131447856380269 0.00986910510271703 0.00331859659125323 -0.000174957096796667 0.999990269870321 0.00440789685645541 -0.00330974055023657 -0.00986842966645163 -0.00440940882022999 0.999941583898667 -0.00296061049327054 3.86887623216556e-05 -4.58942908156942e-05 2.44324614795615e-06 -2.76859347913896e-05 -1.91434231420097e-05 8.13041850912391e-06 -4.58942908156942e-05 9.49195081901409e-05 -5.71617611751305e-06 8.64557592267737e-05 4.12360547003171e-05 -9.72970939137089e-06 2.44324614795615e-06 -5.71617611751305e-06 8.44053247400171e-06 -3.09052976167953e-06 -1.21449902423228e-06 6.92442829038778e-07 -2.76859347913896e-05 8.64557592267737e-05 -3.09052976167953e-06 0.000141518260390209 5.39443914706343e-05 3.47383349589483e-06 -1.91434231420097e-05 4.12360547003171e-05 -1.21449902423228e-06 5.39443914706343e-05 4.78583893434601e-05 4.28257392087368e-06 8.13041850912391e-06 -9.72970939137089e-06 6.92442829038778e-07 3.47383349589483e-06 4.28257392087368e-06 3.55212676441491e-05 739 739 0 18 0 737 748 0 23 0 0 0 0 0 0 5 18 0 2072 0 0 0 0 0 2744 +879 883 0.999992508808713 -0.000147923260069165 -0.00386787346808513 -0.0117459053751892 0.000175372797752535 0.999974797565244 0.00709742761365382 -0.00850509734173201 0.00386672611362569 -0.00709805276525738 0.999967332504469 -0.00334228321876468 2.91064286452073e-05 -3.04764062314475e-05 3.09102707494666e-07 -1.04628472579073e-05 -1.12683573499048e-05 1.01385415511548e-05 -3.04764062314475e-05 4.64025230336476e-05 7.29125058119156e-07 2.38816532052491e-05 2.07303262881629e-05 -2.26472832594872e-06 3.09102707494666e-07 7.29125058119156e-07 8.59783515452124e-06 1.71869804943768e-07 1.29437717937514e-06 -3.27319877148777e-07 -1.04628472579073e-05 2.38816532052491e-05 1.71869804943768e-07 7.11467338188431e-05 2.96097411680671e-05 6.57940309567233e-06 -1.12683573499048e-05 2.07303262881629e-05 1.29437717937514e-06 2.96097411680671e-05 3.80175151381426e-05 6.84336949271235e-06 1.01385415511548e-05 -2.26472832594872e-06 -3.27319877148777e-07 6.57940309567233e-06 6.84336949271235e-06 3.91150122874189e-05 807 804 0 8 0 804 809 0 17 0 0 0 0 0 0 5 17 0 2102 0 0 0 0 0 2170 +879 918 0.997186196008734 -0.00482275953651857 0.0748093007592242 -0.0221120031400628 -0.00550471839508873 0.990523533593584 0.137232749271707 -0.0326526754280061 -0.0747622134839647 -0.137258407348087 0.987709846588179 0.00171331227062167 6.09149570306188e-05 -7.6816535725961e-05 -6.77162527939801e-06 -1.13621599019465e-05 -1.39255521173777e-05 8.37570727292506e-06 -7.6816535725961e-05 0.00017602392005389 1.25571745373267e-05 5.60895249507507e-05 3.61926877139134e-05 1.42670223794069e-05 -6.77162527939801e-06 1.25571745373267e-05 1.06915561449884e-05 9.95798960946405e-07 4.2001140512654e-06 -2.69437379450413e-06 -1.13621599019465e-05 5.60895249507507e-05 9.95798960946405e-07 6.59498885960732e-05 1.48219883068675e-05 1.6622184397164e-05 -1.39255521173777e-05 3.61926877139134e-05 4.2001140512654e-06 1.48219883068675e-05 3.13527685409961e-05 7.72328899211197e-06 8.37570727292506e-06 1.42670223794069e-05 -2.69437379450413e-06 1.6622184397164e-05 7.72328899211197e-06 5.3939430573048e-05 866 870 0 25 0 865 875 0 32 0 0 0 0 0 0 4 13 0 2278 0 0 0 0 0 1604 +879 882 0.999939317654063 -0.0002025772320431 0.0110145345790092 0.00342840830628404 8.13587743519919e-05 0.999939443666612 0.0110046526731138 -0.00136408240018577 -0.0110160968712592 -0.01100308875594 0.999878781476811 -0.000583812805654645 4.17441879015888e-05 -6.56181424334611e-05 4.80446212315936e-06 -4.43149647266913e-05 -2.75292170716733e-05 1.99015009016494e-05 -6.56181424334611e-05 0.000152696743921053 -7.53434352972627e-06 0.000139968379151272 7.94184893009684e-05 -2.5140504396986e-05 4.80446212315936e-06 -7.53434352972627e-06 8.78740974786333e-06 -4.00943539922556e-06 -2.2798705332667e-06 -2.1722274841954e-07 -4.43149647266913e-05 0.000139968379151272 -4.00943539922556e-06 0.000196867451771102 9.60743656393011e-05 -6.96952219352789e-06 -2.75292170716733e-05 7.94184893009684e-05 -2.2798705332667e-06 9.60743656393011e-05 7.37286925229742e-05 -6.14260964155804e-06 1.99015009016494e-05 -2.5140504396986e-05 -2.1722274841954e-07 -6.96952219352789e-06 -6.14260964155804e-06 4.58892832915832e-05 814 816 0 12 0 813 824 0 23 0 0 0 0 0 0 10 22 0 2111 0 0 0 0 0 2779 +879 928 0.996415638913389 -0.00533127365337605 0.0844242385222191 -0.0194671068339384 -0.00649654613114452 0.990241884341292 0.139207777744537 -0.0290155512578083 -0.0843425717961554 -0.139257272763182 0.9866578649995 0.00183376237918363 0.00010595265402075 -0.000162134915622396 -1.22902630036809e-05 -7.75065079367702e-05 -4.68326344717746e-05 -4.96280470913184e-05 -0.000162134915622396 0.000353214761504012 2.75176637554732e-05 0.000175941160014597 9.32059708840384e-05 0.000122200338075794 -1.22902630036809e-05 2.75176637554732e-05 1.1820559454135e-05 1.0750058940868e-05 1.01789258816266e-05 7.45875159080015e-06 -7.75065079367702e-05 0.000175941160014597 1.0750058940868e-05 0.000137726083711193 5.88653687460199e-05 8.4791817577216e-05 -4.68326344717746e-05 9.32059708840384e-05 1.01789258816266e-05 5.88653687460199e-05 5.4487416664235e-05 4.36626851389666e-05 -4.96280470913184e-05 0.000122200338075794 7.45875159080015e-06 8.4791817577216e-05 4.36626851389666e-05 0.000105443765718484 836 837 0 22 0 834 844 0 30 0 0 0 0 0 0 3 13 0 2470 0 0 0 0 0 1574 +879 919 0.997059619557262 -0.00452893090659226 0.0764957765708041 -0.0235736788285578 -0.0058716633318709 0.9908019241365 0.135192716879006 -0.0317608672705754 -0.076404441088488 -0.135244356304628 0.987861997178605 -0.00195470386418008 8.2983001582932e-05 -7.85602301716999e-05 -5.28886925726212e-06 -3.97079233527616e-05 -3.52704644129675e-05 -3.72264454988257e-05 -7.85602301716999e-05 0.000112781761542194 7.83815964705184e-06 5.3130931655086e-05 3.77626021337851e-05 5.16550627209038e-05 -5.28886925726212e-06 7.83815964705184e-06 1.06238264674484e-05 2.20125862200684e-06 3.76127078179558e-06 -6.38977194806698e-07 -3.97079233527616e-05 5.3130931655086e-05 2.20125862200684e-06 9.08630004759239e-05 3.61565655426677e-05 6.70338423611765e-05 -3.52704644129675e-05 3.77626021337851e-05 3.76127078179558e-06 3.61565655426677e-05 4.96882088993206e-05 4.04647300182964e-05 -3.72264454988257e-05 5.16550627209038e-05 -6.38977194806698e-07 6.70338423611765e-05 4.04647300182964e-05 9.76578913446557e-05 866 870 0 20 0 866 877 0 31 0 0 0 0 0 0 4 14 0 2312 0 0 0 0 0 1434 +879 913 0.996574372284642 -0.00481340980411005 0.0825611990679047 -0.0177833883215222 -0.00679018844016629 0.990171906387783 0.139690690961608 -0.0277490125496628 -0.082422168416146 -0.139772768758589 0.986747262102682 -0.00152005922409218 2.27516085488766e-05 -2.16981437938254e-05 2.41153649112179e-06 -8.52046185212544e-06 -8.06478596864776e-07 -5.13423921336106e-07 -2.16981437938254e-05 4.2940623514584e-05 2.76389800696992e-07 1.64113029856797e-05 8.06211476812687e-06 1.2291599405026e-05 2.41153649112179e-06 2.76389800696992e-07 8.90895133161411e-06 7.27683193686865e-07 2.88412088404552e-06 9.7241067391843e-07 -8.52046185212544e-06 1.64113029856797e-05 7.27683193686865e-07 4.88522963217808e-05 1.10217246871315e-05 8.44939392069611e-06 -8.06478596864776e-07 8.06211476812687e-06 2.88412088404552e-06 1.10217246871315e-05 2.14337771550529e-05 8.0749419257433e-06 -5.13423921336106e-07 1.2291599405026e-05 9.7241067391843e-07 8.44939392069611e-06 8.0749419257433e-06 3.35659631909859e-05 894 894 0 23 0 892 902 0 27 0 0 0 0 0 0 4 15 0 2474 0 0 0 0 0 1790 +879 912 0.996544971003185 -0.00498208225498984 0.0829053654757449 -0.0170516421471741 -0.00672173474829678 0.990086935837298 0.14029496700268 -0.0276980494100581 -0.0827824803339201 -0.140367511699517 0.9866326685292 0.00156117513310081 5.43619094020796e-05 -5.8902256610725e-05 -6.52592576421318e-06 -1.46391918280774e-05 -2.01545030857915e-05 1.69422060359298e-05 -5.8902256610725e-05 9.77784350089495e-05 8.9061244287246e-06 4.45682126282319e-05 3.75902175988118e-05 -5.2219051944931e-06 -6.52592576421318e-06 8.9061244287246e-06 1.00461540610544e-05 3.235778456661e-06 5.46092392523719e-06 -3.76972033367852e-06 -1.46391918280774e-05 4.45682126282319e-05 3.235778456661e-06 6.27370566150102e-05 2.25531308713825e-05 1.78943082294143e-05 -2.01545030857915e-05 3.75902175988118e-05 5.46092392523719e-06 2.25531308713825e-05 3.6077270901761e-05 6.36405207678528e-06 1.69422060359298e-05 -5.2219051944931e-06 -3.76972033367852e-06 1.78943082294143e-05 6.36405207678528e-06 4.40986709500403e-05 868 870 0 18 0 866 876 0 26 0 0 0 0 0 0 2 15 0 2484 0 0 0 0 0 2215 +879 908 0.996698020787508 -0.00524378979585197 0.0810281310832352 -0.0199611612264496 -0.00603694552338657 0.990364938954637 0.138350435409965 -0.0293871871010576 -0.0809729006953109 -0.138382767561413 0.987063118040093 -0.000413864691210007 4.97505149742426e-05 -5.17307138600882e-05 3.39002671004091e-06 -3.58775632153285e-05 -2.09067045434428e-05 -9.2442412219863e-06 -5.17307138600882e-05 6.85236287194725e-05 -1.28692330663642e-06 4.54238563539281e-05 2.61582786697067e-05 1.85736895851045e-05 3.39002671004091e-06 -1.28692330663642e-06 1.0645798447804e-05 -7.62038729300112e-07 5.36607082102076e-06 4.99160898483562e-06 -3.58775632153285e-05 4.54238563539281e-05 -7.62038729300112e-07 8.07843254461143e-05 3.16191797613628e-05 3.06055861895935e-05 -2.09067045434428e-05 2.61582786697067e-05 5.36607082102076e-06 3.16191797613628e-05 3.62689558631552e-05 2.08359897510031e-05 -9.2442412219863e-06 1.85736895851045e-05 4.99160898483562e-06 3.06055861895935e-05 2.08359897510031e-05 5.55705813020973e-05 891 888 0 19 0 890 896 0 26 0 0 0 0 0 0 4 12 0 2508 0 0 0 0 0 1529 +879 914 0.996063690491131 -0.00509505311555749 0.0884938693861829 -0.012955544062825 -0.00777100814948536 0.98948331854236 0.144438131249126 -0.0243436949960997 -0.0882991275015205 -0.144557264639826 0.985548812247431 0.00405553901330202 3.79209058808927e-05 -4.5509663916274e-05 -4.69561555307428e-07 -1.91037145141832e-05 -9.84188440675719e-06 -1.41271346212953e-06 -4.5509663916274e-05 7.8823432058291e-05 1.50723541482505e-06 4.58277947000578e-05 2.55194175676495e-05 1.70434398733987e-05 -4.69561555307428e-07 1.50723541482505e-06 8.91294475219255e-06 -1.36884144478265e-06 2.99185575788589e-06 -1.44957036028049e-06 -1.91037145141832e-05 4.58277947000578e-05 -1.36884144478265e-06 8.16073827367082e-05 2.91436327455168e-05 2.70376699041149e-05 -9.84188440675719e-06 2.55194175676495e-05 2.99185575788589e-06 2.91436327455168e-05 3.28100341686528e-05 1.65746194417842e-05 -1.41271346212953e-06 1.70434398733987e-05 -1.44957036028049e-06 2.70376699041149e-05 1.65746194417842e-05 4.13018177388883e-05 887 891 0 22 0 886 899 0 34 0 0 0 0 0 0 2 14 0 2521 0 0 0 0 0 1755 +879 917 0.996502500539939 -0.00436857714468898 0.0834486785478333 -0.0137581529222759 -0.0073996377942691 0.990096292009938 0.140194785597341 -0.0258935360346006 -0.0832346789395041 -0.140321944406075 0.986601104874678 -0.00019667359996924 4.93377631771412e-05 -7.80334641480705e-05 -1.23054444414579e-06 -3.79688724686682e-05 -1.98663203248132e-05 3.33510982675133e-06 -7.80334641480705e-05 0.000295314328841608 2.12608151307328e-05 0.000146717871209308 5.78126800602813e-05 4.33078365133826e-05 -1.23054444414579e-06 2.12608151307328e-05 1.11641879321537e-05 9.70763233616444e-06 4.49347727068073e-06 4.19560032223181e-06 -3.79688724686682e-05 0.000146717871209308 9.70763233616444e-06 0.000133829019800806 5.07350501848774e-05 3.48863325443794e-05 -1.98663203248132e-05 5.78126800602813e-05 4.49347727068073e-06 5.07350501848774e-05 4.76840505030393e-05 1.16648352853921e-05 3.33510982675133e-06 4.33078365133826e-05 4.19560032223181e-06 3.48863325443794e-05 1.16648352853921e-05 4.64269351212995e-05 827 828 0 23 0 827 835 0 26 0 0 0 0 0 0 4 16 0 2210 0 0 0 0 0 1741 +879 910 0.996089337155344 -0.0052487477031974 0.0881957088127099 -0.0147283711284478 -0.0073753813716637 0.989809863937389 0.142204208805049 -0.0271597739255803 -0.0880433765541205 -0.142298573077159 0.98590033976318 0.00204738103355633 4.34804985764256e-05 -5.1667050660326e-05 -5.7761808246323e-07 -1.47942523093977e-05 -9.02597435541835e-06 8.28102530220252e-06 -5.1667050660326e-05 9.32652962582725e-05 2.47395121098912e-06 4.04920917156201e-05 2.14450641819152e-05 2.96374791521059e-06 -5.7761808246323e-07 2.47395121098912e-06 9.54411619987824e-06 4.61108571614293e-07 3.80677589479225e-06 1.52628686731793e-06 -1.47942523093977e-05 4.04920917156201e-05 4.61108571614293e-07 6.33725665423975e-05 1.72431921423834e-05 6.26197987355654e-06 -9.02597435541835e-06 2.14450641819152e-05 3.80677589479225e-06 1.72431921423834e-05 3.12788161313182e-05 7.418938374958e-06 8.28102530220252e-06 2.96374791521059e-06 1.52628686731793e-06 6.26197987355654e-06 7.418938374958e-06 3.77575499364712e-05 866 871 0 22 0 865 878 0 32 0 0 0 0 0 0 2 14 0 2522 0 0 0 0 0 1706 +879 915 0.997251051029529 -0.00431858470121757 0.0739708797208593 -0.0248151502320656 -0.00585464840705882 0.990586483321222 0.136763087685693 -0.0316662586273573 -0.0738651765890338 -0.136820206429727 0.987838127832692 -0.00269978958281397 5.7432386541084e-05 -6.82021628005133e-05 -5.83885203088482e-06 -2.17770394285768e-05 -2.19889569311419e-05 1.35584114837009e-05 -6.82021628005133e-05 0.000148442310268474 1.44933036216308e-05 6.70141734102843e-05 4.32343913197923e-05 7.19233472201745e-06 -5.83885203088482e-06 1.44933036216308e-05 1.09784707791666e-05 5.20267787460814e-06 7.65297843253309e-06 -4.43690953741716e-07 -2.17770394285768e-05 6.70141734102843e-05 5.20267787460814e-06 7.82004271665677e-05 2.48679320680965e-05 1.99590594846615e-05 -2.19889569311419e-05 4.32343913197923e-05 7.65297843253309e-06 2.48679320680965e-05 3.6563484910432e-05 6.85737755197751e-06 1.35584114837009e-05 7.19233472201745e-06 -4.43690953741716e-07 1.99590594846615e-05 6.85737755197751e-06 4.76734986469237e-05 856 855 0 17 0 856 862 0 25 0 0 0 0 0 0 3 14 0 2553 0 0 0 0 0 2019 +879 911 0.997148768735237 -0.00456056559913498 0.0753228667219801 -0.0229576915080481 -0.00605184428810708 0.990123785494816 0.140065215446688 -0.0290204930340165 -0.0752177385362901 -0.140121699386036 0.987273113768756 0.00149245942933557 4.21412999564504e-05 -4.38913519428882e-05 -3.24326803498938e-06 -1.10503867125876e-05 -9.3947439984157e-06 3.19280169023127e-06 -4.38913519428882e-05 6.72665119344297e-05 5.31679190168343e-06 2.2218713236727e-05 1.54168002577977e-05 6.07053281955322e-06 -3.24326803498938e-06 5.31679190168343e-06 9.53926994571999e-06 -8.87423431129324e-08 3.57534011485315e-06 -5.95474758675362e-07 -1.10503867125876e-05 2.2218713236727e-05 -8.87423431129324e-08 5.02714104569109e-05 1.40711418021278e-05 1.77222952068723e-05 -9.3947439984157e-06 1.54168002577977e-05 3.57534011485315e-06 1.40711418021278e-05 2.5975038149846e-05 1.18576059807434e-05 3.19280169023127e-06 6.07053281955322e-06 -5.95474758675362e-07 1.77222952068723e-05 1.18576059807434e-05 4.16355650025947e-05 863 870 0 23 0 862 873 0 28 0 0 0 0 0 0 4 13 0 2548 0 0 0 0 0 1646 +879 909 0.997285781082368 -0.00475731598585735 0.0734740688647539 -0.0227960783727093 -0.00554476755488907 0.990223999493007 0.139376061003447 -0.0290836953795399 -0.0734188422933387 -0.139405160495173 0.987509936569562 0.00171057857269142 5.87442801078408e-05 -7.82190011243338e-05 -2.35036356665469e-06 -2.25021859946739e-05 -1.79700621363129e-05 2.7827859205895e-06 -7.82190011243338e-05 0.000177453793650786 8.22836238460762e-06 7.40500953580279e-05 4.39827321474878e-05 9.26536971737579e-06 -2.35036356665469e-06 8.22836238460762e-06 1.03307684668626e-05 2.21873689389979e-06 5.40025880646301e-06 3.12585132852071e-07 -2.25021859946739e-05 7.40500953580279e-05 2.21873689389979e-06 8.43188625304448e-05 3.04729540513947e-05 1.69222511964546e-05 -1.79700621363129e-05 4.39827321474878e-05 5.40025880646301e-06 3.04729540513947e-05 3.69786711551757e-05 8.06831664166444e-06 2.7827859205895e-06 9.26536971737579e-06 3.12585132852071e-07 1.69222511964546e-05 8.06831664166444e-06 3.92079493297982e-05 839 842 0 25 0 839 846 0 30 0 0 0 0 0 0 2 10 0 2498 0 0 0 0 0 1635 +879 923 0.9966608543605 -0.00536835944640782 0.0814758989042297 -0.0210081514208351 -0.00583517009471644 0.990602351291846 0.136648938543375 -0.0313760784258922 -0.0814437976482176 -0.136668073564822 0.987263260479552 -0.00254789688981163 5.57835390601781e-05 -5.43953268897672e-05 5.16848938438973e-07 -3.27537162117708e-05 -2.03622727077286e-05 -1.45018340689538e-05 -5.43953268897672e-05 6.37269247044101e-05 6.52568094276392e-07 3.54789135581253e-05 2.3497162173037e-05 1.95421439754407e-05 5.16848938438973e-07 6.52568094276392e-07 1.03809457580071e-05 2.09562490928724e-07 4.89448851198061e-06 3.65965888160044e-06 -3.27537162117708e-05 3.54789135581253e-05 2.09562490928724e-07 7.01971018607963e-05 2.81895009932442e-05 2.70954846290242e-05 -2.03622727077286e-05 2.3497162173037e-05 4.89448851198061e-06 2.81895009932442e-05 3.77336652549541e-05 2.70214426813046e-05 -1.45018340689538e-05 1.95421439754407e-05 3.65965888160044e-06 2.70954846290242e-05 2.70214426813046e-05 6.70931826772485e-05 890 893 0 18 0 890 901 0 28 0 0 0 0 0 0 3 14 0 2458 0 0 0 0 0 1498 +879 906 0.996239196770211 -0.00525785590315391 0.0864859397240128 -0.0159315023940919 -0.00726438425095478 0.989574350855838 0.143839608069893 -0.0249600974323947 -0.0863405555929448 -0.143926922705753 0.985814561355407 0.00209809543598889 5.87507964367153e-05 -7.97928198318064e-05 -3.53256406396846e-06 -3.57054725000407e-05 -2.22512167591414e-05 -1.08422892305862e-05 -7.97928198318064e-05 0.000159829148711657 7.9932807370776e-06 8.65508568737132e-05 4.90586366836633e-05 3.99828460419576e-05 -3.53256406396846e-06 7.9932807370776e-06 9.82710203042392e-06 2.55351134990745e-06 5.48863077576551e-06 1.87898795819675e-06 -3.57054725000407e-05 8.65508568737132e-05 2.55351134990745e-06 9.732123461193e-05 3.7033462529401e-05 3.05379181007808e-05 -2.22512167591414e-05 4.90586366836633e-05 5.48863077576551e-06 3.7033462529401e-05 3.96709917518714e-05 2.08032315069085e-05 -1.08422892305862e-05 3.99828460419576e-05 1.87898795819675e-06 3.05379181007808e-05 2.08032315069085e-05 5.11872278707938e-05 867 871 0 23 0 866 877 0 30 0 0 0 0 0 0 4 14 0 2515 0 0 0 0 0 1746 +880 882 0.99999745355419 0.000668888502441153 0.00215533600807803 -0.00387613771649254 -0.000675133530947186 0.999995572741814 0.00289804960051184 -0.0058822434100518 -0.00215338799379176 -0.00289949736039508 0.999993477896334 0.00221645522234056 4.06511635912919e-05 -4.09374134928844e-05 7.38355075108034e-06 -2.93804941232593e-05 -1.3420372724902e-05 9.84516009695251e-06 -4.09374134928844e-05 5.20204028725866e-05 -7.24626620131151e-06 4.1621021412217e-05 2.16295335094294e-05 -7.05801379959993e-06 7.38355075108034e-06 -7.24626620131151e-06 9.65266494445708e-06 -1.74282921335979e-06 1.30336935905313e-06 4.88683982796237e-06 -2.93804941232593e-05 4.1621021412217e-05 -1.74282921335979e-06 9.32756499502918e-05 3.91249793054901e-05 5.21773714311262e-06 -1.3420372724902e-05 2.16295335094294e-05 1.30336935905313e-06 3.91249793054901e-05 4.05471987747716e-05 8.49285733214946e-06 9.84516009695251e-06 -7.05801379959993e-06 4.88683982796237e-06 5.21773714311262e-06 8.49285733214946e-06 3.9060379650737e-05 807 805 0 17 0 806 815 0 26 0 0 0 0 0 0 7 21 0 2107 0 0 0 0 0 2363 +879 905 0.996888743205766 -0.00444137183236259 0.0786963016022664 -0.018530821612021 -0.00675484776124924 0.989924420983678 0.141435542816694 -0.027927607878791 -0.0785315586331414 -0.141527082059856 0.986814511112535 0.00200889086093481 2.78052563553279e-05 -2.73309503627184e-05 2.78264597499609e-06 -1.00277336756564e-05 -2.08354976306327e-06 6.10431138952397e-06 -2.73309503627184e-05 6.72666212827795e-05 2.01030604451665e-06 2.60346247466117e-05 8.79211840663438e-06 6.51042502135202e-06 2.78264597499609e-06 2.01030604451665e-06 9.30805957743351e-06 -3.38557187861096e-07 3.90340935388889e-06 1.25319004787584e-06 -1.00277336756564e-05 2.60346247466117e-05 -3.38557187861096e-07 5.54414359940264e-05 1.12678980255628e-05 1.01672204320422e-05 -2.08354976306327e-06 8.79211840663438e-06 3.90340935388889e-06 1.12678980255628e-05 2.59854656369834e-05 9.15624869789338e-06 6.10431138952397e-06 6.51042502135202e-06 1.25319004787584e-06 1.01672204320422e-05 9.15624869789338e-06 3.11169099005807e-05 876 881 0 22 0 875 887 0 29 0 0 0 0 0 0 4 14 0 2555 0 0 0 0 0 1697 +880 884 0.99994703285594 0.000330020546484268 0.010287009723018 0.00411724675019227 -0.000424307550822975 0.999957912286872 0.00916480321571662 -0.00140730988363707 -0.0102835521929381 -0.00916868263816527 0.999905087402287 -0.00565160741341617 6.29573448312623e-05 -7.56216012423439e-05 5.16281787075233e-07 -3.92366678999884e-05 -2.95441137470098e-05 5.17824274215235e-06 -7.56216012423439e-05 0.000114316395348482 -2.19330710415102e-06 8.59035135995701e-05 6.00930337800081e-05 1.59048484800207e-05 5.16281787075233e-07 -2.19330710415102e-06 1.12613580024033e-05 -8.5995378425555e-06 -1.1890557299769e-06 -4.98072670622865e-06 -3.92366678999884e-05 8.59035135995701e-05 -8.5995378425555e-06 0.000151302064625978 7.5851891618856e-05 5.12356869112246e-05 -2.95441137470098e-05 6.00930337800081e-05 -1.1890557299769e-06 7.5851891618856e-05 6.96830916792877e-05 2.98211898648778e-05 5.17824274215235e-06 1.59048484800207e-05 -4.98072670622865e-06 5.12356869112246e-05 2.98211898648778e-05 5.94824994896789e-05 716 715 0 15 0 714 722 0 25 0 0 0 0 0 0 8 22 0 2170 0 0 0 0 0 1728 +879 907 0.997550149123994 -0.00448833195235649 0.0698108505820014 -0.0254026244077519 -0.00525531687707041 0.99031142206123 0.138764797335588 -0.0298258355575711 -0.0697573051889094 -0.138791722416543 0.987861719149715 0.000992773649333734 5.74521066868057e-05 -7.45509684079896e-05 -1.89725679951013e-06 -2.08033627660934e-05 -1.16966055873445e-05 -1.90263927391692e-07 -7.45509684079896e-05 0.000158083599617374 9.66896069430547e-06 5.62456969919661e-05 2.87380438886444e-05 1.98072328487669e-05 -1.89725679951013e-06 9.66896069430547e-06 1.04282191476465e-05 2.53189232580413e-06 5.82451635880659e-06 6.95844313606095e-07 -2.08033627660934e-05 5.62456969919661e-05 2.53189232580413e-06 6.61349950769037e-05 1.90964042062549e-05 1.8944758891159e-05 -1.16966055873445e-05 2.87380438886444e-05 5.82451635880659e-06 1.90964042062549e-05 2.86911453062722e-05 9.94941381765132e-06 -1.90263927391692e-07 1.98072328487669e-05 6.95844313606095e-07 1.8944758891159e-05 9.94941381765132e-06 4.74168884362996e-05 858 862 0 22 0 858 867 0 28 0 0 0 0 0 0 3 12 0 2556 0 0 0 0 0 1615 +880 920 0.996519587138699 -0.00486180057611326 0.0832170375829096 -0.0185616467173582 -0.00635231770759029 0.990965839215154 0.133964001016494 -0.0311313825679723 -0.0831165477426674 -0.134026372045816 0.987485985261349 0.00216845014040565 5.78847535811318e-05 -5.95229759543878e-05 -1.02242531645786e-05 -5.18790102645373e-06 -1.55894151552463e-05 1.56630796959023e-05 -5.95229759543878e-05 0.000107420521081136 1.35199180223838e-05 2.88612228364076e-05 2.43444087988601e-05 -4.39915355720106e-06 -1.02242531645786e-05 1.35199180223838e-05 1.19130991415437e-05 -8.1459956368665e-07 5.40541429504353e-06 -4.17361885356979e-06 -5.18790102645373e-06 2.88612228364076e-05 -8.1459956368665e-07 6.06141084826693e-05 1.22695817300576e-05 9.46413355193643e-06 -1.55894151552463e-05 2.43444087988601e-05 5.40541429504353e-06 1.22695817300576e-05 2.96844206993626e-05 -1.78799454740872e-07 1.56630796959023e-05 -4.39915355720106e-06 -4.17361885356979e-06 9.46413355193643e-06 -1.78799454740872e-07 3.08277769135227e-05 845 847 0 16 0 839 848 0 21 0 0 0 0 0 0 3 13 0 2349 0 0 0 0 0 2089 +880 919 0.9963691342161 -0.00447780923489544 0.0850205716630699 -0.0161846562880561 -0.00716233978060785 0.990667509476936 0.136112404121121 -0.0276395642415834 -0.0848366033639162 -0.136227144472825 0.987038457122342 0.0032810371857863 3.85777641829676e-05 -4.09622165174757e-05 -3.45311636712996e-06 -5.04248543218848e-06 -8.40004814469579e-06 1.7107279775141e-05 -4.09622165174757e-05 0.000108261684732006 7.8700676914909e-06 4.80304358776615e-05 2.48158095512761e-05 -6.05037494785298e-06 -3.45311636712996e-06 7.8700676914909e-06 9.85125792922612e-06 3.60082602558142e-06 3.07916069138125e-06 -1.79836751757468e-06 -5.04248543218848e-06 4.80304358776615e-05 3.60082602558142e-06 6.49437053795353e-05 1.14511050236133e-05 7.94380621153565e-06 -8.40004814469579e-06 2.48158095512761e-05 3.07916069138125e-06 1.14511050236133e-05 2.9587682828318e-05 1.08391571652571e-07 1.7107279775141e-05 -6.05037494785298e-06 -1.79836751757468e-06 7.94380621153565e-06 1.08391571652571e-07 3.10192145530378e-05 849 852 0 14 0 847 857 0 22 0 0 0 0 0 0 4 15 0 2363 0 0 0 0 0 2047 +879 925 0.996673034623096 -0.00500786531476777 0.0813497593123601 -0.0204304993310149 -0.0064114930327636 0.990200171440603 0.139508111721475 -0.0282442265910113 -0.0812511834515695 -0.139565546479028 0.98687370186044 0.00162447499174907 4.08872108491618e-05 -4.27269276163686e-05 4.66641269114856e-06 -2.37470514558625e-05 -1.5772990305746e-05 7.15844365070732e-06 -4.27269276163686e-05 5.89198383922314e-05 -2.5702678226519e-06 3.55771424425791e-05 2.14964054050508e-05 -5.53675818259988e-07 4.66641269114856e-06 -2.5702678226519e-06 1.05147457213069e-05 1.27595463469876e-06 3.54295234816888e-06 4.60482479136118e-06 -2.37470514558625e-05 3.55771424425791e-05 1.27595463469876e-06 7.72820346359695e-05 3.23137189801561e-05 1.43792367065081e-05 -1.5772990305746e-05 2.14964054050508e-05 3.54295234816888e-06 3.23137189801561e-05 3.8982496185337e-05 1.08171457203095e-05 7.15844365070732e-06 -5.53675818259988e-07 4.60482479136118e-06 1.43792367065081e-05 1.08171457203095e-05 3.00560723897901e-05 883 890 0 21 0 882 896 0 29 0 0 0 0 0 0 4 14 0 2467 0 0 0 0 0 2201 +879 924 0.997040857003874 -0.00454631703539451 0.0767389110321037 -0.0224357838623501 -0.00595736190237919 0.990678080380986 0.136093537288916 -0.0324462312170073 -0.0766422814387954 -0.136147978516242 0.987719438222108 -0.00118711353695219 3.88919963601437e-05 -4.19800699923097e-05 -1.2894244800885e-06 -1.57995919816636e-05 -1.04247732599138e-05 -1.22313106053253e-06 -4.19800699923097e-05 8.26704549066141e-05 4.81288831397919e-06 3.7368514582802e-05 1.75953265169261e-05 2.14943611316218e-05 -1.2894244800885e-06 4.81288831397919e-06 8.88475424254031e-06 1.52337614082507e-07 3.05664377958564e-06 9.71611227644905e-07 -1.57995919816636e-05 3.7368514582802e-05 1.52337614082507e-07 6.75012324827051e-05 1.72447517128286e-05 2.37650881323059e-05 -1.04247732599138e-05 1.75953265169261e-05 3.05664377958564e-06 1.72447517128286e-05 2.80876025783342e-05 1.25067607348571e-05 -1.22313106053253e-06 2.14943611316218e-05 9.71611227644905e-07 2.37650881323059e-05 1.25067607348571e-05 4.69262149738054e-05 843 844 0 24 0 842 846 0 26 0 0 0 0 0 0 5 13 0 2513 0 0 0 0 0 2028 +879 929 0.996092230765166 -0.0276153792300037 0.0838907541941236 -0.0255419412640785 0.0140705318851338 0.98734710093511 0.157948480231695 -0.0319831245156506 -0.0871911001292289 -0.1561508664882 0.983877339383949 -0.00400603743989162 3.84038980736226e-05 -3.89287786292237e-05 -6.0974637092998e-06 -1.16661811702871e-06 -5.40614476849914e-06 3.97694990555991e-06 -3.89287786292237e-05 6.92683217400271e-05 7.91332527208536e-06 2.00912963392506e-05 1.31296711010495e-05 5.7473844294765e-06 -6.0974637092998e-06 7.91332527208536e-06 1.08969946570242e-05 -1.29659180159117e-06 3.48582205362689e-06 -1.60129556554743e-06 -1.16661811702871e-06 2.00912963392506e-05 -1.29659180159117e-06 5.13648337406782e-05 6.37238286702477e-06 1.08123546970447e-05 -5.40614476849914e-06 1.31296711010495e-05 3.48582205362689e-06 6.37238286702477e-06 2.35928083263356e-05 2.15892108985797e-06 3.97694990555991e-06 5.7473844294765e-06 -1.60129556554743e-06 1.08123546970447e-05 2.15892108985797e-06 3.31120046803419e-05 870 869 0 1 0 880 882 0 9 0 0 0 0 0 0 26 39 0 2509 0 0 0 0 0 1932 +880 921 0.996550803863914 -0.00430216854370831 0.0828733169603316 -0.0168658620801613 -0.00681956615565161 0.991031781936856 0.133452241301932 -0.0316151389361871 -0.0827042250168318 -0.133557098414431 0.987584180020864 -0.0032436624589737 3.75240817580485e-05 -4.47894475792257e-05 -1.33430126711494e-06 -1.97245288762091e-05 -9.17752991159857e-06 -5.17828136060759e-06 -4.47894475792257e-05 8.93026994809454e-05 6.05982917822742e-06 4.42700512168665e-05 2.27279883586139e-05 1.90733641565065e-05 -1.33430126711494e-06 6.05982917822742e-06 1.00173979322488e-05 1.55388573606603e-06 5.72136535867212e-06 2.73189245677152e-06 -1.97245288762091e-05 4.42700512168665e-05 1.55388573606603e-06 6.91094685476172e-05 1.58518516800474e-05 1.94279234611307e-05 -9.17752991159857e-06 2.27279883586139e-05 5.72136535867212e-06 1.58518516800474e-05 2.8749686555346e-05 1.11343103544864e-05 -5.17828136060759e-06 1.90733641565065e-05 2.73189245677152e-06 1.94279234611307e-05 1.11343103544864e-05 3.6151273036868e-05 838 836 0 16 0 831 844 0 27 0 0 0 0 0 0 5 15 0 2470 0 0 0 0 0 1585 +880 913 0.996826730813898 -0.00432053930917536 0.0794846002377452 -0.0164427836099952 -0.00672789457616538 0.990380173335431 0.138209434188315 -0.0266764639821175 -0.079317111454265 -0.138305622460404 0.987208362315875 0.00228565869041739 4.84246075373466e-05 -5.98524150909976e-05 -3.8756160196091e-07 -2.99859007890854e-05 -1.67906276120661e-05 9.20599651711449e-07 -5.98524150909976e-05 0.000119539875189067 5.08171366246608e-06 6.61553394906023e-05 3.43984031158926e-05 9.04448254674132e-06 -3.8756160196091e-07 5.08171366246608e-06 9.48850969342437e-06 2.11034445399999e-06 5.21704162993255e-06 -8.07015853749213e-07 -2.99859007890854e-05 6.61553394906023e-05 2.11034445399999e-06 8.82939352148046e-05 3.14750421490674e-05 1.84455884493156e-05 -1.67906276120661e-05 3.43984031158926e-05 5.21704162993255e-06 3.14750421490674e-05 3.70761617958074e-05 9.4239841313323e-06 9.20599651711449e-07 9.04448254674132e-06 -8.07015853749213e-07 1.84455884493156e-05 9.4239841313323e-06 3.19315038178927e-05 850 851 0 12 0 847 860 0 24 0 0 0 0 0 0 4 15 0 2516 0 0 0 0 0 1701 +880 883 0.999940359463171 0.00118848288384586 0.0108565659901619 0.00991283042923827 -0.00128874852753168 0.999956542981309 0.00923316176086791 0.000334946923971577 -0.0108451207414542 -0.00924660247357774 0.999898436691847 -0.00329513633942805 4.734803372867e-05 -6.7504848527145e-05 -7.34573578468377e-07 -3.04196928630982e-05 -2.29748508493356e-05 2.57461430737833e-05 -6.7504848527145e-05 0.000147151108084382 -3.7139339698553e-07 0.000106378588938369 6.23336196832738e-05 -2.59966055216016e-05 -7.34573578468377e-07 -3.7139339698553e-07 9.35068432665638e-06 -3.6812712093163e-06 1.96010935767161e-06 -1.90918734415094e-06 -3.04196928630982e-05 0.000106378588938369 -3.6812712093163e-06 0.000155634655182941 6.44629109624396e-05 -5.8930987558544e-07 -2.29748508493356e-05 6.23336196832738e-05 1.96010935767161e-06 6.44629109624396e-05 5.61910428187253e-05 -5.24179881688519e-06 2.57461430737833e-05 -2.59966055216016e-05 -1.90918734415094e-06 -5.8930987558544e-07 -5.24179881688519e-06 4.12457379073224e-05 765 762 0 13 0 757 769 0 26 0 0 0 0 0 0 12 23 0 2112 0 0 0 0 0 2415 +880 916 0.996014447015738 -0.00461205376133473 0.0890727247592456 -0.0128477429997558 -0.00756553386017666 0.990694390870364 0.135894762943278 -0.0278487186772275 -0.0888706027511027 -0.136027029880469 0.986711033235442 0.00402090909361716 3.93259174785249e-05 -4.51293110477473e-05 -2.51938890169314e-06 -1.51279171055061e-05 -8.83797780113449e-06 1.58735590387121e-05 -4.51293110477473e-05 0.000113564069285614 6.73833986782879e-06 5.82806424702654e-05 2.59319725037684e-05 -7.66990249136626e-06 -2.51938890169314e-06 6.73833986782879e-06 9.39017521379042e-06 1.58360124453073e-06 4.33119049080678e-06 -1.81874313222386e-06 -1.51279171055061e-05 5.82806424702654e-05 1.58360124453073e-06 7.83764909663205e-05 1.63224698449501e-05 5.39262610111869e-06 -8.83797780113449e-06 2.59319725037684e-05 4.33119049080678e-06 1.63224698449501e-05 2.95695641100186e-05 3.30837326269416e-06 1.58735590387121e-05 -7.66990249136626e-06 -1.81874313222386e-06 5.39262610111869e-06 3.30837326269416e-06 3.17149584205386e-05 848 849 0 15 0 844 853 0 20 0 0 0 0 0 0 2 13 0 2456 0 0 0 0 0 2062 +880 926 0.996658750246422 -0.0045934737791664 0.08154897642448 -0.019879620434397 -0.00662369822909332 0.990583507866979 0.136749554162786 -0.0295536066574408 -0.0814092266208825 -0.136832795559365 0.987243295181284 0.00167825487556452 4.77354944142397e-05 -5.72129044636125e-05 2.53951826713181e-07 -2.94390319938147e-05 -1.25355965642463e-05 -2.53493364682576e-06 -5.72129044636125e-05 9.71742578158595e-05 2.97190693903302e-06 5.77167763596553e-05 2.40284164778548e-05 1.67834064114113e-05 2.53951826713181e-07 2.97190693903302e-06 8.93522504685589e-06 3.23812690433418e-06 5.01080119927137e-06 2.0613255161583e-06 -2.94390319938147e-05 5.77167763596553e-05 3.23812690433418e-06 7.3566153183285e-05 2.0454991379878e-05 2.1654943456249e-05 -1.25355965642463e-05 2.40284164778548e-05 5.01080119927137e-06 2.0454991379878e-05 2.94539477242114e-05 1.65640549812472e-05 -2.53493364682576e-06 1.67834064114113e-05 2.0613255161583e-06 2.1654943456249e-05 1.65640549812472e-05 4.2108271857835e-05 835 837 0 14 0 830 841 0 22 0 0 0 0 0 0 3 15 0 2504 0 0 0 0 0 1687 +880 915 0.99627563651753 -0.00450552051452345 0.0861078182657262 -0.0149039301611723 -0.00751661147169232 0.990294116811033 0.13878423095381 -0.0264233633696084 -0.085897361039637 -0.138914587046681 0.986572035318292 0.00278804791467757 4.84165903725001e-05 -5.51665552808053e-05 -2.96144411736765e-06 -3.35100494330186e-05 -1.80692531270799e-05 1.70393049031236e-06 -5.51665552808053e-05 9.70293439694403e-05 6.5261918759381e-06 6.47355609648944e-05 3.29504989654622e-05 1.44600839640778e-05 -2.96144411736765e-06 6.5261918759381e-06 9.5261144087487e-06 1.22941642689467e-06 4.40321236881865e-06 9.24914121955157e-08 -3.35100494330186e-05 6.47355609648944e-05 1.22941642689467e-06 9.51285936378928e-05 3.41905767315539e-05 2.30577593144477e-05 -1.80692531270799e-05 3.29504989654622e-05 4.40321236881865e-06 3.41905767315539e-05 3.68545469722918e-05 1.37585661921249e-05 1.70393049031236e-06 1.44600839640778e-05 9.24914121955157e-08 2.30577593144477e-05 1.37585661921249e-05 4.02005201105364e-05 849 847 0 12 0 842 851 0 20 0 0 0 0 0 0 3 15 0 2570 0 0 0 0 0 1739 +880 914 0.997055210220382 -0.00386148648024452 0.0765897949765682 -0.0204923647833464 -0.00656723215684346 0.990763089907726 0.135445085323512 -0.0296385963570199 -0.0764053612921762 -0.135549210985008 0.987820141608357 6.18201596819304e-05 4.09052918800593e-05 -4.69284543581019e-05 -4.51286873621487e-07 -1.22171328081511e-05 -7.71538049467827e-06 5.85083554108386e-06 -4.69284543581019e-05 0.000116909133962172 7.00881003297844e-06 4.1233136841394e-05 1.91877773307728e-05 -2.30926984819146e-06 -4.51286873621487e-07 7.00881003297844e-06 9.90574157504795e-06 5.22907567840298e-07 5.36931692677836e-06 -1.09506685266153e-06 -1.22171328081511e-05 4.1233136841394e-05 5.22907567840298e-07 5.91330700536498e-05 9.45856074006215e-06 8.28549438168991e-06 -7.71538049467827e-06 1.91877773307728e-05 5.36931692677836e-06 9.45856074006215e-06 2.42926148775445e-05 3.53325366026634e-06 5.85083554108386e-06 -2.30926984819146e-06 -1.09506685266153e-06 8.28549438168991e-06 3.53325366026634e-06 2.63083730976924e-05 855 860 0 19 0 852 865 0 28 0 0 0 0 0 0 3 14 0 2614 0 0 0 0 0 2128 +880 918 0.996323675857693 -0.00472035589993503 0.085538594596777 -0.0172069208250968 -0.00675442957394533 0.991044247330053 0.133362954058238 -0.0340198058212084 -0.085402052706855 -0.133450433023602 0.987368964126009 0.000866878315051013 3.69209702210657e-05 -3.7234900426104e-05 -2.0292552025701e-06 -1.28524096869911e-05 -5.33717052541144e-06 9.41338521324809e-06 -3.7234900426104e-05 8.55072403107307e-05 4.54452276160567e-06 4.2922186217093e-05 1.29563008410154e-05 4.2304135943018e-06 -2.0292552025701e-06 4.54452276160567e-06 9.15369106967424e-06 5.93153135650183e-07 3.83401795475971e-06 -8.8972008459292e-07 -1.28524096869911e-05 4.2922186217093e-05 5.93153135650183e-07 6.55217041721921e-05 3.39152111730324e-06 8.41717858870176e-06 -5.33717052541144e-06 1.29563008410154e-05 3.83401795475971e-06 3.39152111730324e-06 2.79962360040089e-05 5.93844412119876e-06 9.41338521324809e-06 4.2304135943018e-06 -8.8972008459292e-07 8.41717858870176e-06 5.93844412119876e-06 3.43056480448883e-05 855 859 0 18 0 851 863 0 25 0 0 0 0 0 0 3 15 0 2290 0 0 0 0 0 2125 +880 927 0.996497722966352 -0.00503486414226973 0.0834681871490285 -0.0192586984779488 -0.00655961362970304 0.990402869282578 0.138054800662149 -0.0284539003687213 -0.0833622192117351 -0.138118813562474 0.986901177295979 0.00307680136325182 4.2356370390676e-05 -4.59968343595808e-05 -4.85736605482105e-06 -1.63758944794303e-05 -1.11563721783828e-05 1.70817160960543e-06 -4.59968343595808e-05 7.94524509356181e-05 7.8042669270224e-06 3.60341094664116e-05 2.034210797351e-05 1.06399424919242e-05 -4.85736605482105e-06 7.8042669270224e-06 1.08131036497912e-05 -2.07697006613658e-06 3.85557467252357e-06 -1.1285830188367e-06 -1.63758944794303e-05 3.60341094664116e-05 -2.07697006613658e-06 7.41300767023733e-05 1.87922700875474e-05 1.42879210120785e-05 -1.11563721783828e-05 2.034210797351e-05 3.85557467252357e-06 1.87922700875474e-05 2.74725293491099e-05 8.36840993013263e-06 1.70817160960543e-06 1.06399424919242e-05 -1.1285830188367e-06 1.42879210120785e-05 8.36840993013263e-06 3.4695849033264e-05 842 845 0 13 0 838 848 0 20 0 0 0 0 0 0 5 17 0 2560 0 0 0 0 0 1726 +880 917 0.996792314444143 -0.00402432686939749 0.0799305114354743 -0.0161584437677642 -0.00679555501947541 0.990872117994549 0.134633822693165 -0.0305244471518495 -0.0797427256686497 -0.134745131912977 0.987666364279299 0.00111213465612581 5.92645470084611e-05 -5.72500080985144e-05 -5.25197243766365e-06 -1.88128146021687e-05 -2.04731070011427e-05 -9.66127248766406e-07 -5.72500080985144e-05 9.22286392583055e-05 9.45683505725349e-06 2.9810081686218e-05 1.8248633945098e-05 1.51225899881631e-05 -5.25197243766365e-06 9.45683505725349e-06 1.12200971775668e-05 -1.34212762400976e-06 2.86459043207039e-06 4.86630692623833e-07 -1.88128146021687e-05 2.9810081686218e-05 -1.34212762400976e-06 7.20963838157007e-05 2.29066509577836e-05 1.82379331543598e-05 -2.04731070011427e-05 1.8248633945098e-05 2.86459043207039e-06 2.29066509577836e-05 4.48449986871991e-05 1.12211885790913e-05 -9.66127248766406e-07 1.51225899881631e-05 4.86630692623833e-07 1.82379331543598e-05 1.12211885790913e-05 4.59130742844283e-05 868 868 0 15 0 864 876 0 26 0 0 0 0 0 0 4 17 0 2268 0 0 0 0 0 1665 +880 922 0.996238800449 -0.00471589104513367 0.0865217478532864 -0.0125801579718381 -0.00718310768497994 0.990586345452795 0.136700750423914 -0.0264199313200693 -0.0863519278529624 -0.136808086654721 0.986826677781844 0.00284953188474636 3.01589461404291e-05 -3.37196228087357e-05 -1.51374214292763e-06 -1.00280601987944e-05 -5.44489914179494e-06 9.72237140770931e-06 -3.37196228087357e-05 7.17881625395645e-05 6.11589334267886e-06 2.44916824585969e-05 1.29962797476389e-05 -4.93361889452314e-06 -1.51374214292763e-06 6.11589334267886e-06 9.35762940601506e-06 1.58535258308969e-06 4.06152771009352e-06 -1.31368606114946e-06 -1.00280601987944e-05 2.44916824585969e-05 1.58535258308969e-06 4.98420588825357e-05 9.77735455841747e-06 3.16197895847169e-06 -5.44489914179494e-06 1.29962797476389e-05 4.06152771009352e-06 9.77735455841747e-06 2.61575334921484e-05 2.61437140422743e-06 9.72237140770931e-06 -4.93361889452314e-06 -1.31368606114946e-06 3.16197895847169e-06 2.61437140422743e-06 3.17540688518579e-05 847 846 0 14 0 841 852 0 24 0 0 0 0 0 0 5 16 0 2585 0 0 0 0 0 2032 +880 908 0.996573526247783 -0.00423712713837019 0.0826029874500446 -0.0150057953827889 -0.00725998945588661 0.990351318458991 0.138389156293545 -0.0262172362148748 -0.0823923499795907 -0.138514666299825 0.98692714416247 0.000764804258354584 2.69784512498521e-05 -3.0171842096009e-05 2.79783082448734e-06 -8.77134929487764e-06 -4.61084419079421e-06 1.1368057914804e-05 -3.0171842096009e-05 8.5098906162014e-05 3.35313338755747e-06 2.96354172314948e-05 1.77034124351804e-05 -3.63159845158345e-06 2.79783082448734e-06 3.35313338755747e-06 9.54487601470222e-06 2.19394044409533e-06 5.12707927644806e-06 2.8347139482612e-07 -8.77134929487764e-06 2.96354172314948e-05 2.19394044409533e-06 4.64093485896824e-05 1.04286662571722e-05 2.01293361809255e-06 -4.61084419079421e-06 1.77034124351804e-05 5.12707927644806e-06 1.04286662571722e-05 2.459402193199e-05 1.06743020373763e-06 1.1368057914804e-05 -3.63159845158345e-06 2.8347139482612e-07 2.01293361809255e-06 1.06743020373763e-06 3.01992109702781e-05 830 829 0 13 0 822 833 0 23 0 0 0 0 0 0 7 14 0 2519 0 0 0 0 0 2088 +880 928 0.996733945975757 -0.00461588851875034 0.0806234116915116 -0.019566814660283 -0.00655159510889144 0.990452021737054 0.137702103246504 -0.0277745805537929 -0.0804892386665799 -0.13778057268775 0.987186910492998 0.00150297868936678 4.0690827428938e-05 -4.42577787181332e-05 -5.19358885912694e-06 -7.26140086445974e-06 -6.61645263349286e-06 1.4200937955363e-05 -4.42577787181332e-05 8.23961237454146e-05 8.77811288240663e-06 2.68587897277407e-05 1.41138267693811e-05 -5.22824066249382e-06 -5.19358885912694e-06 8.77811288240663e-06 1.03633029195826e-05 5.65224724667678e-07 4.36023734055396e-06 -1.8239405327829e-06 -7.26140086445974e-06 2.68587897277407e-05 5.65224724667678e-07 5.44839580641619e-05 1.24641734229431e-05 7.35828381991457e-06 -6.61645263349286e-06 1.41138267693811e-05 4.36023734055396e-06 1.24641734229431e-05 2.44063850411983e-05 5.25758265872759e-06 1.4200937955363e-05 -5.22824066249382e-06 -1.8239405327829e-06 7.35828381991457e-06 5.25758265872759e-06 2.90088475343076e-05 857 856 0 11 0 848 860 0 22 0 0 0 0 0 0 4 14 0 2508 0 0 0 0 0 2087 +880 909 0.996692845449031 -0.00443014244412718 0.0811402838831553 -0.0183450372763664 -0.00667539485659844 0.990674384919256 0.136087112425689 -0.0280598034649697 -0.0809864861209744 -0.136178694746199 0.987368498668556 -0.00116259533107176 3.26485671477127e-05 -3.35150509632248e-05 -2.43240147344137e-06 -1.66749722299287e-06 -3.29750891762671e-06 9.70272271341479e-06 -3.35150509632248e-05 5.421667727105e-05 4.52940576391438e-06 8.33003105553715e-06 7.01820924713627e-06 -1.50891145665398e-06 -2.43240147344137e-06 4.52940576391438e-06 9.47398115827674e-06 6.51316745120532e-07 2.7443945107299e-06 1.92344716152037e-07 -1.66749722299287e-06 8.33003105553715e-06 6.51316745120532e-07 4.21672012682966e-05 1.00968804466263e-05 3.84743241322543e-06 -3.29750891762671e-06 7.01820924713627e-06 2.7443945107299e-06 1.00968804466263e-05 2.26089352939296e-05 3.44300100132814e-06 9.70272271341479e-06 -1.50891145665398e-06 1.92344716152037e-07 3.84743241322543e-06 3.44300100132814e-06 2.84940712461005e-05 858 860 0 21 0 853 861 0 27 0 0 0 0 0 0 4 14 0 2530 0 0 0 0 0 2135 +880 911 0.996439579257815 -0.00429453148384515 0.0842004862684449 -0.0150326631583149 -0.00726488943240306 0.990613630824243 0.136498556061028 -0.0275271298795391 -0.0839963467660545 -0.136624270993645 0.987055430209171 -0.000830684045782508 4.16842167530705e-05 -4.87336665036752e-05 -3.14871031886166e-06 -9.36188823356741e-06 -6.75102955705669e-06 6.95607645319082e-06 -4.87336665036752e-05 0.000103978412722776 9.25504506564518e-06 3.16172778853801e-05 1.96015929649086e-05 -2.29768608723777e-06 -3.14871031886166e-06 9.25504506564518e-06 1.00451202069291e-05 -2.06658159339624e-06 3.97714115553981e-06 -1.93237927739561e-06 -9.36188823356741e-06 3.16172778853801e-05 -2.06658159339624e-06 6.94256660295742e-05 1.18378984116766e-05 8.22357987212041e-06 -6.75102955705669e-06 1.96015929649086e-05 3.97714115553981e-06 1.18378984116766e-05 2.56809543966747e-05 5.14608429012284e-06 6.95607645319082e-06 -2.29768608723777e-06 -1.93237927739561e-06 8.22357987212041e-06 5.14608429012284e-06 3.18939997297937e-05 846 853 0 18 0 843 855 0 23 0 0 0 0 0 0 5 16 0 2605 0 0 0 0 0 2122 +880 907 0.996761401975759 -0.00419619120871491 0.080306285623602 -0.0183883592805915 -0.00665744790263808 0.990903542817559 0.134409252728497 -0.0288243674240595 -0.0801397898596153 -0.134508590100964 0.987666468637215 0.000616403176909215 5.9715827803361e-05 -6.77119474363576e-05 -6.55758754440236e-06 -2.28758728747906e-05 -1.58954548495553e-05 9.76623806443414e-06 -6.77119474363576e-05 0.000112394238910185 9.33276736259883e-06 5.14727877693111e-05 3.00737446714794e-05 4.15611163912251e-06 -6.55758754440236e-06 9.33276736259883e-06 1.01943077882629e-05 1.65510011121084e-06 5.41612256872772e-06 -2.4303026128648e-06 -2.28758728747906e-05 5.14727877693111e-05 1.65510011121084e-06 6.55800039658513e-05 1.78222965809382e-05 1.40160580777941e-05 -1.58954548495553e-05 3.00737446714794e-05 5.41612256872772e-06 1.78222965809382e-05 2.84285746473147e-05 6.63073089583815e-06 9.76623806443414e-06 4.15611163912251e-06 -2.4303026128648e-06 1.40160580777941e-05 6.63073089583815e-06 3.28567300968086e-05 858 861 0 16 0 855 865 0 25 0 0 0 0 0 0 3 13 0 2624 0 0 0 0 0 2132 +880 912 0.996810973288079 -0.00422694619373506 0.079686990521334 -0.0177273910965155 -0.00650521613053744 0.990968152029679 0.133939552881061 -0.0287576039218651 -0.0795334250209741 -0.134030797165274 0.987780430923631 -0.00322086503733082 3.30021295405227e-05 -3.326634103002e-05 -2.43297256772731e-06 -1.76728076523385e-05 -7.58316381936908e-06 5.53700426767093e-07 -3.326634103002e-05 5.47943860627445e-05 5.46829104824332e-06 2.48673816858474e-05 1.1293119517574e-05 4.40767883682759e-06 -2.43297256772731e-06 5.46829104824332e-06 9.63348444411151e-06 1.03636982481684e-06 3.07632282818784e-06 -1.09087413897294e-06 -1.76728076523385e-05 2.48673816858474e-05 1.03636982481684e-06 5.5408205280192e-05 1.0350895790158e-05 1.34592841289283e-05 -7.58316381936908e-06 1.1293119517574e-05 3.07632282818784e-06 1.0350895790158e-05 2.14899517911826e-05 6.13244630703675e-06 5.53700426767093e-07 4.40767883682759e-06 -1.09087413897294e-06 1.34592841289283e-05 6.13244630703675e-06 3.075487732653e-05 846 848 0 14 0 842 851 0 21 0 0 0 0 0 0 2 11 0 2522 0 0 0 0 0 1631 +880 910 0.9967476935417 -0.00411413195601906 0.080480490415688 -0.0165537319111652 -0.00690930385663441 0.990655427439422 0.13621338262092 -0.0292666672468063 -0.0802888344635658 -0.136326439119728 0.98740508660702 -0.000925798458483843 3.9091719969557e-05 -3.71424448488866e-05 -9.42894094074109e-07 -1.17837312444299e-05 -7.72149794901153e-06 1.17603054400734e-05 -3.71424448488866e-05 5.16164455685369e-05 2.70580766927559e-06 2.00187711144357e-05 1.10831288402325e-05 -4.17262920958254e-06 -9.42894094074109e-07 2.70580766927559e-06 9.30004497188027e-06 1.49366001520359e-06 4.91684484093014e-06 1.05556454540657e-06 -1.17837312444299e-05 2.00187711144357e-05 1.49366001520359e-06 4.21996637369195e-05 8.2073077020692e-06 5.71686887300194e-06 -7.72149794901153e-06 1.10831288402325e-05 4.91684484093014e-06 8.2073077020692e-06 2.49423715531842e-05 6.9479787740229e-06 1.17603054400734e-05 -4.17262920958254e-06 1.05556454540657e-06 5.71686887300194e-06 6.9479787740229e-06 3.14862038577366e-05 862 867 0 17 0 859 871 0 26 0 0 0 0 0 0 4 13 0 2559 0 0 0 0 0 2123 +880 925 0.996170965165662 -0.00459883999462462 0.0873055486874541 -0.0102594397338183 -0.00823840285054745 0.989234090589898 0.14610969417958 -0.0205390887789725 -0.0870375601644811 -0.146269493352107 0.985408391701193 0.0113442786065386 0.00110157690091048 4.34507126886872e-06 2.91593715842809e-06 -0.000375682331606785 -0.000379977626104343 -0.00147971837847361 4.34507126886872e-06 0.000180879536950236 6.96431980793817e-06 0.000105985483170839 4.68874896499031e-05 -8.64774138529221e-05 2.91593715842809e-06 6.96431980793817e-06 1.12149955187835e-05 4.32853015706659e-06 3.75185444940324e-06 -3.2979171818615e-06 -0.000375682331606785 0.000105985483170839 4.32853015706659e-06 0.000259520741728664 0.000188525281821261 0.000489837314490442 -0.000379977626104343 4.68874896499031e-05 3.75185444940324e-06 0.000188525281821261 0.000193720776039916 0.000520585567918214 -0.00147971837847361 -8.64774138529221e-05 -3.2979171818615e-06 0.000489837314490442 0.000520585567918214 0.00214290440953741 817 824 0 20 0 814 827 0 28 0 0 0 0 0 0 4 17 0 2484 0 0 0 0 0 1703 +881 883 0.999991950248335 0.00087797339669278 0.00391517576177019 0.00619659635812777 -0.000897884265385054 0.999986659516831 0.00508670740422431 0.00060644264848013 -0.00391065753765616 -0.00509018183220562 0.999979398191052 -0.000159631807744148 5.26853802262393e-05 -6.75817860381917e-05 -8.9206432794686e-07 -2.70831627225571e-05 -2.30346178049879e-05 2.02868730383575e-05 -6.75817860381917e-05 0.000127892021515427 3.34896484714331e-07 8.75805132782934e-05 5.76768120323207e-05 -1.63838401409537e-05 -8.9206432794686e-07 3.34896484714331e-07 8.94593279594026e-06 8.34523623399824e-07 6.73120240185374e-07 -1.77885648106163e-06 -2.70831627225571e-05 8.75805132782934e-05 8.34523623399824e-07 0.000126978125947415 5.97112733901635e-05 5.60581530791514e-06 -2.30346178049879e-05 5.76768120323207e-05 6.73120240185374e-07 5.97112733901635e-05 5.78163262004781e-05 2.76828677491376e-06 2.02868730383575e-05 -1.63838401409537e-05 -1.77885648106163e-06 5.60581530791514e-06 2.76828677491376e-06 5.78541421258818e-05 780 774 0 13 0 777 783 0 22 0 0 0 0 0 0 7 20 0 2108 0 0 0 0 0 2353 +880 923 0.996698399564414 -0.00461797890954753 0.0810615480762975 -0.0186186447184458 -0.00651383342396249 0.990615143154956 0.13652548526268 -0.0280005869205542 -0.0809312688635226 -0.136602754082326 0.987314447021446 0.00211144277644288 2.92957218769981e-05 -3.61128657214022e-05 1.12383786637051e-06 -1.21945396417701e-05 -6.77762941880669e-06 9.74747558464138e-06 -3.61128657214022e-05 8.66233199259126e-05 2.63935819166421e-06 3.86033541786892e-05 2.20773942168529e-05 -8.3768839819493e-06 1.12383786637051e-06 2.63935819166421e-06 8.65637560300414e-06 3.1444124765705e-06 4.56338980020717e-06 -1.90274954865687e-06 -1.21945396417701e-05 3.86033541786892e-05 3.1444124765705e-06 5.51922270876253e-05 1.58117068687766e-05 3.7651510723526e-06 -6.77762941880669e-06 2.20773942168529e-05 4.56338980020717e-06 1.58117068687766e-05 2.60923702249195e-05 1.46893198319159e-06 9.74747558464138e-06 -8.3768839819493e-06 -1.90274954865687e-06 3.7651510723526e-06 1.46893198319159e-06 3.2430576190524e-05 841 844 0 15 0 835 847 0 26 0 0 0 0 0 0 4 15 0 2493 0 0 0 0 0 2052 +881 885 0.999945064695558 0.000964013388755388 0.0104373497201908 0.00949770509212281 -0.00108204593239687 0.999935466497648 0.011308935260713 0.00145160408463919 -0.0104257741964542 -0.0113196076927213 0.99988157784514 -0.00282871380104558 4.62889015320532e-05 -6.39361259735242e-05 2.22628494660905e-06 -3.29191262618709e-05 -2.28536872267821e-05 3.29108494237513e-05 -6.39361259735242e-05 0.000130100347697023 -3.1726338374698e-06 9.82383461745435e-05 5.5491936187853e-05 -5.1285436002144e-05 2.22628494660905e-06 -3.1726338374698e-06 8.76204653522138e-06 -2.58944994210926e-06 3.63363178167628e-07 -1.10293421647417e-07 -3.29191262618709e-05 9.82383461745435e-05 -2.58944994210926e-06 0.000145985749812175 5.90023498822394e-05 -2.90533613313389e-05 -2.28536872267821e-05 5.5491936187853e-05 3.63363178167628e-07 5.90023498822394e-05 5.20480558332678e-05 -1.86968935872698e-05 3.29108494237513e-05 -5.1285436002144e-05 -1.10293421647417e-07 -2.90533613313389e-05 -1.86968935872698e-05 5.48225615809154e-05 743 740 0 8 0 738 749 0 22 0 0 0 0 0 0 9 19 0 2136 0 0 0 0 0 2708 +880 924 0.99633884565415 -0.00504068039204133 0.0853434015125992 -0.0144356175795651 -0.00671962419506467 0.990554662212019 0.136953670344065 -0.0283442217123789 -0.0852276439380588 -0.137025737404398 0.986894217227737 0.00215219269693117 5.79332489666204e-05 -6.37504742907753e-05 -2.9103000966844e-06 -2.47590337530153e-05 -1.72661906155272e-05 -9.06032963875175e-07 -6.37504742907753e-05 0.000109323026758609 7.37714586498014e-06 5.47762586930283e-05 2.93540242173086e-05 1.11750430283148e-05 -2.9103000966844e-06 7.37714586498014e-06 9.73333081261356e-06 1.46553434380685e-06 6.32870653431993e-06 -8.34216585866905e-07 -2.47590337530153e-05 5.47762586930283e-05 1.46553434380685e-06 8.51259200575812e-05 2.41004896412955e-05 2.03298145921241e-05 -1.72661906155272e-05 2.93540242173086e-05 6.32870653431993e-06 2.41004896412955e-05 3.44733628206626e-05 9.34468946599846e-06 -9.06032963875175e-07 1.11750430283148e-05 -8.34216585866905e-07 2.03298145921241e-05 9.34468946599846e-06 3.80934705364434e-05 839 842 0 18 0 836 844 0 24 0 0 0 0 0 0 8 14 0 2513 0 0 0 0 0 1711 +880 906 0.996774344443743 -0.00389659185160051 0.0801606064765445 -0.0152681779843674 -0.0070619944535259 0.990687643518967 0.135971030786615 -0.0274769523615169 -0.079943945943916 -0.136098528833997 0.987464508707092 -0.000905255340017187 3.37781533017557e-05 -3.9653195548704e-05 -1.2064697618443e-06 -8.36039035217826e-06 -5.85940371305246e-06 1.2010665622683e-05 -3.9653195548704e-05 6.71881703998234e-05 3.81192245719735e-06 2.26799923194734e-05 1.38220297556374e-05 -5.1374232533407e-06 -1.2064697618443e-06 3.81192245719735e-06 9.03506419540474e-06 5.54189796528252e-07 5.1758752155808e-06 6.34669247465345e-07 -8.36039035217826e-06 2.26799923194734e-05 5.54189796528252e-07 4.26425929362038e-05 4.85117465518646e-06 4.82855868793849e-06 -5.85940371305246e-06 1.38220297556374e-05 5.1758752155808e-06 4.85117465518646e-06 2.2664741152618e-05 4.98240686322208e-06 1.2010665622683e-05 -5.1374232533407e-06 6.34669247465345e-07 4.82855868793849e-06 4.98240686322208e-06 2.85252566160368e-05 860 862 0 15 0 857 869 0 25 0 0 0 0 0 0 5 16 0 2599 0 0 0 0 0 2136 +880 929 0.996370732219507 -0.0268337428202453 0.0807794170727955 -0.0265913539177636 0.014086663871411 0.987905442579133 0.154416328228272 -0.0310958709623588 -0.0839459938135084 -0.152717997527418 0.984698067101727 -0.00772304902309654 2.73684611849055e-05 -2.68646375510169e-05 -2.89903976877978e-06 -2.76588621768613e-06 -2.87352308620261e-06 9.29398345677227e-06 -2.68646375510169e-05 6.98131578182689e-05 8.31204083406654e-06 2.22648738996347e-05 1.09629464288479e-05 -8.87488831988785e-06 -2.89903976877978e-06 8.31204083406654e-06 1.00754961167086e-05 1.69164010264061e-06 5.37555427764343e-06 -2.51318742647487e-06 -2.76588621768613e-06 2.22648738996347e-05 1.69164010264061e-06 4.64499054882807e-05 4.15293232290647e-06 2.98715389387299e-06 -2.87352308620261e-06 1.09629464288479e-05 5.37555427764343e-06 4.15293232290647e-06 2.09081074136455e-05 -8.3935353458323e-07 9.29398345677227e-06 -8.87488831988785e-06 -2.51318742647487e-06 2.98715389387299e-06 -8.3935353458323e-07 2.54461541752522e-05 871 869 0 3 0 880 880 0 12 0 0 0 0 0 0 20 32 0 2545 0 0 0 0 0 1946 +881 927 0.996702403478169 -0.00479950480400918 0.0810017509346371 -0.0185198018294378 -0.00595618510483192 0.991228991562672 0.132021248837625 -0.0283045115761836 -0.0809249205117785 -0.132068357449033 0.987931731548732 0.0018638129865463 3.83598576513141e-05 -3.80849883595801e-05 -4.16069659244868e-06 -2.47834020615262e-06 -9.0946111794952e-06 1.40087732155774e-05 -3.80849883595801e-05 7.03658323639656e-05 7.80141800428606e-06 1.87599933974772e-05 1.3951328955571e-05 -8.9960663699991e-06 -4.16069659244868e-06 7.80141800428606e-06 1.0399337710928e-05 1.78258020997894e-07 2.86251534159406e-06 -3.03376714555061e-06 -2.47834020615262e-06 1.87599933974772e-05 1.78258020997894e-07 5.63832714236399e-05 5.73255006827649e-06 8.13890911974717e-06 -9.0946111794952e-06 1.3951328955571e-05 2.86251534159406e-06 5.73255006827649e-06 2.80854605301083e-05 2.02275070513454e-06 1.40087732155774e-05 -8.9960663699991e-06 -3.03376714555061e-06 8.13890911974717e-06 2.02275070513454e-06 3.08248015287861e-05 864 866 0 10 0 856 868 0 24 0 0 0 0 0 0 4 15 0 2575 0 0 0 0 0 1790 +881 914 0.996673819096527 -0.00517462703734775 0.0813297089787486 -0.0186662264374263 -0.00574255047311268 0.991041771210055 0.133428748142599 -0.0290007806262457 -0.0812915828459954 -0.133451979947327 0.98771567143917 0.00372571275109393 3.29633536513936e-05 -3.04970559650551e-05 3.51761202642918e-07 -8.17334439636948e-06 -5.23295734075413e-06 7.56263772179456e-06 -3.04970559650551e-05 4.65607218493207e-05 2.41097474343239e-06 1.60211280900781e-05 5.22055137236082e-06 -2.08698750532519e-06 3.51761202642918e-07 2.41097474343239e-06 9.76564500440222e-06 1.45711145349151e-06 2.19189284848467e-06 -4.47487262906166e-07 -8.17334439636948e-06 1.60211280900781e-05 1.45711145349151e-06 4.45422342364809e-05 4.18303829443985e-06 4.61675241342121e-06 -5.23295734075413e-06 5.22055137236082e-06 2.19189284848467e-06 4.18303829443985e-06 2.74189490861005e-05 1.40018360559372e-06 7.56263772179456e-06 -2.08698750532519e-06 -4.47487262906166e-07 4.61675241342121e-06 1.40018360559372e-06 2.72604977061813e-05 901 904 0 16 0 895 908 0 29 0 0 0 0 0 0 5 17 0 2613 0 0 0 0 0 1667 +881 884 0.99992747619454 0.000748895940249635 0.0120200460102307 0.0118714033670922 -0.000841699341791096 0.999969865272043 0.00771751838542148 0.00333214297760429 -0.0120139041712266 -0.00772707594643457 0.999897973997289 -0.00199246559359923 5.13752889254686e-05 -7.28049877266726e-05 8.16441529490638e-07 -3.04495169516301e-05 -2.43559264472126e-05 3.64622190965772e-05 -7.28049877266726e-05 0.000152278678985482 -7.47050767815173e-07 9.32432207936779e-05 5.59456029561785e-05 -6.00691322454025e-05 8.16441529490638e-07 -7.47050767815173e-07 9.82374590129367e-06 -2.09174583113233e-06 5.0848112697076e-07 -3.85570526809739e-07 -3.04495169516301e-05 9.32432207936779e-05 -2.09174583113233e-06 0.000128001087220057 5.10905445246995e-05 -2.87198546580831e-05 -2.43559264472126e-05 5.59456029561785e-05 5.0848112697076e-07 5.10905445246995e-05 4.80116656690116e-05 -2.23645748430265e-05 3.64622190965772e-05 -6.00691322454025e-05 -3.85570526809739e-07 -2.87198546580831e-05 -2.23645748430265e-05 6.09572561473905e-05 732 732 0 12 0 729 742 0 24 0 0 0 0 0 0 7 21 0 2167 0 0 0 0 0 2181 +881 922 0.996604424018094 -0.00487413130779354 0.0821940683477662 -0.0149160789413232 -0.0060101274229722 0.991277256378697 0.131655912722073 -0.0274746923416849 -0.0821188187684316 -0.131702861891141 0.987882004985292 0.000808008763778626 4.91067999629422e-05 -4.81599672985624e-05 -3.80111642184715e-06 -1.69847638433679e-05 -1.18697257049386e-05 -1.35149876101595e-05 -4.81599672985624e-05 9.05461470844977e-05 9.94842512964091e-06 2.84009402097975e-05 1.6148873411441e-05 2.14481014713996e-05 -3.80111642184715e-06 9.94842512964091e-06 1.17564170366356e-05 1.34097993915699e-06 2.40788436965418e-06 2.69385487540991e-06 -1.69847638433679e-05 2.84009402097975e-05 1.34097993915699e-06 5.72825372467513e-05 1.19685117470633e-05 1.48261914821919e-05 -1.18697257049386e-05 1.6148873411441e-05 2.40788436965418e-06 1.19685117470633e-05 2.97126984327417e-05 1.0539605161016e-05 -1.35149876101595e-05 2.14481014713996e-05 2.69385487540991e-06 1.48261914821919e-05 1.0539605161016e-05 4.94438813751415e-05 874 873 0 11 0 869 879 0 25 0 0 0 0 0 0 5 18 0 2629 0 0 0 0 0 1733 +881 920 0.996292042678022 -0.00584840660743823 0.0858368326338292 -0.0157993200683301 -0.0055941413693859 0.991172207457412 0.132462676804981 -0.0301001683080768 -0.0858537784770901 -0.132451694229087 0.987464266400082 0.00475937639510992 6.0395276567459e-05 -6.3950576163693e-05 -6.89369344584766e-06 -9.96205441767559e-06 -1.08208189300953e-05 7.39621718081812e-06 -6.3950576163693e-05 0.000106774241144629 1.13202599951421e-05 2.79919555013564e-05 1.16689866583796e-05 7.07932633341872e-06 -6.89369344584766e-06 1.13202599951421e-05 1.26000935119495e-05 1.30714458820406e-06 1.9159519456252e-06 -2.32516599805642e-06 -9.96205441767559e-06 2.79919555013564e-05 1.30714458820406e-06 5.26683812458308e-05 3.08981366978189e-06 1.28650358763724e-05 -1.08208189300953e-05 1.16689866583796e-05 1.9159519456252e-06 3.08981366978189e-06 3.37456847097697e-05 3.153903140369e-06 7.39621718081812e-06 7.07932633341872e-06 -2.32516599805642e-06 1.28650358763724e-05 3.153903140369e-06 3.67398456404264e-05 850 849 0 9 0 843 852 0 21 0 0 0 0 0 0 4 14 0 2358 0 0 0 0 0 1658 +881 921 0.996395757066721 -0.00502792647230437 0.0846771235625373 -0.0137680986165286 -0.0063864491423023 0.990962061022149 0.133990323837531 -0.0279733030118299 -0.0845855103832145 -0.13404817630286 0.987358282419856 0.0047405309350477 3.05166213853591e-05 -3.29661535777288e-05 1.84994970653535e-06 -1.45838870189234e-05 -7.2944915875889e-06 7.12504353939642e-06 -3.29661535777288e-05 7.03727521944142e-05 1.65312188232564e-06 4.22314185593363e-05 1.66042188130004e-05 -1.70950964563499e-06 1.84994970653535e-06 1.65312188232564e-06 9.50969795837441e-06 2.34102717496879e-06 3.66846710329155e-06 8.08106085327927e-07 -1.45838870189234e-05 4.22314185593363e-05 2.34102717496879e-06 7.22228644338294e-05 1.51238275185073e-05 7.27415597133335e-06 -7.2944915875889e-06 1.66042188130004e-05 3.66846710329155e-06 1.51238275185073e-05 3.13013445416596e-05 6.4536772237415e-06 7.12504353939642e-06 -1.70950964563499e-06 8.08106085327927e-07 7.27415597133335e-06 6.4536772237415e-06 3.21879358279797e-05 848 845 0 16 0 841 850 0 28 0 0 0 0 0 0 6 16 0 2488 0 0 0 0 0 2041 +881 913 0.996744221845458 -0.00460034802776366 0.0804971615382501 -0.0157811683788723 -0.00616091725156007 0.99110660271831 0.132927593624462 -0.0256819751183822 -0.0803927814938077 -0.132990747220227 0.98785143712883 0.00227641636288985 2.72806909105668e-05 -2.41934377717041e-05 2.157846848915e-06 -8.23439726261383e-06 -5.1291935719929e-06 6.5508938906939e-06 -2.41934377717041e-05 4.45461123974282e-05 1.38864658217279e-06 1.26887893644548e-05 6.58840043318504e-06 -9.82418282448454e-07 2.157846848915e-06 1.38864658217279e-06 9.65541746564936e-06 2.22649949148431e-06 2.22303113376639e-06 1.03816482530666e-06 -8.23439726261383e-06 1.26887893644548e-05 2.22649949148431e-06 4.43903901746287e-05 7.80519059847804e-06 9.23539045225463e-06 -5.1291935719929e-06 6.58840043318504e-06 2.22303113376639e-06 7.80519059847804e-06 2.59175282661883e-05 6.66571304703005e-06 6.5508938906939e-06 -9.82418282448454e-07 1.03816482530666e-06 9.23539045225463e-06 6.66571304703005e-06 2.70349164497459e-05 892 895 0 16 0 885 900 0 30 0 0 0 0 0 0 7 19 0 2519 0 0 0 0 0 1776 +881 919 0.996690738812002 -0.00463240447102169 0.0811548642732054 -0.0178172358672357 -0.00599947950745039 0.991459717966268 0.130275223645513 -0.0307130829439147 -0.0810652663723817 -0.130330995849282 0.988150926786445 0.00166162946406754 7.40574562642798e-05 -9.48659968234599e-05 -9.1876906814326e-06 -3.71227512389208e-05 -3.16014904266909e-05 -2.20656610589697e-05 -9.48659968234599e-05 0.000201050127090623 1.72019877455753e-05 9.58064167519232e-05 4.72857482322657e-05 6.65548748531867e-05 -9.1876906814326e-06 1.72019877455753e-05 1.23470056075703e-05 6.78362921688225e-06 5.1493226782412e-06 4.52680469983446e-06 -3.71227512389208e-05 9.58064167519232e-05 6.78362921688225e-06 0.00010440193623074 2.76810615458551e-05 5.33715603676109e-05 -3.16014904266909e-05 4.72857482322657e-05 5.1493226782412e-06 2.76810615458551e-05 4.93910480086206e-05 2.06950559336433e-05 -2.20656610589697e-05 6.65548748531867e-05 4.52680469983446e-06 5.33715603676109e-05 2.06950559336433e-05 7.69048797732163e-05 860 862 0 12 0 857 867 0 23 0 0 0 0 0 0 3 13 0 2374 0 0 0 0 0 1789 +881 926 0.99652422640708 -0.00501843162710746 0.0831521588882408 -0.0165192805682066 -0.00612221557615542 0.991072374277375 0.133184336243588 -0.027546091466542 -0.0830781840208985 -0.133230493087018 0.987596907169914 0.000114640812417718 3.8644358596524e-05 -4.33321611455146e-05 -2.18319436360065e-06 -1.10761486547287e-05 -1.00840695158662e-05 1.18427825474419e-05 -4.33321611455146e-05 9.23290971257537e-05 7.91449833034873e-06 3.12206887638103e-05 1.81348835048344e-05 -5.27895949506847e-06 -2.18319436360065e-06 7.91449833034873e-06 1.0438414081478e-05 2.53195830138174e-06 3.41503924779139e-06 -8.31728738478325e-07 -1.10761486547287e-05 3.12206887638103e-05 2.53195830138174e-06 5.47235455560268e-05 7.94342725561671e-06 9.72345357481224e-06 -1.00840695158662e-05 1.81348835048344e-05 3.41503924779139e-06 7.94342725561671e-06 2.87979147518135e-05 2.07300912471771e-06 1.18427825474419e-05 -5.27895949506847e-06 -8.31728738478325e-07 9.72345357481224e-06 2.07300912471771e-06 3.01035760793172e-05 872 871 0 10 0 861 873 0 25 0 0 0 0 0 0 5 16 0 2542 0 0 0 0 0 1786 +881 916 0.996332230767004 -0.00488395543156736 0.0854296957397562 -0.0148950687488548 -0.00639997735113136 0.991320240719536 0.131313444207613 -0.0283766006806405 -0.0853295155544075 -0.131378564914918 0.987653049636433 0.00206579322857165 8.39379644374698e-05 -9.50147553601108e-05 -8.09462314697864e-06 -3.89826565433227e-05 -3.21640162914195e-05 -2.05220082055683e-05 -9.50147553601108e-05 0.000148630600857227 1.27167549528417e-05 7.09948663784784e-05 4.1112503805965e-05 3.44115304002132e-05 -8.09462314697864e-06 1.27167549528417e-05 1.16379104322084e-05 3.70469766276775e-06 5.6855787023261e-06 1.43710920566984e-06 -3.89826565433227e-05 7.09948663784784e-05 3.70469766276775e-06 9.35408799917099e-05 2.50368482331421e-05 3.62897762523867e-05 -3.21640162914195e-05 4.1112503805965e-05 5.6855787023261e-06 2.50368482331421e-05 4.07775614201501e-05 2.08230527857197e-05 -2.05220082055683e-05 3.44115304002132e-05 1.43710920566984e-06 3.62897762523867e-05 2.08230527857197e-05 5.72223893077381e-05 846 844 0 7 0 840 849 0 20 0 0 0 0 0 0 3 12 0 2484 0 0 0 0 0 1780 +881 915 0.996506007155561 -0.00456080698862726 0.0833965031790454 -0.0148598756466614 -0.00664151795269928 0.991018924300625 0.133556661823048 -0.0265030059819805 -0.0832566390275515 -0.133643895175367 0.987526020588922 -1.27829518923642e-05 3.92322463686016e-05 -4.9130855177918e-05 -2.9359635078617e-06 -1.25874811366173e-05 -1.22700970771335e-05 1.23343684982505e-05 -4.9130855177918e-05 0.00011415664600803 9.23663981842571e-06 5.1160029856632e-05 2.67651313652784e-05 -5.04935141035801e-06 -2.9359635078617e-06 9.23663981842571e-06 1.05161797389326e-05 4.67498424863073e-06 3.51234978309744e-06 -8.51494138138076e-07 -1.25874811366173e-05 5.1160029856632e-05 4.67498424863073e-06 7.15210246664396e-05 1.5223603686046e-05 1.27721068513442e-05 -1.22700970771335e-05 2.67651313652784e-05 3.51234978309744e-06 1.5223603686046e-05 3.46407798601259e-05 6.03597086580683e-06 1.23343684982505e-05 -5.04935141035801e-06 -8.51494138138076e-07 1.27721068513442e-05 6.03597086580683e-06 3.5474992639249e-05 862 857 0 7 0 856 863 0 20 0 0 0 0 0 0 3 12 0 2594 0 0 0 0 0 1776 +881 910 0.996626788390022 -0.00481615612904094 0.0819258768859487 -0.0152144196558856 -0.0062620774569031 0.990903299997666 0.134430042920694 -0.0281249216284602 -0.0818280578366288 -0.134489608125968 0.987530614339023 0.00146636080432705 4.67902486344139e-05 -5.40435076507669e-05 1.52652727319005e-06 -2.13975234288417e-05 -1.15096887161871e-05 6.18599855715648e-07 -5.40435076507669e-05 0.000100900554450418 2.94674055597211e-06 4.87774354274024e-05 2.10501302803493e-05 1.38184444007687e-05 1.52652727319005e-06 2.94674055597211e-06 1.04200087201777e-05 1.66744817529478e-06 3.6135100191268e-06 3.65437448618219e-06 -2.13975234288417e-05 4.87774354274024e-05 1.66744817529478e-06 6.64347891527336e-05 1.61976934658937e-05 1.23228936111534e-05 -1.15096887161871e-05 2.10501302803493e-05 3.6135100191268e-06 1.61976934658937e-05 3.30741689754077e-05 1.39642808452256e-05 6.18599855715648e-07 1.38184444007687e-05 3.65437448618219e-06 1.23228936111534e-05 1.39642808452256e-05 3.70709268165582e-05 889 893 0 15 0 882 894 0 26 0 0 0 0 0 0 5 14 0 2573 0 0 0 0 0 1669 +881 908 0.996818768055714 -0.00481301165078038 0.0795561347146626 -0.0191678032070843 -0.00571989769357481 0.991281121274326 0.131639740866844 -0.0292970907432393 -0.0794960780306999 -0.131676017269525 0.98810009617132 0.000703621786982208 4.15688508346372e-05 -3.54057684368065e-05 3.17924605563222e-06 -2.39046061071619e-05 -1.52789773869911e-05 -2.51184799259309e-06 -3.54057684368065e-05 5.01125971308294e-05 1.28035505531649e-07 2.9763510377272e-05 1.53781865288723e-05 6.68598814307175e-06 3.17924605563222e-06 1.28035505531649e-07 1.08174161053698e-05 2.18713708597919e-06 3.77188932201413e-06 4.26942944091101e-06 -2.39046061071619e-05 2.9763510377272e-05 2.18713708597919e-06 6.16856678289456e-05 1.50599936384966e-05 1.53651753514931e-05 -1.52789773869911e-05 1.53781865288723e-05 3.77188932201413e-06 1.50599936384966e-05 3.17980628289529e-05 1.13731999550467e-05 -2.51184799259309e-06 6.68598814307175e-06 4.26942944091101e-06 1.53651753514931e-05 1.13731999550467e-05 3.92718480941041e-05 866 864 0 14 0 862 871 0 28 0 0 0 0 0 0 6 16 0 2564 0 0 0 0 0 1784 +881 918 0.996575223475173 -0.00529841696267187 0.0825212138367951 -0.0177414111498291 -0.00553369296193131 0.991434847031668 0.130484950601576 -0.0324976568982694 -0.0825057706927913 -0.130494715866131 0.988010084429003 0.00307772920983878 5.34318979976679e-05 -6.11771338783961e-05 -6.71546248051014e-06 -1.28379979585142e-05 -1.66808716927732e-05 1.14374409654492e-05 -6.11771338783961e-05 0.000124345729824957 1.2471305373115e-05 4.14407197547078e-05 2.49562413254873e-05 4.65396488819672e-06 -6.71546248051014e-06 1.2471305373115e-05 1.17502625159452e-05 1.35356628089022e-06 3.43294208982299e-06 -2.01837939671879e-06 -1.28379979585142e-05 4.14407197547078e-05 1.35356628089022e-06 6.33895053069708e-05 9.77584177494949e-06 1.95850869311819e-05 -1.66808716927732e-05 2.49562413254873e-05 3.43294208982299e-06 9.77584177494949e-06 3.52147334290979e-05 3.23314189427646e-06 1.14374409654492e-05 4.65396488819672e-06 -2.01837939671879e-06 1.95850869311819e-05 3.23314189427646e-06 4.34885784736344e-05 867 869 0 15 0 861 873 0 28 0 0 0 0 0 0 4 15 0 2314 0 0 0 0 0 1674 +881 923 0.996639958752735 -0.00495244494880802 0.081757359952341 -0.0165618142842579 -0.00586491704723192 0.991293233785372 0.131542112645987 -0.0275419031926147 -0.0816969728042399 -0.131579625855865 0.987933401952912 0.00160147936699265 3.40881622696922e-05 -2.7194709446616e-05 2.41078793312791e-06 -1.18064359737724e-05 -8.41209308993526e-06 -3.18872721482012e-06 -2.7194709446616e-05 4.64662668153235e-05 2.00261741053927e-06 1.54200435581569e-05 6.85990858648602e-06 3.49026781209294e-06 2.41078793312791e-06 2.00261741053927e-06 1.03841156153128e-05 1.85511909725249e-06 1.27691794308676e-06 6.68783702142e-07 -1.18064359737724e-05 1.54200435581569e-05 1.85511909725249e-06 4.37932620589275e-05 9.04116455255919e-06 9.89903786330751e-06 -8.41209308993526e-06 6.85990858648602e-06 1.27691794308676e-06 9.04116455255919e-06 2.55188502883381e-05 6.17934719927003e-06 -3.18872721482012e-06 3.49026781209294e-06 6.68783702142e-07 9.89903786330751e-06 6.17934719927003e-06 3.62933657443225e-05 863 865 0 15 0 851 865 0 29 0 0 0 0 0 0 5 18 0 2505 0 0 0 0 0 1784 +881 928 0.996696808845921 -0.00499766538225638 0.0810585873124098 -0.0192134546176371 -0.00578864416625876 0.991194251311704 0.13228925793634 -0.0286071616729626 -0.0810059432083413 -0.132321500548316 0.987891217522238 0.000597215199986055 3.87938633048698e-05 -5.23171578014979e-05 -3.52751897260643e-06 -1.21866134607904e-05 -8.90979151465742e-06 -1.43896973312177e-06 -5.23171578014979e-05 0.000137008392809447 1.21915500303581e-05 4.31973582749155e-05 1.66656048776278e-05 1.8455000228079e-05 -3.52751897260643e-06 1.21915500303581e-05 1.13138359421785e-05 1.73865676282065e-06 3.41703600424857e-06 4.43079827619998e-07 -1.21866134607904e-05 4.31973582749155e-05 1.73865676282065e-06 5.91938393810474e-05 7.66843371810881e-06 2.07608113065178e-05 -8.90979151465742e-06 1.66656048776278e-05 3.41703600424857e-06 7.66843371810881e-06 2.58216287811243e-05 9.82274764460766e-06 -1.43896973312177e-06 1.8455000228079e-05 4.43079827619998e-07 2.07608113065178e-05 9.82274764460766e-06 4.4236556238755e-05 857 858 0 13 0 850 863 0 29 0 0 0 0 0 0 5 19 0 2519 0 0 0 0 0 1778 +881 912 0.996332242603341 -0.00491364415484128 0.085427855235376 -0.0111350725347186 -0.00681904843409701 0.990615524093292 0.136507816640018 -0.02321015844057 -0.0852969104214813 -0.136589675768306 0.986948680300075 0.00398086460920582 4.07797547563704e-05 -4.83461141661375e-05 -3.91939090739979e-06 -1.51739246100747e-05 -1.37382860874335e-05 9.33307165339736e-06 -4.83461141661375e-05 9.78209560245635e-05 8.91900341527188e-06 4.52199713409757e-05 2.7063130189249e-05 -6.02158134400465e-07 -3.91939090739979e-06 8.91900341527188e-06 9.98519950457263e-06 3.65548205063026e-06 2.56788944000361e-06 -2.32345486208372e-06 -1.51739246100747e-05 4.52199713409757e-05 3.65548205063026e-06 7.15679730770026e-05 2.30155463732397e-05 1.66889566513786e-05 -1.37382860874335e-05 2.7063130189249e-05 2.56788944000361e-06 2.30155463732397e-05 3.36083613874606e-05 6.16317595921286e-06 9.33307165339736e-06 -6.02158134400465e-07 -2.32345486208372e-06 1.66889566513786e-05 6.16317595921286e-06 3.18014933389617e-05 862 863 0 13 0 855 865 0 25 0 0 0 0 0 0 3 13 0 2520 0 0 0 0 0 2127 +881 925 0.996739032121292 -0.00496118466016455 0.080539980709446 -0.0184224338950549 -0.00591129318288842 0.990937018108271 0.134197178642454 -0.0253929638264844 -0.0804758253068343 -0.134235661392406 0.987676277305336 0.00488439309158972 3.94254018860591e-05 -3.77949845840396e-05 5.30582327258511e-06 -3.14961847858267e-05 -2.15836558430787e-05 4.83533630024701e-06 -3.77949845840396e-05 6.4530050954474e-05 -2.57879359009614e-06 5.06014638646833e-05 2.67175555258684e-05 5.8617305372079e-09 5.30582327258511e-06 -2.57879359009614e-06 9.78364669359117e-06 8.37788729600046e-07 -4.32787039693564e-07 9.82880916633416e-07 -3.14961847858267e-05 5.06014638646833e-05 8.37788729600046e-07 9.1214296803434e-05 3.96939364132952e-05 1.46340935739781e-05 -2.15836558430787e-05 2.67175555258684e-05 -4.32787039693564e-07 3.96939364132952e-05 4.30449132568537e-05 8.19995356394413e-06 4.83533630024701e-06 5.8617305372079e-09 9.82880916633416e-07 1.46340935739781e-05 8.19995356394413e-06 3.29960892600863e-05 851 854 0 12 0 845 856 0 23 0 0 0 0 0 0 5 16 0 2512 0 0 0 0 0 2098 +881 917 0.996523350738857 -0.00447896642834967 0.0831934510158945 -0.0126897265539037 -0.00666332520797976 0.99107039316984 0.133173104939967 -0.0252713018024868 -0.0830470440736636 -0.133264453782366 0.987594944209778 0.000979416507745931 5.86268022936947e-05 -7.13617009107607e-05 -7.10420202101706e-06 -2.74742702251562e-05 -2.13449804712333e-05 1.7114328259906e-05 -7.13617009107607e-05 0.000177738163814442 1.74527852064438e-05 8.87402528860024e-05 3.76033028585055e-05 7.48615175049241e-06 -7.10420202101706e-06 1.74527852064438e-05 1.16945105220646e-05 6.62231178185683e-06 2.74024276391076e-06 -1.60552455843956e-06 -2.74742702251562e-05 8.87402528860024e-05 6.62231178185683e-06 0.000108978956672993 3.54994898977705e-05 2.15267507297597e-05 -2.13449804712333e-05 3.76033028585055e-05 2.74024276391076e-06 3.54994898977705e-05 4.46140399369777e-05 1.62303799212513e-06 1.7114328259906e-05 7.48615175049241e-06 -1.60552455843956e-06 2.15267507297597e-05 1.62303799212513e-06 4.53452220984948e-05 857 855 0 12 0 852 863 0 26 0 0 0 0 0 0 4 17 0 2273 0 0 0 0 0 1767 +881 929 0.996202677575439 -0.0268757494053523 0.0828125551195378 -0.018472170769196 0.0138116451085558 0.987902148474558 0.154462239718148 -0.0253695497497664 -0.0859619895705136 -0.152731919169675 0.984521963805697 -0.00591883727885552 3.72230765485271e-05 -3.87267252965183e-05 -3.76381928114091e-06 -6.30051791949651e-06 -6.29205201193503e-06 4.05909241478549e-06 -3.87267252965183e-05 0.000107439939445293 1.56342844664971e-05 1.53281940619512e-05 7.34375746784072e-06 1.33293752996791e-05 -3.76381928114091e-06 1.56342844664971e-05 1.23213808716474e-05 -2.65626886655523e-07 5.65663926196632e-07 2.48745811527941e-07 -6.30051791949651e-06 1.53281940619512e-05 -2.65626886655523e-07 4.59724991873993e-05 8.01407230768566e-06 9.94557259740626e-06 -6.29205201193503e-06 7.34375746784072e-06 5.65663926196632e-07 8.01407230768566e-06 2.61933941528457e-05 1.01054217667318e-06 4.05909241478549e-06 1.33293752996791e-05 2.48745811527941e-07 9.94557259740626e-06 1.01054217667318e-06 3.17382074728542e-05 878 875 0 0 0 886 888 0 11 0 0 0 0 0 0 19 33 0 2523 0 0 0 0 0 1857 +881 909 0.996992299928922 -0.00491602350798296 0.0773445964195781 -0.0200307417269626 -0.00534009118367086 0.991256695403729 0.131839475285015 -0.0283133502976567 -0.0773164750139874 -0.131855968883274 0.988249040556713 0.00134531934356617 4.73220182748123e-05 -5.99828340328787e-05 -4.09743484100338e-06 -1.26594853282758e-05 -1.43767878069275e-05 1.00061152974375e-05 -5.99828340328787e-05 0.000139914465684844 1.14291288191735e-05 5.18901726006926e-05 2.92868593037772e-05 7.09680725195424e-06 -4.09743484100338e-06 1.14291288191735e-05 1.12819911203703e-05 4.81787507205867e-06 4.54162751996638e-06 -1.57656581732384e-07 -1.26594853282758e-05 5.18901726006926e-05 4.81787507205867e-06 6.44491815479125e-05 1.62781538754024e-05 2.00901414251894e-05 -1.43767878069275e-05 2.92868593037772e-05 4.54162751996638e-06 1.62781538754024e-05 3.17076715362979e-05 8.05129735640405e-06 1.00061152974375e-05 7.09680725195424e-06 -1.57656581732384e-07 2.00901414251894e-05 8.05129735640405e-06 3.92899620172553e-05 855 854 0 12 0 847 854 0 23 0 0 0 0 0 0 3 14 0 2535 0 0 0 0 0 1657 +881 911 0.996759722950332 -0.0044414298747949 0.0803139365530379 -0.0154238725207779 -0.00642427267755356 0.990889056670615 0.13452734328375 -0.0261731828225821 -0.0801796945899806 -0.13460739604898 0.987649768644923 0.00259204680781706 3.64526852795483e-05 -4.05258379488681e-05 -2.39479622075371e-06 -1.06978645738925e-05 -7.11355926548499e-06 7.57146907206266e-06 -4.05258379488681e-05 8.64895539459371e-05 7.94120136564336e-06 2.52762346354043e-05 1.05635798971731e-05 9.72797709876176e-07 -2.39479622075371e-06 7.94120136564336e-06 1.09985696851921e-05 1.12710771963822e-07 2.69791919182934e-06 -1.21825516319856e-06 -1.06978645738925e-05 2.52762346354043e-05 1.12710771963822e-07 4.83300494297685e-05 9.38413573414391e-06 9.6381601246879e-06 -7.11355926548499e-06 1.05635798971731e-05 2.69791919182934e-06 9.38413573414391e-06 2.85566657097934e-05 2.90941960686467e-06 7.57146907206266e-06 9.72797709876176e-07 -1.21825516319856e-06 9.6381601246879e-06 2.90941960686467e-06 3.07195773742818e-05 862 865 0 14 0 850 862 0 27 0 0 0 0 0 0 4 15 0 2617 0 0 0 0 0 1661 +882 920 0.996021752505163 -0.00510220946155487 0.0889642399796402 -0.00923948666118755 -0.00674025043077947 0.991185746438234 0.132307917683756 -0.0245651120804206 -0.0888551493199745 -0.13238120529853 0.987208174056026 0.00508698639868443 5.34408902401778e-05 -6.34868926919819e-05 -6.86441700461531e-06 -1.09961160033927e-05 -1.23468503123527e-05 1.03029729189507e-05 -6.34868926919819e-05 0.000160452704441428 1.07842171255271e-05 8.40334173853678e-05 3.81338757241334e-05 1.15489213348715e-05 -6.86441700461531e-06 1.07842171255271e-05 1.23871960882791e-05 -6.2531304981263e-06 8.78906421799529e-08 -4.03342698384991e-06 -1.09961160033927e-05 8.40334173853678e-05 -6.2531304981263e-06 0.000184255939665649 6.0776778436626e-05 3.20230699034392e-05 -1.23468503123527e-05 3.81338757241334e-05 8.78906421799529e-08 6.0776778436626e-05 5.07415606596143e-05 9.40459505155121e-06 1.03029729189507e-05 1.15489213348715e-05 -4.03342698384991e-06 3.20230699034392e-05 9.40459505155121e-06 3.78109172919084e-05 837 840 0 13 0 837 846 0 21 0 0 0 0 0 0 6 15 0 2313 0 0 0 0 0 1858 +882 884 0.999998791312642 0.000535697664910761 0.00145958941727013 0.00227754981482636 -0.000537276858306396 0.999999270557275 0.00108176637756563 -0.000492288204952492 -0.00145900885286081 -0.00108254927366482 0.999998349688757 -0.00342505246018431 3.9537255469536e-05 -4.84835022903646e-05 1.33238059335306e-06 -1.63481610437883e-05 -1.20408633799499e-05 7.74845751870232e-06 -4.84835022903646e-05 8.1303635593304e-05 -1.08293505508719e-06 4.24770022823041e-05 2.76292623105818e-05 7.01728938157467e-06 1.33238059335306e-06 -1.08293505508719e-06 9.36072782137261e-06 -1.12066142810369e-06 7.14540229162198e-07 -1.05761580552461e-06 -1.63481610437883e-05 4.24770022823041e-05 -1.12066142810369e-06 8.4312919102787e-05 3.28493696700318e-05 3.31019121737916e-05 -1.20408633799499e-05 2.76292623105818e-05 7.14540229162198e-07 3.28493696700318e-05 3.76841128560968e-05 1.84443970566991e-05 7.74845751870232e-06 7.01728938157467e-06 -1.05761580552461e-06 3.31019121737916e-05 1.84443970566991e-05 5.66162232034144e-05 745 741 0 8 0 742 754 0 23 0 0 0 0 0 0 8 23 0 2168 0 0 0 0 0 2367 +882 913 0.997422899805269 -0.00340841160809184 0.071665484540038 -0.0195728611501968 -0.00572111237759461 0.991911753981402 0.126800399000559 -0.028429639354679 -0.0715180244219003 -0.126883627958251 0.989335998101222 9.45525022977619e-05 3.90193274681656e-05 -4.1394429466226e-05 1.14104026107792e-06 -1.2961301121294e-05 -1.10855310269288e-05 5.11815570453189e-07 -4.1394429466226e-05 7.16992315144993e-05 1.76902908720263e-06 3.03949743017916e-05 1.94728750305536e-05 6.33613682169287e-06 1.14104026107792e-06 1.76902908720263e-06 9.83656560402539e-06 1.8108669292605e-07 3.45127510638372e-06 -5.82810582496614e-07 -1.2961301121294e-05 3.03949743017916e-05 1.8108669292605e-07 6.56996049492207e-05 1.46038571289434e-05 1.76857740455609e-05 -1.10855310269288e-05 1.94728750305536e-05 3.45127510638372e-06 1.46038571289434e-05 3.32888595888127e-05 1.21154891959967e-05 5.11815570453189e-07 6.33613682169287e-06 -5.82810582496614e-07 1.76857740455609e-05 1.21154891959967e-05 3.92471793136136e-05 909 910 0 20 0 908 921 0 33 0 0 0 0 0 0 3 17 0 2492 0 0 0 0 0 1998 +882 919 0.995913442743276 -0.0049757947106323 0.0901756953409981 -0.0121695117223666 -0.00698885947596793 0.991240845521556 0.131881545384238 -0.0246736916998434 -0.0900420479912581 -0.131972829160806 0.987155307921116 0.00563691078960523 5.67464837669323e-05 -6.10829994806016e-05 -4.94042265022073e-06 -1.87858116435061e-05 -1.66375460067496e-05 -4.84055497018143e-06 -6.10829994806016e-05 9.80059188115004e-05 8.48053043495196e-06 3.75572969356879e-05 1.92613166306062e-05 1.92003756824766e-05 -4.94042265022073e-06 8.48053043495196e-06 1.09381128856262e-05 1.86514346203334e-06 2.76290836246556e-06 -1.96349325839317e-06 -1.87858116435061e-05 3.75572969356879e-05 1.86514346203334e-06 6.06620197760741e-05 1.00317975121806e-05 2.81604264679799e-05 -1.66375460067496e-05 1.92613166306062e-05 2.76290836246556e-06 1.00317975121806e-05 3.07448001158822e-05 7.97612638107409e-06 -4.84055497018143e-06 1.92003756824766e-05 -1.96349325839317e-06 2.81604264679799e-05 7.97612638107409e-06 4.94803537752921e-05 849 851 0 15 0 848 857 0 23 0 0 0 0 0 0 1 10 0 2309 0 0 0 0 0 1686 +881 907 0.996305664695838 -0.00517783550947367 0.0857217155359232 -0.0142464670280266 -0.00641313196558102 0.990907677936736 0.134390645300997 -0.0272892255770462 -0.0856381587458356 -0.134443905869561 0.98721372657655 0.00173207268527909 4.05421328130048e-05 -4.54521598220343e-05 -3.31329954724365e-06 -1.22358212368231e-05 -1.11562127099928e-05 4.9174659647074e-06 -4.54521598220343e-05 8.97679692743537e-05 8.66826584772085e-06 3.26591090837841e-05 2.01065409392606e-05 1.26988182307578e-06 -3.31329954724365e-06 8.66826584772085e-06 1.22087347782214e-05 1.55404702656739e-06 3.11422191224308e-06 -2.64723471269472e-06 -1.22358212368231e-05 3.26591090837841e-05 1.55404702656739e-06 5.74342708678464e-05 1.21051115719044e-05 9.36428347008896e-06 -1.11562127099928e-05 2.01065409392606e-05 3.11422191224308e-06 1.21051115719044e-05 3.05338344523877e-05 6.75543948541588e-06 4.9174659647074e-06 1.26988182307578e-06 -2.64723471269472e-06 9.36428347008896e-06 6.75543948541588e-06 3.78107540034258e-05 874 876 0 16 0 866 875 0 26 0 0 0 0 0 0 4 14 0 2622 0 0 0 0 0 1687 +882 885 0.999971970885892 0.000524795945376876 0.00746873696152658 0.00506765724346472 -0.000574359241759797 0.999977819849822 0.00663550449163844 0.000222674627981246 -0.00746508901796639 -0.00663960824242401 0.999950092778805 -0.00414756038542252 4.1707170764362e-05 -5.47882570898054e-05 -1.00616330230702e-06 -2.094774264147e-05 -1.31206404298367e-05 4.01676360473486e-06 -5.47882570898054e-05 0.000110118483264534 1.92573760344377e-06 7.21858688601706e-05 3.79534648821513e-05 9.41070644241086e-06 -1.00616330230702e-06 1.92573760344377e-06 9.03680981019248e-06 1.76825888264083e-06 1.76482800142566e-06 4.82847161883328e-07 -2.094774264147e-05 7.21858688601706e-05 1.76825888264083e-06 0.000106803017057772 3.88754246265712e-05 1.52413283017236e-05 -1.31206404298367e-05 3.79534648821513e-05 1.76482800142566e-06 3.88754246265712e-05 4.06309850786152e-05 1.25708199261103e-05 4.01676360473486e-06 9.41070644241086e-06 4.82847161883328e-07 1.52413283017236e-05 1.25708199261103e-05 4.92372852967385e-05 770 768 0 12 0 770 777 0 19 0 0 0 0 0 0 7 18 0 2148 0 0 0 0 0 2429 +882 886 0.999998531975958 0.00041923220853791 0.00166141213560336 0.00216327356837859 -0.000430861507976165 0.999975368484955 0.00700548226309175 -0.00194457689474567 -0.00165843428870432 -0.00700618781741348 0.999974081128095 -0.000902928950180004 3.13651557795166e-05 -3.48196235588933e-05 4.2778319026571e-06 -1.10812169299138e-05 -3.69943973973781e-06 1.6522133305077e-05 -3.48196235588933e-05 6.1223425734987e-05 -4.76802884736103e-07 1.82454313038437e-05 8.47858523632418e-06 -1.95060796648572e-05 4.2778319026571e-06 -4.76802884736103e-07 9.55986240317664e-06 1.53876328032615e-06 2.36715218872398e-06 3.48893032830299e-07 -1.10812169299138e-05 1.82454313038437e-05 1.53876328032615e-06 4.81440447872572e-05 1.13637966879245e-05 -7.48839678126118e-06 -3.69943973973781e-06 8.47858523632418e-06 2.36715218872398e-06 1.13637966879245e-05 2.90632841714231e-05 2.72691381014181e-07 1.6522133305077e-05 -1.95060796648572e-05 3.48893032830299e-07 -7.48839678126118e-06 2.72691381014181e-07 3.72465939940194e-05 776 775 0 13 0 775 784 0 23 0 0 0 0 0 0 9 19 0 2121 0 0 0 0 0 1971 +882 921 0.996953818792471 -0.00456997923951706 0.0778601212743627 -0.0179340904906327 -0.00553257639608396 0.991623368250901 0.12904451223186 -0.0278328457463118 -0.0777976464523805 -0.129082186332923 0.988577420022318 0.0012601543799163 3.67656121302514e-05 -4.46664635807207e-05 8.70599588917333e-07 -1.97186565716529e-05 -1.15310772204414e-05 7.59594336475581e-06 -4.46664635807207e-05 0.000100953003630207 3.49104130301548e-06 5.66869279016892e-05 2.60864750074181e-05 7.03500057898325e-07 8.70599588917333e-07 3.49104130301548e-06 8.91480560745634e-06 4.70692165089426e-06 4.62558407249963e-06 1.50020143872729e-06 -1.97186565716529e-05 5.66869279016892e-05 4.70692165089426e-06 7.21197216312051e-05 1.76843141564237e-05 9.45001965999188e-06 -1.15310772204414e-05 2.60864750074181e-05 4.62558407249963e-06 1.76843141564237e-05 2.90475019265564e-05 6.88289391325618e-06 7.59594336475581e-06 7.03500057898325e-07 1.50020143872729e-06 9.45001965999188e-06 6.88289391325618e-06 2.94514413762508e-05 843 841 0 22 0 839 851 0 35 0 0 0 0 0 0 3 17 0 2453 0 0 0 0 0 2198 +882 927 0.996391800284105 -0.00453171448739537 0.0847516601041258 -0.0141463335665013 -0.00664761813615015 0.991338817047639 0.13116081346082 -0.0246624279926651 -0.0846119938289866 -0.131250955723731 0.987731743502197 0.00167431174274016 4.14155526438091e-05 -5.12318306425945e-05 -3.2482345742853e-06 -2.13187222636386e-05 -7.34212201944377e-06 -3.9185024183098e-06 -5.12318306425945e-05 9.79992564840824e-05 7.55452032491299e-06 4.19680530212237e-05 1.40615817452321e-05 2.48658333468339e-05 -3.2482345742853e-06 7.55452032491299e-06 1.02743477845479e-05 2.58060910405989e-06 4.44028020941781e-06 1.32451222272416e-06 -2.13187222636386e-05 4.19680530212237e-05 2.58060910405989e-06 5.81501867636366e-05 1.00227919880804e-05 2.33746261977809e-05 -7.34212201944377e-06 1.40615817452321e-05 4.44028020941781e-06 1.00227919880804e-05 2.45293377337075e-05 1.18372660954756e-05 -3.9185024183098e-06 2.48658333468339e-05 1.32451222272416e-06 2.33746261977809e-05 1.18372660954756e-05 4.62956437931653e-05 847 851 0 13 0 847 858 0 22 0 0 0 0 0 0 6 16 0 2547 0 0 0 0 0 1680 +882 926 0.996803932610465 -0.00442603541887913 0.0797642159290879 -0.0185470798197076 -0.00594364222927707 0.991587813492027 0.129299192770684 -0.0267823894934001 -0.0796655072748658 -0.129360033799358 0.988392325246441 0.000763722282459145 3.58575979461836e-05 -4.4270332884983e-05 -1.19462782553008e-06 -2.2329876403676e-05 -1.02296866060735e-05 1.96714372117753e-06 -4.4270332884983e-05 8.65741701285523e-05 5.25302619481778e-06 4.62116595767189e-05 2.01360069079702e-05 1.18406974053794e-05 -1.19462782553008e-06 5.25302619481778e-06 9.56237100275011e-06 4.04052630303013e-06 4.36398315748997e-06 2.10070910604212e-06 -2.2329876403676e-05 4.62116595767189e-05 4.04052630303013e-06 6.62184264962911e-05 1.42361553773104e-05 2.06135508929111e-05 -1.02296866060735e-05 2.01360069079702e-05 4.36398315748997e-06 1.42361553773104e-05 2.745945833231e-05 9.27093125115381e-06 1.96714372117753e-06 1.18406974053794e-05 2.10070910604212e-06 2.06135508929111e-05 9.27093125115381e-06 3.64036067650249e-05 858 862 0 15 0 858 870 0 25 0 0 0 0 0 0 5 15 0 2551 0 0 0 0 0 1724 +882 914 0.997592110055824 -0.00369390417992961 0.0692555920217177 -0.0218301361555899 -0.00532762965294148 0.991548342569827 0.129628317544085 -0.0268817776670101 -0.0691491020668397 -0.129685154967477 0.989141123533144 0.00203271701956091 3.72360735817606e-05 -3.59607485279778e-05 -1.3890152380744e-06 -7.62701444175845e-06 -4.54656164075439e-06 4.65105377852827e-06 -3.59607485279778e-05 7.18525075232878e-05 5.82090263035458e-06 2.06382214110047e-05 9.35574068746485e-06 7.6867791165909e-06 -1.3890152380744e-06 5.82090263035458e-06 1.00920897889487e-05 3.80357497564821e-08 4.62845641028775e-06 6.26933685607598e-07 -7.62701444175845e-06 2.06382214110047e-05 3.80357497564821e-08 5.11724296648325e-05 5.15429435985158e-06 1.39842893309908e-05 -4.54656164075439e-06 9.35574068746485e-06 4.62845641028775e-06 5.15429435985158e-06 2.25682094320214e-05 7.30011126947103e-06 4.65105377852827e-06 7.6867791165909e-06 6.26933685607598e-07 1.39842893309908e-05 7.30011126947103e-06 3.9066273552273e-05 907 912 0 18 0 907 920 0 28 0 0 0 0 0 0 6 17 0 2605 0 0 0 0 0 1866 +882 922 0.996798844073308 -0.00467227991287064 0.0798137472778518 -0.0161865425155998 -0.00576356954725278 0.991494168949813 0.130023437135748 -0.0257037290296443 -0.0797423709215558 -0.130067223922615 0.988293312504376 0.000460616658976434 5.41373352298847e-05 -6.27044958943789e-05 -2.75109851318811e-06 -1.98692431937912e-05 -1.49803781449527e-05 -3.39000865785331e-06 -6.27044958943789e-05 0.000104794267298208 7.02852414309592e-06 3.79774300293059e-05 2.62929148582838e-05 8.80722652551614e-06 -2.75109851318811e-06 7.02852414309592e-06 1.04613020563433e-05 -5.83714730746268e-07 4.95142124167868e-06 -1.39451130740695e-06 -1.98692431937912e-05 3.79774300293059e-05 -5.83714730746268e-07 6.02074225390456e-05 1.3839479096938e-05 1.16544068639451e-05 -1.49803781449527e-05 2.62929148582838e-05 4.95142124167868e-06 1.3839479096938e-05 3.1682019784603e-05 6.53363129400696e-06 -3.39000865785331e-06 8.80722652551614e-06 -1.39451130740695e-06 1.16544068639451e-05 6.53363129400696e-06 3.66962823757291e-05 868 868 0 15 0 866 877 0 27 0 0 0 0 0 0 4 17 0 2584 0 0 0 0 0 1592 +882 918 0.996551523858874 -0.0048327952180786 0.0828354053828158 -0.0165498792858818 -0.00603785896427618 0.991432454885771 0.130480771220521 -0.0285488735960165 -0.0827562961573488 -0.130530959889041 0.98798434398363 0.00394044361674401 3.43273044403769e-05 -3.45805777182442e-05 -1.61064934571792e-06 -1.0355000511466e-05 -5.49439747309313e-06 6.00651302471339e-06 -3.45805777182442e-05 6.8187180602045e-05 4.73239755242428e-06 2.50355833095723e-05 9.16593530094034e-06 1.02684578824411e-05 -1.61064934571792e-06 4.73239755242428e-06 9.28811726317478e-06 1.8267398998638e-06 2.40443278274227e-06 -1.22554891219791e-07 -1.0355000511466e-05 2.50355833095723e-05 1.8267398998638e-06 4.75955376665902e-05 3.42217138600243e-06 1.19552796546372e-05 -5.49439747309313e-06 9.16593530094034e-06 2.40443278274227e-06 3.42217138600243e-06 2.70692519627661e-05 4.66401712465938e-06 6.00651302471339e-06 1.02684578824411e-05 -1.22554891219791e-07 1.19552796546372e-05 4.66401712465938e-06 3.3472219641881e-05 854 858 0 18 0 854 865 0 28 0 0 0 0 0 0 4 14 0 2320 0 0 0 0 0 1860 +882 917 0.99648747081817 -0.00417230921410186 0.0836379838245067 -0.0122861371317168 -0.00679802903389458 0.991431372431008 0.130451602369696 -0.0237676426655727 -0.0834656055130546 -0.130561960751932 0.987920577324387 0.00189151210733838 3.69006562198134e-05 -3.41308693022165e-05 -9.50424571673096e-07 -1.02676402765392e-05 -8.90259371136752e-06 4.11844646493131e-06 -3.41308693022165e-05 4.9752235980105e-05 3.0039386387906e-06 1.25523830653926e-05 5.88357780035147e-06 7.58711156361252e-06 -9.50424571673096e-07 3.0039386387906e-06 1.00799427788297e-05 -1.11302490762564e-06 2.14881764102233e-06 5.91239560938816e-07 -1.02676402765392e-05 1.25523830653926e-05 -1.11302490762564e-06 5.74064939381871e-05 1.46723038883643e-05 1.49041988733859e-05 -8.90259371136752e-06 5.88357780035147e-06 2.14881764102233e-06 1.46723038883643e-05 3.32632537759315e-05 4.49050102247543e-06 4.11844646493131e-06 7.58711156361252e-06 5.91239560938816e-07 1.49041988733859e-05 4.49050102247543e-06 3.73748227278267e-05 863 865 0 18 0 863 874 0 30 0 0 0 0 0 0 5 17 0 2255 0 0 0 0 0 1703 +882 912 0.996799028356984 -0.00429553532370273 0.0798326088942059 -0.0130823542707134 -0.00614789061894189 0.991480292276317 0.130111619268254 -0.0254155530970509 -0.079711357456199 -0.130185937811856 0.988280183494811 -0.000693760008543501 3.06016796786018e-05 -2.7498686989536e-05 3.58546935837756e-07 -1.20335437664082e-05 -9.10695339309136e-06 4.98399647616528e-06 -2.7498686989536e-05 4.25483474121168e-05 5.41823159152678e-07 1.72187588266824e-05 1.06070415608198e-05 -3.87315206284549e-07 3.58546935837756e-07 5.41823159152678e-07 8.69813355521093e-06 1.87504236111977e-06 2.0769154508191e-06 5.48442309817861e-07 -1.20335437664082e-05 1.72187588266824e-05 1.87504236111977e-06 5.12375152508165e-05 9.97792577749674e-06 3.43414232323366e-06 -9.10695339309136e-06 1.06070415608198e-05 2.0769154508191e-06 9.97792577749674e-06 2.98320335358446e-05 4.85480100741014e-06 4.98399647616528e-06 -3.87315206284549e-07 5.48442309817861e-07 3.43414232323366e-06 4.85480100741014e-06 2.78917367986299e-05 873 877 0 15 0 873 884 0 27 0 0 0 0 0 0 5 16 0 2534 0 0 0 0 0 2213 +882 923 0.996787121118021 -0.00453352900837944 0.0799680079030236 -0.015626857792768 -0.00576288291621139 0.991750015003808 0.128057396976671 -0.0278776988105209 -0.0798888249615796 -0.128106810336832 0.988537516127527 0.00220407972171547 3.6456825195756e-05 -3.79290180639231e-05 7.45091608482991e-07 -9.76986966720363e-06 -6.7140482122217e-06 3.29949160808903e-06 -3.79290180639231e-05 6.93951656800689e-05 4.04168564090873e-06 2.04256835276474e-05 1.04618002112868e-05 6.67561994723075e-06 7.45091608482991e-07 4.04168564090873e-06 1.07621172080821e-05 1.6146167929377e-06 5.06251315781398e-06 2.03382655988426e-06 -9.76986966720363e-06 2.04256835276474e-05 1.6146167929377e-06 4.15120493960066e-05 5.37027000638018e-09 8.49827159969621e-06 -6.7140482122217e-06 1.04618002112868e-05 5.06251315781398e-06 5.37027000638018e-09 2.64482105202132e-05 2.94408388005452e-06 3.29949160808903e-06 6.67561994723075e-06 2.03382655988426e-06 8.49827159969621e-06 2.94408388005452e-06 3.25730918459506e-05 861 866 0 19 0 861 874 0 30 0 0 0 0 0 0 6 18 0 2487 0 0 0 0 0 1609 +882 916 0.996217904588087 -0.00481568252421676 0.0867565316270067 -0.0128344069303485 -0.00667932839529842 0.991264290290007 0.13172127150934 -0.0236006554784152 -0.0866329795765425 -0.131802564457887 0.98748306864068 0.00341239004998618 5.1578646502814e-05 -5.85601294588394e-05 -3.31587128481828e-06 -1.61858422901586e-05 -1.48273077865239e-05 -1.31075152170851e-06 -5.85601294588394e-05 0.000113430343607445 8.48419484292428e-06 4.94660229468204e-05 2.22659403775523e-05 1.88446242975291e-05 -3.31587128481828e-06 8.48419484292428e-06 1.10896721358347e-05 5.27717397765517e-07 3.56460625996705e-06 7.10001957915411e-07 -1.61858422901586e-05 4.94660229468204e-05 5.27717397765517e-07 7.30239250195839e-05 1.84610717713508e-05 2.2761948111609e-05 -1.48273077865239e-05 2.22659403775523e-05 3.56460625996705e-06 1.84610717713508e-05 3.51218979933772e-05 1.34930888796367e-05 -1.31075152170851e-06 1.88446242975291e-05 7.10001957915411e-07 2.2761948111609e-05 1.34930888796367e-05 4.6962248605398e-05 856 860 0 11 0 856 865 0 18 0 0 0 0 0 0 3 11 0 2428 0 0 0 0 0 1670 +882 928 0.996468043536763 -0.0051124991379357 0.083817066058053 -0.0151484228157794 -0.00586206858868571 0.991474658182594 0.130167731537309 -0.0276068691319964 -0.0837679793350476 -0.130199326166736 0.987942843034885 0.00279369806126098 3.77176807946225e-05 -4.13790844844178e-05 -2.2195245506828e-06 -7.54583585949467e-06 -1.05504254022648e-05 1.37613219702335e-06 -4.13790844844178e-05 6.53452700641737e-05 5.36270163470027e-06 1.5122003724615e-05 1.13607860579835e-05 1.07657476741781e-05 -2.2195245506828e-06 5.36270163470027e-06 1.00606359628309e-05 -4.71554504986846e-08 2.68448505094732e-06 -5.13397507106661e-07 -7.54583585949467e-06 1.5122003724615e-05 -4.71554504986846e-08 4.31724962469562e-05 2.77744630267159e-06 1.14280848730239e-05 -1.05504254022648e-05 1.13607860579835e-05 2.68448505094732e-06 2.77744630267159e-06 2.82178211716936e-05 7.22740040266515e-06 1.37613219702335e-06 1.07657476741781e-05 -5.13397507106661e-07 1.14280848730239e-05 7.22740040266515e-06 3.85862747678465e-05 862 865 0 18 0 861 875 0 31 0 0 0 0 0 0 2 16 0 2512 0 0 0 0 0 1661 +882 915 0.996762621673363 -0.00423356076770449 0.080289183568344 -0.0182934469682949 -0.00625183389639096 0.991507979647178 0.129895499802358 -0.0254288607202601 -0.0801572866792347 -0.129976933565916 0.98827162568447 -0.000536033053032366 3.00739060158638e-05 -3.36785722863154e-05 -1.27091873707502e-06 -6.9746795170599e-06 -2.70384186935268e-06 -6.73050125180013e-07 -3.36785722863154e-05 6.48776219975875e-05 3.28455394613158e-06 2.05138371910158e-05 9.01429806692551e-06 1.08605634140537e-05 -1.27091873707502e-06 3.28455394613158e-06 9.51587013863949e-06 6.97145200984683e-07 2.60435192233805e-06 5.33863224949025e-07 -6.9746795170599e-06 2.05138371910158e-05 6.97145200984683e-07 4.75157005489382e-05 5.0147838528465e-06 1.44194974382574e-05 -2.70384186935268e-06 9.01429806692551e-06 2.60435192233805e-06 5.0147838528465e-06 2.32347197622507e-05 6.09629855093084e-06 -6.73050125180013e-07 1.08605634140537e-05 5.33863224949025e-07 1.44194974382574e-05 6.09629855093084e-06 3.50754267337988e-05 849 851 0 12 0 847 857 0 21 0 0 0 0 0 0 1 11 0 2558 0 0 0 0 0 1701 +882 909 0.996574841595071 -0.00462679674539598 0.0825662028413267 -0.0133662268581668 -0.00628953540754664 0.99130090091581 0.131464693312925 -0.0251676998150016 -0.0824562116769594 -0.13153370896991 0.987876437901271 0.00383328993673861 3.87588825121446e-05 -3.64018710688853e-05 -2.42213683064963e-06 -1.09830312764314e-05 -8.55694442772378e-06 5.88751208729625e-06 -3.64018710688853e-05 4.99451538732148e-05 4.20859798452711e-06 1.37085674466282e-05 1.05477814417418e-05 1.74347061147614e-06 -2.42213683064963e-06 4.20859798452711e-06 9.79110338757644e-06 1.78630089271607e-06 2.73061210200795e-06 5.47169488388355e-08 -1.09830312764314e-05 1.37085674466282e-05 1.78630089271607e-06 4.09052453522196e-05 9.14690646509808e-06 7.67445935387945e-06 -8.55694442772378e-06 1.05477814417418e-05 2.73061210200795e-06 9.14690646509808e-06 2.96379752621817e-05 9.61634309842299e-06 5.88751208729625e-06 1.74347061147614e-06 5.47169488388355e-08 7.67445935387945e-06 9.61634309842299e-06 3.71960082175823e-05 854 854 0 14 0 853 861 0 24 0 0 0 0 0 0 6 17 0 2510 0 0 0 0 0 1889 +882 925 0.996798382947802 -0.00413188891931129 0.0798493033570457 -0.0155483443200676 -0.00632140848324677 0.991465271970739 0.130217718728203 -0.0257544351747512 -0.0797058564186784 -0.130305571523047 0.988264860491669 0.00258687055207427 2.84637481761027e-05 -3.43153412788226e-05 1.0908697578353e-06 -1.05637296473055e-05 -6.3146811790217e-06 5.42385157617468e-06 -3.43153412788226e-05 9.47395196010249e-05 3.61661764133128e-06 3.89961635380837e-05 1.66493267581309e-05 1.26498863070116e-05 1.0908697578353e-06 3.61661764133128e-06 9.30978935618583e-06 2.85706710129266e-06 3.26677139838532e-06 1.26963094066426e-06 -1.05637296473055e-05 3.89961635380837e-05 2.85706710129266e-06 5.63756946683422e-05 9.90329510367208e-06 1.63077014594565e-05 -6.3146811790217e-06 1.66493267581309e-05 3.26677139838532e-06 9.90329510367208e-06 2.9287517614217e-05 7.33342521525916e-06 5.42385157617468e-06 1.26498863070116e-05 1.26963094066426e-06 1.63077014594565e-05 7.33342521525916e-06 3.16987046454492e-05 864 868 0 14 0 864 875 0 23 0 0 0 0 0 0 5 15 0 2479 0 0 0 0 0 2218 +882 911 0.996301977415373 -0.00483063760088106 0.0857848164804651 -0.0114071670354712 -0.00670370574985383 0.991004416417507 0.133661164779513 -0.0218660665215922 -0.0856588006420677 -0.133741958940961 0.987307276531069 0.0030884928370229 4.44052437404313e-05 -5.83722551821398e-05 -1.62109266190685e-06 -2.27443390774389e-05 -1.48484748700606e-05 -3.30538641109126e-06 -5.83722551821398e-05 0.000110697528791416 5.39132804820443e-06 5.24160895464126e-05 3.2295949320209e-05 2.08501437566894e-05 -1.62109266190685e-06 5.39132804820443e-06 8.94241628658731e-06 4.04208747317374e-06 3.35666955035208e-06 -3.47339705347767e-07 -2.27443390774389e-05 5.24160895464126e-05 4.04208747317374e-06 6.75234536492152e-05 2.20828109505125e-05 2.24397904024611e-05 -1.48484748700606e-05 3.2295949320209e-05 3.35666955035208e-06 2.20828109505125e-05 3.06803064785687e-05 1.11596042101854e-05 -3.30538641109126e-06 2.08501437566894e-05 -3.47339705347767e-07 2.24397904024611e-05 1.11596042101854e-05 4.09294121899564e-05 859 862 0 13 0 859 870 0 24 0 0 0 0 0 0 4 16 0 2599 0 0 0 0 0 1929 +882 908 0.997074389290641 -0.00403971389730869 0.076330484947517 -0.0173925167741667 -0.00575519508236151 0.991800284393589 0.12766782525899 -0.0280659971971112 -0.0762203381667858 -0.127733615733776 0.988875413518466 0.00263084775340408 3.5534281436021e-05 -4.0161049181929e-05 3.35536252405238e-06 -2.22183835764292e-05 -1.01783104577204e-05 1.47655395617391e-06 -4.0161049181929e-05 7.13041743442051e-05 -7.46280014711294e-07 4.35738407660725e-05 1.50284411457108e-05 7.32711296100601e-06 3.35536252405238e-06 -7.46280014711294e-07 1.03121956688405e-05 -2.49219832916055e-06 3.2978071948833e-06 7.5080424427087e-07 -2.22183835764292e-05 4.35738407660725e-05 -2.49219832916055e-06 8.20654731975864e-05 1.70696564947602e-05 1.80234291826538e-05 -1.01783104577204e-05 1.50284411457108e-05 3.2978071948833e-06 1.70696564947602e-05 3.19121449486848e-05 8.10156600226281e-06 1.47655395617391e-06 7.32711296100601e-06 7.5080424427087e-07 1.80234291826538e-05 8.10156600226281e-06 3.09514272238606e-05 887 886 0 21 0 884 894 0 32 0 0 0 0 0 0 4 17 0 2590 0 0 0 0 0 1599 +882 910 0.996657501905536 -0.00419186548619435 0.0815858575928572 -0.0111520038924874 -0.00679744459106052 0.990964302046874 0.133953524835234 -0.0245927844737632 -0.0814101875839123 -0.134060360780127 0.987623511782225 0.00183985718077814 4.24260964954878e-05 -4.63200863087116e-05 -1.37657603761895e-06 -1.40755644805744e-05 -1.38150414621557e-05 4.54013013196522e-06 -4.63200863087116e-05 7.59095485646039e-05 3.73524102840303e-06 3.57841426256533e-05 2.30355013685797e-05 6.40855307727116e-06 -1.37657603761895e-06 3.73524102840303e-06 9.87376374949603e-06 1.05905344768777e-06 4.96268321319757e-06 8.41921108457329e-07 -1.40755644805744e-05 3.57841426256533e-05 1.05905344768777e-06 5.95009669704476e-05 1.0635577471314e-05 1.29922681394838e-05 -1.38150414621557e-05 2.30355013685797e-05 4.96268321319757e-06 1.0635577471314e-05 3.24855257148678e-05 7.65911146191343e-06 4.54013013196522e-06 6.40855307727116e-06 8.41921108457329e-07 1.29922681394838e-05 7.65911146191343e-06 4.14346343783445e-05 892 896 0 15 0 892 904 0 26 0 0 0 0 0 0 5 16 0 2583 0 0 0 0 0 1932 +883 887 0.99992633532324 -0.000114943620994875 0.0121371625596602 -0.00846609800411383 -0.000199417747770085 0.999664613576401 0.0258963432883171 -0.00586804436706944 -0.0121360685395848 -0.0258968560081814 0.999590950683976 -0.00147408517556003 4.03745169089565e-05 -6.04034854176884e-05 2.5056890042624e-06 -3.98606391737894e-05 -2.18348882115749e-05 2.16575694594102e-05 -6.04034854176884e-05 0.000130054620349681 -2.74329067989534e-06 0.000112246893636017 6.04254522914465e-05 -2.92021884501833e-05 2.5056890042624e-06 -2.74329067989534e-06 8.24448041549936e-06 -3.89754112240097e-07 1.90405326075897e-06 -4.17561058731964e-07 -3.98606391737894e-05 0.000112246893636017 -3.89754112240097e-07 0.000158811548876062 7.06909278826883e-05 -1.62053760932896e-05 -2.18348882115749e-05 6.04254522914465e-05 1.90405326075897e-06 7.06909278826883e-05 5.39068272427686e-05 -9.23935800467174e-06 2.16575694594102e-05 -2.92021884501833e-05 -4.17561058731964e-07 -1.62053760932896e-05 -9.23935800467174e-06 3.6528098257421e-05 859 857 0 10 0 852 865 0 19 0 0 0 0 0 0 3 16 0 2306 0 0 0 0 0 2667 +883 921 0.997154260555688 -0.00437747114275547 0.0752610018670611 -0.0193363520739657 -0.00538237533881037 0.991631322946741 0.128989725895546 -0.0272246124523085 -0.0751958156505506 -0.129027737705078 0.988785837384091 0.00229171140004267 2.20271210607804e-05 -2.04173018722312e-05 2.94359106868717e-06 -7.13532228866243e-06 -2.22456150955428e-06 3.33668099148197e-07 -2.04173018722312e-05 4.07571309913722e-05 9.70961841344658e-07 1.01923077960094e-05 6.09421893221029e-06 3.05290868448559e-06 2.94359106868717e-06 9.70961841344658e-07 9.35568718551302e-06 -2.36778666883258e-07 2.3802893926725e-06 2.27710347499567e-06 -7.13532228866243e-06 1.01923077960094e-05 -2.36778666883258e-07 4.52561078595104e-05 1.05391620403822e-05 5.19422727179445e-06 -2.22456150955428e-06 6.09421893221029e-06 2.3802893926725e-06 1.05391620403822e-05 2.38755789412342e-05 4.70893018343162e-06 3.33668099148197e-07 3.05290868448559e-06 2.27710347499567e-06 5.19422727179445e-06 4.70893018343162e-06 2.21366595220539e-05 883 879 0 23 0 875 888 0 35 0 0 0 0 0 0 2 13 0 2448 0 0 0 0 0 1939 +883 913 0.996620069123862 -0.00463269405211261 0.0820181441229153 -0.0148422746487608 -0.00604606192848969 0.991564346667807 0.129474289155812 -0.0248575378978109 -0.0819260822614182 -0.129532561786856 0.988184918161692 0.00169684422624482 2.05107517622986e-05 -1.91039793862497e-05 2.19292231640249e-06 -3.85549685231543e-06 -2.21865038369962e-06 5.0199282103272e-06 -1.91039793862497e-05 4.19889441606652e-05 5.30234279436787e-07 1.40028065411568e-05 4.22679413714903e-06 -6.09460936820981e-07 2.19292231640249e-06 5.30234279436787e-07 8.25210712447507e-06 2.06190473165809e-06 2.99377561688838e-06 1.47016017550774e-06 -3.85549685231543e-06 1.40028065411568e-05 2.06190473165809e-06 4.0275374391522e-05 3.47749621133101e-06 4.85123550411997e-06 -2.21865038369962e-06 4.22679413714903e-06 2.99377561688838e-06 3.47749621133101e-06 2.44635941629364e-05 9.58671245033919e-07 5.0199282103272e-06 -6.09460936820981e-07 1.47016017550774e-06 4.85123550411997e-06 9.58671245033919e-07 2.19071809092335e-05 905 904 0 19 0 901 911 0 31 0 0 0 0 0 0 3 15 0 2464 0 0 0 0 0 1876 +882 924 0.996579344093461 -0.00492474024756673 0.0824945929121414 -0.0155773936307108 -0.00572839571500078 0.991705310731937 0.128404681178704 -0.0282372730388568 -0.0824426855990165 -0.128438014620152 0.988284817242305 0.00172085006064947 4.40585710242814e-05 -4.29648353488163e-05 -3.42572140950869e-06 -1.00741882315973e-05 -7.66577218012525e-06 -1.37651703119738e-06 -4.29648353488163e-05 7.78238966859163e-05 8.03230593358344e-06 2.33690113871287e-05 1.13490893323062e-05 1.20942943656978e-05 -3.42572140950869e-06 8.03230593358344e-06 1.02434528357625e-05 1.82057863533564e-06 3.68293645055344e-06 4.12655026372787e-07 -1.00741882315973e-05 2.33690113871287e-05 1.82057863533564e-06 5.28210112952272e-05 4.81881228311425e-06 1.53974454134142e-05 -7.66577218012525e-06 1.13490893323062e-05 3.68293645055344e-06 4.81881228311425e-06 2.69034746025013e-05 4.40004248844696e-06 -1.37651703119738e-06 1.20942943656978e-05 4.12655026372787e-07 1.53974454134142e-05 4.40004248844696e-06 3.92833556876923e-05 839 838 0 19 0 837 842 0 27 0 0 0 0 0 0 4 14 0 2576 0 0 0 0 0 1737 +883 919 0.997331921468422 -0.00398565398033159 0.0728913779706168 -0.0232813926999171 -0.00535895239021214 0.991816961616413 0.12755546354142 -0.0271727349099463 -0.0728032969678276 -0.127605756971761 0.989149357143944 0.00265044466470501 4.87953466617895e-05 -5.14552302001365e-05 -5.3898692297391e-06 -1.87468934083483e-05 -1.26721142632858e-05 -5.93368470325222e-06 -5.14552302001365e-05 7.96651644399393e-05 6.43491428879513e-06 3.78371843313449e-05 2.14118357853134e-05 2.16231255960847e-05 -5.3898692297391e-06 6.43491428879513e-06 9.8636950913444e-06 3.62737323611773e-06 1.30551299889382e-06 -7.57432525347566e-07 -1.87468934083483e-05 3.78371843313449e-05 3.62737323611773e-06 5.83107096784554e-05 1.60580969847547e-05 2.22186492881602e-05 -1.26721142632858e-05 2.14118357853134e-05 1.30551299889382e-06 1.60580969847547e-05 3.20837252737972e-05 1.10468842216989e-05 -5.93368470325222e-06 2.16231255960847e-05 -7.57432525347566e-07 2.22186492881602e-05 1.10468842216989e-05 4.07830716362829e-05 901 904 0 17 0 900 911 0 24 0 0 0 0 0 0 3 13 0 2331 0 0 0 0 0 1991 +882 929 0.996441705062523 -0.0265692473364108 0.0799875209521299 -0.0214561112851241 0.0145368563382472 0.988968530258796 0.147410738976362 -0.028609093506185 -0.0830217334189786 -0.145723440989199 0.985835721875798 -0.00350754667915854 2.27008224550435e-05 -1.19099584905339e-05 -1.80114182864953e-07 1.80339500336518e-06 -3.89615947343959e-06 4.53863178541442e-06 -1.19099584905339e-05 3.71321019950599e-05 1.6436601849463e-06 7.49488936006236e-06 2.65599499604931e-06 -3.01842931527594e-06 -1.80114182864953e-07 1.6436601849463e-06 8.53840165351114e-06 8.26431695862774e-07 1.53076036146957e-06 -1.36275867733733e-06 1.80339500336518e-06 7.49488936006236e-06 8.26431695862774e-07 3.5202908980788e-05 -4.05063874369463e-06 3.84151453694261e-06 -3.89615947343959e-06 2.65599499604931e-06 1.53076036146957e-06 -4.05063874369463e-06 2.63134832318254e-05 -4.38318815016718e-06 4.53863178541442e-06 -3.01842931527594e-06 -1.36275867733733e-06 3.84151453694261e-06 -4.38318815016718e-06 2.212448928261e-05 870 870 0 0 0 879 881 0 11 0 0 0 0 0 0 31 45 0 2574 0 0 0 0 0 2106 +883 886 0.999961421389036 0.000234403430006551 0.00878070547566582 0.00516260094470775 -0.000306519619841165 0.999966229185182 0.0082125839350974 0.0019409658167395 -0.00877848388624363 -0.0082149585635211 0.999927723726299 -0.00321694318542123 3.20432546979727e-05 -3.61808310338922e-05 7.07631069765096e-06 -2.33380304346709e-05 -1.17060229101476e-05 9.19144057148118e-06 -3.61808310338922e-05 6.21106555052567e-05 -5.62915463842632e-06 3.68362312903255e-05 2.25097818231771e-05 -1.76361830954127e-06 7.07631069765096e-06 -5.62915463842632e-06 9.93192486046327e-06 -4.34792614017918e-06 9.5603428655803e-08 1.93318328935973e-06 -2.33380304346709e-05 3.68362312903255e-05 -4.34792614017918e-06 9.16670727909276e-05 3.858022483327e-05 3.50562569744676e-06 -1.17060229101476e-05 2.25097818231771e-05 9.5603428655803e-08 3.858022483327e-05 4.38088420571104e-05 4.08312335877355e-06 9.19144057148118e-06 -1.76361830954127e-06 1.93318328935973e-06 3.50562569744676e-06 4.08312335877355e-06 3.24566084531841e-05 795 794 0 12 0 794 803 0 23 0 0 0 0 0 0 7 16 0 2123 0 0 0 0 0 2248 +883 885 0.999990201491701 -0.000233209118489004 -0.0044206938475088 -0.00767773398377185 0.000254250729761551 0.999988639603401 0.00475983410490989 -0.00335785847219497 0.00441953358995769 -0.0047609114302727 0.999978900500006 -0.000400056714011018 4.65329286927285e-05 -5.91316072802642e-05 9.60255206312331e-07 -2.46051282788801e-05 -1.8129018052824e-05 1.99751162011462e-05 -5.91316072802642e-05 0.000100838679616631 -3.46064920370559e-06 6.63609569023308e-05 4.01266913451192e-05 -2.08008069721631e-05 9.60255206312331e-07 -3.46064920370559e-06 8.76954408396837e-06 -4.89655524634348e-06 -1.48468903248636e-06 1.33847359057595e-06 -2.46051282788801e-05 6.63609569023308e-05 -4.89655524634348e-06 0.000113878860303214 4.30505769804077e-05 -5.78952221145613e-06 -1.8129018052824e-05 4.01266913451192e-05 -1.48468903248636e-06 4.30505769804077e-05 3.84622198855558e-05 -5.90058406062742e-06 1.99751162011462e-05 -2.08008069721631e-05 1.33847359057595e-06 -5.78952221145613e-06 -5.90058406062742e-06 4.21205662699818e-05 740 737 0 9 0 739 746 0 19 0 0 0 0 0 0 8 18 0 2136 0 0 0 0 0 2472 +883 927 0.997780591209141 -0.00365061488961465 0.0664873282457953 -0.0245300733145265 -0.00494133310282107 0.991683551827706 0.128605273070557 -0.0270182117035459 -0.0664038781510792 -0.128648381432933 0.98946456173083 0.00153025175863463 3.50603209753854e-05 -3.44553326277673e-05 -4.51325100091966e-06 -7.7182772909706e-06 -8.48016818056074e-06 1.33880166774517e-05 -3.44553326277673e-05 5.2353268172677e-05 5.66316310936804e-06 2.33254962875708e-05 1.48703905052448e-05 -7.66424573547887e-06 -4.51325100091966e-06 5.66316310936804e-06 9.01838389589888e-06 9.20263108948901e-07 4.03471869765415e-06 -3.26994792020652e-06 -7.7182772909706e-06 2.33254962875708e-05 9.20263108948901e-07 5.42434017163481e-05 1.42687661363238e-05 1.04690152434403e-05 -8.48016818056074e-06 1.48703905052448e-05 4.03471869765415e-06 1.42687661363238e-05 2.31466909168968e-05 2.81080821714847e-06 1.33880166774517e-05 -7.66424573547887e-06 -3.26994792020652e-06 1.04690152434403e-05 2.81080821714847e-06 2.9159972997576e-05 881 885 0 16 0 879 891 0 26 0 0 0 0 0 0 4 14 0 2549 0 0 0 0 0 1865 +883 914 0.996971915390602 -0.00476285968228261 0.0776164614630283 -0.0205310587760159 -0.00533717566119107 0.991577793693023 0.129402448241282 -0.0254604501626089 -0.0775790853152862 -0.129424859368373 0.988549792018146 0.000814573861851343 3.38477621232696e-05 -3.45181827548466e-05 1.13959501257424e-06 -1.31720217521525e-05 -5.03700966243074e-06 2.30299271188885e-06 -3.45181827548466e-05 5.99113210738766e-05 2.89147277594131e-06 2.07062648822203e-05 9.8948084954293e-06 6.2152290510115e-06 1.13959501257424e-06 2.89147277594131e-06 9.40421575042616e-06 1.25780734652859e-06 2.93257890435667e-06 1.40126803609108e-06 -1.31720217521525e-05 2.07062648822203e-05 1.25780734652859e-06 4.61941209779762e-05 1.13630650969405e-05 1.15748766233643e-05 -5.03700966243074e-06 9.8948084954293e-06 2.93257890435667e-06 1.13630650969405e-05 2.58157292071407e-05 5.79017287006639e-06 2.30299271188885e-06 6.2152290510115e-06 1.40126803609108e-06 1.15748766233643e-05 5.79017287006639e-06 3.11200275839444e-05 909 913 0 21 0 907 919 0 29 0 0 0 0 0 0 4 13 0 2567 0 0 0 0 0 1564 +883 922 0.997332423146459 -0.00434694694135274 0.0728638579345244 -0.0213989567444253 -0.00500490789515132 0.991803464518323 0.127674737776947 -0.0266930528625369 -0.0728216220484997 -0.127698832499519 0.989135996484045 0.000665519583264615 4.10088012637652e-05 -5.37352425565384e-05 -5.74937420104784e-06 -1.7481480986085e-05 -9.99736672670219e-06 -7.28619860199537e-06 -5.37352425565384e-05 9.86419324884985e-05 1.00183558738661e-05 4.73249163685297e-05 2.49192058374926e-05 2.83345963174986e-05 -5.74937420104784e-06 1.00183558738661e-05 9.8829059497751e-06 1.65288406339617e-06 3.40116211428516e-06 1.19248115347171e-06 -1.7481480986085e-05 4.73249163685297e-05 1.65288406339617e-06 7.84274285527055e-05 2.57098750497315e-05 2.78087942759733e-05 -9.99736672670219e-06 2.49192058374926e-05 3.40116211428516e-06 2.57098750497315e-05 3.04529129497577e-05 1.05831883122927e-05 -7.28619860199537e-06 2.83345963174986e-05 1.19248115347171e-06 2.78087942759733e-05 1.05831883122927e-05 4.39635431354247e-05 901 898 0 15 0 892 906 0 29 0 0 0 0 0 0 3 15 0 2594 0 0 0 0 0 1975 +883 926 0.997703648817771 -0.00385165945342483 0.0676209572186123 -0.0240457502204127 -0.00486604316431942 0.991725589832394 0.128283576873707 -0.0276154427800273 -0.0675555383342441 -0.128318039226931 0.989429497260581 0.00202958038158266 3.04303535914879e-05 -3.31462324321601e-05 -5.08264920797796e-07 -1.5737631523986e-05 -1.04693021177063e-05 9.76187837883416e-06 -3.31462324321601e-05 6.00469252177638e-05 2.90961783273404e-06 3.80775561272359e-05 1.91187077842114e-05 -2.77880781671133e-06 -5.08264920797796e-07 2.90961783273404e-06 8.73119015537293e-06 2.58434476265742e-06 4.39411812577337e-06 -1.47777826834573e-07 -1.5737631523986e-05 3.80775561272359e-05 2.58434476265742e-06 6.33668757799935e-05 1.94065999304844e-05 1.05240876813367e-05 -1.04693021177063e-05 1.91187077842114e-05 4.39411812577337e-06 1.94065999304844e-05 2.86244568121861e-05 3.29236080091294e-06 9.76187837883416e-06 -2.77880781671133e-06 -1.47777826834573e-07 1.05240876813367e-05 3.29236080091294e-06 2.96421186318563e-05 893 895 0 16 0 890 902 0 26 0 0 0 0 0 0 5 14 0 2539 0 0 0 0 0 1870 +883 928 0.99786837906784 -0.00376530407670494 0.0651499849710756 -0.0268610971015944 -0.00442934220643561 0.99212401649538 0.12518113604171 -0.0307859512567837 -0.0651082098059816 -0.125202868889993 0.989992506354253 0.000810020817971991 4.46094974273188e-05 -4.7444843699911e-05 -3.57383580094065e-06 -7.65752981325487e-06 -1.01297002031245e-05 2.0184906275023e-06 -4.7444843699911e-05 7.53506103635157e-05 4.57543747993825e-06 3.17522698864382e-05 1.5363589557059e-05 9.96453317555104e-06 -3.57383580094065e-06 4.57543747993825e-06 8.63548431410695e-06 1.82004116791753e-06 3.4450404543721e-06 -9.11855644451648e-07 -7.65752981325487e-06 3.17522698864382e-05 1.82004116791753e-06 5.51595712493068e-05 4.46274818747378e-06 1.74546998107526e-05 -1.01297002031245e-05 1.5363589557059e-05 3.4450404543721e-06 4.46274818747378e-06 2.82490067786434e-05 6.79396948798359e-06 2.0184906275023e-06 9.96453317555104e-06 -9.11855644451648e-07 1.74546998107526e-05 6.79396948798359e-06 4.05625763155566e-05 885 886 0 19 0 879 895 0 33 0 0 0 0 0 0 5 17 0 2522 0 0 0 0 0 1972 +883 918 0.997494049055854 -0.00415696782817998 0.0706281934968863 -0.0236670562363203 -0.00487053723875763 0.991869496654776 0.127165952490468 -0.0302147674398792 -0.0705825755067354 -0.127191278098294 0.989363673686556 0.00315899057284901 5.09404886339751e-05 -5.20150507542233e-05 -6.20962819389139e-06 -1.23343556921696e-05 -1.21299351743158e-05 7.9351960501622e-06 -5.20150507542233e-05 7.95390169974432e-05 7.66995070745576e-06 3.01710737897407e-05 1.98544815265488e-05 8.49811709570962e-06 -6.20962819389139e-06 7.66995070745576e-06 1.0112516464574e-05 4.79761921981295e-07 2.67589479337032e-06 -1.59041971481e-06 -1.23343556921696e-05 3.01710737897407e-05 4.79761921981295e-07 4.97368819537853e-05 9.28847296923051e-06 2.27716578021381e-05 -1.21299351743158e-05 1.98544815265488e-05 2.67589479337032e-06 9.28847296923051e-06 2.85325946985924e-05 7.35113058800604e-06 7.9351960501622e-06 8.49811709570962e-06 -1.59041971481e-06 2.27716578021381e-05 7.35113058800604e-06 4.27168732259622e-05 892 895 0 24 0 890 902 0 31 0 0 0 0 0 0 3 13 0 2322 0 0 0 0 0 1452 +883 917 0.997564850900914 -0.00388310027227928 0.0696368421118704 -0.0221061712724451 -0.0050745970214822 0.99176149441275 0.127997604138743 -0.0269803172633513 -0.0695601661305356 -0.128039289799906 0.989326702134046 0.00127477388710173 4.08274676162018e-05 -4.9649837900626e-05 -1.88687576971428e-06 -2.01017317923072e-05 -1.69388109561271e-05 1.05090275089967e-05 -4.9649837900626e-05 0.000138534043162386 9.03350538508827e-06 6.674870630091e-05 3.25520629527242e-05 3.85243684315671e-06 -1.88687576971428e-06 9.03350538508827e-06 9.93897622034209e-06 2.61489240524459e-06 3.54287944368101e-06 8.04432208931598e-07 -2.01017317923072e-05 6.674870630091e-05 2.61489240524459e-06 8.45623241275374e-05 2.84929731088236e-05 1.08547855114867e-05 -1.69388109561271e-05 3.25520629527242e-05 3.54287944368101e-06 2.84929731088236e-05 4.14936396682351e-05 1.75246693782067e-06 1.05090275089967e-05 3.85243684315671e-06 8.04432208931598e-07 1.08547855114867e-05 1.75246693782067e-06 3.21321055466981e-05 884 884 0 18 0 878 892 0 31 0 0 0 0 0 0 3 15 0 2257 0 0 0 0 0 1875 +883 916 0.997278443806557 -0.00392682708547257 0.073622588570443 -0.0222101030719081 -0.00556172090392239 0.991728324800576 0.128234149308322 -0.0263649194018053 -0.0735171597612339 -0.128294621154914 0.989007440519715 0.00188273871255184 5.22989880682965e-05 -6.52126229149983e-05 -3.61210220189531e-06 -2.69025534040337e-05 -1.30281979822376e-05 -3.32760501518434e-06 -6.52126229149983e-05 0.000108965381938053 5.81765514996619e-06 5.8307292153409e-05 2.50433526726809e-05 2.42833615538509e-05 -3.61210220189531e-06 5.81765514996619e-06 9.22588214873825e-06 1.80325072546046e-06 2.56885130738202e-06 1.27075036787824e-07 -2.69025534040337e-05 5.8307292153409e-05 1.80325072546046e-06 8.16019736140788e-05 2.64998920335432e-05 3.27129272983801e-05 -1.30281979822376e-05 2.50433526726809e-05 2.56885130738202e-06 2.64998920335432e-05 3.28147318649423e-05 1.7843278578791e-05 -3.32760501518434e-06 2.42833615538509e-05 1.27075036787824e-07 3.27129272983801e-05 1.7843278578791e-05 4.30980784253179e-05 892 892 0 12 0 889 899 0 22 0 0 0 0 0 0 5 14 0 2445 0 0 0 0 0 1997 +883 915 0.997474686518418 -0.00379724059406361 0.0709212994723992 -0.0227163190689591 -0.0054206032476934 0.991586872520722 0.129329390723862 -0.0258223820814022 -0.070815724351404 -0.129387229696153 0.989062221488689 0.00224808481236692 3.4492248749485e-05 -3.70009321258177e-05 -2.71578931529258e-06 -1.37559130674934e-05 -1.07675758837359e-05 7.70853224004528e-06 -3.70009321258177e-05 6.93505376696899e-05 5.4183052836954e-06 3.79662407770234e-05 2.26002288954415e-05 -6.17237406425686e-07 -2.71578931529258e-06 5.4183052836954e-06 9.18229394050314e-06 3.63634108468986e-06 4.4102477531247e-06 -4.2951018233711e-07 -1.37559130674934e-05 3.79662407770234e-05 3.63634108468986e-06 5.9564414642349e-05 1.89419595123912e-05 1.05955282905509e-05 -1.07675758837359e-05 2.26002288954415e-05 4.4102477531247e-06 1.89419595123912e-05 3.02242848273189e-05 5.73246571685319e-06 7.70853224004528e-06 -6.17237406425686e-07 -4.2951018233711e-07 1.05955282905509e-05 5.73246571685319e-06 2.66798020229283e-05 888 885 0 13 0 881 891 0 22 0 0 0 0 0 0 4 13 0 2558 0 0 0 0 0 1861 +883 925 0.996604987538276 -0.0046841662415202 0.0821982810066936 -0.014934454251796 -0.00607505887339926 0.991474808591851 0.130156819212202 -0.0240579942218067 -0.0821072011063481 -0.130214294585406 0.988080282675505 0.00437932990949736 3.66897063056153e-05 -3.25888249629797e-05 2.87460024502535e-06 -2.01896989553761e-05 -1.44137447297502e-05 6.53839781949087e-06 -3.25888249629797e-05 4.95041624829931e-05 -7.71141170911779e-07 2.82834562204708e-05 1.7446424535597e-05 -1.52096713909413e-06 2.87460024502535e-06 -7.71141170911779e-07 9.48962000393491e-06 2.14305141643778e-06 3.50082984973841e-06 3.42313015248565e-06 -2.01896989553761e-05 2.82834562204708e-05 2.14305141643778e-06 5.40737093615054e-05 1.66284371219886e-05 8.50799934666688e-06 -1.44137447297502e-05 1.7446424535597e-05 3.50082984973841e-06 1.66284371219886e-05 3.21964381199327e-05 6.55436329370102e-06 6.53839781949087e-06 -1.52096713909413e-06 3.42313015248565e-06 8.50799934666688e-06 6.55436329370102e-06 2.8232838084218e-05 883 886 0 14 0 883 894 0 25 0 0 0 0 0 0 4 14 0 2468 0 0 0 0 0 1985 +883 910 0.997016810079796 -0.0045391664359731 0.0770511283913149 -0.0181030938623707 -0.00553400463231633 0.991496142112716 0.13001836396575 -0.0268670853544362 -0.0769860715391938 -0.130056895794368 0.988513201047561 0.00140774359144127 4.47895500316375e-05 -6.02718908740207e-05 -3.43907037333097e-06 -1.76521338545565e-05 -1.09339538188468e-05 4.5864771536928e-06 -6.02718908740207e-05 0.000151754770302456 1.15755173611223e-05 6.31226809221974e-05 3.03153211724846e-05 1.65352264231807e-05 -3.43907037333097e-06 1.15755173611223e-05 1.10067481223888e-05 2.18696769707395e-06 5.32707187871472e-06 1.26689639812237e-06 -1.76521338545565e-05 6.31226809221974e-05 2.18696769707395e-06 7.20393480935441e-05 1.7954381916028e-05 1.80654205029721e-05 -1.09339538188468e-05 3.03153211724846e-05 5.32707187871472e-06 1.7954381916028e-05 3.14578544658528e-05 8.53694663649998e-06 4.5864771536928e-06 1.65352264231807e-05 1.26689639812237e-06 1.80654205029721e-05 8.53694663649998e-06 3.75586463502586e-05 898 901 0 18 0 897 907 0 25 0 0 0 0 0 0 4 12 0 2560 0 0 0 0 0 1557 +883 909 0.997778963866246 -0.00410617521519607 0.066485175724393 -0.0239906582846531 -0.00432501059418461 0.991998651091395 0.126174365527287 -0.0288764002637809 -0.0664712986886934 -0.126181676791662 0.989777626991378 0.00139350872219387 4.89929427211969e-05 -5.27722450809702e-05 -3.1887803433561e-06 -1.23595441819704e-05 -1.53443710087384e-05 5.04758904241727e-06 -5.27722450809702e-05 8.21232976067623e-05 5.97883968380038e-06 3.00339376764147e-05 2.16694413403626e-05 6.96163377414404e-06 -3.1887803433561e-06 5.97883968380038e-06 9.92458355882469e-06 9.44384782424361e-07 4.36372513913952e-06 6.67255962738828e-07 -1.23595441819704e-05 3.00339376764147e-05 9.44384782424361e-07 5.9009646182938e-05 1.45552107329998e-05 1.74915488416885e-05 -1.53443710087384e-05 2.16694413403626e-05 4.36372513913952e-06 1.45552107329998e-05 3.49668740437725e-05 6.29312569148069e-06 5.04758904241727e-06 6.96163377414404e-06 6.67255962738828e-07 1.74915488416885e-05 6.29312569148069e-06 3.47788299580253e-05 878 880 0 20 0 872 884 0 31 0 0 0 0 0 0 3 13 0 2489 0 0 0 0 0 1313 +883 923 0.996692801842704 -0.00474432983983542 0.0811230552266818 -0.0168181775269539 -0.00569444712666381 0.991762414856531 0.127964392507698 -0.0267423069864447 -0.0810619024379644 -0.128003139853339 0.988455443690217 0.00294872479789468 3.70650253707885e-05 -4.37237304287852e-05 -3.24194926351931e-07 -1.68816142253914e-05 -1.26938775623988e-05 1.8415452743246e-06 -4.37237304287852e-05 7.35739323579937e-05 2.8567799619132e-06 3.49234905983528e-05 2.1628986357987e-05 1.08633858351728e-05 -3.24194926351931e-07 2.8567799619132e-06 9.15760739538399e-06 2.89852129624591e-06 4.15508718649046e-06 2.39437962675977e-06 -1.68816142253914e-05 3.49234905983528e-05 2.89852129624591e-06 5.29608087576483e-05 1.26093253247085e-05 1.62704419573768e-05 -1.26938775623988e-05 2.1628986357987e-05 4.15508718649046e-06 1.26093253247085e-05 2.99932689391278e-05 7.92186920618506e-06 1.8415452743246e-06 1.08633858351728e-05 2.39437962675977e-06 1.62704419573768e-05 7.92186920618506e-06 3.7176396851894e-05 898 902 0 21 0 898 908 0 30 0 0 0 0 0 0 4 14 0 2458 0 0 0 0 0 1587 +883 929 0.995984600191968 -0.027183102236717 0.085298037100709 -0.0175347920338281 0.0143546562544233 0.988950426544527 0.147549983670671 -0.026870440656091 -0.0883663964653029 -0.145733087492807 0.985369599280164 -0.00267879240804733 4.42906527523206e-05 -4.23751254826709e-05 -7.12429436827169e-06 -7.88331439008571e-06 -1.31441135128105e-05 4.47458515685406e-06 -4.23751254826709e-05 6.3020722311082e-05 8.14670974211045e-06 2.16161036548115e-05 1.47703811994134e-05 4.32440913896031e-06 -7.12429436827169e-06 8.14670974211045e-06 1.02953629503491e-05 -7.68359708466972e-07 2.23741241519289e-06 -4.33600648034136e-06 -7.88331439008571e-06 2.16161036548115e-05 -7.68359708466972e-07 5.76709445055285e-05 9.21172867404193e-06 1.26010988062573e-05 -1.31441135128105e-05 1.47703811994134e-05 2.23741241519289e-06 9.21172867404193e-06 3.21658289651727e-05 6.02657346064429e-06 4.47458515685406e-06 4.32440913896031e-06 -4.33600648034136e-06 1.26010988062573e-05 6.02657346064429e-06 3.72491867281408e-05 868 868 0 1 0 875 876 0 9 0 0 0 0 0 0 25 38 0 2550 0 0 0 0 0 1372 +883 912 0.997211083230373 -0.00408736962555155 0.0745207950309892 -0.0171079003385479 -0.00562688045149517 0.991539720595228 0.129681612799667 -0.0252527673687124 -0.0744203849687112 -0.129739261179808 0.988751399700464 0.00358524541902423 4.7819619112766e-05 -5.65401345061604e-05 -4.61792830857773e-06 -1.91213463464508e-05 -1.78388518434234e-05 9.63817870067986e-06 -5.65401345061604e-05 9.20102440860634e-05 7.14668525280369e-06 4.34662060153556e-05 2.988308550129e-05 -2.34066609516163e-06 -4.61792830857773e-06 7.14668525280369e-06 9.50437831059753e-06 1.58741221899049e-06 5.15939832545771e-06 -1.904630176968e-06 -1.91213463464508e-05 4.34662060153556e-05 1.58741221899049e-06 6.80393925007486e-05 1.90892553364357e-05 1.36448678072166e-05 -1.78388518434234e-05 2.988308550129e-05 5.15939832545771e-06 1.90892553364357e-05 3.44073158476329e-05 4.89759431271333e-06 9.63817870067986e-06 -2.34066609516163e-06 -1.904630176968e-06 1.36448678072166e-05 4.89759431271333e-06 3.36896800324197e-05 885 888 0 18 0 882 893 0 29 0 0 0 0 0 0 6 14 0 2517 0 0 0 0 0 1988 +884 888 0.999429475056185 -0.000981127359196484 0.0337603580849503 -0.00926718782989452 -0.00103379930282829 0.998220966164401 0.0596140417083949 -0.0106064697399522 -0.0337587862329276 -0.0596149318452501 0.997650441914985 0.00199858069876176 3.82457671276927e-05 -5.69306191879975e-05 9.38378983925749e-08 -2.88376966104402e-05 -1.72541418110961e-05 1.75255147464892e-05 -5.69306191879975e-05 0.000123169130028286 1.94914703026337e-06 8.28048426854503e-05 4.92869893212937e-05 -1.94995550672568e-05 9.38378983925749e-08 1.94914703026337e-06 9.27717790653446e-06 2.59683729702186e-07 2.52300595708711e-06 -2.56274120984421e-06 -2.88376966104402e-05 8.28048426854503e-05 2.59683729702186e-07 0.000118981706731383 4.98759070209666e-05 4.42116450357907e-06 -1.72541418110961e-05 4.92869893212937e-05 2.52300595708711e-06 4.98759070209666e-05 4.55791869062915e-05 -1.7845963528615e-06 1.75255147464892e-05 -1.94995550672568e-05 -2.56274120984421e-06 4.42116450357907e-06 -1.7845963528615e-06 3.49562895357886e-05 899 901 0 19 0 896 906 0 28 0 0 0 0 0 0 6 16 0 2443 0 0 0 0 0 1762 +883 911 0.997365556255921 -0.0041647237853986 0.0724196262770599 -0.0207839314125795 -0.00524484234329713 0.991597238612345 0.129257139087816 -0.0252967769158658 -0.0723494217192622 -0.129296447948752 0.988963088150778 0.000399356038205794 5.62083023788039e-05 -6.18231917060197e-05 -2.46688353504193e-06 -3.11816829441291e-05 -2.22226443375125e-05 -2.22145103386537e-06 -6.18231917060197e-05 9.35975244646468e-05 3.80065880302813e-06 5.21545908351314e-05 3.30947887290156e-05 2.09743111692752e-05 -2.46688353504193e-06 3.80065880302813e-06 9.13875926155786e-06 3.61861644654267e-07 2.00365611578921e-06 -5.68263019903461e-07 -3.11816829441291e-05 5.21545908351314e-05 3.61861644654267e-07 7.0116187980288e-05 2.64187599054274e-05 2.63068961727517e-05 -2.22226443375125e-05 3.30947887290156e-05 2.00365611578921e-06 2.64187599054274e-05 3.4889934962668e-05 1.49526625794451e-05 -2.22145103386537e-06 2.09743111692752e-05 -5.68263019903461e-07 2.63068961727517e-05 1.49526625794451e-05 4.72889350157456e-05 899 901 0 19 0 898 911 0 31 0 0 0 0 0 0 2 14 0 2602 0 0 0 0 0 1520 +883 924 0.997172482811282 -0.00434503592545698 0.075021064953712 -0.0182155028167962 -0.00526103913885674 0.991840782330142 0.127374188805702 -0.0281260972068295 -0.0749623971812669 -0.127408724856415 0.989013476065569 0.00232052330794637 3.81492706816542e-05 -4.18978120525337e-05 -3.46832199957495e-07 -1.99908021186158e-05 -1.68401143427145e-05 5.47916786679798e-06 -4.18978120525337e-05 7.75125216039292e-05 3.33246799094027e-06 4.40375044677731e-05 2.5384115452489e-05 5.34251350438895e-06 -3.46832199957495e-07 3.33246799094027e-06 8.89723499125167e-06 2.93937813038297e-06 3.72631968932141e-06 7.36251164922496e-07 -1.99908021186158e-05 4.40375044677731e-05 2.93937813038297e-06 6.93420886104752e-05 2.41321153416123e-05 1.21191002556328e-05 -1.68401143427145e-05 2.5384115452489e-05 3.72631968932141e-06 2.41321153416123e-05 3.68182588016717e-05 6.02785511204275e-06 5.47916786679798e-06 5.34251350438895e-06 7.36251164922496e-07 1.21191002556328e-05 6.02785511204275e-06 2.63025578276047e-05 883 882 0 22 0 877 884 0 28 0 0 0 0 0 0 2 11 0 2549 0 0 0 0 0 1872 +884 913 0.996853304523581 -0.00456687915270403 0.0791367984898344 -0.0173585451715116 -0.00571782380058406 0.991595722354149 0.129248713339589 -0.0238114632516659 -0.0790619741177864 -0.129294497267898 0.988449359969867 -0.000571478739002278 2.9975761541928e-05 -3.89978605345355e-05 1.42215629350951e-07 -1.40441644622894e-05 -8.83268797244345e-06 6.56988501541911e-06 -3.89978605345355e-05 0.000112289632791765 7.54828100146693e-06 4.96274199034474e-05 2.61934874794145e-05 1.80092776730091e-06 1.42215629350951e-07 7.54828100146693e-06 9.16986657574381e-06 2.19580796946211e-06 4.95330200037715e-06 -4.82714815261443e-07 -1.40441644622894e-05 4.96274199034474e-05 2.19580796946211e-06 7.21013010353506e-05 2.44276169825265e-05 1.38473432083587e-05 -8.83268797244345e-06 2.61934874794145e-05 4.95330200037715e-06 2.44276169825265e-05 3.14415290134211e-05 3.21095906761915e-06 6.56988501541911e-06 1.80092776730091e-06 -4.82714815261443e-07 1.38473432083587e-05 3.21095906761915e-06 2.80995460407441e-05 909 913 0 25 0 909 920 0 34 0 0 0 0 0 0 5 19 0 2491 0 0 0 0 0 2128 +884 887 0.999974407134861 -0.000203358388527386 0.00715148380753238 -0.0128286164593714 4.76228674152234e-05 0.999763002073547 0.0217701037423028 -0.0099359282770957 -0.00715421605391404 -0.0217692060088085 0.999737424958374 -0.000693885135402045 3.81750177887207e-05 -4.73609654896859e-05 -1.11325751562046e-06 -2.30099866977539e-05 -1.93532592240839e-05 1.41839092103803e-05 -4.73609654896859e-05 7.90290994044556e-05 4.04836024670756e-07 6.30275830608322e-05 4.07936476665587e-05 -6.9282561712354e-06 -1.11325751562046e-06 4.04836024670756e-07 9.12804885266518e-06 -2.95853687467382e-06 1.70159520711188e-06 -2.45812498449757e-06 -2.30099866977539e-05 6.30275830608322e-05 -2.95853687467382e-06 0.000129619277038332 5.25088234353006e-05 1.75412295058277e-05 -1.93532592240839e-05 4.07936476665587e-05 1.70159520711188e-06 5.25088234353006e-05 4.70662082450929e-05 7.12362896121283e-06 1.41839092103803e-05 -6.9282561712354e-06 -2.45812498449757e-06 1.75412295058277e-05 7.12362896121283e-06 3.71673743446972e-05 861 860 0 10 0 860 873 0 25 0 0 0 0 0 0 11 25 0 2308 0 0 0 0 0 2651 +884 928 0.997696046518468 -0.00396721007053897 0.0677263612316173 -0.0269722849249955 -0.00460787745840751 0.992020862401735 0.125989586970697 -0.0299774356229989 -0.0676857904345336 -0.126011387596418 0.989717012064195 -0.000566175962074937 4.71567534349729e-05 -4.81341790841267e-05 -3.71767012634982e-06 -1.20234867195732e-05 -9.73768536974834e-06 4.42169194455883e-06 -4.81341790841267e-05 6.79261414593499e-05 4.89228763075048e-06 2.53996995303969e-05 1.61793795134232e-05 7.20973454161768e-06 -3.71767012634982e-06 4.89228763075048e-06 1.01738996044354e-05 -9.34053041190269e-07 3.14085207548007e-06 -3.5788800924266e-07 -1.20234867195732e-05 2.53996995303969e-05 -9.34053041190269e-07 5.40751811702668e-05 1.56365216766936e-05 1.43410740237827e-05 -9.73768536974834e-06 1.61793795134232e-05 3.14085207548007e-06 1.56365216766936e-05 2.29026324325637e-05 6.77127051016081e-06 4.42169194455883e-06 7.20973454161768e-06 -3.5788800924266e-07 1.43410740237827e-05 6.77127051016081e-06 3.94419619766596e-05 900 899 0 18 0 899 910 0 33 0 0 0 0 0 0 6 22 0 2528 0 0 0 0 0 2035 +884 886 0.999906462870861 0.000495177026818652 0.013668222590971 0.010328101520671 -0.000611848889858735 0.999963404976327 0.00853313243109777 0.00448353068784225 -0.0136634969908951 -0.00854069715320623 0.999870174243695 -0.00378685597254286 3.80882502901668e-05 -5.08824685038898e-05 6.06377645658076e-06 -2.8015853413849e-05 -1.32558015621201e-05 2.29419343375743e-05 -5.08824685038898e-05 0.000106071245971759 -4.86358805103441e-06 7.22963658485122e-05 4.13176859134927e-05 -2.46013446828402e-05 6.06377645658076e-06 -4.86358805103441e-06 1.0020039699624e-05 -4.5529944161058e-06 -8.5431190474697e-08 2.07932383084623e-06 -2.8015853413849e-05 7.22963658485122e-05 -4.5529944161058e-06 0.000121151275930257 5.07335968420033e-05 -6.39705951027951e-06 -1.32558015621201e-05 4.13176859134927e-05 -8.5431190474697e-08 5.07335968420033e-05 4.38074574421985e-05 -4.6680779626917e-06 2.29419343375743e-05 -2.46013446828402e-05 2.07932383084623e-06 -6.39705951027951e-06 -4.6680779626917e-06 4.31015567769553e-05 800 802 0 17 0 800 810 0 24 0 0 0 0 0 0 7 18 0 2137 0 0 0 0 0 2450 +884 921 0.996969819374032 -0.00448913914392368 0.0776596863698085 -0.0163040586750121 -0.00554218030644412 0.991697385279108 0.128474045114299 -0.025799341400882 -0.0775916457794355 -0.128515149536258 0.988667483456856 0.00217032758046287 5.95970474556472e-05 -7.02740287849013e-05 7.44712565040558e-07 -3.6944871589317e-05 -2.59536643379455e-05 -6.64673793217683e-06 -7.02740287849013e-05 0.000113812914569216 2.15768995326155e-06 6.96406523329275e-05 4.22880626519851e-05 2.78185575351903e-05 7.44712565040558e-07 2.15768995326155e-06 8.75068099334669e-06 3.73125800369269e-06 5.10109022786614e-06 3.42531418717765e-06 -3.6944871589317e-05 6.96406523329275e-05 3.73125800369269e-06 9.16423143981887e-05 3.72602615695844e-05 3.32590360622823e-05 -2.59536643379455e-05 4.22880626519851e-05 5.10109022786614e-06 3.72602615695844e-05 4.07215620978601e-05 1.73014720331562e-05 -6.64673793217683e-06 2.78185575351903e-05 3.42531418717765e-06 3.32590360622823e-05 1.73014720331562e-05 4.66266039399721e-05 884 882 0 27 0 884 890 0 36 0 0 0 0 0 0 5 19 0 2508 0 0 0 0 0 1705 +884 920 0.996510470844182 -0.0050820206007757 0.0833129915710581 -0.0141389573821657 -0.00563068745463079 0.991777981933374 0.127846509185632 -0.0272189135681354 -0.0832777092425949 -0.127869494480806 0.988288528479679 0.00437152641567217 6.65507009240023e-05 -7.25638745731828e-05 -9.40257713963323e-06 -1.64452873233415e-05 -1.77793401165295e-05 -3.4297040013687e-06 -7.25638745731828e-05 0.000131584081919391 1.5402071487161e-05 4.85380781010968e-05 2.91786861029624e-05 2.97341495283349e-05 -9.40257713963323e-06 1.5402071487161e-05 1.28692215808448e-05 -6.40546031670405e-07 4.91017140699222e-06 8.25578089580195e-08 -1.64452873233415e-05 4.85380781010968e-05 -6.40546031670405e-07 7.89030241654206e-05 2.23802123720571e-05 3.18859958277098e-05 -1.77793401165295e-05 2.91786861029624e-05 4.91017140699222e-06 2.23802123720571e-05 3.57612046427729e-05 1.30221492813115e-05 -3.4297040013687e-06 2.97341495283349e-05 8.25578089580195e-08 3.18859958277098e-05 1.30221492813115e-05 4.79453934035809e-05 888 888 0 18 0 887 894 0 26 0 0 0 0 0 0 2 12 0 2340 0 0 0 0 0 1427 +884 916 0.996627396932595 -0.00453435663692352 0.0819345549401999 -0.0160413217819075 -0.00604490086924454 0.9917026938223 0.128410382131175 -0.0246726171453643 -0.0818369773197939 -0.128472591144892 0.988330664538785 0.00253880060423921 4.94084715613017e-05 -5.86185762019738e-05 -3.70813474243677e-06 -2.0716292310679e-05 -1.3706610306728e-05 5.30433122036282e-06 -5.86185762019738e-05 0.000101074860454749 8.04633640558409e-06 4.3658406953248e-05 2.52828287410362e-05 9.48077563420408e-06 -3.70813474243677e-06 8.04633640558409e-06 1.03049742376727e-05 -5.00516442821993e-07 4.10316773169868e-06 -6.93356957769788e-07 -2.0716292310679e-05 4.3658406953248e-05 -5.00516442821993e-07 7.8869110057211e-05 2.26573676511167e-05 2.16813019511063e-05 -1.3706610306728e-05 2.52828287410362e-05 4.10316773169868e-06 2.26573676511167e-05 3.39133604130494e-05 6.90800266772646e-06 5.30433122036282e-06 9.48077563420408e-06 -6.93356957769788e-07 2.16813019511063e-05 6.90800266772646e-06 4.03559793804774e-05 893 893 0 16 0 891 897 0 22 0 0 0 0 0 0 3 12 0 2464 0 0 0 0 0 1559 +884 917 0.997622226260049 -0.00333558774040516 0.0688387066000631 -0.0206421238566306 -0.00533045163466686 0.992101772725432 0.125322220058637 -0.0294615592992575 -0.0687130261108764 -0.125391173570874 0.989724998993763 0.00245682348315742 3.21580334565655e-05 -3.28171738395062e-05 -1.6747382880054e-06 -1.06000405530518e-05 -5.53692639220732e-06 9.34394941034694e-06 -3.28171738395062e-05 5.87478401172975e-05 3.88397185677321e-06 2.49196522002289e-05 7.18811112798677e-06 2.81900902175648e-06 -1.6747382880054e-06 3.88397185677321e-06 9.18660710753327e-06 -1.75316645294203e-06 -7.3177782522949e-08 -1.68245344490382e-06 -1.06000405530518e-05 2.49196522002289e-05 -1.75316645294203e-06 6.63069861754661e-05 1.8850787903073e-05 1.64409193050703e-05 -5.53692639220732e-06 7.18811112798677e-06 -7.3177782522949e-08 1.8850787903073e-05 3.66091425206661e-05 7.80665234648298e-06 9.34394941034694e-06 2.81900902175648e-06 -1.68245344490382e-06 1.64409193050703e-05 7.80665234648298e-06 3.73442119769042e-05 901 900 0 21 0 899 908 0 33 0 0 0 0 0 0 5 18 0 2273 0 0 0 0 0 2137 +884 915 0.99717513907672 -0.00373271266390536 0.0750187234195126 -0.0189467424391941 -0.00594566940888396 0.991707693396493 0.128376399207515 -0.0258528081202146 -0.0748758373749828 -0.128459790262851 0.988884063610603 0.00199959763477129 3.2388837511749e-05 -3.80194784839962e-05 -1.12243288234752e-06 -1.82813618398114e-05 -9.75103242315227e-06 6.66204899314323e-06 -3.80194784839962e-05 7.11681670880241e-05 2.7897116023233e-06 4.57100196265482e-05 2.10298238235877e-05 4.34993111635496e-06 -1.12243288234752e-06 2.7897116023233e-06 8.41871550586797e-06 3.7518629981548e-06 3.4583119448343e-06 4.21205688918156e-07 -1.82813618398114e-05 4.57100196265482e-05 3.7518629981548e-06 6.68726995016029e-05 2.10223294670612e-05 1.58631824607055e-05 -9.75103242315227e-06 2.10298238235877e-05 3.4583119448343e-06 2.10223294670612e-05 2.50822973556784e-05 6.45785406930324e-06 6.66204899314323e-06 4.34993111635496e-06 4.21205688918156e-07 1.58631824607055e-05 6.45785406930324e-06 3.05887604074868e-05 884 881 0 15 0 884 887 0 22 0 0 0 0 0 0 4 14 0 2600 0 0 0 0 0 2119 +884 914 0.996555190065167 -0.00490944791707347 0.0827867771768477 -0.0168225553491354 -0.00591983359380249 0.991488682991394 0.130058244914396 -0.0248356152582141 -0.0827206668517679 -0.130100302924862 0.988044129811244 0.000629084170528017 3.29043358602853e-05 -3.68056876920999e-05 1.35972278846479e-06 -9.58240708716816e-06 -6.03064376538239e-06 5.87066943056885e-06 -3.68056876920999e-05 7.33943898740832e-05 3.34723816194029e-06 1.86898366867497e-05 1.12849967090261e-05 2.70941852656369e-06 1.35972278846479e-06 3.34723816194029e-06 9.2628034954171e-06 -2.03466262876711e-06 3.45325361626562e-06 3.07069662552215e-07 -9.58240708716816e-06 1.86898366867497e-05 -2.03466262876711e-06 5.28181517939514e-05 1.10804461219965e-05 1.82327022361483e-05 -6.03064376538239e-06 1.12849967090261e-05 3.45325361626562e-06 1.10804461219965e-05 2.59058340833354e-05 5.19092134450857e-06 5.87066943056885e-06 2.70941852656369e-06 3.07069662552215e-07 1.82327022361483e-05 5.19092134450857e-06 3.49267068790318e-05 920 923 0 20 0 918 929 0 31 0 0 0 0 0 0 2 13 0 2610 0 0 0 0 0 1472 +884 919 0.996474352057441 -0.00467868652403202 0.0837673897415484 -0.0178285380624208 -0.00622428550514185 0.991569693913526 0.129424883164661 -0.0257635809051618 -0.0836667434626991 -0.129489968741388 0.988044646781562 0.00232375375070023 3.84612534644146e-05 -4.2024362517689e-05 -2.535795909003e-06 -9.05383926240874e-06 -6.71150749144987e-06 7.53805093052627e-06 -4.2024362517689e-05 6.25538550483956e-05 3.456780625772e-06 2.2273783935043e-05 1.36638314144703e-05 2.59959581417249e-06 -2.535795909003e-06 3.456780625772e-06 1.01309451948303e-05 1.82254567288868e-07 1.12898390388437e-06 -1.7831145975297e-06 -9.05383926240874e-06 2.2273783935043e-05 1.82254567288868e-07 5.74005598223801e-05 1.30953183946642e-05 1.86267668421325e-05 -6.71150749144987e-06 1.36638314144703e-05 1.12898390388437e-06 1.30953183946642e-05 2.82768853915786e-05 6.00819724253177e-06 7.53805093052627e-06 2.59959581417249e-06 -1.7831145975297e-06 1.86267668421325e-05 6.00819724253177e-06 3.76060239180288e-05 891 895 0 17 0 891 901 0 27 0 0 0 0 0 0 4 14 0 2350 0 0 0 0 0 1527 +884 922 0.996302927860672 -0.00483124049626963 0.0857737433689293 -0.0122987500131593 -0.00635979907521575 0.991530212117682 0.129720435605138 -0.0235604703371226 -0.0856739685784114 -0.129786353570516 0.98783372767632 0.00218969088901955 3.38618371045022e-05 -3.62198389272956e-05 -1.24246705235507e-06 -1.18409483355517e-05 -7.41085833703912e-06 -7.21971348104968e-07 -3.62198389272956e-05 8.09568039856153e-05 6.72200604956808e-06 3.38578584956699e-05 1.54842232903755e-05 1.62739790815962e-05 -1.24246705235507e-06 6.72200604956808e-06 1.06692452594919e-05 8.21791786603483e-07 3.62492480346189e-06 5.31528736279059e-07 -1.18409483355517e-05 3.38578584956699e-05 8.21791786603483e-07 6.39933015616976e-05 1.6609150137816e-05 2.20830599561783e-05 -7.41085833703912e-06 1.54842232903755e-05 3.62492480346189e-06 1.6609150137816e-05 2.68008248975854e-05 5.82252071534404e-06 -7.21971348104968e-07 1.62739790815962e-05 5.31528736279059e-07 2.20830599561783e-05 5.82252071534404e-06 3.69487452441772e-05 889 890 0 21 0 889 896 0 29 0 0 0 0 0 0 4 17 0 2615 0 0 0 0 0 1494 +884 926 0.9971760268502 -0.00397315992669837 0.0749945696397107 -0.0187839545184047 -0.00570158111996006 0.991712270329037 0.128352112766247 -0.0258377175837262 -0.0748829983906965 -0.128417237468432 0.988889048211676 0.00218211510428399 3.43863782087238e-05 -4.41144491959336e-05 -3.03775926715715e-07 -2.81002761819362e-05 -1.41778314709421e-05 4.11596233010202e-06 -4.41144491959336e-05 8.53135440967254e-05 2.29390995824372e-06 6.40516628624813e-05 2.97117317638551e-05 8.51399094125512e-06 -3.03775926715715e-07 2.29390995824372e-06 8.41760668025118e-06 2.32191099673742e-06 3.86546179158501e-06 6.17512735941424e-07 -2.81002761819362e-05 6.40516628624813e-05 2.32191099673742e-06 8.76032283686831e-05 3.21223048168806e-05 1.66606143065026e-05 -1.41778314709421e-05 2.97117317638551e-05 3.86546179158501e-06 3.21223048168806e-05 3.07303782292947e-05 9.7348996785287e-06 4.11596233010202e-06 8.51399094125512e-06 6.17512735941424e-07 1.66606143065026e-05 9.7348996785287e-06 2.98321679155958e-05 907 908 0 17 0 904 914 0 27 0 0 0 0 0 0 3 14 0 2547 0 0 0 0 0 2126 +884 918 0.996630787268781 -0.0046808905752416 0.0818850604898818 -0.0151727856385237 -0.00575188538823918 0.991923230652802 0.126709195821728 -0.0305105756644873 -0.081816805623842 -0.12675327906895 0.988554306329591 0.0055902240088778 5.05681113420308e-05 -5.75458194376017e-05 -6.52583864448102e-06 -1.68590088383896e-05 -1.27168714366005e-05 -7.76202256930695e-06 -5.75458194376017e-05 8.56404265735684e-05 8.15200985752989e-06 3.54118277950599e-05 1.73834869102344e-05 2.63124789429246e-05 -6.52583864448102e-06 8.15200985752989e-06 1.06322847299753e-05 -8.78606355405828e-07 2.6259637604294e-06 -2.79343583279923e-06 -1.68590088383896e-05 3.54118277950599e-05 -8.78606355405828e-07 5.79776647613825e-05 5.1893388157017e-06 3.65222513313886e-05 -1.27168714366005e-05 1.73834869102344e-05 2.6259637604294e-06 5.1893388157017e-06 3.16865293949043e-05 1.41388301209571e-05 -7.76202256930695e-06 2.63124789429246e-05 -2.79343583279923e-06 3.65222513313886e-05 1.41388301209571e-05 5.84640491291394e-05 887 890 0 23 0 887 897 0 35 0 0 0 0 0 0 5 16 0 2311 0 0 0 0 0 1453 +884 912 0.997036898180638 -0.00410728466856129 0.0768150628391621 -0.0155161656805607 -0.00599111197529589 0.991394300015842 0.130772506565401 -0.0239000736501617 -0.0766911353653895 -0.130845221956133 0.988432090559396 0.00444126410526521 4.66132468285953e-05 -5.30342823807856e-05 -1.63205771743146e-06 -3.16622330814803e-05 -2.09017059100625e-05 4.08588658053531e-07 -5.30342823807856e-05 9.23465597162254e-05 3.98273819078282e-06 6.12566068855176e-05 3.69362505313923e-05 1.6641611541426e-05 -1.63205771743146e-06 3.98273819078282e-06 8.30329536226649e-06 4.2184472160552e-06 4.70366170083842e-06 3.98719772699225e-07 -3.16622330814803e-05 6.12566068855176e-05 4.2184472160552e-06 7.82055179472683e-05 3.40349526524872e-05 2.4229199485222e-05 -2.09017059100625e-05 3.69362505313923e-05 4.70366170083842e-06 3.40349526524872e-05 3.67685742292434e-05 1.29439556095692e-05 4.08588658053531e-07 1.6641611541426e-05 3.98719772699225e-07 2.4229199485222e-05 1.29439556095692e-05 3.35631877962895e-05 896 897 0 18 0 894 904 0 28 0 0 0 0 0 0 5 17 0 2523 0 0 0 0 0 1831 +884 927 0.997133429758056 -0.00415915479603427 0.0755488232225875 -0.0186935869872294 -0.00562566201517372 0.991649012393388 0.128843269696597 -0.0253437123212971 -0.0754537950392569 -0.128898943558905 0.988782982844857 0.00191392362474509 4.07209692677381e-05 -4.4676596532784e-05 -3.80488162056563e-06 -1.42376330229189e-05 -1.16295783890403e-05 1.00599488709833e-05 -4.4676596532784e-05 7.94517978851318e-05 6.22951504496367e-06 4.2750035756763e-05 2.35176132473068e-05 1.62511836436595e-06 -3.80488162056563e-06 6.22951504496367e-06 9.13009053653998e-06 1.41086755806799e-06 4.33720831262287e-06 -1.11563405041795e-06 -1.42376330229189e-05 4.2750035756763e-05 1.41086755806799e-06 7.31067437253216e-05 2.23859243624319e-05 1.70121643893937e-05 -1.16295783890403e-05 2.35176132473068e-05 4.33720831262287e-06 2.23859243624319e-05 2.65864397695585e-05 7.13923867669625e-06 1.00599488709833e-05 1.62511836436595e-06 -1.11563405041795e-06 1.70121643893937e-05 7.13923867669625e-06 3.12044745928278e-05 890 893 0 18 0 889 899 0 26 0 0 0 0 0 0 2 12 0 2592 0 0 0 0 0 2126 +884 923 0.996797772172262 -0.0046368343740958 0.0798291999170864 -0.0180843818534954 -0.00560641120241971 0.991808088625121 0.12761380603686 -0.0262383993864507 -0.079766970268679 -0.127652712876661 0.988606097163771 0.000602003712728201 3.8042288035821e-05 -5.1720456388208e-05 -1.61467932128361e-06 -2.10089870020611e-05 -1.42173463230736e-05 4.45563168777917e-06 -5.1720456388208e-05 0.000120686730239744 6.64406687839903e-06 6.81642908707679e-05 3.5355868429237e-05 1.64493503736582e-05 -1.61467932128361e-06 6.64406687839903e-06 9.57940988864853e-06 1.44426194932868e-06 4.65065090250282e-06 6.34688826377549e-07 -2.10089870020611e-05 6.81642908707679e-05 1.44426194932868e-06 9.60873766065534e-05 3.02447379748794e-05 3.18764800522513e-05 -1.42173463230736e-05 3.5355868429237e-05 4.65065090250282e-06 3.02447379748794e-05 3.22203785731632e-05 8.61111428614715e-06 4.45563168777917e-06 1.64493503736582e-05 6.34688826377549e-07 3.18764800522513e-05 8.61111428614715e-06 4.0008764310163e-05 894 899 0 20 0 894 907 0 32 0 0 0 0 0 0 2 14 0 2482 0 0 0 0 0 1618 +884 925 0.996865664823658 -0.00479888858100306 0.0789671891615271 -0.0188491498934616 -0.00560437385719883 0.991367251497168 0.13099451764337 -0.0226813698433915 -0.0789141133724129 -0.131026498569326 0.988233079482421 0.00312330401052569 2.14713211573598e-05 -2.67445140901669e-05 1.01712174143945e-06 -4.52461537229674e-06 -4.72260667308992e-06 7.42785993731754e-06 -2.67445140901669e-05 7.14893223070376e-05 3.7841038296909e-06 1.99992581637345e-05 1.86806005724846e-05 -1.74072725927672e-06 1.01712174143945e-06 3.7841038296909e-06 9.03850367721479e-06 2.65621335135884e-07 4.9764957951183e-06 1.6973739384598e-07 -4.52461537229674e-06 1.99992581637345e-05 2.65621335135884e-07 4.5872952633051e-05 1.03619334982773e-05 7.58115829352324e-06 -4.72260667308992e-06 1.86806005724846e-05 4.9764957951183e-06 1.03619334982773e-05 2.55601246460724e-05 1.44777610574369e-06 7.42785993731754e-06 -1.74072725927672e-06 1.6973739384598e-07 7.58115829352324e-06 1.44777610574369e-06 2.46940724373426e-05 888 891 0 15 0 887 898 0 25 0 0 0 0 0 0 4 15 0 2485 0 0 0 0 0 1826 +885 887 0.999936274741371 -0.000216613034021074 0.0112871402552874 -0.00681311552739767 -9.83733979648179e-06 0.999798802558499 0.0200587712938389 -0.00510697716539297 -0.0112892143028549 -0.0200576040788845 0.999735087990333 -0.000361670754439455 3.70149398025156e-05 -4.54849112567314e-05 1.24010133550472e-06 -2.13719041734343e-05 -1.48338158280271e-05 8.11616304447587e-06 -4.54849112567314e-05 7.64655922683141e-05 -2.75215915459921e-07 4.28077502106723e-05 3.18557174473603e-05 3.27004321746682e-06 1.24010133550472e-06 -2.75215915459921e-07 8.56000395843362e-06 -1.76693548784067e-06 1.40443379241676e-06 -9.75072425423933e-07 -2.13719041734343e-05 4.28077502106723e-05 -1.76693548784067e-06 8.85875449676659e-05 3.76212568403316e-05 1.74632895898586e-05 -1.48338158280271e-05 3.18557174473603e-05 1.40443379241676e-06 3.76212568403316e-05 3.81554941715868e-05 1.12316521350291e-05 8.11616304447587e-06 3.27004321746682e-06 -9.75072425423933e-07 1.74632895898586e-05 1.12316521350291e-05 3.88741853411081e-05 840 842 0 13 0 837 850 0 23 0 0 0 0 0 0 4 14 0 2306 0 0 0 0 0 2404 +884 929 0.995610483113818 -0.0278774188506687 0.0893454835573404 -0.01868088578616 0.0142508537472365 0.988633452141611 0.149669003050184 -0.0244967419833403 -0.092502319329547 -0.147738779014805 0.984691105928082 -0.00405600070899524 3.92579551305646e-05 -4.6643560654989e-05 -6.11833538764771e-06 -2.98253524426394e-06 -5.28260501873041e-06 9.30710224058064e-06 -4.6643560654989e-05 0.000104100755640782 1.14010561939407e-05 3.9633533775177e-05 1.90995165833698e-05 1.0413770704416e-05 -6.11833538764771e-06 1.14010561939407e-05 1.10358599010721e-05 1.56205544160094e-06 4.76400873941434e-06 -3.44612596326929e-06 -2.98253524426394e-06 3.9633533775177e-05 1.56205544160094e-06 6.77032603372421e-05 9.82232648896829e-06 2.75685923816589e-05 -5.28260501873041e-06 1.90995165833698e-05 4.76400873941434e-06 9.82232648896829e-06 2.15053580026484e-05 1.87931625068921e-06 9.30710224058064e-06 1.0413770704416e-05 -3.44612596326929e-06 2.75685923816589e-05 1.87931625068921e-06 3.99050860884846e-05 888 888 0 1 0 896 899 0 11 0 0 0 0 0 0 31 42 0 2565 0 0 0 0 0 1318 +884 924 0.996717630396796 -0.00455179932349377 0.0808284997950246 -0.0146257705297829 -0.00595772257572923 0.991586742921047 0.129306754676388 -0.0248274347256803 -0.0807370472454021 -0.129363875893341 0.988304870379554 -2.14405157039654e-06 3.35102846716788e-05 -3.4245964988669e-05 -3.06952565968557e-07 -1.12376696504645e-05 -7.08539305965534e-06 1.31060482058612e-05 -3.4245964988669e-05 5.54790290442233e-05 2.58067494854546e-06 2.86060137819218e-05 1.50852957541824e-05 -6.82583391591673e-06 -3.06952565968557e-07 2.58067494854546e-06 9.14133587556898e-06 2.72578561282405e-06 5.11597448584742e-06 1.74841543513554e-07 -1.12376696504645e-05 2.86060137819218e-05 2.72578561282405e-06 5.87644137640894e-05 1.5496949716148e-05 1.02930597259561e-05 -7.08539305965534e-06 1.50852957541824e-05 5.11597448584742e-06 1.5496949716148e-05 2.70061405861404e-05 3.18616335642473e-06 1.31060482058612e-05 -6.82583391591673e-06 1.74841543513554e-07 1.02930597259561e-05 3.18616335642473e-06 2.95201502770649e-05 876 874 0 20 0 876 879 0 29 0 0 0 0 0 0 5 14 0 2559 0 0 0 0 0 2124 +884 910 0.997614214489063 -0.00383924609846658 0.0689285081716133 -0.0219174560575358 -0.00501084878758728 0.991791855488855 0.127764653877359 -0.0282247875379793 -0.0688532529645237 -0.12780522514893 0.989406414968507 0.000891342632401417 6.08266320685394e-05 -6.98138889463585e-05 -2.97303335656775e-06 -2.97859806278372e-05 -1.97474314870241e-05 -5.91382356536249e-06 -6.98138889463585e-05 9.47780221802479e-05 5.0290709779698e-06 4.7612506888591e-05 3.17038718586052e-05 2.15163222260324e-05 -2.97303335656775e-06 5.0290709779698e-06 1.04335525225504e-05 9.58109632207926e-07 4.6724398335211e-06 2.73759966048084e-06 -2.97859806278372e-05 4.7612506888591e-05 9.58109632207926e-07 7.54662703741344e-05 3.03166055755149e-05 3.0612403558464e-05 -1.97474314870241e-05 3.17038718586052e-05 4.6724398335211e-06 3.03166055755149e-05 3.63235922760623e-05 1.97270563489787e-05 -5.91382356536249e-06 2.15163222260324e-05 2.73759966048084e-06 3.0612403558464e-05 1.97270563489787e-05 5.42592909550849e-05 928 930 0 18 0 925 935 0 28 0 0 0 0 0 0 2 12 0 2574 0 0 0 0 0 1376 +884 911 0.996354579426403 -0.00472444626621463 0.085177647675392 -0.0120409304118418 -0.00671425285439801 0.991025111055646 0.133507108671227 -0.021443422517727 -0.085043934908039 -0.133592323374591 0.987380686600025 0.00387936158175759 5.24351175061817e-05 -6.19705266915837e-05 -2.44010425991353e-06 -2.46284575724049e-05 -1.66185591255083e-05 -1.24810109202695e-05 -6.19705266915837e-05 0.000100129945599891 5.08256608525059e-06 4.53591876325839e-05 2.68311715521001e-05 3.37677105460223e-05 -2.44010425991353e-06 5.08256608525059e-06 1.01709179787017e-05 -7.48506307001327e-07 3.7115969279887e-06 1.14345871458902e-06 -2.46284575724049e-05 4.53591876325839e-05 -7.48506307001327e-07 7.24783290011701e-05 2.52422371147572e-05 3.47141431442143e-05 -1.66185591255083e-05 2.68311715521001e-05 3.7115969279887e-06 2.52422371147572e-05 3.34549647083363e-05 1.9130490660155e-05 -1.24810109202695e-05 3.37677105460223e-05 1.14345871458902e-06 3.47141431442143e-05 1.9130490660155e-05 5.6445197401168e-05 886 889 0 19 0 886 896 0 28 0 0 0 0 0 0 2 13 0 2630 0 0 0 0 0 1483 +885 922 0.996814506359472 -0.00446411035106761 0.0796298413290864 -0.0136168028398299 -0.00550714359881264 0.992196506486601 0.124562289177613 -0.0236816069961855 -0.0795645101832723 -0.124604029768538 0.989011286328289 0.0029816871456121 4.98273888912631e-05 -6.20077627040214e-05 -5.16647305247417e-06 -1.72561365351349e-05 -1.35082066419388e-05 -2.04661572058466e-07 -6.20077627040214e-05 0.000119862651227639 1.05220684176809e-05 4.00965089964874e-05 2.29328923208512e-05 2.48471975249169e-05 -5.16647305247417e-06 1.05220684176809e-05 1.0205527591037e-05 2.49885712357825e-06 5.77281506153284e-06 1.47118059730395e-06 -1.72561365351349e-05 4.00965089964874e-05 2.49885712357825e-06 4.90432743058674e-05 8.99269470548356e-06 2.08553324814805e-05 -1.35082066419388e-05 2.29328923208512e-05 5.77281506153284e-06 8.99269470548356e-06 2.37938017644121e-05 7.69191139698766e-06 -2.04661572058466e-07 2.48471975249169e-05 1.47118059730395e-06 2.08553324814805e-05 7.69191139698766e-06 4.20816831548258e-05 888 890 0 19 0 887 895 0 28 0 0 0 0 0 0 3 12 0 2645 0 0 0 0 0 1800 +885 914 0.997174428064286 -0.00420629262678299 0.0750031140486944 -0.0202798165960123 -0.00511566495181648 0.9923110023774 0.123663675074212 -0.024994379301116 -0.0749465808877519 -0.123697945266271 0.989485638273815 0.00375271217689636 3.81373378982971e-05 -5.48009925771816e-05 -7.94058465895043e-07 -1.42275921071815e-05 -7.5396292853397e-06 7.77888727249999e-07 -5.48009925771816e-05 0.000139646466056447 9.0332264065682e-06 3.4304407884342e-05 1.32364921582564e-05 1.2714282270443e-05 -7.94058465895043e-07 9.0332264065682e-06 9.47303679520303e-06 7.06991224145226e-07 4.50296111763656e-06 -4.53066960996008e-07 -1.42275921071815e-05 3.4304407884342e-05 7.06991224145226e-07 4.86082429319195e-05 1.15357947718423e-05 1.49171859208512e-05 -7.5396292853397e-06 1.32364921582564e-05 4.50296111763656e-06 1.15357947718423e-05 2.48381134348314e-05 8.04244752849838e-06 7.77888727249999e-07 1.2714282270443e-05 -4.53066960996008e-07 1.49171859208512e-05 8.04244752849838e-06 3.79281247042664e-05 912 916 0 20 0 910 924 0 28 0 0 0 0 0 0 4 14 0 2622 0 0 0 0 0 1853 +885 916 0.996804268302456 -0.00425538845862945 0.0797693071492542 -0.0156337017043 -0.00565171491454343 0.99232090130417 0.123560863356505 -0.0244021211877756 -0.0796825502386226 -0.123616829371839 0.989125659703317 0.00296939215369834 4.17137732236229e-05 -4.68114148442548e-05 -2.22533320127402e-06 -2.01158461980443e-05 -1.22132149747443e-05 4.30687784649721e-06 -4.68114148442548e-05 8.79623375374345e-05 5.47115930075069e-06 3.73547101696989e-05 1.89614346847097e-05 1.599254856386e-05 -2.22533320127402e-06 5.47115930075069e-06 9.2317594694786e-06 -8.22230167314535e-08 3.45091938630581e-06 9.06349817132471e-07 -2.01158461980443e-05 3.73547101696989e-05 -8.22230167314535e-08 5.95591471159023e-05 1.38824630452886e-05 1.55393336953134e-05 -1.22132149747443e-05 1.89614346847097e-05 3.45091938630581e-06 1.38824630452886e-05 2.85885365862678e-05 5.87333420329353e-06 4.30687784649721e-06 1.599254856386e-05 9.06349817132471e-07 1.55393336953134e-05 5.87333420329353e-06 4.0479992774844e-05 877 877 0 17 0 875 888 0 30 0 0 0 0 0 0 2 11 0 2489 0 0 0 0 0 1832 +885 888 0.999798191294485 -0.0012355572702054 0.0200511865611253 -0.0174779016717767 0.000194742942039624 0.99865605829554 0.051827013273015 -0.0124902519662578 -0.0200882741783244 -0.0518126493034934 0.998454761425218 0.000456750275976833 5.16284548238256e-05 -7.18783109849111e-05 5.40544714213679e-06 -4.2197246953668e-05 -2.29098444474957e-05 1.42884297874798e-05 -7.18783109849111e-05 0.000135994674421404 -6.83909543740538e-06 9.68211640819143e-05 4.93740015606074e-05 -1.80600102520994e-05 5.40544714213679e-06 -6.83909543740538e-06 1.01359902860811e-05 -4.75632347531591e-06 -4.50304518114316e-07 -4.64815717113576e-07 -4.2197246953668e-05 9.68211640819143e-05 -4.75632347531591e-06 0.000139657427909773 5.64759436088478e-05 1.91988292902462e-07 -2.29098444474957e-05 4.93740015606074e-05 -4.50304518114316e-07 5.64759436088478e-05 4.7186717098245e-05 5.79766108518089e-07 1.42884297874798e-05 -1.80600102520994e-05 -4.64815717113576e-07 1.91988292902462e-07 5.79766108518089e-07 3.67926470795258e-05 855 858 0 13 0 849 861 0 22 0 0 0 0 0 0 9 16 0 2454 0 0 0 0 0 2503 +885 889 0.998530627330755 -0.00166702674479717 0.0541646314884536 -0.00812789216968023 -0.00253544085271484 0.996994903808274 0.0774256631874297 -0.015805630807081 -0.0541309322119084 -0.077449227253492 0.99552572009753 0.00132212412850689 4.44952298319053e-05 -8.04306454043361e-05 1.46203941815275e-06 -4.56824002097896e-05 -2.15045011057183e-05 1.1472510613817e-05 -8.04306454043361e-05 0.000207617985347474 9.55520523743091e-07 0.000141135542636339 6.25087293409454e-05 -8.71974092175173e-06 1.46203941815275e-06 9.55520523743091e-07 8.53220908538995e-06 9.11155146272044e-07 3.66806521014763e-06 -1.11377662734596e-06 -4.56824002097896e-05 0.000141135542636339 9.11155146272044e-07 0.000154983990513198 5.35319273795915e-05 1.09253089254692e-05 -2.15045011057183e-05 6.25087293409454e-05 3.66806521014763e-06 5.35319273795915e-05 4.21569381400957e-05 2.01531207410367e-06 1.1472510613817e-05 -8.71974092175173e-06 -1.11377662734596e-06 1.09253089254692e-05 2.01531207410367e-06 3.37411157594911e-05 828 835 0 16 0 828 842 0 25 0 0 0 0 0 0 11 18 0 2500 0 0 0 0 0 1903 +885 921 0.997071000189948 -0.00430749260825384 0.0763601079598969 -0.0166074890237854 -0.00505973415799359 0.992510421119544 0.122055164001183 -0.0263466099607128 -0.0763139546247454 -0.12208402629556 0.989581563517125 0.00118444538347203 3.29684721304909e-05 -3.21422705210446e-05 2.13581007098633e-06 -1.16345670113351e-05 -7.71237372604651e-06 2.99224751582854e-06 -3.21422705210446e-05 6.21840968550049e-05 1.68706075626069e-06 2.18270498362779e-05 1.41862320001471e-05 2.988951005434e-06 2.13581007098633e-06 1.68706075626069e-06 8.98403602413636e-06 1.83976025391986e-06 3.50797735990171e-06 9.54474202579073e-07 -1.16345670113351e-05 2.18270498362779e-05 1.83976025391986e-06 4.96301316124302e-05 1.62332614095849e-05 8.49225848861198e-06 -7.71237372604651e-06 1.41862320001471e-05 3.50797735990171e-06 1.62332614095849e-05 3.04267464862325e-05 4.64108235169629e-06 2.99224751582854e-06 2.988951005434e-06 9.54474202579073e-07 8.49225848861198e-06 4.64108235169629e-06 2.56290800062659e-05 865 863 0 25 0 862 870 0 31 0 0 0 0 0 0 2 14 0 2478 0 0 0 0 0 1855 +885 913 0.997181836820745 -0.00410553237243318 0.0749101389582402 -0.0188868683296803 -0.00513200014166493 0.992429687099118 0.122706881383615 -0.0258889944720322 -0.0748468228407185 -0.122745512212405 0.989611788704219 0.00375830229351892 3.51618046760726e-05 -4.87278661713607e-05 -1.6856153891492e-06 -1.03159005158594e-05 -2.96543167196433e-06 5.34845759574354e-06 -4.87278661713607e-05 0.000138910214068958 1.08478464466718e-05 4.16561719265715e-05 1.47700259659201e-05 1.02051067185846e-05 -1.6856153891492e-06 1.08478464466718e-05 9.96269714187576e-06 1.8875742876742e-06 5.48392124463185e-06 -9.63492283189278e-08 -1.03159005158594e-05 4.16561719265715e-05 1.8875742876742e-06 5.56263644947442e-05 7.53670560824629e-06 1.42790523546392e-05 -2.96543167196433e-06 1.47700259659201e-05 5.48392124463185e-06 7.53670560824629e-06 2.10915239966162e-05 2.90283176950671e-06 5.34845759574354e-06 1.02051067185846e-05 -9.63492283189278e-08 1.42790523546392e-05 2.90283176950671e-06 3.62729462891476e-05 903 909 0 27 0 902 914 0 34 0 0 0 0 0 0 1 11 0 2517 0 0 0 0 0 2049 +885 915 0.997382754722357 -0.00378402045174334 0.0722033362917804 -0.0211498428251504 -0.00510670644691284 0.992448743187088 0.122553717592058 -0.0261700484415173 -0.0721218561304977 -0.122601685696363 0.989831937519043 0.00268290892101855 4.01100929973563e-05 -4.42915896712479e-05 1.98913542977159e-07 -2.67167496095619e-05 -1.38572886142996e-05 -6.62695084176878e-06 -4.42915896712479e-05 7.02596166662362e-05 8.64982419008296e-07 4.5529264362493e-05 2.44252784359098e-05 1.96669299113895e-05 1.98913542977159e-07 8.64982419008296e-07 8.85122212033769e-06 8.45859011842036e-07 3.1032342416552e-06 8.61122666912479e-07 -2.67167496095619e-05 4.5529264362493e-05 8.45859011842036e-07 7.05439161918008e-05 2.39182546747703e-05 2.61079317306511e-05 -1.38572886142996e-05 2.44252784359098e-05 3.1032342416552e-06 2.39182546747703e-05 3.03807504089483e-05 1.48043983655736e-05 -6.62695084176878e-06 1.96669299113895e-05 8.61122666912479e-07 2.61079317306511e-05 1.48043983655736e-05 4.31708740625758e-05 895 894 0 16 0 892 904 0 29 0 0 0 0 0 0 2 11 0 2612 0 0 0 0 0 2046 +885 918 0.996888345959615 -0.00448167200747716 0.0786990489518163 -0.0176546849197418 -0.00522216976985954 0.992434290002424 0.12266584272029 -0.0279745926517857 -0.078653382843955 -0.122695128849525 0.989322773782046 0.00604262517941799 6.33086166290326e-05 -6.39321953673111e-05 -6.722371831522e-06 -1.83631776300698e-05 -1.66121009173015e-05 -6.1561313428264e-06 -6.39321953673111e-05 9.51562355258475e-05 9.0045948352965e-06 3.46430700296212e-05 1.95054048953506e-05 2.54635468094667e-05 -6.722371831522e-06 9.0045948352965e-06 1.00570043585671e-05 2.23522277863934e-06 3.78823070086476e-06 -2.60267509472909e-06 -1.83631776300698e-05 3.46430700296212e-05 2.23522277863934e-06 5.25300752721768e-05 1.1854114953073e-05 2.75570141357521e-05 -1.66121009173015e-05 1.95054048953506e-05 3.78823070086476e-06 1.1854114953073e-05 2.97961093747925e-05 1.30860677034355e-05 -6.1561313428264e-06 2.54635468094667e-05 -2.60267509472909e-06 2.75570141357521e-05 1.30860677034355e-05 6.14038942271547e-05 883 884 0 19 0 881 893 0 27 0 0 0 0 0 0 3 15 0 2348 0 0 0 0 0 1857 +885 912 0.997010364163685 -0.00412500201911847 0.0771577482080667 -0.0152372578088492 -0.00539528013790971 0.992420118203904 0.12277296093352 -0.0262084863517312 -0.0770793403087405 -0.122822202156175 0.989430887912378 0.00342615141377915 3.3352185850594e-05 -4.13805426122495e-05 -1.15245047129731e-06 -1.42269790630344e-05 -1.00796878753526e-05 2.41000261654224e-07 -4.13805426122495e-05 0.00010813275863939 6.40694535683291e-06 5.20932635407861e-05 2.37744291791782e-05 2.43092370229208e-05 -1.15245047129731e-06 6.40694535683291e-06 8.87028444375303e-06 2.53075068121053e-06 4.4532966596051e-06 2.32449559419164e-07 -1.42269790630344e-05 5.20932635407861e-05 2.53075068121053e-06 6.59050310335645e-05 1.8787703364549e-05 2.16269207767048e-05 -1.00796878753526e-05 2.37744291791782e-05 4.4532966596051e-06 1.8787703364549e-05 2.79022194419016e-05 8.01370326776924e-06 2.41000261654224e-07 2.43092370229208e-05 2.32449559419164e-07 2.16269207767048e-05 8.01370326776924e-06 3.97818104879394e-05 884 887 0 18 0 884 895 0 26 0 0 0 0 0 0 3 11 0 2548 0 0 0 0 0 1934 +885 927 0.997050593655955 -0.0040712952646519 0.0766390125534941 -0.0169561426383701 -0.00559587509432801 0.992077483092743 0.12550280364317 -0.0219136784907539 -0.0765427976509565 -0.125561507219511 0.989128661010553 0.00441034968078802 5.24646389186869e-05 -5.61013538861933e-05 -4.4725063090468e-06 -1.60594286810784e-05 -1.07409108967495e-05 -2.79752597291829e-06 -5.61013538861933e-05 9.10976034150314e-05 6.89019166872969e-06 3.82933601204109e-05 2.11150957172655e-05 2.15202337744796e-05 -4.4725063090468e-06 6.89019166872969e-06 9.3409822852978e-06 1.39116515392403e-06 2.98025457493433e-06 -1.33005507964424e-06 -1.60594286810784e-05 3.82933601204109e-05 1.39116515392403e-06 6.0487651269141e-05 1.89744695867201e-05 2.78340860713308e-05 -1.07409108967495e-05 2.11150957172655e-05 2.98025457493433e-06 1.89744695867201e-05 2.6869675015787e-05 1.59320014293018e-05 -2.79752597291829e-06 2.15202337744796e-05 -1.33005507964424e-06 2.78340860713308e-05 1.59320014293018e-05 4.54533852243391e-05 878 882 0 15 0 879 894 0 27 0 0 0 0 0 0 3 13 0 2585 0 0 0 0 0 1832 +885 928 0.997526771507522 -0.00349682610687653 0.0702005151901231 -0.0193698416788619 -0.00515331543517074 0.992435111636586 0.122662107151729 -0.0264186061522309 -0.0700983841882683 -0.122720501131861 0.9899625725936 0.00212163169044789 5.06743404032733e-05 -5.36416211900565e-05 -5.86104788984101e-06 -1.03688532181019e-05 -9.58080530973416e-06 -5.70950949089666e-06 -5.36416211900565e-05 8.66313809949924e-05 9.17294498908719e-06 2.86164680666249e-05 1.67205800631434e-05 2.99956121253315e-05 -5.86104788984101e-06 9.17294498908719e-06 1.05510263137205e-05 -3.09852759907974e-07 3.02542108589467e-06 5.38823723833606e-07 -1.03688532181019e-05 2.86164680666249e-05 -3.09852759907974e-07 5.70570676233006e-05 1.37293024572728e-05 2.52753531449189e-05 -9.58080530973416e-06 1.67205800631434e-05 3.02542108589467e-06 1.37293024572728e-05 2.68141387994239e-05 1.36511639273815e-05 -5.70950949089666e-06 2.99956121253315e-05 5.38823723833606e-07 2.52753531449189e-05 1.36511639273815e-05 5.43396706519956e-05 897 903 0 26 0 896 911 0 34 0 0 0 0 0 0 2 12 0 2545 0 0 0 0 0 1694 +885 923 0.996986176853031 -0.00470424650224423 0.0774366400925437 -0.0180623914358081 -0.00483960572442213 0.992444379760823 0.122599882942798 -0.0258950160528542 -0.0774282983179158 -0.122605151384441 0.989430561218719 0.00267873403914686 3.59819551367217e-05 -4.11500360293166e-05 -2.0411228285388e-07 -1.04175205305715e-05 -9.55152299668851e-06 7.91332940274917e-06 -4.11500360293166e-05 0.000102740885567253 6.6752396740626e-06 3.0413772473453e-05 1.92490893903437e-05 2.73229230669319e-07 -2.0411228285388e-07 6.6752396740626e-06 9.50097708107925e-06 2.53926383588042e-06 4.61305195147549e-06 -4.94495274381558e-07 -1.04175205305715e-05 3.0413772473453e-05 2.53926383588042e-06 4.92207326239813e-05 9.22817733208202e-06 8.30606013942381e-06 -9.55152299668851e-06 1.92490893903437e-05 4.61305195147549e-06 9.22817733208202e-06 2.5643952693192e-05 5.4331918069986e-07 7.91332940274917e-06 2.73229230669319e-07 -4.94495274381558e-07 8.30606013942381e-06 5.4331918069986e-07 2.81194993318123e-05 881 885 0 18 0 880 893 0 28 0 0 0 0 0 0 4 13 0 2516 0 0 0 0 0 1770 +885 926 0.997205745731549 -0.00386852214154141 0.074603855238358 -0.0181037610302284 -0.00539029769172949 0.992329086986284 0.123506792573377 -0.0251137489793449 -0.0745093643160376 -0.123563820179732 0.989535414713294 0.00367372223102796 4.02862100429165e-05 -4.82602786343859e-05 -1.2633774237538e-06 -2.23290383161405e-05 -1.14464099692275e-05 -5.43039734966117e-06 -4.82602786343859e-05 8.77407018155795e-05 4.07744736150406e-06 4.4295721100089e-05 2.08160871104737e-05 2.7332988153727e-05 -1.2633774237538e-06 4.07744736150406e-06 8.42574375843331e-06 2.24165613440069e-06 4.40599229728651e-06 9.62854985967554e-07 -2.23290383161405e-05 4.4295721100089e-05 2.24165613440069e-06 5.69721931290752e-05 1.36692110544053e-05 2.64056056518949e-05 -1.14464099692275e-05 2.08160871104737e-05 4.40599229728651e-06 1.36692110544053e-05 2.61627759844198e-05 1.3264867765211e-05 -5.43039734966117e-06 2.7332988153727e-05 9.62854985967554e-07 2.64056056518949e-05 1.3264867765211e-05 4.83373802363748e-05 899 900 0 16 0 897 913 0 28 0 0 0 0 0 0 4 16 0 2571 0 0 0 0 0 2071 +885 917 0.997428236396523 -0.003451094839324 0.0715891275497304 -0.0187370194886105 -0.00533773120431279 0.99248944413875 0.122213795860963 -0.0263712794967266 -0.0714732248084 -0.122281614388937 0.989918574892866 0.00411101527834673 4.66225487668202e-05 -4.45249628480164e-05 -4.70632526057467e-06 -1.45529686323474e-05 -1.59450020560164e-05 3.22936619044205e-06 -4.45249628480164e-05 6.84555776879511e-05 7.02251521778997e-06 2.84754842097598e-05 1.84170291180071e-05 1.07817878958818e-05 -4.70632526057467e-06 7.02251521778997e-06 9.7770443320837e-06 -2.01596527187178e-07 2.86698026341376e-06 -1.20776950295696e-06 -1.45529686323474e-05 2.84754842097598e-05 -2.01596527187178e-07 6.23279365044382e-05 2.05209371825374e-05 1.89150423276806e-05 -1.59450020560164e-05 1.84170291180071e-05 2.86698026341376e-06 2.05209371825374e-05 3.79971008082094e-05 9.16852482646044e-06 3.22936619044205e-06 1.07817878958818e-05 -1.20776950295696e-06 1.89150423276806e-05 9.16852482646044e-06 4.03791072970275e-05 885 886 0 21 0 882 894 0 31 0 0 0 0 0 0 3 13 0 2282 0 0 0 0 0 2054 +886 889 0.99894830875727 -0.00146210281408781 0.0458272701167219 -0.00952280275418995 -0.00200683420934642 0.997139344425531 0.0755585892872463 -0.0140819729314066 -0.0458066485070252 -0.0755710927139711 0.996087727511272 -0.000770417445645003 4.33489640470598e-05 -4.88185814239343e-05 5.26729432528668e-06 -2.88211450726365e-05 -1.57716458733683e-05 1.21204664607566e-05 -4.88185814239343e-05 6.67656129159815e-05 -4.76056338080797e-06 5.05436941196929e-05 2.7339490253514e-05 -5.29773339154446e-06 5.26729432528668e-06 -4.76056338080797e-06 9.20366930137132e-06 7.22983020880638e-07 4.49073659096572e-06 4.3438424029497e-06 -2.88211450726365e-05 5.05436941196929e-05 7.22983020880638e-07 8.64756869389412e-05 3.60649729753597e-05 1.0678688827841e-05 -1.57716458733683e-05 2.7339490253514e-05 4.49073659096572e-06 3.60649729753597e-05 3.45812370400918e-05 7.68326179220366e-06 1.21204664607566e-05 -5.29773339154446e-06 4.3438424029497e-06 1.0678688827841e-05 7.68326179220366e-06 3.40833015685953e-05 879 881 0 15 0 875 890 0 27 0 0 0 0 0 0 8 21 0 2535 0 0 0 0 0 2430 +885 925 0.997127684488448 -0.00444647010651926 0.0756082649602356 -0.0189214637354658 -0.00490789723593722 0.992383730956969 0.123087136113599 -0.0258657479086244 -0.0755797153436478 -0.12310466861788 0.989511468954784 0.00159231434162678 3.7170073321451e-05 -5.03049181083274e-05 3.22847749221672e-07 -1.82155996494117e-05 -1.13174543559224e-05 3.10972538072374e-06 -5.03049181083274e-05 0.000120179755399366 6.4716799087052e-06 5.03561085472103e-05 2.52794337014133e-05 6.64388381798211e-06 3.22847749221672e-07 6.4716799087052e-06 9.62406360883869e-06 2.39389591303336e-06 5.71140035541135e-06 -6.71227290417453e-07 -1.82155996494117e-05 5.03561085472103e-05 2.39389591303336e-06 6.37438485210236e-05 1.3883385152323e-05 1.28118312369857e-05 -1.13174543559224e-05 2.52794337014133e-05 5.71140035541135e-06 1.3883385152323e-05 2.67444438960213e-05 3.54443107140797e-06 3.10972538072374e-06 6.64388381798211e-06 -6.71227290417453e-07 1.28118312369857e-05 3.54443107140797e-06 2.9631327247308e-05 888 892 0 17 0 888 903 0 32 0 0 0 0 0 0 4 16 0 2532 0 0 0 0 0 1929 +885 924 0.996898797630027 -0.00426991539517846 0.0785783373858512 -0.0151430069544918 -0.00545882308933865 0.992369412997021 0.123179338358459 -0.0261171727900525 -0.0785047038991037 -0.123226279544854 0.989268565908797 0.00369676205021045 5.10189585254015e-05 -5.37626891130274e-05 -2.22241281225521e-06 -2.01002821507884e-05 -1.3194380251328e-05 1.18659039834659e-06 -5.37626891130274e-05 8.58593758250261e-05 5.00888145538867e-06 4.08275393248321e-05 2.22225631964084e-05 1.55288801780866e-05 -2.22241281225521e-06 5.00888145538867e-06 9.50302171344642e-06 2.56816450849845e-06 4.2656939621988e-06 7.38105610783261e-08 -2.01002821507884e-05 4.08275393248321e-05 2.56816450849845e-06 6.09355364886454e-05 1.38777713298719e-05 1.91427893386123e-05 -1.3194380251328e-05 2.22225631964084e-05 4.2656939621988e-06 1.38777713298719e-05 2.7219495856373e-05 7.8727047458274e-06 1.18659039834659e-06 1.55288801780866e-05 7.38105610783261e-08 1.91427893386123e-05 7.8727047458274e-06 4.48083157503865e-05 859 857 0 18 0 856 863 0 26 0 0 0 0 0 0 3 13 0 2595 0 0 0 0 0 2027 +885 929 0.995991909160331 -0.0271810085812261 0.0852133185579912 -0.0196171598963203 0.0149352783034095 0.989871489920196 0.141178507235241 -0.0265260523469905 -0.0881876088186888 -0.139339966325812 0.986309950996726 -0.003671163058285 3.18302729529605e-05 -3.60369940625318e-05 -3.54667989723836e-06 -1.56532202616944e-07 -8.69399021201873e-07 5.8253783988235e-06 -3.60369940625318e-05 9.3908860969123e-05 9.20330789543317e-06 2.07879032059656e-05 9.54399149938961e-06 3.992530106022e-06 -3.54667989723836e-06 9.20330789543317e-06 1.06597982296034e-05 -6.348623363009e-07 3.59595364089213e-06 -3.69861091715511e-06 -1.56532202616944e-07 2.07879032059656e-05 -6.348623363009e-07 4.40582314941705e-05 2.20993574849641e-06 1.39953985491529e-05 -8.69399021201873e-07 9.54399149938961e-06 3.59595364089213e-06 2.20993574849641e-06 2.42881695429279e-05 3.20808394259996e-07 5.8253783988235e-06 3.992530106022e-06 -3.69861091715511e-06 1.39953985491529e-05 3.20808394259996e-07 3.44074517902659e-05 914 914 0 2 0 920 922 0 8 0 0 0 0 0 0 24 39 0 2578 0 0 0 0 0 1531 +885 911 0.996640243708061 -0.00441246676453261 0.0817848076270146 -0.0156743376257479 -0.00603890809114392 0.991870949113034 0.127104492031858 -0.0217430525290268 -0.0816808191107472 -0.127171342851532 0.988511857969714 0.00395802052906855 3.59197253491416e-05 -3.66787284261411e-05 -1.17022077221885e-06 -1.4699550109663e-05 -9.59623667589857e-06 7.88249653524674e-06 -3.66787284261411e-05 5.18398346697764e-05 2.05589702573776e-06 2.67123360942011e-05 1.73185499989198e-05 2.98162480036494e-07 -1.17022077221885e-06 2.05589702573776e-06 8.84064822084537e-06 4.36289384164345e-07 3.59973119893057e-06 -1.8815645241338e-06 -1.4699550109663e-05 2.67123360942011e-05 4.36289384164345e-07 5.38663537190075e-05 1.62086102502886e-05 1.05438565394335e-05 -9.59623667589857e-06 1.73185499989198e-05 3.59973119893057e-06 1.62086102502886e-05 2.59300008774231e-05 6.23750013186183e-06 7.88249653524674e-06 2.98162480036494e-07 -1.8815645241338e-06 1.05438565394335e-05 6.23750013186183e-06 3.51198104388477e-05 872 877 0 20 0 870 885 0 31 0 0 0 0 0 0 4 17 0 2626 0 0 0 0 0 1801 +886 913 0.99737334728835 -0.00377436415128012 0.0723336733070168 -0.0183790110998402 -0.00517617464561958 0.992374108922292 0.123153705412074 -0.0242125950352561 -0.0722468915239317 -0.1232046351236 0.989747950010097 0.0021368369096729 2.52121858498543e-05 -2.57515433635642e-05 1.88698083625345e-06 -1.39029349684722e-05 -5.37314677190725e-06 4.66774307318171e-06 -2.57515433635642e-05 4.26087405841715e-05 -4.53969922562145e-07 2.27809574253441e-05 1.28409704212691e-05 -2.67308468335912e-06 1.88698083625345e-06 -4.53969922562145e-07 8.49675061759404e-06 9.32624099622088e-07 3.32892582863573e-06 1.40817618626264e-06 -1.39029349684722e-05 2.27809574253441e-05 9.32624099622088e-07 5.1352980811588e-05 1.41441963742922e-05 4.35341689940855e-06 -5.37314677190725e-06 1.28409704212691e-05 3.32892582863573e-06 1.41441963742922e-05 2.20786473019147e-05 5.63608471941701e-06 4.66774307318171e-06 -2.67308468335912e-06 1.40817618626264e-06 4.35341689940855e-06 5.63608471941701e-06 2.44496061193355e-05 882 886 0 17 0 881 896 0 29 0 0 0 0 0 0 9 23 0 2559 0 0 0 0 0 1911 +886 922 0.997518574986621 -0.00362453177678974 0.0703104211768086 -0.0169577129289653 -0.0049731494145423 0.992551739804796 0.121722272388309 -0.0241994559400217 -0.0702279171096638 -0.121769891926831 0.990070771752487 0.00419751423889635 4.7276753759379e-05 -4.89235905934778e-05 -3.73855601829953e-06 -1.23934366020704e-05 -1.08591978072052e-05 1.3402467887194e-05 -4.89235905934778e-05 7.10300685736555e-05 5.64321345811741e-06 2.83419299662239e-05 1.76252905148021e-05 -5.37522800393391e-06 -3.73855601829953e-06 5.64321345811741e-06 9.5131323346314e-06 1.69029268542547e-06 3.88050510078562e-06 -9.78960381778548e-07 -1.23934366020704e-05 2.83419299662239e-05 1.69029268542547e-06 5.24503304086547e-05 1.6044362108843e-05 8.81123517034087e-06 -1.08591978072052e-05 1.76252905148021e-05 3.88050510078562e-06 1.6044362108843e-05 2.42591160814216e-05 1.9228906675832e-06 1.3402467887194e-05 -5.37522800393391e-06 -9.78960381778548e-07 8.81123517034087e-06 1.9228906675832e-06 3.05936906201678e-05 894 892 0 14 0 894 905 0 29 0 0 0 0 0 0 9 24 0 2693 0 0 0 0 0 2103 +886 919 0.997763930633439 -0.00326983335591146 0.0667566245157338 -0.0210216906820438 -0.00478587356195886 0.99274336302799 0.120157024672403 -0.0263870246693401 -0.0666650893733673 -0.120207833994711 0.990507870996057 0.00362726995008676 4.3744646583399e-05 -4.9847313458704e-05 -2.46144360190914e-06 -1.29605779766581e-05 -1.34300486526111e-05 6.38967851435286e-06 -4.9847313458704e-05 0.000100293563846156 4.81846204407677e-06 4.60143733842242e-05 2.53563851451922e-05 6.16349532786659e-06 -2.46144360190914e-06 4.81846204407677e-06 9.18841201805143e-06 3.40137222675323e-06 2.29217301908606e-06 -1.36215774217477e-06 -1.29605779766581e-05 4.60143733842242e-05 3.40137222675323e-06 5.8821160435064e-05 1.39990195226435e-05 1.3911563618422e-05 -1.34300486526111e-05 2.53563851451922e-05 2.29217301908606e-06 1.39990195226435e-05 2.91462280273068e-05 2.50887018341097e-06 6.38967851435286e-06 6.16349532786659e-06 -1.36215774217477e-06 1.3911563618422e-05 2.50887018341097e-06 3.1664473322456e-05 880 884 0 16 0 880 893 0 29 0 0 0 0 0 0 8 23 0 2429 0 0 0 0 0 2142 +886 914 0.997461167640781 -0.00369996379123077 0.0711163083732091 -0.0206242935806354 -0.00495432660445741 0.992624111166251 0.121131451651937 -0.0267911717747762 -0.0710399443734731 -0.121176252621348 0.990085674123235 0.00108613685248368 2.18028766050415e-05 -2.03158869260541e-05 1.6567976329848e-06 -9.09038951990803e-06 -2.78145390237107e-06 5.81204954333298e-06 -2.03158869260541e-05 3.98133425758763e-05 1.86578996605376e-06 1.38933389036673e-05 6.59648629847045e-06 -6.39270122128363e-06 1.6567976329848e-06 1.86578996605376e-06 8.39099311929972e-06 1.3526124842788e-06 2.88075078805554e-06 -2.02187956955106e-07 -9.09038951990803e-06 1.38933389036673e-05 1.3526124842788e-06 4.19915073622026e-05 1.01549931490607e-05 3.30580076927641e-06 -2.78145390237107e-06 6.59648629847045e-06 2.88075078805554e-06 1.01549931490607e-05 1.92319415992104e-05 9.5057186085056e-07 5.81204954333298e-06 -6.39270122128363e-06 -2.02187956955106e-07 3.30580076927641e-06 9.5057186085056e-07 2.28561486348313e-05 890 895 0 17 0 890 903 0 27 0 0 0 0 0 0 9 24 0 2673 0 0 0 0 0 2025 +886 927 0.99762960512051 -0.00348769511326485 0.0687241367344331 -0.0215569679691918 -0.00498826369070299 0.992421818135075 0.122776431430568 -0.0246525303601201 -0.0686315394876741 -0.12282821692213 0.990051988996175 0.00298612527899209 4.92070321601283e-05 -7.1831378554992e-05 -6.60419162253828e-06 -2.47192358179371e-05 -1.87318301420594e-05 1.47810593169443e-05 -7.1831378554992e-05 0.00017962798131935 1.51231722955674e-05 8.4837615235992e-05 4.7582759358269e-05 -9.05428710320778e-06 -6.60419162253828e-06 1.51231722955674e-05 1.00398665136983e-05 5.64562761457714e-06 6.96797611873825e-06 -3.22406588955441e-06 -2.47192358179371e-05 8.4837615235992e-05 5.64562761457714e-06 8.66652607624691e-05 2.82005573652336e-05 9.77635004330274e-06 -1.87318301420594e-05 4.7582759358269e-05 6.96797611873825e-06 2.82005573652336e-05 3.13047924896329e-05 9.29475697655417e-07 1.47810593169443e-05 -9.05428710320778e-06 -3.22406588955441e-06 9.77635004330274e-06 9.29475697655417e-07 3.2094130675857e-05 847 850 0 13 0 846 861 0 28 0 0 0 0 0 0 11 27 0 2651 0 0 0 0 0 1876 +886 888 0.999336547913622 -0.000432283365588638 0.0364180880219777 -6.1040809906969e-05 -0.00156431353386303 0.998497333645224 0.054777984871166 -0.00797612750554407 -0.036387043398062 -0.0547986116107858 0.997834202279255 -0.00142511815139329 3.39459254892384e-05 -3.82329976323887e-05 4.26619878579953e-06 -2.35529087813297e-05 -1.22501129231766e-05 1.41955088274445e-05 -3.82329976323887e-05 6.0733264629999e-05 -3.30435753244935e-06 4.31554194738093e-05 2.33077558946337e-05 -1.36753765679016e-05 4.26619878579953e-06 -3.30435753244935e-06 9.16480173475669e-06 5.26395380422447e-07 2.68089711029238e-06 1.1637902980506e-06 -2.35529087813297e-05 4.31554194738093e-05 5.26395380422447e-07 8.42522263566292e-05 3.70240640655805e-05 -5.97345493016019e-06 -1.22501129231766e-05 2.33077558946337e-05 2.68089711029238e-06 3.70240640655805e-05 3.32877246703941e-05 -1.12573878140755e-06 1.41955088274445e-05 -1.36753765679016e-05 1.1637902980506e-06 -5.97345493016019e-06 -1.12573878140755e-06 2.94993307226146e-05 858 857 0 11 0 856 867 0 23 0 0 0 0 0 0 9 21 0 2459 0 0 0 0 0 2587 +886 890 0.998019516747861 -0.00277122518027323 0.0628439694908451 -0.0126870424837232 -0.00331060427300896 0.995330733043856 0.096466428138119 -0.0173867344529781 -0.062817864415416 -0.0964834295067271 0.993350322766801 -0.00165894813933441 3.53322294861911e-05 -3.77714399805248e-05 3.84711045407321e-06 -2.19756846446754e-05 -1.2912868550316e-05 1.10360687340906e-05 -3.77714399805248e-05 6.95107891739491e-05 -4.50603290017883e-07 4.5598963842492e-05 2.45016945003243e-05 -5.95665617282557e-06 3.84711045407321e-06 -4.50603290017883e-07 9.31711154918302e-06 4.32439633706871e-07 4.88504861846675e-06 1.22913938672086e-06 -2.19756846446754e-05 4.5598963842492e-05 4.32439633706871e-07 8.30596754655206e-05 3.27943458445154e-05 -1.4986717775277e-06 -1.2912868550316e-05 2.45016945003243e-05 4.88504861846675e-06 3.27943458445154e-05 3.30130675550009e-05 -7.25020063095048e-07 1.10360687340906e-05 -5.95665617282557e-06 1.22913938672086e-06 -1.4986717775277e-06 -7.25020063095048e-07 2.51674479317205e-05 836 840 0 15 0 830 842 0 26 0 0 0 0 0 0 8 18 0 2538 0 0 0 0 0 2042 +886 920 0.997449465196334 -0.00410139978460551 0.0712582830227752 -0.0200573197905786 -0.00437985557744753 0.992949315332218 0.118458744068981 -0.0300095117990038 -0.0712417100066232 -0.118468711907772 0.990398800006465 0.00218604546577352 3.88448632721298e-05 -4.010381387359e-05 -2.85485464869718e-06 -5.99422689654278e-06 -6.95784291952895e-06 8.73620943409154e-06 -4.010381387359e-05 6.51010316771748e-05 4.8467088848528e-06 2.1031279825015e-05 1.10682311812736e-05 -1.03866890902812e-06 -2.85485464869718e-06 4.8467088848528e-06 1.0255427824823e-05 -1.14693402515947e-06 3.63687914907278e-06 -2.18807988321936e-06 -5.99422689654278e-06 2.1031279825015e-05 -1.14693402515947e-06 5.17719600694673e-05 7.52174344877698e-06 1.02360765261902e-05 -6.95784291952895e-06 1.10682311812736e-05 3.63687914907278e-06 7.52174344877698e-06 2.39242151213075e-05 9.38469996409589e-07 8.73620943409154e-06 -1.03866890902812e-06 -2.18807988321936e-06 1.02360765261902e-05 9.38469996409589e-07 2.99752924517044e-05 887 889 0 16 0 886 896 0 26 0 0 0 0 0 0 11 24 0 2405 0 0 0 0 0 2033 +886 921 0.99737411616966 -0.00393000378493708 0.0723147804051185 -0.0174372221456319 -0.0049501920777628 0.992491749048282 0.122211389278889 -0.0271731063316627 -0.0722521141087469 -0.122248448420965 0.989866126739108 0.00285716503568617 2.95323573934323e-05 -2.91615333205479e-05 3.29753399160169e-06 -9.55755049769513e-06 -3.43719994170778e-06 -4.32666261973518e-07 -2.91615333205479e-05 4.99377295915065e-05 -5.24233300883386e-07 2.00582502183401e-05 7.73764062906957e-06 4.39257835524414e-06 3.29753399160169e-06 -5.24233300883386e-07 8.54822662738123e-06 7.01325322529921e-07 3.11394253384408e-06 1.32590228300624e-06 -9.55755049769513e-06 2.00582502183401e-05 7.01325322529921e-07 5.06957992717511e-05 1.22653126167344e-05 8.72601373294968e-06 -3.43719994170778e-06 7.73764062906957e-06 3.11394253384408e-06 1.22653126167344e-05 2.44929135551291e-05 4.35488242688844e-06 -4.32666261973518e-07 4.39257835524414e-06 1.32590228300624e-06 8.72601373294968e-06 4.35488242688844e-06 2.72512304204414e-05 859 855 0 15 0 858 865 0 29 0 0 0 0 0 0 9 25 0 2544 0 0 0 0 0 1830 +886 916 0.997263563833101 -0.00358112173385171 0.0738414505412055 -0.0162314126636209 -0.00553170084107985 0.992411363409108 0.122837641064459 -0.0238379255622963 -0.073720991153855 -0.122909972514859 0.989675883367726 0.0045952170366428 4.047939854157e-05 -4.5766310914901e-05 -4.12983433104727e-06 -1.02299624964787e-05 -9.02000988027375e-06 1.57466735842773e-05 -4.5766310914901e-05 8.69779644723916e-05 7.67335178072898e-06 3.21010365069089e-05 1.9083388938285e-05 -8.54344210225402e-06 -4.12983433104727e-06 7.67335178072898e-06 9.26434435213815e-06 1.55680875906078e-06 4.57885954474734e-06 -3.05032138980943e-06 -1.02299624964787e-05 3.21010365069089e-05 1.55680875906078e-06 5.69643872508879e-05 1.39976141601505e-05 6.88776438988556e-06 -9.02000988027375e-06 1.9083388938285e-05 4.57885954474734e-06 1.39976141601505e-05 2.50439108708142e-05 1.02495736214437e-06 1.57466735842773e-05 -8.54344210225402e-06 -3.05032138980943e-06 6.88776438988556e-06 1.02495736214437e-06 3.27149416408721e-05 858 858 0 12 0 856 867 0 24 0 0 0 0 0 0 9 22 0 2532 0 0 0 0 0 2146 +886 918 0.997620045950092 -0.00381377990414479 0.0688454719017894 -0.0211946174281851 -0.00440743479123793 0.992900067808265 0.118869802157246 -0.030372480271894 -0.0688100169822557 -0.11889032941827 0.990520202284495 0.00340242754583546 4.73643515805868e-05 -5.40205345215154e-05 -3.68160776648278e-06 -9.73681062845356e-06 -9.85118905134281e-06 2.26467899446438e-05 -5.40205345215154e-05 0.000136233777116162 1.09711090074247e-05 3.84729741376415e-05 1.57053313938032e-05 -2.50738759188157e-05 -3.68160776648278e-06 1.09711090074247e-05 9.04234487520517e-06 4.32460233791044e-06 4.14757501981311e-06 -3.07466920941419e-06 -9.73681062845356e-06 3.84729741376415e-05 4.32460233791044e-06 4.27488822012977e-05 2.00728455199162e-06 3.66320929410973e-06 -9.85118905134281e-06 1.57053313938032e-05 4.14757501981311e-06 2.00728455199162e-06 2.27640103741289e-05 -4.7932866596202e-06 2.26467899446438e-05 -2.50738759188157e-05 -3.07466920941419e-06 3.66320929410973e-06 -4.7932866596202e-06 3.6653862796746e-05 856 861 0 19 0 855 869 0 28 0 0 0 0 0 0 11 27 0 2359 0 0 0 0 0 2058 +886 926 0.997587828791866 -0.00352880246784067 0.0693258350073983 -0.0212903178804568 -0.00499425456960218 0.992470141675557 0.122384947210816 -0.026035003265696 -0.069235693595313 -0.122435964633122 0.990058510037024 0.00344255892396137 3.36406242683315e-05 -3.87600676302758e-05 -1.78444172798057e-06 -8.85850714786333e-06 -7.86265506549652e-06 1.30427930491048e-05 -3.87600676302758e-05 9.44585305601817e-05 8.33467620763107e-06 3.43804062930799e-05 2.15781815196711e-05 -8.72280045688686e-06 -1.78444172798057e-06 8.33467620763107e-06 1.00068829384638e-05 1.32266615069805e-06 5.25276858942191e-06 -1.25466150611965e-06 -8.85850714786333e-06 3.43804062930799e-05 1.32266615069805e-06 5.76007414019336e-05 1.65497834028257e-05 8.82897381521308e-06 -7.86265506549652e-06 2.15781815196711e-05 5.25276858942191e-06 1.65497834028257e-05 2.67449623185227e-05 2.86259412520383e-06 1.30427930491048e-05 -8.72280045688686e-06 -1.25466150611965e-06 8.82897381521308e-06 2.86259412520383e-06 3.15402375871397e-05 848 850 0 14 0 847 860 0 27 0 0 0 0 0 0 8 24 0 2607 0 0 0 0 0 1877 +886 912 0.997395581115746 -0.00366116318483176 0.0720322889745772 -0.0163865800992953 -0.00526790948888616 0.992345543042512 0.123379788998355 -0.024087441177192 -0.071932634460305 -0.123437915924548 0.989741772894225 0.00139448584577643 5.4859338070118e-05 -6.11056974366991e-05 -4.5802605752373e-06 -2.02028735099584e-05 -2.25797377553843e-05 7.39817521404327e-06 -6.11056974366991e-05 8.86734272709484e-05 7.06167384984409e-06 3.8695431537945e-05 3.39381452618877e-05 2.22160067256011e-06 -4.5802605752373e-06 7.06167384984409e-06 9.36173219101153e-06 2.19116811705636e-06 5.14635410453412e-06 -2.24027592968464e-06 -2.02028735099584e-05 3.8695431537945e-05 2.19116811705636e-06 5.60039943368492e-05 2.41675416699058e-05 1.63163212869964e-05 -2.25797377553843e-05 3.39381452618877e-05 5.14635410453412e-06 2.41675416699058e-05 3.53348790768159e-05 7.53846158011855e-06 7.39817521404327e-06 2.22160067256011e-06 -2.24027592968464e-06 1.63163212869964e-05 7.53846158011855e-06 4.02316424028599e-05 881 883 0 12 0 881 892 0 25 0 0 0 0 0 0 9 21 0 2574 0 0 0 0 0 1930 +886 928 0.997912388961087 -0.00331669079121728 0.0644970039627471 -0.021528532579032 -0.00461494437856736 0.992465193056965 0.12243995613681 -0.0243252382516199 -0.0644171269644796 -0.122481999218647 0.99037800542068 0.00261965607374237 3.51535181695223e-05 -5.33553639670785e-05 -2.84651586795557e-06 -1.02719187170327e-05 -4.75983618126093e-06 1.54070461650261e-05 -5.33553639670785e-05 0.000152399624377586 1.13758694880229e-05 4.68754558918435e-05 1.8174204992616e-05 -2.18078775273986e-05 -2.84651586795557e-06 1.13758694880229e-05 9.94387124043031e-06 1.54041531178727e-06 5.51016071610965e-06 -4.54527177965774e-06 -1.02719187170327e-05 4.68754558918435e-05 1.54041531178727e-06 5.35203133350379e-05 8.03724969363067e-06 5.53128100979364e-06 -4.75983618126093e-06 1.8174204992616e-05 5.51016071610965e-06 8.03724969363067e-06 1.96174586738729e-05 -2.19806369735723e-06 1.54070461650261e-05 -2.18078775273986e-05 -4.54527177965774e-06 5.53128100979364e-06 -2.19806369735723e-06 3.3967914725021e-05 864 865 0 13 0 865 879 0 31 0 0 0 0 0 0 9 24 0 2595 0 0 0 0 0 2154 +886 915 0.99793884805136 -0.00333823554520179 0.064085191217388 -0.0257781259483488 -0.00444980359498445 0.992642536632585 0.120999974031376 -0.0273027554620858 -0.0640176131848923 -0.121035741213381 0.990581695041372 0.00243151424404195 4.8260010248822e-05 -6.94617803256505e-05 -4.80323275414015e-06 -2.79005626678763e-05 -2.01838522037547e-05 1.02679266466928e-05 -6.94617803256505e-05 0.000178356664769536 1.10380850455854e-05 0.00010061597937012 5.5405165611246e-05 -7.97107607952709e-06 -4.80323275414015e-06 1.10380850455854e-05 9.12092202192605e-06 4.80775491741896e-06 6.22830693586758e-06 -2.27946527580864e-06 -2.79005626678763e-05 0.00010061597937012 4.80775491741896e-06 0.000106261654688242 4.01301979375625e-05 8.79179911270315e-06 -2.01838522037547e-05 5.5405165611246e-05 6.22830693586758e-06 4.01301979375625e-05 3.77402146408732e-05 -1.02176577300538e-06 1.02679266466928e-05 -7.97107607952709e-06 -2.27946527580864e-06 8.79179911270315e-06 -1.02176577300538e-06 3.25501942859638e-05 855 852 0 12 0 852 862 0 25 0 0 0 0 0 0 9 23 0 2660 0 0 0 0 0 1860 +887 890 0.999064168005309 -0.00127560447589016 0.0432337951269668 -0.0138701642737101 -0.0019163069901151 0.997278076892196 0.0737072935178264 -0.0163060399491224 -0.0432101374144897 -0.0737211650981214 0.996342347710463 0.000692047246583595 4.31213976824537e-05 -4.65526186649441e-05 3.14335247747344e-06 -2.11282785651438e-05 -1.45081775118934e-05 -6.73701241735466e-07 -4.65526186649441e-05 6.90468973897685e-05 -7.48636320166484e-07 4.03972923592759e-05 2.42709077520382e-05 8.32816425543999e-06 3.14335247747344e-06 -7.48636320166484e-07 1.0012469377315e-05 7.96989607038708e-07 5.23960973184094e-06 2.34974993837224e-06 -2.11282785651438e-05 4.03972923592759e-05 7.96989607038708e-07 7.43829590535439e-05 2.36195528147172e-05 1.41029365553403e-05 -1.45081775118934e-05 2.42709077520382e-05 5.23960973184094e-06 2.36195528147172e-05 3.36555485391914e-05 1.13976080616165e-05 -6.73701241735466e-07 8.32816425543999e-06 2.34974993837224e-06 1.41029365553403e-05 1.13976080616165e-05 3.30258950006543e-05 856 856 0 9 0 853 868 0 24 0 0 0 0 0 0 8 21 0 2601 0 0 0 0 0 1464 +886 924 0.99788075331176 -0.00315644498867681 0.0649926074641343 -0.0228196712069648 -0.00472663289557143 0.992667840017785 0.120781697023583 -0.0273334127522802 -0.0648973120508399 -0.120832927008575 0.990549212628588 0.00145939346665001 5.31680568610549e-05 -6.15461567382249e-05 -5.59645596912151e-06 -2.39117793765743e-05 -1.48501088519792e-05 3.47131711042467e-07 -6.15461567382249e-05 0.000105879949956557 8.97401946521992e-06 5.25341854766328e-05 2.73483397626174e-05 7.37262490462909e-06 -5.59645596912151e-06 8.97401946521992e-06 1.04861490563568e-05 1.7694732717569e-06 2.70151455464198e-06 9.70909412000535e-07 -2.39117793765743e-05 5.25341854766328e-05 1.7694732717569e-06 7.89043159458655e-05 2.75095325963213e-05 1.72221172097551e-05 -1.48501088519792e-05 2.73483397626174e-05 2.70151455464198e-06 2.75095325963213e-05 3.03006936085755e-05 5.06901578213743e-06 3.47131711042467e-07 7.37262490462909e-06 9.70909412000535e-07 1.72221172097551e-05 5.06901578213743e-06 3.63211371972232e-05 840 840 0 15 0 840 846 0 25 0 0 0 0 0 0 10 23 0 2606 0 0 0 0 0 1857 +886 917 0.997408542773971 -0.00329352221544526 0.0718703799413929 -0.0153661291463452 -0.0056649462432622 0.992254997532962 0.124088388880355 -0.0237805345640972 -0.0717224315368962 -0.124173960967175 0.98966495352324 0.00167990343433329 3.13628931785077e-05 -4.23361010597606e-05 -1.05575264092019e-06 -1.52242995071733e-05 -1.41429496838352e-05 1.59465276817019e-05 -4.23361010597606e-05 0.000146477900541706 1.15696922218221e-05 4.94714557002592e-05 2.10156007967894e-05 -1.69959311616263e-05 -1.05575264092019e-06 1.15696922218221e-05 1.0204995714127e-05 3.14400696145283e-07 2.30260069701297e-06 -1.56670588364114e-06 -1.52242995071733e-05 4.94714557002592e-05 3.14400696145283e-07 8.05710216899568e-05 2.7521692313747e-05 5.7276081611851e-07 -1.41429496838352e-05 2.10156007967894e-05 2.30260069701297e-06 2.7521692313747e-05 4.22508912098198e-05 -5.21375718961254e-06 1.59465276817019e-05 -1.69959311616263e-05 -1.56670588364114e-06 5.7276081611851e-07 -5.21375718961254e-06 3.47851666652955e-05 862 862 0 15 0 860 873 0 29 0 0 0 0 0 0 7 23 0 2316 0 0 0 0 0 1958 +887 922 0.998046837358235 -0.00290821550301249 0.0624023454832641 -0.0136328069968535 -0.00351768688321308 0.994714524806516 0.102618906727453 -0.0200548581172401 -0.0623709573296441 -0.102637987224682 0.992761455365915 -0.000331707076450124 3.23513262823913e-05 -4.22245011552711e-05 -9.25596590763626e-07 -1.11946293372951e-05 -6.53308712856599e-06 1.29380075003583e-05 -4.22245011552711e-05 0.000119122721339323 6.20804430768033e-06 5.54815900592701e-05 2.67446725338591e-05 -1.25929607779991e-05 -9.25596590763626e-07 6.20804430768033e-06 8.70428255093371e-06 3.09629712925361e-06 4.92388226571125e-06 -1.20216150321204e-06 -1.11946293372951e-05 5.54815900592701e-05 3.09629712925361e-06 6.7848707402333e-05 1.8696937282596e-05 -2.50802129252275e-07 -6.53308712856599e-06 2.67446725338591e-05 4.92388226571125e-06 1.8696937282596e-05 2.56891561944175e-05 -1.27812935461484e-06 1.29380075003583e-05 -1.25929607779991e-05 -1.20216150321204e-06 -2.50802129252275e-07 -1.27812935461484e-06 2.35026884759782e-05 915 913 0 12 0 915 927 0 26 0 0 0 0 0 0 4 21 0 2728 0 0 0 0 0 2032 +887 921 0.997799934192949 -0.00323039004125185 0.0662182445004975 -0.0106304218832123 -0.0036312393712424 0.994649868321661 0.103239786653841 -0.0215010581947108 -0.066197472951579 -0.103253106625822 0.992449842836877 0.00127957187580946 4.23339568379725e-05 -5.35754930829333e-05 -4.81653494398894e-07 -1.69549195125759e-05 -1.46012971163873e-05 -3.90260692104714e-06 -5.35754930829333e-05 0.000106557437803919 4.19598805437359e-06 4.73890408658617e-05 2.93543191992069e-05 1.99423620392872e-05 -4.81653494398894e-07 4.19598805437359e-06 9.74186686118323e-06 1.21566196112128e-06 4.66375600850213e-06 2.89943040592998e-06 -1.69549195125759e-05 4.73890408658617e-05 1.21566196112128e-06 6.57782478065453e-05 1.92129988770613e-05 1.86321678178783e-05 -1.46012971163873e-05 2.93543191992069e-05 4.66375600850213e-06 1.92129988770613e-05 3.29228862657683e-05 1.11871502296733e-05 -3.90260692104714e-06 1.99423620392872e-05 2.89943040592998e-06 1.86321678178783e-05 1.11871502296733e-05 4.11021081639323e-05 878 876 0 19 0 877 888 0 32 0 0 0 0 0 0 5 20 0 2595 0 0 0 0 0 1633 +886 929 0.997099998011767 -0.0260804882864985 0.0714940703532207 -0.0261537957499239 0.0158487872315699 0.990008978673767 0.140110806466217 -0.0268825294869729 -0.0744339298184765 -0.138571390539545 0.987551294776993 -0.00446667591511473 4.10139402116683e-05 -4.11518612485546e-05 -7.00570248083711e-06 -7.99229194428232e-06 -6.7116068474706e-06 9.0320047458025e-06 -4.11518612485546e-05 6.83754763361471e-05 1.01084001615899e-05 2.08373712130096e-05 1.01676831362631e-05 1.48960903620581e-06 -7.00570248083711e-06 1.01084001615899e-05 1.13432018811151e-05 -1.21232607144271e-06 1.57757181948796e-06 -3.70638494117908e-06 -7.99229194428232e-06 2.08373712130096e-05 -1.21232607144271e-06 5.51989623338037e-05 1.40688469972004e-05 1.14999375299483e-05 -6.7116068474706e-06 1.01676831362631e-05 1.57757181948796e-06 1.40688469972004e-05 2.49342792487929e-05 5.20862327803182e-06 9.0320047458025e-06 1.48960903620581e-06 -3.70638494117908e-06 1.14999375299483e-05 5.20862327803182e-06 2.84391479699066e-05 908 904 0 4 0 920 922 0 13 0 0 0 0 0 0 22 38 0 2610 0 0 0 0 0 1733 +886 923 0.997374499477246 -0.00420308073775875 0.072294134650223 -0.0193675891780331 -0.00468561534285107 0.992476662556594 0.122344265453607 -0.0250007815931664 -0.0722644643055737 -0.122361793027218 0.989851220540639 0.00314993147237487 4.66182805081696e-05 -5.08930877018052e-05 2.86811993744686e-06 -2.71505383346633e-05 -1.75822515533468e-05 1.10065356171251e-05 -5.08930877018052e-05 7.52254214715227e-05 -5.58299171800942e-07 4.59681294778961e-05 2.69929754834691e-05 -4.02472697977295e-06 2.86811993744686e-06 -5.58299171800942e-07 9.27396540125808e-06 1.85621438975197e-06 5.08020440318777e-06 3.56031274064429e-06 -2.71505383346633e-05 4.59681294778961e-05 1.85621438975197e-06 6.65319012525117e-05 2.3908373298112e-05 9.02664003625424e-06 -1.75822515533468e-05 2.69929754834691e-05 5.08020440318777e-06 2.3908373298112e-05 2.96795519741239e-05 5.0365134170902e-06 1.10065356171251e-05 -4.02472697977295e-06 3.56031274064429e-06 9.02664003625424e-06 5.0365134170902e-06 2.65424404692369e-05 880 884 0 14 0 879 893 0 27 0 0 0 0 0 0 11 24 0 2541 0 0 0 0 0 2127 +886 925 0.997368837194051 -0.00401546606091649 0.0723828614141468 -0.0193163026131254 -0.00492754301821716 0.992400537854157 0.122950769768162 -0.0250971777434391 -0.0723264952419898 -0.122983935939185 0.989769584088598 0.00230317631164392 4.62138214776984e-05 -5.25359484514668e-05 6.42371958829926e-06 -3.62921874277542e-05 -1.88099248262972e-05 2.20012833510569e-06 -5.25359484514668e-05 7.11182120780912e-05 -4.69502415601345e-06 5.28480790456386e-05 2.65130029291602e-05 6.88026008859201e-06 6.42371958829926e-06 -4.69502415601345e-06 1.08173665762646e-05 2.14276341302046e-06 5.40158606280751e-06 6.58065253615587e-06 -3.62921874277542e-05 5.28480790456386e-05 2.14276341302046e-06 7.88659126233655e-05 3.45010834459077e-05 2.11964136277717e-05 -1.88099248262972e-05 2.65130029291602e-05 5.40158606280751e-06 3.45010834459077e-05 3.24380504824325e-05 1.27703552720462e-05 2.20012833510569e-06 6.88026008859201e-06 6.58065253615587e-06 2.11964136277717e-05 1.27703552720462e-05 3.66462049371314e-05 885 888 0 13 0 884 896 0 24 0 0 0 0 0 0 8 23 0 2563 0 0 0 0 0 1914 +887 913 0.998478497732756 -0.00231704453293231 0.055093746196567 -0.0182691639934885 -0.003405122637896 0.994619249386981 0.103542039233829 -0.0204343578593932 -0.0550372120038817 -0.10357210074876 0.993098044123202 0.00397556887653209 3.35469846003853e-05 -3.2786057922041e-05 -7.90887948218762e-08 -4.46752629798668e-06 -6.80237573683194e-06 1.81621147541174e-05 -3.2786057922041e-05 7.49792314357292e-05 3.35817153911119e-06 2.58049105063238e-05 1.31061481201747e-05 -1.70562807227399e-05 -7.90887948218762e-08 3.35817153911119e-06 9.01825894993992e-06 1.632785949233e-06 4.01232946093259e-06 -8.35532717149096e-07 -4.46752629798668e-06 2.58049105063238e-05 1.632785949233e-06 5.19478032367287e-05 8.01005260268104e-06 4.19862526202251e-06 -6.80237573683194e-06 1.31061481201747e-05 4.01232946093259e-06 8.01005260268104e-06 2.44757583304938e-05 -1.25884400150773e-06 1.81621147541174e-05 -1.70562807227399e-05 -8.35532717149096e-07 4.19862526202251e-06 -1.25884400150773e-06 2.91111943237524e-05 915 916 0 14 0 915 930 0 29 0 0 0 0 0 0 6 22 0 2615 0 0 0 0 0 2214 +887 889 0.999661861941356 -0.00049562625574032 0.0259983871529691 -0.0132284319690535 -0.000878280854751796 0.998604306919529 0.0528078291970706 -0.0136166694973977 -0.025988274330575 -0.0528128067459156 0.998266205498782 -0.000600593445355664 3.87544137528186e-05 -5.38137800135598e-05 2.71477909292887e-06 -2.8556738396446e-05 -1.61508718038745e-05 9.67568188032666e-06 -5.38137800135598e-05 0.000108746502559086 -3.32382910679017e-06 8.20717676346383e-05 3.7604814752968e-05 -4.75026469353403e-06 2.71477909292887e-06 -3.32382910679017e-06 8.75131970054624e-06 -1.13722398267316e-06 2.54307241894181e-06 -7.86768468376772e-07 -2.8556738396446e-05 8.20717676346383e-05 -1.13722398267316e-06 0.000120431168320538 4.13114161378093e-05 1.39950531528788e-05 -1.61508718038745e-05 3.7604814752968e-05 2.54307241894181e-06 4.13114161378093e-05 3.61415170516617e-05 5.19186835441802e-06 9.67568188032666e-06 -4.75026469353403e-06 -7.86768468376772e-07 1.39950531528788e-05 5.19186835441802e-06 3.06001103122868e-05 839 842 0 10 0 840 856 0 26 0 0 0 0 0 0 12 29 0 2582 0 0 0 0 0 2424 +887 919 0.997558872404675 -0.00298984893998579 0.0697664453016535 -0.0114683805791203 -0.00414288086019133 0.994789196959828 0.101868985222192 -0.0215881013015316 -0.0697074789738577 -0.101909344102182 0.99234840301165 0.00246540888241155 3.85961923907171e-05 -4.65001758318306e-05 -3.74714457741083e-07 -1.30542798420613e-05 -9.51104935061639e-06 1.25506096702762e-05 -4.65001758318306e-05 0.000136186227119865 5.59934547933845e-06 6.84714756368684e-05 2.86293979963079e-05 -1.67850130882841e-06 -3.74714457741083e-07 5.59934547933845e-06 9.38933656974145e-06 2.28056891510843e-06 3.99192961190761e-06 -1.01684552617573e-06 -1.30542798420613e-05 6.84714756368684e-05 2.28056891510843e-06 8.60426624606691e-05 1.40642513563229e-05 1.16951144060687e-05 -9.51104935061639e-06 2.86293979963079e-05 3.99192961190761e-06 1.40642513563229e-05 3.03048428837161e-05 -6.60523670130071e-07 1.25506096702762e-05 -1.67850130882841e-06 -1.01684552617573e-06 1.16951144060687e-05 -6.60523670130071e-07 3.22007197611901e-05 900 901 0 14 0 901 911 0 25 0 0 0 0 0 0 4 16 0 2459 0 0 0 0 0 2069 +887 926 0.997975661933755 -0.00284786160221927 0.0635332029113773 -0.0134199771120901 -0.00375666616705277 0.994612700831071 0.10359277390258 -0.0201404725749765 -0.063485948423198 -0.103621740140843 0.992588570014279 0.00191833359543648 2.16154796420564e-05 -1.92289350693371e-05 1.53942090775603e-06 -1.387341469178e-06 1.08374358467186e-06 1.02669150064209e-05 -1.92289350693371e-05 4.50864448239879e-05 1.49877198568144e-06 9.93036778342573e-06 4.22090650832279e-06 -1.10053473987199e-05 1.53942090775603e-06 1.49877198568144e-06 8.57698239426482e-06 -9.10253501721526e-08 3.66731922507898e-06 2.89956105718568e-07 -1.387341469178e-06 9.93036778342573e-06 -9.10253501721526e-08 3.67206151045211e-05 7.1373166120522e-07 -4.25763221327429e-06 1.08374358467186e-06 4.22090650832279e-06 3.66731922507898e-06 7.1373166120522e-07 1.62200055839287e-05 1.00748578030221e-06 1.02669150064209e-05 -1.10053473987199e-05 2.89956105718568e-07 -4.25763221327429e-06 1.00748578030221e-06 2.22583756786693e-05 918 920 0 14 0 916 929 0 24 0 0 0 0 0 0 5 15 0 2641 0 0 0 0 0 2220 +887 927 0.997974998875835 -0.00262606082212238 0.0635531700494615 -0.0117218123062163 -0.00398979514469085 0.994595498765454 0.10374909816573 -0.0196234925129804 -0.0634821483054934 -0.103792570254606 0.992570964317646 0.00080061487107715 1.51846266812281e-05 -1.02608968764144e-05 2.70817093676061e-06 -2.8551750080652e-06 1.26684137352046e-06 6.20863963726102e-06 -1.02608968764144e-05 2.35207812406957e-05 -4.12116276285126e-07 4.21700572326648e-06 1.57192246006451e-06 -5.44177773778122e-06 2.70817093676061e-06 -4.12116276285126e-07 8.32362674716968e-06 -3.29157356718117e-07 3.80863725562345e-06 1.07103698447854e-06 -2.8551750080652e-06 4.21700572326648e-06 -3.29157356718117e-07 3.85793668240633e-05 3.80609582987284e-06 -3.40593648969293e-06 1.26684137352046e-06 1.57192246006451e-06 3.80863725562345e-06 3.80609582987284e-06 1.89426552691171e-05 2.79300405009636e-06 6.20863963726102e-06 -5.44177773778122e-06 1.07103698447854e-06 -3.40593648969293e-06 2.79300405009636e-06 2.15961259232091e-05 904 907 0 13 0 903 916 0 23 0 0 0 0 0 0 4 15 0 2685 0 0 0 0 0 2209 +887 914 0.998660630726566 -0.00223744975003393 0.0516907966221548 -0.0223536154801877 -0.00294445523181851 0.994987616130428 0.0999548594640427 -0.0241374814972744 -0.051655346482283 -0.0999731842330972 0.993648372219313 -0.000579186835751127 4.52087238513974e-05 -4.56134574004927e-05 -1.7954712682287e-06 -1.08970579444534e-05 -9.10850418177181e-06 7.12686534203909e-06 -4.56134574004927e-05 6.23654576066694e-05 2.98672507774053e-06 2.26303013546523e-05 1.3054241033564e-05 -2.02419166166811e-07 -1.7954712682287e-06 2.98672507774053e-06 8.9658451533073e-06 -5.74531831113893e-07 5.09372399452551e-06 -1.03020801576189e-07 -1.08970579444534e-05 2.26303013546523e-05 -5.74531831113893e-07 5.31530888457428e-05 9.01942725840213e-06 1.35789663566785e-05 -9.10850418177181e-06 1.3054241033564e-05 5.09372399452551e-06 9.01942725840213e-06 2.5681978960688e-05 6.07522857222332e-06 7.12686534203909e-06 -2.02419166166811e-07 -1.03020801576189e-07 1.35789663566785e-05 6.07522857222332e-06 3.51039483230031e-05 937 940 0 16 0 939 954 0 32 0 0 0 0 0 0 6 19 0 2768 0 0 0 0 0 1515 +887 923 0.99837416059189 -0.00272813872474827 0.0569349867966688 -0.018758386562906 -0.0030292841089534 0.99490290624725 0.100792016442589 -0.0236699298125619 -0.0569197584343571 -0.10080061706098 0.993277089587744 0.00091825739725126 4.98111941106679e-05 -6.81883689281009e-05 -1.06559215084376e-06 -2.9930082441417e-05 -2.03808222226441e-05 7.76670647323012e-06 -6.81883689281009e-05 0.000150774174157139 4.32609168766261e-06 8.41350943925695e-05 4.45545490549693e-05 5.91628126175862e-06 -1.06559215084376e-06 4.32609168766261e-06 8.83642654874919e-06 3.23955172595623e-06 4.74632477158374e-06 6.90069601998366e-07 -2.9930082441417e-05 8.41350943925695e-05 3.23955172595623e-06 8.95732020370814e-05 3.16089828242912e-05 1.79440583087204e-05 -2.03808222226441e-05 4.45545490549693e-05 4.74632477158374e-06 3.16089828242912e-05 3.53958978223413e-05 5.26525534898042e-06 7.76670647323012e-06 5.91628126175862e-06 6.90069601998366e-07 1.79440583087204e-05 5.26525534898042e-06 3.23164508360471e-05 893 895 0 12 0 896 910 0 29 0 0 0 0 0 0 5 17 0 2616 0 0 0 0 0 2070 +887 918 0.99757027560211 -0.00314222490521554 0.0695964917059475 -0.0107024069233893 -0.00393141400251689 0.994851397924317 0.10126815902332 -0.0242555287873183 -0.0695563743956784 -0.10129571792863 0.992421829823514 0.00324540310947999 5.70433919306372e-05 -6.63160561334606e-05 -2.69064830715203e-06 -2.82875487843246e-05 -1.67238363956598e-05 -4.92179306454663e-06 -6.63160561334606e-05 0.000133422039161905 6.8033865260076e-06 7.27414779117181e-05 3.37286929930933e-05 3.21862136434387e-05 -2.69064830715203e-06 6.8033865260076e-06 9.97817202244982e-06 1.30619667959613e-06 3.95762595614925e-06 9.28487634383824e-07 -2.82875487843246e-05 7.27414779117181e-05 1.30619667959613e-06 8.17039061131777e-05 1.9704470920933e-05 3.01947842506698e-05 -1.67238363956598e-05 3.37286929930933e-05 3.95762595614925e-06 1.9704470920933e-05 3.51703307885774e-05 1.66655526605497e-05 -4.92179306454663e-06 3.21862136434387e-05 9.28487634383824e-07 3.01947842506698e-05 1.66655526605497e-05 4.68218913622121e-05 913 917 0 17 0 915 926 0 26 0 0 0 0 0 0 6 17 0 2406 0 0 0 0 0 1446 +887 916 0.997695287314911 -0.00287741370948883 0.0677925818947898 -0.0112914083252981 -0.00408569336194236 0.994740081574488 0.102349778792795 -0.0205066487736311 -0.0677305011008298 -0.102390871661132 0.992435735260024 0.000622625732931229 4.05691306905173e-05 -4.68532905770833e-05 -2.78278980823391e-06 -1.58038280139975e-05 -1.18902437125605e-05 1.41830045761783e-05 -4.68532905770833e-05 9.65958314701479e-05 7.15751265634801e-06 4.02418274375394e-05 2.2730850492302e-05 -6.27912994081317e-06 -2.78278980823391e-06 7.15751265634801e-06 9.66891761378861e-06 -2.48150017955502e-07 4.93002940509527e-06 -6.5429825778249e-07 -1.58038280139975e-05 4.02418274375394e-05 -2.48150017955502e-07 6.08791111863725e-05 1.28551871547106e-05 2.68935099864733e-06 -1.18902437125605e-05 2.2730850492302e-05 4.93002940509527e-06 1.28551871547106e-05 2.72068680378502e-05 1.31621119974418e-06 1.41830045761783e-05 -6.27912994081317e-06 -6.5429825778249e-07 2.68935099864733e-06 1.31621119974418e-06 3.50703371540072e-05 898 898 0 11 0 898 907 0 19 0 0 0 0 0 0 5 15 0 2590 0 0 0 0 0 2092 +887 891 0.997892133673535 -0.0027086170094596 0.0648378974549268 -0.00891593752022538 -0.00379063587535583 0.994989664525066 0.0999059486114652 -0.0184441353533084 -0.0647836447889435 -0.0999411370867489 0.992882091935224 0.00242079235694476 4.85385832761618e-05 -5.87924219579348e-05 -6.37583220478363e-06 -1.43619505956517e-05 -1.1681396628095e-05 -1.75149737145688e-06 -5.87924219579348e-05 9.88118152266624e-05 9.35287925291696e-06 4.01190477046689e-05 2.16116073603367e-05 2.18986294950017e-05 -6.37583220478363e-06 9.35287925291696e-06 1.11831688827587e-05 -4.19590962997717e-07 3.58317381604335e-06 -1.94092380121131e-06 -1.43619505956517e-05 4.01190477046689e-05 -4.19590962997717e-07 6.68145377241896e-05 1.62322608851496e-05 2.060990809688e-05 -1.1681396628095e-05 2.16116073603367e-05 3.58317381604335e-06 1.62322608851496e-05 2.78070179439524e-05 8.06044759423602e-06 -1.75149737145688e-06 2.18986294950017e-05 -1.94092380121131e-06 2.060990809688e-05 8.06044759423602e-06 4.53029418771536e-05 901 904 0 12 0 902 915 0 25 0 0 0 0 0 0 5 18 0 2670 0 0 0 0 0 1612 +887 928 0.997757642373265 -0.00321643648213012 0.0668531347215631 -0.0117119874713949 -0.00370928380925256 0.994652221582897 0.103214336764953 -0.0203229597415296 -0.0668276013288332 -0.10323087055994 0.992409924912116 0.000390118287852698 3.90909977202636e-05 -3.94823482056152e-05 -2.71467316933432e-06 -4.41507024700899e-06 -6.69432644601042e-06 1.07220996860299e-05 -3.94823482056152e-05 6.67322141740336e-05 5.62973217632485e-06 2.07002282572068e-05 1.25567629244188e-05 -1.1927139458071e-06 -2.71467316933432e-06 5.62973217632485e-06 9.41609479311328e-06 -2.07930284884991e-07 3.1898806789994e-06 -6.02638735514269e-07 -4.41507024700899e-06 2.07002282572068e-05 -2.07930284884991e-07 5.33467695872614e-05 9.90650588479934e-06 8.30416697840811e-06 -6.69432644601042e-06 1.25567629244188e-05 3.1898806789994e-06 9.90650588479934e-06 2.42838088555667e-05 3.13215400765046e-06 1.07220996860299e-05 -1.1927139458071e-06 -6.02638735514269e-07 8.30416697840811e-06 3.13215400765046e-06 3.22498166145206e-05 900 898 0 13 0 900 912 0 26 0 0 0 0 0 0 5 20 0 2633 0 0 0 0 0 2082 +887 917 0.997755253855265 -0.00275883916526796 0.0669092087135774 -0.00942986624705125 -0.00418132106395421 0.994634855214801 0.103363539732309 -0.0196594262511817 -0.0668353945030402 -0.103411283708755 0.992390616865824 0.0016222213529234 3.02484239705113e-05 -2.63181007610836e-05 -1.84685743846821e-06 -6.02596565527255e-06 -8.10336188291884e-06 1.48150449862966e-05 -2.63181007610836e-05 4.31643059236383e-05 3.52322328739082e-06 1.27544376116891e-05 6.53164134641014e-06 -9.50313269191246e-06 -1.84685743846821e-06 3.52322328739082e-06 9.08024188058393e-06 -1.12921388332836e-07 2.29959922907014e-06 -5.17559873130016e-07 -6.02596565527255e-06 1.27544376116891e-05 -1.12921388332836e-07 4.909715458024e-05 1.17875067959626e-05 3.51548925404946e-07 -8.10336188291884e-06 6.53164134641014e-06 2.29959922907014e-06 1.17875067959626e-05 2.94627923439169e-05 -3.40781245123017e-06 1.48150449862966e-05 -9.50313269191246e-06 -5.17559873130016e-07 3.51548925404946e-07 -3.40781245123017e-06 2.74832530784658e-05 921 919 0 11 0 922 934 0 27 0 0 0 0 0 0 6 21 0 2359 0 0 0 0 0 2207 +887 915 0.997893357775428 -0.00261484505794327 0.0648229056198904 -0.0129966674390806 -0.00416336854330626 0.994546620529599 0.104209816982497 -0.0192069554885608 -0.064741894242097 -0.104260165827971 0.992440580060826 0.00085683324794091 2.55462339035376e-05 -2.38492814747151e-05 7.76617940954429e-08 -6.57213110804164e-06 -1.97915767971567e-06 1.07883939661507e-05 -2.38492814747151e-05 5.65204307320676e-05 3.31868766851142e-06 2.85133912452703e-05 8.34096957413142e-06 -9.68875638823031e-06 7.76617940954429e-08 3.31868766851142e-06 8.51660746862397e-06 8.09837072506227e-07 3.74103012449537e-06 -5.75388572665425e-07 -6.57213110804164e-06 2.85133912452703e-05 8.09837072506227e-07 5.52848085260901e-05 9.89914048665634e-06 1.89539294661464e-06 -1.97915767971567e-06 8.34096957413142e-06 3.74103012449537e-06 9.89914048665634e-06 2.07896045682445e-05 2.07816558500183e-06 1.07883939661507e-05 -9.68875638823031e-06 -5.75388572665425e-07 1.89539294661464e-06 2.07816558500183e-06 2.3162711659366e-05 915 910 0 9 0 912 918 0 18 0 0 0 0 0 0 3 13 0 2695 0 0 0 0 0 2201 +888 921 0.999011421532156 -0.00134358176075279 0.0444339333882617 -0.00831843757048809 -0.00173063685735705 0.997609933372414 0.0690755074737548 -0.0160343161489129 -0.0444205419188945 -0.06908411991725 0.996621392420858 0.00210298664561013 3.84264989314426e-05 -4.84861653752331e-05 -7.76561387401098e-07 -1.01697423220678e-05 -8.27628701772998e-06 7.21520373362087e-06 -4.84861653752331e-05 0.00010436041090326 4.7135228542555e-06 4.27546703831609e-05 2.09980124350517e-05 1.17827299769188e-06 -7.76561387401098e-07 4.7135228542555e-06 9.3688468969658e-06 1.51357955360353e-06 5.30123567926037e-06 1.52083514775908e-06 -1.01697423220678e-05 4.27546703831609e-05 1.51357955360353e-06 5.97375631249502e-05 1.21598125510288e-05 9.28066484733163e-06 -8.27628701772998e-06 2.09980124350517e-05 5.30123567926037e-06 1.21598125510288e-05 2.45937998643985e-05 1.91099304248674e-06 7.21520373362087e-06 1.17827299769188e-06 1.52083514775908e-06 9.28066484733163e-06 1.91099304248674e-06 2.70369219365907e-05 936 931 0 22 0 935 945 0 37 0 0 0 0 0 0 10 30 0 2757 0 0 0 0 0 2298 +888 920 0.999139539896859 -0.00144796921172772 0.0414497671869688 -0.0104372651767466 -0.00138792893532524 0.997663365203445 0.0683072718252513 -0.0178391631241005 -0.0414518210451907 -0.0683060254743326 0.996802906002956 0.00302721122460308 3.47800057884707e-05 -4.19921859107617e-05 -3.54879422584013e-06 -2.90958643941457e-06 -5.49871249279387e-06 9.51644015979222e-06 -4.19921859107617e-05 0.00010271424464958 7.64062719800138e-06 2.97619219504048e-05 1.04195422359717e-05 -1.01188943357696e-07 -3.54879422584013e-06 7.64062719800138e-06 1.01841463352249e-05 -1.14989802180108e-06 4.61148977465252e-06 -8.41853957850795e-07 -2.90958643941457e-06 2.97619219504048e-05 -1.14989802180108e-06 4.89142326507759e-05 5.56717016006358e-06 8.1821707417849e-06 -5.49871249279387e-06 1.04195422359717e-05 4.61148977465252e-06 5.56717016006358e-06 2.24637315579945e-05 -1.80056689698935e-06 9.51644015979222e-06 -1.01188943357696e-07 -8.41853957850795e-07 8.1821707417849e-06 -1.80056689698935e-06 2.52642035596684e-05 946 949 0 19 0 946 957 0 29 0 0 0 0 0 0 5 19 0 2603 0 0 0 0 0 1722 +887 924 0.997712601258714 -0.00314078455570957 0.0675255563616154 -0.0103374059030576 -0.0038255361776028 0.994695785845413 0.102789390961962 -0.0213749564331501 -0.0674902256813899 -0.102812592097232 0.992408504771963 0.00214017101489359 2.96002917014799e-05 -3.23327121563186e-05 -4.70219256258122e-07 -5.06160947256642e-06 -7.13147939351374e-06 1.58996986051382e-05 -3.23327121563186e-05 0.000137542200328158 7.72010349522845e-06 5.52306974955035e-05 2.18875124300016e-05 -2.96103140244175e-05 -4.70219256258122e-07 7.72010349522845e-06 1.04469636322331e-05 1.084408783969e-07 4.3676335526168e-06 -1.40722520622927e-06 -5.06160947256642e-06 5.52306974955035e-05 1.084408783969e-07 7.35062864916813e-05 1.17534154531066e-05 -8.38841739836543e-06 -7.13147939351374e-06 2.18875124300016e-05 4.3676335526168e-06 1.17534154531066e-05 2.71734067700598e-05 -6.14951455245955e-06 1.58996986051382e-05 -2.96103140244175e-05 -1.40722520622927e-06 -8.38841739836543e-06 -6.14951455245955e-06 3.1239973773889e-05 883 883 0 17 0 883 891 0 26 0 0 0 0 0 0 5 16 0 2659 0 0 0 0 0 2197 +888 926 0.999141875844783 -0.00100797986181968 0.0414064718367291 -0.0121407925650587 -0.00181611589199493 0.997676164500676 0.0681100030119421 -0.0161993705141194 -0.0413789035189977 -0.0681267551246798 0.996818203876588 -0.00184484019159756 3.41721921899087e-05 -3.43551026459529e-05 -2.03711170699931e-06 -8.61564788519313e-06 -8.76822534642101e-06 9.97716743475321e-06 -3.43551026459529e-05 6.19986967199457e-05 5.53540489440067e-06 2.04773252368565e-05 1.54281673313188e-05 -8.93547166722941e-06 -2.03711170699931e-06 5.53540489440067e-06 1.02962418427073e-05 -2.8032400184465e-06 4.38261654060887e-06 -2.31031558700947e-06 -8.61564788519313e-06 2.04773252368565e-05 -2.8032400184465e-06 4.78876006099654e-05 8.13470637231003e-06 7.45267960900305e-06 -8.76822534642101e-06 1.54281673313188e-05 4.38261654060887e-06 8.13470637231003e-06 2.3337536528378e-05 -2.30242248924254e-07 9.97716743475321e-06 -8.93547166722941e-06 -2.31031558700947e-06 7.45267960900305e-06 -2.30242248924254e-07 2.69480247226897e-05 941 947 0 19 0 939 956 0 30 0 0 0 0 0 0 7 22 0 2801 0 0 0 0 0 1784 +887 925 0.998508160896809 -0.00225666068108545 0.0545560272109479 -0.0177498773049536 -0.00329000315078389 0.994843773575396 0.101365882117869 -0.0219846079318519 -0.0545034723824003 -0.101394150032615 0.99335220231166 0.00184616888278823 3.92406183936906e-05 -5.00024933839661e-05 4.08832700529031e-06 -2.8000795689275e-05 -1.49715918640474e-05 2.5413576072268e-06 -5.00024933839661e-05 9.54753014837227e-05 -1.60705127161628e-06 6.49061635549601e-05 3.06153839675142e-05 1.10569987251004e-05 4.08832700529031e-06 -1.60705127161628e-06 1.03636972910984e-05 -3.85170807356425e-06 2.61464747832337e-06 1.22430837385085e-07 -2.8000795689275e-05 6.49061635549601e-05 -3.85170807356425e-06 0.000110819167316381 3.87090843840764e-05 2.64226375719251e-05 -1.49715918640474e-05 3.06153839675142e-05 2.61464747832337e-06 3.87090843840764e-05 3.86724716934246e-05 1.14299410418358e-05 2.5413576072268e-06 1.10569987251004e-05 1.22430837385085e-07 2.64226375719251e-05 1.14299410418358e-05 3.40319642421491e-05 907 910 0 8 0 910 922 0 22 0 0 0 0 0 0 4 13 0 2619 0 0 0 0 0 1638 +887 929 0.997763737651199 -0.0245838724067973 0.0621543003001028 -0.019491726995345 0.0170957897634188 0.992835827907554 0.118257146910819 -0.0248508320966135 -0.0646162348073148 -0.116930116054883 0.991035867241301 -0.00577090611995218 2.40797777188204e-05 -2.45876164012083e-05 -4.92398029919635e-07 -3.33946003053014e-06 -3.4116337369818e-06 9.15027140797839e-06 -2.45876164012083e-05 7.00031296839395e-05 7.10479460295674e-06 1.7883604671582e-05 3.20692662041757e-06 -1.66244476614566e-06 -4.92398029919635e-07 7.10479460295674e-06 1.03318524169682e-05 -6.65992378096497e-07 1.64501888128548e-06 -9.6454503297632e-07 -3.33946003053014e-06 1.7883604671582e-05 -6.65992378096497e-07 4.81682067444209e-05 5.76342637142281e-06 -1.2768120382299e-07 -3.4116337369818e-06 3.20692662041757e-06 1.64501888128548e-06 5.76342637142281e-06 2.55013758102042e-05 -2.57649800777274e-06 9.15027140797839e-06 -1.66244476614566e-06 -9.6454503297632e-07 -1.2768120382299e-07 -2.57649800777274e-06 2.61618278598976e-05 900 900 0 0 0 917 919 0 11 0 0 0 0 0 0 35 48 0 2762 0 0 0 0 0 1686 +888 919 0.999151837285691 -0.000964218916050781 0.0411664466587734 -0.0110419375123941 -0.00186323731628589 0.997643198106473 0.0685899235937139 -0.0157013410259012 -0.0411355612011178 -0.0686084510375379 0.99679523777499 0.00325632542555996 5.44657642521055e-05 -6.47733410655947e-05 -3.44893726174653e-06 -2.20700309647776e-05 -1.76710507647895e-05 -1.40592000577316e-06 -6.47733410655947e-05 0.000129863900287779 8.60593858770395e-06 5.39237810248729e-05 3.15055700293085e-05 1.68055298854183e-05 -3.44893726174653e-06 8.60593858770395e-06 1.02941392294735e-05 2.70843242838704e-06 4.74895871654825e-06 -9.08054329755482e-07 -2.20700309647776e-05 5.39237810248729e-05 2.70843242838704e-06 5.91058980941429e-05 1.6072562251637e-05 2.10650881080767e-05 -1.76710507647895e-05 3.15055700293085e-05 4.74895871654825e-06 1.6072562251637e-05 3.24243354397838e-05 7.13859999702836e-06 -1.40592000577316e-06 1.68055298854183e-05 -9.08054329755482e-07 2.10650881080767e-05 7.13859999702836e-06 3.92087658372431e-05 943 947 0 21 0 943 956 0 33 0 0 0 0 0 0 9 23 0 2617 0 0 0 0 0 1914 +888 890 0.999551717272416 -0.000639686846542327 0.0299325123987759 -0.00587669335280829 -0.000653304197976391 0.999067649796418 0.0431671671978375 -0.00774213265361517 -0.0299322182838062 -0.0431673711383901 0.998619367115224 -0.00040923973785983 2.67430845894551e-05 -2.59819905308631e-05 2.36513664985417e-06 -9.4557949763663e-06 -6.49381332051251e-06 9.64844452371599e-06 -2.59819905308631e-05 3.57236787171006e-05 -8.24030975756499e-07 1.43980906470534e-05 9.69328043108508e-06 -7.02001125071108e-06 2.36513664985417e-06 -8.24030975756499e-07 8.6975063238839e-06 1.68680401124587e-06 5.0370025226609e-06 2.27283533812675e-06 -9.4557949763663e-06 1.43980906470534e-05 1.68680401124587e-06 3.43174050126287e-05 1.05995716972753e-05 -2.18791900558681e-07 -6.49381332051251e-06 9.69328043108508e-06 5.0370025226609e-06 1.05995716972753e-05 2.16546928070832e-05 6.91375885722827e-07 9.64844452371599e-06 -7.02001125071108e-06 2.27283533812675e-06 -2.18791900558681e-07 6.91375885722827e-07 2.49565410573756e-05 902 907 0 19 0 895 913 0 30 0 0 0 0 0 0 11 29 0 2696 0 0 0 0 0 2416 +888 922 0.999229709634249 -0.00104604211762119 0.039228729015124 -0.00912529342369933 -0.00171481714163145 0.997525910067334 0.070278859883382 -0.0132850429498962 -0.0392051882590128 -0.0702919948516574 0.996755731698268 0.00157502627151658 4.96622832885981e-05 -6.4890475390347e-05 -4.57502664583442e-06 -1.42242896252372e-05 -7.70177292335138e-06 7.60801991100651e-06 -6.4890475390347e-05 0.000142960216366412 1.05857179311684e-05 5.05179934874997e-05 1.61779696188812e-05 6.98116497949386e-06 -4.57502664583442e-06 1.05857179311684e-05 9.92263528732015e-06 2.79623751735483e-06 4.39841270814319e-06 4.57158853787924e-07 -1.42242896252372e-05 5.05179934874997e-05 2.79623751735483e-06 5.47246231202003e-05 8.50297923464565e-06 1.10907007560755e-05 -7.70177292335138e-06 1.61779696188812e-05 4.39841270814319e-06 8.50297923464565e-06 2.28581254246972e-05 4.12010614852491e-07 7.60801991100651e-06 6.98116497949386e-06 4.57158853787924e-07 1.10907007560755e-05 4.12010614852491e-07 2.92011954874851e-05 942 939 0 15 0 941 954 0 33 0 0 0 0 0 0 8 27 0 2879 0 0 0 0 0 1848 +888 918 0.99909246612895 -0.00113218485922093 0.0425788947932959 -0.0113887015146754 -0.00175560870677957 0.997702571840024 0.0677236737180632 -0.0184089763332559 -0.0425577485593715 -0.0677369640687162 0.996795135289248 0.00239755469977208 4.15964342869275e-05 -4.19487481773454e-05 -4.28544770709318e-06 -1.65114159730028e-06 -8.13277590350064e-06 1.91140793028824e-05 -4.19487481773454e-05 8.99964403210457e-05 7.2974529980295e-06 2.61577759187826e-05 1.2473829494019e-05 -1.07961017091894e-05 -4.28544770709318e-06 7.2974529980295e-06 9.92763174345308e-06 -1.89839339428909e-06 3.6648493053732e-06 -2.76097509025884e-06 -1.65114159730028e-06 2.61577759187826e-05 -1.89839339428909e-06 4.72062957438446e-05 3.66629903207047e-06 8.78129100805529e-06 -8.13277590350064e-06 1.2473829494019e-05 3.6648493053732e-06 3.66629903207047e-06 2.33574241037663e-05 -4.44584091934648e-06 1.91140793028824e-05 -1.07961017091894e-05 -2.76097509025884e-06 8.78129100805529e-06 -4.44584091934648e-06 2.88939723335099e-05 935 939 0 22 0 935 950 0 33 0 0 0 0 0 0 7 25 0 2549 0 0 0 0 0 1761 +888 916 0.999190201819015 -0.000668953975463244 0.0402304994929761 -0.00929764061268766 -0.00218504592926074 0.997484205424015 0.0708553844383595 -0.0124757999477878 -0.0401766868116655 -0.0708859113660776 0.996674982833741 0.00254140512205302 4.45512743109927e-05 -5.14825730655817e-05 -3.17287173746615e-06 -1.1403837633231e-05 -1.06783591722999e-05 5.33985881346451e-06 -5.14825730655817e-05 0.000110515328036164 9.20798628741861e-06 2.84248833522544e-05 1.42933358477558e-05 6.09386930985044e-06 -3.17287173746615e-06 9.20798628741861e-06 1.025689443569e-05 -1.9609374337463e-06 2.9771948455896e-06 -4.67830638359553e-09 -1.1403837633231e-05 2.84248833522544e-05 -1.9609374337463e-06 6.40126501157713e-05 2.03863290561779e-05 9.0375042127766e-06 -1.06783591722999e-05 1.42933358477558e-05 2.9771948455896e-06 2.03863290561779e-05 3.47357017734198e-05 5.37944450416037e-06 5.33985881346451e-06 6.09386930985044e-06 -4.67830638359553e-09 9.0375042127766e-06 5.37944450416037e-06 3.14922512260763e-05 920 924 0 18 0 919 933 0 27 0 0 0 0 0 0 9 24 0 2703 0 0 0 0 0 1875 +888 927 0.999081154084333 -0.00111864666343514 0.0428438581731246 -0.0117145658111253 -0.00185682398484108 0.997590908979847 0.0693464528685642 -0.0148996734394686 -0.0428182175972534 -0.0693622876670389 0.996672199517669 -0.00145704376595754 3.28789455632715e-05 -3.72064976340505e-05 -1.99613019185167e-06 -7.45989319546455e-06 -7.13088426893298e-06 1.0906565068459e-05 -3.72064976340505e-05 7.9825678800854e-05 5.77287394984269e-06 2.76311499410812e-05 1.5306904349575e-05 -6.53571634939456e-06 -1.99613019185167e-06 5.77287394984269e-06 9.00869438101398e-06 6.29484843835317e-07 5.14703507591465e-06 -1.23447851048967e-06 -7.45989319546455e-06 2.76311499410812e-05 6.29484843835317e-07 4.65385060946847e-05 6.58502231274061e-06 7.03724337414475e-06 -7.13088426893298e-06 1.5306904349575e-05 5.14703507591465e-06 6.58502231274061e-06 2.05264332415535e-05 1.77286137651466e-06 1.0906565068459e-05 -6.53571634939456e-06 -1.23447851048967e-06 7.03724337414475e-06 1.77286137651466e-06 3.18668199770877e-05 921 927 0 20 0 920 936 0 31 0 0 0 0 0 0 8 24 0 2836 0 0 0 0 0 1836 +888 923 0.999098845436499 -0.000980267320453506 0.0424327246760618 -0.00826669348228101 -0.00195880875855266 0.997603144318277 0.0691674021091905 -0.015510252191041 -0.0423988221027593 -0.0691881891818791 0.996702229535999 0.00303718712286264 5.02868479728406e-05 -6.18262398779121e-05 3.00239388724394e-07 -2.65740212266915e-05 -1.76589241340896e-05 4.55953101551936e-07 -6.18262398779121e-05 0.000105862978439923 1.11077469503779e-06 5.77422920676696e-05 3.08675575513783e-05 1.11436919449574e-05 3.00239388724394e-07 1.11077469503779e-06 9.21669830373616e-06 -1.27841216758405e-07 3.85025279989043e-06 6.94935248385456e-07 -2.65740212266915e-05 5.77422920676696e-05 -1.27841216758405e-07 7.05168602798215e-05 2.02319578358949e-05 1.81403501263103e-05 -1.76589241340896e-05 3.08675575513783e-05 3.85025279989043e-06 2.02319578358949e-05 2.7838654960422e-05 6.21377485931266e-06 4.55953101551936e-07 1.11436919449574e-05 6.94935248385456e-07 1.81403501263103e-05 6.21377485931266e-06 3.25158766301748e-05 938 943 0 21 0 938 955 0 35 0 0 0 0 0 0 6 24 0 2756 0 0 0 0 0 1907 +888 914 0.999132592610185 -0.000721743127234336 0.0416358195657092 -0.0102293565729694 -0.00225099801021221 0.997451834533813 0.0713075787913862 -0.0133481367307587 -0.0415811903630479 -0.0713394482175887 0.99658501279921 0.00108826888342241 3.67444720200063e-05 -3.67702637891597e-05 -1.93994302467455e-06 -1.94951134273475e-06 -3.20679129820542e-06 1.17798594202197e-05 -3.67702637891597e-05 6.53602046573626e-05 4.90826129237899e-06 1.12394723085402e-05 5.50021302656848e-06 -7.01383694929817e-06 -1.93994302467455e-06 4.90826129237899e-06 1.00115488739864e-05 -2.85444137370571e-06 4.37426072176626e-06 -1.23311895437703e-06 -1.94951134273475e-06 1.12394723085402e-05 -2.85444137370571e-06 4.3967276145122e-05 8.42847509159114e-06 6.87064179664727e-06 -3.20679129820542e-06 5.50021302656848e-06 4.37426072176626e-06 8.42847509159114e-06 2.00511902128941e-05 1.38795762241807e-06 1.17798594202197e-05 -7.01383694929817e-06 -1.23311895437703e-06 6.87064179664727e-06 1.38795762241807e-06 2.79278304104167e-05 990 995 0 22 0 990 1006 0 34 0 0 0 0 0 0 6 24 0 2889 0 0 0 0 0 1852 +888 928 0.999063330846565 -0.0013307909581753 0.0432514734222115 -0.00978318362848593 -0.00168469302487541 0.997572954489957 0.0696086365301799 -0.0167608154177917 -0.0432391346719446 -0.0696163017231194 0.99663631670094 0.00236813441703798 3.61346468654033e-05 -3.44797964702715e-05 -1.85258079869034e-06 -2.52649349731718e-06 -6.36652920124158e-06 1.06948342067452e-05 -3.44797964702715e-05 6.87883045490304e-05 5.68167713093653e-06 1.37361249587333e-05 8.95439337077531e-06 -6.7480935427098e-06 -1.85258079869034e-06 5.68167713093653e-06 9.48917650947483e-06 2.70042026823999e-07 4.75831381662631e-06 -2.83907979186472e-07 -2.52649349731718e-06 1.37361249587333e-05 2.70042026823999e-07 4.22289046468613e-05 1.52676506377123e-06 4.05064906914831e-06 -6.36652920124158e-06 8.95439337077531e-06 4.75831381662631e-06 1.52676506377123e-06 2.36929048685608e-05 1.642805685005e-06 1.06948342067452e-05 -6.7480935427098e-06 -2.83907979186472e-07 4.05064906914831e-06 1.642805685005e-06 2.76440545536248e-05 925 925 0 19 0 925 938 0 34 0 0 0 0 0 0 7 26 0 2771 0 0 0 0 0 1916 +888 929 0.998850168851456 -0.0224059720315005 0.0423829281992211 -0.0139769016897377 0.0186341950030829 0.996000406129759 0.087383967442209 -0.0175889698783387 -0.0441713364299043 -0.0864937188856947 0.995272691090898 -0.00371562804207831 2.85611036263934e-05 -2.54390570591091e-05 -5.69774718546267e-06 5.34672759679708e-06 -5.73898120099701e-06 1.10751861855415e-05 -2.54390570591091e-05 5.93471925941106e-05 9.31482985575693e-06 3.27019000171655e-06 -8.51212806374209e-08 -4.99888429566812e-06 -5.69774718546267e-06 9.31482985575693e-06 1.18755939012735e-05 -4.30848518258724e-06 1.47546628120075e-06 -3.98805129918899e-06 5.34672759679708e-06 3.27019000171655e-06 -4.30848518258724e-06 4.31738627121081e-05 -1.91718539287388e-06 9.48615134606061e-06 -5.73898120099701e-06 -8.51212806374209e-08 1.47546628120075e-06 -1.91718539287388e-06 2.65796192711374e-05 -6.12341758497804e-06 1.10751861855415e-05 -4.99888429566812e-06 -3.98805129918899e-06 9.48615134606061e-06 -6.12341758497804e-06 2.37359495164882e-05 921 921 0 0 0 926 928 0 10 0 0 0 0 0 0 39 54 0 2875 0 0 0 0 0 2204 +889 921 0.999625097589641 -0.000419820615362156 0.0273767788381281 -0.00546957963046999 -0.000827449602354274 0.998962529730997 0.0455321811535858 -0.0117105642824766 -0.0273674915923332 -0.0455377639338857 0.998587668890341 0.000830501936560734 4.2479532615962e-05 -5.10249098004293e-05 -2.58174688432198e-06 -9.07866707636486e-06 -6.06535849177734e-06 8.57935683183524e-06 -5.10249098004293e-05 0.000106109438837901 7.10405389286154e-06 3.99973761503723e-05 1.69790127864228e-05 -4.47203443802772e-06 -2.58174688432198e-06 7.10405389286154e-06 1.03370884094329e-05 1.22433338902107e-06 3.3438099777379e-06 -2.19677833384526e-07 -9.07866707636486e-06 3.99973761503723e-05 1.22433338902107e-06 6.75332798574598e-05 1.44369427873609e-05 7.12345553189662e-06 -6.06535849177734e-06 1.69790127864228e-05 3.3438099777379e-06 1.44369427873609e-05 2.42410038837912e-05 4.15999100221693e-06 8.57935683183524e-06 -4.47203443802772e-06 -2.19677833384526e-07 7.12345553189662e-06 4.15999100221693e-06 2.97558464956186e-05 898 897 0 26 0 898 913 0 41 0 0 0 0 0 0 15 34 0 2797 0 0 0 0 0 1384 +889 922 0.999697336939858 -0.000419815780950797 0.0245979322315214 -0.00668414605391032 -0.000722855605031956 0.998921439768646 0.0464266588320798 -0.00992257790265448 -0.0245908925240775 -0.0464303879506313 0.998618799682653 0.00136755937707471 4.12973410834314e-05 -3.87266889668911e-05 -4.46201581715845e-06 -3.22145583965814e-07 -6.23026857109377e-06 2.14108893575743e-05 -3.87266889668911e-05 6.37834730823123e-05 6.56007188288079e-06 1.8425842444678e-05 1.15927770260497e-05 -1.8787250914224e-05 -4.46201581715845e-06 6.56007188288079e-06 9.95907983873374e-06 -1.35863306400788e-06 3.03855914957998e-06 -4.09587734905526e-06 -3.22145583965814e-07 1.8425842444678e-05 -1.35863306400788e-06 5.48741415184983e-05 1.51621655674223e-05 2.23562272061547e-06 -6.23026857109377e-06 1.15927770260497e-05 3.03855914957998e-06 1.51621655674223e-05 2.09074376782012e-05 -3.32805428153243e-06 2.14108893575743e-05 -1.8787250914224e-05 -4.09587734905526e-06 2.23562272061547e-06 -3.32805428153243e-06 2.70525511406883e-05 931 927 0 19 0 929 946 0 37 0 0 0 0 0 0 14 34 0 2931 0 0 0 0 0 2141 +888 915 0.999122436257407 -0.00105110044681306 0.0418718587468287 -0.0123073743900644 -0.00184348113399109 0.997612814691803 0.0690309607350702 -0.0147133191337601 -0.041844461334474 -0.0690475716484577 0.99673540817264 -0.00256443244798976 3.05196894223802e-05 -3.53727835366709e-05 -1.32651988221378e-06 -9.16232947751983e-06 -4.91766979099341e-06 7.63108073638463e-06 -3.53727835366709e-05 8.73552612775564e-05 7.11042444546518e-06 3.05345663411538e-05 1.34964961572819e-05 -7.65805130028795e-07 -1.32651988221378e-06 7.11042444546518e-06 9.80248336275015e-06 -4.82483553544092e-07 4.59865881269638e-06 -5.56577048891463e-07 -9.16232947751983e-06 3.05345663411538e-05 -4.82483553544092e-07 5.3150962292891e-05 8.86049371462053e-06 9.96457494215848e-06 -4.91766979099341e-06 1.34964961572819e-05 4.59865881269638e-06 8.86049371462053e-06 2.22277934888721e-05 1.75681010233315e-07 7.63108073638463e-06 -7.65805130028795e-07 -5.56577048891463e-07 9.96457494215848e-06 1.75681010233315e-07 2.62539327708363e-05 938 936 0 16 0 934 946 0 28 0 0 0 0 0 0 6 21 0 2865 0 0 0 0 0 1799 +888 917 0.998821832905626 -0.000982882678388838 0.0485178323164352 -0.00442448936375154 -0.00239767224298484 0.99757424801079 0.0695691804862076 -0.0135143955689915 -0.048468518430631 -0.0696035462268111 0.996396582227073 -0.000244217950387458 4.0849085961883e-05 -4.94037110984789e-05 -9.82080956962707e-07 -1.9330249831793e-05 -1.29315811358063e-05 6.28428882504173e-06 -4.94037110984789e-05 0.000137122607139652 7.85095101498115e-06 5.45847340061773e-05 1.96685433362645e-05 1.41369459208834e-05 -9.82080956962707e-07 7.85095101498115e-06 1.03383314512746e-05 2.81395870089063e-07 3.32120547719323e-06 1.3271306064949e-06 -1.9330249831793e-05 5.45847340061773e-05 2.81395870089063e-07 7.26615442791594e-05 2.20299755383139e-05 1.63114020105122e-05 -1.29315811358063e-05 1.96685433362645e-05 3.32120547719323e-06 2.20299755383139e-05 3.65813519390115e-05 1.80482301513676e-06 6.28428882504173e-06 1.41369459208834e-05 1.3271306064949e-06 1.63114020105122e-05 1.80482301513676e-06 3.7704582920904e-05 916 916 0 19 0 916 928 0 34 0 0 0 0 0 0 8 25 0 2485 0 0 0 0 0 1923 +889 927 0.99983154158236 0.000139543775340083 0.0183539909713504 -0.0114839972203452 -0.000990681451276058 0.99892372437698 0.0463725287976116 -0.00964667135608716 -0.0183277660205423 -0.0463828999132006 0.998755585510458 0.00462460998000793 4.81432444359172e-05 -6.06080188508139e-05 -5.61118863051497e-06 -1.04982561279641e-05 -1.00638868265692e-05 1.74500344410964e-05 -6.06080188508139e-05 0.000130415828828979 8.66309549720212e-06 4.778215663419e-05 2.45020585776255e-05 -2.18479474584394e-05 -5.61118863051497e-06 8.66309549720212e-06 9.88580985561477e-06 -1.48382498366759e-06 4.75566584387766e-06 -4.84319131399697e-06 -1.04982561279641e-05 4.778215663419e-05 -1.48382498366759e-06 5.86763756575776e-05 1.35764175865528e-05 4.4390670972423e-06 -1.00638868265692e-05 2.45020585776255e-05 4.75566584387766e-06 1.35764175865528e-05 2.16056751096382e-05 -1.86953486454505e-06 1.74500344410964e-05 -2.18479474584394e-05 -4.84319131399697e-06 4.4390670972423e-06 -1.86953486454505e-06 3.407678864908e-05 905 910 0 23 0 905 923 0 33 0 0 0 0 0 0 11 29 0 2886 0 0 0 0 0 2019 +888 924 0.999188761783174 -0.00103380406829529 0.0402585341928424 -0.0101792434166339 -0.00167608763832156 0.997736747347449 0.0672203371217434 -0.0175738799926308 -0.0402369116165312 -0.0672332822468199 0.99692561242145 -0.000749244116327288 3.46732166504033e-05 -3.24786325190802e-05 -9.6271966609552e-07 -4.06559248265352e-06 -9.42992739692844e-06 1.1784486760782e-05 -3.24786325190802e-05 7.37950027583691e-05 5.14883982323775e-06 2.25933987032546e-05 1.60681815928521e-05 -8.79196446257432e-06 -9.6271966609552e-07 5.14883982323775e-06 9.92940470621763e-06 6.79260830716496e-07 4.23417439885455e-06 -1.03690615986164e-06 -4.06559248265352e-06 2.25933987032546e-05 6.79260830716496e-07 5.06417536692354e-05 8.12204730795575e-06 5.74832841031619e-06 -9.42992739692844e-06 1.60681815928521e-05 4.23417439885455e-06 8.12204730795575e-06 2.68720071580139e-05 -9.30874173347816e-07 1.1784486760782e-05 -8.79196446257432e-06 -1.03690615986164e-06 5.74832841031619e-06 -9.30874173347816e-07 2.7742412648471e-05 931 929 0 20 0 931 940 0 33 0 0 0 0 0 0 9 25 0 2819 0 0 0 0 0 1738 +888 891 0.998921987853037 -0.00104037354868936 0.046408833282209 -0.00459928118030075 -0.00204445056551884 0.997792743208132 0.0663736530791894 -0.0140789212160704 -0.0463754504627376 -0.0663969820403806 0.996714983518512 0.00120134569995276 4.29790699235213e-05 -4.5112273317707e-05 -2.88206508601556e-06 -1.19400722916937e-05 -1.26367335237465e-05 8.80181595179512e-06 -4.5112273317707e-05 8.66505358763722e-05 6.22304206023838e-06 3.41634468086708e-05 1.56700583301686e-05 -2.00750963753126e-06 -2.88206508601556e-06 6.22304206023838e-06 9.06499245628048e-06 -1.68257912600732e-07 2.96485535599122e-06 -1.43409637292469e-06 -1.19400722916937e-05 3.41634468086708e-05 -1.68257912600732e-07 6.80148824724233e-05 2.0367030179945e-05 1.23807496742998e-05 -1.26367335237465e-05 1.56700583301686e-05 2.96485535599122e-06 2.0367030179945e-05 3.47134440052346e-05 3.04109012100175e-06 8.80181595179512e-06 -2.00750963753126e-06 -1.43409637292469e-06 1.23807496742998e-05 3.04109012100175e-06 3.07221984779507e-05 903 905 0 16 0 901 917 0 31 0 0 0 0 0 0 9 27 0 2795 0 0 0 0 0 2364 +889 916 0.999730700100284 -4.69027009417735e-07 0.0232061904839355 -0.00874068611160797 -0.00106107689498461 0.998953192712692 0.0457317492005583 -0.0110875872610238 -0.0231819195240518 -0.0457440571976279 0.998684174220399 0.00243169800788289 3.52447967227522e-05 -3.77008916939141e-05 -3.11553308298265e-07 -1.13162735804774e-05 -8.05285339813565e-06 1.5901825218358e-05 -3.77008916939141e-05 7.55038756249367e-05 3.15608403828047e-06 3.06970135430094e-05 1.70628096970473e-05 -1.54619842774422e-05 -3.11553308298265e-07 3.15608403828047e-06 8.97777682351908e-06 -8.8189631689701e-07 3.79195029626726e-06 -1.3351996923945e-06 -1.13162735804774e-05 3.06970135430094e-05 -8.8189631689701e-07 5.32667443043298e-05 1.18940817999816e-05 -2.24026969005367e-06 -8.05285339813565e-06 1.70628096970473e-05 3.79195029626726e-06 1.18940817999816e-05 2.12851794564573e-05 -2.56214435521818e-06 1.5901825218358e-05 -1.54619842774422e-05 -1.3351996923945e-06 -2.24026969005367e-06 -2.56214435521818e-06 2.5100688571028e-05 923 925 0 21 0 920 935 0 31 0 0 0 0 0 0 8 24 0 2787 0 0 0 0 0 2196 +888 925 0.999244070130203 -0.000747229496559792 0.0388681097778686 -0.0119534010529627 -0.00188628705454213 0.997705676347149 0.0676744065790419 -0.0164905710903436 -0.0388295020670216 -0.0676965658859966 0.996950071335807 0.00100308209922374 4.10613990329058e-05 -4.66325296479946e-05 1.92949263137553e-06 -1.62827559010028e-05 -1.25800681424837e-05 3.9415410211712e-06 -4.66325296479946e-05 8.4563707835531e-05 1.90872209218782e-07 4.2635429427046e-05 2.19769340708906e-05 7.74083828036992e-06 1.92949263137553e-06 1.90872209218782e-07 9.06169940414049e-06 2.92496924408891e-07 3.95995451894687e-06 4.16440320835754e-07 -1.62827559010028e-05 4.2635429427046e-05 2.92496924408891e-07 6.38552184184493e-05 1.58196596792377e-05 1.67554479747427e-05 -1.25800681424837e-05 2.19769340708906e-05 3.95995451894687e-06 1.58196596792377e-05 2.7587939726223e-05 6.49386409172918e-06 3.9415410211712e-06 7.74083828036992e-06 4.16440320835754e-07 1.67554479747427e-05 6.49386409172918e-06 2.85874935183017e-05 931 939 0 20 0 931 948 0 30 0 0 0 0 0 0 8 25 0 2784 0 0 0 0 0 2378 +889 915 0.999864297276417 9.39530950624328e-05 0.0164735607794153 -0.0122828939522152 -0.000853776822454434 0.998935409324145 0.0461228692032544 -0.0111549387050234 -0.0164516897938966 -0.0461306749486608 0.998799931283391 0.00519811530308553 4.8319911105889e-05 -6.52963048849619e-05 -8.70907412686242e-07 -1.8438817159701e-05 -1.19274550117962e-05 2.35450603092674e-05 -6.52963048849619e-05 0.00015282260992255 3.61558372825816e-06 6.57399044406385e-05 3.27332865634528e-05 -3.06305633469683e-05 -8.70907412686242e-07 3.61558372825816e-06 9.19230735200908e-06 -5.97084836181214e-08 4.41794278303432e-06 -1.92734507402834e-06 -1.8438817159701e-05 6.57399044406385e-05 -5.97084836181214e-08 7.63265327445435e-05 2.44583092496542e-05 -3.47569510225182e-06 -1.19274550117962e-05 3.27332865634528e-05 4.41794278303432e-06 2.44583092496542e-05 2.66977801718587e-05 -5.44720178440738e-06 2.35450603092674e-05 -3.06305633469683e-05 -1.92734507402834e-06 -3.47569510225182e-06 -5.44720178440738e-06 3.75170737962437e-05 927 924 0 20 0 922 936 0 28 0 0 0 0 0 0 8 24 0 2904 0 0 0 0 0 1973 +889 920 0.999742479952449 -0.000582761862208876 0.0226855497429506 -0.0102428829059728 -0.000360721813898717 0.999135806006016 0.0415633376484817 -0.0155097393262407 -0.0226901665551601 -0.0415608174284467 0.998878298290827 -0.00181379509749965 3.67884460784e-05 -3.66392047780579e-05 -3.07800683480525e-06 -4.92971080785156e-06 -5.16424889935071e-06 6.91440276949568e-06 -3.66392047780579e-05 7.15802571107566e-05 4.57465066340117e-06 2.68677088198978e-05 1.2916609546598e-05 -3.69843375772361e-06 -3.07800683480525e-06 4.57465066340117e-06 9.09134866728214e-06 5.67569621135868e-07 2.78253000617378e-06 -3.10026307624843e-06 -4.92971080785156e-06 2.68677088198978e-05 5.67569621135868e-07 5.34060978261461e-05 1.08059826436528e-05 4.78648157363311e-06 -5.16424889935071e-06 1.2916609546598e-05 2.78253000617378e-06 1.08059826436528e-05 2.2526380914046e-05 3.40882780878343e-07 6.91440276949568e-06 -3.69843375772361e-06 -3.10026307624843e-06 4.78648157363311e-06 3.40882780878343e-07 2.56642585915551e-05 952 955 0 24 0 949 964 0 31 0 0 0 0 0 0 10 25 0 2702 0 0 0 0 0 2046 +889 926 0.999895280205721 1.38530864456448e-05 0.0144716422846245 -0.0143165712209169 -0.000663727643848817 0.998991134616246 0.0449029222184844 -0.0119089679022236 -0.0144564203016143 -0.0449078252227433 0.99888652966482 0.00427312335974166 5.77384332765859e-05 -7.86131902808501e-05 -3.28928524668534e-06 -2.50701634002216e-05 -1.62539306950643e-05 1.94876793443497e-05 -7.86131902808501e-05 0.000170467703480127 6.982042813765e-06 7.91638084479956e-05 3.82008326797589e-05 -2.0961981669061e-05 -3.28928524668534e-06 6.982042813765e-06 9.26227043687091e-06 5.46084094210768e-07 5.22330529233634e-06 -2.35165940944513e-06 -2.50701634002216e-05 7.91638084479956e-05 5.46084094210768e-07 7.98132189727307e-05 2.41052892024287e-05 1.06165999949884e-06 -1.62539306950643e-05 3.82008326797589e-05 5.22330529233634e-06 2.41052892024287e-05 2.62718569925624e-05 -1.72225620251397e-06 1.94876793443497e-05 -2.0961981669061e-05 -2.35165940944513e-06 1.06165999949884e-06 -1.72225620251397e-06 3.24527315727546e-05 927 931 0 23 0 926 943 0 34 0 0 0 0 0 0 14 31 0 2884 0 0 0 0 0 1828 +889 919 0.999828725099255 5.64952567797481e-05 0.0185072222303514 -0.0135475467849176 -0.000881213659570913 0.999006461542234 0.0445568542353707 -0.0129088487668416 -0.0184863173423978 -0.0445655315816142 0.998835406594082 0.00328024772778363 4.07396648746918e-05 -4.72392988174991e-05 -3.78922261401545e-06 -9.79634503285421e-06 -7.06999992222545e-06 2.24682404466972e-05 -4.72392988174991e-05 0.000106503532586986 4.72234533053936e-06 4.93433410843837e-05 2.22097110113762e-05 -2.06581732628832e-05 -3.78922261401545e-06 4.72234533053936e-06 9.45933351781439e-06 3.86661416519388e-07 2.03482642901529e-06 -3.18387597867832e-06 -9.79634503285421e-06 4.93433410843837e-05 3.86661416519388e-07 6.7910936415988e-05 1.54298104144652e-05 -8.93987997183657e-07 -7.06999992222545e-06 2.22097110113762e-05 2.03482642901529e-06 1.54298104144652e-05 2.49821055810291e-05 -3.79071989521804e-06 2.24682404466972e-05 -2.06581732628832e-05 -3.18387597867832e-06 -8.93987997183657e-07 -3.79071989521804e-06 3.05613397493823e-05 933 939 0 30 0 932 949 0 33 0 0 0 0 0 0 11 29 0 2687 0 0 0 0 0 2194 +889 928 0.99981281315287 -0.000203483126322644 0.0193467632941907 -0.0117418982955811 -0.000693159695031692 0.998926046817288 0.0463278805863334 -0.0109679605346651 -0.0193354127181533 -0.046332619012977 0.998738919953767 0.00195660116191112 3.91900105675161e-05 -6.9941582117293e-05 -2.63730771571485e-06 -1.62992234620204e-05 -6.63660482144281e-06 2.6039298023887e-05 -6.9941582117293e-05 0.000257451863951543 1.33085826468761e-05 0.000109421595165932 3.375538298047e-05 -6.27938792919021e-05 -2.63730771571485e-06 1.33085826468761e-05 9.42034590625492e-06 4.55476632437055e-06 5.12213810958554e-06 -4.51907607249593e-06 -1.62992234620204e-05 0.000109421595165932 4.55476632437055e-06 9.3942690751224e-05 2.26149539363583e-05 -1.66793439002437e-05 -6.63660482144281e-06 3.375538298047e-05 5.12213810958554e-06 2.26149539363583e-05 2.37356875082263e-05 -7.75783489381267e-06 2.6039298023887e-05 -6.27938792919021e-05 -4.51907607249593e-06 -1.66793439002437e-05 -7.75783489381267e-06 4.10376469749288e-05 919 918 0 21 0 915 935 0 35 0 0 0 0 0 0 7 28 0 2801 0 0 0 0 0 2206 +889 918 0.999803844098718 -0.00037862346896849 0.0198022718316763 -0.0133068598098185 -0.000437490261205993 0.999151130009555 0.0411925721811717 -0.0163696687943786 -0.0198010587519507 -0.0411931553161255 0.99895497497505 -0.000758320207118394 5.96415442773081e-05 -8.02030915729e-05 -4.68820703164737e-06 -1.98578244301209e-05 -1.37035059498773e-05 2.52887947739204e-05 -8.02030915729e-05 0.000174569565624868 7.92521708461343e-06 6.63177273302184e-05 3.05547597206324e-05 -2.72186326387544e-05 -4.68820703164737e-06 7.92521708461343e-06 8.82594491329112e-06 1.13008270126214e-06 4.34359070973874e-06 -3.77564022354648e-06 -1.98578244301209e-05 6.63177273302184e-05 1.13008270126214e-06 6.428517176039e-05 1.45530563350807e-05 2.61498181464999e-06 -1.37035059498773e-05 3.05547597206324e-05 4.34359070973874e-06 1.45530563350807e-05 2.42586376965105e-05 -4.57622102756184e-06 2.52887947739204e-05 -2.72186326387544e-05 -3.77564022354648e-06 2.61498181464999e-06 -4.57622102756184e-06 3.510048126744e-05 938 944 0 27 0 937 958 0 37 0 0 0 0 0 0 11 31 0 2604 0 0 0 0 0 2079 +889 923 0.999678286855769 -0.000150038595276891 0.0253633648700989 -0.00548445971588882 -0.0010319847684748 0.998913840522646 0.0465840554238807 -0.00899882595256076 -0.0253428056172058 -0.0465952433271625 0.998592321972651 0.000769430806229575 4.8832698111616e-05 -5.27282358789087e-05 1.71380269223467e-06 -2.24501488294842e-05 -1.70707688133416e-05 2.3528313845578e-05 -5.27282358789087e-05 8.46978175651676e-05 -9.33661154700026e-08 4.43521296935983e-05 2.78705804954971e-05 -2.32788413839972e-05 1.71380269223467e-06 -9.33661154700026e-08 9.53389415362173e-06 -6.12231810390975e-07 4.06658763727334e-06 5.88517201040378e-07 -2.24501488294842e-05 4.43521296935983e-05 -6.12231810390975e-07 7.34354438570467e-05 2.88934520020191e-05 -3.12826704258764e-06 -1.70707688133416e-05 2.78705804954971e-05 4.06658763727334e-06 2.88934520020191e-05 3.18210043979487e-05 -5.12995130639018e-06 2.3528313845578e-05 -2.32788413839972e-05 5.88517201040378e-07 -3.12826704258764e-06 -5.12995130639018e-06 3.11585378601848e-05 953 962 0 27 0 952 973 0 37 0 0 0 0 0 0 14 33 0 2798 0 0 0 0 0 2191 +889 929 0.999467962498799 -0.0216632853552465 0.0243822477658821 -0.0146452605231005 0.0200369535995759 0.997679085652613 0.0650765898139658 -0.0121522254566292 -0.025735431392307 -0.0645534206605962 0.997582349208359 -0.00763096076785409 3.35526712802547e-05 -3.24770128014032e-05 -4.57365957338959e-06 -2.24258952311369e-06 -2.56199892964565e-06 1.26935658262535e-05 -3.24770128014032e-05 4.71836078776612e-05 5.56096453829039e-06 1.37466499782332e-05 7.84995869309329e-06 -9.93773907808669e-06 -4.57365957338959e-06 5.56096453829039e-06 9.90261481597576e-06 -2.10070743151741e-06 2.8006892982666e-06 -4.18725766345041e-06 -2.24258952311369e-06 1.37466499782332e-05 -2.10070743151741e-06 4.87446376952662e-05 1.21912938063243e-05 4.55686833335593e-06 -2.56199892964565e-06 7.84995869309329e-06 2.8006892982666e-06 1.21912938063243e-05 2.24225145678961e-05 2.73705332611785e-07 1.26935658262535e-05 -9.93773907808669e-06 -4.18725766345041e-06 4.55686833335593e-06 2.73705332611785e-07 2.16884738621012e-05 946 946 0 0 0 969 970 0 11 0 0 0 0 0 0 44 64 0 2955 0 0 0 0 0 1653 +889 891 0.999690178979841 -0.000379084061588154 0.0248877951319187 -0.0093233371789432 -0.000655662782992071 0.999135996361594 0.0415551546843561 -0.0115202883876338 -0.0248820448831905 -0.0415585980249576 0.998826194476612 -0.00351481484730567 5.52571260687668e-05 -7.98868236430439e-05 -5.64361845834292e-06 -2.72938154609125e-05 -1.81056332609153e-05 1.53931616864384e-05 -7.98868236430439e-05 0.000173399071499278 9.36487265344512e-06 8.46597674620787e-05 4.81215618624355e-05 -1.93168290317579e-05 -5.64361845834292e-06 9.36487265344512e-06 1.03688388101083e-05 7.04640008375227e-07 5.18538493274853e-06 -4.31714137214526e-06 -2.72938154609125e-05 8.46597674620787e-05 7.04640008375227e-07 9.21021257043077e-05 3.37095329716238e-05 3.36643270281489e-06 -1.81056332609153e-05 4.81215618624355e-05 5.18538493274853e-06 3.37095329716238e-05 3.23755781610766e-05 -8.08821575900525e-07 1.53931616864384e-05 -1.93168290317579e-05 -4.31714137214526e-06 3.36643270281489e-06 -8.08821575900525e-07 3.12448525078275e-05 877 877 0 11 0 877 893 0 31 0 0 0 0 0 0 15 35 0 2865 0 0 0 0 0 1698 +889 925 0.999594751497659 -0.000570406379338545 0.028460629207662 -0.00784223081290883 -0.000769811777062515 0.99889190533326 0.0470570807585642 -0.0110479915892972 -0.0284559337952826 -0.0470599202746089 0.998486666779074 0.000653985835957345 5.09239437850195e-05 -5.23264358724815e-05 4.42702265416671e-06 -3.36508345068642e-05 -1.8562971743998e-05 5.46153263437808e-06 -5.23264358724815e-05 7.0688987045669e-05 -1.5122259867136e-06 4.38822787333822e-05 2.26303548307652e-05 5.09073241103682e-07 4.42702265416671e-06 -1.5122259867136e-06 1.12254737404154e-05 -1.98571700765629e-07 3.29727063997065e-06 3.64468745676286e-06 -3.36508345068642e-05 4.38822787333822e-05 -1.98571700765629e-07 7.25652549570184e-05 2.98285450412439e-05 1.0291205100211e-05 -1.8562971743998e-05 2.26303548307652e-05 3.29727063997065e-06 2.98285450412439e-05 3.2985076339742e-05 7.25951867855322e-06 5.46153263437808e-06 5.09073241103682e-07 3.64468745676286e-06 1.0291205100211e-05 7.25951867855322e-06 3.05297856451011e-05 923 931 0 25 0 923 943 0 37 0 0 0 0 0 0 14 33 0 2848 0 0 0 0 0 1452 +890 926 0.999863476356869 -2.3229647385178e-05 0.016523562204961 -0.00391034298963328 -0.000412087360937528 0.99965292189765 0.0263413349224594 -0.0073322960804895 -0.0165184391382688 -0.0263445478585932 0.999516436066242 -0.00414902693744341 3.88149799275451e-05 -3.81193708968402e-05 -4.15349859190621e-06 -3.75623306511338e-06 -6.79962766299465e-06 1.53382538498254e-05 -3.81193708968402e-05 6.61012739682754e-05 6.43522142723941e-06 1.95581009667667e-05 1.22404715837608e-05 -1.27350163733673e-05 -4.15349859190621e-06 6.43522142723941e-06 1.0244957096035e-05 -4.08983154226469e-06 4.31240942805097e-06 -3.76155733745717e-06 -3.75623306511338e-06 1.95581009667667e-05 -4.08983154226469e-06 4.8192844771486e-05 9.30691320349467e-06 4.16815620633737e-06 -6.79962766299465e-06 1.22404715837608e-05 4.31240942805097e-06 9.30691320349467e-06 2.13420323752375e-05 -1.73735877636752e-06 1.53382538498254e-05 -1.27350163733673e-05 -3.76155733745717e-06 4.16815620633737e-06 -1.73735877636752e-06 2.65109815184587e-05 974 981 0 26 0 974 994 0 38 0 0 0 0 0 0 14 31 0 2891 0 0 0 0 0 1488 +889 917 0.999289453616704 -0.000531271771813874 0.0376869425760867 0.00234520866826772 -0.00142240713068058 0.998656781030459 0.0517939230010358 -0.00517259760940223 -0.0376638374091564 -0.0518107271922244 0.997946433381787 0.00338636624616324 5.19532569979223e-05 -8.06597447983482e-05 -3.06509982316947e-06 -3.29753892933215e-05 -1.60367685104829e-05 1.31342445909585e-05 -8.06597447983482e-05 0.00020320603516134 9.92638987068983e-06 0.000110848258506983 4.33810097749047e-05 -7.40476149061944e-06 -3.06509982316947e-06 9.92638987068983e-06 9.22852649890457e-06 3.19766366823018e-06 3.25929884753559e-06 -5.0321268111446e-07 -3.29753892933215e-05 0.000110848258506983 3.19766366823018e-06 0.000127301614410996 4.86346346152889e-05 8.89018716251709e-06 -1.60367685104829e-05 4.33810097749047e-05 3.25929884753559e-06 4.86346346152889e-05 4.39471203248943e-05 2.46829065573439e-07 1.31342445909585e-05 -7.40476149061944e-06 -5.0321268111446e-07 8.89018716251709e-06 2.46829065573439e-07 3.83243811669244e-05 895 895 0 20 0 894 911 0 33 0 0 0 0 0 0 14 32 0 2533 0 0 0 0 0 2177 +889 924 0.999801178863889 -0.000447725194706327 0.0199349513299366 -0.0104575365741267 -0.000468327935683948 0.998944838536257 0.0459237436487457 -0.0117046045453829 -0.0199344779545784 -0.0459239491324633 0.998746017506331 0.00359323909175166 4.22420863066349e-05 -5.06580078810825e-05 -1.88189787703386e-06 -1.65905913149061e-05 -1.10616997171383e-05 5.92662065316736e-06 -5.06580078810825e-05 0.000103305405616813 4.43100263700771e-06 4.07966947696143e-05 2.09694491107113e-05 2.59673302835581e-07 -1.88189787703386e-06 4.43100263700771e-06 8.86544485244851e-06 -3.42359639722495e-07 3.87126224537246e-06 -1.466362184399e-06 -1.65905913149061e-05 4.07966947696143e-05 -3.42359639722495e-07 5.50662155815324e-05 1.61990016684215e-05 7.41960222897548e-06 -1.10616997171383e-05 2.09694491107113e-05 3.87126224537246e-06 1.61990016684215e-05 2.42355875264738e-05 1.67275525000529e-06 5.92662065316736e-06 2.59673302835581e-07 -1.466362184399e-06 7.41960222897548e-06 1.67275525000529e-06 2.71438455583197e-05 916 917 0 20 0 917 932 0 37 0 0 0 0 0 0 14 33 0 2848 0 0 0 0 0 1956 +890 919 0.999881969494058 0.000328402295200129 0.0153603135585037 -0.00315103591022649 -0.000764431541348492 0.999596644876522 0.0283894909432818 -0.00532139184800229 -0.0153447947233463 -0.0283978820254715 0.999478913019863 0.00390337641848752 4.94088167603484e-05 -7.42610022954325e-05 -2.79348754585728e-06 -2.61264928073091e-05 -1.44561525068249e-05 1.13417048594143e-05 -7.42610022954325e-05 0.000179646157631763 5.95699206421202e-06 8.50210116476053e-05 3.40330423936684e-05 -3.25640074247578e-06 -2.79348754585728e-06 5.95699206421202e-06 9.91462545468069e-06 2.77440858381798e-07 2.61911844533266e-06 -2.58480312096261e-06 -2.61264928073091e-05 8.50210116476053e-05 2.77440858381798e-07 8.94063973932347e-05 1.96454987715202e-05 1.17855860798654e-05 -1.44561525068249e-05 3.40330423936684e-05 2.61911844533266e-06 1.96454987715202e-05 2.97180814856916e-05 8.52168033573646e-07 1.13417048594143e-05 -3.25640074247578e-06 -2.58480312096261e-06 1.17855860798654e-05 8.52168033573646e-07 3.17715849265346e-05 990 994 0 24 0 993 1009 0 40 0 0 0 0 0 0 11 32 0 2718 0 0 0 0 0 1772 +889 892 0.999710987106985 -0.000460596198452118 0.0240360169063099 -0.00925601897410853 -0.000636365076654145 0.998959090904295 0.0456106318653084 -0.00978258539106608 -0.0240320056813338 -0.0456127454863818 0.998670085740094 0.00167511328003273 4.58606413594479e-05 -4.80491969143438e-05 1.50476043051623e-07 -1.58136428239277e-05 -1.49806958723161e-05 2.1973047166406e-05 -4.80491969143438e-05 7.52696641769593e-05 1.75906764864089e-06 3.30131444757339e-05 2.19494648991284e-05 -2.16811572252738e-05 1.50476043051623e-07 1.75906764864089e-06 8.91850915471758e-06 7.91961435757106e-07 3.05059696172062e-06 -3.30087380997022e-07 -1.58136428239277e-05 3.30131444757339e-05 7.91961435757106e-07 5.29292718715081e-05 1.70032372089674e-05 -4.80579996293756e-06 -1.49806958723161e-05 2.19494648991284e-05 3.05059696172062e-06 1.70032372089674e-05 2.63101044958408e-05 -4.58982137034308e-06 2.1973047166406e-05 -2.16811572252738e-05 -3.30087380997022e-07 -4.80579996293756e-06 -4.58982137034308e-06 2.74830164610144e-05 929 930 0 24 0 927 950 0 40 0 0 0 0 0 0 13 35 0 2956 0 0 0 0 0 2188 +890 920 0.999925122395029 -0.000544940150697943 0.0122250825567087 -0.00569907372827435 0.000234350445071409 0.999677518321023 0.0253929998895174 -0.00985322752407002 -0.0122349778567467 -0.0253882335689644 0.999602792569675 0.00405752632647645 3.24706532888192e-05 -3.64155464493432e-05 -4.48793871097232e-06 2.72763901928876e-06 -3.21333609128802e-06 1.82027567329156e-05 -3.64155464493432e-05 8.28348863765292e-05 8.0852124133424e-06 1.25089414036646e-05 7.77295903308578e-06 -1.26783131288621e-05 -4.48793871097232e-06 8.0852124133424e-06 1.09507797385153e-05 -4.37670284483798e-06 3.93294410789048e-06 -3.47345249107222e-06 2.72763901928876e-06 1.25089414036646e-05 -4.37670284483798e-06 4.4788196835046e-05 3.79056726588483e-06 9.5060266987071e-06 -3.21333609128802e-06 7.77295903308578e-06 3.93294410789048e-06 3.79056726588483e-06 2.13021941122084e-05 -2.33656195862151e-06 1.82027567329156e-05 -1.26783131288621e-05 -3.47345249107222e-06 9.5060266987071e-06 -2.33656195862151e-06 2.78446435420012e-05 987 986 0 18 0 990 1004 0 37 0 0 0 0 0 0 11 30 0 2720 0 0 0 0 0 2214 +889 893 0.999591101252278 -0.000398147231938336 0.0285914633420363 -0.00533276587798097 -0.000978070485910092 0.998841865546026 0.0481037525631781 -0.0075697185735893 -0.0285775029591792 -0.0481120474654382 0.998433050941976 0.00301004530515346 5.64927255610255e-05 -8.20052520359468e-05 -3.18740752578909e-06 -3.24384479379496e-05 -1.751204386078e-05 1.02787807272381e-05 -8.20052520359468e-05 0.000180093788487253 7.16413997353173e-06 9.89996288271978e-05 4.75746379156398e-05 -8.43902303122063e-07 -3.18740752578909e-06 7.16413997353173e-06 8.92292534307922e-06 3.84390034092626e-06 4.14761984600522e-06 -8.97914821977251e-07 -3.24384479379496e-05 9.89996288271978e-05 3.84390034092626e-06 0.000103407925419123 3.94727269187989e-05 9.59475297427697e-06 -1.751204386078e-05 4.75746379156398e-05 4.14761984600522e-06 3.94727269187989e-05 3.34423205270587e-05 3.72457311098962e-06 1.02787807272381e-05 -8.43902303122063e-07 -8.97914821977251e-07 9.59475297427697e-06 3.72457311098962e-06 3.03101306035644e-05 932 931 0 19 0 930 949 0 34 0 0 0 0 0 0 13 34 0 2848 0 0 0 0 0 2089 +890 928 0.999815605991032 0.00017657028437986 0.019202157163191 0.000151482528942597 -0.000766755909127094 0.999527355229952 0.0307323645753685 -0.00437005508734098 -0.0191876549416814 -0.0307414210789322 0.999343183760157 0.00283790593396191 4.6586222900917e-05 -5.35607046606129e-05 -4.40615265426478e-06 -9.40041249585774e-06 -1.03173602651671e-05 1.28741602259706e-05 -5.35607046606129e-05 9.39227766500603e-05 6.69113204144743e-06 2.99194376764836e-05 1.7402363866813e-05 -5.9710237908199e-06 -4.40615265426478e-06 6.69113204144743e-06 9.5282978542561e-06 -2.74397246128678e-06 4.44802288868339e-06 -3.47210148745397e-06 -9.40041249585774e-06 2.99194376764836e-05 -2.74397246128678e-06 5.42901678700505e-05 1.21533313815269e-05 1.29736557380619e-05 -1.03173602651671e-05 1.7402363866813e-05 4.44802288868339e-06 1.21533313815269e-05 2.42118504743448e-05 1.81009416577999e-06 1.28741602259706e-05 -5.9710237908199e-06 -3.47210148745397e-06 1.29736557380619e-05 1.81009416577999e-06 2.87633428974949e-05 1009 1014 0 31 0 1009 1023 0 38 0 0 0 0 0 0 9 27 0 2846 0 0 0 0 0 1971 +890 922 0.999922723127913 0.000377654175690995 0.0124259868735615 -0.000775490734740458 -0.000730510722263596 0.999596246990687 0.0284043897350192 -0.00322307068313684 -0.0124102428075762 -0.0284112720492728 0.999519277199794 0.00275796969136526 4.75717086225039e-05 -6.12999366695809e-05 -6.05491291953407e-06 -1.06325907417019e-05 -4.65303376557008e-06 7.12263672025277e-06 -6.12999366695809e-05 0.000116141598762185 8.70233878668569e-06 3.40660796670495e-05 1.29312806343842e-05 -1.62432305038256e-06 -6.05491291953407e-06 8.70233878668569e-06 1.05091826208264e-05 -1.72443733557702e-06 2.4884877938155e-06 -1.74097117246772e-06 -1.06325907417019e-05 3.40660796670495e-05 -1.72443733557702e-06 5.21993178596358e-05 1.20874208868389e-05 7.96165756297329e-06 -4.65303376557008e-06 1.29312806343842e-05 2.4884877938155e-06 1.20874208868389e-05 2.23072673710585e-05 -1.64810345219417e-06 7.12263672025277e-06 -1.62432305038256e-06 -1.74097117246772e-06 7.96165756297329e-06 -1.64810345219417e-06 2.83542869901884e-05 1001 1003 0 27 0 1001 1017 0 42 0 0 0 0 0 0 13 34 0 2954 0 0 0 0 0 1686 +890 921 0.999846625827145 -0.000128747432812119 0.0175130878536838 -0.00149850827040143 -0.000338454818234317 0.999644188558077 0.0266717402956826 -0.00708231418956919 -0.0175102904147338 -0.0266735769285424 0.999490825382319 -0.00187161758067194 4.54889756518267e-05 -5.583934017326e-05 -1.12277569826954e-07 -1.51077104368986e-05 -1.21376531863244e-05 1.96975907058025e-05 -5.583934017326e-05 9.38427582200677e-05 2.05859172149833e-06 3.69633361853465e-05 2.42177546442787e-05 -1.7113564925115e-05 -1.12277569826954e-07 2.05859172149833e-06 9.60705073555329e-06 -2.23943011303315e-06 4.25791220357572e-06 -1.32941963854955e-06 -1.51077104368986e-05 3.69633361853465e-05 -2.23943011303315e-06 6.13993041974684e-05 1.95122792997101e-05 5.33899633247011e-06 -1.21376531863244e-05 2.42177546442787e-05 4.25791220357572e-06 1.95122792997101e-05 2.82017346964484e-05 -1.94821611287293e-06 1.96975907058025e-05 -1.7113564925115e-05 -1.32941963854955e-06 5.33899633247011e-06 -1.94821611287293e-06 2.76468293135999e-05 1024 1028 0 34 0 1024 1038 0 41 0 0 0 0 0 0 13 32 0 2833 0 0 0 0 0 2326 +890 927 0.999865786542931 0.000267554126596847 0.0163810047211633 -0.00293739823114882 -0.000710974726632257 0.999633304941608 0.0270693584418946 -0.00579576350668578 -0.0163677553691251 -0.027077371850071 0.999499330924173 -0.00354848930874658 4.40965062632094e-05 -5.48572248414046e-05 -3.8198326882509e-06 -1.73425303054067e-05 -1.16005118744314e-05 1.3892209517652e-05 -5.48572248414046e-05 0.00010001459628949 6.58623754866951e-06 4.66992264478258e-05 2.44980216899787e-05 -8.53354632598724e-06 -3.8198326882509e-06 6.58623754866951e-06 1.01377332872465e-05 -2.50442156663192e-06 4.90333687127948e-06 -3.23718300772843e-06 -1.73425303054067e-05 4.66992264478258e-05 -2.50442156663192e-06 7.40149237374173e-05 2.25753857664535e-05 1.07328184165956e-05 -1.16005118744314e-05 2.44980216899787e-05 4.90333687127948e-06 2.25753857664535e-05 2.79429263100613e-05 1.63421827044766e-06 1.3892209517652e-05 -8.53354632598724e-06 -3.23718300772843e-06 1.07328184165956e-05 1.63421827044766e-06 2.8118016463747e-05 965 973 0 25 0 968 988 0 39 0 0 0 0 0 0 12 29 0 2945 0 0 0 0 0 1469 +890 918 0.999817577040242 -0.000159703078074379 0.0190994014646143 -0.00104949717894734 -0.000359946189640608 0.9996299171418 0.0272010880998889 -0.00818210739845757 -0.0190966772010269 -0.0272030007536707 0.999447504209138 0.00284720146572135 3.98766291641295e-05 -4.69666387280539e-05 -4.47549342649106e-06 -5.44423112212102e-06 -5.49191231481856e-06 1.87891359911e-05 -4.69666387280539e-05 0.000105371783241606 7.59173415151134e-06 3.15388640096122e-05 9.51553466422208e-06 -1.36027231667712e-05 -4.47549342649106e-06 7.59173415151134e-06 8.95832077759303e-06 4.1734749601196e-07 3.07898290659361e-06 -3.45007464677232e-06 -5.44423112212102e-06 3.15388640096122e-05 4.1734749601196e-07 4.62425780565944e-05 5.53578593141185e-06 7.27714032585178e-06 -5.49191231481856e-06 9.51553466422208e-06 3.07898290659361e-06 5.53578593141185e-06 2.14014553358599e-05 -2.44229878239229e-06 1.87891359911e-05 -1.36027231667712e-05 -3.45007464677232e-06 7.27714032585178e-06 -2.44229878239229e-06 2.57167829278078e-05 991 992 0 23 0 991 1008 0 42 0 0 0 0 0 0 9 29 0 2629 0 0 0 0 0 2248 +890 916 0.999946215827296 0.000243469858089295 0.0103685184621094 -0.00615734198263084 -0.000522977866721529 0.999636290037588 0.0269631996253771 -0.00547982598095482 -0.0103581826022629 -0.0269671719376582 0.99958265275607 0.00329044718977573 4.55752391046111e-05 -5.19547074283245e-05 -3.84439057635469e-06 -8.2099133880636e-06 -9.76209884571406e-06 1.28545512991139e-05 -5.19547074283245e-05 9.07149945031372e-05 4.12704173763334e-06 2.85263476756058e-05 1.82604529669489e-05 -9.01155899022793e-06 -3.84439057635469e-06 4.12704173763334e-06 1.03041476898186e-05 -5.44818340705323e-06 4.49597604003798e-06 -5.03161400780697e-06 -8.2099133880636e-06 2.85263476756058e-05 -5.44818340705323e-06 5.24730085849975e-05 1.25403068041831e-05 1.02639442428224e-05 -9.76209884571406e-06 1.82604529669489e-05 4.49597604003798e-06 1.25403068041831e-05 2.43073506474892e-05 2.15848747598592e-06 1.28545512991139e-05 -9.01155899022793e-06 -5.03161400780697e-06 1.02639442428224e-05 2.15848747598592e-06 2.81506485330512e-05 979 980 0 23 0 979 997 0 39 0 0 0 0 0 0 14 31 0 2812 0 0 0 0 0 1610 +890 917 0.999684633472272 -0.000293198818135054 0.0251107075539767 0.00289202810769081 -0.000364417935574668 0.999657175519189 0.0261801190326883 -0.00774462613279314 -0.0251097749686557 -0.0261810134916611 0.99934181025992 -0.00165711300861054 5.32664292907943e-05 -5.62719095682517e-05 -5.17337949745818e-06 -9.38412109964979e-06 -8.8953662537137e-06 1.43224416889629e-05 -5.62719095682517e-05 9.15867290800727e-05 7.60466762091705e-06 3.20363850296748e-05 1.4143494819943e-05 -4.7148341116736e-06 -5.17337949745818e-06 7.60466762091705e-06 1.06925333278297e-05 -3.88331929924938e-06 2.36771320978641e-06 -3.8396374458358e-06 -9.38412109964979e-06 3.20363850296748e-05 -3.88331929924938e-06 6.62389665014095e-05 1.84415967747008e-05 1.80647782140668e-05 -8.8953662537137e-06 1.4143494819943e-05 2.36771320978641e-06 1.84415967747008e-05 3.20004099144743e-05 3.27313343950955e-06 1.43224416889629e-05 -4.7148341116736e-06 -3.8396374458358e-06 1.80647782140668e-05 3.27313343950955e-06 4.17532595868442e-05 977 979 0 27 0 977 994 0 40 0 0 0 0 0 0 10 30 0 2560 0 0 0 0 0 1476 +890 929 0.999668982593067 -0.0210642269707369 0.0147723926114464 -0.0076958608182789 0.0203895693925524 0.998804730591083 0.0444226924989907 -0.00746929676485766 -0.0156904652999115 -0.0441067850902656 0.998903599356651 -0.00764871259561391 3.40027902184078e-05 -3.31108214914504e-05 -2.99007032168433e-06 -4.25017598365636e-06 -7.1771838573458e-06 1.47648693884368e-05 -3.31108214914504e-05 6.98046919987415e-05 5.61807438536554e-06 1.84537970650214e-05 8.53968957920765e-06 -1.36441679734051e-05 -2.99007032168433e-06 5.61807438536554e-06 9.71216420843485e-06 1.91382728800734e-07 2.14532900795505e-06 -1.86095994643701e-06 -4.25017598365636e-06 1.84537970650214e-05 1.91382728800734e-07 4.08667549274542e-05 -7.61493375206606e-07 2.5195070268048e-08 -7.1771838573458e-06 8.53968957920765e-06 2.14532900795505e-06 -7.61493375206606e-07 2.43426786782948e-05 -6.27931003586205e-06 1.47648693884368e-05 -1.36441679734051e-05 -1.86095994643701e-06 2.5195070268048e-08 -6.27931003586205e-06 2.89832778230806e-05 961 961 0 0 0 977 979 0 12 0 0 0 0 0 0 48 69 0 3003 0 0 0 0 0 2191 +890 924 0.999971515810575 -7.16770944660996e-05 0.00754734588410283 -0.00942423464379667 -9.37920238812151e-05 0.999759690415823 0.0219215105025548 -0.0116675348530163 -0.00754710345473092 -0.0219215939669425 0.999731206348683 -0.0039012289052307 5.16510739315078e-05 -6.6483113165463e-05 -4.85060926718036e-06 -1.60774880792966e-05 -1.04613904206329e-05 1.60976730345452e-05 -6.6483113165463e-05 0.000126525915991853 6.82666701294206e-06 5.00955214970464e-05 2.17049970752041e-05 -7.73305736910456e-06 -4.85060926718036e-06 6.82666701294206e-06 1.04586476691656e-05 -1.28481671108828e-06 3.94623902993353e-06 -2.52865202677083e-06 -1.60774880792966e-05 5.00955214970464e-05 -1.28481671108828e-06 6.67142322856989e-05 1.61492931618207e-05 9.75454696966987e-06 -1.04613904206329e-05 2.17049970752041e-05 3.94623902993353e-06 1.61492931618207e-05 2.63885446437493e-05 6.25615515065833e-07 1.60976730345452e-05 -7.73305736910456e-06 -2.52865202677083e-06 9.75454696966987e-06 6.25615515065833e-07 3.28338046499544e-05 969 971 0 29 0 969 984 0 40 0 0 0 0 0 0 12 30 0 2884 0 0 0 0 0 2017 +890 923 0.999924641417402 -0.000102386793732427 0.0122760336927305 -0.00297256820488846 -0.000222305121194662 0.999650245886841 0.0264449707659448 -0.00640106865267477 -0.0122744477152202 -0.0264457069355888 0.999574890900108 0.00362094994742555 3.46448503540724e-05 -3.68753675440928e-05 8.32085915110794e-08 -7.29295859461796e-06 -7.42961584229711e-06 8.24824305926082e-06 -3.68753675440928e-05 5.80592631385399e-05 1.05323269668662e-06 1.9139910942536e-05 1.10672672680736e-05 -4.07195630421292e-06 8.32085915110794e-08 1.05323269668662e-06 9.91767211519048e-06 -2.83015808857715e-06 3.05686603200552e-06 -2.0837080544129e-06 -7.29295859461796e-06 1.9139910942536e-05 -2.83015808857715e-06 5.16443952790352e-05 1.26156264974497e-05 8.6355677745636e-06 -7.42961584229711e-06 1.10672672680736e-05 3.05686603200552e-06 1.26156264974497e-05 2.56024873756867e-05 1.19178058791881e-06 8.24824305926082e-06 -4.07195630421292e-06 -2.0837080544129e-06 8.6355677745636e-06 1.19178058791881e-06 2.37649164543086e-05 994 999 0 23 0 997 1017 0 42 0 0 0 0 0 0 10 31 0 2825 0 0 0 0 0 1606 +891 927 0.999990053046809 3.0083193429503e-05 0.00446014601119351 0.00032799686219581 -4.80668157462944e-05 0.999991870227377 0.0040320179480257 0.000110814677477675 -0.00445998845524474 -0.00403219222674843 0.999981924801056 -0.00285944483453358 3.35498554311438e-05 -3.7960935414369e-05 -2.0724605149396e-06 -4.69242469278961e-06 -2.48668077112866e-06 7.73195301565374e-06 -3.7960935414369e-05 7.04565778839519e-05 3.09025047456228e-06 1.90701622983848e-05 9.98197843700565e-06 -1.94450242296336e-06 -2.0724605149396e-06 3.09025047456228e-06 9.01520693012477e-06 -1.27428304325773e-06 3.84219441124021e-06 -1.0566925602875e-06 -4.69242469278961e-06 1.90701622983848e-05 -1.27428304325773e-06 3.60246600593385e-05 2.89558545541844e-06 5.782482310801e-06 -2.48668077112866e-06 9.98197843700565e-06 3.84219441124021e-06 2.89558545541844e-06 1.8142191873884e-05 1.20567822500157e-06 7.73195301565374e-06 -1.94450242296336e-06 -1.0566925602875e-06 5.782482310801e-06 1.20567822500157e-06 2.49801429178563e-05 948 948 0 14 0 945 969 0 38 0 0 0 0 0 0 13 37 0 2959 0 0 0 0 0 1739 +890 893 0.999886727574938 8.56695672804283e-05 0.0150507368659038 -0.00408636366888847 -0.000468184907528824 0.999676918453457 0.0254133727453126 -0.00628333795929042 -0.0150436970979144 -0.0254175406388005 0.999563722733824 -0.00342069846651094 4.10451376538661e-05 -3.82233484837209e-05 -2.19999545703291e-06 -1.29769421535819e-05 -8.95450367809181e-06 8.33635287492193e-06 -3.82233484837209e-05 5.44959472292678e-05 4.19900119068774e-06 1.97983322178965e-05 1.06927471311999e-05 -3.31744010534771e-06 -2.19999545703291e-06 4.19900119068774e-06 9.74930145214689e-06 -3.13550447935165e-06 3.71365931460791e-06 -2.98123341110493e-06 -1.29769421535819e-05 1.97983322178965e-05 -3.13550447935165e-06 5.22488097560822e-05 1.34249239138937e-05 1.01820598170044e-05 -8.95450367809181e-06 1.06927471311999e-05 3.71365931460791e-06 1.34249239138937e-05 2.33798586090598e-05 5.48786781919154e-06 8.33635287492193e-06 -3.31744010534771e-06 -2.98123341110493e-06 1.01820598170044e-05 5.48786781919154e-06 2.91237789927307e-05 1027 1032 0 30 0 1027 1044 0 39 0 0 0 0 0 0 13 32 0 2861 0 0 0 0 0 1505 +890 894 0.999883251640892 -0.000393936944925069 0.0152750745242266 -0.00246769400572913 -2.93403450746744e-05 0.999616275258741 0.0277002053599971 -0.0056518192339124 -0.0152801252344804 -0.0276974195824319 0.99949956014062 0.0023630880650426 4.28839800809182e-05 -4.50381108030361e-05 1.61932750930194e-06 -5.98373845391404e-06 -1.0427981397482e-05 1.21730203984475e-05 -4.50381108030361e-05 6.80329978986879e-05 -5.08575584847338e-07 1.62079030886573e-05 1.44355155008249e-05 -9.92508811672848e-06 1.61932750930194e-06 -5.08575584847338e-07 1.10078981299694e-05 -5.60686257574234e-06 3.25080240828576e-06 -2.42764701275352e-06 -5.98373845391404e-06 1.62079030886573e-05 -5.60686257574234e-06 5.63477647072292e-05 1.45696829295473e-05 8.56326308653107e-06 -1.0427981397482e-05 1.44355155008249e-05 3.25080240828576e-06 1.45696829295473e-05 2.85952246066083e-05 1.09629455277989e-06 1.21730203984475e-05 -9.92508811672848e-06 -2.42764701275352e-06 8.56326308653107e-06 1.09629455277989e-06 2.99675058373918e-05 996 1004 0 31 0 996 1017 0 43 0 0 0 0 0 0 12 30 0 2848 0 0 0 0 0 1641 +890 925 0.999934283589385 -0.000205802480303733 0.0114623796797462 -0.0069640130037901 -7.02030946020955e-05 0.999710185226809 0.0240736500204113 -0.00863461438626462 -0.0114640121296633 -0.0240728726810666 0.999644473413809 -0.000801939538323082 3.64950361939514e-05 -3.56262775024958e-05 1.05641622519713e-06 -1.04563660059839e-05 -1.24001535919931e-05 1.50600229056283e-05 -3.56262775024958e-05 5.42518913840305e-05 1.66022567215931e-06 1.52903051213097e-05 1.42340394612543e-05 -1.2092602980112e-05 1.05641622519713e-06 1.66022567215931e-06 9.17070434624373e-06 -2.16336547762185e-06 3.43256536851195e-06 -1.00726813653096e-06 -1.04563660059839e-05 1.52903051213097e-05 -2.16336547762185e-06 4.90166262740419e-05 1.33679173096165e-05 7.44461985678002e-06 -1.24001535919931e-05 1.42340394612543e-05 3.43256536851195e-06 1.33679173096165e-05 2.45589618718879e-05 -1.69204960653941e-06 1.50600229056283e-05 -1.2092602980112e-05 -1.00726813653096e-06 7.44461985678002e-06 -1.69204960653941e-06 2.43192467349839e-05 969 974 0 18 0 974 994 0 41 0 0 0 0 0 0 13 31 0 2848 0 0 0 0 0 2409 +890 892 0.999936944288126 -4.44710432944634e-05 0.0112296691871184 -0.00510767791548288 -0.000250191892036395 0.999655721647069 0.0262369125907499 -0.0048537552938933 -0.0112269698379824 -0.02623806777573 0.999592676517617 0.00212982715975453 7.21126040200273e-05 -7.44622386769268e-05 -3.36759792868724e-06 -1.68531165276415e-05 -1.78259987051172e-05 1.16956884664809e-05 -7.44622386769268e-05 0.00013025915007844 3.77993898664398e-06 4.52509406166736e-05 3.10406780098677e-05 -7.43860098452065e-06 -3.36759792868724e-06 3.77993898664398e-06 9.39647350857766e-06 -1.25359534434295e-06 3.58900067094389e-06 -2.79030561862471e-06 -1.68531165276415e-05 4.52509406166736e-05 -1.25359534434295e-06 5.84974960978446e-05 2.00786263128599e-05 9.55466141946901e-06 -1.78259987051172e-05 3.10406780098677e-05 3.58900067094389e-06 2.00786263128599e-05 2.91730663575333e-05 5.46316352218519e-07 1.16956884664809e-05 -7.43860098452065e-06 -2.79030561862471e-06 9.55466141946901e-06 5.46316352218519e-07 3.10634539165607e-05 967 971 0 25 0 967 984 0 41 0 0 0 0 0 0 9 33 0 2995 0 0 0 0 0 1584 +891 926 0.999998985338395 0.000112905491842936 -0.00142006145298675 -0.00456900702255888 -0.00011165615147212 0.999999606718072 0.000879827600213613 -0.0032929770224875 0.00142016023187018 -0.000879668148889634 0.999998604663458 -0.00442557446425711 4.60124729036526e-05 -5.21263343812489e-05 1.05430413532704e-06 -2.13866348671583e-05 -1.49490605506795e-05 1.31052333781798e-05 -5.21263343812489e-05 8.44227703911232e-05 -1.38158800239657e-07 4.3977372706425e-05 2.89251869801368e-05 -8.8927972332503e-06 1.05430413532704e-06 -1.38158800239657e-07 9.50869522419097e-06 -2.69452424214004e-06 2.56869721145184e-06 -1.0780179649619e-06 -2.13866348671583e-05 4.3977372706425e-05 -2.69452424214004e-06 6.85387815411796e-05 2.55336774282617e-05 4.73627242647118e-06 -1.49490605506795e-05 2.89251869801368e-05 2.56869721145184e-06 2.55336774282617e-05 3.05442192063577e-05 2.51341325193951e-06 1.31052333781798e-05 -8.8927972332503e-06 -1.0780179649619e-06 4.73627242647118e-06 2.51341325193951e-06 2.77675872797601e-05 962 961 0 13 0 960 982 0 35 0 0 0 0 0 0 12 37 0 2928 0 0 0 0 0 2159 +891 924 0.999972569797242 -0.000235968632140748 0.00740297047848767 0.00240623054235459 0.000210338291558151 0.999993982516643 0.00346275732717808 -0.00212987631195292 -0.00740374303334596 -0.00346110521487959 0.999966602112184 -0.00409216116429426 4.34555602999214e-05 -5.57712255724495e-05 -8.68791983553746e-07 -2.06016037920965e-05 -9.67738758843265e-06 8.91148025885007e-06 -5.57712255724495e-05 0.000104431098229431 1.43601123317162e-06 5.40749468339988e-05 2.1800583083822e-05 -6.8801039638345e-06 -8.68791983553746e-07 1.43601123317162e-06 9.43846040591724e-06 -3.78747617757558e-06 3.890072416684e-06 -1.05812192356135e-06 -2.06016037920965e-05 5.40749468339988e-05 -3.78747617757558e-06 7.91920289440531e-05 1.96858908473638e-05 6.05193777368159e-06 -9.67738758843265e-06 2.1800583083822e-05 3.890072416684e-06 1.96858908473638e-05 2.43232681595705e-05 6.03483559502088e-07 8.91148025885007e-06 -6.8801039638345e-06 -1.05812192356135e-06 6.05193777368159e-06 6.03483559502088e-07 2.60138908683393e-05 945 947 0 22 0 946 962 0 39 0 0 0 0 0 0 13 35 0 2917 0 0 0 0 0 1654 +891 928 0.999990640194911 0.000159916233257934 0.00432365000561204 0.000224685709687268 -0.000189042668001548 0.999977288495967 0.00673696928323443 -0.00025080168340456 -0.00432247445826615 -0.00673772358084761 0.999967959134444 -7.61357466342336e-05 3.3895954129366e-05 -3.54115981030579e-05 -6.73747573271706e-07 -8.9072078149441e-06 -4.40480602506899e-06 5.96037073992674e-06 -3.54115981030579e-05 6.06076303214319e-05 2.40822050888636e-06 2.19678846986997e-05 9.95339112276915e-06 1.20784423088476e-06 -6.73747573271706e-07 2.40822050888636e-06 8.96335998841707e-06 -2.29585969813262e-06 4.28007891313306e-06 -1.40048546058622e-06 -8.9072078149441e-06 2.19678846986997e-05 -2.29585969813262e-06 4.68569619926836e-05 1.01229301555927e-05 1.17872844470666e-05 -4.40480602506899e-06 9.95339112276915e-06 4.28007891313306e-06 1.01229301555927e-05 2.02051379119763e-05 3.74615447061788e-06 5.96037073992674e-06 1.20784423088476e-06 -1.40048546058622e-06 1.17872844470666e-05 3.74615447061788e-06 2.56185639178997e-05 965 966 0 17 0 964 980 0 35 0 0 0 0 0 0 16 36 0 2874 0 0 0 0 0 1527 +891 917 0.999965156001181 -1.30393297950191e-05 0.00834785083183034 0.00351554485273246 -1.94275720306337e-05 0.999992437000522 0.00388915984831906 -0.0016199701891403 -0.00834783840907674 -0.00388918651291123 0.999957593011906 -0.00289344857061344 4.80089653372704e-05 -5.52030249279771e-05 -6.42452580496113e-07 -1.73103518996207e-05 -1.27215778538455e-05 8.70188815667375e-07 -5.52030249279771e-05 9.04968640633545e-05 2.54903142519675e-06 3.53556560861122e-05 2.07012940035779e-05 1.02239729833539e-05 -6.42452580496113e-07 2.54903142519675e-06 8.98741319386562e-06 -3.20592805207825e-06 2.59139750425595e-06 -8.05889329044298e-07 -1.73103518996207e-05 3.53556560861122e-05 -3.20592805207825e-06 6.15487540400202e-05 2.33398503341737e-05 1.42057705896247e-05 -1.27215778538455e-05 2.07012940035779e-05 2.59139750425595e-06 2.33398503341737e-05 3.10959589329268e-05 8.75154616440755e-06 8.70188815667375e-07 1.02239729833539e-05 -8.05889329044298e-07 1.42057705896247e-05 8.75154616440755e-06 3.21947542142324e-05 954 951 0 15 0 954 975 0 40 0 0 0 0 0 0 12 35 0 2589 0 0 0 0 0 1578 +891 919 0.999992086129623 0.000339262062582531 0.00396390960769865 -0.000144568076214896 -0.000354553430254372 0.999992496647334 0.00385758226049237 -0.00127623538643956 -0.00396257113377265 -0.00385895714983502 0.999984703122866 0.00180468852026631 4.24285546635172e-05 -5.3305879312018e-05 -5.25804793702957e-06 -8.02768006134497e-06 -4.54205325096962e-06 1.57244343933743e-05 -5.3305879312018e-05 0.000114801490320235 7.84309478496936e-06 3.59237251712747e-05 1.40242371832339e-05 -9.56371966874619e-06 -5.25804793702957e-06 7.84309478496936e-06 1.11197584665632e-05 5.28587364096829e-07 2.34433372142825e-06 -2.82407802507372e-06 -8.02768006134497e-06 3.59237251712747e-05 5.28587364096829e-07 4.99672573247652e-05 2.99836541151501e-06 9.1683728418953e-06 -4.54205325096962e-06 1.40242371832339e-05 2.34433372142825e-06 2.99836541151501e-06 2.15860828138817e-05 -2.17247972570475e-07 1.57244343933743e-05 -9.56371966874619e-06 -2.82407802507372e-06 9.1683728418953e-06 -2.17247972570475e-07 3.05000784200912e-05 965 971 0 22 0 964 982 0 34 0 0 0 0 0 0 16 38 0 2744 0 0 0 0 0 1416 +891 918 0.999992623230023 -7.79429526996687e-05 0.00384023572634637 -0.000662035482899764 5.75764081682088e-05 0.999985935815901 0.0053032872215684 -0.00233215157616685 -0.00384059507042919 -0.0053030269934588 0.999978563637347 0.00231094132033674 2.79422537766048e-05 -2.65428801672852e-05 -1.14475655471077e-06 -3.10525643258129e-06 -2.1179449069695e-06 9.4515699844788e-06 -2.65428801672852e-05 4.62369525712927e-05 2.74102389144234e-06 8.97062071865288e-06 3.43971590614544e-06 -4.83235915789618e-06 -1.14475655471077e-06 2.74102389144234e-06 8.13795368570335e-06 -7.02033258641962e-07 3.23912408944515e-06 -3.60850818313302e-07 -3.10525643258129e-06 8.97062071865288e-06 -7.02033258641962e-07 2.81399501467068e-05 1.38273329340628e-06 4.46153414356911e-06 -2.1179449069695e-06 3.43971590614544e-06 3.23912408944515e-06 1.38273329340628e-06 1.77644138880886e-05 -1.79572292709178e-06 9.4515699844788e-06 -4.83235915789618e-06 -3.60850818313302e-07 4.46153414356911e-06 -1.79572292709178e-06 2.57058837979929e-05 963 970 0 22 0 964 983 0 37 0 0 0 0 0 0 14 37 0 2658 0 0 0 0 0 2135 +891 920 0.999990267737131 -0.000163792230652186 0.00440880971753838 0.00206883311170877 0.000141492398464125 0.999987198968313 0.00505785324121275 -0.00244826995545931 -0.00440958171729017 -0.00505718020379415 0.999977490005382 0.0019838319402012 4.1026236903474e-05 -4.72083582101749e-05 -3.2115349762395e-06 -4.25918757036131e-06 -3.47982107101888e-06 1.96213508611831e-05 -4.72083582101749e-05 9.71086099510606e-05 6.06814668378593e-06 2.5357853327237e-05 1.00917066439074e-05 -2.01248060797826e-05 -3.2115349762395e-06 6.06814668378593e-06 9.4906544923835e-06 -2.84029212957737e-06 3.82642813487092e-06 -2.48986507321946e-06 -4.25918757036131e-06 2.5357853327237e-05 -2.84029212957737e-06 4.80286706078293e-05 6.96029406854763e-06 -4.30815538355535e-07 -3.47982107101888e-06 1.00917066439074e-05 3.82642813487092e-06 6.96029406854763e-06 1.99088205194355e-05 -2.4135007124994e-06 1.96213508611831e-05 -2.01248060797826e-05 -2.48986507321946e-06 -4.30815538355535e-07 -2.4135007124994e-06 2.87211767417439e-05 956 955 0 14 0 954 972 0 37 0 0 0 0 0 0 13 35 0 2746 0 0 0 0 0 2108 +891 925 0.999999948081197 3.2048860540105e-05 -0.000320640724432254 -0.00244517745393311 -3.12245918357902e-05 0.999996696112974 0.00257036732031797 -0.00124524548777405 0.00032072204241531 -0.00257035717499183 0.999996645195055 -0.00256327718392041 3.87451011889611e-05 -5.13196807514145e-05 1.25083943736657e-06 -2.11099213828952e-05 -1.38659553709515e-05 2.33748565175446e-05 -5.13196807514145e-05 0.00011002977767658 8.61086618351413e-07 5.95513197128232e-05 3.18672148907937e-05 -3.13846906125962e-05 1.25083943736657e-06 8.61086618351413e-07 8.3899582572256e-06 -6.59985290539167e-07 4.73426820857543e-06 -4.02198963416352e-08 -2.11099213828952e-05 5.95513197128232e-05 -6.59985290539167e-07 7.59402249478591e-05 2.30951941010551e-05 -8.52404907731476e-06 -1.38659553709515e-05 3.18672148907937e-05 4.73426820857543e-06 2.30951941010551e-05 2.83055593934621e-05 -7.29979086982996e-06 2.33748565175446e-05 -3.13846906125962e-05 -4.02198963416352e-08 -8.52404907731476e-06 -7.29979086982996e-06 3.00904878809315e-05 953 961 0 22 0 950 973 0 41 0 0 0 0 0 0 12 36 0 2880 0 0 0 0 0 2549 +891 923 0.999991285496125 6.51335207583291e-05 0.00417428909286267 0.00164357049016282 -8.74093952430454e-05 0.999985757030375 0.00533648723277187 7.39100568800734e-05 -0.00417388205438796 -0.00533680560001838 0.999977048343903 0.000730809890432639 5.49471858684183e-05 -7.52506399846809e-05 -2.68319110386946e-06 -1.88990627683318e-05 -1.29993079096758e-05 1.28062002013345e-05 -7.52506399846809e-05 0.000143081887708426 7.08874680481624e-06 4.59685664084211e-05 2.35226365179932e-05 -1.07825473517697e-05 -2.68319110386946e-06 7.08874680481624e-06 1.03453218951226e-05 -1.4282055916378e-06 5.70378571138231e-06 -8.4658382576946e-08 -1.88990627683318e-05 4.59685664084211e-05 -1.4282055916378e-06 5.24482308866314e-05 9.87416491021674e-06 5.29254602765017e-06 -1.29993079096758e-05 2.35226365179932e-05 5.70378571138231e-06 9.87416491021674e-06 2.26638146245594e-05 8.40117388259096e-08 1.28062002013345e-05 -1.07825473517697e-05 -8.4658382576946e-08 5.29254602765017e-06 8.40117388259096e-08 2.71864869685796e-05 945 950 0 20 0 943 963 0 35 0 0 0 0 0 0 11 33 0 2864 0 0 0 0 0 1474 +891 922 0.999983733363433 -0.000202161005205497 0.00570018766870926 0.00212513981708404 0.000168905017585898 0.999982967406222 0.00583406963816423 -4.16649066924531e-05 -0.00570127000111073 -0.00583301194717529 0.999966735192725 0.000836630342437643 4.42713692234672e-05 -5.06580596855038e-05 -3.6076777468011e-06 -5.6773218645384e-06 -2.81248876771106e-06 7.14583438408187e-06 -5.06580596855038e-05 7.96321039551204e-05 6.22733957236366e-06 1.39493020871762e-05 7.64923560957089e-06 -7.58390557006e-07 -3.6076777468011e-06 6.22733957236366e-06 9.25663393715771e-06 -1.94733949792755e-06 4.46012054010583e-06 -1.82022923531895e-06 -5.6773218645384e-06 1.39493020871762e-05 -1.94733949792755e-06 3.74095271743478e-05 7.46167417695597e-06 7.73704217683021e-06 -2.81248876771106e-06 7.64923560957089e-06 4.46012054010583e-06 7.46167417695597e-06 1.98608104574882e-05 1.32083407555897e-06 7.14583438408187e-06 -7.58390557006e-07 -1.82022923531895e-06 7.73704217683021e-06 1.32083407555897e-06 2.44297048412306e-05 989 983 0 14 0 987 1005 0 38 0 0 0 0 0 0 14 36 0 2975 0 0 0 0 0 1462 +891 893 0.999997760484582 -6.35541724073676e-05 -0.00211541643354065 -0.00504404773557838 6.48656590615532e-05 0.999999805756123 0.000619903348938285 -0.00303362293115694 0.00211537662518965 -0.000620039178536328 0.999997570363624 -0.00376279746918893 4.58749095260618e-05 -5.5055366088706e-05 -2.52172892852374e-06 -1.65706899934403e-05 -1.01084402900941e-05 7.87560212953829e-06 -5.5055366088706e-05 9.63569352128726e-05 3.39111471699828e-06 4.53039412661426e-05 2.06168609250951e-05 -1.46921456488439e-06 -2.52172892852374e-06 3.39111471699828e-06 8.89679074246012e-06 -1.66636129502865e-06 4.12493149484901e-06 -2.11362685781795e-06 -1.65706899934403e-05 4.53039412661426e-05 -1.66636129502865e-06 6.61380383517975e-05 1.62640015123261e-05 9.32565625738548e-06 -1.01084402900941e-05 2.06168609250951e-05 4.12493149484901e-06 1.62640015123261e-05 2.2216702025903e-05 2.52690713661104e-06 7.87560212953829e-06 -1.46921456488439e-06 -2.11362685781795e-06 9.32565625738548e-06 2.52690713661104e-06 3.06188477601463e-05 1004 999 0 15 0 999 1021 0 38 0 0 0 0 0 0 12 36 0 2904 0 0 0 0 0 2129 +891 895 0.999999342762284 0.00031049669894307 -0.0011036606358324 -0.00203370324676498 -0.000307981733368002 0.999997357497608 0.0022781889852516 -0.00160250898450172 0.00110436508956602 -0.0022778475806242 0.999996795888941 -0.00326336582247649 3.88471829694144e-05 -5.64536748644673e-05 -2.15901600526242e-06 -1.78679828649491e-05 -1.08881625136661e-05 2.48065748104399e-05 -5.64536748644673e-05 0.000136890503627789 5.30084873675915e-06 6.80655250030735e-05 3.41940032174938e-05 -4.02164539264407e-05 -2.15901600526242e-06 5.30084873675915e-06 8.71603368525032e-06 1.7943394758089e-06 5.4445113773061e-06 -2.36441996667047e-06 -1.78679828649491e-05 6.80655250030735e-05 1.7943394758089e-06 7.52112681337226e-05 2.35958622758701e-05 -1.26387647950468e-05 -1.08881625136661e-05 3.41940032174938e-05 5.4445113773061e-06 2.35958622758701e-05 2.49747455022903e-05 -9.88669508019738e-06 2.48065748104399e-05 -4.02164539264407e-05 -2.36441996667047e-06 -1.26387647950468e-05 -9.88669508019738e-06 3.24831171151185e-05 940 949 0 24 0 939 961 0 36 0 0 0 0 0 0 12 36 0 2942 0 0 0 0 0 2541 +892 896 0.999999768416206 -4.06587510739377e-05 -0.000679348511762011 0.00224947509481983 4.06176332889146e-05 0.999999997342618 -6.0539005607331e-05 -0.00168344219831965 0.000679350971397082 6.05113980587523e-05 0.999999767410287 0.00111189383892975 3.93093414169572e-05 -3.90545472114629e-05 -4.05830685096967e-06 -3.53359234786268e-06 -5.39959267576186e-06 1.10466446081839e-05 -3.90545472114629e-05 4.8345252997161e-05 4.90864769513422e-06 1.0073878627042e-05 8.84533647793829e-06 -7.51397701296809e-06 -4.05830685096967e-06 4.90864769513422e-06 1.22715597447958e-05 -5.61990028281474e-06 2.36168971913155e-06 -4.954360463354e-06 -3.53359234786268e-06 1.0073878627042e-05 -5.61990028281474e-06 4.33789762611682e-05 1.31423496592707e-05 1.33905895862177e-05 -5.39959267576186e-06 8.84533647793829e-06 2.36168971913155e-06 1.31423496592707e-05 2.88706339116534e-05 4.78723735323891e-06 1.10466446081839e-05 -7.51397701296809e-06 -4.954360463354e-06 1.33905895862177e-05 4.78723735323891e-06 3.35688948357906e-05 1076 1074 0 20 0 1072 1099 0 44 0 0 0 0 0 0 13 40 0 2930 0 0 0 0 0 1155 +892 895 0.999999452143504 0.00041467932696448 -0.000961121088872928 -0.00132589862610041 -0.000413847420064943 0.999999539736656 0.000865596204757118 -0.000974107494280819 0.000961479591355733 -0.000865197973051614 0.999999163494382 -0.00285205160685295 4.23118044228898e-05 -4.45060878949295e-05 -5.3901381711905e-06 -7.16273219585432e-06 -6.28182967614558e-06 1.35534589611993e-05 -4.45060878949295e-05 6.12663423127732e-05 7.55899003802057e-06 1.26457157497168e-05 9.49138625336797e-06 -1.03942721160811e-05 -5.3901381711905e-06 7.55899003802057e-06 1.16467625522739e-05 -5.45476297427429e-06 3.73030494085308e-06 -3.53283396715105e-06 -7.16273219585432e-06 1.26457157497168e-05 -5.45476297427429e-06 4.07816890014611e-05 1.0914536951322e-05 7.70591274773102e-06 -6.28182967614558e-06 9.49138625336797e-06 3.73030494085308e-06 1.0914536951322e-05 2.29459498915937e-05 5.23297164687627e-07 1.35534589611993e-05 -1.03942721160811e-05 -3.53283396715105e-06 7.70591274773102e-06 5.23297164687627e-07 2.88135482232361e-05 1055 1059 0 20 0 1055 1080 0 42 0 0 0 0 0 0 16 40 0 2944 0 0 0 0 0 1221 +892 925 0.999999858528695 -0.000464490250324531 -0.000259213033786958 -0.00363414457425209 0.000464604246246258 0.999999795319745 0.000439890170163611 -0.00342443728359394 0.000259008656035914 -0.000440010539407955 0.999999869652612 -0.00230327057367647 2.86412266188339e-05 -2.36957663525546e-05 3.04927354106609e-06 -8.77292551212516e-06 -9.08399300143144e-06 9.83052935358973e-06 -2.36957663525546e-05 3.11503317355448e-05 -8.54727863017556e-07 5.92381963642838e-06 5.82333755199445e-06 -9.17653028204513e-06 3.04927354106609e-06 -8.54727863017556e-07 1.53941974980251e-05 -8.12980649229585e-06 8.41529320023206e-07 2.1515992639925e-09 -8.77292551212516e-06 5.92381963642838e-06 -8.12980649229585e-06 5.61673104367529e-05 2.07648591262014e-05 8.80134643528233e-06 -9.08399300143144e-06 5.82333755199445e-06 8.41529320023206e-07 2.07648591262014e-05 3.59442349994326e-05 1.80018630365849e-06 9.83052935358973e-06 -9.17653028204513e-06 2.1515992639925e-09 8.80134643528233e-06 1.80018630365849e-06 2.47949769596374e-05 1125 1132 0 22 0 1127 1153 0 44 0 0 0 0 0 0 18 40 0 2891 0 0 0 0 0 1214 +892 894 0.99999950049442 0.000133784644364651 -0.000990511272029807 0.000141965326395441 -0.000134112520860846 0.999999936240179 -0.000330958410655316 -0.00193469683584379 0.000990466931721717 0.000331091085303376 0.999999454676826 -2.32454172359069e-05 2.24724196533489e-05 -2.07025774455749e-05 -9.01978563265458e-07 -2.01077881622862e-06 -3.43918290191066e-06 1.39151025916741e-05 -2.07025774455749e-05 3.25427378293978e-05 2.52976026719538e-06 8.23704120469017e-06 5.53666413079319e-06 -1.26236004182107e-05 -9.01978563265458e-07 2.52976026719538e-06 1.01833870010269e-05 -4.04856695707782e-06 3.73932670212323e-06 -4.83019558085866e-07 -2.01077881622862e-06 8.23704120469017e-06 -4.04856695707782e-06 4.29761095790751e-05 8.2532654449046e-06 5.5031092693129e-07 -3.43918290191066e-06 5.53666413079319e-06 3.73932670212323e-06 8.2532654449046e-06 1.92896071512669e-05 -3.24414448508669e-06 1.39151025916741e-05 -1.26236004182107e-05 -4.83019558085866e-07 5.5031092693129e-07 -3.24414448508669e-06 2.48472157119414e-05 1088 1087 0 20 0 1089 1109 0 42 0 0 0 0 0 0 14 36 0 2888 0 0 0 0 0 2373 +892 927 0.999990098789563 0.000470194439432704 -0.0044250694943265 -0.000754977428259898 -0.000462073833495115 0.999998207831303 0.00183597983500879 0.00133105461040633 0.0044259248313648 -0.00183391694776136 0.999988523903158 0.00385367355664593 3.2106891084275e-05 -3.23120836416861e-05 -4.41449440288944e-06 -4.44617812487057e-07 -3.59343011269176e-06 1.13239212850144e-05 -3.23120836416861e-05 4.59067822020446e-05 5.74035312381829e-06 4.0691123861762e-06 5.32890687609694e-06 -7.37583561854107e-06 -4.41449440288944e-06 5.74035312381829e-06 1.10341643347118e-05 -5.78707978846712e-06 3.41582184539655e-06 -3.92651170063084e-06 -4.44617812487057e-07 4.0691123861762e-06 -5.78707978846712e-06 4.00117410717735e-05 7.58488668780775e-06 1.22010993029688e-05 -3.59343011269176e-06 5.32890687609694e-06 3.41582184539655e-06 7.58488668780775e-06 1.97620568910863e-05 5.07356391591577e-07 1.13239212850144e-05 -7.37583561854107e-06 -3.92651170063084e-06 1.22010993029688e-05 5.07356391591577e-07 2.5745915849703e-05 1038 1046 0 21 0 1038 1063 0 42 0 0 0 0 0 0 12 32 0 2971 0 0 0 0 0 2317 +891 894 0.999988909181272 -7.35543954986935e-05 0.00470915111244965 -0.000565215997045489 5.23924434608201e-05 0.999989901641419 0.00449375902980898 -0.00106507565337594 -0.00470943409348205 -0.00449346246640877 0.999978814788384 0.000919373912760423 4.79819063709306e-05 -6.19205818810698e-05 -1.90554854089331e-07 -1.79956705512008e-05 -9.85564439905338e-06 1.1077434582468e-05 -6.19205818810698e-05 0.000115342269182664 2.92388321051282e-06 4.42066820774828e-05 2.23231288001824e-05 -5.66119694123012e-06 -1.90554854089331e-07 2.92388321051282e-06 9.47326384430983e-06 -9.72481700757771e-07 4.46659517923539e-06 -2.14576272298905e-07 -1.79956705512008e-05 4.42066820774828e-05 -9.72481700757771e-07 5.65743734167016e-05 1.7102095437895e-05 7.00943545708934e-06 -9.85564439905338e-06 2.23231288001824e-05 4.46659517923539e-06 1.7102095437895e-05 2.35712338601376e-05 1.99679017494067e-06 1.1077434582468e-05 -5.66119694123012e-06 -2.14576272298905e-07 7.00943545708934e-06 1.99679017494067e-06 2.67447813142726e-05 948 953 0 22 0 946 968 0 38 0 0 0 0 0 0 14 38 0 2894 0 0 0 0 0 1435 +891 921 0.999988387544494 -0.000149226387171905 0.0048168981354429 0.00208048728555308 0.000133103404725803 0.99999438885645 0.00334731819511586 -0.00151577886911918 -0.00481737061533696 -0.00334663817899021 0.999982796328644 -0.00311865318198205 3.95937259046348e-05 -4.74740619367715e-05 4.69254197995966e-07 -1.17132884760232e-05 -7.97551746019473e-06 2.20645527215307e-05 -4.74740619367715e-05 9.1189781741875e-05 1.74177832262799e-06 3.56127775700134e-05 1.78255882612334e-05 -2.36734309833878e-05 4.69254197995966e-07 1.74177832262799e-06 8.68412290399405e-06 -7.54864561359843e-07 4.28331863158585e-06 2.56332689809112e-07 -1.17132884760232e-05 3.56127775700134e-05 -7.54864561359843e-07 5.60085843932546e-05 1.2980750531093e-05 -2.47236363418843e-06 -7.97551746019473e-06 1.78255882612334e-05 4.28331863158585e-06 1.2980750531093e-05 2.37355595814446e-05 -2.45142911531503e-06 2.20645527215307e-05 -2.36734309833878e-05 2.56332689809112e-07 -2.47236363418843e-06 -2.45142911531503e-06 3.12415387591513e-05 955 949 0 18 0 954 969 0 41 0 0 0 0 0 0 13 36 0 2864 0 0 0 0 0 2472 +892 928 0.999993447928152 -0.000236593790638063 -0.00361221872876643 -0.0038068344158533 0.000237696447403207 0.999999925289161 0.000304831218634353 -0.00401107906020801 0.00361214633772102 -0.000305687832917378 0.999993429455306 0.000796975090400073 2.80545937285535e-05 -2.44689072485661e-05 -3.46732742025565e-06 5.1599926085432e-07 -3.49025467801933e-06 1.88739212533107e-05 -2.44689072485661e-05 4.47179746531285e-05 5.22765542305922e-06 5.63158440658218e-06 3.28330107457641e-06 -1.85442030953889e-05 -3.46732742025565e-06 5.22765542305922e-06 1.07494638085559e-05 -5.67918922729333e-06 2.88112623374095e-06 -3.26376237002022e-06 5.1599926085432e-07 5.63158440658218e-06 -5.67918922729333e-06 4.41335602909111e-05 8.45400554287526e-06 6.52335988619469e-06 -3.49025467801933e-06 3.28330107457641e-06 2.88112623374095e-06 8.45400554287526e-06 2.17013271892061e-05 -2.48147847141813e-06 1.88739212533107e-05 -1.85442030953889e-05 -3.26376237002022e-06 6.52335988619469e-06 -2.48147847141813e-06 2.7810893971943e-05 1062 1059 0 17 0 1059 1082 0 44 0 0 0 0 0 0 16 41 0 2876 0 0 0 0 0 2376 +892 918 0.999995767509697 8.07511508977994e-05 -0.00290834006689161 -0.000708135693234204 -8.91259516009301e-05 0.999995850068094 -0.00287956648726194 -0.00525080857017345 0.00290809546917044 0.00287981350810074 0.999991624792378 -0.00104890355193522 3.73420565244957e-05 -3.28680812331307e-05 -5.60706857822864e-06 2.7126031534141e-06 -5.14927889173956e-06 1.28323468620639e-05 -3.28680812331307e-05 4.71751020358348e-05 6.66444677689615e-06 1.91797291942839e-06 2.84351117685375e-06 -8.73303979594395e-06 -5.60706857822864e-06 6.66444677689615e-06 1.02586234290094e-05 -2.71874327252678e-06 3.61015340518841e-06 -4.9319271237086e-06 2.7126031534141e-06 1.91797291942839e-06 -2.71874327252678e-06 3.30021299472283e-05 2.90273015739345e-06 1.09162790212452e-05 -5.14927889173956e-06 2.84351117685375e-06 3.61015340518841e-06 2.90273015739345e-06 2.2524083302506e-05 6.64475939463385e-08 1.28323468620639e-05 -8.73303979594395e-06 -4.9319271237086e-06 1.09162790212452e-05 6.64475939463385e-08 2.89944090992617e-05 1083 1084 0 20 0 1080 1104 0 41 0 0 0 0 0 0 11 34 0 2654 0 0 0 0 0 2130 +892 919 0.999999772450484 -2.48759848257982e-05 -0.000674151440877279 -0.000509447411684237 2.46031933748117e-05 0.999999917826752 -0.000404649443359052 -0.00244700478386916 0.000674161451533478 0.000404632765003004 0.999999690889284 0.000152389963258714 2.61232368244472e-05 -2.46789737209043e-05 -4.70207440554405e-06 2.37443496606642e-06 -4.95791243080808e-06 1.27744361949321e-05 -2.46789737209043e-05 4.17684065012689e-05 5.4105596830749e-06 4.74376101496965e-06 7.56063258686894e-06 -9.1893145531686e-06 -4.70207440554405e-06 5.4105596830749e-06 1.08977436860882e-05 -3.72928530549618e-06 3.8732688675049e-06 -3.74550126283901e-06 2.37443496606642e-06 4.74376101496965e-06 -3.72928530549618e-06 3.72647314471016e-05 1.0454268223636e-06 8.55135332586354e-06 -4.95791243080808e-06 7.56063258686894e-06 3.8732688675049e-06 1.0454268223636e-06 2.09683399339474e-05 -2.79345211517655e-06 1.27744361949321e-05 -9.1893145531686e-06 -3.74550126283901e-06 8.55135332586354e-06 -2.79345211517655e-06 2.49044805659465e-05 1093 1093 0 14 0 1095 1116 0 37 0 0 0 0 0 0 13 37 0 2741 0 0 0 0 0 2370 +891 929 0.999787478565355 -0.0205669121632668 0.00141415274904443 -0.00645625296937181 0.0205313292465063 0.99955275490476 0.0217429225651963 -0.0020710568118677 -0.0018607050547346 -0.0217092672924039 0.999762594564493 -0.00968476215388431 3.03660570589446e-05 -3.32649234708122e-05 -4.40038434737218e-06 8.58535616994125e-07 -3.05142568421761e-06 1.59004648313981e-05 -3.32649234708122e-05 7.19046203861833e-05 6.77296663202982e-06 1.55518720397972e-05 1.12975891727636e-05 -1.58747162124521e-05 -4.40038434737218e-06 6.77296663202982e-06 9.5562457071157e-06 -1.64683249982807e-06 3.6145900390246e-06 -2.87970558767718e-06 8.58535616994125e-07 1.55518720397972e-05 -1.64683249982807e-06 4.21430093129911e-05 4.02832809398471e-06 4.56925469516919e-06 -3.05142568421761e-06 1.12975891727636e-05 3.6145900390246e-06 4.02832809398471e-06 1.98869814679711e-05 -4.81894673574333e-06 1.59004648313981e-05 -1.58747162124521e-05 -2.87970558767718e-06 4.56925469516919e-06 -4.81894673574333e-06 2.75009039627797e-05 1041 1041 0 2 0 1062 1065 0 14 0 0 0 0 0 0 45 68 0 3040 0 0 0 0 0 2026 +892 920 0.999998331808171 -0.000452919058980097 0.001769532480741 0.00140291089006661 0.000456131793597718 0.999998247764419 -0.00181560234590021 -0.00404104583219001 -0.00176870705919724 0.00181640645715148 0.999996786166296 -0.00329110016016016 3.20740681988655e-05 -2.83217814198089e-05 -4.82863964390296e-06 3.98849133281955e-07 -3.39720173572103e-06 9.01347374102647e-06 -2.83217814198089e-05 4.15502358180029e-05 6.32835728550427e-06 5.95161044490378e-06 3.30668576806145e-06 -5.11453267031953e-06 -4.82863964390296e-06 6.32835728550427e-06 1.11752692789501e-05 -4.06679859315485e-06 3.53554197635143e-06 -5.4511060930396e-06 3.98849133281955e-07 5.95161044490378e-06 -4.06679859315485e-06 4.06388179357072e-05 4.53272717226895e-06 1.1100502617138e-05 -3.39720173572103e-06 3.30668576806145e-06 3.53554197635143e-06 4.53272717226895e-06 2.07177752145222e-05 1.18638821220493e-06 9.01347374102647e-06 -5.11453267031953e-06 -5.4511060930396e-06 1.1100502617138e-05 1.18638821220493e-06 2.81172799191257e-05 1075 1077 0 19 0 1074 1097 0 39 0 0 0 0 0 0 11 33 0 2745 0 0 0 0 0 2090 +892 924 0.99999564554822 0.000278228744959057 -0.00293793692299269 0.00142279266032656 -0.000277217616905932 0.999999902212937 0.000344564231034595 -0.00120479302688703 0.00293803250337403 -0.000343748282773854 0.999995624891493 0.00194224134159221 2.95833510231139e-05 -2.97970194448901e-05 -5.01917204652913e-06 -2.92130364144999e-06 -1.86301444858557e-06 8.32437228477598e-06 -2.97970194448901e-05 4.34972710548069e-05 6.68910055633202e-06 6.93874174899727e-06 3.63098837419831e-06 -5.73239080132654e-06 -5.01917204652913e-06 6.68910055633202e-06 1.15969141309216e-05 -5.710931963805e-06 1.13753457206596e-06 -3.07038898687348e-06 -2.92130364144999e-06 6.93874174899727e-06 -5.710931963805e-06 4.98324014997758e-05 1.29471414385622e-05 7.03223908657107e-06 -1.86301444858557e-06 3.63098837419831e-06 1.13753457206596e-06 1.29471414385622e-05 2.6505446246233e-05 -3.86783337845001e-07 8.32437228477598e-06 -5.73239080132654e-06 -3.07038898687348e-06 7.03223908657107e-06 -3.86783337845001e-07 2.67182254666782e-05 1090 1087 0 19 0 1087 1105 0 40 0 0 0 0 0 0 17 37 0 2925 0 0 0 0 0 2299 +892 922 0.999999982484025 -0.000164407489575403 -8.94546113296385e-05 0.00186240819892784 0.000164443665947702 0.999999904647403 0.000404553415979942 -0.000855425658483864 8.93880911883886e-05 -0.000404568119138018 0.999999914167199 -0.000565106344618388 2.10580910913069e-05 -2.02938117032819e-05 -3.30681558762226e-06 -5.64711201004415e-07 -3.13009545616709e-06 1.21610672382796e-05 -2.02938117032819e-05 2.51152562606327e-05 4.01243767006659e-06 3.15282346372816e-06 3.94228045869493e-06 -1.07960562808057e-05 -3.30681558762226e-06 4.01243767006659e-06 9.75708718966597e-06 -4.37262670464568e-06 3.01281414630909e-06 -4.15035787546415e-06 -5.64711201004415e-07 3.15282346372816e-06 -4.37262670464568e-06 3.69216746262066e-05 4.67013987599611e-06 7.59314363740456e-06 -3.13009545616709e-06 3.94228045869493e-06 3.01281414630909e-06 4.67013987599611e-06 1.93511700039305e-05 -1.8031583707207e-06 1.21610672382796e-05 -1.07960562808057e-05 -4.15035787546415e-06 7.59314363740456e-06 -1.8031583707207e-06 2.1527608707061e-05 1126 1123 0 16 0 1127 1147 0 40 0 0 0 0 0 0 18 43 0 2983 0 0 0 0 0 2320 +892 929 0.999789050357613 -0.0203944105890138 0.0024336807000365 -0.00265119527627243 0.0203489336761922 0.999640813891062 0.0174403010712727 -2.79979100964996e-05 -0.00278849121657901 -0.0173870992388446 0.999844944527297 -0.00930703834109514 3.14221157913462e-05 -3.02449334660017e-05 -7.26469453914785e-06 2.89166786135785e-06 -7.01550602152946e-07 1.78142162092168e-05 -3.02449334660017e-05 4.1990654944854e-05 6.88435612589434e-06 5.14091913522004e-06 4.29971902457211e-06 -1.76849082664252e-05 -7.26469453914785e-06 6.88435612589434e-06 1.06668523020786e-05 -1.7171569292431e-06 7.99133586815035e-07 -5.19440778606311e-06 2.89166786135785e-06 5.14091913522004e-06 -1.7171569292431e-06 4.08202141707692e-05 3.88730837774752e-06 6.29172454756143e-06 -7.01550602152946e-07 4.29971902457211e-06 7.99133586815035e-07 3.88730837774752e-06 2.52646112104795e-05 -3.34670896801677e-06 1.78142162092168e-05 -1.76849082664252e-05 -5.19440778606311e-06 6.29172454756143e-06 -3.34670896801677e-06 2.75993767081267e-05 1016 1014 0 1 0 1033 1035 0 11 0 0 0 0 0 0 43 67 0 3037 0 0 0 0 0 1668 +892 888 0.999317658117142 -0.00128185661079062 -0.0369130738207966 0.0172312508532732 -0.00118009615670402 0.997779256031875 -0.0665970239991154 0.0175150161545625 0.0369164671702364 0.0665951430369151 0.997096916741578 -0.00453978733097472 7.23930820200269e-05 -8.16400653214351e-05 5.90917609405659e-06 -1.73219321985995e-05 -1.1948991653708e-05 1.06843590084952e-05 -8.16400653214351e-05 0.000131057862252696 -7.80664039622718e-06 5.01131684321228e-05 2.38327953884548e-05 -2.30773176029016e-06 5.90917609405659e-06 -7.80664039622718e-06 1.17010922741774e-05 -6.19997523496908e-06 1.86580945649465e-06 5.36208879420792e-07 -1.73219321985995e-05 5.01131684321228e-05 -6.19997523496908e-06 7.98472828773901e-05 2.23996077588329e-05 4.72775040955136e-06 -1.1948991653708e-05 2.38327953884548e-05 1.86580945649465e-06 2.23996077588329e-05 2.89261339928216e-05 5.6577923188766e-06 1.06843590084952e-05 -2.30773176029016e-06 5.36208879420792e-07 4.72775040955136e-06 5.6577923188766e-06 4.08320329266115e-05 923 920 0 10 0 921 932 0 24 0 0 0 0 0 0 14 29 0 2506 0 0 0 0 0 1890 +892 926 0.999989967273693 0.000325887746418651 -0.00446756635491565 -0.000958615577748596 -0.00032098253117527 0.999999344986113 0.00109863440682085 -0.00115028827845221 0.00446792146008862 -0.00109718937376574 0.999989416870651 0.00365840309196181 3.49709378729192e-05 -3.36530154181965e-05 -1.79817698004512e-06 -6.177870959017e-06 -8.3471520045836e-06 1.14970022775584e-05 -3.36530154181965e-05 4.74631186127183e-05 3.54824014989979e-06 1.23861728485915e-05 1.02023604236505e-05 -7.38611247865965e-06 -1.79817698004512e-06 3.54824014989979e-06 1.09582625468464e-05 -6.685767830712e-06 2.5801381809027e-06 -4.22717397888892e-06 -6.177870959017e-06 1.23861728485915e-05 -6.685767830712e-06 5.37961787065441e-05 1.70710854212489e-05 1.26517326585422e-05 -8.3471520045836e-06 1.02023604236505e-05 2.5801381809027e-06 1.70710854212489e-05 2.5566511495015e-05 2.6149037306823e-06 1.14970022775584e-05 -7.38611247865965e-06 -4.22717397888892e-06 1.26517326585422e-05 2.6149037306823e-06 2.60142463002226e-05 1069 1076 0 20 0 1070 1092 0 38 0 0 0 0 0 0 15 35 0 2931 0 0 0 0 0 2309 +892 921 0.999998548527676 -0.000165201250878936 -0.00169577448023477 0.000463369352096542 0.000164820973809736 0.99999996124224 -0.000224387089136335 -0.00237715436847612 0.00169581148353816 0.000224107264243491 0.999998536998603 -0.00175086306235607 3.17633646761745e-05 -3.09494293364081e-05 -2.12782656608677e-06 -2.56661445134871e-06 -3.52571453965774e-06 8.25892621092371e-06 -3.09494293364081e-05 4.14926695413548e-05 5.05924861054587e-06 6.39392768425895e-06 5.5635674279959e-06 -5.59171505554101e-06 -2.12782656608677e-06 5.05924861054587e-06 1.18451370546906e-05 -5.86789274893072e-06 3.5791974240103e-06 -3.02563227638436e-06 -2.56661445134871e-06 6.39392768425895e-06 -5.86789274893072e-06 4.16954071100895e-05 8.13901711044969e-06 1.01294306546716e-05 -3.52571453965774e-06 5.5635674279959e-06 3.5791974240103e-06 8.13901711044969e-06 2.35346452101231e-05 1.39418193344813e-06 8.25892621092371e-06 -5.59171505554101e-06 -3.02563227638436e-06 1.01294306546716e-05 1.39418193344813e-06 2.723483237655e-05 1068 1064 0 19 0 1067 1084 0 42 0 0 0 0 0 0 20 45 0 2873 0 0 0 0 0 1168 +893 895 0.999998187170892 -0.000319923296762883 -0.00187704661986144 -0.000925810894794738 0.000319606325490801 0.999999934617574 -0.000169164549783174 -0.00139574809674994 0.00187710061681604 0.000168564327143806 0.999998224038094 0.00230030481630749 2.90358282397559e-05 -2.75789050102942e-05 -4.71372538204851e-06 7.80518454399626e-07 -4.20472315662072e-06 1.07074007600201e-05 -2.75789050102942e-05 3.46761405344746e-05 5.96583836880447e-06 2.53587868565155e-06 5.61774990451008e-06 -8.92378868037257e-06 -4.71372538204851e-06 5.96583836880447e-06 1.14042972604537e-05 -4.87421872191571e-06 4.0709464223616e-06 -4.15328080940467e-07 7.80518454399626e-07 2.53587868565155e-06 -4.87421872191571e-06 3.48228402624375e-05 5.22009909368989e-06 1.61747489928824e-06 -4.20472315662072e-06 5.61774990451008e-06 4.0709464223616e-06 5.22009909368989e-06 2.20260849229473e-05 -2.29299589529271e-06 1.07074007600201e-05 -8.92378868037257e-06 -4.15328080940467e-07 1.61747489928824e-06 -2.29299589529271e-06 2.77457692917881e-05 1108 1113 0 24 0 1106 1127 0 40 0 0 0 0 0 0 13 39 0 2946 0 0 0 0 0 2182 +893 897 0.999990162434029 -0.000102160316819209 -0.00443447837230718 -0.00251862055619761 0.000104682203866426 0.999999832940916 0.000568471437741571 -0.000826708085494296 0.0044344195562651 -0.000568930056335311 0.999990006070956 0.00238511298317242 3.58735512920119e-05 -3.83315902406679e-05 -3.46192872760324e-06 -5.13737603023051e-06 -2.91960535208125e-06 1.45927068839443e-05 -3.83315902406679e-05 6.69913647186701e-05 4.25824323339056e-06 2.41979543252278e-05 8.81225457523211e-06 -7.21099583997753e-06 -3.46192872760324e-06 4.25824323339056e-06 1.15335712419178e-05 -8.00175759025883e-06 3.89190116268667e-06 -3.8220613203216e-06 -5.13737603023051e-06 2.41979543252278e-05 -8.00175759025883e-06 5.12045972867754e-05 1.15787075964324e-05 1.19894557946865e-05 -2.91960535208125e-06 8.81225457523211e-06 3.89190116268667e-06 1.15787075964324e-05 2.18396211123464e-05 2.85588631264499e-06 1.45927068839443e-05 -7.21099583997753e-06 -3.8220613203216e-06 1.19894557946865e-05 2.85588631264499e-06 2.96761629503858e-05 1107 1110 0 18 0 1105 1127 0 36 0 0 0 0 0 0 18 43 0 2920 0 0 0 0 0 1268 +893 924 0.999999797242983 -0.000558835717429446 0.000305313992961106 0.000692442864994593 0.000558829929870369 0.999999843673261 1.90410689819282e-05 -0.002301243672055 -0.00030532458606181 -1.8870446523943e-05 0.999999953210401 0.000580585330044384 2.65185399781602e-05 -2.75436325039963e-05 -4.69116760508828e-06 1.52048467986543e-06 1.71381239525793e-06 2.17106596600107e-05 -2.75436325039963e-05 7.80720701391041e-05 6.98301418848791e-06 2.98096365894057e-05 4.44463376051869e-06 -3.66949879698589e-05 -4.69116760508828e-06 6.98301418848791e-06 1.07271298960504e-05 -3.34271521164173e-06 3.01251174477984e-06 -2.7590597039776e-06 1.52048467986543e-06 2.98096365894057e-05 -3.34271521164173e-06 6.00351886790916e-05 7.91533278441434e-06 -5.68488175906019e-06 1.71381239525793e-06 4.44463376051869e-06 3.01251174477984e-06 7.91533278441434e-06 1.99270521059953e-05 -2.38345333538352e-06 2.17106596600107e-05 -3.66949879698589e-05 -2.7590597039776e-06 -5.68488175906019e-06 -2.38345333538352e-06 4.19826377390801e-05 1060 1056 0 12 0 1066 1084 0 41 0 0 0 0 0 0 13 35 0 2919 0 0 0 0 0 2569 +893 927 0.999999017596808 0.000270886974226373 0.00137529112036231 0.00343762159272021 -0.000271878754824633 0.999999703115694 0.00072100656443791 0.00106333677545902 -0.00137509540077333 -0.000721379768556085 0.999998794361207 -0.0021104438371362 1.97671393558647e-05 -1.76971414324403e-05 -3.60403728483496e-06 2.83241842740944e-06 -1.11436609678054e-06 1.46463643682003e-05 -1.76971414324403e-05 3.52406745362733e-05 5.88371352722727e-06 1.92224987288022e-06 5.21102176133631e-07 -1.86763875531133e-05 -3.60403728483496e-06 5.88371352722727e-06 1.08918611023192e-05 -5.16857172298761e-06 4.57895112734072e-06 -2.55281067627072e-06 2.83241842740944e-06 1.92224987288022e-06 -5.16857172298761e-06 3.34037763783913e-05 1.11330604129502e-06 8.73185853290725e-07 -1.11436609678054e-06 5.21102176133631e-07 4.57895112734072e-06 1.11330604129502e-06 1.7100764297677e-05 -1.70742996746297e-06 1.46463643682003e-05 -1.86763875531133e-05 -2.55281067627072e-06 8.73185853290725e-07 -1.70742996746297e-06 2.94675703198362e-05 1065 1070 0 19 0 1065 1092 0 41 0 0 0 0 0 0 15 42 0 2978 0 0 0 0 0 2575 +893 928 0.999999696141959 7.9628059489457e-05 -0.00077548395293718 -0.000346936604942588 -7.90037725904565e-05 0.999999672845604 0.000805026141286073 -0.00121655312832056 0.000775547801903665 -0.000804964630514542 0.99999937527858 -0.005621649965895 2.40306382835757e-05 -2.35379214360074e-05 -3.6965994047006e-06 -1.70083035266144e-06 -2.65459120417193e-06 1.26474561435569e-05 -2.35379214360074e-05 3.54125011067275e-05 6.06418781642775e-06 4.79626086887046e-06 5.25669580326223e-06 -1.11100521052875e-05 -3.6965994047006e-06 6.06418781642775e-06 1.18728328139777e-05 -7.27358644362213e-06 3.44132639234461e-06 -2.78364148171135e-06 -1.70083035266144e-06 4.79626086887046e-06 -7.27358644362213e-06 4.76465775118265e-05 1.27989697826934e-05 8.07381598025898e-06 -2.65459120417193e-06 5.25669580326223e-06 3.44132639234461e-06 1.27989697826934e-05 2.3810270677719e-05 -2.11947731236405e-06 1.26474561435569e-05 -1.11100521052875e-05 -2.78364148171135e-06 8.07381598025898e-06 -2.11947731236405e-06 2.35825078881293e-05 1117 1117 0 21 0 1114 1140 0 45 0 0 0 0 0 0 23 47 0 2899 0 0 0 0 0 2164 +893 896 0.999999646227826 0.000625616684185016 0.000562270386619913 0.0048666605601135 -0.000626761033225824 0.999997728159706 0.0020373625192548 0.00241255347630077 -0.000560994501247614 -0.0020377142076611 0.999997766500494 0.000902953036548623 4.07431790939551e-05 -4.16528165268854e-05 -5.1719080132888e-06 -1.20395609364223e-05 -8.19392458827611e-06 9.85959337242432e-06 -4.16528165268854e-05 5.90790767895336e-05 6.78639551412514e-06 2.07929725281546e-05 1.24877186299484e-05 -5.64553100656782e-06 -5.1719080132888e-06 6.78639551412514e-06 1.09908700972873e-05 -4.31952340580555e-06 4.25317338899746e-06 -2.97222387609305e-06 -1.20395609364223e-05 2.07929725281546e-05 -4.31952340580555e-06 5.18440527360926e-05 1.38291100621149e-05 1.15626045327205e-05 -8.19392458827611e-06 1.24877186299484e-05 4.25317338899746e-06 1.38291100621149e-05 2.43981118160224e-05 2.3837218961487e-06 9.85959337242432e-06 -5.64553100656782e-06 -2.97222387609305e-06 1.15626045327205e-05 2.3837218961487e-06 3.46338330970334e-05 1058 1053 0 10 0 1060 1083 0 41 0 0 0 0 0 0 16 43 0 2941 0 0 0 0 0 2123 +893 919 0.999997206613338 1.37866313255461e-05 -0.00236359375723291 -0.00158363647843369 -2.11551343761555e-05 0.999995140351515 -0.00311750313765749 -0.00378291119655261 0.00236353929113167 0.00311754443140936 0.999992347270087 -0.00120339315844849 4.73317978390757e-05 -4.5169142020269e-05 -4.25268309552015e-06 -2.5284336431402e-06 -1.06926075511312e-05 2.52178638951876e-05 -4.5169142020269e-05 7.0836560075093e-05 5.23408258126519e-06 1.45604952809593e-05 1.46658609698598e-05 -2.4090269279237e-05 -4.25268309552015e-06 5.23408258126519e-06 1.16918349668077e-05 -4.26823269913673e-06 3.06619653365135e-06 -3.97915248054681e-06 -2.5284336431402e-06 1.45604952809593e-05 -4.26823269913673e-06 5.40731723639603e-05 1.13324293609941e-05 7.52317107734337e-06 -1.06926075511312e-05 1.46658609698598e-05 3.06619653365135e-06 1.13324293609941e-05 3.07176197862883e-05 -2.43851039040795e-06 2.52178638951876e-05 -2.4090269279237e-05 -3.97915248054681e-06 7.52317107734337e-06 -2.43851039040795e-06 3.41726282158661e-05 1080 1083 0 19 0 1079 1103 0 40 0 0 0 0 0 0 20 44 0 2751 0 0 0 0 0 2143 +893 922 0.999999761216471 -0.000681322808893215 -0.000115612419511047 0.000465299789278459 0.000681235796422083 0.999999485958369 -0.00075099985882957 -0.00211371351830194 0.000116124033414747 0.000750920920184492 0.999999711316448 -0.0018312574052932 3.1919443979029e-05 -2.91877049601785e-05 -5.35156741075689e-06 4.54716267885538e-07 -2.73580186730356e-06 1.18535841468859e-05 -2.91877049601785e-05 4.67168169784503e-05 7.27871638121114e-06 6.95216938887486e-06 2.58480666793545e-06 -1.35104050361749e-05 -5.35156741075689e-06 7.27871638121114e-06 1.12347758640639e-05 -3.92721195186927e-06 3.45660847667857e-06 -1.68098493286588e-06 4.54716267885538e-07 6.95216938887486e-06 -3.92721195186927e-06 3.84251461751477e-05 1.94299169622346e-06 4.85555634539264e-06 -2.73580186730356e-06 2.58480666793545e-06 3.45660847667857e-06 1.94299169622346e-06 1.85014332747787e-05 -3.2770187160451e-06 1.18535841468859e-05 -1.35104050361749e-05 -1.68098493286588e-06 4.85555634539264e-06 -3.2770187160451e-06 2.80797345077307e-05 1086 1079 0 17 0 1079 1103 0 42 0 0 0 0 0 0 16 41 0 2985 0 0 0 0 0 2090 +893 921 0.999990063470469 -5.02264510027014e-05 -0.00445762690571032 -0.000458436417433235 4.76049797128615e-05 0.999999825882602 -0.000588190898046884 -0.00220554101514012 0.00445765567230124 0.000587972848232242 0.99998989174583 0.00298271303893087 5.73043006531345e-05 -6.30154032559581e-05 -2.79911659555564e-06 -1.10918402939241e-05 -8.93970474385041e-06 2.40039523689063e-05 -6.30154032559581e-05 9.56159449295454e-05 3.63477658908314e-06 3.27773157513151e-05 1.95741165234876e-05 -2.5572765084183e-05 -2.79911659555564e-06 3.63477658908314e-06 1.29615050939034e-05 -8.01904504887775e-06 1.47407036913994e-06 -1.66640245550704e-06 -1.10918402939241e-05 3.27773157513151e-05 -8.01904504887775e-06 7.13320720169958e-05 2.00055221610698e-05 4.25584959601132e-06 -8.93970474385041e-06 1.95741165234876e-05 1.47407036913994e-06 2.00055221610698e-05 3.10858414984576e-05 -1.21676840001975e-06 2.40039523689063e-05 -2.5572765084183e-05 -1.66640245550704e-06 4.25584959601132e-06 -1.21676840001975e-06 3.4348516212611e-05 1073 1064 0 10 0 1076 1095 0 41 0 0 0 0 0 0 16 43 0 2872 0 0 0 0 0 2083 +893 926 0.999998318625203 -7.96552884260363e-05 0.00183204852594151 0.00267697114651551 7.8160712606125e-05 0.999999664138139 0.00081585201648627 -0.000717315020166671 -0.00183211289755397 -0.000815707450514935 0.999997988989821 -0.0021725873365862 2.94335819289824e-05 -3.08482559170414e-05 -5.96438197602098e-06 2.05472989664914e-07 -4.27121990019951e-06 1.92115023669277e-05 -3.08482559170414e-05 6.47644242706613e-05 8.36235542392893e-06 1.7518626629958e-05 6.88303312230785e-06 -2.96620265864937e-05 -5.96438197602098e-06 8.36235542392893e-06 1.1251509322116e-05 -5.90073375964471e-06 3.8215952054006e-06 -3.82375300319737e-06 2.05472989664914e-07 1.7518626629958e-05 -5.90073375964471e-06 5.5608171485468e-05 7.19177613881563e-06 -3.80221701026991e-06 -4.27121990019951e-06 6.88303312230785e-06 3.8215952054006e-06 7.19177613881563e-06 2.11373556050266e-05 -4.42495201208133e-06 1.92115023669277e-05 -2.96620265864937e-05 -3.82375300319737e-06 -3.80221701026991e-06 -4.42495201208133e-06 3.38590737009698e-05 1073 1077 0 20 0 1073 1100 0 43 0 0 0 0 0 0 16 43 0 2918 0 0 0 0 0 2575 +893 925 0.999996842952184 0.000285671369581638 -0.00249649304715756 0.000604506403230552 -0.000282570249171478 0.99999918822932 0.00124245513194489 0.000530751040814918 0.00249684595443688 -0.00124174577479224 0.999996111906297 0.00288280708171377 2.68477248441418e-05 -2.85716090534234e-05 -3.02495186774435e-06 -4.36517597109375e-06 -4.02122266436961e-06 1.13379266982457e-05 -2.85716090534234e-05 5.10348888175042e-05 4.5204515108019e-06 1.45988821131174e-05 6.69344054628244e-06 -1.10006540625976e-05 -3.02495186774435e-06 4.5204515108019e-06 1.06501726208912e-05 -2.2046076621203e-06 2.90835059399298e-06 -2.25341033171971e-06 -4.36517597109375e-06 1.45988821131174e-05 -2.2046076621203e-06 4.28559289200143e-05 8.60603160147362e-06 6.49404670604003e-06 -4.02122266436961e-06 6.69344054628244e-06 2.90835059399298e-06 8.60603160147362e-06 1.99262496290933e-05 -1.33917565731088e-06 1.13379266982457e-05 -1.10006540625976e-05 -2.25341033171971e-06 6.49404670604003e-06 -1.33917565731088e-06 2.47841833037657e-05 1093 1098 0 20 0 1091 1116 0 44 0 0 0 0 0 0 16 43 0 2906 0 0 0 0 0 2183 +893 929 0.999779362484897 -0.020791292300688 -0.00299140665258224 -0.00500935544607882 0.0208436346483197 0.999608155122887 0.0186836588082913 0.000393038318554442 0.00260177707368055 -0.0187418882795897 0.999820970164046 -0.00735564364429608 3.3246851818708e-05 -3.43716064317891e-05 -5.98723234156857e-06 -1.84907973951517e-06 3.95468425412942e-08 1.43179373179409e-05 -3.43716064317891e-05 6.49524749709064e-05 8.05125855017593e-06 1.76696219098493e-05 4.66631207075513e-06 -1.34976385835503e-05 -5.98723234156857e-06 8.05125855017593e-06 1.04177222065884e-05 4.58966491254633e-07 7.57599904655509e-07 -1.90734007853068e-06 -1.84907973951517e-06 1.76696219098493e-05 4.58966491254633e-07 4.64592819951944e-05 5.13928060198103e-06 4.12978832416901e-06 3.95468425412942e-08 4.66631207075513e-06 7.57599904655509e-07 5.13928060198103e-06 2.33298714781145e-05 -2.54213915754314e-06 1.43179373179409e-05 -1.34976385835503e-05 -1.90734007853068e-06 4.12978832416901e-06 -2.54213915754314e-06 2.61767952975519e-05 990 988 0 2 0 1007 1009 0 14 0 0 0 0 0 0 45 71 0 3042 0 0 0 0 0 2037 +893 923 0.999996404657284 -0.000318769396020057 -0.00266252860606327 -0.00145589942047921 0.000316125179200918 0.99999945652684 -0.000993484219799154 -0.0022449617891282 0.00266284385141514 0.000992638955550181 0.99999596195711 -0.00209589983901265 2.96566072313573e-05 -2.6341166932091e-05 -3.95231110048532e-06 -2.57382501662681e-06 -6.34287883765758e-07 1.07782266466071e-05 -2.6341166932091e-05 3.81687002238023e-05 5.95932982863697e-06 2.92751313419295e-06 2.48171794392207e-07 -1.02990329223452e-05 -3.95231110048532e-06 5.95932982863697e-06 1.25057503391734e-05 -2.42872538991042e-06 2.54191173663455e-06 -1.55403721541354e-06 -2.57382501662681e-06 2.92751313419295e-06 -2.42872538991042e-06 3.52184580609322e-05 4.78700435764877e-06 6.79747381749054e-06 -6.34287883765758e-07 2.48171794392207e-07 2.54191173663455e-06 4.78700435764877e-06 1.9226436728606e-05 -1.53349352156631e-06 1.07782266466071e-05 -1.02990329223452e-05 -1.55403721541354e-06 6.79747381749054e-06 -1.53349352156631e-06 2.3888860999644e-05 1084 1087 0 21 0 1078 1099 0 39 0 0 0 0 0 0 11 36 0 2876 0 0 0 0 0 2160 +893 920 0.999999407962013 -0.000674585697638145 -0.000853820683983362 0.00253418179514384 0.000675322269213679 0.99999939985874 0.000862683019543983 -0.00231946125004456 0.000853238217943762 -0.000863259112924674 0.999999263383852 0.00441265236326656 3.03166545156715e-05 -2.76550769609536e-05 -7.68523978721428e-06 2.92978887366083e-06 9.39689235920395e-07 1.21230713767899e-05 -2.76550769609536e-05 4.41562390414642e-05 8.89258256799342e-06 1.35945025696141e-06 -2.18048428128271e-06 -5.03201134359714e-06 -7.68523978721428e-06 8.89258256799342e-06 1.38131428808109e-05 -5.3582507568418e-06 3.58874224332245e-06 -6.16451513826429e-06 2.92978887366083e-06 1.35945025696141e-06 -5.3582507568418e-06 3.10413689598494e-05 -3.1869178272633e-07 6.44699066654451e-06 9.39689235920395e-07 -2.18048428128271e-06 3.58874224332245e-06 -3.1869178272633e-07 2.22613800963586e-05 2.52783035641396e-08 1.21230713767899e-05 -5.03201134359714e-06 -6.16451513826429e-06 6.44699066654451e-06 2.52783035641396e-08 2.52672098690624e-05 1117 1118 0 17 0 1117 1137 0 39 0 0 0 0 0 0 19 44 0 2768 0 0 0 0 0 1225 +894 896 0.999999776016656 -0.000229487074068978 -0.000628730721531835 0.00245707572192037 0.000229380918942673 0.999999959427362 -0.000168907275049514 0.000621018134468365 0.000628769458058912 0.000168763018386426 0.999999788083984 0.00152150045682667 4.18489118715192e-05 -4.40603598655241e-05 -4.55157703421094e-06 -1.1971970068093e-05 -8.05768694264895e-06 -5.57544419982019e-07 -4.40603598655241e-05 6.64120944063884e-05 5.92563277423248e-06 2.65369211824679e-05 1.47839888132716e-05 6.10042378750337e-06 -4.55157703421094e-06 5.92563277423248e-06 1.30915046182887e-05 -6.58925356290218e-06 3.32831360451553e-06 -1.65001978931256e-06 -1.1971970068093e-05 2.65369211824679e-05 -6.58925356290218e-06 5.44208323170215e-05 1.50009909106881e-05 1.0973636380874e-05 -8.05768694264895e-06 1.47839888132716e-05 3.32831360451553e-06 1.50009909106881e-05 2.68768352937321e-05 7.21897136460467e-06 -5.57544419982019e-07 6.10042378750337e-06 -1.65001978931256e-06 1.0973636380874e-05 7.21897136460467e-06 4.28106462214799e-05 1069 1079 0 32 0 1063 1082 0 35 0 0 0 0 0 0 15 32 0 2919 0 0 0 0 0 1204 +894 925 0.999999392390247 0.000408112698076003 0.00102404255898353 0.00116625365084698 -0.000409343070528355 0.999999194340944 0.00120156386119538 0.0015657296954851 -0.00102355136048507 -0.00120198231583891 0.999998753789786 -0.00171984490738873 2.56719189206598e-05 -2.36023951988151e-05 -3.32688393116896e-06 -6.00631819645847e-07 -1.74242650768499e-06 1.02983771356173e-05 -2.36023951988151e-05 3.64522093068641e-05 6.98016351008296e-06 -1.05422031127398e-07 -5.31111004502384e-07 -7.83599406309916e-06 -3.32688393116896e-06 6.98016351008296e-06 1.53203800849064e-05 -5.80492054484996e-06 2.26094152361641e-06 -2.14826157519441e-06 -6.00631819645847e-07 -1.05422031127398e-07 -5.80492054484996e-06 3.18900195898316e-05 2.34220810240111e-06 6.67471350092458e-06 -1.74242650768499e-06 -5.31111004502384e-07 2.26094152361641e-06 2.34220810240111e-06 2.33465839444709e-05 -2.06490164787663e-06 1.02983771356173e-05 -7.83599406309916e-06 -2.14826157519441e-06 6.67471350092458e-06 -2.06490164787663e-06 2.19030385267116e-05 1111 1114 0 10 0 1117 1140 0 42 0 0 0 0 0 0 10 36 0 2898 0 0 0 0 0 1268 +894 924 0.999999597442254 9.20382192444393e-06 -0.000897234985347681 0.00200259494400657 -8.74959716312999e-06 0.999999871816115 0.00050625210916668 -0.000755256175807581 0.000897239529790876 -0.00050624405492629 0.999999469338951 0.00277208308581977 2.34138650432879e-05 -2.15486016297694e-05 -4.59916631435761e-06 -2.56894723671258e-06 -6.70006771592825e-08 6.31156925532977e-06 -2.15486016297694e-05 2.77200322506446e-05 5.19822083470368e-06 3.96512402182154e-06 3.55776752147087e-08 -5.41667144726629e-06 -4.59916631435761e-06 5.19822083470368e-06 1.05625686142608e-05 -2.16839375311915e-06 2.3768270820228e-06 -5.1085200804232e-07 -2.56894723671258e-06 3.96512402182154e-06 -2.16839375311915e-06 3.77678710138751e-05 5.67929727502504e-06 1.91843076876641e-06 -6.70006771592825e-08 3.55776752147087e-08 2.3768270820228e-06 5.67929727502504e-06 2.07840876466233e-05 -2.1321325600983e-06 6.31156925532977e-06 -5.41667144726629e-06 -5.1085200804232e-07 1.91843076876641e-06 -2.1321325600983e-06 2.66655183928809e-05 1098 1091 0 18 0 1092 1111 0 38 0 0 0 0 0 0 15 39 0 2925 0 0 0 0 0 2326 +894 926 0.999999775453445 -0.000220776254659952 -0.000632732885288178 0.000359530446036051 0.000221163437327266 0.999999788322398 0.000611916573669771 -0.000616432999105854 0.000632597654703499 -0.000612056373645833 0.999999612603526 0.00386970185885715 2.80045633103409e-05 -2.80516616868542e-05 -5.25230038448937e-06 -1.58658060054541e-07 -2.91361832444927e-06 1.3380362033412e-05 -2.80516616868542e-05 4.49778626667724e-05 7.20830057676421e-06 8.01222434693255e-06 5.84299124581951e-06 -1.23289985664244e-05 -5.25230038448937e-06 7.20830057676421e-06 1.20979074218625e-05 -7.17858311346161e-06 3.88666029198594e-06 -2.26873027580332e-06 -1.58658060054541e-07 8.01222434693255e-06 -7.17858311346161e-06 4.59319451853862e-05 8.14979982953118e-06 4.62717555022549e-06 -2.91361832444927e-06 5.84299124581951e-06 3.88666029198594e-06 8.14979982953118e-06 2.16267083574764e-05 -1.17829383770498e-06 1.3380362033412e-05 -1.23289985664244e-05 -2.26873027580332e-06 4.62717555022549e-06 -1.17829383770498e-06 2.56786813038552e-05 1067 1076 0 21 0 1068 1094 0 40 0 0 0 0 0 0 15 43 0 2936 0 0 0 0 0 2340 +894 923 0.999999823111456 0.000119017203033257 -0.000582762354378819 8.29523553727917e-05 -0.00011883825590349 0.999999945785963 0.000307092071313259 0.000109626381945029 0.000582798872024321 -0.000307022762530389 0.999999783041225 -0.00112699338925832 2.77514836037607e-05 -2.69150367552678e-05 -4.26316001575264e-06 2.08569725214842e-07 -2.10439945145218e-06 1.61778049541676e-05 -2.69150367552678e-05 4.58155515561522e-05 6.05480634463533e-06 5.10118444335022e-06 2.41871929582506e-06 -1.56362071960144e-05 -4.26316001575264e-06 6.05480634463533e-06 1.32204074351018e-05 -5.10229329689677e-06 6.59312247144992e-07 -1.88720277111659e-06 2.08569725214842e-07 5.10118444335022e-06 -5.10229329689677e-06 3.68047853740659e-05 8.31467933735163e-06 6.13969143085031e-06 -2.10439945145218e-06 2.41871929582506e-06 6.59312247144992e-07 8.31467933735163e-06 2.33058217412429e-05 -3.0599360022301e-06 1.61778049541676e-05 -1.56362071960144e-05 -1.88720277111659e-06 6.13969143085031e-06 -3.0599360022301e-06 2.59069040353661e-05 1119 1123 0 13 0 1125 1146 0 36 0 0 0 0 0 0 15 39 0 2880 0 0 0 0 0 2375 +894 929 0.999775087914378 -0.0208111504697388 0.00408284238281663 -0.000995768519343428 0.0207257167001015 0.999586004396098 0.0199565649026066 0.0035994245106376 -0.00449647117906597 -0.0198674565954151 0.99979251143193 -0.0114034197933431 2.42800182929678e-05 -2.07037683236756e-05 -5.20977046783005e-06 3.25033160477756e-06 2.91401933396493e-06 8.87516687748034e-06 -2.07037683236756e-05 3.96138054991284e-05 6.97781839866712e-06 4.28365521184039e-06 -2.38444922565398e-06 -7.60869727037277e-06 -5.20977046783005e-06 6.97781839866712e-06 9.93502362341768e-06 -9.47002850794035e-07 1.23488358127991e-06 -1.65259674717699e-06 3.25033160477756e-06 4.28365521184039e-06 -9.47002850794035e-07 3.13859010677147e-05 -1.85857365588641e-06 2.05178391894535e-06 2.91401933396493e-06 -2.38444922565398e-06 1.23488358127991e-06 -1.85857365588641e-06 2.02179413218579e-05 -2.88393637421674e-06 8.87516687748034e-06 -7.60869727037277e-06 -1.65259674717699e-06 2.05178391894535e-06 -2.88393637421674e-06 2.29989370807538e-05 1034 1033 0 4 0 1049 1048 0 9 0 0 0 0 0 0 41 64 0 3044 0 0 0 0 0 1694 +894 921 0.999999491934393 -0.000185719098163682 0.000990777155985708 0.00285509757142724 0.000186502377740268 0.999999670133937 -0.000790537083780698 -0.00128566201163449 -0.000990630011327684 0.000790721464431396 0.99999919670555 -0.000359391073407298 2.43430982263309e-05 -2.29363367407255e-05 -5.06972642277571e-08 -4.76943200714834e-06 4.4369937669575e-08 6.43334959134028e-06 -2.29363367407255e-05 2.6481728153235e-05 1.70997150270093e-06 5.6079706460552e-06 4.61456448973085e-07 -5.57078674494971e-06 -5.06972642277571e-08 1.70997150270093e-06 1.15412727255431e-05 -6.41839362536459e-06 2.66299063854479e-06 -1.15338786364004e-06 -4.76943200714834e-06 5.6079706460552e-06 -6.41839362536459e-06 3.81878648666553e-05 4.74652936875839e-06 4.45384922190016e-06 4.4369937669575e-08 4.61456448973085e-07 2.66299063854479e-06 4.74652936875839e-06 2.29846845742713e-05 4.68869983796184e-06 6.43334959134028e-06 -5.57078674494971e-06 -1.15338786364004e-06 4.45384922190016e-06 4.68869983796184e-06 2.56336506097908e-05 1156 1151 0 24 0 1151 1169 0 41 0 0 0 0 0 0 12 39 0 2869 0 0 0 0 0 1219 +894 922 0.99999663804809 3.54254849709124e-05 -0.00259280495839791 0.000196574589849845 -3.68723761681256e-05 0.999999843640869 -0.000557995219991283 8.57398566879524e-05 0.0025927847857379 0.000558088946917944 0.999996482995706 0.000635216106964565 2.79692099630615e-05 -3.22163785569188e-05 -6.31811435400453e-06 3.85299061907299e-07 2.42429695000361e-08 1.0040581580164e-05 -3.22163785569188e-05 6.03520970660786e-05 7.37028019322189e-06 1.39680401593959e-05 4.26241752151688e-06 -1.2298954683894e-05 -6.31811435400453e-06 7.37028019322189e-06 1.13247307970333e-05 -5.17805491712401e-06 2.71990594510027e-06 -3.93976567350565e-07 3.85299061907299e-07 1.39680401593959e-05 -5.17805491712401e-06 4.57340561696675e-05 7.99818013554413e-06 1.75457289775962e-06 2.42429695000361e-08 4.26241752151688e-06 2.71990594510027e-06 7.99818013554413e-06 2.07283136756612e-05 -2.58948586399542e-06 1.0040581580164e-05 -1.2298954683894e-05 -3.93976567350565e-07 1.75457289775962e-06 -2.58948586399542e-06 2.67856616806628e-05 1089 1095 0 24 0 1088 1110 0 40 0 0 0 0 0 0 11 33 0 2976 0 0 0 0 0 2319 +894 897 0.999998412656029 -0.000233305108125731 0.00176642411375507 -6.56597781496815e-05 0.000233204584097057 0.999999971176808 5.71139621456068e-05 -0.00084516253240384 -0.0017664373878202 -5.6701933285316e-05 0.999998438240703 -0.00366069680410181 4.19875947294177e-05 -4.32182780732946e-05 -5.12861891545553e-06 -5.90822945042197e-06 -4.37515909685203e-06 9.71319001803284e-06 -4.32182780732946e-05 6.63474858763166e-05 6.08484427584749e-06 1.92950929955137e-05 9.99079433077787e-06 -9.95770117148185e-06 -5.12861891545553e-06 6.08484427584749e-06 1.11963639306477e-05 -5.85965548617446e-06 4.31736248383054e-06 -3.55425773460324e-06 -5.90822945042197e-06 1.92950929955137e-05 -5.85965548617446e-06 5.00175857589217e-05 1.12988103126738e-05 6.33330810494442e-06 -4.37515909685203e-06 9.99079433077787e-06 4.31736248383054e-06 1.12988103126738e-05 2.20674889389126e-05 -3.5160158915393e-06 9.71319001803284e-06 -9.95770117148185e-06 -3.55425773460324e-06 6.33330810494442e-06 -3.5160158915393e-06 3.24639151537302e-05 1099 1108 0 16 0 1105 1129 0 38 0 0 0 0 0 0 14 40 0 2931 0 0 0 0 0 2144 +895 899 0.99999181485317 0.000281233367974655 0.00403622775086832 0.00215979138808058 -0.000283853059499085 0.999999749446415 0.000648486351872827 0.000577738191080654 -0.00403604436357616 -0.000649626739512739 0.999991644130587 -0.000875130334455555 3.97480009899771e-05 -3.65403573495631e-05 -3.31020410071343e-06 -5.80285198581465e-06 -9.9791605149912e-06 1.5069986834078e-05 -3.65403573495631e-05 5.54541575647358e-05 5.9126525920293e-06 1.51018700884459e-05 1.2148271258288e-05 -1.06131430743173e-05 -3.31020410071343e-06 5.9126525920293e-06 1.21832131362111e-05 -7.00951764335171e-06 3.7163105371216e-06 -3.8684736189752e-06 -5.80285198581465e-06 1.51018700884459e-05 -7.00951764335171e-06 4.1428695787823e-05 9.86438948384988e-06 7.24172974698803e-06 -9.9791605149912e-06 1.2148271258288e-05 3.7163105371216e-06 9.86438948384988e-06 2.32908782154038e-05 -5.01448995240176e-07 1.5069986834078e-05 -1.06131430743173e-05 -3.8684736189752e-06 7.24172974698803e-06 -5.01448995240176e-07 2.86033119812673e-05 1109 1110 0 18 0 1109 1130 0 43 0 0 0 0 0 0 20 45 0 3050 0 0 0 0 0 1116 +895 897 0.999999789217805 -9.64942041426039e-05 -0.000642069478307215 0.000329589284926804 9.6446074096734e-05 0.999999992537226 -7.49913467272232e-05 -0.00237634935239298 0.000642076709745916 7.49294058399025e-05 0.99999979106152 0.00271869323860445 2.99465018469573e-05 -2.80272323908944e-05 -4.96754100332138e-06 1.15608054735217e-06 1.19719930841054e-06 2.08284853833954e-06 -2.80272323908944e-05 3.61567403225316e-05 5.69457599625897e-06 4.0600719230193e-07 -2.69690163004033e-07 1.24602884042221e-06 -4.96754100332138e-06 5.69457599625897e-06 1.08712532082546e-05 -5.84417360141579e-06 3.51756886625781e-06 -3.15195888731826e-06 1.15608054735217e-06 4.0600719230193e-07 -5.84417360141579e-06 3.27887991158537e-05 1.80171600336292e-06 6.73622411654421e-06 1.19719930841054e-06 -2.69690163004033e-07 3.51756886625781e-06 1.80171600336292e-06 1.85321382623641e-05 -9.08210378344669e-07 2.08284853833954e-06 1.24602884042221e-06 -3.15195888731826e-06 6.73622411654421e-06 -9.08210378344669e-07 2.74391457827416e-05 1105 1103 0 12 0 1106 1125 0 38 0 0 0 0 0 0 21 47 0 2918 0 0 0 0 0 2141 +894 898 0.999999621763626 0.000491030494994802 0.000717886939975218 -0.000342526221012719 -0.000490404311335655 0.999999499406701 -0.00087217541712425 -0.000153315479702974 -0.00071831484533262 0.000871823032385367 0.999999361973988 -0.000319934706056513 2.00948569603147e-05 -1.71645796466676e-05 -4.25038652864596e-06 1.72543092898142e-07 -1.33010242896478e-06 9.23697564501655e-06 -1.71645796466676e-05 2.05147140033548e-05 5.89123138666168e-06 -1.65861427946171e-06 2.39259905241435e-07 -8.99565628104603e-06 -4.25038652864596e-06 5.89123138666168e-06 1.25967760341589e-05 -3.94188527821873e-06 3.5151878350403e-06 -4.83459862234293e-06 1.72543092898142e-07 -1.65861427946171e-06 -3.94188527821873e-06 2.9484889952465e-05 -2.56632070942323e-06 4.53748474687906e-06 -1.33010242896478e-06 2.39259905241435e-07 3.5151878350403e-06 -2.56632070942323e-06 1.93969565162015e-05 5.02478931985414e-07 9.23697564501655e-06 -8.99565628104603e-06 -4.83459862234293e-06 4.53748474687906e-06 5.02478931985414e-07 2.04541714708679e-05 1101 1111 0 23 0 1103 1126 0 37 0 0 0 0 0 0 11 33 0 3016 0 0 0 0 0 1270 +894 927 0.999999505848601 0.000170315885905724 -0.000979436088778545 0.00143861887649703 -0.00017007084523029 0.99999995422209 0.000250263312004466 0.00103442607539409 0.000979478667759702 -0.000250096614813033 0.999999489036481 0.00437545833548419 2.41029647632337e-05 -2.18829790928027e-05 -5.60634034454574e-06 1.22970097868595e-06 1.80958227442863e-06 1.03296324611148e-05 -2.18829790928027e-05 4.30706997094567e-05 6.45952022937595e-06 9.84973534405258e-06 7.21452428635127e-07 -3.72783308663773e-06 -5.60634034454574e-06 6.45952022937595e-06 1.07894469192018e-05 -4.03931101100107e-06 2.79074970237049e-06 -1.7678151876934e-06 1.22970097868595e-06 9.84973534405258e-06 -4.03931101100107e-06 3.93155290201486e-05 5.00098658102866e-06 8.46260648763939e-06 1.80958227442863e-06 7.21452428635127e-07 2.79074970237049e-06 5.00098658102866e-06 2.12833082301215e-05 6.00080630201785e-07 1.03296324611148e-05 -3.72783308663773e-06 -1.7678151876934e-06 8.46260648763939e-06 6.00080630201785e-07 3.12911536337398e-05 1055 1066 0 17 0 1061 1088 0 41 0 0 0 0 0 0 18 45 0 2979 0 0 0 0 0 2338 +895 898 0.999999064927152 -0.000112119434971251 0.00136292848423571 -0.000119659763824433 0.000111655410376567 0.999999935785252 0.000340532761823612 0.000171770116119863 -0.00136296657705644 -0.000340380265061451 0.999999013231206 0.00157153030136946 3.01479030571362e-05 -3.15146290467055e-05 -4.62853749143306e-06 -4.28055417840153e-07 -5.59770228581217e-06 2.07040678247445e-05 -3.15146290467055e-05 4.56725185872942e-05 5.20233816173527e-06 7.92863158508283e-06 9.10145825899168e-06 -2.02935056029381e-05 -4.62853749143306e-06 5.20233816173527e-06 1.06524514151146e-05 -5.564129563689e-06 4.87024160706309e-06 -4.18141899595804e-06 -4.28055417840153e-07 7.92863158508283e-06 -5.564129563689e-06 5.00438085955546e-05 1.03632361110933e-05 4.95047927958547e-06 -5.59770228581217e-06 9.10145825899168e-06 4.87024160706309e-06 1.03632361110933e-05 1.93400529709936e-05 -3.35918599966589e-06 2.07040678247445e-05 -2.02935056029381e-05 -4.18141899595804e-06 4.95047927958547e-06 -3.35918599966589e-06 2.52083628256231e-05 1085 1085 0 12 0 1087 1109 0 37 0 0 0 0 0 0 14 40 0 3018 0 0 0 0 0 2583 +894 928 0.999997489487033 -0.000818107335503429 -0.00208607766360278 -0.00447786308188932 0.000819738383803397 0.999999358925897 0.00078113812921866 -0.00157665984180426 0.00208543727143885 -0.000782846206093708 0.999997519048525 0.000326515025405973 2.46064087728249e-05 -2.45733532162707e-05 -5.7996713207329e-06 4.43213550251559e-06 -1.23751161796828e-06 2.07192103013018e-05 -2.45733532162707e-05 4.53938833509444e-05 7.7433099527134e-06 4.29407882245051e-06 5.3655219330114e-06 -2.2637762329876e-05 -5.7996713207329e-06 7.7433099527134e-06 1.12021932162403e-05 -4.4963757974395e-06 3.8814135091988e-06 -3.72676131702029e-06 4.43213550251559e-06 4.29407882245051e-06 -4.4963757974395e-06 4.19431491346181e-05 5.56393216010112e-06 6.4555545947912e-06 -1.23751161796828e-06 5.3655219330114e-06 3.8814135091988e-06 5.56393216010112e-06 1.92592568274966e-05 -5.48576525823261e-06 2.07192103013018e-05 -2.2637762329876e-05 -3.72676131702029e-06 6.4555545947912e-06 -5.48576525823261e-06 3.29797026651447e-05 1080 1080 0 22 0 1074 1093 0 37 0 0 0 0 0 0 17 43 0 2898 0 0 0 0 0 2389 +895 924 0.999999857456283 -0.000456491618874491 0.000276952730554444 0.00242297872143493 0.000457011452205606 0.999998128699174 -0.00187982410971534 -0.00277315500939501 -0.000276094088341527 0.0018799504123278 0.999998194777621 -0.000855495304980094 2.70614882156005e-05 -2.51530550039858e-05 -7.55244485350675e-06 -2.28335611782762e-06 -1.15755859859097e-06 1.08891448876842e-05 -2.51530550039858e-05 4.01764506077113e-05 9.86955992156334e-06 1.77889435859273e-06 -1.03160569953391e-06 -6.76750380850554e-06 -7.55244485350675e-06 9.86955992156334e-06 1.28796390464802e-05 -4.05824955697741e-06 9.46951975626999e-07 -1.09664605284539e-06 -2.28335611782762e-06 1.77889435859273e-06 -4.05824955697741e-06 3.81265690649976e-05 5.61741090423513e-06 1.09950709185528e-06 -1.15755859859097e-06 -1.03160569953391e-06 9.46951975626999e-07 5.61741090423513e-06 2.25247606993794e-05 -5.46865836527865e-06 1.08891448876842e-05 -6.76750380850554e-06 -1.09664605284539e-06 1.09950709185528e-06 -5.46865836527865e-06 2.80617820988413e-05 1101 1097 0 20 0 1099 1112 0 36 0 0 0 0 0 0 16 40 0 2927 0 0 0 0 0 2188 +894 920 0.999978269077058 -0.000999429557191596 0.00651632674224 0.00388168870646126 0.00100424219844113 0.999999225399972 -0.000735321061604467 -0.00254557931330428 -0.00651558679309013 0.000741849052692527 0.999978498163198 -0.00422099618461797 3.72975320561326e-05 -4.00476879275006e-05 -5.38716452593105e-06 -2.14515946064079e-06 -1.39402441962166e-06 5.3207723531408e-06 -4.00476879275006e-05 6.72423638775577e-05 8.68447057339872e-06 1.21879647072268e-05 2.76962187914178e-06 3.05596187771658e-06 -5.38716452593105e-06 8.68447057339872e-06 1.20115283568272e-05 -4.15088238887857e-06 2.81068232543285e-06 -3.05528902758206e-06 -2.14515946064079e-06 1.21879647072268e-05 -4.15088238887857e-06 4.67858412839923e-05 9.95081802846939e-06 1.09659922433019e-05 -1.39402441962166e-06 2.76962187914178e-06 2.81068232543285e-06 9.95081802846939e-06 2.39206295236044e-05 1.02768955633526e-06 5.3207723531408e-06 3.05596187771658e-06 -3.05528902758206e-06 1.09659922433019e-05 1.02768955633526e-06 3.08677469082812e-05 1070 1080 0 20 0 1076 1093 0 37 0 0 0 0 0 0 18 38 0 2757 0 0 0 0 0 2106 +895 923 0.999999921857263 6.96485355621548e-05 -0.000389145922912655 0.00148928774194554 -6.99391017261026e-05 0.999999718764133 -0.000746712914801711 -0.001973439034372 0.000389093806009863 0.000746740072967809 0.999999645492574 0.000576505454369881 3.82636839513402e-05 -3.17492333185767e-05 -5.07888172281329e-06 -5.38419218927665e-06 -3.99345536444175e-07 5.64663900021639e-06 -3.17492333185767e-05 3.52812142144607e-05 5.05947369064437e-06 7.16446156798808e-06 3.62152464227554e-06 -6.74841642535951e-06 -5.07888172281329e-06 5.05947369064437e-06 1.47304223311041e-05 -3.90703349215052e-06 -3.17950592414417e-08 7.10460548168551e-07 -5.38419218927665e-06 7.16446156798808e-06 -3.90703349215052e-06 4.22748883365057e-05 5.77300223916612e-06 7.5207498770664e-06 -3.99345536444175e-07 3.62152464227554e-06 -3.17950592414417e-08 5.77300223916612e-06 2.6326856533981e-05 -1.98802934567505e-06 5.64663900021639e-06 -6.74841642535951e-06 7.10460548168551e-07 7.5207498770664e-06 -1.98802934567505e-06 2.41741609205531e-05 1111 1110 0 15 0 1110 1134 0 40 0 0 0 0 0 0 15 40 0 2876 0 0 0 0 0 1107 +895 928 0.99999494267551 -0.000443413615111114 -0.00314928686694057 -0.00612351265003849 0.000442811824612962 0.999999883568561 -0.000191782565218976 -0.00506193812516763 0.00314937153926513 0.000190387053848532 0.999995022593451 -0.00135197908878804 4.17897314441696e-05 -4.10116112872126e-05 -6.42242425753089e-06 -2.56857254093882e-06 -2.86619110787379e-06 2.04604157920884e-05 -4.10116112872126e-05 5.66259081426816e-05 6.46039230803056e-06 1.10373221413315e-05 8.07259799884931e-06 -2.57124141450601e-05 -6.42242425753089e-06 6.46039230803056e-06 1.37845667938224e-05 -4.44960065736638e-06 8.71393351092438e-07 -2.95304553233881e-06 -2.56857254093882e-06 1.10373221413315e-05 -4.44960065736638e-06 5.32036384086694e-05 1.27902761238349e-05 6.24429489814954e-06 -2.86619110787379e-06 8.07259799884931e-06 8.71393351092438e-07 1.27902761238349e-05 2.9699877347571e-05 -2.6103608528011e-06 2.04604157920884e-05 -2.57124141450601e-05 -2.95304553233881e-06 6.24429489814954e-06 -2.6103608528011e-06 3.80110994248653e-05 1082 1087 0 22 0 1083 1106 0 45 0 0 0 0 0 0 14 39 0 2889 0 0 0 0 0 1121 +895 922 0.99999657019645 -0.000308100569670505 -0.00260089780174172 -0.000469026926754333 0.000308171113103169 0.999999952158249 2.67220058822393e-05 -0.0012075305753733 0.00260088944424498 -2.7523435801639e-05 0.999996617302558 0.00029702885012069 3.68872522514014e-05 -3.4949009847773e-05 -7.75586099689768e-06 -4.08415783292059e-07 1.22339541909785e-06 6.97270404928748e-06 -3.4949009847773e-05 4.4985270210691e-05 8.62479630243985e-06 1.39283828093172e-06 -1.59333983162729e-06 -5.34836717598157e-06 -7.75586099689768e-06 8.62479630243985e-06 1.23472576997029e-05 -4.64891374499838e-06 1.49792971508123e-06 7.04338905618011e-07 -4.08415783292059e-07 1.39283828093172e-06 -4.64891374499838e-06 2.79722070679416e-05 1.99194529832456e-06 5.15334666962378e-06 1.22339541909785e-06 -1.59333983162729e-06 1.49792971508123e-06 1.99194529832456e-06 2.00612678298839e-05 -2.91689281241588e-06 6.97270404928748e-06 -5.34836717598157e-06 7.04338905618011e-07 5.15334666962378e-06 -2.91689281241588e-06 3.55171730342514e-05 1088 1091 0 22 0 1088 1105 0 42 0 0 0 0 0 0 20 46 0 2988 0 0 0 0 0 1058 +895 927 0.999999376439892 -0.000106727632158028 0.0011116335008018 0.00172362748360032 0.000107022279584161 0.999999959160097 -0.00026500195419003 0.00108414521193911 -0.00111160517237171 0.0002651207584967 0.999999347022249 -0.00242383543710429 4.05005673943558e-05 -4.3207398775109e-05 -5.33862145292786e-06 1.43807405157594e-07 -3.4731324682321e-06 2.16757598644117e-05 -4.3207398775109e-05 6.60694627731626e-05 7.79016246282361e-06 8.26740371741599e-06 6.58928677471485e-06 -2.17887114971174e-05 -5.33862145292786e-06 7.79016246282361e-06 1.25353767937421e-05 -8.06019938898872e-06 3.41127858413788e-06 -2.90408896906447e-06 1.43807405157594e-07 8.26740371741599e-06 -8.06019938898872e-06 5.38568815820346e-05 1.47436008164418e-05 5.11290839464079e-06 -3.4731324682321e-06 6.58928677471485e-06 3.41127858413788e-06 1.47436008164418e-05 2.55179361643845e-05 -3.58331272753033e-06 2.16757598644117e-05 -2.17887114971174e-05 -2.90408896906447e-06 5.11290839464079e-06 -3.58331272753033e-06 3.36100380927867e-05 1052 1052 0 12 0 1054 1077 0 41 0 0 0 0 0 0 16 43 0 2980 0 0 0 0 0 2194 +895 926 0.999999670579605 -0.00036230633273023 0.000726343446176971 -0.000167742667833426 0.000363750135253928 0.999997956530727 -0.0019886226914358 -0.00256508757956206 -0.000725621471321939 0.00198888624386971 0.999997758899983 -0.00199594281212841 3.42455636909423e-05 -3.32870459719442e-05 -4.73392631671149e-06 1.55795267574287e-07 -6.48519850096548e-06 2.14335162712663e-05 -3.32870459719442e-05 5.18071889522186e-05 6.49348061739893e-06 5.094335151769e-06 8.07379957347771e-06 -2.0627510417993e-05 -4.73392631671149e-06 6.49348061739893e-06 1.33164381269135e-05 -7.22602905824658e-06 2.54696292514478e-06 -4.17516626619007e-06 1.55795267574287e-07 5.094335151769e-06 -7.22602905824658e-06 5.30511140935876e-05 1.31873798932905e-05 6.6583526485817e-06 -6.48519850096548e-06 8.07379957347771e-06 2.54696292514478e-06 1.31873798932905e-05 2.7328614991443e-05 -3.79397699027139e-06 2.14335162712663e-05 -2.0627510417993e-05 -4.17516626619007e-06 6.6583526485817e-06 -3.79397699027139e-06 3.33012890066201e-05 1074 1073 0 12 0 1075 1097 0 36 0 0 0 0 0 0 16 44 0 2931 0 0 0 0 0 2196 +895 921 0.999991378658383 1.70492979363744e-05 -0.00415238705176816 -0.00117345997123934 -2.31753020658891e-05 0.999998911544645 -0.00147525334424441 -0.00149296197257387 0.00415235738004644 0.00147533685840557 0.999990290607535 0.00156618566695649 4.12012657856688e-05 -4.11185634845916e-05 -1.29059214048098e-06 -1.00641128041815e-05 -6.20730348064718e-06 1.29521007353637e-05 -4.11185634845916e-05 5.3995903592891e-05 1.73468836414968e-06 2.00954679477644e-05 1.0592006087645e-05 -9.11287933036768e-06 -1.29059214048098e-06 1.73468836414968e-06 1.01128271320216e-05 -4.99950885865433e-06 2.62999086858153e-06 1.08673408327789e-06 -1.00641128041815e-05 2.00954679477644e-05 -4.99950885865433e-06 5.38573923684031e-05 1.71818030890944e-05 2.43502483124947e-06 -6.20730348064718e-06 1.0592006087645e-05 2.62999086858153e-06 1.71818030890944e-05 2.3146810811629e-05 -3.61567334332073e-07 1.29521007353637e-05 -9.11287933036768e-06 1.08673408327789e-06 2.43502483124947e-06 -3.61567334332073e-07 3.25749252075413e-05 1108 1107 0 24 0 1106 1120 0 42 0 0 0 0 0 0 20 47 0 2878 0 0 0 0 0 2486 +896 924 0.999998992080056 -0.00056245295329711 0.00130364318247629 0.00107701837805875 0.000562997505809419 0.99999975441109 -0.000417386594289662 -0.00109632690040346 -0.00130340810199336 0.000418120121457589 0.999999063151003 -0.00487986094870304 2.25016922142255e-05 -2.09898310916313e-05 -2.38343622319878e-06 -3.63340190777794e-06 -1.25150331327956e-06 9.05185693312313e-06 -2.09898310916313e-05 2.53000495249444e-05 3.9185112537449e-06 3.37320086379923e-06 1.90641651428767e-07 -8.45452364035538e-06 -2.38343622319878e-06 3.9185112537449e-06 1.20765338526741e-05 -4.27365842752797e-06 5.66332198739324e-08 -8.89122319139352e-07 -3.63340190777794e-06 3.37320086379923e-06 -4.27365842752797e-06 4.15826104608612e-05 1.39944872171048e-05 5.59138441748055e-06 -1.25150331327956e-06 1.90641651428767e-07 5.66332198739324e-08 1.39944872171048e-05 2.60638045133342e-05 -1.03933539540944e-06 9.05185693312313e-06 -8.45452364035538e-06 -8.89122319139352e-07 5.59138441748055e-06 -1.03933539540944e-06 2.44321392498188e-05 1126 1130 0 25 0 1126 1143 0 41 0 0 0 0 0 0 17 34 0 2918 0 0 0 0 0 2159 +896 928 0.999990555599859 0.000148383030256388 -0.00434358073040953 -0.00572493142245791 -0.000141955208516287 0.999998894553746 0.00148011486178165 -0.00200023710024946 0.0043437955527428 -0.00147948428907635 0.99998947122779 -0.00261530394357589 2.82402712869911e-05 -2.67617771588728e-05 -8.10688784585282e-06 1.57468841815664e-06 3.18843488788209e-06 7.78428486643124e-06 -2.67617771588728e-05 3.85868666472568e-05 9.61801570300317e-06 4.71700133210789e-06 1.31826128169453e-06 -3.46389016320287e-06 -8.10688784585282e-06 9.61801570300317e-06 1.50426196636488e-05 -8.16396487275128e-06 -1.99020968052347e-06 -1.55938449383938e-06 1.57468841815664e-06 4.71700133210789e-06 -8.16396487275128e-06 5.15888772222807e-05 1.63586296102654e-05 7.0052931607646e-06 3.18843488788209e-06 1.31826128169453e-06 -1.99020968052347e-06 1.63586296102654e-05 3.0889880047829e-05 -3.68025644160128e-06 7.78428486643124e-06 -3.46389016320287e-06 -1.55938449383938e-06 7.0052931607646e-06 -3.68025644160128e-06 2.6297693620177e-05 1078 1074 0 19 0 1074 1097 0 44 0 0 0 0 0 0 17 41 0 2885 0 0 0 0 0 1093 +896 900 0.999993026891013 1.12537174255117e-05 0.00373444007901311 0.00193172411010723 -1.90887439613977e-05 0.999997798978044 0.00209801684640862 0.000737368094184008 -0.00373440824893976 -0.002098073502479 0.999990826099224 0.000254144915918776 3.62452516596038e-05 -3.35935158321189e-05 -1.71035265081059e-06 -4.25190055521636e-06 -6.72990784494012e-06 1.10681931046435e-05 -3.35935158321189e-05 6.04719949719645e-05 4.64071942468834e-06 1.62947290125325e-05 1.04319259420126e-05 -2.11881740175705e-06 -1.71035265081059e-06 4.64071942468834e-06 1.12311765065611e-05 -6.20067637485025e-06 4.45419909580591e-06 -2.86447127136677e-06 -4.25190055521636e-06 1.62947290125325e-05 -6.20067637485025e-06 4.62762397595998e-05 1.17392702616935e-05 1.4312151113811e-05 -6.72990784494012e-06 1.04319259420126e-05 4.45419909580591e-06 1.17392702616935e-05 2.03443889036834e-05 2.22574735594674e-06 1.10681931046435e-05 -2.11881740175705e-06 -2.86447127136677e-06 1.4312151113811e-05 2.22574735594674e-06 3.15517764151846e-05 1098 1100 0 22 0 1094 1117 0 41 0 0 0 0 0 0 15 42 0 2951 0 0 0 0 0 2130 +895 869 0.998731004571655 0.00513204069518978 -0.0501003260028924 0.0173865276342939 -0.0111312251051974 0.992685995719388 -0.120210688918519 0.0205696765607068 0.0491169658565205 0.120615820110425 0.991483407629265 -0.0181358453231938 6.38420858202317e-05 -8.31506179818905e-05 3.80886864857719e-06 -2.20792259465862e-05 -1.47697763941447e-05 1.92843356919891e-05 -8.31506179818905e-05 0.000162990462668536 -1.04210455108418e-05 6.74326193398001e-05 3.61913202025683e-05 -6.04193947480842e-06 3.80886864857719e-06 -1.04210455108418e-05 1.12213263842217e-05 -7.76816884978096e-06 -6.319204201841e-06 -2.83301332718476e-06 -2.20792259465862e-05 6.74326193398001e-05 -7.76816884978096e-06 8.92803882898585e-05 2.95205258914201e-05 1.58705453904329e-05 -1.47697763941447e-05 3.61913202025683e-05 -6.319204201841e-06 2.95205258914201e-05 4.00297469628171e-05 5.89893442974396e-06 1.92843356919891e-05 -6.04193947480842e-06 -2.83301332718476e-06 1.58705453904329e-05 5.89893442974396e-06 4.20421382315356e-05 886 885 0 16 0 886 893 0 29 0 0 0 0 0 0 11 25 0 2294 0 0 0 0 0 2211 +896 899 0.999999841990508 -0.000395612964358449 -0.000399386207073193 -0.000708473338636851 0.000395316571507697 0.999999646634304 -0.000741927270458195 -0.00124029395155252 0.000399679581990613 0.000741769269240556 0.999999645017228 0.00104664947365162 2.59431496437411e-05 -2.31390101273206e-05 -1.67510508585786e-06 -2.43418765938387e-06 -2.88667717224845e-06 1.12785638804765e-05 -2.31390101273206e-05 2.70012381251456e-05 3.43048024631897e-06 3.05201753123151e-06 3.69112860270854e-06 -9.58771230468048e-06 -1.67510508585786e-06 3.43048024631897e-06 1.12584696133298e-05 -6.99423284029759e-06 4.84601697783975e-06 -4.057278124675e-06 -2.43418765938387e-06 3.05201753123151e-06 -6.99423284029759e-06 2.82448504685219e-05 2.65442874069553e-06 7.21149502945908e-06 -2.88667717224845e-06 3.69112860270854e-06 4.84601697783975e-06 2.65442874069553e-06 1.88811118246302e-05 2.63409764230855e-06 1.12785638804765e-05 -9.58771230468048e-06 -4.057278124675e-06 7.21149502945908e-06 2.63409764230855e-06 2.52392917240546e-05 1139 1155 0 29 0 1142 1166 0 41 0 0 0 0 0 0 15 32 0 3039 0 0 0 0 0 1082 +895 925 0.999999585413718 0.000131143322630397 -0.000901095900062484 0.000392525971845694 -0.000131463542366298 0.9999999282336 -0.000355316947487502 -0.00147341630529758 0.000901049237948994 0.000355435261437004 0.999999530887913 0.000891190683311715 2.50876652461649e-05 -2.57857169996642e-05 -3.57620499605095e-06 -7.84390332911787e-06 -5.93913899492547e-06 1.00798050292979e-05 -2.57857169996642e-05 4.10512416382837e-05 4.89334914794814e-06 1.40181953007176e-05 8.27835073348558e-06 -7.9318075260859e-06 -3.57620499605095e-06 4.89334914794814e-06 1.13708242893097e-05 -4.68734341306979e-06 -8.1555428134752e-08 -9.51171662471927e-08 -7.84390332911787e-06 1.40181953007176e-05 -4.68734341306979e-06 5.07735527526707e-05 1.77876914911912e-05 8.41112764473871e-07 -5.93913899492547e-06 8.27835073348558e-06 -8.1555428134752e-08 1.77876914911912e-05 2.88512901471129e-05 -3.53926875854854e-06 1.00798050292979e-05 -7.9318075260859e-06 -9.51171662471927e-08 8.41112764473871e-07 -3.53926875854854e-06 2.22552992429412e-05 1074 1074 0 16 0 1074 1100 0 45 0 0 0 0 0 0 19 46 0 2896 0 0 0 0 0 2574 +895 929 0.999775849165059 -0.021034012245319 0.00241283135532289 -0.0027642408844889 0.0209821851610797 0.999583759245004 0.0198004080637866 8.86613622634845e-05 -0.00282830906225387 -0.0197453433115271 0.999801041250387 -0.00893264693455633 3.3324555546109e-05 -2.75813647927197e-05 -5.65972714808153e-06 5.70358106902811e-06 1.34331978931719e-07 1.05964770755953e-05 -2.75813647927197e-05 4.70394883819782e-05 5.53728406718688e-06 8.2549065657369e-06 2.92556582691618e-06 -9.35778933672298e-06 -5.65972714808153e-06 5.53728406718688e-06 9.60860848250961e-06 -5.87927900926142e-07 -7.55954281235344e-07 -9.87855651121334e-07 5.70358106902811e-06 8.2549065657369e-06 -5.87927900926142e-07 4.79046454268983e-05 4.64312447155874e-06 3.96993096266674e-06 1.34331978931719e-07 2.92556582691618e-06 -7.55954281235344e-07 4.64312447155874e-06 2.29099852262726e-05 -5.76980108063319e-06 1.05964770755953e-05 -9.35778933672298e-06 -9.87855651121334e-07 3.96993096266674e-06 -5.76980108063319e-06 2.62503506772378e-05 1016 1013 0 0 0 1034 1031 0 13 0 0 0 0 0 0 41 67 0 3038 0 0 0 0 0 1757 +896 923 0.999997633522616 -0.000489359876852914 0.00211978208275445 0.00121655323651993 0.000488331774404725 0.999999762913668 0.000485494269492991 8.69599810607105e-05 -0.00212001916159903 -0.000484457963635959 0.999997635406822 -0.00219280750867938 4.0374710425836e-05 -4.36174818528505e-05 -5.04892293813075e-06 -9.28714156774424e-06 -6.82155033426243e-06 1.64181078018872e-05 -4.36174818528505e-05 6.56356034830567e-05 7.36423349627943e-06 1.83267318932172e-05 1.08343380030781e-05 -1.71280095909176e-05 -5.04892293813075e-06 7.36423349627943e-06 1.38419137500793e-05 -5.11588408345922e-06 1.59802028933331e-06 -4.18073864752287e-06 -9.28714156774424e-06 1.83267318932172e-05 -5.11588408345922e-06 4.75003405816296e-05 1.5436958032656e-05 7.22676868400949e-06 -6.82155033426243e-06 1.08343380030781e-05 1.59802028933331e-06 1.5436958032656e-05 2.82530439455862e-05 -1.98485576935994e-06 1.64181078018872e-05 -1.71280095909176e-05 -4.18073864752287e-06 7.22676868400949e-06 -1.98485576935994e-06 2.76122290091122e-05 1100 1112 0 26 0 1102 1123 0 39 0 0 0 0 0 0 17 38 0 2875 0 0 0 0 0 1088 +896 898 0.999999741863355 0.000294220392595459 -0.00065552084959101 -0.000233119523365281 -0.000293948357601865 0.999999870664624 0.000415048307771611 0.000705952640209826 0.000655642880485033 -0.000414855511355322 0.999999699013614 -0.00142605056496245 2.17124177103464e-05 -1.97338882012562e-05 -5.57285035630372e-06 1.67651501559109e-06 -4.6914294509664e-06 1.45616731829947e-05 -1.97338882012562e-05 2.58457814697871e-05 6.62578730982439e-06 -7.61677176050394e-07 5.81314295825825e-06 -1.23704731883631e-05 -5.57285035630372e-06 6.62578730982439e-06 9.96865400925117e-06 -5.62781295578233e-06 5.23357464718754e-06 -4.95196113751706e-06 1.67651501559109e-06 -7.61677176050394e-07 -5.62781295578233e-06 3.7665978939115e-05 6.14835664902208e-06 4.3435289930021e-06 -4.6914294509664e-06 5.81314295825825e-06 5.23357464718754e-06 6.14835664902208e-06 1.70183035480976e-05 -3.60179595944607e-06 1.45616731829947e-05 -1.23704731883631e-05 -4.95196113751706e-06 4.3435289930021e-06 -3.60179595944607e-06 1.92518534363314e-05 1108 1116 0 23 0 1109 1132 0 40 0 0 0 0 0 0 15 38 0 3012 0 0 0 0 0 2564 +896 927 0.999999455860724 0.00018901189030989 -0.00102593994088479 0.00079756174110807 -0.000190148506906468 0.999999368207187 -0.00110789384481994 0.000870942284120453 0.00102572988759344 0.00110808832291932 0.999998860008583 -0.00176048901116291 2.26511495431878e-05 -2.04083514755292e-05 -5.60241328883823e-06 -1.84109861542424e-06 -2.27659884459199e-06 6.1908082487994e-06 -2.04083514755292e-05 2.42180716645839e-05 6.96810949643418e-06 1.99112733206441e-06 1.82836686592926e-06 -3.88684997651703e-06 -5.60241328883823e-06 6.96810949643418e-06 1.08246860226832e-05 -4.83178616213625e-06 1.76076234269472e-06 -2.69628304211144e-06 -1.84109861542424e-06 1.99112733206441e-06 -4.83178616213625e-06 3.60942513861624e-05 9.14775615428871e-06 5.02412209062106e-06 -2.27659884459199e-06 1.82836686592926e-06 1.76076234269472e-06 9.14775615428871e-06 2.07583090289735e-05 -3.62907265576828e-07 6.1908082487994e-06 -3.88684997651703e-06 -2.69628304211144e-06 5.02412209062106e-06 -3.62907265576828e-07 2.83863584851671e-05 1122 1132 0 26 0 1119 1140 0 36 0 0 0 0 0 0 14 36 0 2978 0 0 0 0 0 2156 +896 869 0.998529056590528 0.00527199941792466 -0.053962293933526 0.0164976789125209 -0.0117459427775022 0.992659782456755 -0.120368555367156 0.0217445887007354 0.0529316160030893 0.120825338050617 0.991261560695388 -0.0191163377844959 4.71500622146795e-05 -4.42216950060055e-05 1.96268109536087e-06 -1.5295910668829e-05 -1.26234050740559e-05 1.89412488796386e-05 -4.42216950060055e-05 5.55714431306075e-05 -1.2370459802979e-06 1.85548483306202e-05 1.53105959978465e-05 -1.45365498316981e-05 1.96268109536087e-06 -1.2370459802979e-06 1.14273816573314e-05 -4.36500701401309e-06 -3.95070821203812e-06 -5.22777851290631e-07 -1.5295910668829e-05 1.85548483306202e-05 -4.36500701401309e-06 6.66787088046427e-05 2.34609529185952e-05 3.64038042282346e-06 -1.26234050740559e-05 1.53105959978465e-05 -3.95070821203812e-06 2.34609529185952e-05 4.10049153557861e-05 2.07216228326026e-08 1.89412488796386e-05 -1.45365498316981e-05 -5.22777851290631e-07 3.64038042282346e-06 2.07216228326026e-08 3.76571458747045e-05 895 890 0 13 0 895 902 0 27 0 0 0 0 0 0 8 22 0 2299 0 0 0 0 0 2186 +896 870 0.997280452385142 0.00298871873922547 -0.0736394381482085 0.00951767873633029 -0.0123435890131519 0.991837227772155 -0.126911581092987 0.0134714878067882 0.0726590331669809 0.127475413964988 0.989176770720832 -0.0160675810115381 5.40065399426217e-05 -7.86205905455087e-05 9.99127477838759e-06 -2.87129165709222e-05 -1.4841848784221e-05 1.99958248396741e-05 -7.86205905455087e-05 0.000185728997056643 -2.06815601452144e-05 9.92548911838888e-05 4.15415754485629e-05 -1.58044223454383e-05 9.99127477838759e-06 -2.06815601452144e-05 1.11677904485321e-05 -1.12950602098278e-05 -2.24341849080413e-06 1.2277884181711e-06 -2.87129165709222e-05 9.92548911838888e-05 -1.12950602098278e-05 0.000109122516006516 3.52898593422632e-05 7.28869862590008e-06 -1.4841848784221e-05 4.15415754485629e-05 -2.24341849080413e-06 3.52898593422632e-05 3.63660913637125e-05 -2.47951381440751e-06 1.99958248396741e-05 -1.58044223454383e-05 1.2277884181711e-06 7.28869862590008e-06 -2.47951381440751e-06 3.54735394469119e-05 870 871 0 14 0 870 882 0 26 0 0 0 0 0 0 5 20 0 2275 0 0 0 0 0 2123 +896 925 0.999998656804001 -0.000833480242466047 0.0014112763300395 -0.00188040099933792 0.000832276403437601 0.999999289523118 0.000853386926927613 -0.000336306188993495 -0.00141198660850307 -0.000852211208673485 0.999998640014012 -0.000466011808515125 3.62623584677122e-05 -3.94278801090432e-05 -2.75862188287457e-06 -6.02920268299984e-06 -7.18912695754137e-06 1.90855665424002e-05 -3.94278801090432e-05 6.31823193644689e-05 4.53970013202743e-06 1.63237346197641e-05 1.06029161129536e-05 -2.00658057209169e-05 -2.75862188287457e-06 4.53970013202743e-06 1.10046078902965e-05 -2.54632288091415e-06 3.78777505600817e-06 -2.64395610343047e-06 -6.02920268299984e-06 1.63237346197641e-05 -2.54632288091415e-06 4.30964902501658e-05 1.17551886523989e-05 3.90755665623886e-06 -7.18912695754137e-06 1.06029161129536e-05 3.78777505600817e-06 1.17551886523989e-05 2.48898250283734e-05 -3.41032837909341e-06 1.90855665424002e-05 -2.00658057209169e-05 -2.64395610343047e-06 3.90755665623886e-06 -3.41032837909341e-06 2.78165998292524e-05 1082 1092 0 23 0 1085 1106 0 37 0 0 0 0 0 0 14 37 0 2903 0 0 0 0 0 2557 +897 900 0.999999438229321 -0.00058134365624369 -0.000886329845858597 -0.00103415269310506 0.000580432268058162 0.999999302969085 -0.00102818273029452 -0.00158868670373325 0.00088692695556701 0.00102766769824893 0.999999078629414 0.00115415577849851 2.92367888072965e-05 -2.65248497551832e-05 1.1172463049175e-06 -6.57063272359089e-06 -7.39776562607328e-06 1.6277847129867e-05 -2.65248497551832e-05 3.68932670693849e-05 1.22840437010169e-06 8.68491032879059e-06 8.66083594067635e-06 -1.37807221529437e-05 1.1172463049175e-06 1.22840437010169e-06 1.12205252341831e-05 -6.5335297857284e-06 4.83590128216108e-06 -1.53461168032589e-06 -6.57063272359089e-06 8.68491032879059e-06 -6.5335297857284e-06 4.01471939695344e-05 8.47629946778457e-06 2.38328303571645e-06 -7.39776562607328e-06 8.66083594067635e-06 4.83590128216108e-06 8.47629946778457e-06 2.18632875613301e-05 -9.97740199767059e-07 1.6277847129867e-05 -1.37807221529437e-05 -1.53461168032589e-06 2.38328303571645e-06 -9.97740199767059e-07 2.13071619231071e-05 1124 1122 0 6 0 1131 1151 0 36 0 0 0 0 0 0 18 41 0 2942 0 0 0 0 0 2328 +896 922 0.999990522047923 -0.000764093601691127 0.00428625422605516 0.00240328565076794 0.000763401949141641 0.999999695324346 0.000162999019425893 -0.000310132715312125 -0.00428637746664568 -0.000159725339698311 0.999990800685701 -0.00194569037562735 4.39972297099867e-05 -4.50174270858172e-05 -4.59824016564067e-06 -8.83801751357305e-06 -6.45291023366704e-06 9.74061008773565e-06 -4.50174270858172e-05 5.9316276770781e-05 4.9954514995159e-06 2.08360847949254e-05 1.34714486213393e-05 -4.85717944545987e-06 -4.59824016564067e-06 4.9954514995159e-06 1.27764563907159e-05 -8.00195355859981e-06 9.56502043188186e-07 -3.58987841393209e-06 -8.83801751357305e-06 2.08360847949254e-05 -8.00195355859981e-06 5.30964728157947e-05 1.74039939471189e-05 9.26465745518504e-06 -6.45291023366704e-06 1.34714486213393e-05 9.56502043188186e-07 1.74039939471189e-05 2.94187184248939e-05 -3.23867673011441e-07 9.74061008773565e-06 -4.85717944545987e-06 -3.58987841393209e-06 9.26465745518504e-06 -3.23867673011441e-07 3.1790333796228e-05 1083 1078 0 15 0 1084 1104 0 41 0 0 0 0 0 0 14 37 0 2980 0 0 0 0 0 1040 +896 929 0.999764703318511 -0.0212697481178011 0.0042586163779456 -0.00295371722137763 0.0211742748368638 0.999548191551862 0.0213322021960966 0.00270785751513888 -0.00471042286659764 -0.0212370096860996 0.999763372671759 -0.0125179223955206 4.14509403072818e-05 -4.46338732410215e-05 -6.21419986783915e-06 -6.34771802393383e-06 -7.38777251443e-06 1.66755389754822e-05 -4.46338732410215e-05 8.17324716668184e-05 8.16618230574579e-06 3.27208182882315e-05 1.50019251202979e-05 -1.76375857025077e-05 -6.21419986783915e-06 8.16618230574579e-06 1.03214491892062e-05 7.65553610546721e-07 1.91954028510752e-06 -3.28405557517955e-06 -6.34771802393383e-06 3.27208182882315e-05 7.65553610546721e-07 6.36548762620691e-05 6.88480300738449e-06 3.52012914379897e-06 -7.38777251443e-06 1.50019251202979e-05 1.91954028510752e-06 6.88480300738449e-06 2.49153076864474e-05 -8.85630944123532e-06 1.66755389754822e-05 -1.76375857025077e-05 -3.28405557517955e-06 3.52012914379897e-06 -8.85630944123532e-06 2.90012528801808e-05 999 998 0 0 0 1018 1020 0 13 0 0 0 0 0 0 49 73 0 3035 0 0 0 0 0 1768 +897 924 0.999996599255428 -0.000667662409345383 -0.00252105225756742 -0.00144507852917961 0.000659709666760646 0.999994808368707 -0.00315404800034572 -0.00551822267820661 0.00252314500848073 0.00315237411168937 0.999991848105136 -0.00269104607339014 3.73266749458129e-05 -3.78817172845996e-05 -3.58648463968687e-06 -8.2748046042769e-06 -4.29336376688045e-06 1.23146804040372e-05 -3.78817172845996e-05 5.47128867934226e-05 6.74338871987172e-06 1.55385050426632e-05 4.21759104205567e-06 -8.07518447208165e-06 -3.58648463968687e-06 6.74338871987172e-06 1.36583357388938e-05 -6.69629584041587e-06 2.23454265610083e-06 -1.69273738285341e-06 -8.2748046042769e-06 1.55385050426632e-05 -6.69629584041587e-06 4.36171344635702e-05 6.55317394563174e-06 5.64092035509341e-06 -4.29336376688045e-06 4.21759104205567e-06 2.23454265610083e-06 6.55317394563174e-06 2.52808446657949e-05 -1.70598153997856e-06 1.23146804040372e-05 -8.07518447208165e-06 -1.69273738285341e-06 5.64092035509341e-06 -1.70598153997856e-06 3.11712844996167e-05 1028 1032 0 17 0 1034 1054 0 40 0 0 0 0 0 0 12 35 0 2909 0 0 0 0 0 1226 +896 926 0.999999826728087 0.000239521314845278 -0.000537748394340408 0.000917598013296967 -0.000239890569854494 0.999999735441408 -0.000686709275613132 -0.000135919078514703 0.000537583770565838 0.000686838157394459 0.999999619628445 -0.00256568900664177 1.99678241934846e-05 -1.73367094351045e-05 -3.02252177300769e-06 -5.3091889609752e-06 -4.02942582227003e-06 7.88944343902128e-06 -1.73367094351045e-05 2.04137431578886e-05 3.98201687740873e-06 3.28616304894556e-06 3.58677976899316e-06 -7.45979553513691e-06 -3.02252177300769e-06 3.98201687740873e-06 1.21107425556306e-05 -7.61463282502153e-06 -4.24381629145299e-07 -3.98417620753314e-06 -5.3091889609752e-06 3.28616304894556e-06 -7.61463282502153e-06 4.41908344241525e-05 1.44863003920884e-05 3.82379855958343e-06 -4.02942582227003e-06 3.58677976899316e-06 -4.24381629145299e-07 1.44863003920884e-05 2.65475527615728e-05 -2.06987258668781e-06 7.88944343902128e-06 -7.45979553513691e-06 -3.98417620753314e-06 3.82379855958343e-06 -2.06987258668781e-06 2.17202491016908e-05 1152 1161 0 24 0 1153 1172 0 37 0 0 0 0 0 0 16 38 0 2929 0 0 0 0 0 2167 +897 927 0.999998385621536 0.000275982724258352 -0.00177555283150738 2.1390343094242e-05 -0.000280351278452941 0.999996933389329 -0.00246061274863979 -0.000227901070929156 0.00177486829996841 0.00246110655478583 0.999995396387925 -0.00223195393807955 4.95452027552383e-05 -6.04642673789195e-05 -8.74951747878742e-06 -2.65901921174779e-06 -6.25066074331223e-07 2.3745628991168e-05 -6.04642673789195e-05 0.000108748259455772 1.11550752074372e-05 2.6851344595513e-05 9.94852565174516e-06 -2.96049683316612e-05 -8.74951747878742e-06 1.11550752074372e-05 1.35551296315391e-05 -7.46478867599664e-06 2.24249901644418e-06 -3.29113532790574e-06 -2.65901921174779e-06 2.6851344595513e-05 -7.46478867599664e-06 5.71980174693015e-05 1.35709839818443e-05 -5.82722871071008e-07 -6.25066074331223e-07 9.94852565174516e-06 2.24249901644418e-06 1.35709839818443e-05 2.81514910075247e-05 -4.07170395498826e-06 2.3745628991168e-05 -2.96049683316612e-05 -3.29113532790574e-06 -5.82722871071008e-07 -4.07170395498826e-06 4.09582185998781e-05 1017 1015 0 14 0 1015 1043 0 42 0 0 0 0 0 0 16 44 0 2981 0 0 0 0 0 1255 +897 923 0.999999736739267 -0.000543553650342925 0.000480698268182563 -6.52391984773066e-05 0.000543938741410879 0.99999953099223 -0.000801340105892123 -0.00136368303557003 -0.000480262471391616 0.000801601365341733 0.999999563391509 0.00275007434480839 2.22010657175021e-05 -2.00241705266057e-05 -1.1110767065519e-06 -2.38412146849519e-06 -1.04916484970463e-06 8.27530102812835e-06 -2.00241705266057e-05 2.30421638035254e-05 2.40964092393272e-06 7.4091490566088e-07 -2.0792663223766e-07 -6.64653702045668e-06 -1.1110767065519e-06 2.40964092393272e-06 1.34957691912632e-05 -4.82517956670382e-06 1.27870079757993e-06 -1.43813684848633e-06 -2.38412146849519e-06 7.4091490566088e-07 -4.82517956670382e-06 3.7400973170539e-05 9.32158469832574e-06 6.61731464692553e-06 -1.04916484970463e-06 -2.0792663223766e-07 1.27870079757993e-06 9.32158469832574e-06 2.19821709329034e-05 1.89729474103346e-07 8.27530102812835e-06 -6.64653702045668e-06 -1.43813684848633e-06 6.61731464692553e-06 1.89729474103346e-07 2.21354227385164e-05 1161 1165 0 21 0 1159 1179 0 41 0 0 0 0 0 0 9 32 0 2880 0 0 0 0 0 2159 +897 926 0.999990286012065 0.000192018439293778 -0.00440352250212237 -0.0018085269517526 -0.00020620428396005 0.99999479050416 -0.00322124887809001 -0.0025567937085978 0.00440288102280807 0.00322212561212172 0.999985116161855 -0.0029353577002532 4.2529215576876e-05 -4.91053879380539e-05 -4.55838531647731e-06 -6.05232303114048e-06 -4.18097352738725e-06 2.61303834369601e-05 -4.91053879380539e-05 8.72178868291341e-05 6.43374726488884e-06 2.58393889976213e-05 1.35575556327605e-05 -3.20417147517865e-05 -4.55838531647731e-06 6.43374726488884e-06 1.19348485725805e-05 -6.09767995288873e-06 3.30440812564013e-06 -3.94482202993382e-06 -6.05232303114048e-06 2.58393889976213e-05 -6.09767995288873e-06 4.73618544016673e-05 7.81384257901509e-06 1.31920787587556e-06 -4.18097352738725e-06 1.35575556327605e-05 3.30440812564013e-06 7.81384257901509e-06 2.29151151755978e-05 -1.97755981566134e-06 2.61303834369601e-05 -3.20417147517865e-05 -3.94482202993382e-06 1.31920787587556e-06 -1.97755981566134e-06 3.9699134071859e-05 1034 1031 0 9 0 1036 1065 0 43 0 0 0 0 0 0 15 44 0 2928 0 0 0 0 0 1259 +897 925 0.99999917275665 -2.73822484528306e-05 0.00128597676057839 0.00220408226099571 2.92505717296464e-05 0.999998944188864 -0.00145284739758229 0.000135833561040733 -0.0012859356206014 0.00145288381127942 0.999998117747334 -0.00151522748445086 2.02368986176635e-05 -1.92940775728595e-05 -7.55773909541191e-07 -1.33630039759666e-06 -8.8849238783338e-07 8.25629349022016e-06 -1.92940775728595e-05 2.24465005394469e-05 1.65101480447014e-06 2.44819655863725e-06 2.16929127176216e-06 -7.12822098733011e-06 -7.55773909541191e-07 1.65101480447014e-06 1.17275432636085e-05 -2.85771636268793e-06 2.39678118534475e-06 1.2003596011455e-06 -1.33630039759666e-06 2.44819655863725e-06 -2.85771636268793e-06 3.46515027055407e-05 8.31280696154579e-06 1.44633741389443e-06 -8.8849238783338e-07 2.16929127176216e-06 2.39678118534475e-06 8.31280696154579e-06 2.01261585672779e-05 -2.37953760390652e-06 8.25629349022016e-06 -7.12822098733011e-06 1.2003596011455e-06 1.44633741389443e-06 -2.37953760390652e-06 2.18076115601408e-05 1149 1158 0 28 0 1148 1172 0 42 0 0 0 0 0 0 13 39 0 2912 0 0 0 0 0 2141 +897 901 0.999990379470707 0.000358998597677518 -0.00437173718763836 -0.00106025393273696 -0.000360656049770563 0.999999863390563 -0.000378346493066067 0.000562246322743127 0.00437160076455735 0.000379919546637276 0.999990372337601 0.00265784072441202 4.71728989065739e-05 -5.8104782012089e-05 -2.96603685157703e-06 -1.10945202186786e-05 -6.15319334630447e-06 1.98625945759882e-05 -5.8104782012089e-05 0.000116860101782531 4.94954364281266e-06 4.43319603882683e-05 1.99627443503771e-05 -2.13012846067863e-05 -2.96603685157703e-06 4.94954364281266e-06 1.02597793418218e-05 -4.99267990500812e-06 4.81216304096131e-06 -4.25915868190028e-06 -1.10945202186786e-05 4.43319603882683e-05 -4.99267990500812e-06 6.31106442407412e-05 1.61047912274936e-05 9.39355941571192e-06 -6.15319334630447e-06 1.99627443503771e-05 4.81216304096131e-06 1.61047912274936e-05 2.10121946675949e-05 1.44601429025288e-06 1.98625945759882e-05 -2.13012846067863e-05 -4.25915868190028e-06 9.39355941571192e-06 1.44601429025288e-06 3.59675121189567e-05 1030 1032 0 16 0 1037 1052 0 41 0 0 0 0 0 0 11 34 0 2927 0 0 0 0 0 2171 +897 928 0.999968956812708 6.10300426739956e-05 -0.00787919324799835 -0.0041234922990356 -7.14153163299655e-05 0.99999912916635 -0.00131778844827573 -0.00179281656974889 0.0078791059618465 0.00131831023500035 0.999968090364571 0.00175058663115363 6.60153396080245e-05 -7.3075477243435e-05 -5.75263741562807e-06 -1.14593348288794e-05 -1.16970719372219e-05 3.44989083400472e-05 -7.3075477243435e-05 0.000113412941260105 7.16050294068816e-06 2.7059526664325e-05 1.93345368739536e-05 -4.03492352998743e-05 -5.75263741562807e-06 7.16050294068816e-06 1.18540631183375e-05 -5.10609817732821e-06 2.57846422512932e-06 -3.60731685232079e-06 -1.14593348288794e-05 2.7059526664325e-05 -5.10609817732821e-06 5.99192794839513e-05 1.64667644868878e-05 3.46274209250319e-06 -1.16970719372219e-05 1.93345368739536e-05 2.57846422512932e-06 1.64667644868878e-05 2.6674054411121e-05 -6.40149166910631e-06 3.44989083400472e-05 -4.03492352998743e-05 -3.60731685232079e-06 3.46274209250319e-06 -6.40149166910631e-06 4.1056561326424e-05 1032 1034 0 13 0 1040 1056 0 35 0 0 0 0 0 0 18 37 0 2894 0 0 0 0 0 2168 +898 900 0.999999720676904 0.000207665710540428 -0.000717997957088561 0.000863511213038812 -0.000207385838986535 0.999999902505273 0.000389846840749326 -0.00161724811288694 0.000718078844908732 -0.000389697829247378 0.999999666249131 0.00268412706776705 2.22368244297587e-05 -2.03645484594856e-05 -5.95375646075815e-07 -1.72001632440534e-06 -2.67502506318531e-06 1.20605627737927e-05 -2.03645484594856e-05 3.15297992435334e-05 3.51096001948862e-06 1.15409218578468e-06 1.66117886434264e-06 -1.15754063587787e-05 -5.95375646075815e-07 3.51096001948862e-06 9.96744762876841e-06 -4.0951022437471e-06 4.30865042906227e-06 -2.64658238026606e-06 -1.72001632440534e-06 1.15409218578468e-06 -4.0951022437471e-06 2.70823227107832e-05 1.13508126880242e-06 4.28144387092889e-06 -2.67502506318531e-06 1.66117886434264e-06 4.30865042906227e-06 1.13508126880242e-06 1.78864634902669e-05 -4.39549363348974e-07 1.20605627737927e-05 -1.15754063587787e-05 -2.64658238026606e-06 4.28144387092889e-06 -4.39549363348974e-07 2.10233399914965e-05 1145 1142 0 15 0 1141 1162 0 41 0 0 0 0 0 0 15 40 0 2945 0 0 0 0 0 2139 +897 871 0.995974116100891 0.00164500639186013 -0.0896261904301414 0.0176903120739523 -0.0126030056056108 0.992470295261328 -0.121835451628817 0.0163556216052903 0.0887509115826658 0.122474515626164 0.988495457104069 -0.0134343606230087 6.08539169197496e-05 -8.42996567965065e-05 5.72157611850427e-06 -2.23261366273477e-05 -1.54779740255094e-05 3.34372501931564e-05 -8.42996567965065e-05 0.000186418192497704 -1.20161419381384e-05 5.95853028583472e-05 3.15756796273056e-05 -3.55953909126721e-05 5.72157611850427e-06 -1.20161419381384e-05 1.20781476200626e-05 -7.49616930520221e-06 -3.72818341898523e-06 2.2175440480483e-06 -2.23261366273477e-05 5.95853028583472e-05 -7.49616930520221e-06 7.70947247236306e-05 2.80021447719696e-05 -1.18581596806397e-05 -1.54779740255094e-05 3.15756796273056e-05 -3.72818341898523e-06 2.80021447719696e-05 3.61856982952075e-05 -7.60252035838101e-06 3.34372501931564e-05 -3.55953909126721e-05 2.2175440480483e-06 -1.18581596806397e-05 -7.60252035838101e-06 4.72753273835057e-05 771 768 0 14 0 767 775 0 24 0 0 0 0 0 0 4 15 0 2323 0 0 0 0 0 2105 +897 899 0.999999639547682 0.000742794423943009 0.000411291805255716 0.00298764475704805 -0.000743036711140824 0.999999550340804 0.000589249213715674 0.00221473747566018 -0.000410853929284312 -0.000589554606229726 0.999999741812174 0.000600408531119551 2.88556059071444e-05 -2.85076563163129e-05 -5.37545797652617e-07 -8.14064405622584e-06 -6.27021071770356e-06 1.46305247317886e-05 -2.85076563163129e-05 3.73826791130371e-05 2.00133854170244e-06 1.11267104901496e-05 7.92301646017673e-06 -1.33640929691731e-05 -5.37545797652617e-07 2.00133854170244e-06 1.05157827707035e-05 -5.91627214478473e-06 4.64088220897982e-06 -2.97182557211758e-06 -8.14064405622584e-06 1.11267104901496e-05 -5.91627214478473e-06 4.41995857504654e-05 9.28751357395918e-06 6.63407892634302e-06 -6.27021071770356e-06 7.92301646017673e-06 4.64088220897982e-06 9.28751357395918e-06 2.11805942426882e-05 1.01550358679488e-06 1.46305247317886e-05 -1.33640929691731e-05 -2.97182557211758e-06 6.63407892634302e-06 1.01550358679488e-06 2.59827267891852e-05 1088 1091 0 22 0 1087 1111 0 43 0 0 0 0 0 0 13 37 0 3049 0 0 0 0 0 2166 +897 929 0.999786500550943 -0.0206602169692557 0.000329773987649955 -0.00215663988049062 0.0206508249170845 0.999621839473295 0.0181582344480131 0.00209563145307071 -0.000704802343619655 -0.0181475475700814 0.999835071284684 -0.00849600425584619 3.34125554003548e-05 -2.96143679732444e-05 -4.68269658682996e-06 -7.86018516491678e-08 -3.72613768101822e-06 1.45403105999492e-05 -2.96143679732444e-05 3.58105968180348e-05 4.79384524327923e-06 3.03460060144492e-06 4.67397753927413e-06 -1.19272295078111e-05 -4.68269658682996e-06 4.79384524327923e-06 1.05759021568384e-05 -4.83846789891974e-07 2.93236243877378e-07 -2.90749271691117e-06 -7.86018516491678e-08 3.03460060144492e-06 -4.83846789891974e-07 3.48563272076255e-05 2.15723092462362e-06 6.61245470224478e-06 -3.72613768101822e-06 4.67397753927413e-06 2.93236243877378e-07 2.15723092462362e-06 2.17776393673454e-05 -3.48647400082902e-06 1.45403105999492e-05 -1.19272295078111e-05 -2.90749271691117e-06 6.61245470224478e-06 -3.48647400082902e-06 2.83882323126326e-05 1011 1009 0 0 0 1033 1034 0 12 0 0 0 0 0 0 41 66 0 3045 0 0 0 0 0 2006 +898 924 0.999997613087628 -0.000459940305022355 0.00213594802447089 0.00340825951929124 0.000465196680399191 0.999996863369796 -0.00246106534220515 -0.00371557927981846 -0.00213480938164763 0.00246205310378832 0.999994690427613 -0.00193716818597221 2.28784430088449e-05 -2.22999089504978e-05 -2.89156744789009e-06 -2.66356955584069e-06 -5.22741681568805e-06 1.10725228261563e-05 -2.22999089504978e-05 3.13819471275406e-05 3.7060371418855e-06 5.27966632455497e-06 5.20211266903984e-06 -8.36347100959942e-06 -2.89156744789009e-06 3.7060371418855e-06 1.12539583450203e-05 -4.71113073534262e-06 4.32166271897313e-06 -4.29332569185612e-06 -2.66356955584069e-06 5.27966632455497e-06 -4.71113073534262e-06 3.97605987798776e-05 5.90467191681306e-06 7.04619904947777e-06 -5.22741681568805e-06 5.20211266903984e-06 4.32166271897313e-06 5.90467191681306e-06 2.19378833239746e-05 -9.98443577687738e-07 1.10725228261563e-05 -8.36347100959942e-06 -4.29332569185612e-06 7.04619904947777e-06 -9.98443577687738e-07 2.30474482089172e-05 1132 1135 0 21 0 1136 1156 0 41 0 0 0 0 0 0 20 43 0 2929 0 0 0 0 0 2179 +898 929 0.999748979588691 -0.0212666976351172 0.00705020446985492 0.000958739722074809 0.0211161799049006 0.999561108096812 0.0207773464738957 0.00263412884281283 -0.00748897573731769 -0.0206232575498862 0.999759269269576 -0.0111235646527876 4.83569428189129e-05 -5.25831852278968e-05 -6.62033081866967e-06 -7.61506907793563e-06 -6.06470688703072e-06 1.96636576711516e-05 -5.25831852278968e-05 9.13474033506491e-05 7.87908371708104e-06 3.26514261803667e-05 1.39407689918248e-05 -1.98235157284761e-05 -6.62033081866967e-06 7.87908371708104e-06 1.01072677975976e-05 -1.33674202635127e-06 2.17913295735348e-06 -4.4742291204089e-06 -7.61506907793563e-06 3.26514261803667e-05 -1.33674202635127e-06 5.47654388540391e-05 2.69709470235532e-06 5.2937243596181e-06 -6.06470688703072e-06 1.39407689918248e-05 2.17913295735348e-06 2.69709470235532e-06 2.41351494504403e-05 -9.17281467324478e-06 1.96636576711516e-05 -1.98235157284761e-05 -4.4742291204089e-06 5.2937243596181e-06 -9.17281467324478e-06 3.08602242855205e-05 1020 1020 0 0 0 1036 1037 0 10 0 0 0 0 0 0 46 70 0 3036 0 0 0 0 0 1766 +899 925 0.99999916703138 -0.000425620648909126 0.00121851697169735 0.00115126747283299 0.000428003593763158 0.999997995400587 -0.00195601833600402 -0.00301256213502889 -0.0012176820072655 0.00195653823634507 0.999997344600804 -0.000107939215880535 3.51914140010725e-05 -3.49631066465338e-05 -7.88168945110542e-07 -6.81053437432421e-06 -7.33562419562566e-06 8.50666614476519e-06 -3.49631066465338e-05 4.54991160745602e-05 2.26695086338975e-06 1.10188067560374e-05 9.61577929540125e-06 -5.6540397184362e-06 -7.88168945110542e-07 2.26695086338975e-06 1.259780707924e-05 -6.53629683368332e-06 1.50686702680981e-06 -3.60650001355139e-06 -6.81053437432421e-06 1.10188067560374e-05 -6.53629683368332e-06 5.0539684977923e-05 1.32003688952085e-05 1.01602107698749e-05 -7.33562419562566e-06 9.61577929540125e-06 1.50686702680981e-06 1.32003688952085e-05 2.88593745379773e-05 5.1212058013578e-06 8.50666614476519e-06 -5.6540397184362e-06 -3.60650001355139e-06 1.01602107698749e-05 5.1212058013578e-06 2.69019488788683e-05 1094 1095 0 17 0 1093 1120 0 43 0 0 0 0 0 0 16 43 0 2893 0 0 0 0 0 1253 +898 872 0.995968448988803 -0.0111775819545642 -0.0890051137884093 0.00695248048548356 -0.000641357910222209 0.991293790649594 -0.13166703945783 0.016998938805848 0.0897019357587654 0.131193301205541 0.987290170334903 -0.0100185454772313 5.96123423426396e-05 -6.85389767153723e-05 6.13408469462006e-06 -1.71017205279734e-05 -7.23670555101841e-06 1.15986785166183e-05 -6.85389767153723e-05 0.000113172573984106 -9.28363151203402e-06 4.68976094577191e-05 1.80808986404576e-05 -1.43062679229388e-06 6.13408469462006e-06 -9.28363151203402e-06 1.11958922577553e-05 -6.24870185242872e-06 -3.01830127848127e-06 -6.54194001759913e-07 -1.71017205279734e-05 4.68976094577191e-05 -6.24870185242872e-06 9.89624723903644e-05 1.96705275550351e-05 8.69073378109939e-06 -7.23670555101841e-06 1.80808986404576e-05 -3.01830127848127e-06 1.96705275550351e-05 3.38406205462761e-05 5.09864015430325e-06 1.15986785166183e-05 -1.43062679229388e-06 -6.54194001759913e-07 8.69073378109939e-06 5.09864015430325e-06 3.8771078749611e-05 787 783 0 3 0 792 796 0 13 0 0 0 0 0 0 15 27 0 2232 0 0 0 0 0 1909 +899 927 0.999999849207625 0.000488085205902996 0.000251709275624007 0.00260887661917411 -0.000488532600443947 0.999998295687011 0.0017804378595302 0.00305123676946293 -0.000250839841253353 -0.00178056055924072 0.999998383340428 0.00107258797820211 2.84470447688866e-05 -2.41768587143031e-05 -5.02658693803947e-06 -1.26231549302576e-06 -4.89405316748797e-06 1.5453479419104e-05 -2.41768587143031e-05 4.06446235411035e-05 6.48239434019519e-06 1.09483496702735e-05 8.49507452760525e-06 -9.38968816706192e-06 -5.02658693803947e-06 6.48239434019519e-06 1.08647380350295e-05 -5.52850693032742e-06 4.11801815062315e-06 -5.63594662307656e-06 -1.26231549302576e-06 1.09483496702735e-05 -5.52850693032742e-06 4.38389066363351e-05 9.30504449515088e-06 1.05903972433875e-05 -4.89405316748797e-06 8.49507452760525e-06 4.11801815062315e-06 9.30504449515088e-06 2.22830707138191e-05 5.20578272813302e-07 1.5453479419104e-05 -9.38968816706192e-06 -5.63594662307656e-06 1.05903972433875e-05 5.20578272813302e-07 2.66612690644907e-05 1101 1100 0 12 0 1102 1129 0 41 0 0 0 0 0 0 15 41 0 2974 0 0 0 0 0 2333 +898 901 0.999996017122171 -0.000440684313026622 -0.00278774768060917 -0.00192339980694532 0.000437357295067363 0.999999191612528 -0.00119394006832347 -0.00168394753665721 0.00278827157768767 0.00119271607122112 0.999995401474418 0.000499309612426624 4.67144453921361e-05 -4.22081484328342e-05 -2.14111356833785e-06 -7.5304471319e-06 -8.19701428560006e-06 1.55018920096031e-05 -4.22081484328342e-05 5.44272501047914e-05 4.46720633698193e-06 1.49855414779674e-05 1.10037777851301e-05 -1.38849259042656e-05 -2.14111356833785e-06 4.46720633698193e-06 1.27886269984394e-05 -6.76215386154162e-06 5.082598800318e-06 -3.69179779328825e-06 -7.5304471319e-06 1.49855414779674e-05 -6.76215386154162e-06 4.02960363869724e-05 6.71248838589429e-06 9.46403159031209e-06 -8.19701428560006e-06 1.10037777851301e-05 5.082598800318e-06 6.71248838589429e-06 2.42824431366846e-05 1.98515517889391e-06 1.55018920096031e-05 -1.38849259042656e-05 -3.69179779328825e-06 9.46403159031209e-06 1.98515517889391e-06 2.91563950265682e-05 1111 1112 0 21 0 1113 1132 0 41 0 0 0 0 0 0 19 41 0 2915 0 0 0 0 0 1076 +898 927 0.999999924616091 -0.000386820151289919 -3.37340008144585e-05 3.33585174098548e-05 0.000386766165935204 0.999998667647897 -0.00158591120909086 -0.000238304334012498 3.43474182827245e-05 0.00158589804236852 0.999998741873036 -0.00121481652579707 2.09219518069339e-05 -1.8094651685075e-05 -3.72067285167306e-06 -5.02186282797488e-07 -3.47333653768329e-06 1.02729902918983e-05 -1.8094651685075e-05 2.39655556673939e-05 4.76590852647817e-06 -6.77200981874797e-07 3.01955623851179e-06 -9.61355062955707e-06 -3.72067285167306e-06 4.76590852647817e-06 1.17125907808128e-05 -5.36519808661467e-06 3.11110548245809e-06 -4.7650351562071e-06 -5.02186282797488e-07 -6.77200981874797e-07 -5.36519808661467e-06 3.58586215071382e-05 5.53507594121519e-06 7.75266062335654e-06 -3.47333653768329e-06 3.01955623851179e-06 3.11110548245809e-06 5.53507594121519e-06 2.04585444312794e-05 -4.04852317628885e-07 1.02729902918983e-05 -9.61355062955707e-06 -4.7650351562071e-06 7.75266062335654e-06 -4.04852317628885e-07 2.28715935496666e-05 1112 1110 0 14 0 1109 1136 0 42 0 0 0 0 0 0 13 40 0 2974 0 0 0 0 0 2179 +899 903 0.999996036197147 -0.000188482942864181 0.00280928178962901 0.00252242147408871 0.000185016499594022 0.99999922134091 0.00123413389426808 -6.72666668005285e-05 -0.00280951221534448 -0.00123360923892154 0.999995292413598 0.00250666944844142 3.30865278916242e-05 -3.77988983324184e-05 -6.47422322886402e-06 -1.44983602653447e-06 -3.55210436600003e-06 1.86945403903061e-05 -3.77988983324184e-05 7.26159040056304e-05 8.10381160320666e-06 1.83820886230547e-05 8.98916684467003e-06 -1.48652573570696e-05 -6.47422322886402e-06 8.10381160320666e-06 1.13737861139252e-05 -5.34353196992366e-06 3.74035506249891e-06 -6.23728256486085e-06 -1.44983602653447e-06 1.83820886230547e-05 -5.34353196992366e-06 4.85575213525525e-05 1.00303303545462e-05 8.28745876703975e-06 -3.55210436600003e-06 8.98916684467003e-06 3.74035506249891e-06 1.00303303545462e-05 1.95919095750402e-05 1.17479230036937e-07 1.86945403903061e-05 -1.48652573570696e-05 -6.23728256486085e-06 8.28745876703975e-06 1.17479230036937e-07 2.9014526903988e-05 1080 1082 0 17 0 1084 1105 0 40 0 0 0 0 0 0 15 41 0 2927 0 0 0 0 0 2319 +899 929 0.999795359523665 -0.0202259147915726 -0.000389160364641266 -0.00153595601902135 0.0202295967929892 0.999654745318264 0.0167676347845915 0.00135552435638535 4.98852527940708e-05 -0.0167720760050867 0.999859337596015 -0.00787441610178386 3.92142640288118e-05 -3.95482729381742e-05 -7.88060256659377e-06 6.8354372597286e-06 -5.18856804690396e-07 2.30802911266835e-05 -3.95482729381742e-05 6.25973262088682e-05 9.04539379819011e-06 4.64418134612953e-06 5.00857400546394e-06 -2.50986740542694e-05 -7.88060256659377e-06 9.04539379819011e-06 1.09597924258369e-05 -3.11839218635599e-06 1.85850298974928e-06 -4.48747466009003e-06 6.8354372597286e-06 4.64418134612953e-06 -3.11839218635599e-06 3.90639304695045e-05 3.53178991279444e-06 3.66603899056368e-06 -5.18856804690396e-07 5.00857400546394e-06 1.85850298974928e-06 3.53178991279444e-06 2.35392637477925e-05 -4.09793812053115e-06 2.30802911266835e-05 -2.50986740542694e-05 -4.48747466009003e-06 3.66603899056368e-06 -4.09793812053115e-06 3.44873066159854e-05 999 998 0 1 0 1017 1017 0 9 0 0 0 0 0 0 42 67 0 3031 0 0 0 0 0 1683 +898 902 0.99999879870416 -0.000471743066034215 -0.00147649880333374 -0.00144434875566046 0.000469453910986997 0.999998688002428 -0.0015503568775828 -0.000951986514594094 0.00147722823627778 0.00154966186700774 0.999997708169792 0.00145487084427562 3.29746053097389e-05 -3.29469692952681e-05 -3.64663067428539e-06 -8.9589302171968e-06 -6.45244357728785e-06 1.44929811488935e-05 -3.29469692952681e-05 4.32960673142687e-05 6.31707956614821e-06 1.09250457040326e-05 7.69395304146398e-06 -1.39872369411235e-05 -3.64663067428539e-06 6.31707956614821e-06 1.23395987484748e-05 -5.07078527903209e-06 4.52539643973267e-06 -4.41103524778154e-06 -8.9589302171968e-06 1.09250457040326e-05 -5.07078527903209e-06 3.6046122902261e-05 8.5815084871221e-06 6.24044928346408e-06 -6.45244357728785e-06 7.69395304146398e-06 4.52539643973267e-06 8.5815084871221e-06 2.3902648981432e-05 5.22625141439947e-07 1.44929811488935e-05 -1.39872369411235e-05 -4.41103524778154e-06 6.24044928346408e-06 5.22625141439947e-07 2.71427420625274e-05 1133 1130 0 14 0 1131 1158 0 42 0 0 0 0 0 0 16 43 0 3002 0 0 0 0 0 1078 +899 926 0.999999933407216 0.000273244370914898 -0.000241915432842884 0.00139198599625595 -0.000273238381835702 0.99999996236313 2.47896166339198e-05 -0.000414998757033558 0.000241922197361147 -2.47235144016992e-05 0.999999970431199 0.00129660950380226 2.86640424067486e-05 -2.58633393846284e-05 -1.94682847147618e-06 -5.038102572253e-06 -4.36455452393355e-06 1.20968570025642e-05 -2.58633393846284e-05 3.06457502044262e-05 4.35216832999243e-06 1.42272455963998e-06 2.93015457629584e-06 -1.1254147358437e-05 -1.94682847147618e-06 4.35216832999243e-06 1.16770781425401e-05 -7.11501956174952e-06 3.42909494836512e-06 -3.90113524329296e-06 -5.038102572253e-06 1.42272455963998e-06 -7.11501956174952e-06 4.00856645846525e-05 8.17772699454048e-06 7.45501603019606e-06 -4.36455452393355e-06 2.93015457629584e-06 3.42909494836512e-06 8.17772699454048e-06 2.30460386792293e-05 2.84073361168174e-07 1.20968570025642e-05 -1.1254147358437e-05 -3.90113524329296e-06 7.45501603019606e-06 2.84073361168174e-07 2.53154047902775e-05 1130 1127 0 9 0 1133 1159 0 41 0 0 0 0 0 0 15 42 0 2935 0 0 0 0 0 2330 +898 926 0.999999266812306 -0.000223464874594598 0.00119014213414382 0.00106979585916507 0.000226400445084595 0.999996931302317 -0.00246700806390025 -0.00194325915449149 -0.00118958719230978 0.00246727570382918 0.99999624870942 -0.000562092736982442 2.44355885216427e-05 -2.198345837302e-05 -2.23457303929712e-06 -1.30974386834399e-06 -3.52506140061323e-06 1.28373089407847e-05 -2.198345837302e-05 2.76539945702573e-05 3.66577034132544e-06 2.96368199578193e-06 3.91670390551437e-06 -1.14628466042538e-05 -2.23457303929712e-06 3.66577034132544e-06 1.06845537211557e-05 -4.59009981396836e-06 3.28666322070245e-06 -4.32454261425413e-06 -1.30974386834399e-06 2.96368199578193e-06 -4.59009981396836e-06 3.47585276090459e-05 5.08283592061679e-06 9.37368370249432e-06 -3.52506140061323e-06 3.91670390551437e-06 3.28666322070245e-06 5.08283592061679e-06 2.05488189713572e-05 1.22767528285674e-06 1.28373089407847e-05 -1.14628466042538e-05 -4.32454261425413e-06 9.37368370249432e-06 1.22767528285674e-06 2.77323678174481e-05 1119 1116 0 14 0 1116 1139 0 37 0 0 0 0 0 0 14 42 0 2936 0 0 0 0 0 2189 +898 928 0.999980635264961 -0.00103432169032492 -0.00613671522283294 -0.00877395584275856 0.00102393573131545 0.999998038703643 -0.00169533019937747 -0.00724684598802961 0.00613845670371321 0.00168901376776779 0.99997973308552 -0.00162506304477385 4.08852828690712e-05 -4.02395610584711e-05 -5.04596346817954e-06 -1.97668483943413e-06 -4.51298705078406e-06 1.24515017023702e-05 -4.02395610584711e-05 5.82157946090864e-05 7.77650665908387e-06 1.03039853487555e-05 4.89935678491304e-06 -6.50526668046181e-06 -5.04596346817954e-06 7.77650665908387e-06 1.38251833917918e-05 -6.09524286855018e-06 2.07284486764873e-06 -3.44853072116184e-06 -1.97668483943413e-06 1.03039853487555e-05 -6.09524286855018e-06 5.07587553537663e-05 1.08690462592173e-05 1.5115860032827e-05 -4.51298705078406e-06 4.89935678491304e-06 2.07284486764873e-06 1.08690462592173e-05 2.78079664052298e-05 8.57524359050351e-07 1.24515017023702e-05 -6.50526668046181e-06 -3.44853072116184e-06 1.5115860032827e-05 8.57524359050351e-07 2.96234893414256e-05 1057 1056 0 16 0 1057 1080 0 42 0 0 0 0 0 0 22 45 0 2876 0 0 0 0 0 1070 +899 902 0.99999934431532 0.000109229261032024 0.00113992890037463 0.00107568868649393 -0.00010969385016878 0.999999910953387 0.000407505186088735 0.00115333246936068 -0.00113988428737748 -0.000407629962083829 0.999999267250544 -0.00135366013602503 2.15999457868415e-05 -1.84392916354929e-05 -1.89736688839845e-06 -1.20738934095772e-07 -2.51719552312125e-06 1.57335421429445e-05 -1.84392916354929e-05 2.4960064469934e-05 3.62292997952007e-06 -1.05688017183926e-06 1.68437486622474e-06 -1.42714867518719e-05 -1.89736688839845e-06 3.62292997952007e-06 1.0486923386848e-05 -6.78545364353351e-06 3.66657592262058e-06 -3.56310364879978e-06 -1.20738934095772e-07 -1.05688017183926e-06 -6.78545364353351e-06 3.54485050355325e-05 8.1487468666317e-06 4.5049741042374e-06 -2.51719552312125e-06 1.68437486622474e-06 3.66657592262058e-06 8.1487468666317e-06 1.81435837239375e-05 -8.33928639798047e-07 1.57335421429445e-05 -1.42714867518719e-05 -3.56310364879978e-06 4.5049741042374e-06 -8.33928639798047e-07 2.39483981682556e-05 1088 1085 0 5 0 1097 1121 0 41 0 0 0 0 0 0 20 46 0 3000 0 0 0 0 0 2382 +899 928 0.999991011809897 0.000124537400727806 -0.00423801720786892 -0.00298477354661229 -0.000128287460966061 0.999999600511065 -0.000884601627034561 -0.00356181916756357 0.00423790534884063 0.0008851373605341 0.999990628301139 -0.00113667743373065 3.82674349843451e-05 -4.12651624728852e-05 -5.32151462138344e-06 -3.57024176799968e-06 -8.58407166924077e-06 3.02979325283219e-05 -4.12651624728852e-05 7.1344966251939e-05 6.48191827891783e-06 1.87966382253535e-05 1.47991903459017e-05 -3.59911296075685e-05 -5.32151462138344e-06 6.48191827891783e-06 1.12167485404633e-05 -6.45619035829725e-06 4.12753308007019e-06 -5.01087297564823e-06 -3.57024176799968e-06 1.87966382253535e-05 -6.45619035829725e-06 5.89239057434173e-05 1.19872843674133e-05 -1.25565205643817e-06 -8.58407166924077e-06 1.47991903459017e-05 4.12753308007019e-06 1.19872843674133e-05 2.43547067208374e-05 -7.69795587393491e-06 3.02979325283219e-05 -3.59911296075685e-05 -5.01087297564823e-06 -1.25565205643817e-06 -7.69795587393491e-06 4.06002119632923e-05 1066 1065 0 6 0 1081 1101 0 42 0 0 0 0 0 0 22 47 0 2886 0 0 0 0 0 2391 +898 925 0.99999066161431 -0.00015232497453521 0.0043189676169249 0.00393859933980212 0.000149434051909936 0.999999764605874 0.000669669814227527 -0.000570634854621043 -0.00431906860770269 -0.000669018159761452 0.999990448984921 -0.00136334336492069 3.65084597088526e-05 -3.80834051620769e-05 -2.73804149214668e-06 -8.52003844424747e-06 -9.0724939874065e-06 2.20182853194308e-05 -3.80834051620769e-05 6.90575800083626e-05 5.07598594070318e-06 2.25793267871381e-05 1.19221375353696e-05 -1.99796878737535e-05 -2.73804149214668e-06 5.07598594070318e-06 1.16815471828916e-05 -7.37649194940675e-06 3.64834351677702e-06 -3.33434372493526e-06 -8.52003844424747e-06 2.25793267871381e-05 -7.37649194940675e-06 6.36651904779001e-05 1.62924886448436e-05 1.34592919530791e-06 -9.0724939874065e-06 1.19221375353696e-05 3.64834351677702e-06 1.62924886448436e-05 2.61218282893586e-05 -4.71275239118971e-06 2.20182853194308e-05 -1.99796878737535e-05 -3.33434372493526e-06 1.34592919530791e-06 -4.71275239118971e-06 2.4872331940591e-05 1130 1139 0 25 0 1130 1157 0 46 0 0 0 0 0 0 14 39 0 2899 0 0 0 0 0 2577 +899 872 0.995950674465501 -0.0114990526478923 -0.0891629172914116 0.00699989336548536 -0.000342493559800523 0.991293601317024 -0.131669581476082 0.0163851406420525 0.0899007048352547 0.131166946202639 0.98727559247355 -0.0121546838143855 7.91615155503743e-05 -7.90970550917088e-05 6.02960603559121e-06 -1.08351322670616e-06 -1.22886099707852e-05 2.79591742651272e-05 -7.90970550917088e-05 0.000167142843444006 -1.16289808703464e-05 4.5208771720832e-05 2.60012664099364e-05 -2.36228630919978e-05 6.02960603559121e-06 -1.16289808703464e-05 1.09550443167988e-05 -2.61417613627106e-06 -2.22440675353859e-06 5.8601332207841e-07 -1.08351322670616e-06 4.5208771720832e-05 -2.61417613627106e-06 7.2885245879686e-05 1.40123426949402e-05 -4.9380823958213e-07 -1.22886099707852e-05 2.60012664099364e-05 -2.22440675353859e-06 1.40123426949402e-05 3.4618195878426e-05 -4.99806134401687e-06 2.79591742651272e-05 -2.36228630919978e-05 5.8601332207841e-07 -4.9380823958213e-07 -4.99806134401687e-06 5.00314084855522e-05 777 776 0 1 0 783 788 0 12 0 0 0 0 0 0 15 26 0 2234 0 0 0 0 0 1701 +899 901 0.999999349266038 0.000802208907263813 -0.000811127837664369 0.00205186346601776 -0.000802131818556923 0.999999673745477 9.53597613484599e-05 -3.77753708094907e-05 0.000811204071480192 -9.47090678471167e-05 0.999999666489018 -0.00115796468986517 3.45565007376301e-05 -3.13596551098396e-05 -1.57587008075403e-06 -6.34397238732286e-06 -6.82115420054415e-06 2.22831284851683e-05 -3.13596551098396e-05 4.82857150897252e-05 4.12680339901456e-06 1.34194948458478e-05 8.94892277111682e-06 -2.25355632040953e-05 -1.57587008075403e-06 4.12680339901456e-06 1.01937437247177e-05 -5.09310364102821e-06 4.82016986965491e-06 -2.29165565318139e-06 -6.34397238732286e-06 1.34194948458478e-05 -5.09310364102821e-06 3.98770804554526e-05 8.22356584332176e-06 -2.06951922587414e-06 -6.82115420054415e-06 8.94892277111682e-06 4.82016986965491e-06 8.22356584332176e-06 2.00959890622176e-05 -4.07784049882798e-06 2.22831284851683e-05 -2.25355632040953e-05 -2.29165565318139e-06 -2.06951922587414e-06 -4.07784049882798e-06 2.76802448546573e-05 1089 1088 0 19 0 1094 1111 0 43 0 0 0 0 0 0 13 37 0 2911 0 0 0 0 0 2376 +900 903 0.999999803456901 0.000622183976807923 7.72868618101585e-05 0.00136735266459051 -0.0006221349642451 0.999999606396691 -0.00063257770259867 0.000316573010493213 -7.76804111004368e-05 0.000632529495410879 0.999999796936075 -0.00268037854301384 2.17663118226477e-05 -1.77724576424479e-05 -4.71621308640037e-06 1.28606805836362e-06 -1.14865399160337e-06 8.07112523762058e-06 -1.77724576424479e-05 2.25980849987983e-05 6.81609510608656e-06 -9.03153087174387e-07 6.41855705536695e-08 -7.18542364922382e-06 -4.71621308640037e-06 6.81609510608656e-06 1.29287797041644e-05 -7.89451770203017e-06 3.51369633349799e-06 -5.41986841169387e-06 1.28606805836362e-06 -9.03153087174387e-07 -7.89451770203017e-06 2.73917247516591e-05 1.9718789151612e-06 4.80778030878321e-06 -1.14865399160337e-06 6.41855705536695e-08 3.51369633349799e-06 1.9718789151612e-06 1.85050826258054e-05 -2.27561387225316e-06 8.07112523762058e-06 -7.18542364922382e-06 -5.41986841169387e-06 4.80778030878321e-06 -2.27561387225316e-06 2.43979739773477e-05 1139 1141 0 13 0 1144 1168 0 44 0 0 0 0 0 0 15 39 0 2929 0 0 0 0 0 1277 +900 928 0.99997443116722 -0.000177527661978392 -0.00714881079093434 -0.00591666534820629 0.000176575974117755 0.999999975465091 -0.00013375628122375 -0.00227278226031473 0.0071488343609788 0.00013249055300257 0.999974437980058 0.00170936700309269 2.54038004358827e-05 -2.45324763049648e-05 -2.88708998771052e-06 3.08422324445306e-06 2.56561046631082e-07 1.45580852943398e-05 -2.45324763049648e-05 4.0457310656608e-05 5.52820715999394e-06 8.84727508241196e-09 1.7604105966883e-06 -1.23241918285136e-05 -2.88708998771052e-06 5.52820715999394e-06 1.03947876697138e-05 -3.99036898069677e-06 3.65843917627518e-06 -2.44833963035025e-06 3.08422324445306e-06 8.84727508241196e-09 -3.99036898069677e-06 4.10399749292347e-05 5.59391112854997e-06 1.08534484536727e-05 2.56561046631082e-07 1.7604105966883e-06 3.65843917627518e-06 5.59391112854997e-06 1.83063218234305e-05 -7.59032791089424e-07 1.45580852943398e-05 -1.23241918285136e-05 -2.44833963035025e-06 1.08534484536727e-05 -7.59032791089424e-07 2.78801645831721e-05 1076 1072 0 16 0 1074 1093 0 41 0 0 0 0 0 0 15 41 0 2885 0 0 0 0 0 2152 +899 873 0.995337698078346 -0.0222378328788871 -0.0938527867084988 0.0134379320882428 0.00889969343185085 0.990081828501373 -0.14020972979147 0.0300403179861077 0.0960398992133965 0.138720768669398 0.985663677984967 -0.0119854136699834 6.74381787154527e-05 -8.27132546657858e-05 1.49886839817663e-05 -3.20242213786144e-05 -1.06769649021573e-05 -6.62199507906855e-06 -8.27132546657858e-05 0.000154197056163698 -2.21441762962097e-05 7.53007263858614e-05 2.7868636070345e-05 4.23924720849441e-05 1.49886839817663e-05 -2.21441762962097e-05 1.3960506355461e-05 -1.03028271623472e-05 -6.64698279983487e-06 -2.6568742744501e-06 -3.20242213786144e-05 7.53007263858614e-05 -1.03028271623472e-05 9.09284549396005e-05 2.65301583086332e-05 4.2521772826684e-05 -1.06769649021573e-05 2.7868636070345e-05 -6.64698279983487e-06 2.65301583086332e-05 4.09989534803783e-05 1.76391223981693e-05 -6.62199507906855e-06 4.23924720849441e-05 -2.6568742744501e-06 4.2521772826684e-05 1.76391223981693e-05 6.84350026217056e-05 767 767 0 0 0 778 778 0 4 0 0 0 0 0 0 31 38 0 2133 0 0 0 0 0 1457 +900 927 0.999990522383253 -8.73141186356656e-05 -0.00435287490200872 -0.00188222958319976 7.83665346096779e-05 0.999997884005583 -0.00205568554098615 -0.000565951917906863 0.00435304518172094 0.00205532493826478 0.999988413251396 -0.00223735879928963 3.62079081168022e-05 -3.69174483917883e-05 -6.69871745357386e-06 4.5901082616359e-06 -4.36643063100688e-07 1.17186490223189e-05 -3.69174483917883e-05 6.24802743710351e-05 7.94903985317144e-06 2.71466956324443e-06 2.60027110544606e-06 -2.75790606705324e-06 -6.69871745357386e-06 7.94903985317144e-06 1.32216254817856e-05 -8.54870052052764e-06 2.89943308863527e-06 -5.01345672049428e-06 4.5901082616359e-06 2.71466956324443e-06 -8.54870052052764e-06 4.11526194182216e-05 6.32942340355151e-06 9.94549699792567e-06 -4.36643063100688e-07 2.60027110544606e-06 2.89943308863527e-06 6.32942340355151e-06 2.12539381849783e-05 3.12744344344365e-06 1.17186490223189e-05 -2.75790606705324e-06 -5.01345672049428e-06 9.94549699792567e-06 3.12744344344365e-06 2.98022626193689e-05 1061 1062 0 16 0 1060 1082 0 40 0 0 0 0 0 0 13 39 0 2981 0 0 0 0 0 1274 +900 926 0.99999923102215 -0.000601489457843416 -0.00108451166016865 -0.00200575300369125 0.000598767161909661 0.999996673849969 -0.00250873810599498 -0.00252763583667327 0.0010860170324434 0.00250808680686213 0.999996265026812 -0.00162218924907253 3.24177909005412e-05 -3.3103295066621e-05 -5.47264151366643e-06 -1.71115706317139e-06 -4.66833637757252e-06 1.43611868549318e-05 -3.3103295066621e-05 4.82791370743058e-05 8.53289595441561e-06 5.54372665199294e-06 5.98609775483342e-06 -1.32566861876707e-05 -5.47264151366643e-06 8.53289595441561e-06 1.31181855589695e-05 -7.36039160186509e-06 4.14514752958223e-06 -5.38726440637491e-06 -1.71115706317139e-06 5.54372665199294e-06 -7.36039160186509e-06 3.64604353269716e-05 3.72050171084686e-06 8.00044669363192e-06 -4.66833637757252e-06 5.98609775483342e-06 4.14514752958223e-06 3.72050171084686e-06 2.05337870325476e-05 -1.46521159890545e-06 1.43611868549318e-05 -1.32566861876707e-05 -5.38726440637491e-06 8.00044669363192e-06 -1.46521159890545e-06 2.68104056377548e-05 1083 1083 0 17 0 1081 1106 0 39 0 0 0 0 0 0 14 41 0 2915 0 0 0 0 0 1278 +900 904 0.999997695745495 0.000204645411517911 -0.00213696606337526 -0.000485935933185878 -0.000206435687701349 0.999999627923284 -0.000837578414343014 0.000336240055873418 0.00213679386168066 0.000838017630408066 0.999997365915753 -0.00209521913632094 4.07457037124099e-05 -4.13482577778959e-05 -3.84674515368727e-06 -7.57223726650336e-06 -8.14875727555011e-06 1.70559478433243e-05 -4.13482577778959e-05 6.78549197666237e-05 6.36060685070478e-06 2.1702589986387e-05 1.26099687603905e-05 -1.47399530109871e-05 -3.84674515368727e-06 6.36060685070478e-06 1.18330225052919e-05 -5.43545371182881e-06 5.46278235515477e-06 -3.73018309786341e-06 -7.57223726650336e-06 2.1702589986387e-05 -5.43545371182881e-06 3.79439333399113e-05 6.30007433711899e-06 3.15609320000825e-06 -8.14875727555011e-06 1.26099687603905e-05 5.46278235515477e-06 6.30007433711899e-06 2.11954483350653e-05 -2.45391384355158e-06 1.70559478433243e-05 -1.47399530109871e-05 -3.73018309786341e-06 3.15609320000825e-06 -2.45391384355158e-06 3.66041969905232e-05 1036 1034 0 9 0 1041 1061 0 40 0 0 0 0 0 0 13 40 0 2922 0 0 0 0 0 1280 +900 872 0.995060189543738 -0.011566465131929 -0.0985973431159923 0.0041511904920672 -0.0015196760714424 0.991298267101272 -0.131626122888478 0.0181873376610483 0.0992618243325133 0.131125750813358 0.986383864275878 -0.0123584284127243 6.02793714766818e-05 -7.61111796654247e-05 7.96934679809315e-06 -5.08412406155969e-06 -2.80890573405916e-06 -9.84446885867909e-06 -7.61111796654247e-05 0.000140700515831251 -1.37534267474207e-05 3.33545748250805e-05 1.32100069290287e-05 3.93192615005636e-05 7.96934679809315e-06 -1.37534267474207e-05 1.22682948150407e-05 -2.29697772663728e-06 -2.57229164015414e-06 -5.80543405279322e-06 -5.08412406155969e-06 3.33545748250805e-05 -2.29697772663728e-06 6.63974260096632e-05 1.16154707469141e-05 1.45962244096672e-05 -2.80890573405916e-06 1.32100069290287e-05 -2.57229164015414e-06 1.16154707469141e-05 2.7047031053134e-05 6.84434231565659e-06 -9.84446885867909e-06 3.93192615005636e-05 -5.80543405279322e-06 1.45962244096672e-05 6.84434231565659e-06 6.30212776512085e-05 777 776 0 2 0 785 792 0 16 0 0 0 0 0 0 16 27 0 2231 0 0 0 0 0 1691 +900 873 0.995619508613233 -0.0221481814223025 -0.090836403101556 0.0149596906474321 0.00941889414443631 0.990354445595442 -0.138236596176416 0.0334160560448706 0.0930219248448423 0.136775473492255 0.986224817852973 -0.0110716633514193 6.1567959387963e-05 -8.18423338751158e-05 1.04598784950035e-05 -2.46072926079256e-05 -1.73310320513454e-05 5.57839194034524e-06 -8.18423338751158e-05 0.000265527713777211 -2.45444909105632e-05 9.61209037637175e-05 4.06534649710619e-05 3.29550610302016e-05 1.04598784950035e-05 -2.45444909105632e-05 1.272794669855e-05 -7.62545612759624e-06 -5.57510101638775e-06 -5.77517214843315e-07 -2.46072926079256e-05 9.61209037637175e-05 -7.62545612759624e-06 7.68943754894714e-05 2.08680785193315e-05 2.26587165764447e-05 -1.73310320513454e-05 4.06534649710619e-05 -5.57510101638775e-06 2.08680785193315e-05 4.21239999679559e-05 7.49929621259346e-06 5.57839194034524e-06 3.29550610302016e-05 -5.77517214843315e-07 2.26587165764447e-05 7.49929621259346e-06 5.60578273395632e-05 768 767 0 3 0 775 776 0 7 0 0 0 0 0 0 23 30 0 2130 0 0 0 0 0 1743 +901 903 0.99998976675252 -0.00026308095643646 0.00451632357695854 0.00266919923852242 0.000252785119019507 0.999997368586787 0.0022801138535483 0.00188614630512433 -0.00451691154717838 -0.00227894886118602 0.999987201869186 0.00217279232667066 3.98456663267922e-05 -4.10099955853426e-05 -5.79755187545457e-06 -9.425491607351e-06 -5.892148517397e-06 2.13240490312576e-06 -4.10099955853426e-05 7.38325994605478e-05 6.61155413700892e-06 3.27044700650307e-05 1.3864719510708e-05 1.31505109031817e-06 -5.79755187545457e-06 6.61155413700892e-06 1.11963609812326e-05 -4.76200179329541e-06 3.39428090280332e-06 -1.39953377994827e-06 -9.425491607351e-06 3.27044700650307e-05 -4.76200179329541e-06 6.2266123797281e-05 1.80965216491327e-05 9.08102180704383e-06 -5.892148517397e-06 1.3864719510708e-05 3.39428090280332e-06 1.80965216491327e-05 2.53655369073099e-05 1.02688381723486e-06 2.13240490312576e-06 1.31505109031817e-06 -1.39953377994827e-06 9.08102180704383e-06 1.02688381723486e-06 3.25286617263059e-05 1070 1068 0 13 0 1068 1089 0 36 0 0 0 0 0 0 11 36 0 2932 0 0 0 0 0 2308 +901 928 0.999998611968686 -0.000204872649827187 -0.00165350775557838 -0.00230825223053338 0.000206565335467252 0.999999454799084 0.00102358795231353 -0.00142725673406631 0.00165329714890832 -0.00102392808892563 0.999998109088115 -0.0013485720086425 1.76745230944989e-05 -1.48669090944656e-05 -2.56912088476385e-06 1.90325738293056e-06 4.40260309418862e-07 1.17866911681518e-05 -1.48669090944656e-05 2.1204203798435e-05 4.26243118135059e-06 -1.23185425833377e-06 1.02292693010181e-07 -9.61528774860321e-06 -2.56912088476385e-06 4.26243118135059e-06 1.19678853121493e-05 -4.73574426659232e-06 1.74978560725174e-06 -3.04425414680101e-06 1.90325738293056e-06 -1.23185425833377e-06 -4.73574426659232e-06 4.2450506254249e-05 9.92170751074746e-06 6.84949438434219e-06 4.40260309418862e-07 1.02292693010181e-07 1.74978560725174e-06 9.92170751074746e-06 2.25255585263886e-05 1.02715797270667e-08 1.17866911681518e-05 -9.61528774860321e-06 -3.04425414680101e-06 6.84949438434219e-06 1.02715797270667e-08 2.00487365880327e-05 1103 1104 0 19 0 1099 1124 0 41 0 0 0 0 0 0 16 42 0 2901 0 0 0 0 0 2390 +900 902 0.999998775723915 0.000132642745553048 -0.00155915251783627 -0.000939924433412045 -0.000132836554263702 0.999999983464283 -0.000124200983011871 0.00101267958765182 0.00155913601769518 0.000124407943403619 0.999998776808023 0.00472864756660712 3.39859788145366e-05 -2.91084362312963e-05 -3.90162551673136e-06 -3.24402379495568e-06 -4.92854404019575e-06 9.15315462102829e-06 -2.91084362312963e-05 4.5754755628008e-05 7.03657310080057e-06 5.35351153008933e-06 3.72995601987756e-06 -7.1598934496473e-06 -3.90162551673136e-06 7.03657310080057e-06 1.19423161456753e-05 -6.20133088993982e-06 3.78816302272778e-06 -2.34932547095218e-06 -3.24402379495568e-06 5.35351153008933e-06 -6.20133088993982e-06 4.06549742676037e-05 1.05321125151293e-05 6.6237097829365e-06 -4.92854404019575e-06 3.72995601987756e-06 3.78816302272778e-06 1.05321125151293e-05 2.16936961970045e-05 2.95908704472431e-07 9.15315462102829e-06 -7.1598934496473e-06 -2.34932547095218e-06 6.6237097829365e-06 2.95908704472431e-07 2.73535256717518e-05 1088 1087 0 17 0 1086 1108 0 37 0 0 0 0 0 0 14 40 0 2984 0 0 0 0 0 2167 +901 929 0.99978089846417 -0.0209126258003676 0.000903962560804533 -0.00408837278204533 0.0208925287518682 0.99961331048729 0.0183502517419835 0.00139402972648311 -0.00128736495598503 -0.0183273451098517 0.999831211311537 -0.00994086220354388 3.38168557765132e-05 -3.34303968004923e-05 -6.97453493819775e-06 2.77541904607292e-06 -2.68960123674801e-06 2.1881730074357e-05 -3.34303968004923e-05 6.00377412933083e-05 8.56209638434344e-06 1.13957740787526e-05 6.55356256135849e-06 -2.53283696336688e-05 -6.97453493819775e-06 8.56209638434344e-06 1.13056126202436e-05 -3.48990483397522e-06 2.51967672227467e-06 -3.65642050919705e-06 2.77541904607292e-06 1.13957740787526e-05 -3.48990483397522e-06 4.40472945925986e-05 3.55642462521515e-06 4.33886709931524e-06 -2.68960123674801e-06 6.55356256135849e-06 2.51967672227467e-06 3.55642462521515e-06 2.25722991451489e-05 -6.73702138507169e-06 2.1881730074357e-05 -2.53283696336688e-05 -3.65642050919705e-06 4.33886709931524e-06 -6.73702138507169e-06 3.78970587990923e-05 1010 1008 0 1 0 1025 1026 0 13 0 0 0 0 0 0 45 69 0 3044 0 0 0 0 0 1676 +901 927 0.999998614733909 -0.000208897673146011 0.00165133038039015 0.00163228208442841 0.000206913116963557 0.999999256345258 0.00120187182892136 0.000907129108212703 -0.00165158022059896 -0.00120152848209293 0.999997914303866 0.0030688860083162 2.52867874767061e-05 -2.19047120824705e-05 -3.44306345447052e-06 -7.44101552797951e-07 -2.30459114606856e-06 8.50075059141118e-06 -2.19047120824705e-05 3.26986282462694e-05 3.49759237032487e-06 9.615557372851e-06 4.82840549159892e-06 -3.21366276176741e-06 -3.44306345447052e-06 3.49759237032487e-06 9.82077953902913e-06 -4.87753211268303e-06 3.5826556446771e-06 -4.08022169874571e-06 -7.44101552797951e-07 9.615557372851e-06 -4.87753211268303e-06 4.22811065273353e-05 6.32649511700283e-06 9.43217158978015e-06 -2.30459114606856e-06 4.82840549159892e-06 3.5826556446771e-06 6.32649511700283e-06 1.96407531444986e-05 2.13279144211715e-06 8.50075059141118e-06 -3.21366276176741e-06 -4.08022169874571e-06 9.43217158978015e-06 2.13279144211715e-06 2.5994526575637e-05 1081 1089 0 14 0 1087 1114 0 41 0 0 0 0 0 0 10 37 0 2972 0 0 0 0 0 2310 +901 872 0.995863162266587 -0.0114553665979735 -0.0901406490796382 0.00691118769567203 -0.000420432380386197 0.991429911413573 -0.13063902170136 0.0174114095659401 0.0908646536173774 0.130136487314592 0.987323710538956 -0.0115209739171978 6.09672467802995e-05 -7.25344152802751e-05 9.08807637119858e-06 -8.29542541342544e-06 -9.82240440992265e-06 2.05931550587778e-05 -7.25344152802751e-05 0.000135659030286134 -1.48393253092405e-05 4.26189006953805e-05 2.10881016148159e-05 -1.17130982338029e-05 9.08807637119858e-06 -1.48393253092405e-05 1.24836534442272e-05 -5.74755920988245e-06 -2.64060084642794e-06 7.0809916094177e-07 -8.29542541342544e-06 4.26189006953805e-05 -5.74755920988245e-06 8.84903750864754e-05 1.7192701716527e-05 4.20882443185678e-06 -9.82240440992265e-06 2.10881016148159e-05 -2.64060084642794e-06 1.7192701716527e-05 3.1171032312024e-05 3.77710926158154e-06 2.05931550587778e-05 -1.17130982338029e-05 7.0809916094177e-07 4.20882443185678e-06 3.77710926158154e-06 4.34250377595097e-05 772 769 0 6 0 778 782 0 14 0 0 0 0 0 0 18 29 0 2231 0 0 0 0 0 1758 +900 929 0.999780850642065 -0.0207881493815296 0.00247053328677732 -0.00210967878763272 0.020733909014341 0.999579768533195 0.0202581182766081 0.0031385753977041 -0.00289062387987325 -0.0202024549106099 0.999791730866569 -0.0104373323417568 3.50944020512918e-05 -3.47117290017105e-05 -6.18576449491617e-06 1.00678621248272e-06 -5.99567330416203e-07 1.76902933811996e-05 -3.47117290017105e-05 5.77988409441245e-05 6.49005178604201e-06 1.02926187644415e-05 5.80176881569036e-06 -1.96556080940796e-05 -6.18576449491617e-06 6.49005178604201e-06 9.50356213877189e-06 1.00939689707925e-07 1.69405352623779e-06 -3.20015794982527e-06 1.00678621248272e-06 1.02926187644415e-05 1.00939689707925e-07 3.16365128686098e-05 6.63012879678331e-07 3.62639718408982e-06 -5.99567330416203e-07 5.80176881569036e-06 1.69405352623779e-06 6.63012879678331e-07 1.93007052838373e-05 -5.03626550894364e-06 1.76902933811996e-05 -1.96556080940796e-05 -3.20015794982527e-06 3.62639718408982e-06 -5.03626550894364e-06 2.8091697292106e-05 1009 1008 0 0 0 1039 1038 0 14 0 0 0 0 0 0 51 74 0 3036 0 0 0 0 0 2031 +901 873 0.995706441119127 -0.021583509448119 -0.090015749920694 0.0179318578832681 0.00884140096023563 0.990165971298139 -0.139617974889598 0.0302918209437627 0.0921439783325113 0.138222651555796 0.986105463859694 -0.00944378944533279 8.4347815180826e-05 -0.000128039811013395 1.72368358509694e-05 -4.81285243277281e-05 -2.10567749722536e-05 -1.67197874254272e-05 -0.000128039811013395 0.000363203665190486 -3.9428161258713e-05 0.000175968948978275 6.05838644102605e-05 0.000110807993329288 1.72368358509694e-05 -3.9428161258713e-05 1.56071790812271e-05 -1.65715306074269e-05 -8.83374340932299e-06 -6.8291838029832e-06 -4.81285243277281e-05 0.000175968948978275 -1.65715306074269e-05 0.000134218617075032 3.34343047214887e-05 7.13967840300544e-05 -2.10567749722536e-05 6.05838644102605e-05 -8.83374340932299e-06 3.34343047214887e-05 4.61201084395899e-05 2.50764999261496e-05 -1.67197874254272e-05 0.000110807993329288 -6.8291838029832e-06 7.13967840300544e-05 2.50764999261496e-05 0.000106040904440008 763 764 0 2 0 773 775 0 5 0 0 0 0 0 0 27 33 0 2133 0 0 0 0 0 1446 +901 904 0.999999874818525 0.000459636148957491 0.000197730991204828 0.00340989056083678 -0.000460035286822027 0.999997847303669 0.00202330313146108 0.0020410010389449 -0.00019680058229053 -0.00202339384141427 0.999997933571312 0.00222265887709392 3.02875123375045e-05 -2.51773157381176e-05 -2.02667665464989e-06 -4.41731837037891e-06 -3.51334652961108e-06 7.4540658916521e-06 -2.51773157381176e-05 3.43690860816545e-05 4.83043099272994e-06 1.4630528546377e-06 1.91917378064094e-06 -5.20403596293464e-06 -2.02667665464989e-06 4.83043099272994e-06 1.15029375065151e-05 -4.32422348280675e-06 4.21761624974069e-06 -2.37801817661935e-06 -4.41731837037891e-06 1.4630528546377e-06 -4.32422348280675e-06 3.2688765699762e-05 5.24446483976237e-06 2.3555240283083e-06 -3.51334652961108e-06 1.91917378064094e-06 4.21761624974069e-06 5.24446483976237e-06 1.9904661439494e-05 -1.11532166333564e-06 7.4540658916521e-06 -5.20403596293464e-06 -2.37801817661935e-06 2.3555240283083e-06 -1.11532166333564e-06 2.62889536774121e-05 1073 1074 0 18 0 1071 1099 0 42 0 0 0 0 0 0 11 39 0 2937 0 0 0 0 0 2310 +901 905 0.999999484420199 0.000223107092047995 0.000990647546908222 0.0020063731439632 -0.000222961530568813 0.999999964333153 -0.00014704369538062 -0.000343263691381697 -0.000990680318066228 0.000146822743274548 0.999999498497669 -0.00395831547037401 3.57321460273682e-05 -3.13304214225351e-05 -1.3801091394244e-06 -4.57873841744665e-06 -6.06344536923791e-06 1.21475734987993e-05 -3.13304214225351e-05 4.55246946375065e-05 4.32335628898931e-06 7.16428680828468e-06 7.04039169877644e-06 -1.05710827140107e-05 -1.3801091394244e-06 4.32335628898931e-06 1.25550228022552e-05 -6.58575278111652e-06 3.92635585074246e-06 -2.6774170885548e-06 -4.57873841744665e-06 7.16428680828468e-06 -6.58575278111652e-06 3.86649181309063e-05 7.38489141083146e-06 6.24726899755201e-06 -6.06344536923791e-06 7.04039169877644e-06 3.92635585074246e-06 7.38489141083146e-06 2.19390812683508e-05 -1.3219617707869e-06 1.21475734987993e-05 -1.05710827140107e-05 -2.6774170885548e-06 6.24726899755201e-06 -1.3219617707869e-06 3.03063349666239e-05 1068 1076 0 15 0 1073 1100 0 46 0 0 0 0 0 0 11 39 0 2999 0 0 0 0 0 2154 +902 906 0.999994878196153 -0.000188218515281057 -0.00319502038374089 -0.00258906348663087 0.000182278447858112 0.999998254787924 -0.00185935356356606 -0.00255084901684739 0.00319536477251985 0.0018587616569654 0.999993167301194 -0.000407647209162318 4.58290729395223e-05 -4.45615454363396e-05 -5.22028669735781e-06 -1.01093696200303e-05 -9.95736575690364e-06 1.06468392154108e-05 -4.45615454363396e-05 6.36800167951199e-05 5.85376480529482e-06 2.26431794985846e-05 1.30135736437447e-05 -3.75617790467884e-06 -5.22028669735781e-06 5.85376480529482e-06 1.1960955634007e-05 -5.54622188006711e-06 4.21194421106069e-06 -3.86951215932154e-06 -1.01093696200303e-05 2.26431794985846e-05 -5.54622188006711e-06 5.0479353248404e-05 1.35944725388012e-05 1.11476537485217e-05 -9.95736575690364e-06 1.30135736437447e-05 4.21194421106069e-06 1.35944725388012e-05 2.37179668881449e-05 -5.7667236129443e-07 1.06468392154108e-05 -3.75617790467884e-06 -3.86951215932154e-06 1.11476537485217e-05 -5.7667236129443e-07 3.40075041456542e-05 1125 1127 0 18 0 1124 1145 0 36 0 0 0 0 0 0 14 37 0 3038 0 0 0 0 0 2149 +901 875 0.996346992647631 -0.0101392058247794 -0.0847930819540376 0.0230201390434612 -0.00164847127734763 0.990458013356165 -0.137804957534217 0.0251010535474118 0.0853812203266569 0.137441333971271 0.986823148761585 0.00508755486428055 5.98720491020787e-05 -6.44991706920073e-05 6.14112886414793e-06 -1.41752026649298e-05 -9.19167223490839e-06 2.20766139169324e-05 -6.44991706920073e-05 0.000123180495201744 -1.16186915355477e-05 4.62377356800686e-05 2.35211769007999e-05 -1.49576507379519e-05 6.14112886414793e-06 -1.16186915355477e-05 1.21097963611741e-05 -5.69195701718483e-06 -1.83585888511227e-06 -1.29582318036431e-07 -1.41752026649298e-05 4.62377356800686e-05 -5.69195701718483e-06 7.01651132845141e-05 1.74054525988577e-05 1.11856465844872e-06 -9.19167223490839e-06 2.35211769007999e-05 -1.83585888511227e-06 1.74054525988577e-05 2.84113814657726e-05 4.04508946679328e-06 2.20766139169324e-05 -1.49576507379519e-05 -1.29582318036431e-07 1.11856465844872e-06 4.04508946679328e-06 5.05563991851837e-05 755 751 0 4 0 759 762 0 12 0 0 0 0 0 0 18 28 0 2092 0 0 0 0 0 1422 +902 929 0.999757031701586 -0.0209510420690236 0.00685064956445391 0.0013928375603016 0.0208225074600724 0.999615248865116 0.0183242303906141 0.0016961947013422 -0.00723192549105553 -0.0181771304818742 0.999808627278809 -0.0109399194111245 3.74566834688227e-05 -3.55866548903631e-05 -7.23153895734736e-06 9.06023252058823e-07 -2.97195584277374e-06 2.16975654607003e-05 -3.55866548903631e-05 0.000105632735004499 1.04739248908388e-05 3.631712414623e-05 1.0563216654989e-05 -3.87658364092719e-05 -7.23153895734736e-06 1.04739248908388e-05 1.11032444233573e-05 -1.68355753515014e-07 1.85578266379588e-06 -4.90404484188719e-06 9.06023252058823e-07 3.631712414623e-05 -1.68355753515014e-07 5.63875462854252e-05 4.65258232390138e-06 -4.15068117253649e-06 -2.97195584277374e-06 1.0563216654989e-05 1.85578266379588e-06 4.65258232390138e-06 2.68273195823936e-05 -9.28908556376636e-06 2.16975654607003e-05 -3.87658364092719e-05 -4.90404484188719e-06 -4.15068117253649e-06 -9.28908556376636e-06 4.08706436208105e-05 1000 998 0 5 0 1010 1008 0 11 0 0 0 0 0 0 37 61 0 3035 0 0 0 0 0 1678 +902 905 0.999996457634753 3.40530104789331e-06 0.00266171116961361 0.0015456882140625 -2.045736427305e-06 0.999999869545459 -0.000510788487728485 -0.00108665575890299 -0.00266171256176987 0.000510781233169599 0.99999632718764 -0.00413466521088108 3.24410604828435e-05 -3.13752783352111e-05 -1.93011979289329e-06 -1.72784400954332e-06 -2.71894572506873e-06 1.07538802970475e-05 -3.13752783352111e-05 4.96317146586523e-05 4.37561041096943e-06 9.765608824291e-06 5.92182841613291e-06 -8.33803004175116e-06 -1.93011979289329e-06 4.37561041096943e-06 1.03941282194074e-05 -4.05792747619333e-06 3.52857608139378e-06 -7.8819473737699e-07 -1.72784400954332e-06 9.765608824291e-06 -4.05792747619333e-06 4.02807850902961e-05 8.91369261706647e-06 5.00656749549183e-06 -2.71894572506873e-06 5.92182841613291e-06 3.52857608139378e-06 8.91369261706647e-06 1.93271685974789e-05 -1.82457136189001e-06 1.07538802970475e-05 -8.33803004175116e-06 -7.8819473737699e-07 5.00656749549183e-06 -1.82457136189001e-06 3.04713867078729e-05 1096 1096 0 17 0 1093 1115 0 37 0 0 0 0 0 0 13 38 0 3003 0 0 0 0 0 2134 +902 872 0.995694430366111 -0.0115789218642322 -0.0919702664254418 0.0072856193281145 -0.000586885152912827 0.991360430506524 -0.131164600375773 0.0166172614018918 0.09269442757643 0.130653838039229 0.987085263643368 -0.0139865238335117 7.61472416126311e-05 -9.93778805691688e-05 1.33273695643189e-05 -2.00487088706697e-05 -1.60673317582598e-05 2.08147106863033e-05 -9.93778805691688e-05 0.000205191201065023 -2.37594349719995e-05 8.88146556596204e-05 3.89870780374496e-05 -2.27056938231106e-05 1.33273695643189e-05 -2.37594349719995e-05 1.311496165861e-05 -8.79705970410314e-06 -4.17215040947999e-06 7.26506022721134e-07 -2.00487088706697e-05 8.88146556596204e-05 -8.79705970410314e-06 0.000105316700406192 2.47915745342691e-05 3.64653866038572e-06 -1.60673317582598e-05 3.89870780374496e-05 -4.17215040947999e-06 2.47915745342691e-05 3.78572028056475e-05 -1.10692613969503e-07 2.08147106863033e-05 -2.27056938231106e-05 7.26506022721134e-07 3.64653866038572e-06 -1.10692613969503e-07 4.84752888656026e-05 788 785 0 4 0 793 795 0 13 0 0 0 0 0 0 14 24 0 2227 0 0 0 0 0 1650 +902 875 0.996510543303516 -0.0097374633446724 -0.0828970378996932 0.0250637771850522 -0.00180158427729233 0.990430940826097 -0.137997484572817 0.0240267252351485 0.0834475366863745 0.137665294326291 0.986957332086363 0.00454770782466573 4.40174042441753e-05 -4.35846566894254e-05 1.68329445860236e-06 3.0336015114593e-06 -1.79553085498565e-06 2.10164195138606e-05 -4.35846566894254e-05 7.49654849827965e-05 -3.68242763733948e-06 7.92681593699654e-06 6.59480415124827e-06 -1.57723602729322e-05 1.68329445860236e-06 -3.68242763733948e-06 1.1706404589437e-05 -3.55983631363789e-06 -6.51216511034771e-07 -1.29450914300529e-06 3.0336015114593e-06 7.92681593699654e-06 -3.55983631363789e-06 5.49303529673359e-05 1.06532873235953e-05 3.73003514454022e-06 -1.79553085498565e-06 6.59480415124827e-06 -6.51216511034771e-07 1.06532873235953e-05 2.96680433429382e-05 2.27434913075461e-06 2.10164195138606e-05 -1.57723602729322e-05 -1.29450914300529e-06 3.73003514454022e-06 2.27434913075461e-06 4.32163856247304e-05 756 751 0 5 0 756 759 0 14 0 0 0 0 0 0 11 20 0 2087 0 0 0 0 0 1395 +902 873 0.995534108074033 -0.0217905804393816 -0.091853199537932 0.0169556114298515 0.0087844977129736 0.990156556442376 -0.139688318531315 0.0299318863860484 0.0939929372940918 0.138257601376164 0.985926043575551 -0.00893970477549125 8.12734703006801e-05 -0.000135775443233516 1.81562368460358e-05 -6.32346192716358e-05 -2.93563391193811e-05 -1.69106908884917e-05 -0.000135775443233516 0.000329839310654972 -4.02592458595608e-05 0.000188209099251683 8.25058029408774e-05 6.95545772587528e-05 1.81562368460358e-05 -4.02592458595608e-05 1.55404272206765e-05 -2.15100697778993e-05 -1.28291917703952e-05 -6.20559628666537e-06 -6.32346192716358e-05 0.000188209099251683 -2.15100697778993e-05 0.000162699100100332 5.7954152438325e-05 5.13548416120159e-05 -2.93563391193811e-05 8.25058029408774e-05 -1.28291917703952e-05 5.7954152438325e-05 6.25946096980704e-05 2.07937559186753e-05 -1.69106908884917e-05 6.95545772587528e-05 -6.20559628666537e-06 5.13548416120159e-05 2.07937559186753e-05 6.50467208085443e-05 769 767 0 0 0 778 777 0 6 0 0 0 0 0 0 26 33 0 2129 0 0 0 0 0 1453 +903 905 0.999999884992904 -2.56120590039845e-05 -0.000478913562758916 -0.000479102405896734 2.57768445553854e-05 0.999999940472588 0.000344079024513596 0.000323896569716299 0.000478904721678154 -0.000344091329822529 0.999999826125697 0.0010366049863282 2.59150656835459e-05 -2.161606101292e-05 -2.73607634414386e-06 -3.76617740234033e-06 -2.40559569054746e-06 1.56616270720794e-06 -2.161606101292e-05 2.9491435607177e-05 4.43728502089861e-06 6.47187226558061e-06 3.9436085983195e-06 4.0181843670209e-07 -2.73607634414386e-06 4.43728502089861e-06 1.25731306032637e-05 -3.10509592481553e-06 2.950879175895e-06 -7.50850656523378e-07 -3.76617740234033e-06 6.47187226558061e-06 -3.10509592481553e-06 2.92447748265079e-05 3.70113899910735e-06 7.0687949294711e-06 -2.40559569054746e-06 3.9436085983195e-06 2.950879175895e-06 3.70113899910735e-06 1.93997968485835e-05 -1.74456157340165e-07 1.56616270720794e-06 4.0181843670209e-07 -7.50850656523378e-07 7.0687949294711e-06 -1.74456157340165e-07 2.90274345667145e-05 1117 1125 0 24 0 1115 1138 0 38 0 0 0 0 0 0 12 38 0 2997 0 0 0 0 0 1228 +902 904 0.999998502175966 0.000896053608160914 -0.00148078822125585 0.00275778509280624 -0.000894639888796535 0.999999143706998 0.000955094099730465 0.000391276395518098 0.00148164276878146 -0.000953767896957972 0.999998447529547 0.00286249977194422 2.41227652394997e-05 -1.99907136154147e-05 -2.9834072744378e-06 -1.96456771359929e-06 -2.88698404816644e-06 1.48646669181292e-06 -1.99907136154147e-05 2.91220021749413e-05 4.81909130775708e-06 3.28676409428709e-06 3.03388302282583e-06 1.17233824647968e-07 -2.9834072744378e-06 4.81909130775708e-06 1.33598119418398e-05 -8.98859973128729e-06 3.87038835829244e-06 -3.6592847170299e-06 -1.96456771359929e-06 3.28676409428709e-06 -8.98859973128729e-06 4.62785312519817e-05 9.57734948779071e-06 8.57781368616031e-06 -2.88698404816644e-06 3.03388302282583e-06 3.87038835829244e-06 9.57734948779071e-06 2.24158199714414e-05 -1.5597998755858e-07 1.48646669181292e-06 1.17233824647968e-07 -3.6592847170299e-06 8.57781368616031e-06 -1.5597998755858e-07 3.0972957450268e-05 1049 1048 0 20 0 1048 1068 0 41 0 0 0 0 0 0 14 37 0 2931 0 0 0 0 0 2306 +903 907 0.999997394117388 0.000108208187569294 -0.00228036168655283 -0.000491740343466312 -0.000107797256916487 0.999999977931089 0.000180326293935061 0.000835230319148649 0.00228038114900917 -0.000180080007291319 0.999997383713081 0.00358102653444227 3.27146400067099e-05 -2.97387235127074e-05 -4.14061186709533e-06 -1.1757608032228e-06 3.84738401317028e-07 2.610503850619e-06 -2.97387235127074e-05 4.66128801426178e-05 4.71040808903111e-06 8.89237140112117e-06 3.32581107981082e-06 -1.58579130491561e-07 -4.14061186709533e-06 4.71040808903111e-06 1.40049172218842e-05 -5.09202869021119e-06 1.9933616985528e-06 -5.63771651753731e-07 -1.1757608032228e-06 8.89237140112117e-06 -5.09202869021119e-06 3.09483502436508e-05 4.8128498351598e-06 2.76026822032427e-06 3.84738401317028e-07 3.32581107981082e-06 1.9933616985528e-06 4.8128498351598e-06 2.21980081635856e-05 1.43736696260724e-08 2.610503850619e-06 -1.58579130491561e-07 -5.63771651753731e-07 2.76026822032427e-06 1.43736696260724e-08 2.90942059735142e-05 1035 1040 0 14 0 1042 1063 0 37 0 0 0 0 0 0 12 36 0 3016 0 0 0 0 0 1221 +904 906 0.999999274305011 -0.000371917587297619 -0.00114589125149695 -0.00077941614521132 0.000373056623722279 0.99999943643144 0.000993964565930048 -0.000186411568167259 0.00114552093280545 -0.00099439132693638 0.999998849483179 0.0031530024543717 2.58815747576167e-05 -1.86627241232402e-05 -2.72649019818343e-06 -1.61782307012725e-06 -3.83427066781188e-06 6.20848874225641e-06 -1.86627241232402e-05 2.4463300176475e-05 4.06447795881314e-06 1.70018165108095e-06 2.18610586099105e-06 -5.11910633468554e-06 -2.72649019818343e-06 4.06447795881314e-06 1.44419735434248e-05 -6.77189179283395e-06 2.68786638306052e-06 -2.49371552559078e-06 -1.61782307012725e-06 1.70018165108095e-06 -6.77189179283395e-06 3.2433295303112e-05 6.33034776190089e-06 1.84076205953564e-06 -3.83427066781188e-06 2.18610586099105e-06 2.68786638306052e-06 6.33034776190089e-06 2.24999311356088e-05 -1.66678969449566e-06 6.20848874225641e-06 -5.11910633468554e-06 -2.49371552559078e-06 1.84076205953564e-06 -1.66678969449566e-06 3.19540011431943e-05 1112 1114 0 20 0 1112 1138 0 45 0 0 0 0 0 0 15 40 0 3042 0 0 0 0 0 1230 +904 907 0.999999990830029 -0.000134935133051665 1.15087785431649e-05 -0.000323732487299025 0.000134925884996412 0.999999671044655 0.000799815971027815 -3.49620694134328e-05 -1.16166980317582e-05 -0.000799814410861396 0.999999680080929 0.00231881239714646 2.13969371774192e-05 -1.79121327298443e-05 -3.86449305436001e-06 1.28240410783785e-06 1.29496227826182e-07 7.09128462993146e-06 -1.79121327298443e-05 2.34606367852392e-05 5.22625156596962e-06 3.34523093857076e-07 1.07363550565274e-06 -6.82894948359714e-06 -3.86449305436001e-06 5.22625156596962e-06 1.2009672569021e-05 -6.12492343971351e-06 2.74405856804261e-06 -2.90731493067497e-06 1.28240410783785e-06 3.34523093857076e-07 -6.12492343971351e-06 2.69197201901838e-05 3.49954981507264e-06 9.94224930061558e-07 1.29496227826182e-07 1.07363550565274e-06 2.74405856804261e-06 3.49954981507264e-06 1.97131235703284e-05 -2.31374066659832e-06 7.09128462993146e-06 -6.82894948359714e-06 -2.90731493067497e-06 9.94224930061558e-07 -2.31374066659832e-06 2.56820175312299e-05 1115 1122 0 22 0 1119 1141 0 41 0 0 0 0 0 0 13 36 0 3020 0 0 0 0 0 1230 +902 928 0.999996073287548 -0.000294751995659866 -0.00278684960954401 -0.00208581251787055 0.00029313885315627 0.999999789280139 -0.000579231638461295 -0.00445000704075971 0.00278701975198083 0.000578412430086747 0.999995948971776 0.000488664876439896 2.74366271178104e-05 -2.64337474612812e-05 -6.30928857044721e-06 3.59906177087603e-06 2.37783114113438e-07 1.51523741718047e-05 -2.64337474612812e-05 4.55491634062779e-05 7.39824250609662e-06 5.54476776812764e-06 1.68772104434149e-06 -1.41555499478366e-05 -6.30928857044721e-06 7.39824250609662e-06 1.25306802415115e-05 -6.10651127717946e-06 4.79479546404242e-07 -1.81360754653401e-06 3.59906177087603e-06 5.54476776812764e-06 -6.10651127717946e-06 4.28752672964537e-05 7.74295796842991e-06 5.46947209917066e-06 2.37783114113438e-07 1.68772104434149e-06 4.79479546404242e-07 7.74295796842991e-06 2.33303620714241e-05 -2.71738258158169e-06 1.51523741718047e-05 -1.41555499478366e-05 -1.81360754653401e-06 5.46947209917066e-06 -2.71738258158169e-06 2.65250337089609e-05 1095 1095 0 20 0 1094 1111 0 37 0 0 0 0 0 0 16 37 0 2885 0 0 0 0 0 2393 +904 908 0.99999993938713 -0.000140520393642858 0.000318558872942234 0.000670174521173396 0.00014078246400095 0.999999651588766 -0.000822801704833761 -0.000567841172031707 -0.00031844314153329 0.00082284650246445 0.999999610758724 -0.00358784363544672 2.83203432277355e-05 -2.48436012735622e-05 -2.10227263057091e-06 -2.80983774055027e-06 -4.29874461017169e-06 9.26070854668694e-06 -2.48436012735622e-05 4.61908305437984e-05 4.1474423876799e-06 1.24620148063789e-05 6.5067283494981e-06 -6.58068883516569e-06 -2.10227263057091e-06 4.1474423876799e-06 1.11284650618139e-05 -4.96948772923241e-06 4.62416197419639e-06 -1.10323398323516e-06 -2.80983774055027e-06 1.24620148063789e-05 -4.96948772923241e-06 4.18640171553514e-05 8.231636337826e-06 1.27444994253673e-06 -4.29874461017169e-06 6.5067283494981e-06 4.62416197419639e-06 8.231636337826e-06 2.06611958542713e-05 -4.96060447917259e-06 9.26070854668694e-06 -6.58068883516569e-06 -1.10323398323516e-06 1.27444994253673e-06 -4.96060447917259e-06 2.96509747158138e-05 1060 1053 0 14 0 1059 1077 0 41 0 0 0 0 0 0 16 40 0 2946 0 0 0 0 0 2143 +903 906 0.999999436227749 0.00010638409017124 -0.00105651626072868 -0.000501176290152127 -0.00010657632940043 0.999999977776731 -0.00018190113655434 0.000582512052597926 0.00105649688586252 0.000182013633628547 0.999999425342519 0.0027360770561455 6.04593815498027e-05 -6.69219996773285e-05 -5.02827627519659e-06 -1.41457621795541e-05 -1.09096538049767e-05 1.7409009873215e-05 -6.69219996773285e-05 0.000107365228131577 5.08878514506076e-06 3.84347537511727e-05 2.16438922558196e-05 -1.92073694533005e-05 -5.02827627519659e-06 5.08878514506076e-06 1.25311562584927e-05 -6.93926369445815e-06 2.84803665860892e-06 -3.43488215368412e-06 -1.41457621795541e-05 3.84347537511727e-05 -6.93926369445815e-06 6.28385387453827e-05 1.96372047618745e-05 1.77098891468117e-06 -1.09096538049767e-05 2.16438922558196e-05 2.84803665860892e-06 1.96372047618745e-05 2.90005012267099e-05 -3.36558091780433e-06 1.7409009873215e-05 -1.92073694533005e-05 -3.43488215368412e-06 1.77098891468117e-06 -3.36558091780433e-06 4.06318553180637e-05 1099 1107 0 23 0 1098 1120 0 42 0 0 0 0 0 0 13 37 0 3029 0 0 0 0 0 1224 +903 929 0.999781120002141 -0.0208817814637937 0.00128968607156205 -0.00165601694288158 0.0208520320638387 0.999584826391794 0.0198838528986429 0.00353233777203814 -0.00170436089882995 -0.0198526081456465 0.999801464843767 -0.00989051681254014 4.00268325293896e-05 -3.50585648383079e-05 -7.9155514066365e-06 -4.80856311233424e-06 -5.39687014450451e-06 1.85079827486079e-05 -3.50585648383079e-05 4.80196461505155e-05 7.2041219600284e-06 1.55611241816785e-05 8.3493221541183e-06 -1.67806490619051e-05 -7.9155514066365e-06 7.2041219600284e-06 1.15297691765489e-05 -1.91907645573436e-06 -7.70689590429015e-07 -4.56387142295742e-06 -4.80856311233424e-06 1.55611241816785e-05 -1.91907645573436e-06 5.19345762382016e-05 7.87915645963768e-06 5.34746587591161e-06 -5.39687014450451e-06 8.3493221541183e-06 -7.70689590429015e-07 7.87915645963768e-06 2.57236257108725e-05 -5.66289087741995e-06 1.85079827486079e-05 -1.67806490619051e-05 -4.56387142295742e-06 5.34746587591161e-06 -5.66289087741995e-06 3.04773378300735e-05 1029 1029 0 0 0 1045 1046 0 14 0 0 0 0 0 0 48 72 0 3046 0 0 0 0 0 2033 +905 908 0.999999809953941 -7.23906245589802e-05 0.000612251319942148 0.00164421827040919 7.1534642921773e-05 0.999999020245855 0.00139799503764333 0.00178845962412808 -0.000612351921820285 -0.00139795097478034 0.99999883537842 -0.00204288706029093 3.30417870102221e-05 -3.04332385407197e-05 -1.38892577621623e-06 -5.95357870694312e-06 -7.10565035827509e-06 6.07831141739867e-06 -3.04332385407197e-05 4.93327430918769e-05 1.85937734211682e-06 1.79356918659719e-05 1.07557497376127e-05 -1.51606052078772e-06 -1.38892577621623e-06 1.85937734211682e-06 1.18285519458984e-05 -6.86116207769883e-06 2.74642228206696e-06 -1.44252145808736e-06 -5.95357870694312e-06 1.79356918659719e-05 -6.86116207769883e-06 5.54838146411748e-05 1.66519826904257e-05 6.6792042509986e-06 -7.10565035827509e-06 1.07557497376127e-05 2.74642228206696e-06 1.66519826904257e-05 2.41044110422091e-05 -8.56775245655477e-07 6.07831141739867e-06 -1.51606052078772e-06 -1.44252145808736e-06 6.6792042509986e-06 -8.56775245655477e-07 2.98898226526159e-05 1103 1103 0 18 0 1108 1125 0 42 0 0 0 0 0 0 12 35 0 2940 0 0 0 0 0 2144 +906 908 0.999999346157499 -0.000466894591597503 -0.00104388410021582 0.000308776876904055 0.000466297786139957 0.999999727756061 -0.000571886508771497 -0.00136120984474076 0.00104415082674266 0.000571399374002874 0.999999291625652 0.0027468118910131 2.75231510327942e-05 -2.2519915871623e-05 -8.91420314342976e-07 -3.55253683846349e-06 -3.89137317443706e-06 9.94296972189117e-06 -2.2519915871623e-05 3.5165585924915e-05 2.43384590404628e-06 8.00148477756325e-06 3.0819639247087e-06 -5.94605333182332e-06 -8.91420314342976e-07 2.43384590404628e-06 1.20400357832151e-05 -5.33029369953816e-06 2.99128671040186e-06 -1.8594046228393e-06 -3.55253683846349e-06 8.00148477756325e-06 -5.33029369953816e-06 4.08413657484741e-05 9.15638805756051e-06 2.01263840639995e-06 -3.89137317443706e-06 3.0819639247087e-06 2.99128671040186e-06 9.15638805756051e-06 2.21915433851943e-05 -2.64766118790328e-06 9.94296972189117e-06 -5.94605333182332e-06 -1.8594046228393e-06 2.01263840639995e-06 -2.64766118790328e-06 3.11478780699462e-05 1065 1061 0 5 0 1076 1096 0 40 0 0 0 0 0 0 19 44 0 2949 0 0 0 0 0 2135 +905 870 0.997421436050176 0.00309125381523003 -0.0717002305258164 0.012036669312165 -0.0122866456607485 0.991676785017819 -0.1281647080718 0.0145131179405147 0.0707072644500733 0.128715182502191 0.989157664150369 -0.019490233401283 6.87672127738765e-05 -8.24724658158009e-05 1.05503945662809e-05 -1.84242863114925e-05 -1.61535005515541e-05 2.35042987602543e-05 -8.24724658158009e-05 0.000170488417842313 -1.77415106804652e-05 6.77748956896196e-05 3.66267829006378e-05 -3.33547129330353e-05 1.05503945662809e-05 -1.77415106804652e-05 1.17138125650002e-05 -7.99602708093205e-06 -1.4528502578188e-06 3.41972614104389e-06 -1.84242863114925e-05 6.77748956896196e-05 -7.99602708093205e-06 7.35371915628332e-05 1.95316577125782e-05 -6.3322842525527e-06 -1.61535005515541e-05 3.66267829006378e-05 -1.4528502578188e-06 1.95316577125782e-05 3.19090893836072e-05 -3.67873434564593e-06 2.35042987602543e-05 -3.33547129330353e-05 3.41972614104389e-06 -6.3322842525527e-06 -3.67873434564593e-06 3.91520474368396e-05 871 872 0 12 0 871 883 0 25 0 0 0 0 0 0 5 21 0 2274 0 0 0 0 0 1594 +905 907 0.999999394324584 -0.000605098546227035 0.000919350974919497 -0.000942478165402499 0.000605072267984976 0.99999981652727 2.88613392468695e-05 -0.000821902391157388 -0.000919368270198084 -2.83050479867971e-05 0.999999576980314 0.00137005205218107 3.12110724081204e-05 -3.04386065603811e-05 -4.85222854215658e-06 -1.41989933608698e-06 -3.3396001858505e-06 1.42456034415424e-05 -3.04386065603811e-05 4.36380091249679e-05 4.6640993665704e-06 1.02125248960691e-05 7.22369054789382e-06 -1.69288474424181e-05 -4.85222854215658e-06 4.6640993665704e-06 1.10817831495086e-05 -6.16166395025703e-06 3.2662670321864e-06 -3.20144994154576e-06 -1.41989933608698e-06 1.02125248960691e-05 -6.16166395025703e-06 4.48850860309839e-05 1.10982134747629e-05 -2.2914764553285e-09 -3.3396001858505e-06 7.22369054789382e-06 3.2662670321864e-06 1.10982134747629e-05 2.04069288598977e-05 -5.26752537045257e-06 1.42456034415424e-05 -1.69288474424181e-05 -3.20144994154576e-06 -2.2914764553285e-09 -5.26752537045257e-06 3.77277164001577e-05 1104 1111 0 26 0 1104 1120 0 35 0 0 0 0 0 0 14 38 0 3025 0 0 0 0 0 2332 +906 870 0.997718449742358 0.00385584493351578 -0.0674019844185153 0.0153015174950469 -0.0125207610271276 0.991615998275503 -0.128611595540133 0.0130124293647687 0.0663409796958612 0.129162085860852 0.989401854652126 -0.0187703199182801 5.31049538068684e-05 -6.36403199470466e-05 9.46107134293798e-06 -1.93732612458172e-05 -1.25250780249542e-05 3.12380918363084e-06 -6.36403199470466e-05 0.000110581289572361 -1.34208305956395e-05 4.41397621262645e-05 2.32756170252976e-05 6.21057287985464e-06 9.46107134293798e-06 -1.34208305956395e-05 1.13651228734252e-05 -4.78087535861041e-06 -2.20703096338734e-06 -4.05414677630937e-07 -1.93732612458172e-05 4.41397621262645e-05 -4.78087535861041e-06 6.23014428531242e-05 1.64186233278872e-05 1.38555206122511e-05 -1.25250780249542e-05 2.32756170252976e-05 -2.20703096338734e-06 1.64186233278872e-05 3.45064925652482e-05 9.13407168412213e-06 3.12380918363084e-06 6.21057287985464e-06 -4.05414677630937e-07 1.38555206122511e-05 9.13407168412213e-06 3.37619054214039e-05 886 886 0 12 0 885 896 0 22 0 0 0 0 0 0 4 19 0 2270 0 0 0 0 0 1569 +906 872 0.995551931918115 -0.0114812224813233 -0.0935122044678861 0.00597205883018695 -0.000990481556193796 0.991216660188068 -0.132244287256198 0.0162318677911323 0.0942091810833542 0.131748677776846 0.986796289060542 -0.0110741785938364 8.62890884449004e-05 -0.000131045446232921 1.05857042359815e-05 -1.71538225403928e-05 -1.30907542445492e-05 6.21685327812118e-06 -0.000131045446232921 0.000307757270845678 -2.41876029304932e-05 9.40095553681975e-05 4.21092623666479e-05 4.44976239713867e-06 1.05857042359815e-05 -2.41876029304932e-05 1.28496656677891e-05 -8.51577617681521e-06 -4.9343430635829e-06 -2.098208752001e-06 -1.71538225403928e-05 9.40095553681975e-05 -8.51577617681521e-06 0.00010183914350742 2.10959771163427e-05 7.80526654530757e-06 -1.30907542445492e-05 4.21092623666479e-05 -4.9343430635829e-06 2.10959771163427e-05 3.52088535439612e-05 8.109686298458e-06 6.21685327812118e-06 4.44976239713867e-06 -2.098208752001e-06 7.80526654530757e-06 8.109686298458e-06 5.05083010823036e-05 780 776 0 6 0 783 787 0 16 0 0 0 0 0 0 15 27 0 2232 0 0 0 0 0 1680 +904 870 0.997046072244179 0.00246186508349454 -0.0767663275321062 0.00611866832998019 -0.0124116798249524 0.991513979382519 -0.129406255231213 0.0102721799272788 0.0757963061526009 0.129976797580774 0.988615674599724 -0.0226535454887145 4.75021246333307e-05 -4.8772127066124e-05 8.02896373508646e-06 -1.60339728948524e-05 -9.6108305735938e-06 1.00837148879079e-05 -4.8772127066124e-05 7.64598577175443e-05 -9.20968477057503e-06 3.57326386576605e-05 1.81193595849693e-05 -2.97887220914797e-06 8.02896373508646e-06 -9.20968477057503e-06 1.10870824945593e-05 -3.78847221234939e-06 -2.08181308431759e-07 1.8528226042684e-06 -1.60339728948524e-05 3.57326386576605e-05 -3.78847221234939e-06 6.5218568614114e-05 1.84847971530617e-05 8.49659086653436e-06 -9.6108305735938e-06 1.81193595849693e-05 -2.08181308431759e-07 1.84847971530617e-05 2.95609787092663e-05 1.73366758173948e-06 1.00837148879079e-05 -2.97887220914797e-06 1.8528226042684e-06 8.49659086653436e-06 1.73366758173948e-06 3.86446508371865e-05 876 875 0 9 0 877 890 0 27 0 0 0 0 0 0 5 21 0 2278 0 0 0 0 0 1683 +904 871 0.997042173164329 0.00143580137577349 -0.0768429788995863 0.0173515504566153 -0.0106057205358475 0.992830543855179 -0.119058934482652 0.0149771684226721 0.0761211115504 0.119521753930564 0.989909150737427 -0.0160389679817445 7.42339079992599e-05 -8.4637732539269e-05 7.49040484122306e-06 -2.94984052756423e-05 -1.48750749897746e-05 2.27519984189758e-05 -8.4637732539269e-05 0.00013515296933294 -8.20893946686961e-06 5.03119011791576e-05 2.35486758107894e-05 -1.78357522250523e-05 7.49040484122306e-06 -8.20893946686961e-06 1.35355672590306e-05 -5.8358763802444e-06 -2.39557028947691e-06 1.20904922911035e-06 -2.94984052756423e-05 5.03119011791576e-05 -5.8358763802444e-06 8.22136659183966e-05 3.06624500295214e-05 3.94031667202261e-06 -1.48750749897746e-05 2.35486758107894e-05 -2.39557028947691e-06 3.06624500295214e-05 4.23428562691697e-05 4.01458335960871e-06 2.27519984189758e-05 -1.78357522250523e-05 1.20904922911035e-06 3.94031667202261e-06 4.01458335960871e-06 4.46921009404476e-05 808 806 0 13 0 809 820 0 29 0 0 0 0 0 0 6 22 0 2333 0 0 0 0 0 1355 +906 909 0.999998703941107 3.17927883308435e-05 0.00160969106491586 0.00167743369219719 -3.07641856623931e-05 0.999999795349015 -0.000639026988868252 -0.000688115455669998 -0.0016097110519408 0.00063897663981686 0.999998500268467 -0.00203297673316692 2.59707127190064e-05 -2.07046238435128e-05 -8.26192471376084e-07 -2.28415344073643e-06 -2.99776711335405e-06 1.02853837530712e-05 -2.07046238435128e-05 3.04237788502063e-05 1.97517655351961e-06 6.44892621473795e-06 3.50352928842632e-06 -8.23077304442452e-06 -8.26192471376084e-07 1.97517655351961e-06 9.8255641382731e-06 -4.32598525418545e-06 4.26226309835961e-06 -3.34779406355997e-07 -2.28415344073643e-06 6.44892621473795e-06 -4.32598525418545e-06 3.69178175188079e-05 7.32686293994329e-06 -6.54928529374428e-10 -2.99776711335405e-06 3.50352928842632e-06 4.26226309835961e-06 7.32686293994329e-06 2.02389385150826e-05 -3.54201649045473e-06 1.02853837530712e-05 -8.23077304442452e-06 -3.34779406355997e-07 -6.54928529374428e-10 -3.54201649045473e-06 2.79809335733199e-05 1120 1126 0 25 0 1123 1143 0 40 0 0 0 0 0 0 18 42 0 2907 0 0 0 0 0 2319 +907 909 0.99999983099678 -0.000150073402510561 -0.000561679966108952 -0.00066180365842957 0.000150112592516346 0.999999986301875 6.97313316503908e-05 7.42353051486201e-05 0.000561669493596787 -6.98156351014484e-05 0.999999839826566 -0.00104894471512483 2.38813758318119e-05 -2.25200091750193e-05 -2.81739798472986e-06 -1.73230781052879e-06 -2.36614680647496e-06 7.81938043564934e-06 -2.25200091750193e-05 2.93405115497883e-05 3.76820460031744e-06 3.90046819392661e-06 3.06510287539954e-06 -7.84601543744436e-06 -2.81739798472986e-06 3.76820460031744e-06 1.10664133967823e-05 -6.46572437108053e-06 2.27015143725475e-06 -2.63184942905112e-06 -1.73230781052879e-06 3.90046819392661e-06 -6.46572437108053e-06 3.73208618028328e-05 8.11231573106287e-06 1.22605701476526e-06 -2.36614680647496e-06 3.06510287539954e-06 2.27015143725475e-06 8.11231573106287e-06 2.00505218629019e-05 -2.5974735865356e-06 7.81938043564934e-06 -7.84601543744436e-06 -2.63184942905112e-06 1.22605701476526e-06 -2.5974735865356e-06 2.20647049323899e-05 1110 1106 0 11 0 1111 1131 0 40 0 0 0 0 0 0 14 38 0 2917 0 0 0 0 0 2334 +907 872 0.996495967663185 -0.0104827396586511 -0.0829813147658031 0.00953389122631484 -0.000235460128977686 0.991759538582042 -0.128113083602192 0.0194498073269789 0.0836404865453328 0.127683710005559 0.988281912821274 -0.00942589558984917 7.3792108889697e-05 -9.27440879012892e-05 9.21272869268098e-06 -1.02210608471783e-05 -8.88110066320325e-06 1.68119513089585e-06 -9.27440879012892e-05 0.000166566330567896 -1.57967321341949e-05 4.29949705445231e-05 2.32091373656598e-05 1.66031448447176e-05 9.21272869268098e-06 -1.57967321341949e-05 1.3686992050719e-05 -6.31491838689855e-06 -2.24174920085447e-06 -3.40925223333863e-06 -1.02210608471783e-05 4.29949705445231e-05 -6.31491838689855e-06 8.70757792090441e-05 2.13821343671004e-05 9.2609558063753e-06 -8.88110066320325e-06 2.32091373656598e-05 -2.24174920085447e-06 2.13821343671004e-05 3.0028146732921e-05 3.97634522667423e-06 1.68119513089585e-06 1.66031448447176e-05 -3.40925223333863e-06 9.2609558063753e-06 3.97634522667423e-06 5.39618025842374e-05 778 775 0 3 0 785 790 0 15 0 0 0 0 0 0 16 27 0 2238 0 0 0 0 0 1521 +907 871 0.997415990581004 0.00194677841284464 -0.0718160969917358 0.0211425101881374 -0.0105357423019659 0.992788761604602 -0.119413035158424 0.0164908012171856 0.0710657432766428 0.119861106641862 0.990243896849219 -0.0127552562573739 6.96022203116048e-05 -8.34329076330795e-05 8.70914465545118e-06 -1.73339373581779e-05 -7.93295210828688e-06 2.52358085879621e-05 -8.34329076330795e-05 0.000164644032427819 -1.42275008690577e-05 5.45714411008423e-05 1.98281238000517e-05 -1.37165633428904e-05 8.70914465545118e-06 -1.42275008690577e-05 1.21402806898072e-05 -7.138229658303e-06 -7.47528178366328e-07 2.95119660848878e-06 -1.73339373581779e-05 5.45714411008423e-05 -7.138229658303e-06 8.58284771714942e-05 2.47240764729567e-05 -1.71237835357967e-06 -7.93295210828688e-06 1.98281238000517e-05 -7.47528178366328e-07 2.47240764729567e-05 3.33549720997628e-05 2.41584002941316e-06 2.52358085879621e-05 -1.37165633428904e-05 2.95119660848878e-06 -1.71237835357967e-06 2.41584002941316e-06 3.8796574570844e-05 804 808 0 18 0 804 814 0 26 0 0 0 0 0 0 5 19 0 2339 0 0 0 0 0 2122 +906 910 0.999999978821599 0.000205546273552464 1.03697121674775e-05 0.00173295796070533 -0.000205547167279796 0.999999975154873 8.62589993657396e-05 -0.000991697637119277 -1.03519816939607e-05 -8.62611290038735e-05 0.999999996225927 0.000501157132414793 2.79696159635155e-05 -2.47759811197462e-05 -2.23846940297301e-06 -2.90325958399472e-06 -3.89060798281097e-06 9.83425989738244e-06 -2.47759811197462e-05 3.85233668831939e-05 3.18892516090151e-06 8.22037123102976e-06 3.37479733050625e-06 -7.94631550821958e-06 -2.23846940297301e-06 3.18892516090151e-06 1.19722947974529e-05 -6.03210089433299e-06 2.25010410633782e-06 -2.83659713757467e-06 -2.90325958399472e-06 8.22037123102976e-06 -6.03210089433299e-06 4.32431882017197e-05 1.09248275911693e-05 3.27269046423943e-06 -3.89060798281097e-06 3.37479733050625e-06 2.25010410633782e-06 1.09248275911693e-05 2.35288312139157e-05 -2.85555745255504e-06 9.83425989738244e-06 -7.94631550821958e-06 -2.83659713757467e-06 3.27269046423943e-06 -2.85555745255504e-06 2.66217054172756e-05 1150 1155 0 19 0 1152 1176 0 42 0 0 0 0 0 0 17 42 0 2948 0 0 0 0 0 2318 +905 909 0.99999967345594 -0.000441083659653072 0.000677150809747062 -0.00112871118524243 0.000440978484361847 0.999999890684799 0.000155461784089339 -0.000486015439633802 -0.000677219307376847 -0.00015516312438645 0.999999758649178 6.90118577391098e-05 3.76520318973242e-05 -3.44435293631056e-05 -2.8387633211157e-06 -7.39442142377076e-06 -7.98241309949388e-06 1.71380203223201e-05 -3.44435293631056e-05 4.45588456501256e-05 3.54826042125594e-06 1.43104551917275e-05 1.04362709128478e-05 -1.68606990726553e-05 -2.8387633211157e-06 3.54826042125594e-06 1.10444348320721e-05 -3.98041647957121e-06 4.57645845615803e-06 -1.76242047474214e-06 -7.39442142377076e-06 1.43104551917275e-05 -3.98041647957121e-06 4.17358847700193e-05 1.15952829117504e-05 -2.017101593276e-06 -7.98241309949388e-06 1.04362709128478e-05 4.57645845615803e-06 1.15952829117504e-05 2.15020074244782e-05 -6.03027608792315e-06 1.71380203223201e-05 -1.68606990726553e-05 -1.76242047474214e-06 -2.017101593276e-06 -6.03027608792315e-06 3.93478871037257e-05 1095 1099 0 24 0 1096 1117 0 42 0 0 0 0 0 0 15 40 0 2903 0 0 0 0 0 2336 +908 912 0.999999998078121 3.13550817001463e-05 5.34847440098601e-05 -0.000937108299661655 -3.13097140354304e-05 0.999999639936031 -0.000848025654678114 -0.000696911362861564 -5.35113146656171e-05 0.00084802397845627 0.999999638995871 -0.00119130794712443 3.32613649801774e-05 -2.64424514115781e-05 -3.34665800382619e-06 -1.4174514277217e-07 -3.52771931134639e-06 6.97249040784921e-06 -2.64424514115781e-05 3.76779989569431e-05 3.49913876843236e-06 3.93101141475306e-06 3.51768896826785e-06 -4.48799779553995e-06 -3.34665800382619e-06 3.49913876843236e-06 1.2506207988827e-05 -7.10077220545786e-06 2.31730394423312e-06 -5.88559734335718e-06 -1.4174514277217e-07 3.93101141475306e-06 -7.10077220545786e-06 3.46477152063559e-05 6.90865920585438e-06 1.11891776995874e-05 -3.52771931134639e-06 3.51768896826785e-06 2.31730394423312e-06 6.90865920585438e-06 2.31553327893876e-05 -6.53203439463257e-07 6.97249040784921e-06 -4.48799779553995e-06 -5.88559734335718e-06 1.11891776995874e-05 -6.53203439463257e-07 3.64186737010351e-05 1133 1137 0 20 0 1131 1149 0 33 0 0 0 0 0 0 13 37 0 2903 0 0 0 0 0 1275 +907 870 0.997067942967064 0.00269488293920825 -0.0764738825571912 0.0108143312411676 -0.0126198281920944 0.991486265842304 -0.129598320137594 0.0141057703349064 0.0754735519492035 0.130183417730632 0.988613180523172 -0.0199153730698042 4.78360838963966e-05 -5.05860678843597e-05 7.41876369045567e-06 -9.2321407623881e-06 -5.42008494353013e-06 1.35116421600372e-05 -5.05860678843597e-05 8.7446087841618e-05 -1.09640463007245e-05 3.66585596749618e-05 1.58439550731734e-05 -1.08454285269737e-05 7.41876369045567e-06 -1.09640463007245e-05 1.16346372266484e-05 -4.6037984982652e-06 -1.10710138347561e-06 3.77516319007649e-06 -9.2321407623881e-06 3.66585596749618e-05 -4.6037984982652e-06 6.02751645981088e-05 1.17133255253279e-05 8.50648470524039e-07 -5.42008494353013e-06 1.58439550731734e-05 -1.10710138347561e-06 1.17133255253279e-05 2.76624835004063e-05 5.58651911299241e-07 1.35116421600372e-05 -1.08454285269737e-05 3.77516319007649e-06 8.50648470524039e-07 5.58651911299241e-07 4.61155855728432e-05 864 868 0 15 0 864 874 0 24 0 0 0 0 0 0 6 17 0 2271 0 0 0 0 0 1613 +907 911 0.999997325330689 4.68649235983168e-05 0.0023123873261835 0.000895003395368072 -5.04480316369105e-05 0.999998798261525 0.0015494936274742 0.00147469016318767 -0.00231231193039821 -0.00154960613848014 0.999996125959672 -0.00327318317636395 3.75158062034576e-05 -3.54136054148829e-05 -4.33170212973758e-06 -1.50999587923983e-06 -5.32809783577809e-06 9.17005192719566e-06 -3.54136054148829e-05 4.76466336801817e-05 4.4589858252165e-06 9.49751618434638e-06 8.93251783889762e-06 -8.44982065107363e-06 -4.33170212973758e-06 4.4589858252165e-06 1.00853801046319e-05 -4.95995210188272e-06 3.08676218680919e-06 -1.12877329295531e-06 -1.50999587923983e-06 9.49751618434638e-06 -4.95995210188272e-06 4.02043043924877e-05 7.94795356025137e-06 1.14589264915246e-06 -5.32809783577809e-06 8.93251783889762e-06 3.08676218680919e-06 7.94795356025137e-06 1.91021020306905e-05 -2.7120055003642e-06 9.17005192719566e-06 -8.44982065107363e-06 -1.12877329295531e-06 1.14589264915246e-06 -2.7120055003642e-06 3.23769115570584e-05 1095 1102 0 23 0 1093 1113 0 35 0 0 0 0 0 0 13 38 0 3049 0 0 0 0 0 2320 +907 910 0.999999855572455 -0.000535122597906405 4.99887509832652e-05 -0.000829326490095527 0.000535137346024465 0.999999813158973 -0.000295482724650028 -0.00132648840809769 -4.98306221600645e-05 0.000295509432821716 0.999999955095541 0.000571480711326045 2.50618582232467e-05 -2.30667175200342e-05 -1.54401739030516e-06 -1.8616746780789e-06 -2.00124893581911e-06 1.23597008988549e-05 -2.30667175200342e-05 3.07403565794924e-05 2.82628472871828e-06 4.39336424636272e-06 3.50362215205357e-06 -1.25831372586723e-05 -1.54401739030516e-06 2.82628472871828e-06 1.11860680498718e-05 -5.87868961554301e-06 4.00504068844605e-06 -1.16792427646756e-06 -1.8616746780789e-06 4.39336424636272e-06 -5.87868961554301e-06 3.93135349850478e-05 8.48234615532764e-06 1.04511424660602e-08 -2.00124893581911e-06 3.50362215205357e-06 4.00504068844605e-06 8.48234615532764e-06 1.83160978164051e-05 -3.53302723098112e-06 1.23597008988549e-05 -1.25831372586723e-05 -1.16792427646756e-06 1.04511424660602e-08 -3.53302723098112e-06 3.10274827164892e-05 1129 1128 0 11 0 1131 1156 0 41 0 0 0 0 0 0 15 39 0 2953 0 0 0 0 0 2333 +909 870 0.997524964455957 0.00359619761535442 -0.0702211695278091 0.0153333470799366 -0.012583107418158 0.991699289058567 -0.12796165632109 0.0146810247832546 0.0691781084942706 0.128528547192618 0.989290049410035 -0.0190384226371492 5.65260140474751e-05 -6.03036293339678e-05 7.93426006686172e-06 -9.30861288117599e-06 -3.92061614463518e-06 1.74392480417301e-05 -6.03036293339678e-05 8.92377173526257e-05 -8.91768394393889e-06 2.22327011178367e-05 1.00757921367491e-05 -1.92615051181522e-05 7.93426006686172e-06 -8.91768394393889e-06 1.09423948602297e-05 -2.00837625153905e-06 1.27549502498961e-06 2.91664983827605e-06 -9.30861288117599e-06 2.22327011178367e-05 -2.00837625153905e-06 4.70090605671892e-05 6.34326253050014e-06 -1.82430624253183e-06 -3.92061614463518e-06 1.00757921367491e-05 1.27549502498961e-06 6.34326253050014e-06 2.64885267015419e-05 1.94216810296453e-06 1.74392480417301e-05 -1.92615051181522e-05 2.91664983827605e-06 -1.82430624253183e-06 1.94216810296453e-06 4.09029058690651e-05 862 864 0 13 0 862 870 0 21 0 0 0 0 0 0 3 15 0 2265 0 0 0 0 0 1533 +909 872 0.995710482191587 -0.0109938065711515 -0.0918682310207069 0.00750985836817097 -0.00111219396999651 0.991421707334309 -0.130697212100706 0.0187925637137445 0.0925170183175559 0.130238759374465 0.987156759019675 -0.0105342526400309 9.93495455247179e-05 -0.000126274932879925 1.40447438220695e-05 -2.7046137248205e-05 -1.83853167201269e-05 2.06205874264828e-05 -0.000126274932879925 0.000250239424207416 -2.50207229138619e-05 9.87204453530313e-05 4.47294363943632e-05 -4.97074406305014e-08 1.40447438220695e-05 -2.50207229138619e-05 1.35291991813456e-05 -1.13822866092399e-05 -4.99468490213694e-06 -8.59416482205401e-07 -2.7046137248205e-05 9.87204453530313e-05 -1.13822866092399e-05 0.00010163736003541 2.30494330739978e-05 1.78499304224533e-05 -1.83853167201269e-05 4.47294363943632e-05 -4.99468490213694e-06 2.30494330739978e-05 3.60830362711863e-05 5.14780029624262e-06 2.06205874264828e-05 -4.97074406305014e-08 -8.59416482205401e-07 1.78499304224533e-05 5.14780029624262e-06 5.56992379704418e-05 766 763 0 6 0 769 771 0 16 0 0 0 0 0 0 13 25 0 2225 0 0 0 0 0 1628 +909 912 0.999998845880305 0.000566500215670215 -0.00140972180367785 0.0011935489032451 -0.000569015184879024 0.999998246322853 -0.00178425697119607 0.000408520304463973 0.00140870854952194 0.0017850570650627 0.999997414552406 -0.00278585135074721 3.21872497925065e-05 -2.28697579821577e-05 -3.25962602094425e-06 -4.14255435438851e-07 -4.38970788534926e-06 3.59684139731132e-06 -2.28697579821577e-05 3.30260396098414e-05 3.96723592871186e-06 6.25247079184874e-06 4.30325116497551e-06 1.43560850227255e-06 -3.25962602094425e-06 3.96723592871186e-06 9.65380208248067e-06 -3.49663060786095e-06 4.05345939835169e-06 -2.32867007419649e-06 -4.14255435438851e-07 6.25247079184874e-06 -3.49663060786095e-06 3.58105146567588e-05 5.46093369409084e-06 7.47261604685045e-06 -4.38970788534926e-06 4.30325116497551e-06 4.05345939835169e-06 5.46093369409084e-06 1.71690660840769e-05 4.05851716471487e-07 3.59684139731132e-06 1.43560850227255e-06 -2.32867007419649e-06 7.47261604685045e-06 4.05851716471487e-07 2.7008833536021e-05 1075 1073 0 14 0 1074 1094 0 37 0 0 0 0 0 0 18 42 0 2914 0 0 0 0 0 2128 +908 910 0.999991827157617 -0.000456287211170282 0.00401714076825931 0.000658668220791763 0.00045603493529775 0.999999893986223 6.37156167072305e-05 -0.0011544874846988 -0.0040171694150081 -6.18831394392027e-05 0.999991929227615 -0.00400772703755653 3.13213302042362e-05 -3.10402703501513e-05 -2.70491656931378e-06 -4.96708407524752e-06 -2.37624002722851e-06 -1.41696369517791e-06 -3.10402703501513e-05 4.39765941290005e-05 3.91937395395555e-06 9.48209009732485e-06 4.02154230294286e-06 3.90637731560081e-06 -2.70491656931378e-06 3.91937395395555e-06 1.02823480289324e-05 -4.0530438009929e-06 3.67645622126748e-06 -5.55628621675763e-07 -4.96708407524752e-06 9.48209009732485e-06 -4.0530438009929e-06 4.07069332561202e-05 9.78240757467191e-06 6.24846577398084e-06 -2.37624002722851e-06 4.02154230294286e-06 3.67645622126748e-06 9.78240757467191e-06 1.88451095508647e-05 -2.89670746965809e-08 -1.41696369517791e-06 3.90637731560081e-06 -5.55628621675763e-07 6.24846577398084e-06 -2.89670746965809e-08 3.26816563963251e-05 1094 1098 0 20 0 1092 1116 0 40 0 0 0 0 0 0 14 38 0 2940 0 0 0 0 0 2150 +909 913 0.999996513223301 -2.58484131504484e-05 -0.00264061983245735 -0.00141024982116011 2.07029611650526e-05 0.999998101290002 -0.00194858609713974 -0.00101948386472593 0.00264066518654457 0.0019485246342053 0.999994615055062 -0.00260155008034161 4.55043331005574e-05 -4.7755257099977e-05 -3.65362772112944e-06 -4.92764487567258e-06 -3.09290924493652e-06 1.53980282868831e-05 -4.7755257099977e-05 8.79471896086071e-05 5.7146834039945e-06 2.56566128121988e-05 1.13125235427662e-05 -1.741618297456e-05 -3.65362772112944e-06 5.7146834039945e-06 1.36677136499737e-05 -6.29296897061514e-06 3.26033821183017e-06 -3.80275711789427e-06 -4.92764487567258e-06 2.56566128121988e-05 -6.29296897061514e-06 4.5146472764437e-05 1.05915921391196e-05 6.15708051121473e-06 -3.09290924493652e-06 1.13125235427662e-05 3.26033821183017e-06 1.05915921391196e-05 2.29603190250307e-05 2.89319630376276e-07 1.53980282868831e-05 -1.741618297456e-05 -3.80275711789427e-06 6.15708051121473e-06 2.89319630376276e-07 4.19846582103047e-05 1064 1067 0 26 0 1060 1080 0 41 0 0 0 0 0 0 11 35 0 2889 0 0 0 0 0 1213 +910 912 0.999995456829426 0.000198926023151948 0.00300778139898359 0.00246778792293591 -0.00019677802344923 0.999999725436473 -0.000714426614161597 0.000849303333739433 -0.00300792269120171 0.000713831503120967 0.999995221411417 -0.00405642045347729 3.1385645616583e-05 -2.94843690257699e-05 -3.62112886206167e-06 -1.59945560929561e-06 -2.24816154384153e-06 9.9182184981862e-06 -2.94843690257699e-05 4.39816927494371e-05 3.27676024826554e-06 1.00127415027368e-05 5.43185873285172e-06 -8.54733091502724e-06 -3.62112886206167e-06 3.27676024826554e-06 9.85792838153124e-06 -3.40316999105476e-06 3.88743441219028e-06 -3.41089257551653e-06 -1.59945560929561e-06 1.00127415027368e-05 -3.40316999105476e-06 3.29958820101168e-05 5.30505186352446e-06 4.87727472870164e-06 -2.24816154384153e-06 5.43185873285172e-06 3.88743441219028e-06 5.30505186352446e-06 1.70578110373358e-05 -2.83277461538335e-06 9.9182184981862e-06 -8.54733091502724e-06 -3.41089257551653e-06 4.87727472870164e-06 -2.83277461538335e-06 2.92034784237897e-05 1089 1087 0 9 0 1093 1115 0 37 0 0 0 0 0 0 13 39 0 2914 0 0 0 0 0 2133 +911 913 0.999988134614393 -0.000158578743150029 0.0048688277037568 0.00293834865592153 0.000157235615647085 0.999999949483065 0.000276244146451241 -0.000128072263762026 -0.00486887126424809 -0.000275475315586442 0.999988109032284 -0.00487038450186877 2.93497358954378e-05 -2.96255598192262e-05 -2.36393512346126e-06 -2.12175639825513e-06 -3.32872438586807e-07 4.84069781261876e-06 -2.96255598192262e-05 5.08986972208477e-05 3.46825126666469e-06 1.5014807351343e-05 5.76901307241684e-06 -2.04604144226002e-06 -2.36393512346126e-06 3.46825126666469e-06 1.2618443972899e-05 -5.06843705167004e-06 2.45507767184637e-06 -1.2472137246931e-06 -2.12175639825513e-06 1.5014807351343e-05 -5.06843705167004e-06 4.03272617347489e-05 5.00274483436674e-06 5.19190116200698e-06 -3.32872438586807e-07 5.76901307241684e-06 2.45507767184637e-06 5.00274483436674e-06 2.22535939518305e-05 -1.29679323881041e-06 4.84069781261876e-06 -2.04604144226002e-06 -1.2472137246931e-06 5.19190116200698e-06 -1.29679323881041e-06 3.16353826196468e-05 1073 1076 0 22 0 1076 1093 0 44 0 0 0 0 0 0 15 35 0 2875 0 0 0 0 0 1233 +909 911 0.999994242321844 0.000122117705746883 0.00339122550514182 0.00233235328309696 -0.000123053641643545 0.999999954401531 0.000275780233534989 0.00111719226504015 -0.00339119167285772 -0.000276195948329205 0.999994211750666 -0.00217965183801513 3.33443852900834e-05 -3.16106631813147e-05 -3.98208188340237e-06 -4.45895072392544e-06 -5.53514417597116e-06 1.10003710592217e-05 -3.16106631813147e-05 4.92432178518345e-05 4.91705700506502e-06 1.25465150499336e-05 8.16778882548538e-06 -9.57807120304753e-06 -3.98208188340237e-06 4.91705700506502e-06 9.89874770398027e-06 -3.96634524628079e-06 3.9513178734247e-06 -1.61940990761074e-06 -4.45895072392544e-06 1.25465150499336e-05 -3.96634524628079e-06 3.97866145847748e-05 6.9654957406886e-06 2.86715048448032e-07 -5.53514417597116e-06 8.16778882548538e-06 3.9513178734247e-06 6.9654957406886e-06 2.01655916880556e-05 -3.46001926908596e-06 1.10003710592217e-05 -9.57807120304753e-06 -1.61940990761074e-06 2.86715048448032e-07 -3.46001926908596e-06 2.9320791151254e-05 1085 1091 0 22 0 1084 1106 0 37 0 0 0 0 0 0 19 44 0 3055 0 0 0 0 0 2328 +911 915 0.999999578362357 -0.000469159338000233 -0.000789407767196951 -0.00305940015338179 0.000468246783154184 0.999999222450017 -0.0011557873124604 -0.00350343087835866 0.000789949401803338 0.00115541718748937 0.999999020495053 -0.00198969720259464 2.47089331819129e-05 -1.88359071155077e-05 -1.21061334875764e-06 -4.01218556513248e-07 -2.21466409366523e-06 8.19997059437048e-06 -1.88359071155077e-05 2.29776974291334e-05 3.22777895091264e-06 1.90349968241927e-07 3.60670979612016e-07 -6.42462357409627e-06 -1.21061334875764e-06 3.22777895091264e-06 1.34822842020893e-05 -7.27376423708008e-06 1.57018456499826e-06 -2.11111539617356e-06 -4.01218556513248e-07 1.90349968241927e-07 -7.27376423708008e-06 3.10338467405999e-05 2.3616823664995e-06 4.46136647907625e-06 -2.21466409366523e-06 3.60670979612016e-07 1.57018456499826e-06 2.3616823664995e-06 2.33943948142316e-05 4.32953518917292e-07 8.19997059437048e-06 -6.42462357409627e-06 -2.11111539617356e-06 4.46136647907625e-06 4.32953518917292e-07 2.81779621915662e-05 1146 1141 0 10 0 1151 1175 0 43 0 0 0 0 0 0 17 44 0 2990 0 0 0 0 0 1221 +908 911 0.999994315805954 -2.16967967288114e-05 -0.00337162943277062 -0.00293122089806543 1.2963035889131e-05 0.999996644906596 -0.00259036821912404 -0.00169470922508356 0.00337167432333165 0.00259030978841509 0.999990961012877 -0.000764837441075563 3.36873533298899e-05 -3.13150080890355e-05 -5.45611670078253e-06 -3.25749849088478e-06 -5.64771868424225e-06 3.46105095676037e-06 -3.13150080890355e-05 5.03620470178827e-05 6.34364024570255e-06 1.06769994184612e-05 8.06004239762952e-06 4.01835786150791e-06 -5.45611670078253e-06 6.34364024570255e-06 1.07460339255965e-05 -3.61600004054798e-06 3.32740627668563e-06 -3.08426750775528e-06 -3.25749849088478e-06 1.06769994184612e-05 -3.61600004054798e-06 3.88733281754623e-05 8.10061695165222e-06 1.15881243375734e-05 -5.64771868424225e-06 8.06004239762952e-06 3.32740627668563e-06 8.10061695165222e-06 2.13854450564145e-05 -5.79898590746543e-07 3.46105095676037e-06 4.01835786150791e-06 -3.08426750775528e-06 1.15881243375734e-05 -5.79898590746543e-07 3.76157166836468e-05 1090 1092 0 19 0 1085 1105 0 35 0 0 0 0 0 0 17 44 0 3039 0 0 0 0 0 2149 +911 914 0.999997311163427 -0.000158042409783518 0.00231358780110731 0.000957041142808581 0.000156863003533446 0.999999857674375 0.000509946298559859 0.000843951970357828 -0.00231366806496637 -0.000509582011066181 0.999997193629192 -0.00254104180725647 3.15709798149134e-05 -3.1764542350326e-05 -4.30943483277384e-06 -3.83114471108605e-06 -4.20351185360281e-06 1.14772949034931e-05 -3.1764542350326e-05 5.62308174368811e-05 5.11355362640496e-06 1.6637870127648e-05 9.59887584635412e-06 -1.15424640239466e-05 -4.30943483277384e-06 5.11355362640496e-06 1.07796128311822e-05 -3.7295825664533e-06 4.14655959635033e-06 -4.40786266724932e-06 -3.83114471108605e-06 1.6637870127648e-05 -3.7295825664533e-06 4.23615994117444e-05 9.73944992773655e-06 5.77507474853606e-06 -4.20351185360281e-06 9.59887584635412e-06 4.14655959635033e-06 9.73944992773655e-06 1.91367298425735e-05 -2.7581361883022e-06 1.14772949034931e-05 -1.15424640239466e-05 -4.40786266724932e-06 5.77507474853606e-06 -2.7581361883022e-06 3.36082549270789e-05 1073 1074 0 19 0 1074 1095 0 40 0 0 0 0 0 0 14 36 0 3018 0 0 0 0 0 2323 +910 914 0.999986973310406 0.000131132823397548 -0.00510254972313253 -0.00262816270923526 -0.000139188603458695 0.999998744556592 -0.00157845233486695 -0.00026766578002386 0.00510233633025884 0.00157914198962839 0.999985736135546 0.00180437427626337 3.12559437013727e-05 -2.49348783821523e-05 -2.07170627103949e-06 -3.9823471370747e-06 -5.07551897554337e-06 1.58329738077104e-05 -2.49348783821523e-05 4.62144838273326e-05 4.05977086456113e-06 1.0727946816038e-05 4.88404613695179e-06 -1.29114589291232e-05 -2.07170627103949e-06 4.05977086456113e-06 1.13501118685519e-05 -5.69183924204696e-06 3.60111936745649e-06 -1.57125515485617e-06 -3.9823471370747e-06 1.0727946816038e-05 -5.69183924204696e-06 4.25113655461356e-05 1.165153278282e-05 -1.88711720252514e-07 -5.07551897554337e-06 4.88404613695179e-06 3.60111936745649e-06 1.165153278282e-05 2.19390692170221e-05 -4.71242689340172e-06 1.58329738077104e-05 -1.29114589291232e-05 -1.57125515485617e-06 -1.88711720252514e-07 -4.71242689340172e-06 3.01726777902374e-05 1106 1104 0 15 0 1102 1128 0 41 0 0 0 0 0 0 15 42 0 3034 0 0 0 0 0 2328 +912 914 0.999993613070143 -0.000350933318361971 0.00355677729515563 0.000676038496682602 0.000348261896229318 0.999999656852187 0.000751670912485008 2.24666173130386e-05 -0.00355703986102292 -0.000750427421610338 0.999993392141224 0.000834715703303506 4.15945390485711e-05 -3.99373942147058e-05 -2.2453219289623e-06 -7.3377860894262e-06 -6.87016852423773e-06 1.06457957057459e-05 -3.99373942147058e-05 7.19082276469399e-05 3.85495454398023e-06 2.15470461146119e-05 1.14533761829044e-05 -1.11756464072044e-05 -2.2453219289623e-06 3.85495454398023e-06 1.04011701485779e-05 -2.80932368327566e-06 2.63209359739294e-06 -5.96345298317396e-07 -7.3377860894262e-06 2.15470461146119e-05 -2.80932368327566e-06 4.15236762976395e-05 7.61603748673183e-06 4.189942120544e-06 -6.87016852423773e-06 1.14533761829044e-05 2.63209359739294e-06 7.61603748673183e-06 2.33550683241463e-05 -2.72690283167575e-07 1.06457957057459e-05 -1.11756464072044e-05 -5.96345298317396e-07 4.189942120544e-06 -2.72690283167575e-07 3.40793468670482e-05 1095 1094 0 15 0 1095 1117 0 40 0 0 0 0 0 0 14 40 0 3025 0 0 0 0 0 2141 +910 913 0.999992827849059 -0.0003366203659245 -0.00377239143936419 -0.00294596501233729 0.000327568452625435 0.999997066640478 -0.00239987694448311 -0.0013451714128796 0.00377318822103906 0.00239862401577694 0.999990004776788 -0.000934534720301253 3.9533393210427e-05 -3.70229910196969e-05 -2.80425145500891e-06 -4.8344370279541e-06 -3.73100584301112e-06 1.38640499988997e-06 -3.70229910196969e-05 6.31808293781307e-05 2.99021422070266e-06 2.22948958393141e-05 8.54339750798613e-06 6.67082566523674e-06 -2.80425145500891e-06 2.99021422070266e-06 1.13068623583522e-05 -3.8117085576547e-06 3.59085708898424e-06 -1.16987899705403e-06 -4.8344370279541e-06 2.22948958393141e-05 -3.8117085576547e-06 4.33418688440277e-05 8.76524639813108e-06 1.21415154765237e-05 -3.73100584301112e-06 8.54339750798613e-06 3.59085708898424e-06 8.76524639813108e-06 1.97910133527369e-05 4.10397474029005e-06 1.38640499988997e-06 6.67082566523674e-06 -1.16987899705403e-06 1.21415154765237e-05 4.10397474029005e-06 3.97571609028279e-05 1111 1109 0 15 0 1111 1134 0 41 0 0 0 0 0 0 13 37 0 2886 0 0 0 0 0 1227 +912 915 0.999999705423355 0.000264369836507119 -0.00072059821866101 -0.00082381044830952 -0.00026512204069089 0.999999419923348 -0.00104396516713149 -0.0011932513258015 0.000720321807758254 0.00104415590607398 0.999999195437145 -0.002368484000816 2.78295768575527e-05 -2.0533330715734e-05 -4.45857897012402e-06 1.44724043292474e-07 -4.2494775687022e-06 6.33352027498552e-06 -2.0533330715734e-05 3.2386530951688e-05 5.92407472075169e-06 4.46904894595516e-06 3.66742767424442e-06 -1.94521171917597e-06 -4.45857897012402e-06 5.92407472075169e-06 1.09843720555176e-05 -4.83049212331866e-06 3.73044957118717e-06 -3.11164030249415e-06 1.44724043292474e-07 4.46904894595516e-06 -4.83049212331866e-06 3.47886069180172e-05 3.07112602964607e-06 5.42951419765271e-06 -4.2494775687022e-06 3.66742767424442e-06 3.73044957118717e-06 3.07112602964607e-06 2.00465371282434e-05 1.41139270685703e-06 6.33352027498552e-06 -1.94521171917597e-06 -3.11164030249415e-06 5.42951419765271e-06 1.41139270685703e-06 2.9247030259623e-05 1078 1074 0 16 0 1075 1101 0 43 0 0 0 0 0 0 20 47 0 2976 0 0 0 0 0 2192 +912 916 0.999998947153544 0.000406057442068772 0.00139312926791247 0.00393438729771796 -0.00040444868348677 0.999999251350304 -0.00115486799871435 0.00134136216217945 -0.00139359716769215 0.00115430333351733 0.999998362734034 -0.00213404795202822 3.61147942443575e-05 -3.03991870017198e-05 -3.84962289977886e-06 -4.15715293823527e-06 -5.65239946129958e-06 1.16824645751756e-05 -3.03991870017198e-05 5.26421364129402e-05 5.85364889321216e-06 1.38489203323281e-05 5.5759579565528e-06 -4.97627866135596e-06 -3.84962289977886e-06 5.85364889321216e-06 1.33700534785488e-05 -8.43202088510461e-06 2.02183779554056e-06 -4.30523222859462e-06 -4.15715293823527e-06 1.38489203323281e-05 -8.43202088510461e-06 4.29974316804272e-05 8.49393567266719e-06 8.52394400707685e-06 -5.65239946129958e-06 5.5759579565528e-06 2.02183779554056e-06 8.49393567266719e-06 2.97800825639895e-05 1.05810478168485e-06 1.16824645751756e-05 -4.97627866135596e-06 -4.30523222859462e-06 8.52394400707685e-06 1.05810478168485e-06 3.21264712349136e-05 1045 1045 0 17 0 1044 1071 0 47 0 0 0 0 0 0 15 42 0 2834 0 0 0 0 0 1130 +913 916 0.999998834517482 0.000249652462149321 -0.00150619963004089 0.00200477767611915 -0.000253229898348208 0.999997146628371 -0.00237541780236818 -0.00063905909769944 0.00150560230339061 0.00237579644863947 0.999996044368646 -0.000375843581230164 2.9748111520188e-05 -2.11868186222174e-05 -4.7388712798571e-06 2.40785283703802e-06 -4.7913257044075e-06 1.09330451415605e-05 -2.11868186222174e-05 4.09701786882479e-05 7.16554421690309e-06 3.50104004524244e-06 5.39600603109559e-06 -6.47693425222459e-06 -4.7388712798571e-06 7.16554421690309e-06 1.22401910189902e-05 -6.98896259688843e-06 4.01893625403185e-06 -3.23821609299775e-06 2.40785283703802e-06 3.50104004524244e-06 -6.98896259688843e-06 3.9902838587923e-05 6.25604724476877e-06 1.42724462511598e-06 -4.7913257044075e-06 5.39600603109559e-06 4.01893625403185e-06 6.25604724476877e-06 2.41973219600595e-05 -3.4807034161377e-06 1.09330451415605e-05 -6.47693425222459e-06 -3.23821609299775e-06 1.42724462511598e-06 -3.4807034161377e-06 3.49490794529735e-05 1079 1082 0 23 0 1077 1094 0 35 0 0 0 0 0 0 13 37 0 2841 0 0 0 0 0 2143 +913 915 0.999998009600324 0.000403351561550091 -0.00195399664979117 3.84865828179876e-05 -0.000404871580050144 0.999999615732487 -0.000777569213773149 -0.00110394495654307 0.00195368226517715 0.000778358783810651 0.99999778863916 0.00203484352897352 2.47476160149975e-05 -2.73929765971853e-05 -3.17409074505271e-06 -9.54330282776959e-07 -2.83093201463692e-06 1.65032776610362e-05 -2.73929765971853e-05 7.4171954033795e-05 5.95060227448745e-06 2.56075104978503e-05 1.13902846511166e-05 -3.90265902747354e-05 -3.17409074505271e-06 5.95060227448745e-06 1.08588516743016e-05 -5.12868497323497e-06 4.92464627678806e-06 -1.83340358096913e-06 -9.54330282776959e-07 2.56075104978503e-05 -5.12868497323497e-06 5.45379866125866e-05 1.02515565703567e-05 -1.62485085549144e-05 -2.83093201463692e-06 1.13902846511166e-05 4.92464627678806e-06 1.02515565703567e-05 2.06977905111309e-05 -1.12500644565601e-05 1.65032776610362e-05 -3.90265902747354e-05 -1.83340358096913e-06 -1.62485085549144e-05 -1.12500644565601e-05 5.93631552285438e-05 1045 1044 0 22 0 1040 1059 0 40 0 0 0 0 0 0 20 45 0 2990 0 0 0 0 0 2568 +915 917 0.999999233427792 0.000167394086123849 -0.00122683456435859 0.00196275204398672 -0.000168393313919027 0.999999654183151 -0.000814418362724733 -0.00190845658716993 0.00122669781128097 0.000814624329152173 0.999998915799253 0.000975832123073144 2.43314499808069e-05 -2.19483374646382e-05 -3.32222770911897e-06 1.86487467346182e-06 -1.45679965019279e-06 1.72329249966826e-05 -2.19483374646382e-05 4.08987539143301e-05 4.97927514311747e-06 6.87966235316286e-06 4.38330082262887e-06 -2.02358320290163e-05 -3.32222770911897e-06 4.97927514311747e-06 1.03501522505888e-05 -4.63268419347909e-06 4.63217942045555e-06 -4.22326786006892e-06 1.86487467346182e-06 6.87966235316286e-06 -4.63268419347909e-06 3.95245007684889e-05 -2.13170879666056e-06 1.15777092952669e-06 -1.45679965019279e-06 4.38330082262887e-06 4.63217942045555e-06 -2.13170879666056e-06 1.75442055434781e-05 -2.97597015650605e-06 1.72329249966826e-05 -2.02358320290163e-05 -4.22326786006892e-06 1.15777092952669e-06 -2.97597015650605e-06 3.10190983963775e-05 1049 1045 0 5 0 1054 1080 0 41 0 0 0 0 0 0 13 40 0 2601 0 0 0 0 0 2580 +914 917 0.999998530389944 0.00125222309587487 0.00117096339384791 0.0103454821574092 -0.0012508922833267 0.999998571756445 -0.00113655337090297 0.00588349127900791 -0.00117238493980773 0.00113508695153929 0.999998668544696 -0.00433927109581648 6.66223674712385e-05 -7.59975164994693e-05 -4.63784327767911e-06 -2.44400157147433e-05 -1.77053910454598e-05 2.83887595984952e-05 -7.59975164994693e-05 0.00015645486675613 1.11891666604096e-05 5.5139309842741e-05 1.88785850914242e-05 -2.86467069775667e-05 -4.63784327767911e-06 1.11891666604096e-05 1.4261007392615e-05 -6.62113480022534e-06 -2.1681189084412e-06 -3.23952292502031e-06 -2.44400157147433e-05 5.5139309842741e-05 -6.62113480022534e-06 7.73119295210835e-05 3.08247367827178e-05 -7.69204149702327e-06 -1.77053910454598e-05 1.88785850914242e-05 -2.1681189084412e-06 3.08247367827178e-05 4.4891559330762e-05 -9.59758065502293e-06 2.83887595984952e-05 -2.86467069775667e-05 -3.23952292502031e-06 -7.69204149702327e-06 -9.59758065502293e-06 4.50731519743473e-05 1029 1030 0 24 0 1027 1049 0 44 0 0 0 0 0 0 15 40 0 2586 0 0 0 0 0 1214 +915 918 0.999999452098758 -0.000567808925046601 0.000879428910812057 0.0012064224781595 0.000568437823529764 0.999999582800409 -0.000715036675839731 -0.00419191349916654 -0.000879022539708398 0.000715536184726259 0.999999357663465 0.00213962556931863 2.17743689922198e-05 -1.91685910273022e-05 -5.34000137089152e-06 1.8470809073178e-07 -3.16335889073129e-06 1.21915698298019e-05 -1.91685910273022e-05 2.21478009001441e-05 7.04307531673088e-06 1.90715410510742e-07 1.44507814026703e-06 -1.01397990170276e-05 -5.34000137089152e-06 7.04307531673088e-06 1.34892187241234e-05 -5.05067638993064e-06 3.07853504624877e-06 -5.65380009581787e-06 1.8470809073178e-07 1.90715410510742e-07 -5.05067638993064e-06 2.7725755967376e-05 -5.04293140343495e-06 6.72673485909674e-06 -3.16335889073129e-06 1.44507814026703e-06 3.07853504624877e-06 -5.04293140343495e-06 2.47664429247322e-05 -7.23030327060458e-07 1.21915698298019e-05 -1.01397990170276e-05 -5.65380009581787e-06 6.72673485909674e-06 -7.23030327060458e-07 2.12648758623261e-05 1120 1122 0 12 0 1125 1149 0 41 0 0 0 0 0 0 14 36 0 2663 0 0 0 0 0 1192 +915 919 0.999999059482721 0.000520491605107056 0.00126890589167643 0.00128636115941358 -0.000519106796984965 0.999999269659017 -0.00109142547429072 0.000127795950640706 -0.00126947304273942 0.0010907657501131 0.999998599333155 -0.00432444067931906 2.66138980789031e-05 -2.25677151749942e-05 -4.1829901684604e-06 4.8001605479291e-07 -5.89503270978088e-06 1.36172626136089e-05 -2.25677151749942e-05 3.22308628353789e-05 5.06533221541355e-06 2.83643731193824e-06 6.30955173697974e-06 -1.30616944303325e-05 -4.1829901684604e-06 5.06533221541355e-06 1.17327740615004e-05 -5.33839698076623e-06 3.05806724446973e-06 -5.90595693655371e-06 4.8001605479291e-07 2.83643731193824e-06 -5.33839698076623e-06 3.99876615809723e-05 6.59190314488155e-06 1.02822349364514e-05 -5.89503270978088e-06 6.30955173697974e-06 3.05806724446973e-06 6.59190314488155e-06 2.25728584666606e-05 3.51021687356779e-08 1.36172626136089e-05 -1.30616944303325e-05 -5.90595693655371e-06 1.02822349364514e-05 3.51021687356779e-08 2.50897567734305e-05 1136 1137 0 19 0 1134 1160 0 43 0 0 0 0 0 0 12 38 0 2746 0 0 0 0 0 2139 +917 919 0.999976740105325 0.000358390913894797 0.006811079523905 0.00573166061050717 -0.000360514925751811 0.999999886771668 0.000310621376595558 0.00255239021439238 -0.0068109674288188 -0.000313069647403905 0.9999767560849 -0.00377734264952779 4.22615114886625e-05 -4.74963832951723e-05 -6.92781620606756e-06 -4.39381636045734e-06 -4.48424305189821e-06 1.9479162886698e-05 -4.74963832951723e-05 8.40973096818304e-05 7.86974665490714e-06 2.91833345053987e-05 1.47918766785149e-05 -1.2202445781592e-05 -6.92781620606756e-06 7.86974665490714e-06 1.120349933411e-05 -2.04554433373508e-06 2.928204448727e-06 -5.06021312596211e-06 -4.39381636045734e-06 2.91833345053987e-05 -2.04554433373508e-06 5.95057223706445e-05 1.30223979703111e-05 1.15568860714569e-05 -4.48424305189821e-06 1.47918766785149e-05 2.928204448727e-06 1.30223979703111e-05 2.33988984643871e-05 2.03065606611097e-06 1.9479162886698e-05 -1.2202445781592e-05 -5.06021312596211e-06 1.15568860714569e-05 2.03065606611097e-06 3.09125603800805e-05 1071 1073 0 11 0 1080 1101 0 38 0 0 0 0 0 0 11 36 0 2744 0 0 0 0 0 2116 +917 920 0.999992681333313 -0.000302158974038559 0.00381391921337704 0.00557786945224126 0.000295331915663621 0.999998353490018 0.00179047376752833 0.0031340277827066 -0.00381445394143763 -0.00178933429158014 0.99999112407257 0.00208025451335113 4.44602046702266e-05 -4.46812099058512e-05 -6.19596088239967e-06 -5.03376321428343e-06 -5.25549087504327e-06 2.29264520535465e-05 -4.46812099058512e-05 6.44388385069342e-05 6.7629283963509e-06 1.98379425467302e-05 1.14344195051521e-05 -1.96946620020074e-05 -6.19596088239967e-06 6.7629283963509e-06 1.29935091608618e-05 -8.86459426625113e-06 1.76163289665924e-06 -6.07923189086537e-06 -5.03376321428343e-06 1.98379425467302e-05 -8.86459426625113e-06 5.41998064383691e-05 1.76181699921878e-05 4.7062259785491e-06 -5.25549087504327e-06 1.14344195051521e-05 1.76163289665924e-06 1.76181699921878e-05 2.79877614587123e-05 -4.14700118723798e-07 2.29264520535465e-05 -1.96946620020074e-05 -6.07923189086537e-06 4.7062259785491e-06 -4.14700118723798e-07 3.13508366060521e-05 1082 1078 0 13 0 1083 1104 0 41 0 0 0 0 0 0 9 35 0 2756 0 0 0 0 0 1163 +916 918 0.999999740569292 -0.000119053758634361 -0.000710413648580004 6.77303330621663e-05 0.000117345148112256 0.999997101940859 -0.00240464966237756 -0.00374012336202622 0.000710697872339741 0.00240456567494278 0.999996856481284 -0.00231851413445335 2.52555662011955e-05 -2.20718504238811e-05 -4.81874094521926e-06 1.48641257346257e-07 -5.68784465212896e-06 1.22383858304917e-05 -2.20718504238811e-05 2.60040507907162e-05 5.70969779127147e-06 1.69929545013051e-06 4.32753220312401e-06 -1.02345224118003e-05 -4.81874094521926e-06 5.70969779127147e-06 1.08380462026376e-05 -5.94628548067559e-06 3.30081823491708e-06 -5.40765934105697e-06 1.48641257346257e-07 1.69929545013051e-06 -5.94628548067559e-06 3.6460333939069e-05 2.35378811588627e-06 8.72214513160267e-06 -5.68784465212896e-06 4.32753220312401e-06 3.30081823491708e-06 2.35378811588627e-06 2.57474705227353e-05 4.99125922371874e-07 1.22383858304917e-05 -1.02345224118003e-05 -5.40765934105697e-06 8.72214513160267e-06 4.99125922371874e-07 2.37582955932146e-05 1118 1120 0 23 0 1117 1137 0 41 0 0 0 0 0 0 20 44 0 2658 0 0 0 0 0 2097 +918 920 0.999998584264165 0.000420539695411545 -0.00162929924546722 0.0023627969688438 -0.000419862612224152 0.999999825376733 0.000415886871493462 0.00224803375181246 0.00162947385789193 -0.000415202200870218 0.99999858621004 -0.000318274711320097 2.75236327617345e-05 -2.71181343777422e-05 -6.07136808769895e-06 9.53838078683297e-07 -3.46347218639459e-06 1.90626903351403e-05 -2.71181343777422e-05 4.13612328868277e-05 7.42962505918013e-06 3.60979118401336e-06 5.73861044384633e-06 -1.81760000709187e-05 -6.07136808769895e-06 7.42962505918013e-06 1.150044215214e-05 -6.58999040226643e-06 6.14737026253777e-06 -5.33485852963464e-06 9.53838078683297e-07 3.60979118401336e-06 -6.58999040226643e-06 3.65270274461912e-05 4.26000380097689e-06 4.31965432219864e-06 -3.46347218639459e-06 5.73861044384633e-06 6.14737026253777e-06 4.26000380097689e-06 1.67506920682833e-05 -2.08384817720937e-06 1.90626903351403e-05 -1.81760000709187e-05 -5.33485852963464e-06 4.31965432219864e-06 -2.08384817720937e-06 2.62803235297301e-05 1086 1084 0 14 0 1086 1110 0 44 0 0 0 0 0 0 15 40 0 2756 0 0 0 0 0 2283 +913 917 0.999994842428586 0.00129071426118778 -0.00294094762336139 0.0061874906449944 -0.00128821737845246 0.999998808365993 0.00085074236942103 0.00519598486241539 0.00294204218413699 -0.000846949401818972 0.999995313521267 -0.000557678286105034 2.98163366454738e-05 -3.57657424753517e-05 -3.97483366492423e-06 -7.79953730675262e-06 -9.09268416520753e-06 2.73271156943403e-05 -3.57657424753517e-05 0.000109295081793845 8.73174390020641e-06 4.20473474107801e-05 1.50431279558681e-05 -5.9072312843681e-05 -3.97483366492423e-06 8.73174390020641e-06 1.1151362147126e-05 -5.45411143601394e-06 1.10078486746687e-06 -3.49977233997301e-06 -7.79953730675262e-06 4.20473474107801e-05 -5.45411143601394e-06 7.45779319558468e-05 2.82015078436193e-05 -3.03340757705851e-05 -9.09268416520753e-06 1.50431279558681e-05 1.10078486746687e-06 2.82015078436193e-05 3.54495501078694e-05 -2.24495937909169e-05 2.73271156943403e-05 -5.9072312843681e-05 -3.49977233997301e-06 -3.03340757705851e-05 -2.24495937909169e-05 6.73062442247902e-05 1029 1030 0 18 0 1029 1050 0 42 0 0 0 0 0 0 20 46 0 2612 0 0 0 0 0 2580 +914 916 0.999994519071626 0.000506029240156524 -0.00327196594045308 0.00241487128443028 -0.000507332494207326 0.999999792307121 -0.000397491453174694 0.00179396503914849 0.00327176411859103 0.000399149249194041 0.999994568104962 0.00365268813148279 3.00106704767896e-05 -3.12576587605197e-05 -3.90226762236491e-06 -1.96790135710202e-06 -2.53277371431303e-06 6.31609613074348e-06 -3.12576587605197e-05 5.08395758023647e-05 5.12669218277186e-06 6.08789990161975e-06 1.70717217547802e-06 -2.12052837381432e-06 -3.90226762236491e-06 5.12669218277186e-06 9.89667707576601e-06 -4.28988834804203e-06 2.5866011914274e-06 -3.01092505754413e-06 -1.96790135710202e-06 6.08789990161975e-06 -4.28988834804203e-06 3.99747529403817e-05 9.04010712261106e-06 6.12898686381779e-06 -2.53277371431303e-06 1.70717217547802e-06 2.5866011914274e-06 9.04010712261106e-06 2.36860220963131e-05 2.51295560578854e-07 6.31609613074348e-06 -2.12052837381432e-06 -3.01092505754413e-06 6.12898686381779e-06 2.51295560578854e-07 2.74952753676577e-05 1082 1078 0 5 0 1088 1114 0 43 0 0 0 0 0 0 20 46 0 2841 0 0 0 0 0 2139 +914 918 0.999999381491962 0.000268572974873152 -0.00107929803595113 0.00109279687938069 -0.000270434021952018 0.999998476418252 -0.00172453663782712 -0.00224491246282481 0.00107883322761725 0.0017248274500961 0.999997930542426 0.00150735340563211 3.43606377334714e-05 -3.68278979910548e-05 -4.14608407672033e-06 -4.68651782683401e-07 -7.99363548611288e-06 2.76951546685693e-05 -3.68278979910548e-05 7.1230863537544e-05 5.31539257664132e-06 1.80523103628872e-05 1.36344869125964e-05 -3.25662469189827e-05 -4.14608407672033e-06 5.31539257664132e-06 9.84211920305864e-06 -4.44145703427217e-06 3.54175548483268e-06 -3.97307791651201e-06 -4.68651782683401e-07 1.80523103628872e-05 -4.44145703427217e-06 4.53688499205385e-05 8.05156053922219e-06 1.72537344815338e-06 -7.99363548611288e-06 1.36344869125964e-05 3.54175548483268e-06 8.05156053922219e-06 2.31824077151986e-05 -7.95708892892265e-06 2.76951546685693e-05 -3.25662469189827e-05 -3.97307791651201e-06 1.72537344815338e-06 -7.95708892892265e-06 3.81659600069829e-05 1061 1059 0 19 0 1060 1080 0 41 0 0 0 0 0 0 11 37 0 2658 0 0 0 0 0 2319 +918 922 0.999996582143635 -0.00026867167427409 0.00260067617740218 0.00475733925649644 0.00026194474869728 0.999996620433133 0.00258660148883548 0.00398423310178212 -0.00260136233479582 -0.00258591141473538 0.999993272965453 0.00115513784454959 3.55802866549109e-05 -3.10932246603065e-05 -3.79692152421102e-06 -3.94386924633345e-07 -6.07676615291921e-06 1.39957806832289e-05 -3.10932246603065e-05 5.00256579629647e-05 5.62474944488018e-06 7.69882058562248e-06 4.5724518166235e-06 -2.54074721565334e-06 -3.79692152421102e-06 5.62474944488018e-06 9.53101416393091e-06 -3.29885288101458e-06 4.37621695763822e-06 -3.68144734515385e-06 -3.94386924633345e-07 7.69882058562248e-06 -3.29885288101458e-06 3.51035233439752e-05 5.66432070886836e-06 1.11817954358035e-05 -6.07676615291921e-06 4.5724518166235e-06 4.37621695763822e-06 5.66432070886836e-06 1.8980795914494e-05 -4.67687127139181e-08 1.39957806832289e-05 -2.54074721565334e-06 -3.68144734515385e-06 1.11817954358035e-05 -4.67687127139181e-08 2.9266234674529e-05 1086 1089 0 21 0 1082 1106 0 42 0 0 0 0 0 0 14 39 0 2938 0 0 0 0 0 2090 +919 922 0.999999547391538 -0.000387365169480955 0.000869002269917143 0.00127895193700852 0.000387263291758788 0.999999918122132 0.000117400480651757 0.000478696009498394 -0.000869047675622174 -0.000117063894835712 0.999999615526017 -0.000499936413045005 1.91707759097303e-05 -1.63207314262944e-05 -4.67677084920063e-06 8.40591621560262e-07 -1.86169388172282e-06 1.08207437350666e-05 -1.63207314262944e-05 2.27080531013316e-05 5.4982257567978e-06 -1.63099446916906e-06 2.96415810709246e-07 -9.37337746244532e-06 -4.67677084920063e-06 5.4982257567978e-06 9.20771987810897e-06 -3.09946004334769e-06 3.62426733720141e-06 -2.8077954741767e-06 8.40591621560262e-07 -1.63099446916906e-06 -3.09946004334769e-06 2.56432681504987e-05 2.78405940540552e-06 2.47826432330766e-06 -1.86169388172282e-06 2.96415810709246e-07 3.62426733720141e-06 2.78405940540552e-06 1.5525513758805e-05 -2.03239670753598e-06 1.08207437350666e-05 -9.37337746244532e-06 -2.8077954741767e-06 2.47826432330766e-06 -2.03239670753598e-06 1.74053759641619e-05 1126 1122 0 15 0 1127 1147 0 40 0 0 0 0 0 0 13 36 0 2949 0 0 0 0 0 2314 +918 921 0.99999242214684 -0.000259396117834601 0.00388437415176975 0.00492150469078124 0.000259419943568172 0.999999966334798 -5.62989534486615e-06 0.00286293147009085 -0.00388437256062852 6.63753680559569e-06 0.999992455774419 -0.00383440733054636 2.95860339988662e-05 -2.78985837266589e-05 -2.73788855793687e-07 -1.57191754329144e-06 -1.62421445119727e-06 1.5258707650764e-05 -2.78985837266589e-05 4.41559144517536e-05 2.97561921568311e-06 7.29814185155998e-06 4.30457526840331e-06 -1.18344863200457e-05 -2.73788855793687e-07 2.97561921568311e-06 1.09563038985373e-05 -4.74395710410999e-06 4.6773516927929e-06 -1.52386230922486e-06 -1.57191754329144e-06 7.29814185155998e-06 -4.74395710410999e-06 4.47006606284746e-05 1.17202436346784e-05 6.83248925702017e-06 -1.62421445119727e-06 4.30457526840331e-06 4.6773516927929e-06 1.17202436346784e-05 1.99042716025683e-05 8.31779494127086e-07 1.5258707650764e-05 -1.18344863200457e-05 -1.52386230922486e-06 6.83248925702017e-06 8.31779494127086e-07 2.5324742373821e-05 1076 1075 0 26 0 1069 1086 0 41 0 0 0 0 0 0 13 40 0 2873 0 0 0 0 0 2080 +917 921 0.999998816681419 0.00062384514089627 -0.00140621940020816 0.00539898305159707 -0.000623227282798162 0.999999709094699 0.00043977070333506 0.00333512938184204 0.00140649333994786 -0.000438893788650405 0.999998914573774 0.000744552393094791 4.55043198972686e-05 -4.9096461045973e-05 9.55989105930422e-07 -1.71290830686853e-05 -1.26541841003207e-05 2.25716061553339e-05 -4.9096461045973e-05 7.28197468983892e-05 1.76002748223779e-06 3.02125109537487e-05 1.88548922561185e-05 -2.13719385868143e-05 9.55989105930422e-07 1.76002748223779e-06 1.20335545675663e-05 -7.88111138129202e-06 4.06403359551871e-06 -1.86530623146773e-06 -1.71290830686853e-05 3.02125109537487e-05 -7.88111138129202e-06 6.59511428155405e-05 1.88645776043061e-05 -8.77974016163807e-07 -1.26541841003207e-05 1.88548922561185e-05 4.06403359551871e-06 1.88645776043061e-05 2.83953992137187e-05 -1.12431828886426e-06 2.25716061553339e-05 -2.13719385868143e-05 -1.86530623146773e-06 -8.77974016163807e-07 -1.12431828886426e-06 3.03939090168826e-05 1047 1048 0 28 0 1042 1063 0 43 0 0 0 0 0 0 20 44 0 2874 0 0 0 0 0 2057 +920 923 0.999999922926554 0.000379981400353074 -9.87978812690367e-05 0.000505825518770533 -0.000379890023377478 0.999999501630121 0.000923267610318982 0.001199112034453 9.91486565506182e-05 -0.00092323000683014 0.999999568907856 0.00264615817489873 3.16380871591017e-05 -3.02753910491263e-05 -6.19766562616201e-06 -6.32994414303945e-06 -2.17086010411998e-07 3.80372167642393e-06 -3.02753910491263e-05 4.39399028499008e-05 7.04203011253863e-06 1.53202691705423e-05 5.4659675464206e-06 -2.47480153997493e-08 -6.19766562616201e-06 7.04203011253863e-06 1.2340565530899e-05 -4.06129828618902e-06 1.05557666068456e-06 5.87917947170839e-07 -6.32994414303945e-06 1.53202691705423e-05 -4.06129828618902e-06 4.91566774186857e-05 1.33623126850708e-05 1.11764247143637e-05 -2.17086010411998e-07 5.4659675464206e-06 1.05557666068456e-06 1.33623126850708e-05 2.48797536648487e-05 -7.74442721289527e-07 3.80372167642393e-06 -2.47480153997493e-08 5.87917947170839e-07 1.11764247143637e-05 -7.74442721289527e-07 2.59734889367e-05 1112 1118 0 25 0 1111 1134 0 43 0 0 0 0 0 0 21 43 0 2851 0 0 0 0 0 2124 +921 923 0.99999925211957 7.92258189852263e-05 0.00122044400523865 0.000453709416784483 -7.77292413969208e-05 0.999999245127782 -0.00122625528798562 -0.00184763508123159 -0.00122054023503885 0.00122615950670659 0.999998503406079 -0.000960329989507698 4.24831358372301e-05 -3.9358467453583e-05 -3.94251699207735e-06 -1.29927223022907e-05 -7.29634847579936e-06 1.25825026889315e-05 -3.9358467453583e-05 5.3561701974926e-05 6.06317031173171e-06 1.72521085102129e-05 7.05329925123969e-06 -1.39219154655552e-05 -3.94251699207735e-06 6.06317031173171e-06 1.51793833124941e-05 -7.58317683113496e-06 -1.00833590071421e-06 -8.95080817033885e-07 -1.29927223022907e-05 1.72521085102129e-05 -7.58317683113496e-06 5.4842525281031e-05 1.68890595479053e-05 6.70806780621314e-06 -7.29634847579936e-06 7.05329925123969e-06 -1.00833590071421e-06 1.68890595479053e-05 3.75830102774852e-05 -2.55543454822948e-06 1.25825026889315e-05 -1.39219154655552e-05 -8.95080817033885e-07 6.70806780621314e-06 -2.55543454822948e-06 3.07100686704633e-05 1102 1101 0 8 0 1106 1125 0 40 0 0 0 0 0 0 16 40 0 2885 0 0 0 0 0 1154 +919 923 0.999985005255685 -0.0005903042134475 0.00544433694062652 0.00122864195924927 0.000586482664189269 0.999999580562211 0.000703500878380731 0.000538514045632095 -0.00544474993659854 -0.000700297320331252 0.999984932027373 -0.00142770024642896 2.6273936111198e-05 -2.71904788316815e-05 -5.38856755683834e-07 -8.98864404020733e-06 -4.7822533588924e-06 1.83049589674812e-05 -2.71904788316815e-05 4.56999576649273e-05 1.73876259893482e-06 2.30559322212163e-05 9.48415616359056e-06 -1.58236109072606e-05 -5.38856755683834e-07 1.73876259893482e-06 1.06202412345368e-05 -5.72779327483806e-06 3.51332065971742e-06 -2.2024528144455e-07 -8.98864404020733e-06 2.30559322212163e-05 -5.72779327483806e-06 5.64991967957266e-05 1.63590863524374e-05 1.51347492078724e-06 -4.7822533588924e-06 9.48415616359056e-06 3.51332065971742e-06 1.63590863524374e-05 2.40691818088612e-05 -3.9334348035533e-06 1.83049589674812e-05 -1.58236109072606e-05 -2.2024528144455e-07 1.51347492078724e-06 -3.9334348035533e-06 2.80483073726508e-05 1109 1110 0 12 0 1114 1134 0 37 0 0 0 0 0 0 14 36 0 2824 0 0 0 0 0 2365 +919 921 0.99999995273983 -0.000228099008029065 0.000206133889085309 0.00202579508834199 0.000228169148921511 0.999999916064247 -0.000340309180146589 0.000756625064252296 -0.000206056247596891 0.000340356197457556 0.999999920849238 -0.00166095488087494 2.42776767288788e-05 -2.07113556351359e-05 -3.74125381801573e-07 -2.62804421123934e-06 -1.53237789122832e-06 7.52195962310944e-06 -2.07113556351359e-05 2.82645687370264e-05 3.23233436075544e-06 5.21056214441865e-06 2.35196953627133e-06 -6.77979156735963e-06 -3.74125381801573e-07 3.23233436075544e-06 1.12277515978819e-05 -4.12728667407171e-06 3.65478168124887e-06 -1.71572251496546e-06 -2.62804421123934e-06 5.21056214441865e-06 -4.12728667407171e-06 3.28103234523928e-05 4.36326677950994e-06 4.89061653762816e-06 -1.53237789122832e-06 2.35196953627133e-06 3.65478168124887e-06 4.36326677950994e-06 1.90680091998795e-05 1.31878894075733e-06 7.52195962310944e-06 -6.77979156735963e-06 -1.71572251496546e-06 4.89061653762816e-06 1.31878894075733e-06 2.42621071308996e-05 1110 1105 0 10 0 1115 1130 0 35 0 0 0 0 0 0 10 34 0 2869 0 0 0 0 0 1175 +921 924 0.999999958547534 -0.000287918512568916 2.80375601094624e-06 0.000905186754977937 0.000287926399023428 0.99999414518711 -0.00340979323256113 -0.00329482375294033 -1.82199699979285e-06 0.00340979389849217 0.999994186634227 -0.00261074539515943 3.3810407857171e-05 -3.19715576116486e-05 -8.96927316718518e-06 -2.88069099145258e-06 -2.76905444256502e-06 3.7714560566434e-06 -3.19715576116486e-05 4.11425408052812e-05 1.05654343627922e-05 4.4915855058386e-06 3.11740094966835e-06 -4.29621382018458e-07 -8.96927316718518e-06 1.05654343627922e-05 1.36074067994647e-05 -3.9591854718754e-06 -8.90452642648087e-07 1.20563657341263e-06 -2.88069099145258e-06 4.4915855058386e-06 -3.9591854718754e-06 4.05314219636452e-05 7.45674703375158e-06 2.89184416181942e-06 -2.76905444256502e-06 3.11740094966835e-06 -8.90452642648087e-07 7.45674703375158e-06 2.6651687822577e-05 -6.69584718076019e-06 3.7714560566434e-06 -4.29621382018458e-07 1.20563657341263e-06 2.89184416181942e-06 -6.69584718076019e-06 2.94670303864556e-05 1097 1091 0 16 0 1091 1110 0 38 0 0 0 0 0 0 19 41 0 2925 0 0 0 0 0 2187 +921 925 0.999999290767609 0.000459788248319 -0.00109866238966722 -0.000218492120184594 -0.000460274194760039 0.999999796349622 -0.000442095442867141 -0.000685338498368429 0.00109845889563494 0.00044260081526545 0.999999298746041 -0.000801359473099209 2.84956619719354e-05 -2.91461973330974e-05 -2.70435973951801e-06 -2.55478396817178e-06 -2.19368303736909e-06 1.69772946957525e-05 -2.91461973330974e-05 4.31895942012972e-05 3.89955312955778e-06 6.20116622395585e-06 3.11958241587259e-06 -1.72489223561533e-05 -2.70435973951801e-06 3.89955312955778e-06 1.18547691976091e-05 -6.61149330806635e-06 1.02691944668549e-06 -1.06054956505458e-06 -2.55478396817178e-06 6.20116622395585e-06 -6.61149330806635e-06 4.82190557032988e-05 1.28837567878834e-05 2.74385840305355e-06 -2.19368303736909e-06 3.11958241587259e-06 1.02691944668549e-06 1.28837567878834e-05 2.55037055007935e-05 -3.39898902131759e-06 1.69772946957525e-05 -1.72489223561533e-05 -1.06054956505458e-06 2.74385840305355e-06 -3.39898902131759e-06 2.60002944312241e-05 1098 1098 0 9 0 1101 1123 0 40 0 0 0 0 0 0 17 43 0 2907 0 0 0 0 0 2552 +922 926 0.999983851977268 -0.000155925297224494 -0.0056807985359784 -0.00521638620716967 0.000156305026908644 0.999999985579855 6.64005092063052e-05 -0.000976725936976117 0.00568078810054133 -6.72873743374018e-05 0.999983861929264 0.00280552799926745 4.14231484764005e-05 -4.64991567170877e-05 -7.37445426870503e-06 -3.25888857403096e-06 -3.57367520551805e-06 9.78311599462348e-06 -4.64991567170877e-05 6.82701199648933e-05 8.59360866367325e-06 1.18029744652409e-05 7.02171116070165e-06 -6.36989580966589e-06 -7.37445426870503e-06 8.59360866367325e-06 1.18575900283052e-05 -6.27891810761895e-06 3.04617917616732e-06 -1.7418869220571e-06 -3.25888857403096e-06 1.18029744652409e-05 -6.27891810761895e-06 5.14883028135624e-05 1.33977535045391e-05 7.21728255607028e-06 -3.57367520551805e-06 7.02171116070165e-06 3.04617917616732e-06 1.33977535045391e-05 2.34361113824873e-05 -1.2782191748569e-06 9.78311599462348e-06 -6.36989580966589e-06 -1.7418869220571e-06 7.21728255607028e-06 -1.2782191748569e-06 2.80061469509545e-05 1058 1068 0 24 0 1058 1079 0 36 0 0 0 0 0 0 20 45 0 2929 0 0 0 0 0 2287 +923 925 0.999999949398594 0.00028417365106557 0.000142997013104094 0.000333772460186401 -0.000284170716453758 0.999999959412513 -2.05420888979362e-05 0.00136206814660398 -0.000143002844820607 2.05014522948131e-05 0.999999989564938 -0.000493293600407178 2.56443262326773e-05 -2.14966703829085e-05 -2.66538648437852e-07 -5.74573709939401e-06 -3.52241327290016e-06 6.72541834583683e-06 -2.14966703829085e-05 2.43469480950461e-05 2.20453405378351e-06 4.20033096456151e-06 3.29250788443541e-06 -7.29841729799619e-06 -2.66538648437852e-07 2.20453405378351e-06 1.85237622965371e-05 -4.81229997389406e-06 -3.71587177382902e-06 3.68262107566077e-06 -5.74573709939401e-06 4.20033096456151e-06 -4.81229997389406e-06 4.2739998267468e-05 1.74755249451094e-05 7.09945721257418e-06 -3.52241327290016e-06 3.29250788443541e-06 -3.71587177382902e-06 1.74755249451094e-05 3.9496563668082e-05 -4.07529863318639e-06 6.72541834583683e-06 -7.29841729799619e-06 3.68262107566077e-06 7.09945721257418e-06 -4.07529863318639e-06 3.04852916613488e-05 1116 1117 0 20 0 1115 1141 0 44 0 0 0 0 0 0 17 44 0 2902 0 0 0 0 0 1241 +922 924 0.999999264218181 -0.000373098691132771 -0.00115427919660554 -0.00157721870652976 0.000374363110643757 0.99999932997854 0.00109539706620704 -0.00112543920967659 0.00115386973200203 -0.00109582837978439 0.9999987338716 0.0024581362187749 3.63082576509212e-05 -3.29075872726378e-05 -6.89150576003106e-06 -1.6932380478251e-06 -3.61530338435461e-08 3.96469513625995e-06 -3.29075872726378e-05 4.13838005918717e-05 8.86527024284669e-06 1.87322924432038e-06 -3.74418775899371e-07 -5.15606788860447e-07 -6.89150576003106e-06 8.86527024284669e-06 1.24030424399995e-05 -4.22174644997712e-06 6.15713164039844e-07 1.39165671371954e-07 -1.6932380478251e-06 1.87322924432038e-06 -4.22174644997712e-06 3.79967809928379e-05 1.09078288746629e-05 5.97033800587579e-06 -3.61530338435461e-08 -3.74418775899371e-07 6.15713164039844e-07 1.09078288746629e-05 2.28898137576006e-05 -3.24119094436579e-06 3.96469513625995e-06 -5.15606788860447e-07 1.39165671371954e-07 5.97033800587579e-06 -3.24119094436579e-06 3.23378062155314e-05 1084 1083 0 12 0 1089 1109 0 39 0 0 0 0 0 0 13 37 0 2920 0 0 0 0 0 2280 +920 922 0.999999591061813 0.000183413367407982 -0.000885570857261005 0.00227608479058181 -0.000183075999721651 0.999999910650902 0.000381026727011875 0.00146574057323698 0.000885640663531121 -0.000380864444425479 0.999999535291337 0.00257098663560164 5.21161771386355e-05 -5.53788966190385e-05 -9.60406459812128e-06 -1.49583115241763e-05 -6.09969956977306e-06 7.39939458107187e-06 -5.53788966190385e-05 7.314783536752e-05 1.05294706517653e-05 2.64976203075192e-05 1.05344269612673e-05 -3.0465484674483e-06 -9.60406459812128e-06 1.05294706517653e-05 1.20564644026109e-05 -3.25972647508925e-06 9.31323938887728e-07 4.07436997805592e-07 -1.49583115241763e-05 2.64976203075192e-05 -3.25972647508925e-06 5.41487814287538e-05 1.56224099577172e-05 6.1339713767342e-06 -6.09969956977306e-06 1.05344269612673e-05 9.31323938887728e-07 1.56224099577172e-05 2.86737190000252e-05 -4.74771029932565e-06 7.39939458107187e-06 -3.0465484674483e-06 4.07436997805592e-07 6.1339713767342e-06 -4.74771029932565e-06 3.55870238673552e-05 1101 1097 0 14 0 1104 1122 0 42 0 0 0 0 0 0 19 42 0 2963 0 0 0 0 0 2089 +920 924 0.999999775477419 -0.000412088785305005 0.00052842023488179 0.000114805971323179 0.000412900572607744 0.99999873347056 -0.00153706551377107 -0.00238718405744347 -0.000527786158161502 0.00153728335368271 0.999998679099959 -0.00168449991046849 2.88046596283176e-05 -2.83209896496688e-05 -7.44001806159475e-06 -1.14503885708524e-06 2.72605209433213e-06 5.31181497402775e-06 -2.83209896496688e-05 3.50205854315042e-05 7.84092948556971e-06 4.23217798306626e-06 -7.47535606481861e-07 -3.92676283370067e-06 -7.44001806159475e-06 7.84092948556971e-06 1.48560464028843e-05 -7.40307225746371e-06 -5.3365103564563e-08 -1.36828508332352e-06 -1.14503885708524e-06 4.23217798306626e-06 -7.40307225746371e-06 3.74011373708874e-05 9.053010297451e-06 4.72428072152662e-06 2.72605209433213e-06 -7.47535606481861e-07 -5.3365103564563e-08 9.053010297451e-06 2.94539977594029e-05 -3.77321610215052e-06 5.31181497402775e-06 -3.92676283370067e-06 -1.36828508332352e-06 4.72428072152662e-06 -3.77321610215052e-06 3.14424805303264e-05 1126 1131 0 25 0 1128 1143 0 38 0 0 0 0 0 0 21 43 0 2889 0 0 0 0 0 1228 +922 925 0.999999497838988 0.000636364495925879 0.000774184732680259 -0.00134123252630989 -0.000636767848664376 0.999999661611382 0.000520868340578426 0.000847203026140371 -0.000773853008585961 -0.000521361054965351 0.999999564666991 -0.00321217493099844 2.94782855709289e-05 -2.72932734634753e-05 1.22563317945462e-06 -1.03358300240309e-05 -3.14455783723197e-06 9.30811549666918e-06 -2.72932734634753e-05 3.08712601109019e-05 7.89346428903761e-08 9.56457236333422e-06 2.68292974696228e-06 -1.01807812257247e-05 1.22563317945462e-06 7.89346428903761e-08 1.494386505675e-05 -6.56539983082061e-06 -2.94342899641214e-07 2.51734148046075e-06 -1.03358300240309e-05 9.56457236333422e-06 -6.56539983082061e-06 5.42472958227406e-05 2.1865442516347e-05 8.82107776120639e-06 -3.14455783723197e-06 2.68292974696228e-06 -2.94342899641214e-07 2.1865442516347e-05 3.58879660614987e-05 1.85291788254611e-06 9.30811549666918e-06 -1.01807812257247e-05 2.51734148046075e-06 8.82107776120639e-06 1.85291788254611e-06 2.93344787145663e-05 1130 1140 0 25 0 1129 1150 0 37 0 0 0 0 0 0 13 38 0 2911 0 0 0 0 0 1243 +924 926 0.999999489683058 -6.04186946105275e-05 -0.00100845585187027 -0.00200187904718196 6.05071829523636e-05 0.999999994322384 8.77160927427696e-05 -0.000141766722407371 0.00100845054645282 -8.77770668024898e-05 0.99999948766121 0.00149312684674193 1.90502758960802e-05 -1.81406153069088e-05 -4.90549812109325e-06 -1.92845699306958e-06 5.78758271137564e-08 1.46719157206871e-05 -1.81406153069088e-05 2.62316969814346e-05 6.02361226397113e-06 5.29933623705444e-06 1.05838743140271e-06 -1.56301100583824e-05 -4.90549812109325e-06 6.02361226397113e-06 1.25801992454787e-05 -6.45634720652557e-06 1.81359980884842e-06 -1.19332286673661e-06 -1.92845699306958e-06 5.29933623705444e-06 -6.45634720652557e-06 3.91189011919549e-05 7.98175493543787e-06 -1.51808540940609e-06 5.78758271137564e-08 1.05838743140271e-06 1.81359980884842e-06 7.98175493543787e-06 2.02485104572873e-05 -4.32842739751745e-06 1.46719157206871e-05 -1.56301100583824e-05 -1.19332286673661e-06 -1.51808540940609e-06 -4.32842739751745e-06 2.73116722634166e-05 1123 1121 0 5 0 1131 1159 0 42 0 0 0 0 0 0 14 43 0 2936 0 0 0 0 0 2574 +924 927 0.999999715654869 0.000388851084309819 -0.000646130803160801 6.3376486566704e-06 -0.000388530497028125 0.999999801406776 0.000496216143373389 0.00117155073475949 0.000646323629029004 -0.000495964960754648 0.999999668142207 0.00170943222451162 1.68752294353889e-05 -1.59254791003851e-05 -6.17579888444953e-06 2.24080755866646e-06 -2.91534591093655e-07 9.57105948188816e-06 -1.59254791003851e-05 2.6642058363011e-05 6.80549891526602e-06 1.08682796975494e-06 -2.70375287713808e-08 -1.03765209738561e-05 -6.17579888444953e-06 6.80549891526602e-06 1.17518454822717e-05 -6.66748400856591e-06 2.08860161677159e-06 -1.71093844577597e-06 2.24080755866646e-06 1.08682796975494e-06 -6.66748400856591e-06 3.58625621645845e-05 6.08201732305484e-06 1.96839329253578e-06 -2.91534591093655e-07 -2.70375287713808e-08 2.08860161677159e-06 6.08201732305484e-06 2.0404905641082e-05 -4.99816678684973e-06 9.57105948188816e-06 -1.03765209738561e-05 -1.71093844577597e-06 1.96839329253578e-06 -4.99816678684973e-06 2.47430352845042e-05 1086 1086 0 2 0 1099 1126 0 42 0 0 0 0 0 0 16 42 0 2982 0 0 0 0 0 2576 +925 928 0.999995282482376 0.000160787193603578 -0.00306743548787937 -0.00306951307254309 -0.000158411587530525 0.999999687382679 0.000774687235326404 -9.45205823978218e-05 0.00306755908873239 -0.000774197663400435 0.999994995337084 -0.00195407351603408 5.82999571440168e-05 -7.16101750478607e-05 -8.25959724052829e-06 -8.64937124151531e-06 -3.28114701370498e-06 2.53610063253214e-05 -7.16101750478607e-05 0.000127450355923001 1.05095326432135e-05 3.49694834239677e-05 1.64179655176486e-05 -2.80954462516086e-05 -8.25959724052829e-06 1.05095326432135e-05 1.56827592681103e-05 -7.35097899345591e-06 -4.38601825964143e-07 -4.05553419547416e-06 -8.64937124151531e-06 3.49694834239677e-05 -7.35097899345591e-06 6.46563943955708e-05 1.99931365651426e-05 8.16860442625169e-06 -3.28114701370498e-06 1.64179655176486e-05 -4.38601825964143e-07 1.99931365651426e-05 3.2782463259334e-05 1.6423899876917e-07 2.53610063253214e-05 -2.80954462516086e-05 -4.05553419547416e-06 8.16860442625169e-06 1.6423899876917e-07 3.67718199398121e-05 1005 1006 0 20 0 1009 1028 0 42 0 0 0 0 0 0 21 44 0 2868 0 0 0 0 0 1095 +923 926 0.999987385569674 0.000761781056527282 -0.00496471460914258 -0.000799285994312146 -0.000760206427883508 0.999999660148697 0.000319043378564146 0.000568311873847554 0.00496495596307985 -0.000315265146055199 0.999987624833514 0.00236461407404343 5.00446424520886e-05 -5.77284407064396e-05 -7.14278727062227e-06 -2.24324979724573e-08 -5.70899431825463e-06 2.6725807339409e-05 -5.77284407064396e-05 0.00010665796624103 9.37966900899922e-06 2.21699900391214e-05 1.67738450937109e-05 -2.89205353325323e-05 -7.14278727062227e-06 9.37966900899922e-06 1.15512487939193e-05 -5.13544500741766e-06 5.38278399333171e-06 -3.69508937809965e-06 -2.24324979724573e-08 2.21699900391214e-05 -5.13544500741766e-06 5.24421029542592e-05 9.87896904347113e-06 1.11952888271134e-05 -5.70899431825463e-06 1.67738450937109e-05 5.38278399333171e-06 9.87896904347113e-06 2.54332124668829e-05 -6.6979375401035e-07 2.6725807339409e-05 -2.89205353325323e-05 -3.69508937809965e-06 1.11952888271134e-05 -6.6979375401035e-07 4.35927222141751e-05 1039 1038 0 9 0 1043 1064 0 35 0 0 0 0 0 0 15 42 0 2932 0 0 0 0 0 2316 +924 928 0.999972235735772 -7.16566919425975e-05 -0.00745135040922028 -0.00650869163909316 6.09627387592927e-05 0.999998967973261 -0.00143538704125832 -0.00223123395875384 0.00745144557431445 0.00143489293406483 0.999971208106074 -0.00231784825422484 3.62297176300537e-05 -3.81743953738331e-05 -8.76876157892035e-06 -4.19212895551146e-06 -1.29969703749776e-06 1.12577111906997e-05 -3.81743953738331e-05 6.06456639752122e-05 1.06623057299927e-05 1.13439496019678e-05 2.40412414065645e-06 -6.72300371145163e-06 -8.76876157892035e-06 1.06623057299927e-05 1.46341631268136e-05 -4.87133615275112e-06 -1.26992040847907e-06 -2.02352017564975e-06 -4.19212895551146e-06 1.13439496019678e-05 -4.87133615275112e-06 4.73970969681692e-05 1.13856326869025e-05 8.18448928121082e-06 -1.29969703749776e-06 2.40412414065645e-06 -1.26992040847907e-06 1.13856326869025e-05 2.55972380757445e-05 -2.79190524864266e-06 1.12577111906997e-05 -6.72300371145163e-06 -2.02352017564975e-06 8.18448928121082e-06 -2.79190524864266e-06 2.72183308756589e-05 1066 1070 0 15 0 1067 1090 0 39 0 0 0 0 0 0 15 37 0 2887 0 0 0 0 0 2158 +926 929 0.99976632731558 -0.0211560976800466 0.00443962801009122 -0.000391168420329536 0.0210578413627851 0.99955515368962 0.0211201810991133 0.00370391848368086 -0.00488447367230459 -0.0210217569073541 0.999767086702434 -0.0106774698064362 3.51008449400763e-05 -4.15692239944315e-05 -6.46721437507468e-06 -8.56098352342598e-06 -6.01126955695948e-06 1.61739518714122e-05 -4.15692239944315e-05 7.4983029440826e-05 8.59764590090045e-06 2.43913494197814e-05 1.46025374371921e-05 -1.8527097869188e-05 -6.46721437507468e-06 8.59764590090045e-06 1.02579821223881e-05 -1.45916852763086e-06 1.68909462004152e-06 -2.83535458614774e-06 -8.56098352342598e-06 2.43913494197814e-05 -1.45916852763086e-06 4.93240002414158e-05 1.28465040658592e-05 -7.02778344014142e-07 -6.01126955695948e-06 1.46025374371921e-05 1.68909462004152e-06 1.28465040658592e-05 2.60602237283115e-05 -5.76149940801536e-06 1.61739518714122e-05 -1.8527097869188e-05 -2.83535458614774e-06 -7.02778344014142e-07 -5.76149940801536e-06 2.86787336126406e-05 998 997 0 1 0 1016 1016 0 13 0 0 0 0 0 0 38 62 0 3027 0 0 0 0 0 2019 +923 927 0.999992782604217 0.000116810454199075 -0.00379751165794102 -0.00248119778511331 -0.00011571877714351 0.999999951921775 0.000287690131366772 -0.000308657494522162 0.00379754508057832 -0.000287248611587987 0.999992748043503 0.00331084284867394 4.04953687451887e-05 -4.59482399555853e-05 -8.12174585142668e-06 -2.50381908581704e-06 -2.64943284979729e-06 1.56216854537382e-05 -4.59482399555853e-05 7.88804876238788e-05 1.13082352159071e-05 1.77478216678875e-05 9.01553177862583e-06 -1.16762038449092e-05 -8.12174585142668e-06 1.13082352159071e-05 1.22032327571722e-05 -4.21375247317328e-06 3.41937696632096e-06 -2.03656963905338e-06 -2.50381908581704e-06 1.77478216678875e-05 -4.21375247317328e-06 4.89616581202953e-05 9.04775713431204e-06 9.61229749414665e-06 -2.64943284979729e-06 9.01553177862583e-06 3.41937696632096e-06 9.04775713431204e-06 2.26795546608267e-05 -6.36182269283874e-07 1.56216854537382e-05 -1.16762038449092e-05 -2.03656963905338e-06 9.61229749414665e-06 -6.36182269283874e-07 3.78747916235138e-05 1029 1029 0 13 0 1028 1051 0 41 0 0 0 0 0 0 16 42 0 2970 0 0 0 0 0 2310 +926 928 0.999995596373605 -6.79925324095854e-05 -0.00296691934747288 -0.002322723256977 6.51663527897381e-05 0.999999544105598 -0.000952649957644149 -0.00146797352790809 0.00296698276795408 0.000952452419216754 0.999995144912036 -0.00350958625064988 2.46100977311025e-05 -2.43671451876612e-05 -4.62479540656159e-06 3.1718616285837e-07 -7.36584083601968e-07 1.03896749289204e-05 -2.43671451876612e-05 3.50751019282679e-05 6.14071885438115e-06 2.84088868935519e-06 2.73205875208965e-06 -7.80332666970199e-06 -4.62479540656159e-06 6.14071885438115e-06 1.11322282148994e-05 -5.52201514019417e-06 2.29675183676106e-06 -2.06411071483205e-06 3.1718616285837e-07 2.84088868935519e-06 -5.52201514019417e-06 4.06205501303319e-05 8.6510861150257e-06 5.83324752460543e-06 -7.36584083601968e-07 2.73205875208965e-06 2.29675183676106e-06 8.6510861150257e-06 2.13787531079102e-05 -1.16106607980033e-06 1.03896749289204e-05 -7.80332666970199e-06 -2.06411071483205e-06 5.83324752460543e-06 -1.16106607980033e-06 2.25288101819232e-05 1101 1099 0 18 0 1100 1116 0 35 0 0 0 0 0 0 17 39 0 2868 0 0 0 0 0 2158 +927 929 0.999758085999572 -0.0215012121583174 0.00463328762277671 -0.000782910888193552 0.0214096811443782 0.999590728867753 0.0189736742601345 0.000394781386629004 -0.00503934834759527 -0.0188698870520376 0.999809247972269 -0.00995490105416857 4.36957993766232e-05 -5.33119109590098e-05 -8.51235024129775e-06 -1.3803058101699e-05 -1.29596428787799e-05 1.97887251350374e-05 -5.33119109590098e-05 0.00010566663092502 1.15283563274936e-05 4.75391820881516e-05 2.57216874209583e-05 -2.80367708765731e-05 -8.51235024129775e-06 1.15283563274936e-05 1.10533999345581e-05 -9.85000836296493e-07 3.09630120682186e-06 -4.50277398324924e-06 -1.3803058101699e-05 4.75391820881516e-05 -9.85000836296493e-07 6.78431148697341e-05 1.75189225958358e-05 -4.98896987830801e-06 -1.29596428787799e-05 2.57216874209583e-05 3.09630120682186e-06 1.75189225958358e-05 2.81409716239984e-05 -9.94907058330893e-06 1.97887251350374e-05 -2.80367708765731e-05 -4.50277398324924e-06 -4.98896987830801e-06 -9.94907058330893e-06 3.26266645601746e-05 981 979 0 1 0 1007 1007 0 11 0 0 0 0 0 0 39 63 0 3027 0 0 0 0 0 2030 +925 927 0.999991959537229 0.000116659648658471 -0.00400839761236713 -0.00307601409391996 -0.000127656863818464 0.999996228729347 -0.00274339767614697 -0.00205619331394079 0.00400806245180582 0.00274388731742822 0.999988203189303 -0.00294481895032978 4.16797212518879e-05 -4.88891422180755e-05 -6.48778992759242e-06 -1.03857950406927e-05 -5.40006071043448e-06 1.23083507146306e-05 -4.88891422180755e-05 7.8159989355823e-05 6.64377899266216e-06 2.90226905510179e-05 1.42270679911282e-05 -1.52473003891805e-05 -6.48778992759242e-06 6.64377899266216e-06 1.17088373600464e-05 -6.66793268721462e-06 2.60092736198108e-06 -2.8297206680848e-06 -1.03857950406927e-05 2.90226905510179e-05 -6.66793268721462e-06 6.36568791639219e-05 1.90843716997315e-05 7.45232130974967e-06 -5.40006071043448e-06 1.42270679911282e-05 2.60092736198108e-06 1.90843716997315e-05 2.75377227635304e-05 -4.3083546028893e-07 1.23083507146306e-05 -1.52473003891805e-05 -2.8297206680848e-06 7.45232130974967e-06 -4.3083546028893e-07 3.85790776767415e-05 1045 1045 0 13 0 1047 1071 0 38 0 0 0 0 0 0 15 43 0 2980 0 0 0 0 0 2203 +930 871 0.986636267748268 0.0782802600048102 -0.142902330482561 0.0384491431753887 -0.0968482435301334 0.987036886138431 -0.127978916729587 0.0116966820716083 0.131031648424706 0.140108480456145 0.981427695154042 0.0418653907185192 6.47992715680779e-05 -0.000102160249814121 1.32547828474289e-05 -2.58167969549696e-05 -9.86320883193453e-06 1.08476885576617e-05 -0.000102160249814121 0.0002813289210252 -2.97821249516744e-05 9.92485511938938e-05 3.58156314087624e-05 7.56098559798652e-07 1.32547828474289e-05 -2.97821249516744e-05 1.66122839974969e-05 -1.35033401885348e-05 -6.14454044712064e-06 -9.52457691112638e-07 -2.58167969549696e-05 9.92485511938938e-05 -1.35033401885348e-05 0.000107546019437769 3.83841310702827e-05 6.82821807113223e-06 -9.86320883193453e-06 3.58156314087624e-05 -6.14454044712064e-06 3.83841310702827e-05 4.08526364946728e-05 3.64643541380444e-06 1.08476885576617e-05 7.56098559798652e-07 -9.52457691112638e-07 6.82821807113223e-06 3.64643541380444e-06 3.67529623957709e-05 763 772 0 96 0 763 772 0 105 0 0 0 0 0 0 0 0 0 2245 0 0 0 0 0 1500 +930 898 0.994705576844535 0.0821741479308477 -0.0617108159581534 0.00202871455458755 -0.0832760623019576 0.996406007711088 -0.0154972657179317 -0.00935163482262731 0.0602155531558283 0.0205542503899041 0.997973752134317 0.0447904290469575 4.59451712842312e-05 -4.9487255910039e-05 -8.50666685716881e-07 -7.64823384354177e-06 -6.96321200166985e-06 1.03580022423021e-05 -4.9487255910039e-05 0.00012086262104573 -5.9375243694007e-07 4.12000258015183e-05 1.77384148522901e-05 2.26169880579371e-06 -8.50666685716881e-07 -5.9375243694007e-07 9.85678742957968e-06 -4.78526143145405e-06 2.26619598525863e-06 -2.58002794442641e-06 -7.64823384354177e-06 4.12000258015183e-05 -4.78526143145405e-06 6.80309262569662e-05 1.75900939382765e-05 3.66100473093138e-06 -6.96321200166985e-06 1.77384148522901e-05 2.26619598525863e-06 1.75900939382765e-05 2.6521573295284e-05 2.74450210541293e-06 1.03580022423021e-05 2.26169880579371e-06 -2.58002794442641e-06 3.66100473093138e-06 2.74450210541293e-06 2.99009149802505e-05 964 983 0 140 0 964 983 0 158 0 0 0 0 0 0 0 0 0 2887 0 0 0 0 0 1668 +930 899 0.995072290571656 0.0818573732401377 -0.0559509337071638 0.00358939522048257 -0.082869192602211 0.996431889724691 -0.0160058132295532 -0.0106813233397951 0.0544411007781467 0.0205635499344461 0.998305217335939 0.0434045572889863 2.61972252905365e-05 -2.6632803699579e-05 -7.69505821600556e-07 -2.32375341966643e-06 -6.1970256817159e-06 7.7983075702237e-06 -2.6632803699579e-05 6.77439913548107e-05 1.00149831797914e-06 1.93556484918046e-05 1.33223035066713e-05 1.87123761605854e-06 -7.69505821600556e-07 1.00149831797914e-06 9.26653776196395e-06 -3.05333203832498e-06 2.23281926038466e-06 -1.22062673517048e-06 -2.32375341966643e-06 1.93556484918046e-05 -3.05333203832498e-06 5.50085127612807e-05 1.23085466236096e-05 3.70943498545735e-06 -6.1970256817159e-06 1.33223035066713e-05 2.23281926038466e-06 1.23085466236096e-05 2.47472866475884e-05 3.53726144827113e-06 7.7983075702237e-06 1.87123761605854e-06 -1.22062673517048e-06 3.70943498545735e-06 3.53726144827113e-06 2.91902644236336e-05 983 1006 0 145 0 983 1006 0 163 0 0 0 0 0 0 0 0 0 2916 0 0 0 0 0 1648 +930 900 0.994765428059855 0.082043201470695 -0.0609151559903722 0.00481649230728458 -0.0831749782407047 0.996402000491252 -0.0162780960707576 -0.00987942917140759 0.0593604761735511 0.021259503979855 0.9980102040355 0.0464400388630909 3.75077602801725e-05 -3.78967455297121e-05 3.72796903029512e-06 -1.81964204756819e-06 -5.03534538135202e-06 7.24192391615213e-06 -3.78967455297121e-05 5.80177605725822e-05 -4.65102865014864e-06 1.17561760926339e-05 1.01003633619543e-05 9.51442734130866e-07 3.72796903029512e-06 -4.65102865014864e-06 1.01015934306434e-05 -3.20647293027175e-06 1.54383906452374e-06 2.64139502624652e-07 -1.81964204756819e-06 1.17561760926339e-05 -3.20647293027175e-06 6.99234814571824e-05 1.98359898205764e-05 4.29032944299494e-06 -5.03534538135202e-06 1.01003633619543e-05 1.54383906452374e-06 1.98359898205764e-05 2.71445487398927e-05 4.19693869443258e-06 7.24192391615213e-06 9.51442734130866e-07 2.64139502624652e-07 4.29032944299494e-06 4.19693869443258e-06 2.70467563297184e-05 1003 1025 0 144 0 1003 1025 0 158 0 0 0 0 0 0 0 0 0 2810 0 0 0 0 0 1534 +930 872 0.986465200005187 0.0641174211950505 -0.150915093605722 0.026484743538901 -0.0855724251895212 0.986409089138812 -0.140265708252311 0.0102747885581943 0.139870544525684 0.151281410502531 0.978544922632811 0.0444290407049283 5.45118806637599e-05 -7.4088388498354e-05 1.19192256164713e-05 -1.57926623623472e-05 -9.4313539402278e-06 8.10285468807006e-06 -7.4088388498354e-05 0.000313049426220416 -2.85365330992638e-05 0.000113718614639442 3.77226306520644e-05 1.44273111278306e-05 1.19192256164713e-05 -2.85365330992638e-05 1.3819869016719e-05 -8.37656546246586e-06 -3.8332578235492e-06 -9.07686877520137e-07 -1.57926623623472e-05 0.000113718614639442 -8.37656546246586e-06 8.34639944945324e-05 1.64358168777337e-05 1.65541051574643e-05 -9.4313539402278e-06 3.77226306520644e-05 -3.8332578235492e-06 1.64358168777337e-05 3.15824566163451e-05 6.70284468090523e-06 8.10285468807006e-06 1.44273111278306e-05 -9.07686877520137e-07 1.65541051574643e-05 6.70284468090523e-06 3.90609058610138e-05 778 786 0 84 0 778 786 0 92 0 0 0 0 0 0 0 0 0 2164 0 0 0 0 0 1768 +925 929 0.99977574049095 -0.0211527731798458 -0.00101435327865228 -0.00584880404640701 0.0211681961590395 0.999596545119152 0.0189381746012775 -2.78755538140779e-05 0.00061334912108996 -0.0189553995647161 0.999820142140674 -0.00946649070721232 3.04466248338519e-05 -2.87206342994516e-05 -7.20419927975745e-06 2.26797680435896e-06 2.50283457301419e-07 1.191644795932e-05 -2.87206342994516e-05 4.39210845601886e-05 7.40242098077099e-06 1.07157141360102e-05 6.45233310949888e-06 -1.06822254820374e-05 -7.20419927975745e-06 7.40242098077099e-06 1.08244132904284e-05 -2.03806635084447e-06 9.75248557814796e-07 -3.39186325787925e-06 2.26797680435896e-06 1.07157141360102e-05 -2.03806635084447e-06 4.70242239510169e-05 6.58336058644073e-06 6.07635481430069e-06 2.50283457301419e-07 6.45233310949888e-06 9.75248557814796e-07 6.58336058644073e-06 2.15876675962138e-05 -2.90117811741828e-06 1.191644795932e-05 -1.06822254820374e-05 -3.39186325787925e-06 6.07635481430069e-06 -2.90117811741828e-06 2.77122405056184e-05 1030 1030 0 0 0 1043 1043 0 10 0 0 0 0 0 0 36 60 0 3041 0 0 0 0 0 1745 +930 870 0.988938472472977 0.0790395803714647 -0.125512718070792 0.0290407658244314 -0.095975174548705 0.986160723058561 -0.13518799564666 0.00648121213473604 0.113090510358567 0.145738714936418 0.982838116596788 0.0322196067839871 3.85138334178522e-05 -3.96620845716877e-05 7.94435418074742e-06 -1.00343480982112e-06 9.2382773687533e-07 1.11533527987035e-05 -3.96620845716877e-05 8.47939798800999e-05 -1.16472433746725e-05 1.99225145322771e-05 4.70793414788338e-06 -3.72893150540797e-07 7.94435418074742e-06 -1.16472433746725e-05 1.32895547841534e-05 -4.88859820530569e-06 1.7554022244639e-06 2.42456978965552e-06 -1.00343480982112e-06 1.99225145322771e-05 -4.88859820530569e-06 5.36859423274001e-05 9.62956042952632e-06 6.42456308102971e-06 9.2382773687533e-07 4.70793414788338e-06 1.7554022244639e-06 9.62956042952632e-06 2.4075594191871e-05 4.46632308100703e-06 1.11533527987035e-05 -3.72893150540797e-07 2.42456978965552e-06 6.42456308102971e-06 4.46632308100703e-06 3.09216540405376e-05 892 903 0 115 0 892 903 0 122 0 0 0 0 0 0 0 0 0 2184 0 0 0 0 0 1673 +930 892 0.994953521191266 0.0814206208675941 -0.0586359375011266 0.00466653210789876 -0.0825697352402065 0.996432596917695 -0.0174447305000713 -0.0105245329746855 0.0570063986887676 0.0221982498723079 0.998127000041149 0.04651329562367 2.86993482771856e-05 -3.08564468494896e-05 -3.73580460389552e-06 -1.27967502714806e-07 -7.44065787276302e-07 1.07960093679359e-05 -3.08564468494896e-05 8.18463570580153e-05 2.64896298246254e-06 2.08512152383932e-05 8.92225639894059e-06 -1.93045582172859e-06 -3.73580460389552e-06 2.64896298246254e-06 9.53449874856104e-06 -2.4025959406538e-06 1.99059128481322e-06 -2.20774475643024e-06 -1.27967502714806e-07 2.08512152383932e-05 -2.4025959406538e-06 4.88528026820938e-05 9.03852546475626e-06 6.19869161547842e-06 -7.44065787276302e-07 8.92225639894059e-06 1.99059128481322e-06 9.03852546475626e-06 2.16225438186108e-05 4.97139050715183e-06 1.07960093679359e-05 -1.93045582172859e-06 -2.20774475643024e-06 6.19869161547842e-06 4.97139050715183e-06 2.51324696604096e-05 987 1011 0 148 0 987 1011 0 164 0 0 0 0 0 0 0 0 0 2899 0 0 0 0 0 1761 +930 873 0.988333648369163 0.051970115428127 -0.143163216657376 0.0239931561893494 -0.0730651502387485 0.986541069517251 -0.146281242735858 0.0161373754164528 0.133634139806745 0.15503491625484 0.978828938793682 0.0431680903821064 4.6120525864927e-05 -5.50655299398803e-05 1.41298066014783e-05 -2.21611620491944e-05 -5.60810034005424e-06 1.20163425722675e-05 -5.50655299398803e-05 0.000100285765781664 -2.05887364116663e-05 5.228206223204e-05 1.88698275250101e-05 2.13206965323583e-06 1.41298066014783e-05 -2.05887364116663e-05 1.53039881224379e-05 -9.42529997078828e-06 -2.26986734898088e-06 2.2389950896503e-06 -2.21611620491944e-05 5.228206223204e-05 -9.42529997078828e-06 7.05606901639601e-05 1.74524659008088e-05 1.1808651046932e-05 -5.60810034005424e-06 1.88698275250101e-05 -2.26986734898088e-06 1.74524659008088e-05 3.35418106976551e-05 7.72813713796104e-06 1.20163425722675e-05 2.13206965323583e-06 2.2389950896503e-06 1.1808651046932e-05 7.72813713796104e-06 3.51036658813311e-05 796 801 0 69 0 796 801 0 74 0 0 0 0 0 0 0 0 0 2073 0 0 0 0 0 1417 +930 895 0.994978281733773 0.0818170259823726 -0.05765581616375 0.00412929111404762 -0.0828544291555492 0.996435857812337 -0.0158342930091998 -0.0112619732734101 0.0561548078744504 0.0205318173865075 0.998210940647011 0.0444451775696236 2.75319780960718e-05 -2.41970791662942e-05 -1.10476341854357e-06 3.61661171565905e-06 9.07261955848058e-07 1.06294093078537e-05 -2.41970791662942e-05 5.89092881798789e-05 1.04817831664368e-06 1.09256551355526e-05 4.40956799486607e-06 2.88482262695635e-07 -1.10476341854357e-06 1.04817831664368e-06 9.27425800316165e-06 -1.8786022272708e-06 2.2060024852917e-06 -1.02234948793597e-06 3.61661171565905e-06 1.09256551355526e-05 -1.8786022272708e-06 4.71953101062232e-05 4.72664813885693e-06 -1.91263568332348e-06 9.07261955848058e-07 4.40956799486607e-06 2.2060024852917e-06 4.72664813885693e-06 2.06033483331657e-05 2.03534402981414e-06 1.06294093078537e-05 2.88482262695635e-07 -1.02234948793597e-06 -1.91263568332348e-06 2.03534402981414e-06 3.09119328676841e-05 951 976 0 148 0 951 976 0 158 0 0 0 0 0 0 0 0 0 2816 0 0 0 0 0 1685 +930 896 0.995360319318734 0.0822771672802518 -0.0498828875471929 0.0113043596932992 -0.0831056817341794 0.996431344073322 -0.0147655752251742 -0.00752924808679685 0.0484900029821169 0.0188426190475331 0.998645920893999 0.0456368852920657 4.71323844082939e-05 -7.33637247756091e-05 1.05532189366698e-07 -2.42821119696306e-05 -1.5248962673663e-05 1.51963024947522e-05 -7.33637247756091e-05 0.00024448250701217 -2.86779869821413e-06 0.000125981147577955 6.01470957493653e-05 -6.29869673642504e-06 1.05532189366698e-07 -2.86779869821413e-06 9.65194975966558e-06 -6.52004958298301e-06 2.42262132451862e-06 -2.07247713265839e-06 -2.42821119696306e-05 0.000125981147577955 -6.52004958298301e-06 0.000124071711220456 4.24617303072447e-05 3.74405918996273e-06 -1.5248962673663e-05 6.01470957493653e-05 2.42262132451862e-06 4.24617303072447e-05 3.69140871660618e-05 9.29197226742315e-07 1.51963024947522e-05 -6.29869673642504e-06 -2.07247713265839e-06 3.74405918996273e-06 9.29197226742315e-07 3.14046896806791e-05 947 969 0 151 0 947 969 0 164 0 0 0 0 0 0 0 0 0 2800 0 0 0 0 0 1631 +930 897 0.994842667139855 0.0816273941330399 -0.0602082732280985 0.00310116131318033 -0.0827638436099056 0.9964305029912 -0.0166252488588441 -0.0109069867876112 0.0586362842357451 0.0215225750260691 0.998047376097584 0.0456114136725884 2.89772966130278e-05 -3.15403750269615e-05 5.64055148800937e-07 -7.92765662036016e-07 -2.5645462591268e-06 2.86825160243077e-06 -3.15403750269615e-05 6.60519388608074e-05 -2.48646595001811e-06 1.39689236858692e-05 8.69159330363382e-06 9.8450358833529e-06 5.64055148800937e-07 -2.48646595001811e-06 8.85487129649508e-06 -3.60470805144533e-06 1.64435887569489e-06 -2.84872399187155e-06 -7.92765662036016e-07 1.39689236858692e-05 -3.60470805144533e-06 5.54008650897884e-05 1.46320900645574e-05 1.10303831874934e-05 -2.5645462591268e-06 8.69159330363382e-06 1.64435887569489e-06 1.46320900645574e-05 2.31588527032258e-05 7.36337852711825e-06 2.86825160243077e-06 9.8450358833529e-06 -2.84872399187155e-06 1.10303831874934e-05 7.36337852711825e-06 3.3526349925371e-05 997 1015 0 136 0 997 1015 0 155 0 0 0 0 0 0 0 0 0 2772 0 0 0 0 0 1538 +930 901 0.995290358375399 0.0822910288633131 -0.0512375750166601 0.00967408238803307 -0.0831596102247594 0.996422531208017 -0.0150538542664046 -0.00851630656859954 0.0498154770351203 0.0192438527749882 0.998573028064617 0.0450388185878922 4.0103980136563e-05 -5.42327943135349e-05 7.86710573700796e-07 -9.36851806150381e-06 -6.06125700824024e-06 1.52302898820709e-05 -5.42327943135349e-05 0.000149183734898418 -2.02894727260458e-06 5.79946830628464e-05 2.46527623483012e-05 -1.06218205687969e-05 7.86710573700796e-07 -2.02894727260458e-06 9.50574648138408e-06 -4.45961926389427e-06 2.68398214529982e-06 -9.7610636307417e-07 -9.36851806150381e-06 5.79946830628464e-05 -4.45961926389427e-06 8.74561802994055e-05 2.5026454092134e-05 1.43779080944505e-06 -6.06125700824024e-06 2.46527623483012e-05 2.68398214529982e-06 2.5026454092134e-05 2.85736321356338e-05 -6.95571766289346e-08 1.52302898820709e-05 -1.06218205687969e-05 -9.7610636307417e-07 1.43779080944505e-06 -6.95571766289346e-08 2.99268042692658e-05 964 980 0 151 0 964 980 0 166 0 0 0 0 0 0 0 0 0 2771 0 0 0 0 0 1562 +930 894 0.994872385457703 0.0821570645754934 -0.0589843487209806 0.00286155544504583 -0.0832451042440008 0.996396959134303 -0.0162281375184787 -0.0111284984355548 0.0574385695600568 0.0210550841425871 0.998126993001714 0.0460225274811829 3.92759867410633e-05 -4.27299569009221e-05 3.62845159075996e-06 -6.85307765581686e-06 -7.30437363964746e-06 9.78693306082674e-06 -4.27299569009221e-05 9.66491908073164e-05 -3.2418419334701e-06 2.94843113275749e-05 1.43707760244324e-05 2.20916176919092e-06 3.62845159075996e-06 -3.2418419334701e-06 9.5381757714048e-06 -2.58183635505989e-06 1.40310080316909e-06 1.39332254185056e-06 -6.85307765581686e-06 2.94843113275749e-05 -2.58183635505989e-06 5.72588799759436e-05 1.55515639384726e-05 1.25315442568362e-06 -7.30437363964746e-06 1.43707760244324e-05 1.40310080316909e-06 1.55515639384726e-05 2.53620950530007e-05 4.7706780782127e-07 9.78693306082674e-06 2.20916176919092e-06 1.39332254185056e-06 1.25315442568362e-06 4.7706780782127e-07 3.26254963493364e-05 973 993 0 147 0 973 993 0 161 0 0 0 0 0 0 0 0 0 2757 0 0 0 0 0 1707 +930 902 0.995040246950969 0.08229402944522 -0.0558802260681125 0.00779957609787223 -0.0832659209409478 0.996410075492503 -0.0152888150907865 -0.00873075354129138 0.0544214420758024 0.0198659048294736 0.998320415732192 0.0443311652680557 3.95522454451833e-05 -4.86599320883366e-05 -2.22811753775898e-06 3.38371941504688e-07 -3.11300720810175e-06 1.01408090992143e-05 -4.86599320883366e-05 0.000132622499018986 2.0781637160751e-06 3.19482028288803e-05 1.32925699684975e-05 -1.35661671668761e-05 -2.22811753775898e-06 2.0781637160751e-06 8.89304557354438e-06 -1.1991194684069e-06 3.25438137850319e-06 -1.77115534526367e-06 3.38371941504688e-07 3.19482028288803e-05 -1.1991194684069e-06 5.98004899450076e-05 8.02317723669376e-06 -2.24997291786713e-06 -3.11300720810175e-06 1.32925699684975e-05 3.25438137850319e-06 8.02317723669376e-06 2.07130296325433e-05 6.19997838925848e-07 1.01408090992143e-05 -1.35661671668761e-05 -1.77115534526367e-06 -2.24997291786713e-06 6.19997838925848e-07 3.29776337253562e-05 961 980 0 139 0 961 980 0 156 0 0 0 0 0 0 0 0 0 2873 0 0 0 0 0 1642 +930 927 0.995670527958745 0.0816078424323966 -0.0445012337793354 0.00885064813933802 -0.0823298741364061 0.996497627471437 -0.0146379735100498 -0.0113829373437438 0.0431508004449217 0.0182383797889649 0.998902082250125 0.0438374875527277 3.16056254008363e-05 -3.48801243003023e-05 -2.35946960117398e-06 -1.00309229978695e-06 -2.30811874650214e-06 9.18227190429588e-06 -3.48801243003023e-05 9.73294591197526e-05 3.66734257313023e-06 2.36439998972129e-05 1.28414036204628e-05 -3.32533310883387e-06 -2.35946960117398e-06 3.66734257313023e-06 9.53195104553373e-06 -1.99396455976379e-06 1.83076637805889e-06 -1.7132788428051e-06 -1.00309229978695e-06 2.36439998972129e-05 -1.99396455976379e-06 4.64643698988874e-05 1.03777442283924e-05 5.96084265938304e-06 -2.30811874650214e-06 1.28414036204628e-05 1.83076637805889e-06 1.03777442283924e-05 2.31428488694344e-05 1.56997678880094e-06 9.18227190429588e-06 -3.32533310883387e-06 -1.7132788428051e-06 5.96084265938304e-06 1.56997678880094e-06 2.6954933498632e-05 935 956 0 146 0 935 956 0 157 0 0 0 0 0 0 0 0 0 2843 0 0 0 0 0 2001 +930 889 0.992999568741466 0.0778476335886677 -0.0888346915563239 0.0122854891484883 -0.0834656312783258 0.994618537471843 -0.0613795838425359 -0.0011951966897236 0.0835783756397145 0.0683645438953327 0.99415338065281 0.0429819574292201 3.06988568999156e-05 -3.05087415595088e-05 4.06652276644393e-06 -6.58691050504602e-07 3.45145571714531e-07 7.08384848808656e-06 -3.05087415595088e-05 5.78771715289922e-05 -5.46898256584481e-06 9.62493957095161e-06 7.09609196968152e-06 3.74233761095423e-06 4.06652276644393e-06 -5.46898256584481e-06 9.98776266552745e-06 -4.61192259144794e-07 2.37111182495698e-06 -1.95979777335604e-07 -6.58691050504602e-07 9.62493957095161e-06 -4.61192259144794e-07 3.83431195967548e-05 4.15700678109889e-06 1.37661758042145e-06 3.45145571714531e-07 7.09609196968152e-06 2.37111182495698e-06 4.15700678109889e-06 1.85960679608647e-05 6.06606242445798e-06 7.08384848808656e-06 3.74233761095423e-06 -1.95979777335604e-07 1.37661758042145e-06 6.06606242445798e-06 2.91656283337206e-05 894 912 0 115 0 894 912 0 126 0 0 0 0 0 0 0 0 0 2535 0 0 0 0 0 1725 +930 891 0.995310977162246 0.0814472746956564 -0.0521766248906954 0.00915839947029509 -0.0824766314239393 0.996432500403166 -0.0178851169762307 -0.00895792198645244 0.0505337907671067 0.0221046055143283 0.998477702508054 0.0454365667407909 3.92090492323701e-05 -4.37418220950259e-05 -5.04291056900215e-06 2.05079604600858e-06 -1.6616545878521e-06 1.1742565839402e-05 -4.37418220950259e-05 9.66514424999238e-05 5.16207462288839e-06 1.6887631573738e-05 8.65515486307303e-06 -9.36495405152073e-06 -5.04291056900215e-06 5.16207462288839e-06 1.0641564824726e-05 -4.29334793767396e-06 2.18733133841264e-06 -4.08538625519889e-06 2.05079604600858e-06 1.6887631573738e-05 -4.29334793767396e-06 4.70445414165882e-05 7.86254288989545e-06 1.43256594703782e-06 -1.6616545878521e-06 8.65515486307303e-06 2.18733133841264e-06 7.86254288989545e-06 2.36278173399683e-05 5.10911590624068e-06 1.1742565839402e-05 -9.36495405152073e-06 -4.08538625519889e-06 1.43256594703782e-06 5.10911590624068e-06 3.22301591696146e-05 934 959 0 146 0 934 959 0 166 0 0 0 0 0 0 0 0 0 2783 0 0 0 0 0 1663 +930 928 0.995676504221859 0.0817341872242507 -0.0441341316820508 0.0140374250219708 -0.0824881263989828 0.99647091507362 -0.0155378381870678 -0.0106159348623203 0.0427084060077509 0.0191112022419629 0.998904777246132 0.0483374470718042 3.39775936130383e-05 -3.83780871285295e-05 -1.55256554832198e-06 4.16136308079987e-06 -1.229091331832e-06 1.45322469030094e-05 -3.83780871285295e-05 0.000120437376785611 1.87150565914338e-06 3.31585188177103e-05 1.21658501326052e-05 -8.85412838432429e-06 -1.55256554832198e-06 1.87150565914338e-06 1.01305211557533e-05 -2.37975964320268e-06 1.85496680570279e-06 -1.20908772959408e-06 4.16136308079987e-06 3.31585188177103e-05 -2.37975964320268e-06 5.84695449118616e-05 6.14415834114602e-06 1.18768487699258e-05 -1.229091331832e-06 1.21658501326052e-05 1.85496680570279e-06 6.14415834114602e-06 2.52777806718875e-05 4.8125291663217e-06 1.45322469030094e-05 -8.85412838432429e-06 -1.20908772959408e-06 1.18768487699258e-05 4.8125291663217e-06 3.10678384954499e-05 943 962 0 148 0 943 962 0 158 0 0 0 0 0 0 0 0 0 2739 0 0 0 0 0 1568 +930 903 0.994729836001035 0.0820208065055234 -0.0615234968896998 0.00516074230314285 -0.0832473893996713 0.996372746628025 -0.0176414833578312 -0.0101221320027043 0.0598533668851878 0.0226701803501568 0.997949716867237 0.0448680944417806 3.86725295522232e-05 -4.4439932282976e-05 -2.78045267244397e-06 -1.27906818960178e-06 -1.40735371868433e-06 1.4847279181431e-06 -4.4439932282976e-05 0.00010098377124464 4.35876069649626e-07 3.27211034638696e-05 1.27575480765277e-05 1.39812581145172e-05 -2.78045267244397e-06 4.35876069649626e-07 9.04290956126773e-06 -2.35793499653888e-06 2.56819052473176e-06 -2.44034260153487e-06 -1.27906818960178e-06 3.27211034638696e-05 -2.35793499653888e-06 5.63543141291897e-05 1.04020639488991e-05 8.00618823278249e-06 -1.40735371868433e-06 1.27575480765277e-05 2.56819052473176e-06 1.04020639488991e-05 1.99876395886603e-05 4.16517484625789e-06 1.4847279181431e-06 1.39812581145172e-05 -2.44034260153487e-06 8.00618823278249e-06 4.16517484625789e-06 3.17726804001246e-05 967 989 0 142 0 967 989 0 159 0 0 0 0 0 0 0 0 0 2798 0 0 0 0 0 1928 +930 904 0.995070062630113 0.0820388646078761 -0.055724277932996 0.00789900344335292 -0.0830827759037441 0.996403068268424 -0.0166786658158986 -0.00875908379336741 0.0541555427027691 0.021226168733918 0.998306880150311 0.0440106327386094 4.93711130965704e-05 -7.08339285423426e-05 -1.01384873246605e-06 -8.50066710867568e-06 -4.71525280942784e-06 1.29056275917953e-05 -7.08339285423426e-05 0.000212522831436731 -9.37684251503562e-08 8.27594805610948e-05 3.28182032520358e-05 -3.76924587609192e-06 -1.01384873246605e-06 -9.37684251503562e-08 9.43437577880907e-06 -2.36223444084717e-06 2.51496091257752e-06 -1.40347634563487e-06 -8.50066710867568e-06 8.27594805610948e-05 -2.36223444084717e-06 8.24001295769713e-05 1.83292264442706e-05 5.26794227328153e-06 -4.71525280942784e-06 3.28182032520358e-05 2.51496091257752e-06 1.83292264442706e-05 2.34442195471132e-05 4.34150929168569e-06 1.29056275917953e-05 -3.76924587609192e-06 -1.40347634563487e-06 5.26794227328153e-06 4.34150929168569e-06 3.14458090916778e-05 897 918 0 149 0 897 918 0 157 0 0 0 0 0 0 0 0 0 2796 0 0 0 0 0 1984 +930 926 0.995066975397319 0.0815707714419781 -0.0564617013557967 0.00232931506250567 -0.0826457275461347 0.996434510885055 -0.0169690670229979 -0.0119977972257624 0.0548762078864848 0.0215516765849313 0.998260550680221 0.0439655234153561 3.93498533140197e-05 -6.03146698560616e-05 -3.0185131627202e-06 -1.47696418546963e-05 -7.33111080086701e-06 8.53508128712756e-06 -6.03146698560616e-05 0.000209189473354876 4.94523439160258e-06 7.99986864857571e-05 3.1314106931113e-05 -5.6887726017845e-06 -3.0185131627202e-06 4.94523439160258e-06 9.68162150508118e-06 -1.65920527689892e-06 2.02576596592978e-06 -2.31849487500929e-06 -1.47696418546963e-05 7.99986864857571e-05 -1.65920527689892e-06 7.48141222953249e-05 1.7237415194478e-05 6.19917657215102e-06 -7.33111080086701e-06 3.1314106931113e-05 2.02576596592978e-06 1.7237415194478e-05 2.63647792554081e-05 2.87380287018207e-06 8.53508128712756e-06 -5.6887726017845e-06 -2.31849487500929e-06 6.19917657215102e-06 2.87380287018207e-06 2.51796446528386e-05 942 962 0 143 0 942 962 0 157 0 0 0 0 0 0 0 0 0 2798 0 0 0 0 0 1985 +930 874 0.984587649062118 0.0551575589745435 -0.165966276701926 0.0226460336608858 -0.079309507577277 0.986595942070513 -0.142612934539076 0.0132890297057785 0.1558754737673 0.153577637623342 0.975764698018868 0.0483360060901274 4.41596399538271e-05 -5.25919023625172e-05 9.00869291025825e-06 -5.57909432071929e-06 -1.5801915512888e-06 1.22565350505462e-05 -5.25919023625172e-05 0.000102600385691471 -1.54483141312123e-05 2.91239133258733e-05 1.29232560083819e-05 1.42119159767764e-06 9.00869291025825e-06 -1.54483141312123e-05 1.32426126783882e-05 -5.18006251422979e-06 -1.73304733148844e-06 -1.61094453895352e-06 -5.57909432071929e-06 2.91239133258733e-05 -5.18006251422979e-06 5.13793274230758e-05 1.35350053300171e-05 1.87035672720754e-05 -1.5801915512888e-06 1.29232560083819e-05 -1.73304733148844e-06 1.35350053300171e-05 2.71928668690156e-05 1.09955077732308e-05 1.22565350505462e-05 1.42119159767764e-06 -1.61094453895352e-06 1.87035672720754e-05 1.09955077732308e-05 3.5927451004843e-05 760 766 0 66 0 760 766 0 69 0 0 0 0 0 0 0 0 0 2019 0 0 0 0 0 1484 +931 865 0.983329513596903 0.107895659069819 -0.146361178060195 0.00677728795819066 -0.122802685607381 0.987685023168177 -0.0969422272123539 -0.00257707780562671 0.134099098046533 0.113299698866176 0.984469710118062 0.084596321719262 3.63950827105727e-05 -3.29391289178769e-05 5.60106464685615e-06 4.36458246073912e-06 1.11115025632402e-07 1.31248887190115e-05 -3.29391289178769e-05 9.30347073829959e-05 -9.47185754937369e-06 1.85496596428222e-05 9.17896116391058e-06 -3.3866558335958e-06 5.60106464685615e-06 -9.47185754937369e-06 1.18033866439491e-05 -1.4577154079133e-06 1.21665178952893e-06 9.73166573267072e-07 4.36458246073912e-06 1.85496596428222e-05 -1.4577154079133e-06 4.67506837152367e-05 3.0869703970272e-06 5.59909794210395e-06 1.11115025632402e-07 9.17896116391058e-06 1.21665178952893e-06 3.0869703970272e-06 2.12555653209259e-05 2.85423550828997e-06 1.31248887190115e-05 -3.3866558335958e-06 9.73166573267072e-07 5.59909794210395e-06 2.85423550828997e-06 2.95318362607491e-05 897 900 0 135 0 897 900 0 145 0 0 0 0 0 0 0 0 0 2326 0 0 0 0 0 1642 +931 866 0.985804064848083 0.111245743034198 -0.125756631577682 0.00569888352706468 -0.124672225698627 0.986682441362721 -0.104472944085307 -0.00527878393074088 0.11245968997088 0.118668212101094 0.986544815793172 0.0825484363346692 3.23351799382685e-05 -1.85331684102742e-05 3.32757378865435e-06 -2.92445970349234e-06 -2.06252662880651e-07 2.96643784605306e-06 -1.85331684102742e-05 4.06876319268391e-05 -5.83330639558704e-06 1.1891048214528e-05 -2.72457799368288e-07 -1.42679113274747e-06 3.32757378865435e-06 -5.83330639558704e-06 1.30272803567783e-05 1.93356866488005e-06 -1.00870145760231e-06 3.88980441677755e-06 -2.92445970349234e-06 1.1891048214528e-05 1.93356866488005e-06 3.86687263870217e-05 5.25959692829359e-07 5.73801261977565e-06 -2.06252662880651e-07 -2.72457799368288e-07 -1.00870145760231e-06 5.25959692829359e-07 2.59822822516165e-05 -3.78288080350368e-07 2.96643784605306e-06 -1.42679113274747e-06 3.88980441677755e-06 5.73801261977565e-06 -3.78288080350368e-07 2.87179919909698e-05 864 871 0 141 0 864 871 0 151 0 0 0 0 0 0 0 0 0 2332 0 0 0 0 0 1303 +930 890 0.994626221381664 0.0794136891937192 -0.0664239844384199 0.00814381844533794 -0.0822211235083743 0.995784612348876 -0.0406533228435145 -0.00671895579008318 0.062915551249693 0.0458963155148834 0.996962969038021 0.0478912139535725 3.46498293096007e-05 -3.71094675816546e-05 -1.30795844077239e-07 -5.18859601273126e-06 -4.95906173059096e-07 1.68369488521533e-06 -3.71094675816546e-05 7.90771959922011e-05 1.11274577999992e-06 1.96523601750217e-05 4.23135272250237e-06 7.62585609591036e-06 -1.30795844077239e-07 1.11274577999992e-06 1.10729910091157e-05 -3.43827021793247e-06 -1.11364022957938e-07 2.36940962763697e-06 -5.18859601273126e-06 1.96523601750217e-05 -3.43827021793247e-06 6.29327542003005e-05 1.87149875642189e-05 6.18694458486206e-06 -4.95906173059096e-07 4.23135272250237e-06 -1.11364022957938e-07 1.87149875642189e-05 3.26998741302643e-05 2.29716075295993e-06 1.68369488521533e-06 7.62585609591036e-06 2.36940962763697e-06 6.18694458486206e-06 2.29716075295993e-06 3.26712360982942e-05 933 954 0 135 0 933 954 0 142 0 0 0 0 0 0 0 0 0 2623 0 0 0 0 0 1590 +930 888 0.991374662535208 0.0751982273007625 -0.107338274133814 0.0141789500151758 -0.0842879160902419 0.992993829482074 -0.0828178834050342 0.00332264986195609 0.100358485861273 0.0911508706560082 0.990767224475196 0.0444820409136349 3.70587538019325e-05 -3.64928768505788e-05 6.63585105278344e-06 -9.22215446103245e-07 -1.25693150549285e-06 8.14285005913717e-06 -3.64928768505788e-05 8.30028036451957e-05 -9.03555463325873e-06 2.03631916602077e-05 8.178830706955e-06 2.29586171211392e-06 6.63585105278344e-06 -9.03555463325873e-06 1.15229481015693e-05 -2.64778924651683e-06 2.2833580262067e-06 1.4778162418974e-06 -9.22215446103245e-07 2.03631916602077e-05 -2.64778924651683e-06 4.25851131133542e-05 4.8453468016566e-06 3.5187579646055e-06 -1.25693150549285e-06 8.178830706955e-06 2.2833580262067e-06 4.8453468016566e-06 2.18262428093132e-05 4.84592544609854e-06 8.14285005913717e-06 2.29586171211392e-06 1.4778162418974e-06 3.5187579646055e-06 4.84592544609854e-06 3.56390498928387e-05 895 907 0 114 0 895 907 0 124 0 0 0 0 0 0 0 0 0 2410 0 0 0 0 0 1360 +931 868 0.984211159622407 0.141110780309463 -0.10684634273185 0.00905418674178361 -0.153372635328 0.981231206468573 -0.11688521799087 -0.0110515343047583 0.0883472014681941 0.131427041101454 0.98738123582538 0.0844754852190458 3.40884169686913e-05 -4.14507394582798e-05 4.07101006109977e-06 3.47758095342907e-06 -1.13775350538027e-06 1.34686947610776e-05 -4.14507394582798e-05 0.000211636375252819 -1.47245224940787e-05 3.08621716389546e-05 4.98723876954641e-06 7.17356894569041e-06 4.07101006109977e-06 -1.47245224940787e-05 1.24942430872919e-05 -3.97548246705508e-06 9.50189580049124e-07 -8.07176062379022e-07 3.47758095342907e-06 3.08621716389546e-05 -3.97548246705508e-06 4.8231810422749e-05 -5.65622051379917e-06 1.20959376994847e-05 -1.13775350538027e-06 4.98723876954641e-06 9.50189580049124e-07 -5.65622051379917e-06 2.7381728914572e-05 4.5482653173454e-06 1.34686947610776e-05 7.17356894569041e-06 -8.07176062379022e-07 1.20959376994847e-05 4.5482653173454e-06 3.28021467798675e-05 848 849 0 161 0 848 849 0 169 0 0 0 0 0 0 0 0 0 2162 0 0 0 0 0 1467 +931 870 0.980203235488631 0.151198776639293 -0.127830149340448 0.00838685061232771 -0.165799999788591 0.979717161184002 -0.11253730115683 -0.0137028999184472 0.10822188876435 0.131503665440705 0.985390688391125 0.0885516108424345 3.40778097075435e-05 -3.36577219721293e-05 5.20136396145272e-06 -4.98002840784177e-06 -2.65899890408687e-06 4.59311090569699e-06 -3.36577219721293e-05 9.9781518240807e-05 -1.01845020080406e-05 2.39814200685812e-05 1.05640512375326e-05 1.33771454231657e-05 5.20136396145272e-06 -1.01845020080406e-05 1.27547910781658e-05 -4.09403479029315e-06 -5.07729838444528e-07 5.7907388002442e-07 -4.98002840784177e-06 2.39814200685812e-05 -4.09403479029315e-06 5.687959610407e-05 1.47255533936265e-05 8.35407289521315e-06 -2.65899890408687e-06 1.05640512375326e-05 -5.07729838444528e-07 1.47255533936265e-05 2.77250603132301e-05 4.19073467825473e-08 4.59311090569699e-06 1.33771454231657e-05 5.7907388002442e-07 8.35407289521315e-06 4.19073467825473e-08 3.58149232936427e-05 842 853 0 173 0 842 853 0 193 0 0 0 0 0 0 0 0 0 2102 0 0 0 0 0 1248 +931 863 0.986979852149422 0.101141266745257 -0.125064845629261 -0.00989349803448376 -0.111072868243232 0.990966579081759 -0.0751535566903974 0.00429417391561768 0.116333956312539 0.0880663573912306 0.989298098302282 0.0673080332867367 2.4918931108745e-05 -1.62356255976805e-05 7.12708140987921e-07 1.7387539665995e-06 1.27496557371804e-06 1.55369674518665e-05 -1.62356255976805e-05 3.73245319454879e-05 -1.08995451519005e-06 4.47330928882832e-06 2.09317490594498e-06 -5.34989103159339e-07 7.12708140987921e-07 -1.08995451519005e-06 1.19925640322189e-05 9.00805313743648e-07 6.24273683012631e-07 -2.43074988548631e-07 1.7387539665995e-06 4.47330928882832e-06 9.00805313743648e-07 3.89864037112607e-05 1.67857780471207e-06 9.59634867685156e-06 1.27496557371804e-06 2.09317490594498e-06 6.24273683012631e-07 1.67857780471207e-06 2.46521805098216e-05 2.84320256388079e-06 1.55369674518665e-05 -5.34989103159339e-07 -2.43074988548631e-07 9.59634867685156e-06 2.84320256388079e-06 3.87564083088376e-05 1035 1026 0 133 0 1035 1026 0 135 0 0 0 0 0 0 0 0 0 2568 0 0 0 0 0 1706 +931 864 0.983416352556398 0.0884598102570206 -0.158326054375021 -0.0176554167774722 -0.103424590132859 0.990655843235914 -0.0889064363158877 -0.00521156770448473 0.14898198441597 0.103806850601647 0.983376075612808 0.0731705681475806 5.43061001535243e-05 -5.81175331175218e-05 5.32888189403026e-06 -6.30114410618342e-06 -9.57354739653693e-06 -1.02888850536858e-05 -5.81175331175218e-05 0.000126798115114235 -9.0024432951475e-06 2.89035662192792e-05 1.75315625879316e-05 3.80751770760401e-05 5.32888189403026e-06 -9.0024432951475e-06 1.12803499450615e-05 -1.72431493543308e-06 -6.08076505577784e-07 -4.46489396714394e-06 -6.30114410618342e-06 2.89035662192792e-05 -1.72431493543308e-06 5.34514808612805e-05 1.34336289545975e-05 1.99057519162662e-05 -9.57354739653693e-06 1.75315625879316e-05 -6.08076505577784e-07 1.34336289545975e-05 2.68796428036218e-05 8.74736423417825e-06 -1.02888850536858e-05 3.80751770760401e-05 -4.46489396714394e-06 1.99057519162662e-05 8.74736423417825e-06 5.06290796591568e-05 918 922 0 111 0 918 922 0 116 0 0 0 0 0 0 0 0 0 2481 0 0 0 0 0 1634 +931 867 0.984429458178062 0.123125795532118 -0.125453897292312 0.00753588145012621 -0.138237522109399 0.983118610627926 -0.119867363857178 -0.00619513800825863 0.108577296670624 0.13534339995581 0.984831526067327 0.0858041462537213 4.51726565349871e-05 -4.35183890998316e-05 6.25004302114656e-06 -9.1188158444699e-06 -6.25778305777445e-06 6.45050318199009e-06 -4.35183890998316e-05 0.000167038429570749 -1.94500872486647e-05 5.32348183039125e-05 1.26166286606481e-05 7.34833844390182e-06 6.25004302114656e-06 -1.94500872486647e-05 1.5098819609475e-05 -4.53119364856194e-06 -4.70479509212434e-06 1.67215191664086e-06 -9.1188158444699e-06 5.32348183039125e-05 -4.53119364856194e-06 6.60781611539859e-05 8.09476651187774e-06 1.34268354477674e-05 -6.25778305777445e-06 1.26166286606481e-05 -4.70479509212434e-06 8.09476651187774e-06 2.87285622283066e-05 -7.9342195121643e-07 6.45050318199009e-06 7.34833844390182e-06 1.67215191664086e-06 1.34268354477674e-05 -7.9342195121643e-07 4.09678131381374e-05 812 818 0 150 0 812 818 0 161 0 0 0 0 0 0 0 0 0 2217 0 0 0 0 0 1391 +931 929 0.990788465888791 0.133306934675257 -0.0238217763657978 -0.0087710723842418 -0.132764532753092 0.990879153277525 0.023066912295928 -0.0276414086686572 0.0266794809655014 -0.01969174363792 0.999450069051931 0.103242078292455 3.16390188773738e-05 -2.45571227601968e-05 -3.28478233052648e-06 4.57575950571295e-06 4.33429769100426e-06 1.10836824188073e-05 -2.45571227601968e-05 9.20776577926617e-05 5.17279119658051e-06 2.48424069648135e-05 4.73513747299734e-06 -9.99836014860217e-06 -3.28478233052648e-06 5.17279119658051e-06 9.45255807642727e-06 -2.84349992595502e-06 3.21432804224743e-06 -2.64361932892606e-06 4.57575950571295e-06 2.48424069648135e-05 -2.84349992595502e-06 5.41839605513791e-05 6.9582205379117e-06 -2.39588226568775e-07 4.33429769100426e-06 4.73513747299734e-06 3.21432804224743e-06 6.9582205379117e-06 1.99405037578641e-05 1.12949731160266e-06 1.10836824188073e-05 -9.99836014860217e-06 -2.64361932892606e-06 -2.39588226568775e-07 1.12949731160266e-06 2.21016549478844e-05 975 997 0 242 0 975 997 0 263 0 0 0 0 0 0 0 0 0 2825 0 0 0 0 0 1472 +931 869 0.983436447042656 0.153319759991749 -0.096673708029587 0.00901815591284785 -0.163566287189469 0.980505127374509 -0.108884181070297 -0.0124485282728933 0.0780949698967203 0.12289323166216 0.989342422666925 0.0852071051847875 3.77371798448116e-05 -4.27757781029432e-05 3.66211432306709e-06 -1.47016950069096e-07 -3.41474070159088e-06 1.60167521674863e-05 -4.27757781029432e-05 9.87862490707431e-05 -1.06154200803305e-05 3.60559653697687e-05 2.26078958029787e-05 -5.65935529836142e-06 3.66211432306709e-06 -1.06154200803305e-05 1.31942822286785e-05 -6.44339881524139e-06 -3.4704437079964e-06 -1.74861203763409e-06 -1.47016950069096e-07 3.60559653697687e-05 -6.44339881524139e-06 7.20714235885463e-05 1.75193267795066e-05 8.041045168138e-06 -3.41474070159088e-06 2.26078958029787e-05 -3.4704437079964e-06 1.75193267795066e-05 3.42240271118875e-05 6.38433248895916e-06 1.60167521674863e-05 -5.65935529836142e-06 -1.74861203763409e-06 8.041045168138e-06 6.38433248895916e-06 3.58503466170989e-05 841 848 0 181 0 841 848 0 201 0 0 0 0 0 0 0 0 0 2123 0 0 0 0 0 1749 +931 873 0.983264062290587 0.126225986479596 -0.131372691778256 0.0158174507336826 -0.142269591081239 0.982417644567701 -0.120892245804387 -0.00455819874664943 0.11380310743292 0.137559339847587 0.983934083543866 0.105362058199257 2.40544312910822e-05 -1.92578757964032e-05 3.54652215258731e-06 4.57952928403053e-06 3.24491353341777e-06 9.81040706730256e-06 -1.92578757964032e-05 4.22953628121318e-05 -4.07667976264357e-06 1.2459548170268e-06 -1.65647356929014e-06 -5.15637445059263e-06 3.54652215258731e-06 -4.07667976264357e-06 1.08115569717634e-05 -1.85904256706869e-07 1.46918464306825e-06 2.45075807160197e-06 4.57952928403053e-06 1.2459548170268e-06 -1.85904256706869e-07 4.40528642190687e-05 -5.86601961240785e-06 2.35192701607087e-06 3.24491353341777e-06 -1.65647356929014e-06 1.46918464306825e-06 -5.86601961240785e-06 2.44981364853822e-05 -1.53609313869071e-08 9.81040706730256e-06 -5.15637445059263e-06 2.45075807160197e-06 2.35192701607087e-06 -1.53609313869071e-08 3.14702342450959e-05 771 775 0 132 0 771 775 0 147 0 0 0 0 0 0 0 0 0 1998 0 0 0 0 0 1451 +931 875 0.979591943812971 0.138237454137435 -0.145911034162346 0.0200175145379875 -0.155762622252078 0.980911493184918 -0.116407250834696 -0.00328228598510408 0.127033968393816 0.136759090415724 0.982425224667396 0.111447916039133 3.20449579823273e-05 -3.34363563176276e-05 1.07985704969582e-06 6.99582434250585e-06 1.17733359163521e-06 1.58165575179316e-05 -3.34363563176276e-05 0.000127808322093328 -6.87390233231321e-06 1.38118704534848e-05 8.37339060310664e-06 -9.45686187015823e-06 1.07985704969582e-06 -6.87390233231321e-06 1.23848153026483e-05 -1.83993905692846e-06 2.0419044439124e-06 -1.75281656569658e-06 6.99582434250585e-06 1.38118704534848e-05 -1.83993905692846e-06 5.28172117287921e-05 8.60998884628331e-06 2.30163082018166e-06 1.17733359163521e-06 8.37339060310664e-06 2.0419044439124e-06 8.60998884628331e-06 2.72127435431843e-05 3.42074150308249e-07 1.58165575179316e-05 -9.45686187015823e-06 -1.75281656569658e-06 2.30163082018166e-06 3.42074150308249e-07 3.92524873786215e-05 704 710 0 142 0 704 710 0 157 0 0 0 0 0 0 0 0 0 1950 0 0 0 0 0 1530 +931 872 0.981350102609803 0.138600680515732 -0.133198451448596 0.0168161272595444 -0.153966109964023 0.981599468952207 -0.112946533967588 -0.00855309702408222 0.115093062737397 0.131348140121286 0.984632547195351 0.103115075288687 2.96306449725147e-05 -2.65769092188701e-05 2.6117491129823e-06 2.02359030871066e-06 -1.2167951881411e-06 1.12281128579653e-05 -2.65769092188701e-05 5.35841058384769e-05 -2.12264977311716e-06 6.09530058654086e-06 5.56049150242213e-06 -2.44414344418189e-06 2.6117491129823e-06 -2.12264977311716e-06 1.08334322146902e-05 4.39782904269093e-07 4.20751205060133e-07 7.01618181575326e-07 2.02359030871066e-06 6.09530058654086e-06 4.39782904269093e-07 3.42596741111441e-05 1.16087887996887e-06 6.63983751315287e-06 -1.2167951881411e-06 5.56049150242213e-06 4.20751205060133e-07 1.16087887996887e-06 2.25944817407374e-05 5.79577137995811e-07 1.12281128579653e-05 -2.44414344418189e-06 7.01618181575326e-07 6.63983751315287e-06 5.79577137995811e-07 3.19081107325675e-05 752 760 0 150 0 752 760 0 166 0 0 0 0 0 0 0 0 0 2076 0 0 0 0 0 1588 +931 871 0.980252605697878 0.151829784882203 -0.126698640265572 0.0304169352427325 -0.1652371420207 0.980860390971945 -0.103002817044943 -0.00773207667539211 0.108634782272308 0.121904101017919 0.986578873803641 0.100897737071172 4.07703475660503e-05 -4.45935641881439e-05 2.09118744402182e-06 -3.90560647830184e-06 -4.58663442892755e-06 1.96570339343987e-05 -4.45935641881439e-05 9.62341968823847e-05 -6.05094375818949e-06 1.82134172554477e-05 1.38649162995068e-05 -1.63714386391694e-05 2.09118744402182e-06 -6.05094375818949e-06 1.3325280591416e-05 -6.40261544898204e-06 -3.30236182333795e-06 2.56793746459188e-07 -3.90560647830184e-06 1.82134172554477e-05 -6.40261544898204e-06 8.29061568796618e-05 3.08020032449155e-05 -1.25309974028637e-06 -4.58663442892755e-06 1.38649162995068e-05 -3.30236182333795e-06 3.08020032449155e-05 3.56299279185253e-05 -2.83690528433279e-06 1.96570339343987e-05 -1.63714386391694e-05 2.56793746459188e-07 -1.25309974028637e-06 -2.83690528433279e-06 3.39520948971309e-05 736 745 0 167 0 736 745 0 187 0 0 0 0 0 0 0 0 0 2153 0 0 0 0 0 1685 +931 898 0.987598724159754 0.154523078161028 -0.0277736989554438 -0.00118988661545654 -0.154416183991751 0.987987878103885 0.00596614123275387 -0.023818886849823 0.0283619844061135 -0.00160344486158931 0.999596431968984 0.107592648388706 3.22990640116297e-05 -3.16241215698018e-05 -3.24871294696592e-06 6.66574996495028e-07 -1.43318521369942e-06 7.49466525964476e-06 -3.16241215698018e-05 6.2270188702445e-05 3.59004457860924e-06 6.92575753464524e-06 6.88719536729513e-06 4.41507770337983e-06 -3.24871294696592e-06 3.59004457860924e-06 1.01743021965198e-05 -7.76418040859862e-07 4.17923487283204e-06 -2.70812396028314e-06 6.66574996495028e-07 6.92575753464524e-06 -7.76418040859862e-07 4.21215342075523e-05 6.64215202746793e-06 8.50539669201903e-06 -1.43318521369942e-06 6.88719536729513e-06 4.17923487283204e-06 6.64215202746793e-06 2.05843805521717e-05 3.46357686406087e-06 7.49466525964476e-06 4.41507770337983e-06 -2.70812396028314e-06 8.50539669201903e-06 3.46357686406087e-06 3.24011327110201e-05 952 971 0 260 0 952 971 0 273 0 0 0 0 0 0 0 0 0 2757 0 0 0 0 0 1795 +931 888 0.985133187076792 0.149845737125908 -0.0840170148548256 0.0109065437368212 -0.154862203690341 0.986306037546497 -0.0567282836643089 -0.0113778890121299 0.0743659975263823 0.0688959749515193 0.994848251266185 0.105994366619518 2.497043733376e-05 -1.94874365541323e-05 7.11114475062884e-07 4.68429620770607e-06 -1.05134870817935e-06 1.02299415035054e-05 -1.94874365541323e-05 6.03113852448627e-05 -1.03650364482734e-06 3.14149535953955e-06 3.50159917101701e-06 -2.40383775857408e-06 7.11114475062884e-07 -1.03650364482734e-06 1.12295470103208e-05 4.40158250089878e-07 2.4341399032509e-06 -5.0037817018544e-07 4.68429620770607e-06 3.14149535953955e-06 4.40158250089878e-07 3.79411612034175e-05 1.96241162130323e-06 -5.5284802550349e-06 -1.05134870817935e-06 3.50159917101701e-06 2.4341399032509e-06 1.96241162130323e-06 2.2325103791519e-05 1.05003734232488e-06 1.02299415035054e-05 -2.40383775857408e-06 -5.0037817018544e-07 -5.5284802550349e-06 1.05003734232488e-06 2.95496550378941e-05 826 832 0 188 0 826 832 0 208 0 0 0 0 0 0 0 0 0 2299 0 0 0 0 0 1477 +931 874 0.980826710610669 0.129975640259164 -0.145207770769593 0.0140143496156207 -0.147191205220357 0.982416099358835 -0.114862338589942 -0.00632710216721874 0.127725145756162 0.13403335651916 0.982711222324125 0.106575550144052 3.93134713367914e-05 -3.58812080972538e-05 3.43454648735149e-06 4.25405843145823e-06 -8.32520427113132e-07 1.80888511377694e-05 -3.58812080972538e-05 8.29380349194103e-05 -7.58089931428509e-06 1.15933313017028e-05 9.67850396824793e-06 -3.36902611122299e-06 3.43454648735149e-06 -7.58089931428509e-06 1.31870191444357e-05 -6.54974562167473e-06 6.33015240541375e-07 -2.21547861501037e-06 4.25405843145823e-06 1.15933313017028e-05 -6.54974562167473e-06 5.83501727842573e-05 1.63327197692152e-05 2.05179258378233e-05 -8.32520427113132e-07 9.67850396824793e-06 6.33015240541375e-07 1.63327197692152e-05 3.29283621618924e-05 1.13258887851289e-05 1.80888511377694e-05 -3.36902611122299e-06 -2.21547861501037e-06 2.05179258378233e-05 1.13258887851289e-05 4.22763345774766e-05 727 733 0 129 0 727 733 0 144 0 0 0 0 0 0 0 0 0 1945 0 0 0 0 0 1460 +931 890 0.987193676860093 0.152871478745289 -0.0455955628727 0.0011683672890483 -0.153861044880684 0.987909305556171 -0.0190258472544176 -0.0205599204994201 0.042135771449847 0.0257975770519836 0.998778785208503 0.108019017780689 1.99282986679706e-05 -1.68809817444145e-05 1.07972847581338e-06 1.80379576314184e-07 -1.41504807108471e-06 7.93158805261219e-06 -1.68809817444145e-05 4.11820420623106e-05 -4.60237820911091e-08 4.22226640449863e-06 3.79650943626405e-06 -5.50152519109868e-06 1.07972847581338e-06 -4.60237820911091e-08 9.72926721066691e-06 -1.73589094936284e-06 4.69101714850534e-06 5.60818786800288e-08 1.80379576314184e-07 4.22226640449863e-06 -1.73589094936284e-06 3.79648798345098e-05 3.9490701892543e-06 3.31796029122757e-07 -1.41504807108471e-06 3.79650943626405e-06 4.69101714850534e-06 3.9490701892543e-06 1.96931482849587e-05 2.75002736801227e-07 7.93158805261219e-06 -5.50152519109868e-06 5.60818786800288e-08 3.31796029122757e-07 2.75002736801227e-07 2.18628366693288e-05 895 911 0 222 0 895 911 0 245 0 0 0 0 0 0 0 0 0 2510 0 0 0 0 0 1907 +931 887 0.983824170811669 0.147670951664528 -0.101406562712799 0.0263489694113244 -0.156622183866789 0.983834554535367 -0.086827765276977 -0.00295851021688529 0.0869453417241541 0.101305771487555 0.99104876177501 0.109460831469066 3.61560827014393e-05 -3.28243809485988e-05 3.73404170262158e-06 -1.73758103994395e-06 -3.7156568139693e-07 9.62160251421837e-06 -3.28243809485988e-05 6.56435356217853e-05 -5.69344432244589e-06 1.82152737810542e-05 1.1374973750913e-05 8.41472490623302e-08 3.73404170262158e-06 -5.69344432244589e-06 1.10105554676368e-05 -3.71491424079074e-06 6.46616080106469e-07 9.68416556845865e-07 -1.73758103994395e-06 1.82152737810542e-05 -3.71491424079074e-06 6.70165982579973e-05 2.20701716751052e-05 -3.43941146291328e-07 -3.7156568139693e-07 1.1374973750913e-05 6.46616080106469e-07 2.20701716751052e-05 2.96922123066419e-05 1.46363475025534e-06 9.62160251421837e-06 8.41472490623302e-08 9.68416556845865e-07 -3.43941146291328e-07 1.46363475025534e-06 2.8936980134445e-05 814 823 0 166 0 814 823 0 184 0 0 0 0 0 0 0 0 0 2154 0 0 0 0 0 1426 +931 899 0.987554321628945 0.153828133442411 -0.0327622830953329 -0.00793508953431189 -0.153747965008646 0.988097610592145 0.00496741359196613 -0.0268701198385418 0.0331364616049304 0.00013154359488008 0.999450828009356 0.106483313898053 2.99744368761316e-05 -2.53349227269428e-05 -3.55969653880162e-07 -5.23498827581381e-06 -3.01867731474826e-06 1.16699967750997e-05 -2.53349227269428e-05 4.54661803487507e-05 1.30824785338283e-06 1.13668011126793e-05 7.68951243151158e-06 -4.48232350923535e-06 -3.55969653880162e-07 1.30824785338283e-06 1.01883454237642e-05 -4.36407633642309e-06 3.43266135624699e-06 -1.29175167163188e-06 -5.23498827581381e-06 1.13668011126793e-05 -4.36407633642309e-06 4.31501315940256e-05 7.95651756595323e-06 8.87697075224409e-07 -3.01867731474826e-06 7.68951243151158e-06 3.43266135624699e-06 7.95651756595323e-06 1.9623404069669e-05 2.40920137954223e-06 1.16699967750997e-05 -4.48232350923535e-06 -1.29175167163188e-06 8.87697075224409e-07 2.40920137954223e-06 2.56652762213558e-05 940 951 0 235 0 940 951 0 276 0 0 0 0 0 0 0 0 0 2778 0 0 0 0 0 1378 +931 892 0.987947581812518 0.153578076801369 -0.0193222647945312 0.000414605787452199 -0.153522232564589 0.988135619537808 0.00434988609230707 -0.0264005795882294 0.0197610652339792 -0.00133106221659408 0.999803845048715 0.107776516531597 3.84510972803242e-05 -3.37889968415379e-05 -1.12110799395281e-06 4.10793145367951e-06 -1.92337594550197e-06 1.0128363137134e-05 -3.37889968415379e-05 6.62419219531873e-05 2.77195210212351e-06 2.30282746302319e-06 4.38545561903751e-06 -2.15481056037678e-06 -1.12110799395281e-06 2.77195210212351e-06 9.81268905322593e-06 -2.73827602048948e-06 4.06555198225149e-06 -7.56193617176489e-07 4.10793145367951e-06 2.30282746302319e-06 -2.73827602048948e-06 3.55924485922158e-05 4.05779637341186e-06 3.07415599282665e-06 -1.92337594550197e-06 4.38545561903751e-06 4.06555198225149e-06 4.05779637341186e-06 1.9535027438552e-05 1.73630518762359e-06 1.0128363137134e-05 -2.15481056037678e-06 -7.56193617176489e-07 3.07415599282665e-06 1.73630518762359e-06 2.64000840547988e-05 937 961 0 260 0 937 961 0 298 0 0 0 0 0 0 0 0 0 2762 0 0 0 0 0 1335 +931 900 0.987734138374449 0.153880364488981 -0.0264972699428182 -0.00337864704186839 -0.15377628616367 0.988087871440056 0.00593398068485373 -0.0266728099865538 0.0270947541674277 -0.0017865435336018 0.999631273299715 0.108879868829911 2.89326871721238e-05 -3.41355364597243e-05 1.91913244720838e-06 -5.02846004596219e-06 -4.33825451046018e-06 1.47595496471923e-05 -3.41355364597243e-05 0.000140222964828424 -5.14877544072974e-07 4.39841353498816e-05 1.75007776017857e-05 -1.44710599610186e-05 1.91913244720838e-06 -5.14877544072974e-07 9.6056190281697e-06 -2.23020316265041e-06 4.20929674123437e-06 3.03757720515563e-07 -5.02846004596219e-06 4.39841353498816e-05 -2.23020316265041e-06 5.04135144183489e-05 8.61208236504766e-06 1.65687420572298e-06 -4.33825451046018e-06 1.75007776017857e-05 4.20929674123437e-06 8.61208236504766e-06 2.03236550835942e-05 3.66046104734237e-07 1.47595496471923e-05 -1.44710599610186e-05 3.03757720515563e-07 1.65687420572298e-06 3.66046104734237e-07 3.01409131712222e-05 969 991 0 253 0 969 991 0 296 0 0 0 0 0 0 0 0 0 2671 0 0 0 0 0 1886 +931 889 0.986159955609538 0.151124526769371 -0.0681903172080028 -0.00132900615583536 -0.153982687812104 0.987312202822937 -0.0387807427866032 -0.0177683603466975 0.0614644108924379 0.0487441439113898 0.996918318934902 0.108529455664765 3.05111989684449e-05 -3.26734933162765e-05 3.68231720285346e-06 1.29615584743127e-06 7.2136820905202e-08 1.48705302051502e-05 -3.26734933162765e-05 0.000139789204056883 -4.51277938826096e-06 3.78370929555538e-05 1.39412931867153e-05 -1.25379993412881e-05 3.68231720285346e-06 -4.51277938826096e-06 1.07363105954953e-05 -1.4519322348086e-06 3.68307958081779e-06 7.85593538192909e-07 1.29615584743127e-06 3.78370929555538e-05 -1.4519322348086e-06 6.04513359161333e-05 1.06093996441092e-05 2.24056724452978e-07 7.2136820905202e-08 1.39412931867153e-05 3.68307958081779e-06 1.06093996441092e-05 2.28806006421591e-05 1.7310669410499e-06 1.48705302051502e-05 -1.25379993412881e-05 7.85593538192909e-07 2.24056724452978e-07 1.7310669410499e-06 2.69405199325555e-05 830 848 0 214 0 830 848 0 232 0 0 0 0 0 0 0 0 0 2416 0 0 0 0 0 1608 +931 891 0.987605275338281 0.153493770921466 -0.0327945485150656 -0.00403463641947535 -0.153563039341292 0.988138767605148 0.000410979372310336 -0.027004385922262 0.032468647527471 0.00463014514765002 0.999462029635768 0.108176281271796 2.6764165377002e-05 -2.69700342843123e-05 -3.89138111064559e-06 -2.8599197899859e-06 -1.6161232436959e-06 7.21634038689695e-06 -2.69700342843123e-05 7.64472422224222e-05 3.1616365403261e-06 1.92226403229376e-05 8.72608785662023e-06 1.57825613096407e-06 -3.89138111064559e-06 3.1616365403261e-06 9.25440061325338e-06 -9.35497304148707e-07 3.57726612183241e-06 -2.64715301942205e-06 -2.8599197899859e-06 1.92226403229376e-05 -9.35497304148707e-07 3.9473105377721e-05 5.48191618986005e-06 3.71626889854769e-06 -1.6161232436959e-06 8.72608785662023e-06 3.57726612183241e-06 5.48191618986005e-06 1.98514536698303e-05 6.44779504278476e-07 7.21634038689695e-06 1.57825613096407e-06 -2.64715301942205e-06 3.71626889854769e-06 6.44779504278476e-07 2.57905467290828e-05 914 938 0 265 0 914 938 0 291 0 0 0 0 0 0 0 0 0 2645 0 0 0 0 0 1857 +931 893 0.987679367521422 0.153333440157765 -0.0312781569448824 -0.00815578386611869 -0.153244565759162 0.988174435511047 0.00523336103373231 -0.0279285469558319 0.0317107243337249 -0.000375675137042571 0.999497017919724 0.107911405304762 3.29375170776057e-05 -3.39581611592994e-05 -1.61731317338012e-06 1.69640089823024e-06 7.09862081424143e-07 8.21854320602984e-06 -3.39581611592994e-05 7.91304322524198e-05 2.34262480429984e-06 1.38896915947917e-05 5.47106988130711e-06 2.66883085321598e-06 -1.61731317338012e-06 2.34262480429984e-06 9.84413659719683e-06 -1.9112534647105e-06 2.79546692152083e-06 -1.12352074258184e-06 1.69640089823024e-06 1.38896915947917e-05 -1.9112534647105e-06 3.91795887944207e-05 4.00685070576306e-06 4.63493487023793e-06 7.09862081424143e-07 5.47106988130711e-06 2.79546692152083e-06 4.00685070576306e-06 1.84710469968601e-05 1.15132176137962e-06 8.21854320602984e-06 2.66883085321598e-06 -1.12352074258184e-06 4.63493487023793e-06 1.15132176137962e-06 2.79816628539926e-05 942 959 0 257 0 942 959 0 283 0 0 0 0 0 0 0 0 0 2650 0 0 0 0 0 1551 +931 876 0.980080367829003 0.136752440763973 -0.144018202117869 0.0229024447081415 -0.153970082806587 0.981233798080071 -0.116075178681282 -0.00131047748655376 0.12544196346 0.135937498323512 0.982743766376997 0.110935999811472 3.93596957091395e-05 -4.05382888137454e-05 5.81631410211372e-06 -1.38681347943489e-06 -4.09840917695853e-06 1.82747417373744e-05 -4.05382888137454e-05 0.000103877680072268 -1.21293229123945e-05 3.95809139387463e-05 2.22480317373931e-05 -9.21139238708693e-06 5.81631410211372e-06 -1.21293229123945e-05 1.39310604389858e-05 -8.04511579215454e-06 -5.65667321403998e-06 -3.56440546506029e-08 -1.38681347943489e-06 3.95809139387463e-05 -8.04511579215454e-06 8.12264796893164e-05 2.73201093984046e-05 1.20989975478712e-05 -4.09840917695853e-06 2.22480317373931e-05 -5.65667321403998e-06 2.73201093984046e-05 3.76736884981886e-05 3.35072685050013e-06 1.82747417373744e-05 -9.21139238708693e-06 -3.56440546506029e-08 1.20989975478712e-05 3.35072685050013e-06 3.76265704584272e-05 696 703 0 137 0 696 703 0 152 0 0 0 0 0 0 0 0 0 1982 0 0 0 0 0 1302 +931 894 0.987911110747944 0.153415745694083 -0.0222541284685108 -0.0050095379889623 -0.15334533791003 0.988160774805502 0.00484669754039971 -0.0287087365365303 0.0227342165473789 -0.0013755395006986 0.999740597999831 0.108014820846253 3.08124466372448e-05 -2.7870040495014e-05 2.03205783302217e-06 -9.36050980694557e-07 -6.49580808886415e-07 7.41450610675048e-06 -2.7870040495014e-05 5.46394220201542e-05 -1.49751825559085e-06 1.28304592578978e-05 7.77467058691861e-06 -8.03614616333106e-07 2.03205783302217e-06 -1.49751825559085e-06 1.08831186951406e-05 -3.87944244618941e-06 3.71882408937451e-06 -3.75193298275046e-07 -9.36050980694557e-07 1.28304592578978e-05 -3.87944244618941e-06 4.52646728534298e-05 8.81583003381055e-06 6.38357804042489e-06 -6.49580808886415e-07 7.77467058691861e-06 3.71882408937451e-06 8.81583003381055e-06 2.25260549165777e-05 2.61786716156725e-06 7.41450610675048e-06 -8.03614616333106e-07 -3.75193298275046e-07 6.38357804042489e-06 2.61786716156725e-06 2.78842221984561e-05 971 989 0 261 0 971 989 0 277 0 0 0 0 0 0 0 0 0 2638 0 0 0 0 0 1332 +931 902 0.987663596791445 0.153820354873032 -0.0293243584707561 -0.00571298690308745 -0.153726893150465 0.988098461235097 0.00542892504456426 -0.0257224556178759 0.0298104326585944 -0.000854009114885654 0.999555205465481 0.105774077719337 3.03556535908726e-05 -2.54623975953001e-05 -8.43145561484114e-07 4.31424350937322e-06 1.09244043092707e-06 9.64903870620038e-06 -2.54623975953001e-05 4.31014791768194e-05 2.34418591365075e-06 -2.00121479058106e-06 -2.02629396704056e-07 -1.2216221669241e-06 -8.43145561484114e-07 2.34418591365075e-06 9.82233149057786e-06 -4.00408033497307e-06 4.78077345947263e-06 -1.69913000514181e-06 4.31424350937322e-06 -2.00121479058106e-06 -4.00408033497307e-06 2.79575518996037e-05 1.85661168097966e-07 2.9423805996018e-06 1.09244043092707e-06 -2.02629396704056e-07 4.78077345947263e-06 1.85661168097966e-07 1.64436526134801e-05 1.20117960624617e-06 9.64903870620038e-06 -1.2216221669241e-06 -1.69913000514181e-06 2.9423805996018e-06 1.20117960624617e-06 2.96982208080667e-05 959 978 0 260 0 959 978 0 293 0 0 0 0 0 0 0 0 0 2738 0 0 0 0 0 1369 +931 897 0.987696394315228 0.153915088954209 -0.0276763084408958 -0.00429862430222902 -0.153808334209896 0.988082736601984 0.00595835184516404 -0.0264577591902365 0.0282635628375898 -0.00162819573515654 0.999599179668718 0.109174846830008 2.73390048594188e-05 -2.93070096008516e-05 -5.75742520889156e-07 3.35542704701983e-06 2.82317643449337e-07 1.38100084569313e-05 -2.93070096008516e-05 0.000115588017014373 2.31757034250206e-06 2.55977329591693e-05 8.99353247252689e-06 -1.19706242325287e-05 -5.75742520889156e-07 2.31757034250206e-06 9.5988333565599e-06 -3.3758263419773e-06 4.68453435251835e-06 -6.80235739245913e-07 3.35542704701983e-06 2.55977329591693e-05 -3.3758263419773e-06 5.61706326753121e-05 1.24455665327778e-05 3.88509711250913e-06 2.82317643449337e-07 8.99353247252689e-06 4.68453435251835e-06 1.24455665327778e-05 2.16644809109813e-05 8.52287167272319e-07 1.38100084569313e-05 -1.19706242325287e-05 -6.80235739245913e-07 3.88509711250913e-06 8.52287167272319e-07 3.03408765758314e-05 933 950 0 252 0 933 950 0 274 0 0 0 0 0 0 0 0 0 2650 0 0 0 0 0 1905 +931 927 0.987605159698184 0.154143776733023 -0.0295929828169442 -0.00337388942648919 -0.154044875564999 0.98804794314515 0.00560699195672272 -0.0256939967232723 0.0301035687201324 -0.000978846831212238 0.999546305585286 0.108036009671853 3.19316990744417e-05 -3.25875549907355e-05 -2.64563153806169e-06 -3.48433567873667e-07 -1.1890379368371e-06 1.02303887840124e-05 -3.25875549907355e-05 5.75698941818996e-05 3.48141253521273e-06 9.12943817267274e-06 5.02171880868915e-06 -2.91333897245085e-06 -2.64563153806169e-06 3.48141253521273e-06 1.04601931272441e-05 -3.3251067079136e-06 4.16536197448281e-06 -3.12713735164322e-06 -3.48433567873667e-07 9.12943817267274e-06 -3.3251067079136e-06 3.70365994709019e-05 3.89037476316957e-06 7.22712340617671e-06 -1.1890379368371e-06 5.02171880868915e-06 4.16536197448281e-06 3.89037476316957e-06 1.80117352600683e-05 4.29204570204233e-06 1.02303887840124e-05 -2.91333897245085e-06 -3.12713735164322e-06 7.22712340617671e-06 4.29204570204233e-06 2.76760518243082e-05 937 958 0 258 0 937 958 0 285 0 0 0 0 0 0 0 0 0 2705 0 0 0 0 0 1520 +932 861 0.983280529857178 0.179966700238699 -0.0277738439720022 -0.029730330767407 -0.18189412459844 0.97789398106077 -0.103140143696268 -0.0202125269509966 0.00859808352797935 0.106467594179233 0.994278997238367 0.117126164750022 3.1831431000991e-05 -2.11144464681676e-05 8.81218495805647e-07 5.34612738352826e-06 -7.88899874859769e-07 9.03324596554698e-06 -2.11144464681676e-05 6.75064431444033e-05 -4.85290313939742e-06 2.30387788735985e-05 1.31367477357709e-05 -2.44391466354016e-06 8.81218495805647e-07 -4.85290313939742e-06 9.48365101175302e-06 -2.99593587141337e-06 1.87710346737358e-06 -2.95985402043099e-06 5.34612738352826e-06 2.30387788735985e-05 -2.99593587141337e-06 5.56671391022704e-05 6.72710722187982e-06 -4.96381698747551e-07 -7.88899874859769e-07 1.31367477357709e-05 1.87710346737358e-06 6.72710722187982e-06 2.64346179594045e-05 2.91668715304945e-06 9.03324596554698e-06 -2.44391466354016e-06 -2.95985402043099e-06 -4.96381698747551e-07 2.91668715304945e-06 3.7632826473892e-05 1191 1193 0 238 0 1191 1193 0 250 0 0 0 0 0 0 0 0 0 2261 0 0 0 0 0 1885 +931 901 0.987749477482097 0.154010537968428 -0.0251341188132623 -0.00330683781704747 -0.15392636160474 0.988068312090759 0.00526173405300682 -0.0265161507162915 0.0256445888438591 -0.00132847160044053 0.999670240742534 0.107520954838078 2.2763769155088e-05 -2.18057921106307e-05 2.42989375860699e-07 2.31643601905766e-06 -8.0370551431339e-07 9.76508436523756e-06 -2.18057921106307e-05 4.59077974189105e-05 1.72806789143543e-06 3.65291222872857e-06 3.71541955748935e-06 -9.25312067267199e-07 2.42989375860699e-07 1.72806789143543e-06 1.00763290655483e-05 -3.38266270780021e-06 4.03693121274424e-06 -1.29246822939814e-06 2.31643601905766e-06 3.65291222872857e-06 -3.38266270780021e-06 3.80074450316662e-05 7.87462143917762e-06 5.39819675521275e-06 -8.0370551431339e-07 3.71541955748935e-06 4.03693121274424e-06 7.87462143917762e-06 2.07015940262012e-05 2.47300761715559e-06 9.76508436523756e-06 -9.25312067267199e-07 -1.29246822939814e-06 5.39819675521275e-06 2.47300761715559e-06 2.64457833523005e-05 952 968 0 266 0 952 968 0 293 0 0 0 0 0 0 0 0 0 2658 0 0 0 0 0 1363 +932 862 0.979794567373337 0.182588350893378 -0.0816339381858605 -0.0346842191784129 -0.188604516272988 0.979315273930382 -0.0732798109174239 -0.0217988807853011 0.0665653227073109 0.0871956900580405 0.993964772740047 0.134696204114307 2.45373907153222e-05 -1.20821903522172e-05 2.48237225366049e-06 7.08819325974298e-06 4.03523443958984e-07 1.65841293524344e-05 -1.20821903522172e-05 9.27362220811117e-05 -2.08357511334764e-06 1.10859869297263e-05 -1.39137878639349e-06 1.75981320021953e-05 2.48237225366049e-06 -2.08357511334764e-06 1.13978896732545e-05 8.41272133425571e-07 2.00673175206514e-06 -2.01860333663671e-06 7.08819325974298e-06 1.10859869297263e-05 8.41272133425571e-07 3.89823198992275e-05 -1.96464556005174e-06 1.03962365503944e-05 4.03523443958984e-07 -1.39137878639349e-06 2.00673175206514e-06 -1.96464556005174e-06 2.35117957619804e-05 3.74563980746802e-06 1.65841293524344e-05 1.75981320021953e-05 -2.01860333663671e-06 1.03962365503944e-05 3.74563980746802e-06 5.00339679621435e-05 1044 1044 0 218 0 1044 1044 0 228 0 0 0 0 0 0 0 0 0 2188 0 0 0 0 0 1309 +931 895 0.987478320621008 0.153945467152556 -0.0344580824581882 -0.0069502820641497 -0.153874600391339 0.988079134261734 0.00471506001950773 -0.0265616792142024 0.0347731744009615 0.000646204118814771 0.999395021381594 0.106929384492268 4.02737405432371e-05 -4.30955990675004e-05 -9.23663905926613e-07 -2.77761404559766e-06 -5.30894952167253e-06 8.79845422300266e-06 -4.30955990675004e-05 8.62804074575841e-05 2.2720520376671e-06 1.64711769097219e-05 9.61494550578716e-06 -7.62975496628499e-07 -9.23663905926613e-07 2.2720520376671e-06 8.82569998419254e-06 -4.90945183889361e-07 2.52511610612936e-06 -1.14388903638861e-06 -2.77761404559766e-06 1.64711769097219e-05 -4.90945183889361e-07 5.11545808590512e-05 1.16907613309303e-05 1.33101691016898e-06 -5.30894952167253e-06 9.61494550578716e-06 2.52511610612936e-06 1.16907613309303e-05 2.46808239895022e-05 1.92720998177236e-06 8.79845422300266e-06 -7.62975496628499e-07 -1.14388903638861e-06 1.33101691016898e-06 1.92720998177236e-06 2.8609644875856e-05 907 919 0 245 0 907 919 0 262 0 0 0 0 0 0 0 0 0 2683 0 0 0 0 0 1821 +932 930 0.985112818220251 0.147376145009985 0.0885042782025267 -0.0159072669958717 -0.148995554324075 0.988765748739736 0.0119423159735283 -0.0395844294702187 -0.0857499864129214 -0.0249512725355968 0.996004203720566 0.139655502718403 1.87761672962169e-05 -5.72165855482028e-06 3.05298287917772e-06 4.37034797464352e-07 -5.55190628833611e-07 8.83592180968901e-06 -5.72165855482028e-06 7.07772025195751e-05 1.98344011574496e-06 -2.49533236612108e-06 -4.7057632959652e-06 -1.36058026688036e-05 3.05298287917772e-06 1.98344011574496e-06 1.0479881164351e-05 -2.70517093008461e-06 1.50786051354366e-06 -2.14127823086767e-06 4.37034797464352e-07 -2.49533236612108e-06 -2.70517093008461e-06 3.75724981939766e-05 5.2221320147062e-07 4.16320497450192e-06 -5.55190628833611e-07 -4.7057632959652e-06 1.50786051354366e-06 5.2221320147062e-07 2.16805198876635e-05 1.75618048541981e-06 8.83592180968901e-06 -1.36058026688036e-05 -2.14127823086767e-06 4.16320497450192e-06 1.75618048541981e-06 2.87288903658304e-05 1231 1247 0 287 0 1231 1247 0 306 0 0 0 0 0 0 0 0 0 2772 0 0 0 0 0 1593 +932 863 0.980787264006814 0.181764984983039 -0.0708366642081897 -0.0202331869589388 -0.186914647910465 0.979548777102157 -0.0744789075790968 -0.025584742103569 0.0558503102814607 0.0862883741403443 0.994703503225801 0.150830139464061 2.84056940540941e-05 -1.83589757133538e-05 1.32727928021428e-06 2.61933683771298e-06 5.26348752361818e-07 1.67207472324869e-05 -1.83589757133538e-05 4.15081216074198e-05 -1.83459062790779e-06 1.55526319343737e-06 -3.41875008472475e-07 -2.56959601234381e-06 1.32727928021428e-06 -1.83459062790779e-06 1.03095973979595e-05 -2.76622210923635e-07 4.20980414462796e-08 -1.30330047471827e-06 2.61933683771298e-06 1.55526319343737e-06 -2.76622210923635e-07 4.73280549785749e-05 5.25956102305144e-06 6.22938870942613e-06 5.26348752361818e-07 -3.41875008472475e-07 4.20980414462796e-08 5.25956102305144e-06 2.3652486717338e-05 3.09501855463792e-06 1.67207472324869e-05 -2.56959601234381e-06 -1.30330047471827e-06 6.22938870942613e-06 3.09501855463792e-06 3.61192972774795e-05 983 982 0 211 0 983 982 0 221 0 0 0 0 0 0 0 0 0 2183 0 0 0 0 0 1544 +932 867 0.976062275667376 0.20771830997751 -0.0644634603407974 0.00825466769074683 -0.213909092421051 0.970421954424198 -0.111911261949463 -0.0289587603395788 0.0393107389732705 0.123021681307021 0.99162509635939 0.161118858786764 5.50783533670625e-05 -4.38846539599549e-05 2.17060218695253e-06 5.97974934133098e-06 3.21872086257484e-06 7.84197356438094e-06 -4.38846539599549e-05 0.000212390050121766 -1.62690010474473e-05 5.74895060530527e-05 2.81491596517407e-05 1.71272482460591e-05 2.17060218695253e-06 -1.62690010474473e-05 1.19214481034373e-05 -3.11597535805071e-06 -2.85442556386318e-06 -1.82340953505899e-06 5.97974934133098e-06 5.74895060530527e-05 -3.11597535805071e-06 6.29981463198404e-05 1.17582498498171e-05 1.92440288058287e-05 3.21872086257484e-06 2.81491596517407e-05 -2.85442556386318e-06 1.17582498498171e-05 3.10346407804358e-05 1.00074282530906e-05 7.84197356438094e-06 1.71272482460591e-05 -1.82340953505899e-06 1.92440288058287e-05 1.00074282530906e-05 5.25474716725388e-05 805 813 0 214 0 805 813 0 225 0 0 0 0 0 0 0 0 0 1962 0 0 0 0 0 1298 +932 864 0.9819777057276 0.172804178421252 -0.0765408477488633 -0.00441510085975971 -0.178405551690422 0.981198988231448 -0.0736206806516902 -0.0205005557506018 0.0623798411347334 0.0859491792499397 0.994344756111414 0.156362015684053 3.52596334817835e-05 -2.41218272099667e-05 3.29684365485337e-06 4.97527921558854e-06 -2.6784230314957e-06 2.52689454573449e-05 -2.41218272099667e-05 0.000203204690900528 -9.1292496628226e-06 6.54451874768829e-05 3.02485281871578e-05 -2.74806525619521e-05 3.29684365485337e-06 -9.1292496628226e-06 1.0549496784341e-05 -4.78209944869747e-06 8.29723851233546e-07 1.26445927057304e-07 4.97527921558854e-06 6.54451874768829e-05 -4.78209944869747e-06 7.0221555319179e-05 1.25761741766314e-05 9.89378047690554e-06 -2.6784230314957e-06 3.02485281871578e-05 8.29723851233546e-07 1.25761741766314e-05 2.95324726962273e-05 9.02333235960741e-07 2.52689454573449e-05 -2.74806525619521e-05 1.26445927057304e-07 9.89378047690554e-06 9.02333235960741e-07 5.61920738742536e-05 884 890 0 182 0 884 890 0 195 0 0 0 0 0 0 0 0 0 2173 0 0 0 0 0 1793 +932 866 0.97804698342258 0.193426920364047 -0.0775249940114261 -0.00226926628021177 -0.20042029111487 0.975015852651623 -0.0957903647944824 -0.0283620174888127 0.0570596628751172 0.109225059196641 0.99237799316393 0.158912287071611 3.23555150799632e-05 -2.57525630273222e-05 5.35316601531381e-06 -7.0281228076283e-06 4.93299076101712e-07 9.77669980287195e-06 -2.57525630273222e-05 6.45637869207481e-05 -6.70371632092262e-06 1.11995087092362e-05 3.40017523155275e-06 -8.42326003353714e-06 5.35316601531381e-06 -6.70371632092262e-06 1.15842573554779e-05 -9.75039624278378e-07 2.33052938685067e-06 3.7314625081987e-06 -7.0281228076283e-06 1.11995087092362e-05 -9.75039624278378e-07 4.16800484992897e-05 3.75966662565463e-06 3.13820003966941e-06 4.93299076101712e-07 3.40017523155275e-06 2.33052938685067e-06 3.75966662565463e-06 2.58683888267712e-05 5.54416032200921e-07 9.77669980287195e-06 -8.42326003353714e-06 3.7314625081987e-06 3.13820003966941e-06 5.54416032200921e-07 3.47836446173166e-05 814 822 0 213 0 814 822 0 222 0 0 0 0 0 0 0 0 0 2020 0 0 0 0 0 1477 +931 896 0.98768285915973 0.15384008527377 -0.0285621757753064 -0.00337067531587999 -0.153765996176924 0.988095701878014 0.00478563996894805 -0.0256594369129139 0.0289583863807771 -0.000334803156369292 0.999580561918382 0.109077715711894 2.78357079886113e-05 -3.08474486100304e-05 -7.56213625026213e-07 -3.59887862087888e-06 -6.68351276626914e-06 8.02016610284731e-06 -3.08474486100304e-05 5.94180603291165e-05 5.62728389020249e-07 1.96921296536482e-05 1.5784980923936e-05 4.81451862787278e-06 -7.56213625026213e-07 5.62728389020249e-07 9.52252752989333e-06 -9.98225740468674e-07 3.64192991178707e-06 -8.35369916832368e-07 -3.59887862087888e-06 1.96921296536482e-05 -9.98225740468674e-07 4.77392140511715e-05 1.25764768051008e-05 1.06657773008215e-05 -6.68351276626914e-06 1.5784980923936e-05 3.64192991178707e-06 1.25764768051008e-05 2.22881063226206e-05 5.20564647678887e-06 8.02016610284731e-06 4.81451862787278e-06 -8.35369916832368e-07 1.06657773008215e-05 5.20564647678887e-06 3.21073576028617e-05 946 968 0 259 0 946 968 0 286 0 0 0 0 0 0 0 0 0 2669 0 0 0 0 0 1776 +931 928 0.987647036823739 0.153820701295366 -0.0298751151677951 -0.00252442582464898 -0.153767926094383 0.98809860943882 0.00406975794148177 -0.0266071896666216 0.030145572774784 0.000574350129688331 0.99954535393048 0.107364056861778 3.20580342889375e-05 -3.44009417929594e-05 -1.65689674141996e-06 1.36745868908845e-06 -2.8104150318339e-06 1.28459303354536e-05 -3.44009417929594e-05 8.6375531082421e-05 3.31902760407271e-06 1.10552923752288e-05 6.65863643091709e-06 -3.30477023736936e-06 -1.65689674141996e-06 3.31902760407271e-06 9.22564694364619e-06 -2.18621937389094e-06 3.09252360644668e-06 -2.56442544954687e-06 1.36745868908845e-06 1.10552923752288e-05 -2.18621937389094e-06 3.54322862913069e-05 5.30053968013794e-06 3.51824032895591e-06 -2.8104150318339e-06 6.65863643091709e-06 3.09252360644668e-06 5.30053968013794e-06 2.10660644876421e-05 1.86023603093667e-07 1.28459303354536e-05 -3.30477023736936e-06 -2.56442544954687e-06 3.51824032895591e-06 1.86023603093667e-07 2.58892097909432e-05 921 940 0 261 0 921 940 0 297 0 0 0 0 0 0 0 0 0 2626 0 0 0 0 0 1352 +932 865 0.978012549269652 0.190968769575887 -0.0837996570264304 0.00639229925507125 -0.198315760464761 0.975957795985168 -0.0904280908073177 -0.0258953554042619 0.064515987339258 0.105058600325935 0.992371088794507 0.165901170731989 3.93368498603167e-05 -2.49621199260934e-05 3.82046748651278e-06 5.76908513408657e-06 2.50950292426102e-06 2.44403898808563e-05 -2.49621199260934e-05 7.8336164474089e-05 -4.04249106528923e-06 1.33072033925363e-05 7.34446021978214e-06 -1.10932127549885e-05 3.82046748651278e-06 -4.04249106528923e-06 9.94929348808204e-06 -4.93845504485873e-07 4.17862433149085e-07 -5.76135507461358e-07 5.76908513408657e-06 1.33072033925363e-05 -4.93845504485873e-07 4.14523230037479e-05 9.27869206217474e-06 1.35585918233751e-05 2.50950292426102e-06 7.34446021978214e-06 4.17862433149085e-07 9.27869206217474e-06 2.64301692684977e-05 5.60077168823448e-06 2.44403898808563e-05 -1.10932127549885e-05 -5.76135507461358e-07 1.35585918233751e-05 5.60077168823448e-06 4.95791075547806e-05 875 886 0 213 0 875 886 0 220 0 0 0 0 0 0 0 0 0 2037 0 0 0 0 0 1699 +932 869 0.97077909245142 0.234631093921153 -0.0503607329628925 -0.00193379503129121 -0.238732332974151 0.965575189290221 -0.103302599289041 -0.0376485378248831 0.024389072387353 0.112306738856207 0.993374234392844 0.159312117610662 3.6257341225317e-05 -3.52654090807286e-05 2.9973234707976e-06 7.81393377882902e-07 4.22020558188837e-07 2.15260090158676e-05 -3.52654090807286e-05 8.88099687836078e-05 -6.15892853173412e-06 2.02831201583581e-05 1.07321704413424e-05 -8.98969528826594e-06 2.9973234707976e-06 -6.15892853173412e-06 1.10124756310341e-05 -1.45447276083285e-06 -2.23268257699784e-06 -9.86339220816114e-07 7.81393377882902e-07 2.02831201583581e-05 -1.45447276083285e-06 5.21998313997354e-05 1.00347429831992e-05 8.97416321555699e-06 4.22020558188837e-07 1.07321704413424e-05 -2.23268257699784e-06 1.00347429831992e-05 3.21504475345844e-05 9.11638052515981e-06 2.15260090158676e-05 -8.98969528826594e-06 -9.86339220816114e-07 8.97416321555699e-06 9.11638052515981e-06 4.11204552094469e-05 819 829 0 260 0 819 829 0 268 0 0 0 0 0 0 0 0 0 1812 0 0 0 0 0 1832 +932 873 0.973873647123539 0.209265533823813 -0.0881932865457009 0.00835865961236926 -0.218429428117451 0.969436456709434 -0.111720818717649 -0.0253708777858536 0.0621184704462418 0.12806597032816 0.989818368627965 0.180776224768278 2.98896187295452e-05 -1.94285685919798e-05 4.23010421480288e-06 3.55947405063825e-06 -5.96136759087272e-07 1.17219155179147e-05 -1.94285685919798e-05 8.85839683952362e-05 -6.39420281550782e-06 2.23384811726084e-05 1.27764243703541e-05 9.32989898379369e-06 4.23010421480288e-06 -6.39420281550782e-06 1.05756419358337e-05 -9.27525259189564e-07 -1.30107354568539e-07 8.63191159135442e-07 3.55947405063825e-06 2.23384811726084e-05 -9.27525259189564e-07 4.72487027602742e-05 -1.13518923490501e-06 1.11123861936079e-05 -5.96136759087272e-07 1.27764243703541e-05 -1.30107354568539e-07 -1.13518923490501e-06 2.61755095524861e-05 1.67572761217605e-06 1.17219155179147e-05 9.32989898379369e-06 8.63191159135442e-07 1.11123861936079e-05 1.67572761217605e-06 4.94674223828532e-05 709 715 0 204 0 709 715 0 213 0 0 0 0 0 0 0 0 0 1708 0 0 0 0 0 1572 +932 872 0.971673441424426 0.221670223857701 -0.0819331134846566 0.00712224096559808 -0.229405406824252 0.968008523251119 -0.101649683880414 -0.0326805354876136 0.0567792440088129 0.117566197387112 0.99144052100049 0.179100879236396 3.21111334127493e-05 -2.54925086801827e-05 4.27537622068684e-06 6.22889716532951e-06 1.3914008206135e-06 1.75554422918854e-05 -2.54925086801827e-05 7.12415792642953e-05 -5.12991651730617e-06 1.58247518732798e-05 9.41545384876426e-06 -1.44957493662039e-06 4.27537622068684e-06 -5.12991651730617e-06 1.106547384847e-05 7.4487513809289e-07 -5.58680644184173e-07 4.59341109282853e-07 6.22889716532951e-06 1.58247518732798e-05 7.4487513809289e-07 4.54603378019955e-05 1.62279901032632e-06 6.85314673074164e-06 1.3914008206135e-06 9.41545384876426e-06 -5.58680644184173e-07 1.62279901032632e-06 2.51176423625417e-05 2.40456955762997e-06 1.75554422918854e-05 -1.44957493662039e-06 4.59341109282853e-07 6.85314673074164e-06 2.40456955762997e-06 5.05014424303023e-05 749 758 0 201 0 749 758 0 212 0 0 0 0 0 0 0 0 0 1844 0 0 0 0 0 1504 +932 870 0.970002381330184 0.234823940449787 -0.0628736606649097 0.00096728923138526 -0.240341863848972 0.965201918076849 -0.103058458276721 -0.0382056454598282 0.0364851846010641 0.115078122735849 0.992686182523067 0.168257989549012 2.93066135890831e-05 -2.6189599336176e-05 6.30678043255425e-06 9.8586554144773e-07 -2.85026388723189e-06 1.25358201898375e-05 -2.6189599336176e-05 0.000125171597661131 -1.1530393312601e-05 3.31701252673881e-05 1.32315581010328e-05 -1.89744956282413e-06 6.30678043255425e-06 -1.1530393312601e-05 1.20646009790381e-05 -4.38228545818048e-06 -2.23493991010789e-07 1.20961222182537e-06 9.8586554144773e-07 3.31701252673881e-05 -4.38228545818048e-06 5.5792541450732e-05 5.95275070504141e-06 5.42278553474005e-06 -2.85026388723189e-06 1.32315581010328e-05 -2.23493991010789e-07 5.95275070504141e-06 2.91614837528734e-05 1.05178268379361e-06 1.25358201898375e-05 -1.89744956282413e-06 1.20961222182537e-06 5.42278553474005e-06 1.05178268379361e-06 3.434492088809e-05 779 788 0 250 0 779 788 0 257 0 0 0 0 0 0 0 0 0 1796 0 0 0 0 0 1307 +932 868 0.973126019134425 0.224828599906199 -0.0497780227389946 0.0102308697026724 -0.229041519327321 0.967363649421995 -0.108386125501342 -0.0316108520156043 0.0237851488920805 0.116874592795774 0.992861821328126 0.162400840465341 2.8108207475151e-05 -2.28555300651412e-05 4.81807568869517e-06 2.95295453282631e-06 -5.98920614379198e-07 7.70316962895016e-06 -2.28555300651412e-05 9.48004283601049e-05 -7.54247680485916e-06 1.6408427271137e-05 1.14433738752344e-05 1.5693567441088e-05 4.81807568869517e-06 -7.54247680485916e-06 1.09213374665021e-05 -1.22145935542436e-06 -9.67928485580539e-07 -1.53788587620501e-06 2.95295453282631e-06 1.6408427271137e-05 -1.22145935542436e-06 4.59038325256219e-05 5.88676016361108e-06 1.054272450995e-05 -5.98920614379198e-07 1.14433738752344e-05 -9.67928485580539e-07 5.88676016361108e-06 2.82321335124401e-05 5.68436213966869e-06 7.70316962895016e-06 1.5693567441088e-05 -1.53788587620501e-06 1.054272450995e-05 5.68436213966869e-06 4.10663374064833e-05 802 805 0 237 0 802 805 0 246 0 0 0 0 0 0 0 0 0 1895 0 0 0 0 0 1741 +932 876 0.971578912853715 0.220974987038993 -0.0848791564585221 0.0278065243433046 -0.229503025485468 0.967176408100108 -0.109078673019016 -0.0258536078600893 0.057989459309513 0.125458561755227 0.990402631201725 0.189083955869673 3.77842154387863e-05 -2.73638290345438e-05 4.32864421109064e-06 5.98168948402167e-06 -1.07514213693608e-06 2.09476132472735e-05 -2.73638290345438e-05 7.92379723911016e-05 -6.07192189277886e-06 1.09892505210142e-05 5.85088163930485e-06 9.25445099599512e-06 4.32864421109064e-06 -6.07192189277886e-06 1.16170926807903e-05 -2.16330453254516e-06 -1.77372460160307e-06 -1.55267088939856e-06 5.98168948402167e-06 1.09892505210142e-05 -2.16330453254516e-06 5.23588534523046e-05 1.3553262359453e-05 1.59275936433526e-05 -1.07514213693608e-06 5.85088163930485e-06 -1.77372460160307e-06 1.3553262359453e-05 2.92449507739983e-05 4.5057715574968e-06 2.09476132472735e-05 9.25445099599512e-06 -1.55267088939856e-06 1.59275936433526e-05 4.5057715574968e-06 5.66833096613545e-05 701 708 0 200 0 701 708 0 206 0 0 0 0 0 0 0 0 0 1802 0 0 0 0 0 1297 +932 871 0.969410377386988 0.232847890159925 -0.0776233229286802 0.0104557021515445 -0.239730330074311 0.96609019292966 -0.0959119803131767 -0.0384361374911358 0.0526582287670265 0.111586733858487 0.992358560082954 0.175725390841454 3.80792262130348e-05 -3.35227743119663e-05 -1.94125356875833e-06 7.5004177732088e-06 -3.62853303138494e-06 2.05491875207942e-05 -3.35227743119663e-05 5.64620013677385e-05 1.4538179646247e-06 1.32454874073926e-06 6.77296067259554e-06 -1.39368601077051e-05 -1.94125356875833e-06 1.4538179646247e-06 1.17535830422766e-05 -2.04334629077042e-06 -1.48305157237755e-06 -2.92431873073644e-06 7.5004177732088e-06 1.32454874073926e-06 -2.04334629077042e-06 5.23126057778556e-05 5.53349496696553e-06 9.2033282640636e-06 -3.62853303138494e-06 6.77296067259554e-06 -1.48305157237755e-06 5.53349496696553e-06 2.73132250203286e-05 4.60589232101848e-07 2.05491875207942e-05 -1.39368601077051e-05 -2.92431873073644e-06 9.2033282640636e-06 4.60589232101848e-07 4.07724852754519e-05 747 757 0 245 0 747 757 0 254 0 0 0 0 0 0 0 0 0 1897 0 0 0 0 0 1839 +932 874 0.972568996537836 0.213413115367917 -0.0925439850144052 0.0141113352820457 -0.222793727652685 0.968995013777681 -0.106825175837029 -0.029283824598679 0.0668767664589693 0.12451307346199 0.989961611702717 0.187140447168376 3.2925710161431e-05 -2.55926394865524e-05 2.05613406786564e-06 2.39977190654367e-06 1.07921637101828e-07 2.48122352426092e-05 -2.55926394865524e-05 6.82835092084915e-05 -3.6173585445747e-06 1.12668141978658e-05 9.22316131969244e-06 -1.21300213066146e-05 2.05613406786564e-06 -3.6173585445747e-06 1.00226811689602e-05 -1.98130518232098e-06 -2.69807406358814e-07 4.74559491113987e-07 2.39977190654367e-06 1.12668141978658e-05 -1.98130518232098e-06 4.22273889342235e-05 7.12551347798353e-06 7.78649167382558e-06 1.07921637101828e-07 9.22316131969244e-06 -2.69807406358814e-07 7.12551347798353e-06 2.31122280565962e-05 9.1875560195304e-07 2.48122352426092e-05 -1.21300213066146e-05 4.74559491113987e-07 7.78649167382558e-06 9.1875560195304e-07 4.49189080047202e-05 723 730 0 199 0 723 730 0 210 0 0 0 0 0 0 0 0 0 1714 0 0 0 0 0 1659 +932 886 0.971951285710995 0.227086092271462 -0.0611768330466732 0.0199232446635908 -0.232268758730044 0.967683660470338 -0.0981812455448227 -0.0274526819814369 0.0369042263534688 0.109636854914783 0.993286382732415 0.186350633613666 3.32922374007692e-05 -3.04939674989863e-05 7.84107774330594e-06 2.12339968581865e-06 1.26766889400167e-06 2.35893268565482e-05 -3.04939674989863e-05 0.000181314074434845 -1.57321863372116e-05 4.58644230389438e-05 1.81246173223051e-05 -3.64961267633474e-05 7.84107774330594e-06 -1.57321863372116e-05 1.2388106914288e-05 -4.79551393629281e-06 -2.29925995298849e-07 5.23146733282312e-06 2.12339968581865e-06 4.58644230389438e-05 -4.79551393629281e-06 6.57323463957118e-05 1.3617965523459e-05 -6.65007917465173e-06 1.26766889400167e-06 1.81246173223051e-05 -2.29925995298849e-07 1.3617965523459e-05 2.96743185521253e-05 -5.6839868876227e-06 2.35893268565482e-05 -3.64961267633474e-05 5.23146733282312e-06 -6.65007917465173e-06 -5.6839868876227e-06 4.65825894804575e-05 741 749 0 229 0 741 749 0 241 0 0 0 0 0 0 0 0 0 1789 0 0 0 0 0 1738 +932 875 0.971163558750714 0.222116566910476 -0.0866347093176394 0.0233902354197565 -0.230788690568553 0.967005619040113 -0.107873597559829 -0.0277460390589104 0.0598157375637927 0.124757218022651 0.990382609949785 0.188786514821587 2.9950781101988e-05 -2.04655044234613e-05 1.5683104339022e-06 4.44977664131485e-06 2.66524690414611e-06 2.18893976513439e-05 -2.04655044234613e-05 5.68989709677211e-05 -3.43918728047765e-07 -6.93921103941358e-08 5.06748471354897e-07 -9.15857671174518e-06 1.5683104339022e-06 -3.43918728047765e-07 1.25704747492256e-05 -3.8240666051158e-06 1.68611823017172e-06 -8.44470446260875e-07 4.44977664131485e-06 -6.93921103941358e-08 -3.8240666051158e-06 4.30909840196352e-05 6.94362874805285e-07 5.22272091890505e-06 2.66524690414611e-06 5.06748471354897e-07 1.68611823017172e-06 6.94362874805285e-07 2.34126912169342e-05 -2.07359696859671e-07 2.18893976513439e-05 -9.15857671174518e-06 -8.44470446260875e-07 5.22272091890505e-06 -2.07359696859671e-07 4.59582097868618e-05 734 740 0 205 0 734 740 0 215 0 0 0 0 0 0 0 0 0 1748 0 0 0 0 0 1549 +932 898 0.972683733725848 0.229597298965511 0.0342262246367472 -0.0109407802311412 -0.22989127470083 0.973204166270053 0.00486339089919273 -0.0488299213636761 -0.032192482997909 -0.0125988516283339 0.999402277852155 0.187700100442246 3.30968807246283e-05 -3.11351970234114e-05 -6.62472087183928e-06 6.84224157924249e-06 -4.32317371458678e-07 1.88042292756097e-05 -3.11351970234114e-05 6.64206714957016e-05 8.63929894746021e-06 -2.0793793459804e-08 3.57553592033554e-06 -4.40184467190536e-06 -6.62472087183928e-06 8.63929894746021e-06 1.11329813873117e-05 -3.5624878170675e-06 3.45109108220404e-06 -6.10566716391627e-06 6.84224157924249e-06 -2.0793793459804e-08 -3.5624878170675e-06 3.59280831838343e-05 1.14500499176933e-06 9.3165266416044e-06 -4.32317371458678e-07 3.57553592033554e-06 3.45109108220404e-06 1.14500499176933e-06 1.88453462748326e-05 1.25190720581686e-06 1.88042292756097e-05 -4.40184467190536e-06 -6.10566716391627e-06 9.3165266416044e-06 1.25190720581686e-06 3.78958209461117e-05 986 1005 0 376 0 986 1005 0 393 0 0 0 0 0 0 0 0 0 2466 0 0 0 0 0 1697 +932 888 0.972879198972977 0.229623363574615 -0.0279137082161996 0.00685857303260227 -0.230840152204987 0.971510420321794 -0.0536686811478547 -0.0354680202384445 0.0147948753180761 0.0586567481782941 0.998168571713952 0.183285607432607 2.98640366312219e-05 -2.28847554734106e-05 8.74307397817271e-07 5.69552414890474e-06 1.52969786697561e-06 1.88193912710693e-05 -2.28847554734106e-05 9.4044459212601e-05 -1.9458313150628e-06 2.0323720150174e-05 5.89346419636743e-06 -1.58606856952841e-05 8.74307397817271e-07 -1.9458313150628e-06 9.55580492004958e-06 -2.59144185015113e-06 3.11737677889448e-06 -2.09712746650671e-06 5.69552414890474e-06 2.0323720150174e-05 -2.59144185015113e-06 5.01319094569549e-05 5.71031690622402e-06 1.68949268605894e-06 1.52969786697561e-06 5.89346419636743e-06 3.11737677889448e-06 5.71031690622402e-06 1.94803426618143e-05 -1.63482673133244e-08 1.88193912710693e-05 -1.58606856952841e-05 -2.09712746650671e-06 1.68949268605894e-06 -1.63482673133244e-08 3.32915065730444e-05 783 790 0 271 0 783 790 0 286 0 0 0 0 0 0 0 0 0 2042 0 0 0 0 0 1507 +932 887 0.972415372726932 0.227207776389594 -0.0527728076990209 0.00569660004455232 -0.230976154792248 0.96949794149201 -0.0819985204753278 -0.0329573691291094 0.0325324269265187 0.0919258820509834 0.995234280663312 0.190574954471268 2.57552766985427e-05 -1.57445067532335e-05 2.99055356074384e-06 2.71309370732364e-06 9.8677660331083e-07 1.85605842667123e-05 -1.57445067532335e-05 8.87323999755479e-05 -4.50348092835284e-06 1.5215875668925e-05 5.07038613211115e-06 -5.13091670857753e-06 2.99055356074384e-06 -4.50348092835284e-06 1.00402879559831e-05 -7.86731165945825e-07 1.55756120949734e-06 1.7431528583045e-09 2.71309370732364e-06 1.5215875668925e-05 -7.86731165945825e-07 4.12192210709221e-05 4.39038332588e-06 -1.41504557503394e-07 9.8677660331083e-07 5.07038613211115e-06 1.55756120949734e-06 4.39038332588e-06 2.27834228270567e-05 -1.01670062400747e-06 1.85605842667123e-05 -5.13091670857753e-06 1.7431528583045e-09 -1.41504557503394e-07 -1.01670062400747e-06 3.93019018703129e-05 745 756 0 241 0 745 756 0 252 0 0 0 0 0 0 0 0 0 1911 0 0 0 0 0 1682 +932 929 0.977167636726626 0.207728721253798 0.0446339344038011 -0.0124837900016326 -0.208881923019691 0.977672809013285 0.0228958675675041 -0.0493026105159819 -0.038881254734085 -0.0316963228519445 0.998741003037308 0.180666874754145 2.97498304710415e-05 -2.01215062097617e-05 -4.03313903895243e-06 6.04037312301374e-06 2.17764215251715e-06 1.86141334543371e-05 -2.01215062097617e-05 5.56590099078652e-05 6.76567743203411e-06 -4.6335662465798e-07 4.10637885484398e-07 -6.55562798848463e-06 -4.03313903895243e-06 6.76567743203411e-06 1.06449735207381e-05 -1.60243652713446e-06 2.49362861291314e-06 -5.38495325545354e-06 6.04037312301374e-06 -4.6335662465798e-07 -1.60243652713446e-06 3.1901561004926e-05 -3.89112909417e-06 2.90002003614372e-06 2.17764215251715e-06 4.10637885484398e-07 2.49362861291314e-06 -3.89112909417e-06 2.05676688009128e-05 3.74747543204085e-06 1.86141334543371e-05 -6.55562798848463e-06 -5.38495325545354e-06 2.90002003614372e-06 3.74747543204085e-06 3.44210933498426e-05 960 983 0 356 0 960 983 0 373 0 0 0 0 0 0 0 0 0 2561 0 0 0 0 0 1740 +932 890 0.973181731652248 0.229903038119857 0.00786830614498022 -0.00558215738581074 -0.229721325477995 0.973067996352386 -0.0191516864893472 -0.0426090892221853 -0.012059427804203 0.0168305537048724 0.99978562835391 0.190981546426659 1.94942243020419e-05 -1.11284974087366e-05 1.40924413368252e-06 1.72318345201355e-06 -9.45443004338065e-07 8.09914975108075e-06 -1.11284974087366e-05 6.4587720125088e-05 1.17660021479106e-06 1.33598740917353e-05 6.75374082092309e-06 -5.42274290113275e-06 1.40924413368252e-06 1.17660021479106e-06 9.28103297717162e-06 -8.56315432450618e-07 1.9830957251801e-06 -2.41441111011903e-06 1.72318345201355e-06 1.33598740917353e-05 -8.56315432450618e-07 4.26489283053104e-05 7.31700341643922e-06 2.26043188033998e-06 -9.45443004338065e-07 6.75374082092309e-06 1.9830957251801e-06 7.31700341643922e-06 2.27232359186888e-05 2.61346712095153e-06 8.09914975108075e-06 -5.42274290113275e-06 -2.41441111011903e-06 2.26043188033998e-06 2.61346712095153e-06 2.71053108716685e-05 823 835 0 320 0 823 835 0 337 0 0 0 0 0 0 0 0 0 2230 0 0 0 0 0 2035 +932 899 0.972834396702775 0.229234462356128 0.0323233330621291 -0.0135171934058424 -0.229485416126808 0.97330290672364 0.00423031304026492 -0.0507628149176389 -0.0304906604889833 -0.0115331275727581 0.999468512055951 0.190101593217921 2.57069738991654e-05 -2.07040992033333e-05 -7.40723574440173e-07 3.98572364063202e-06 -5.29451107756526e-07 1.8151400711897e-05 -2.07040992033333e-05 6.59173766935102e-05 2.30326802359744e-06 2.07028831971685e-05 9.98914238758629e-06 -1.19185000798922e-05 -7.40723574440173e-07 2.30326802359744e-06 9.74262522529808e-06 -4.24314876910409e-06 3.10589216897684e-06 -3.48132447465057e-06 3.98572364063202e-06 2.07028831971685e-05 -4.24314876910409e-06 4.83184104372041e-05 6.48615477941796e-06 5.96167875780279e-06 -5.29451107756526e-07 9.98914238758629e-06 3.10589216897684e-06 6.48615477941796e-06 2.037804845934e-05 1.49313599190105e-06 1.8151400711897e-05 -1.19185000798922e-05 -3.48132447465057e-06 5.96167875780279e-06 1.49313599190105e-06 3.30736107370245e-05 931 953 0 379 0 931 953 0 399 0 0 0 0 0 0 0 0 0 2481 0 0 0 0 0 1781 +932 889 0.973317088499477 0.229463246214082 -0.000681081344089961 -0.00201575425798993 -0.229333369998683 0.972657384119611 -0.0366581303757043 -0.0415601773478433 -0.00774923479763292 0.0358361794069981 0.99932763276393 0.18851510158972 2.67034458749137e-05 -1.63776264568771e-05 4.06859172045692e-06 -1.26054855477347e-06 -2.9704262785737e-06 1.41014558906231e-05 -1.63776264568771e-05 9.12013039133834e-05 1.12990812723715e-06 7.1212989581193e-06 8.77591597684718e-06 -3.36973489878984e-06 4.06859172045692e-06 1.12990812723715e-06 1.18001434972386e-05 -5.64924917119795e-06 2.3982704815952e-06 -3.10915816145346e-06 -1.26054855477347e-06 7.1212989581193e-06 -5.64924917119795e-06 5.88328843795528e-05 1.39712744924773e-05 1.07220912790847e-06 -2.9704262785737e-06 8.77591597684718e-06 2.3982704815952e-06 1.39712744924773e-05 2.97368113643404e-05 7.75873192542989e-07 1.41014558906231e-05 -3.36973489878984e-06 -3.10915816145346e-06 1.07220912790847e-06 7.75873192542989e-07 3.19022513207875e-05 801 819 0 318 0 801 819 0 332 0 0 0 0 0 0 0 0 0 2143 0 0 0 0 0 1823 +932 897 0.972713650453114 0.228847000899875 0.0381733467397121 -0.00894651112558098 -0.229179126375586 0.973373839119005 0.00450525831133222 -0.0493057914547981 -0.0361259222152269 -0.0131308605148897 0.999260976044916 0.189834062445882 3.04558467014892e-05 -1.85886223638627e-05 -1.34988583578465e-07 5.45047391844733e-06 -2.11315985713651e-06 1.65362213372668e-05 -1.85886223638627e-05 6.98154977554311e-05 5.09288940183599e-06 8.34197701563143e-06 5.62663110458833e-06 -3.28651881572749e-06 -1.34988583578465e-07 5.09288940183599e-06 9.53786974075986e-06 -1.99112154158649e-06 2.73781925034947e-06 -2.08705035673413e-06 5.45047391844733e-06 8.34197701563143e-06 -1.99112154158649e-06 3.81859527348135e-05 8.13850201092555e-07 7.97805630483782e-06 -2.11315985713651e-06 5.62663110458833e-06 2.73781925034947e-06 8.13850201092555e-07 2.02826391508071e-05 1.93970112547212e-06 1.65362213372668e-05 -3.28651881572749e-06 -2.08705035673413e-06 7.97805630483782e-06 1.93970112547212e-06 3.60124871021602e-05 925 942 0 378 0 925 942 0 397 0 0 0 0 0 0 0 0 0 2339 0 0 0 0 0 1724 +932 900 0.972764092781831 0.229190187100805 0.0346681111547837 -0.013275487119508 -0.229443481760292 0.973315837280801 0.00345970751495776 -0.0519136779627208 -0.032950090622895 -0.0113198513714848 0.999392891956347 0.190509225110853 1.85071955729839e-05 -1.31156854565581e-05 1.09724681262939e-06 2.96244150911825e-06 -5.06462605243411e-07 9.20303662523482e-06 -1.31156854565581e-05 4.10354487989547e-05 1.07266719868766e-06 2.45446530105998e-06 7.82947626422355e-06 -2.47696463402389e-06 1.09724681262939e-06 1.07266719868766e-06 9.07403206398992e-06 -1.91669157839322e-06 2.48006446053447e-06 -2.30302220125347e-06 2.96244150911825e-06 2.45446530105998e-06 -1.91669157839322e-06 3.04955439759467e-05 1.59741553478733e-06 3.97633697883201e-06 -5.06462605243411e-07 7.82947626422355e-06 2.48006446053447e-06 1.59741553478733e-06 1.9358147957492e-05 3.11473804218364e-06 9.20303662523482e-06 -2.47696463402389e-06 -2.30302220125347e-06 3.97633697883201e-06 3.11473804218364e-06 2.77465816795847e-05 970 992 0 383 0 970 992 0 398 0 0 0 0 0 0 0 0 0 2371 0 0 0 0 0 1722 +932 885 0.971278162273887 0.22630353382098 -0.0735217115551393 0.0132387826699033 -0.232936444701609 0.967373561385632 -0.0996443950348141 -0.0297661639785108 0.0485730812244301 0.113908310988339 0.992303155526651 0.185915003202631 3.15255227295278e-05 -2.79541268654366e-05 1.92681403869143e-06 3.29385478767774e-06 5.17719973816198e-07 1.5118355856738e-05 -2.79541268654366e-05 0.000134250485811961 -6.05124893426001e-06 2.58430166383242e-05 1.00908354890735e-05 1.10866504439439e-05 1.92681403869143e-06 -6.05124893426001e-06 1.13893355474639e-05 -2.47646413086359e-07 -4.1320689435728e-07 3.45488144734578e-07 3.29385478767774e-06 2.58430166383242e-05 -2.47646413086359e-07 4.606972881801e-05 2.12181812315491e-06 1.37312888400291e-05 5.17719973816198e-07 1.00908354890735e-05 -4.1320689435728e-07 2.12181812315491e-06 2.59979590296476e-05 4.92191692791945e-06 1.5118355856738e-05 1.10866504439439e-05 3.45488144734578e-07 1.37312888400291e-05 4.92191692791945e-06 4.65831180568665e-05 700 707 0 200 0 700 707 0 213 0 0 0 0 0 0 0 0 0 1760 0 0 0 0 0 1448 +932 891 0.972896749052526 0.229128814127684 0.0311753463407657 -0.00940811309700835 -0.229254983466288 0.973366280431445 0.000486492472111719 -0.0497333631096619 -0.0302335614656561 -0.00762041045446405 0.999513812363595 0.187265749994445 2.37943008024276e-05 -1.72872475837916e-05 -5.09670403630443e-07 3.19431535391764e-06 -1.43796142446189e-06 9.71162082121769e-06 -1.72872475837916e-05 4.66184044133302e-05 2.62091533308447e-06 6.28760011117033e-06 5.20355331233662e-06 -6.18369561795724e-06 -5.09670403630443e-07 2.62091533308447e-06 8.85798730340064e-06 -2.3965041868447e-06 1.909728508773e-06 -1.39777678158121e-06 3.19431535391764e-06 6.28760011117033e-06 -2.3965041868447e-06 4.38039371769428e-05 7.53014556443548e-06 9.63622927502309e-06 -1.43796142446189e-06 5.20355331233662e-06 1.909728508773e-06 7.53014556443548e-06 2.33122125687901e-05 6.3465508220835e-06 9.71162082121769e-06 -6.18369561795724e-06 -1.39777678158121e-06 9.63622927502309e-06 6.3465508220835e-06 3.044551938998e-05 883 907 0 380 0 883 907 0 393 0 0 0 0 0 0 0 0 0 2322 0 0 0 0 0 2019 +932 884 0.971500101796217 0.225250013075103 -0.0738240057136279 0.00699149321195388 -0.232085395436248 0.967228133882509 -0.102985951718477 -0.028584010363889 0.0482070683109851 0.117184336136816 0.991939468883578 0.188704189286778 3.59606675434196e-05 -3.23327911196222e-05 1.95554906372808e-06 5.18411462402528e-06 -5.26423775126238e-07 1.34702248306633e-05 -3.23327911196222e-05 9.254691487426e-05 -3.24867660783843e-06 1.87649096068185e-05 9.83498889446966e-06 1.26175266674439e-05 1.95554906372808e-06 -3.24867660783843e-06 1.20777474456703e-05 -8.54775757564425e-07 8.62320830505811e-07 -3.82737794725617e-08 5.18411462402528e-06 1.87649096068185e-05 -8.54775757564425e-07 5.42356269495666e-05 7.31068372244624e-06 1.77889522741879e-05 -5.26423775126238e-07 9.83498889446966e-06 8.62320830505811e-07 7.31068372244624e-06 2.83581680296412e-05 8.36902603015829e-06 1.34702248306633e-05 1.26175266674439e-05 -3.82737794725617e-08 1.77889522741879e-05 8.36902603015829e-06 4.80393244513919e-05 671 681 0 214 0 671 681 0 220 0 0 0 0 0 0 0 0 0 1802 0 0 0 0 0 1100 +932 892 0.972720478187838 0.229078107291999 0.0365799408629913 -0.00666103626084505 -0.229338132046975 0.973342124748725 0.00302148619764778 -0.0500513135345897 -0.0349126410234006 -0.0113282368069211 0.999326162245149 0.190464415579225 2.43185589785834e-05 -1.70560599541486e-05 -7.26228958905004e-07 4.15827991655845e-06 -1.97289072595359e-06 1.47576294330059e-05 -1.70560599541486e-05 4.87038838915001e-05 1.95999586297547e-06 3.16856853985172e-06 4.54813318401248e-06 -4.41328994592717e-06 -7.26228958905004e-07 1.95999586297547e-06 9.14725071913404e-06 -2.35433763718189e-06 3.11588802411438e-06 -2.68385865785412e-06 4.15827991655845e-06 3.16856853985172e-06 -2.35433763718189e-06 4.05132657962436e-05 6.57877801591977e-06 5.57839051519364e-06 -1.97289072595359e-06 4.54813318401248e-06 3.11588802411438e-06 6.57877801591977e-06 2.34533112121882e-05 8.99608362367563e-07 1.47576294330059e-05 -4.41328994592717e-06 -2.68385865785412e-06 5.57839051519364e-06 8.99608362367563e-07 2.93853245553638e-05 949 973 0 383 0 949 973 0 399 0 0 0 0 0 0 0 0 0 2466 0 0 0 0 0 1797 +932 901 0.972824357152274 0.229537369398533 0.0304198320321937 -0.0145435948449887 -0.229767844719519 0.973236127566877 0.00426351164846022 -0.049794187624907 -0.0286270442800595 -0.0111371472213915 0.999528116806904 0.190506037875234 2.29147404149408e-05 -1.43734061890225e-05 2.09109672019248e-06 1.97238774234835e-06 -1.16374849190652e-06 1.4752172643071e-05 -1.43734061890225e-05 5.696747296192e-05 3.33687286725481e-06 7.90911809629346e-06 6.142338578081e-06 -7.96826975933863e-06 2.09109672019248e-06 3.33687286725481e-06 1.07591711094871e-05 -3.62410349630249e-06 5.41433865722416e-06 -2.92062635215097e-06 1.97238774234835e-06 7.90911809629346e-06 -3.62410349630249e-06 3.86300493869982e-05 7.58156885084508e-07 6.26139128452968e-07 -1.16374849190652e-06 6.142338578081e-06 5.41433865722416e-06 7.58156885084508e-07 2.21059989558665e-05 -8.19566715471266e-07 1.4752172643071e-05 -7.96826975933863e-06 -2.92062635215097e-06 6.26139128452968e-07 -8.19566715471266e-07 3.5715030680257e-05 909 930 0 384 0 909 930 0 399 0 0 0 0 0 0 0 0 0 2331 0 0 0 0 0 1773 +932 877 0.97203684540384 0.218834712017462 -0.0851806315636651 0.0237119636521575 -0.227708693778638 0.967012555241084 -0.114172977467244 -0.0270213100123483 0.0573857295412087 0.130376711196225 0.989802400089371 0.190051036181893 3.06862225294587e-05 -2.27153480653436e-05 1.29452169257838e-06 8.08767423794963e-06 3.29411250762921e-06 1.15121583591849e-05 -2.27153480653436e-05 9.19012971035584e-05 -7.10593187012137e-06 2.92666459381583e-05 1.44408388672572e-05 9.09553118644859e-06 1.29452169257838e-06 -7.10593187012137e-06 1.02967108982516e-05 -1.22533153873103e-06 -2.62028636099429e-06 -3.45867919423502e-06 8.08767423794963e-06 2.92666459381583e-05 -1.22533153873103e-06 5.80910664684823e-05 1.1368867674591e-05 1.40407184935978e-05 3.29411250762921e-06 1.44408388672572e-05 -2.62028636099429e-06 1.1368867674591e-05 3.0103697359416e-05 5.42367423130272e-06 1.15121583591849e-05 9.09553118644859e-06 -3.45867919423502e-06 1.40407184935978e-05 5.42367423130272e-06 4.66566007208639e-05 703 711 0 197 0 703 711 0 208 0 0 0 0 0 0 0 0 0 1669 0 0 0 0 0 1528 +932 895 0.973014136982301 0.229013511906011 0.0282187986466953 -0.0193888857976213 -0.229194111088891 0.973375152086552 0.00329738421394306 -0.0525508616832193 -0.0267123318854883 -0.00967598392705461 0.999596331856156 0.185713043889924 2.92749048146598e-05 -2.31829746134484e-05 -2.22107324599317e-06 6.60304735555515e-06 -1.00564111830475e-06 2.10482824309977e-05 -2.31829746134484e-05 6.3087250413626e-05 3.53665812957805e-06 2.73293424648901e-06 5.18467239050367e-07 -1.70522275735716e-05 -2.22107324599317e-06 3.53665812957805e-06 1.07830287309672e-05 -4.25553908705099e-06 3.47263863706349e-06 -4.87402694324528e-06 6.60304735555515e-06 2.73293424648901e-06 -4.25553908705099e-06 4.71183514478625e-05 5.03834932264606e-06 2.1985624296535e-06 -1.00564111830475e-06 5.18467239050367e-07 3.47263863706349e-06 5.03834932264606e-06 2.32750734850739e-05 -3.81996556604172e-07 2.10482824309977e-05 -1.70522275735716e-05 -4.87402694324528e-06 2.1985624296535e-06 -3.81996556604172e-07 3.73895605067795e-05 896 919 0 371 0 896 919 0 389 0 0 0 0 0 0 0 0 0 2381 0 0 0 0 0 1849 +932 894 0.97288012281428 0.228924985208032 0.0331303151263883 -0.0118158715379349 -0.229155493267256 0.973384285393871 0.00328524789084001 -0.0517081351388107 -0.031496452789358 -0.0107881460764029 0.999445641026025 0.189058701423258 2.48045688038951e-05 -1.95919226554763e-05 1.28599526851996e-06 4.34231613795609e-06 1.21372010830331e-06 1.6857226466036e-05 -1.95919226554763e-05 4.22926706189661e-05 1.204911870145e-06 2.09907933630707e-07 2.47872441200565e-06 -9.16732504755107e-06 1.28599526851996e-06 1.204911870145e-06 1.02129550511387e-05 -4.56460069664121e-06 2.97130063209126e-06 -2.63813294479473e-06 4.34231613795609e-06 2.09907933630707e-07 -4.56460069664121e-06 4.63087294080957e-05 7.05640645760803e-06 5.62398996923764e-06 1.21372010830331e-06 2.47872441200565e-06 2.97130063209126e-06 7.05640645760803e-06 2.09075203746858e-05 1.0718439313697e-06 1.6857226466036e-05 -9.16732504755107e-06 -2.63813294479473e-06 5.62398996923764e-06 1.0718439313697e-06 3.27361228078702e-05 937 956 0 370 0 937 956 0 386 0 0 0 0 0 0 0 0 0 2324 0 0 0 0 0 1759 +933 859 0.956527101423819 0.290778744127543 0.0224416177080867 -0.0593862382149119 -0.289293067282786 0.95575467046603 -0.0533153927537675 -0.0518286691525169 -0.0369516638849242 0.0445054136704736 0.998325519402442 0.159841797790331 2.66387310846594e-05 -7.34765172959022e-06 4.22070775808115e-07 4.78029840206173e-06 -1.28368407890647e-06 1.67350635906456e-05 -7.34765172959022e-06 5.39864258701606e-05 -1.68785703742099e-06 9.08278159720504e-07 2.1772838551939e-06 6.57160400108612e-06 4.22070775808115e-07 -1.68785703742099e-06 1.15289811512036e-05 -8.83491483445612e-07 4.65191198437511e-06 -4.90348176729309e-06 4.78029840206173e-06 9.08278159720504e-07 -8.83491483445612e-07 3.93601379393414e-05 -3.76320576373465e-06 -1.9415390457261e-06 -1.28368407890647e-06 2.1772838551939e-06 4.65191198437511e-06 -3.76320576373465e-06 2.28145589946483e-05 1.19407074438847e-07 1.67350635906456e-05 6.57160400108612e-06 -4.90348176729309e-06 -1.9415390457261e-06 1.19407074438847e-07 5.32224405669043e-05 1233 1230 0 408 0 1233 1230 0 412 0 0 0 0 0 0 0 0 0 2452 0 0 0 0 0 975 +933 931 0.979192816079457 0.166457864665689 0.116074149703205 -0.0215849237313093 -0.167990695026125 0.985782435285892 0.00348090023641621 -0.0615577988247895 -0.113844434747697 -0.0229078495881959 0.993234451227011 0.17810580289473 3.07109753524952e-05 -9.48368822473039e-06 -5.79946242514582e-07 3.49200224143815e-06 -4.1426184392969e-06 1.43269288359884e-05 -9.48368822473039e-06 4.82485851645492e-05 2.59794483928014e-06 -1.60300621587254e-06 -1.21889451648228e-06 6.37235900280003e-06 -5.79946242514582e-07 2.59794483928014e-06 1.1594054216729e-05 -3.51051930001613e-06 4.12743774173997e-06 -5.01241852898038e-06 3.49200224143815e-06 -1.60300621587254e-06 -3.51051930001613e-06 3.9861781541357e-05 -6.53930061560626e-06 -8.51970556926243e-07 -4.1426184392969e-06 -1.21889451648228e-06 4.12743774173997e-06 -6.53930061560626e-06 2.18181895313673e-05 -5.10445551193817e-07 1.43269288359884e-05 6.37235900280003e-06 -5.01241852898038e-06 -8.51970556926243e-07 -5.10445551193817e-07 4.24571535500291e-05 1475 1485 0 321 0 1475 1485 0 329 0 0 0 0 0 0 0 0 0 2917 0 0 0 0 0 1198 +933 863 0.960747042980499 0.272202137341838 -0.0535827941671743 -0.0401697185370701 -0.274750669960437 0.960324541488732 -0.0478418683868798 -0.0535693230397113 0.0384342134109412 0.0606858421791403 0.997416683136236 0.244707543567832 2.64357735498931e-05 -1.27253685018249e-05 1.93806420071513e-06 5.19675301310388e-06 3.09345294936555e-07 1.36827720066237e-05 -1.27253685018249e-05 9.70863657184041e-05 -2.00492968181194e-06 2.13134129823251e-05 8.98916965158748e-06 -7.64140049318349e-06 1.93806420071513e-06 -2.00492968181194e-06 1.10541252636762e-05 -3.06955234928138e-06 6.06349984409051e-06 4.32930761404596e-07 5.19675301310388e-06 2.13134129823251e-05 -3.06955234928138e-06 4.88061496956604e-05 -5.29921378760495e-07 5.76280627576402e-06 3.09345294936555e-07 8.98916965158748e-06 6.06349984409051e-06 -5.29921378760495e-07 2.46352210859899e-05 3.39135689690102e-06 1.36827720066237e-05 -7.64140049318349e-06 4.32930761404596e-07 5.76280627576402e-06 3.39135689690102e-06 4.31919813577521e-05 841 836 0 298 0 841 836 0 303 0 0 0 0 0 0 0 0 0 2030 0 0 0 0 0 1496 +932 896 0.972918940238445 0.229032730395503 0.0311888462896758 -0.012134914847442 -0.229229702496653 0.973368197267147 0.00284535449469579 -0.0501487787148118 -0.0297065517789605 -0.00991770923577835 0.999509459597516 0.190036214688846 2.4801903906411e-05 -2.10002049530265e-05 -1.70595369122625e-06 4.29639719745853e-06 -2.53606242304826e-06 1.53766245661827e-05 -2.10002049530265e-05 4.36785723504373e-05 4.37754891651407e-06 5.42465160325753e-06 7.45753381438818e-06 -8.17132596898699e-06 -1.70595369122625e-06 4.37754891651407e-06 1.02574066095713e-05 -1.98473571542358e-06 2.34799946424346e-06 -4.05294645909089e-06 4.29639719745853e-06 5.42465160325753e-06 -1.98473571542358e-06 3.91820081709885e-05 2.27978828602905e-06 7.1602361118142e-06 -2.53606242304826e-06 7.45753381438818e-06 2.34799946424346e-06 2.27978828602905e-06 1.78808349559997e-05 6.52446893069123e-07 1.53766245661827e-05 -8.17132596898699e-06 -4.05294645909089e-06 7.1602361118142e-06 6.52446893069123e-07 2.87861964126019e-05 934 956 0 384 0 934 956 0 397 0 0 0 0 0 0 0 0 0 2424 0 0 0 0 0 1724 +933 860 0.961231863494846 0.273974040407594 0.0311693725468454 -0.0591407620846441 -0.270714805923196 0.95914581395595 -0.0821754307852654 -0.0562421551678594 -0.052409907996414 0.0705516318274453 0.996130347289094 0.188869216232833 3.09775702451457e-05 -8.96816168754779e-06 -3.297273604258e-07 9.12333944196694e-06 1.29527311318191e-06 2.23218051034864e-05 -8.96816168754779e-06 4.44223391838619e-05 -1.85715946586383e-06 1.02493626307547e-05 6.84507586696941e-06 6.66204745768689e-06 -3.297273604258e-07 -1.85715946586383e-06 1.14997989273692e-05 -4.89929625914985e-06 1.13549983584226e-06 -5.58769384850694e-06 9.12333944196694e-06 1.02493626307547e-05 -4.89929625914985e-06 4.96727826094632e-05 7.27443628158424e-06 1.42650157726373e-05 1.29527311318191e-06 6.84507586696941e-06 1.13549983584226e-06 7.27443628158424e-06 3.54522866700077e-05 7.8931988763809e-06 2.23218051034864e-05 6.66204745768689e-06 -5.58769384850694e-06 1.42650157726373e-05 7.8931988763809e-06 5.74844768397662e-05 1279 1286 0 363 0 1279 1286 0 370 0 0 0 0 0 0 0 0 0 2135 0 0 0 0 0 1030 +933 865 0.957704106882573 0.282542930200502 -0.0545191365849468 -0.00650806496476738 -0.285782543342572 0.956057314721022 -0.0654427145607542 -0.0595937723722077 0.0336330429920424 0.0782553740144654 0.996365853919609 0.257313143754629 3.15143821757447e-05 -2.10220167208775e-05 3.78649404876614e-06 5.61991959271609e-06 -3.61937248557839e-06 1.96677638664794e-05 -2.10220167208775e-05 9.71950975678609e-05 -6.33693349298017e-06 3.90418372106858e-05 1.52032684304319e-05 -6.3515655376884e-06 3.78649404876614e-06 -6.33693349298017e-06 1.17022931540857e-05 -5.76175245275196e-06 3.97294986891155e-06 -3.30326289518271e-07 5.61991959271609e-06 3.90418372106858e-05 -5.76175245275196e-06 7.54170286402836e-05 7.21400475246798e-06 9.26770752041546e-06 -3.61937248557839e-06 1.52032684304319e-05 3.97294986891155e-06 7.21400475246798e-06 3.10589927959351e-05 -1.93857004443474e-06 1.96677638664794e-05 -6.3515655376884e-06 -3.30326289518271e-07 9.26770752041546e-06 -1.93857004443474e-06 4.59953171855312e-05 793 796 0 286 0 793 796 0 291 0 0 0 0 0 0 0 0 0 1826 0 0 0 0 0 1251 +933 861 0.962420800161395 0.271247820681181 -0.013069934675038 -0.0459848879400196 -0.271385224806609 0.958939022074504 -0.0823772523179794 -0.048316663414439 -0.00981137978909708 0.0828285682509598 0.996515511724795 0.210555533367124 2.50061637189399e-05 -9.11611471488833e-06 -4.29840334685849e-07 8.62161397136756e-06 -9.17800489081539e-07 1.5894440134195e-05 -9.11611471488833e-06 5.86335617295422e-05 -1.72898032710285e-06 3.04778671717852e-06 6.43676146596223e-06 1.20345691910842e-05 -4.29840334685849e-07 -1.72898032710285e-06 9.0727861814921e-06 -1.41694348044094e-06 3.1069508986596e-06 -4.01452325834102e-06 8.62161397136756e-06 3.04778671717852e-06 -1.41694348044094e-06 3.96264638196443e-05 -4.74499208112658e-06 1.34274721581583e-05 -9.17800489081539e-07 6.43676146596223e-06 3.1069508986596e-06 -4.74499208112658e-06 2.42123538808013e-05 6.28617657677232e-06 1.5894440134195e-05 1.20345691910842e-05 -4.01452325834102e-06 1.34274721581583e-05 6.28617657677232e-06 5.24391966150139e-05 1113 1118 0 328 0 1113 1118 0 335 0 0 0 0 0 0 0 0 0 2029 0 0 0 0 0 1530 +933 866 0.95757594533111 0.286350597855453 -0.0324290615198145 -0.00566516622201432 -0.287960763041944 0.955165379533466 -0.0688309282880314 -0.0602810704423184 0.0112653393882641 0.0752491385234094 0.99710112791028 0.256202729528863 2.45563279268976e-05 -1.55270406987389e-05 7.1819943111795e-06 3.53195883142286e-06 5.02102688993643e-06 1.89059140989806e-05 -1.55270406987389e-05 8.45923058694772e-05 -1.04238357529122e-05 3.37148548624031e-05 1.22084037000099e-05 -1.4298959654704e-05 7.1819943111795e-06 -1.04238357529122e-05 1.1852296269282e-05 -4.0628131448484e-06 5.58880786587485e-06 4.29088647697527e-06 3.53195883142286e-06 3.37148548624031e-05 -4.0628131448484e-06 6.03733451891931e-05 9.40767274122116e-06 9.24313661683544e-06 5.02102688993643e-06 1.22084037000099e-05 5.58880786587485e-06 9.40767274122116e-06 3.06384884689782e-05 8.30899308479095e-06 1.89059140989806e-05 -1.4298959654704e-05 4.29088647697527e-06 9.24313661683544e-06 8.30899308479095e-06 4.40348971236958e-05 765 771 0 281 0 765 771 0 284 0 0 0 0 0 0 0 0 0 1849 0 0 0 0 0 1427 +933 868 0.948415965289338 0.316468182061992 -0.018842678330603 -0.00180289269783983 -0.316838935506156 0.944117017707745 -0.0908633359609868 -0.068496995753452 -0.0109656614765463 0.0921463326292019 0.995685094621472 0.26081097593384 3.14062213517023e-05 -8.62213022692557e-06 2.43906951867141e-06 1.01391878232936e-05 -1.14090358026702e-06 2.58976676800187e-05 -8.62213022692557e-06 7.98938762909878e-05 -5.69249440194898e-06 2.18421928932159e-05 1.33851462056862e-05 5.78306677970544e-06 2.43906951867141e-06 -5.69249440194898e-06 1.14037342967521e-05 -2.80128989824885e-06 7.93966804736821e-07 -1.82365107216882e-06 1.01391878232936e-05 2.18421928932159e-05 -2.80128989824885e-06 5.65188073509342e-05 8.52725123964393e-07 1.41555468532074e-05 -1.14090358026702e-06 1.33851462056862e-05 7.93966804736821e-07 8.52725123964393e-07 3.59266902925438e-05 4.92865799607417e-06 2.58976676800187e-05 5.78306677970544e-06 -1.82365107216882e-06 1.41555468532074e-05 4.92865799607417e-06 6.67398301152457e-05 775 782 0 308 0 775 782 0 307 0 0 0 0 0 0 0 0 0 1641 0 0 0 0 0 1398 +933 862 0.960993309850992 0.274130461385419 -0.0366653591589233 -0.0387773207687799 -0.275691565338644 0.960047616859757 -0.0479868123866265 -0.0501401245654826 0.0220458436618699 0.0562233359248499 0.998174792946966 0.227268341481879 3.40312314206757e-05 -2.69972574063016e-06 1.62203057090978e-06 7.06570234833336e-06 -7.193798117249e-07 2.57613264331817e-05 -2.69972574063016e-06 7.15904200630448e-05 -1.5260628368103e-06 2.11583322573104e-05 1.06420941052004e-05 1.67422147905849e-05 1.62203057090978e-06 -1.5260628368103e-06 1.03538301631383e-05 -4.13753997615114e-06 4.53899645989109e-06 -2.10839740594725e-06 7.06570234833336e-06 2.11583322573104e-05 -4.13753997615114e-06 5.2883328543269e-05 5.40722445807329e-06 1.34014925457686e-05 -7.193798117249e-07 1.06420941052004e-05 4.53899645989109e-06 5.40722445807329e-06 2.88706452839353e-05 6.09381165860361e-06 2.57613264331817e-05 1.67422147905849e-05 -2.10839740594725e-06 1.34014925457686e-05 6.09381165860361e-06 7.16586078146812e-05 986 983 0 308 0 986 983 0 313 0 0 0 0 0 0 0 0 0 2025 0 0 0 0 0 1624 +933 871 0.945212899699945 0.32471811878812 -0.0336261441667827 0.00246343443509127 -0.326359401682348 0.942397961373715 -0.0733186424601949 -0.0722442236191089 0.00788131805986142 0.08027593493302 0.996741520704475 0.271124861682922 3.68706065267177e-05 -1.06144964072917e-05 -1.80075132536227e-06 1.89859386645272e-05 7.91106705960618e-06 2.35421176659249e-05 -1.06144964072917e-05 0.000165749556088178 -5.89450796720374e-06 5.52917209634904e-05 2.35025310631025e-05 4.14558462987553e-06 -1.80075132536227e-06 -5.89450796720374e-06 1.43906171338257e-05 -1.23030406222406e-05 -2.07844746933386e-07 -5.47006217334635e-06 1.89859386645272e-05 5.52917209634904e-05 -1.23030406222406e-05 9.869589003121e-05 2.54754423729039e-05 2.47869066166087e-05 7.91106705960618e-06 2.35025310631025e-05 -2.07844746933386e-07 2.54754423729039e-05 3.4095649192562e-05 1.22253977199076e-05 2.35421176659249e-05 4.14558462987553e-06 -5.47006217334635e-06 2.47869066166087e-05 1.22253977199076e-05 5.12600430668453e-05 718 726 0 332 0 718 726 0 335 0 0 0 0 0 0 0 0 0 1745 0 0 0 0 0 867 +933 930 0.963121487122204 0.234202492002207 0.132462046577389 -0.0314338504989892 -0.23883502827194 0.970853942679603 0.0200112781653602 -0.0721886786505205 -0.12391460896059 -0.0509098686251074 0.99098605185074 0.236880284841714 2.16816140012219e-05 -2.97550313069235e-06 3.69186945077906e-06 4.32353072939974e-06 -4.62930236231622e-06 8.81916189709193e-06 -2.97550313069235e-06 5.69840395273322e-05 -5.95577806386561e-08 3.86751327572232e-06 2.77826089475719e-06 2.15211015762971e-05 3.69186945077906e-06 -5.95577806386561e-08 1.06603966845973e-05 -1.85571325091576e-06 2.50666421174063e-06 -4.00484985472467e-06 4.32353072939974e-06 3.86751327572232e-06 -1.85571325091576e-06 3.98956235320975e-05 -1.09670773754499e-06 7.61013113569589e-06 -4.62930236231622e-06 2.77826089475719e-06 2.50666421174063e-06 -1.09670773754499e-06 2.36319100666613e-05 3.49887442883581e-06 8.81916189709193e-06 2.15211015762971e-05 -4.00484985472467e-06 7.61013113569589e-06 3.49887442883581e-06 5.06286315560069e-05 1136 1150 0 447 0 1136 1150 0 457 0 0 0 0 0 0 0 0 0 2475 0 0 0 0 0 1080 +933 864 0.962756380222234 0.26302105351365 -0.0626105242746892 -0.0309365767065962 -0.266277503131808 0.96254919277223 -0.0509445072546434 -0.0563239448979943 0.0468662316307981 0.0657189234703235 0.996736966019938 0.245362133620028 3.45969820458258e-05 -1.42837063530455e-05 1.61680329070577e-06 1.39734567273601e-05 -3.89658437307024e-07 2.72740086434735e-05 -1.42837063530455e-05 8.32305390001379e-05 -4.31810640612761e-06 3.11649156787899e-05 1.89919299948472e-05 3.34767737888706e-06 1.61680329070577e-06 -4.31810640612761e-06 1.03589102331973e-05 -4.16309152989067e-06 3.27895647906167e-06 -1.22636232868712e-06 1.39734567273601e-05 3.11649156787899e-05 -4.16309152989067e-06 7.19526120172594e-05 1.02815977711906e-05 2.74525969452129e-05 -3.89658437307024e-07 1.89919299948472e-05 3.27895647906167e-06 1.02815977711906e-05 2.9785222715859e-05 8.71420952566231e-06 2.72740086434735e-05 3.34767737888706e-06 -1.22636232868712e-06 2.74525969452129e-05 8.71420952566231e-06 5.90347694927575e-05 847 850 0 265 0 847 850 0 274 0 0 0 0 0 0 0 0 0 1966 0 0 0 0 0 1337 +933 935 0.989367472854601 -0.122557095341123 -0.0783055683770107 0.0476669450606327 0.122577889643539 0.992448423689651 -0.00455930767378456 0.0814087185804904 0.0782730134071519 -0.00508770060781298 0.996918978992119 -0.229751985463125 2.61787899579898e-05 -2.86347761623182e-06 2.45760971758085e-06 1.5132763395863e-07 -2.70749000232386e-06 2.10524471138507e-05 -2.86347761623182e-06 5.62506636210192e-05 -2.04970689398396e-06 2.35273472330856e-05 2.09025738279838e-07 6.09442308691781e-06 2.45760971758085e-06 -2.04970689398396e-06 1.07161836382965e-05 -4.51286262580136e-06 2.49111143302961e-06 -5.3684251834055e-08 1.5132763395863e-07 2.35273472330856e-05 -4.51286262580136e-06 0.000110490674377336 1.04985652027432e-05 -2.00407716371613e-06 -2.70749000232386e-06 2.09025738279838e-07 2.49111143302961e-06 1.04985652027432e-05 1.67044378483033e-05 -6.06214331377743e-06 2.10524471138507e-05 6.09442308691781e-06 -5.3684251834055e-08 -2.00407716371613e-06 -6.06214331377743e-06 6.33373467475673e-05 2114 2114 0 0 0 2117 2117 0 0 0 0 0 0 0 0 374 363 0 3380 0 0 0 0 0 588 +933 869 0.944974886623111 0.327085126095971 -0.0061468641127229 -0.00401694013506487 -0.326392922826446 0.941370597900824 -0.0853759763437891 -0.0696556543105497 -0.0221387348429658 0.0826844465097782 0.996329844341182 0.257498909725258 3.07868696020424e-05 -1.61880779240324e-05 7.82912560283459e-07 9.73508290740068e-06 8.90622957584818e-10 2.24168133241661e-05 -1.61880779240324e-05 5.88607710629192e-05 1.21896632690988e-06 9.05820354186197e-08 4.78722043113913e-06 3.53838502942298e-07 7.82912560283459e-07 1.21896632690988e-06 1.27189081801041e-05 -4.04157083490261e-06 1.66190186308665e-06 -3.06547394319892e-06 9.73508290740068e-06 9.05820354186197e-08 -4.04157083490261e-06 4.47822641307466e-05 1.50882732377581e-06 1.21764869434385e-05 8.90622957584818e-10 4.78722043113913e-06 1.66190186308665e-06 1.50882732377581e-06 2.83364584256809e-05 4.84787134118036e-06 2.24168133241661e-05 3.53838502942298e-07 -3.06547394319892e-06 1.21764869434385e-05 4.84787134118036e-06 4.8206252628431e-05 781 791 0 345 0 781 791 0 346 0 0 0 0 0 0 0 0 0 1637 0 0 0 0 0 845 +933 873 0.952041135426121 0.301532630603785 -0.051920604173144 -0.00452885658797651 -0.305099170843635 0.948357398836929 -0.086791359142374 -0.0611169775284658 0.0230688622838068 0.0984698773860088 0.994872610357987 0.274420871111151 3.69345538348049e-05 -2.91386925069426e-05 7.19811870112466e-06 1.94480574467098e-06 -2.6753345340118e-06 2.05471883997373e-05 -2.91386925069426e-05 9.8648770698235e-05 -9.25095375714107e-06 3.50692509635578e-05 2.36370460121413e-05 7.92255230675799e-06 7.19811870112466e-06 -9.25095375714107e-06 1.43000385034737e-05 -8.7400308922486e-06 2.69239621332316e-06 6.18004327090527e-07 1.94480574467098e-06 3.50692509635578e-05 -8.7400308922486e-06 6.80072608456238e-05 1.03254516114725e-05 2.18043758560762e-05 -2.6753345340118e-06 2.36370460121413e-05 2.69239621332316e-06 1.03254516114725e-05 3.71427917172706e-05 1.53647726829667e-05 2.05471883997373e-05 7.92255230675799e-06 6.18004327090527e-07 2.18043758560762e-05 1.53647726829667e-05 5.85609795308893e-05 676 680 0 274 0 676 680 0 274 0 0 0 0 0 0 0 0 0 1556 0 0 0 0 0 934 +933 872 0.948783708571605 0.313969298071058 -0.0351105997937735 0.0101850780807359 -0.315845003898338 0.945185607147042 -0.0828619427393265 -0.068751932265137 0.00716992758470404 0.0897075688604036 0.995942339810687 0.282862370934739 4.22433329573352e-05 9.02711658717703e-06 -1.35437057973822e-06 2.30595286495833e-05 5.15893961971681e-06 3.42174621916128e-05 9.02711658717703e-06 0.000142659867054577 -5.72546064697115e-06 4.73733702607267e-05 2.08525875598648e-05 2.29707983993451e-05 -1.35437057973822e-06 -5.72546064697115e-06 1.15620089803544e-05 -6.00756796689355e-06 2.17823694583279e-06 -4.02681853661164e-06 2.30595286495833e-05 4.73733702607267e-05 -6.00756796689355e-06 6.61843525514746e-05 4.99052654829755e-06 3.12674057484698e-05 5.15893961971681e-06 2.08525875598648e-05 2.17823694583279e-06 4.99052654829755e-06 3.12972383396128e-05 1.37498210176304e-05 3.42174621916128e-05 2.29707983993451e-05 -4.02681853661164e-06 3.12674057484698e-05 1.37498210176304e-05 6.70255581926641e-05 714 722 0 287 0 714 722 0 290 0 0 0 0 0 0 0 0 0 1620 0 0 0 0 0 1473 +933 875 0.947935873936186 0.312697820404753 -0.0603129506735954 0.00242209988826534 -0.317017065916824 0.944575428880744 -0.0853079074426612 -0.0664341676230347 0.030294534528964 0.0999866604546557 0.994527480218017 0.285039662137302 3.28098730747188e-05 -1.303279540133e-05 1.69405453709107e-06 5.93659267105188e-06 -1.90039958524213e-06 2.02935607792796e-05 -1.303279540133e-05 0.000130019219382477 -1.05719995889832e-05 5.9991400279871e-05 4.14653660153499e-05 2.05024222043038e-05 1.69405453709107e-06 -1.05719995889832e-05 1.27006303074306e-05 -8.5796943921468e-06 -2.93550026124197e-06 -4.70251028353641e-06 5.93659267105188e-06 5.9991400279871e-05 -8.5796943921468e-06 9.03478335716458e-05 2.81596351890389e-05 2.96701733793306e-05 -1.90039958524213e-06 4.14653660153499e-05 -2.93550026124197e-06 2.81596351890389e-05 4.79103423240293e-05 1.79615164401659e-05 2.02935607792796e-05 2.05024222043038e-05 -4.70251028353641e-06 2.96701733793306e-05 1.79615164401659e-05 6.07513975799566e-05 647 650 0 256 0 647 650 0 254 0 0 0 0 0 0 0 0 0 1570 0 0 0 0 0 1043 +933 874 0.950240105724716 0.305344796443921 -0.0617113989219309 0.00329715918624316 -0.309675685200607 0.947413882151143 -0.080671592911226 -0.0625885674065454 0.0338335849093192 0.0957679027227815 0.994828526601577 0.280667825771955 3.84092394325142e-05 5.11726828831944e-06 9.79697683942074e-08 1.52398382559362e-05 2.24867091230688e-06 3.13749413550364e-05 5.11726828831944e-06 0.000134094044339392 -3.67554960868537e-06 4.12810462127718e-05 2.20223407614415e-05 2.41690204093908e-05 9.79697683942074e-08 -3.67554960868537e-06 1.12457619672626e-05 -7.00399058591977e-06 -2.6121476606773e-06 -3.43343817489383e-06 1.52398382559362e-05 4.12810462127718e-05 -7.00399058591977e-06 8.46090408106404e-05 2.15335732445304e-05 2.39143981278321e-05 2.24867091230688e-06 2.20223407614415e-05 -2.6121476606773e-06 2.15335732445304e-05 4.15609659829462e-05 9.77019714917402e-06 3.13749413550364e-05 2.41690204093908e-05 -3.43343817489383e-06 2.39143981278321e-05 9.77019714917402e-06 6.86503720752859e-05 657 663 0 270 0 657 663 0 270 0 0 0 0 0 0 0 0 0 1550 0 0 0 0 0 1452 +933 867 0.953727866476666 0.298642366261873 -0.0348696684724031 -0.00781430703226705 -0.30057559560941 0.949915348006041 -0.0855286089364869 -0.0623567615722193 0.00758076710593925 0.092051989093508 0.995725345300608 0.258435114065942 3.03503546267421e-05 -1.0289085663604e-05 9.11774336530441e-07 1.06469674318803e-05 -3.39593666924605e-06 2.27756130792397e-05 -1.0289085663604e-05 0.000117034620275981 -7.35262792589435e-06 3.3502507048502e-05 1.73285725081044e-05 2.14788869910602e-05 9.11774336530441e-07 -7.35262792589435e-06 1.11425819908856e-05 -4.71667796527398e-06 3.34203095444537e-06 -3.36617394012606e-06 1.06469674318803e-05 3.3502507048502e-05 -4.71667796527398e-06 5.18542180463539e-05 -2.05509683016752e-06 2.06596125743495e-05 -3.39593666924605e-06 1.73285725081044e-05 3.34203095444537e-06 -2.05509683016752e-06 2.65818117205624e-05 2.84281582522294e-06 2.27756130792397e-05 2.14788869910602e-05 -3.36617394012606e-06 2.06596125743495e-05 2.84281582522294e-06 6.30746111712643e-05 730 737 0 287 0 730 737 0 290 0 0 0 0 0 0 0 0 0 1670 0 0 0 0 0 1230 +933 870 0.944932042205151 0.326634111432697 -0.020336982632039 -0.00184290618749696 -0.327171943634499 0.941338393180076 -0.0827076104332447 -0.0731302279086495 -0.00787114428960991 0.0848067613679792 0.996366327368527 0.26785590437527 2.37948197356532e-05 -1.1173539453776e-06 4.42231370253019e-06 5.26324968570795e-06 1.10693059339959e-06 1.82614654644581e-05 -1.1173539453776e-06 7.0067597322967e-05 -5.83933146689476e-06 1.13678268347987e-05 -5.81149770116204e-07 1.13254549034295e-05 4.42231370253019e-06 -5.83933146689476e-06 1.03543131031554e-05 -1.0370120605621e-06 5.06569698793406e-07 1.51750960227736e-07 5.26324968570795e-06 1.13678268347987e-05 -1.0370120605621e-06 4.48771350803707e-05 5.76384852596481e-06 9.41471835492947e-06 1.10693059339959e-06 -5.81149770116204e-07 5.06569698793406e-07 5.76384852596481e-06 3.07873794426317e-05 6.739998402919e-06 1.82614654644581e-05 1.13254549034295e-05 1.51750960227736e-07 9.41471835492947e-06 6.739998402919e-06 4.47136685154939e-05 774 781 0 332 0 774 781 0 337 0 0 0 0 0 0 0 0 0 1610 0 0 0 0 0 1561 +933 876 0.948446809843663 0.311488651710066 -0.0585104157669773 0.00747256910592392 -0.31559300377859 0.945172831998616 -0.0839605479836953 -0.0625566926635757 0.0291496974836109 0.0980975917520961 0.994749796496111 0.283825291575118 2.39727137552e-05 -5.36287158898487e-06 2.14809931505343e-06 6.38514574891775e-06 2.06051029391095e-06 1.62596448487327e-05 -5.36287158898487e-06 6.36926117435413e-05 -3.21517119243219e-06 1.41708188567762e-05 1.02627417205738e-05 6.86484974533536e-06 2.14809931505343e-06 -3.21517119243219e-06 1.10246295699651e-05 -5.29758137847096e-06 3.83594075848327e-06 -7.90478593088507e-07 6.38514574891775e-06 1.41708188567762e-05 -5.29758137847096e-06 5.46600494212047e-05 4.52457971506661e-06 1.25740801983497e-05 2.06051029391095e-06 1.02627417205738e-05 3.83594075848327e-06 4.52457971506661e-06 3.09746130913717e-05 3.46295267515795e-06 1.62596448487327e-05 6.86484974533536e-06 -7.90478593088507e-07 1.25740801983497e-05 3.46295267515795e-06 4.50597300383318e-05 641 644 0 268 0 641 644 0 265 0 0 0 0 0 0 0 0 0 1593 0 0 0 0 0 1307 +933 887 0.947684336217975 0.319022059957445 -0.0109235592919223 0.00754372862241904 -0.319089712042745 0.945839736449234 -0.059740678119037 -0.06457350449261 -0.00872665775503041 0.0601009002773926 0.998154160052581 0.27890023758567 2.11442780111097e-05 -1.07083162343346e-05 4.17061049499467e-06 5.13722877775277e-06 3.09302369323272e-06 1.36870363615493e-05 -1.07083162343346e-05 4.98144640647828e-05 -4.20614315788082e-06 1.62568159129955e-05 1.72086518000075e-05 1.24650997165086e-05 4.17061049499467e-06 -4.20614315788082e-06 1.03609337279653e-05 -4.17198233537046e-06 2.28926805903222e-06 -2.54778754766643e-06 5.13722877775277e-06 1.62568159129955e-05 -4.17198233537046e-06 6.27852989542897e-05 1.71447372090433e-05 2.3664549428504e-05 3.09302369323272e-06 1.72086518000075e-05 2.28926805903222e-06 1.71447372090433e-05 3.69973197445076e-05 2.30333577139112e-05 1.36870363615493e-05 1.24650997165086e-05 -2.54778754766643e-06 2.3664549428504e-05 2.30333577139112e-05 6.61742872039388e-05 749 754 0 323 0 749 754 0 324 0 0 0 0 0 0 0 0 0 1732 0 0 0 0 0 1348 +933 888 0.947900405429331 0.318135815700198 0.0165657524936304 -0.00505344871426126 -0.317419350515197 0.947617889634002 -0.0355709314484614 -0.0699772477998233 -0.0270143907097853 0.0284594099441718 0.999229845771336 0.280354102009484 2.38719997871723e-05 -1.24289538948088e-05 2.5551245289365e-06 6.86166939494951e-06 -1.88333990549804e-07 1.67765179570761e-05 -1.24289538948088e-05 8.1396185285423e-05 6.88220379058747e-08 1.36788866967622e-05 6.86184448220995e-06 1.02760277719506e-05 2.5551245289365e-06 6.88220379058747e-08 1.02714676973565e-05 -1.38825195891351e-06 3.3608819560533e-06 1.22464898074717e-07 6.86166939494951e-06 1.36788866967622e-05 -1.38825195891351e-06 3.95286117091149e-05 -1.48398073980164e-06 1.2626984349146e-05 -1.88333990549804e-07 6.86184448220995e-06 3.3608819560533e-06 -1.48398073980164e-06 2.54263675051562e-05 1.18596375900689e-05 1.67765179570761e-05 1.02760277719506e-05 1.22464898074717e-07 1.2626984349146e-05 1.18596375900689e-05 4.95698651423913e-05 755 764 0 380 0 755 764 0 385 0 0 0 0 0 0 0 0 0 1851 0 0 0 0 0 1298 +933 929 0.951894722741582 0.293948695131373 0.0865482607987567 -0.0222840069332081 -0.297628413624912 0.954113511117967 0.032935320026721 -0.081389493278044 -0.0728955706462665 -0.05711017888877 0.995703099948698 0.28004753477451 2.26840539853449e-05 4.05221054944191e-06 8.39714960595442e-07 8.40120666959675e-06 -3.12760346286524e-06 1.69765337016537e-05 4.05221054944191e-06 9.31691881207455e-05 6.27462721675407e-06 8.53207185014576e-06 5.02732017129069e-06 3.25288618160689e-05 8.39714960595442e-07 6.27462721675407e-06 1.04030295255787e-05 -4.38722358454295e-06 4.98605888090025e-06 -2.58791649518691e-06 8.40120666959675e-06 8.53207185014576e-06 -4.38722358454295e-06 3.88439192388305e-05 -1.58202588506955e-06 1.13311329112229e-05 -3.12760346286524e-06 5.02732017129069e-06 4.98605888090025e-06 -1.58202588506955e-06 2.30105943717067e-05 3.60054967064046e-06 1.69765337016537e-05 3.25288618160689e-05 -2.58791649518691e-06 1.13311329112229e-05 3.60054967064046e-06 6.11894609349521e-05 870 890 0 494 0 870 890 0 498 0 0 0 0 0 0 0 0 0 2339 0 0 0 0 0 929 +933 877 0.948599783295545 0.311060970757161 -0.0583054337369872 0.0160335485938507 -0.31525610504265 0.944936908239899 -0.0877942348867966 -0.0590323559833213 0.0277855963582458 0.101662736130958 0.994430816456018 0.282375600678862 2.53864462274251e-05 -1.1398011652573e-05 1.29392261474735e-07 1.03327116718209e-05 -5.79207947755992e-07 1.40637207007163e-05 -1.1398011652573e-05 7.02277143911284e-05 -3.24375169766516e-06 1.93006041173889e-05 1.52254067123112e-05 1.39244488182798e-05 1.29392261474735e-07 -3.24375169766516e-06 1.20806798607085e-05 -4.8046325616247e-06 4.9448160528786e-09 -4.17745109799538e-06 1.03327116718209e-05 1.93006041173889e-05 -4.8046325616247e-06 6.62444840365518e-05 1.17741397942938e-05 2.29616305746721e-05 -5.79207947755992e-07 1.52254067123112e-05 4.9448160528786e-09 1.17741397942938e-05 3.04578911758565e-05 7.86314968616887e-06 1.40637207007163e-05 1.39244488182798e-05 -4.17745109799538e-06 2.29616305746721e-05 7.86314968616887e-06 5.2391591823308e-05 637 644 0 264 0 637 644 0 264 0 0 0 0 0 0 0 0 0 1532 0 0 0 0 0 871 +933 889 0.947539506573232 0.317764636327655 0.0345618197221951 -0.0112348421273115 -0.317283333943388 0.948145144129522 -0.0187635728307807 -0.0738720184284797 -0.0387320214386598 0.00681333715302045 0.99922640525164 0.279402978571224 2.30281791955895e-05 -4.63250562752779e-06 3.82084096415287e-06 5.12316834124697e-06 -2.92305046803229e-06 1.68876564336228e-05 -4.63250562752779e-06 9.06704689419067e-05 -4.12187485974164e-06 3.03592481059183e-05 8.2489653245919e-06 3.41254693061147e-05 3.82084096415287e-06 -4.12187485974164e-06 9.8397524281989e-06 -3.62707890466762e-06 3.5122640538178e-06 -2.18880447807036e-06 5.12316834124697e-06 3.03592481059183e-05 -3.62707890466762e-06 5.58130774541121e-05 1.89459006855582e-06 2.47836130535397e-05 -2.92305046803229e-06 8.2489653245919e-06 3.5122640538178e-06 1.89459006855582e-06 2.47737460064914e-05 8.01131017869779e-06 1.68876564336228e-05 3.41254693061147e-05 -2.18880447807036e-06 2.47836130535397e-05 8.01131017869779e-06 7.37326515960234e-05 794 808 0 422 0 794 808 0 421 0 0 0 0 0 0 0 0 0 1942 0 0 0 0 0 1570 +933 898 0.945496985351197 0.315558955155564 0.080361660715331 -0.0176482700415367 -0.317907897485168 0.947950692564479 0.0180014772473095 -0.0788208072530306 -0.0704983645793121 -0.0425679490656266 0.996603206047416 0.287266552814777 3.32953348978043e-05 -1.21388285250612e-05 3.10814507326144e-07 5.38426973504431e-06 -2.12972601570824e-06 1.99184927609017e-05 -1.21388285250612e-05 7.78260714217221e-05 6.81824963984762e-06 1.06869324614867e-05 4.8190730405013e-06 1.82851076023278e-06 3.10814507326144e-07 6.81824963984762e-06 1.34683987626586e-05 -3.50761718005702e-06 3.59256656389062e-06 -5.21049270401805e-07 5.38426973504431e-06 1.06869324614867e-05 -3.50761718005702e-06 4.40303285491921e-05 2.03419846811918e-06 4.81009746983677e-06 -2.12972601570824e-06 4.8190730405013e-06 3.59256656389062e-06 2.03419846811918e-06 2.4980072912838e-05 1.31024812996904e-06 1.99184927609017e-05 1.82851076023278e-06 -5.21049270401805e-07 4.81009746983677e-06 1.31024812996904e-06 4.3804862226064e-05 902 919 0 511 0 902 919 0 518 0 0 0 0 0 0 0 0 0 2220 0 0 0 0 0 796 +933 883 0.947607265366298 0.317976637322321 -0.0305176791744547 0.0119598354163093 -0.319425808559715 0.944063447352539 -0.0819228917874154 -0.0616164157998909 0.00276105975635174 0.0873788618032381 0.996171326157801 0.282760199773281 3.23760559718556e-05 9.70952113413648e-06 2.04695011547917e-06 1.47578080349547e-05 8.34204552148647e-06 2.43878234569766e-05 9.70952113413648e-06 0.000129348129391529 -3.78750877621228e-06 4.27438481898441e-05 2.55916626371546e-05 2.10040029448528e-05 2.04695011547917e-06 -3.78750877621228e-06 1.06624458800718e-05 -3.47298990194907e-06 2.04233461751087e-06 -2.0517748760454e-06 1.47578080349547e-05 4.27438481898441e-05 -3.47298990194907e-06 6.52346692488047e-05 1.32963978880551e-05 2.4669875737598e-05 8.34204552148647e-06 2.55916626371546e-05 2.04233461751087e-06 1.32963978880551e-05 3.42990250370863e-05 1.59494001362923e-05 2.43878234569766e-05 2.10040029448528e-05 -2.0517748760454e-06 2.4669875737598e-05 1.59494001362923e-05 6.41652120904312e-05 693 699 0 294 0 693 699 0 295 0 0 0 0 0 0 0 0 0 1565 0 0 0 0 0 1619 +933 884 0.947693908556633 0.317851949154295 -0.0290928531338481 0.00974368434201685 -0.319176480278969 0.944199894356778 -0.0813199479425441 -0.0604533525527317 0.00162176489685325 0.0863521737738262 0.996263354722613 0.28190081578951 3.3332186396921e-05 -1.47118842745988e-05 2.47162898282814e-06 6.65901372908415e-06 2.41243625179872e-06 1.82460215368987e-05 -1.47118842745988e-05 8.39181950158045e-05 -4.81880639452241e-06 3.6788694966883e-05 1.88375813118466e-05 6.29739797352482e-07 2.47162898282814e-06 -4.81880639452241e-06 1.18900267052532e-05 -8.35795850572875e-06 8.2431465520132e-07 -2.89460931235882e-06 6.65901372908415e-06 3.6788694966883e-05 -8.35795850572875e-06 8.49366106845826e-05 2.25788843401561e-05 2.56310733738191e-05 2.41243625179872e-06 1.88375813118466e-05 8.2431465520132e-07 2.25788843401561e-05 3.67677489493494e-05 1.03445995324363e-05 1.82460215368987e-05 6.29739797352482e-07 -2.89460931235882e-06 2.56310733738191e-05 1.03445995324363e-05 5.99919634459916e-05 666 668 0 289 0 666 668 0 291 0 0 0 0 0 0 0 0 0 1626 0 0 0 0 0 1530 +933 878 0.947795210324447 0.314774863717369 -0.0510002397812826 0.0102634466519139 -0.318316374787232 0.943444081599819 -0.0926711952906052 -0.0587454144191653 0.0189453115136968 0.104067526471935 0.994389775241913 0.281149728541139 3.08728942364272e-05 -1.21254505828116e-05 3.25806904827712e-06 1.05824817806652e-05 9.29260457028403e-07 1.75650040102368e-05 -1.21254505828116e-05 5.6606941393608e-05 -5.38141433118516e-06 1.50349641340396e-05 1.16241304219444e-05 -1.11894683984918e-05 3.25806904827712e-06 -5.38141433118516e-06 1.15349108006483e-05 -3.62050361466376e-06 -4.55328409293006e-09 -8.73345771218787e-07 1.05824817806652e-05 1.50349641340396e-05 -3.62050361466376e-06 5.9421642344908e-05 6.92136235560712e-06 1.36950504485319e-05 9.29260457028403e-07 1.16241304219444e-05 -4.55328409293006e-09 6.92136235560712e-06 3.26778895138224e-05 6.63697973164045e-06 1.75650040102368e-05 -1.11894683984918e-05 -8.73345771218787e-07 1.36950504485319e-05 6.63697973164045e-06 4.89965518060672e-05 635 639 0 264 0 635 639 0 265 0 0 0 0 0 0 0 0 0 1519 0 0 0 0 0 1528 +933 886 0.947474273961113 0.318768737644716 -0.026057476513596 0.0139967596992387 -0.319831375023002 0.944482116303091 -0.0752424317425322 -0.0630585070353782 0.000625885579193533 0.0796242669292972 0.996824751088783 0.282732784395129 2.34910145039102e-05 -1.59482233595489e-05 5.91505124862661e-06 3.94737889856721e-06 4.76422953879156e-07 1.56947590429609e-05 -1.59482233595489e-05 5.75337923959005e-05 -4.3478269241041e-06 1.06347555031653e-05 6.17250191327449e-06 -1.01247586173381e-05 5.91505124862661e-06 -4.3478269241041e-06 1.15386284342213e-05 -2.62964999131755e-06 1.88111975979617e-06 -1.29093886716564e-06 3.94737889856721e-06 1.06347555031653e-05 -2.62964999131755e-06 4.73552122264484e-05 4.35318397842643e-07 1.22808629870259e-05 4.76422953879156e-07 6.17250191327449e-06 1.88111975979617e-06 4.35318397842643e-07 2.72611901700052e-05 8.1545087980469e-06 1.56947590429609e-05 -1.01247586173381e-05 -1.29093886716564e-06 1.22808629870259e-05 8.1545087980469e-06 4.96492757280172e-05 697 703 0 314 0 697 703 0 317 0 0 0 0 0 0 0 0 0 1600 0 0 0 0 0 1339 +933 899 0.945509148182161 0.315605194321602 0.0800363168884528 -0.0183989297650781 -0.317901710104524 0.947963012729091 0.0174536302872514 -0.0797486090076637 -0.0703630117068926 -0.0419462491148922 0.996639131666386 0.284416290922213 2.51529323722777e-05 -1.50529782567348e-05 2.89438303741752e-06 3.31137866618053e-07 -1.79869664193578e-06 1.29185459855907e-05 -1.50529782567348e-05 5.98986832581249e-05 4.50190939321828e-06 7.46280190883446e-06 6.01714308176467e-06 1.17595007392336e-05 2.89438303741752e-06 4.50190939321828e-06 1.0687399780699e-05 -3.20372518328557e-06 5.10930313885251e-06 8.56059693447004e-07 3.31137866618053e-07 7.46280190883446e-06 -3.20372518328557e-06 3.82093500865519e-05 2.32802521094566e-06 1.18969678524145e-05 -1.79869664193578e-06 6.01714308176467e-06 5.10930313885251e-06 2.32802521094566e-06 2.06690725215837e-05 5.4025756147682e-06 1.29185459855907e-05 1.17595007392336e-05 8.56059693447004e-07 1.18969678524145e-05 5.4025756147682e-06 4.83976717667908e-05 898 920 0 516 0 898 920 0 519 0 0 0 0 0 0 0 0 0 2240 0 0 0 0 0 1243 +933 881 0.947535335029546 0.317831578440447 -0.0340569613515517 0.0125861566397301 -0.319613085799917 0.943671924185271 -0.0856199444634418 -0.0616406484102544 0.00492587615572308 0.0920129732729164 0.995745624390876 0.284929779551317 2.78098485516115e-05 -1.43762301783553e-05 3.54235085576677e-06 4.49206726556038e-06 7.81519054748238e-07 2.6036451818657e-05 -1.43762301783553e-05 6.94252016560471e-05 -4.47316816629571e-06 2.12040441729554e-05 1.1105359282709e-05 -4.54326724575035e-06 3.54235085576677e-06 -4.47316816629571e-06 1.09118509540893e-05 -3.66826246085871e-06 2.63222633801363e-06 3.07146236070123e-07 4.49206726556038e-06 2.12040441729554e-05 -3.66826246085871e-06 4.77768246524287e-05 2.00222324908912e-06 1.09991937198444e-05 7.81519054748238e-07 1.1105359282709e-05 2.63222633801363e-06 2.00222324908912e-06 3.19951585940082e-05 6.26820907032723e-06 2.6036451818657e-05 -4.54326724575035e-06 3.07146236070123e-07 1.09991937198444e-05 6.26820907032723e-06 5.72661039818001e-05 663 669 0 298 0 663 669 0 302 0 0 0 0 0 0 0 0 0 1544 0 0 0 0 0 1523 +933 885 0.947570409661435 0.318741660214684 -0.0226731730829109 0.0158050115119749 -0.31953140907776 0.944433787101644 -0.07710058620807 -0.0632021449912281 -0.00316185813118105 0.0803030250017641 0.996765482362188 0.284150039007344 3.42754330765918e-05 -2.18772561098718e-05 2.72177323036833e-06 -4.38161332121744e-07 3.03958859093515e-07 1.90753174700589e-05 -2.18772561098718e-05 0.000112845666409256 -4.33772935392895e-06 4.67530006164461e-05 2.66808983535721e-05 1.48690746720283e-05 2.72177323036833e-06 -4.33772935392895e-06 1.15554649217228e-05 -5.88111619020394e-06 1.6157040593334e-06 -2.7709686780941e-06 -4.38161332121744e-07 4.67530006164461e-05 -5.88111619020394e-06 8.70553967150792e-05 2.12788910255483e-05 2.64329244574523e-05 3.03958859093515e-07 2.66808983535721e-05 1.6157040593334e-06 2.12788910255483e-05 3.60603608900018e-05 1.7656529271817e-05 1.90753174700589e-05 1.48690746720283e-05 -2.7709686780941e-06 2.64329244574523e-05 1.7656529271817e-05 6.38418283341285e-05 720 728 0 317 0 720 728 0 318 0 0 0 0 0 0 0 0 0 1582 0 0 0 0 0 1357 +933 879 0.947231687995533 0.31755196201539 -0.0437364913694409 0.0120738857903791 -0.320285042036124 0.943141987981519 -0.088885782632465 -0.0616466396705945 0.0130238667472983 0.0982035738985279 0.99508112079795 0.281047823025636 2.66087844933053e-05 -8.09879759017192e-06 5.9259419009608e-06 5.6086676753786e-06 5.77773953287322e-06 1.99896267796413e-05 -8.09879759017192e-06 9.25578064774859e-05 -1.28286624481334e-05 4.31329855358548e-05 1.88359553277142e-05 7.9215461290185e-06 5.9259419009608e-06 -1.28286624481334e-05 1.32657455107298e-05 -9.85435706154364e-06 1.02472246364642e-06 6.45495324663934e-07 5.6086676753786e-06 4.31329855358548e-05 -9.85435706154364e-06 7.89665190038794e-05 1.8421294467925e-05 1.5628194109326e-05 5.77773953287322e-06 1.88359553277142e-05 1.02472246364642e-06 1.8421294467925e-05 3.70146751594241e-05 1.28841372319503e-05 1.99896267796413e-05 7.9215461290185e-06 6.45495324663934e-07 1.5628194109326e-05 1.28841372319503e-05 5.49407903172536e-05 642 643 0 275 0 642 643 0 274 0 0 0 0 0 0 0 0 0 1516 0 0 0 0 0 1234 +933 900 0.945124790953663 0.315094378744401 0.0863403845745098 -0.0176406830615776 -0.317299536217619 0.948239353715078 0.0127723287655158 -0.085035741919524 -0.0778468614709551 -0.0394672085368424 0.996183821194377 0.287821587381964 2.95425211058388e-05 8.96592565458337e-08 4.0184811755218e-06 6.98426921899796e-06 -4.64606434847376e-06 2.14983774118362e-05 8.96592565458337e-08 8.18794063056173e-05 -1.4010306375476e-06 1.14995654468414e-05 -2.90776927219068e-06 1.72450813752218e-05 4.0184811755218e-06 -1.4010306375476e-06 1.25546243509873e-05 -3.66651283146209e-06 5.54493816163711e-06 4.57063850422683e-07 6.98426921899796e-06 1.14995654468414e-05 -3.66651283146209e-06 3.24261989669388e-05 -8.17589046982872e-06 1.30294434379885e-05 -4.64606434847376e-06 -2.90776927219068e-06 5.54493816163711e-06 -8.17589046982872e-06 2.08130602911748e-05 -1.77626622546635e-06 2.14983774118362e-05 1.72450813752218e-05 4.57063850422683e-07 1.30294434379885e-05 -1.77626622546635e-06 5.55170940543583e-05 886 904 0 516 0 886 904 0 522 0 0 0 0 0 0 0 0 0 2142 0 0 0 0 0 993 +933 890 0.947157893674021 0.31664349643798 0.0512720256526283 -0.019561954253587 -0.316824496826897 0.948472169727985 -0.004772992967914 -0.0759568076804415 -0.0501414265989315 -0.0117234557626794 0.998673318920459 0.27883045104651 2.99470753350811e-05 -1.34353558405404e-05 3.81118846163657e-06 6.05791690435014e-06 -3.20167797451624e-06 1.35152603511927e-05 -1.34353558405404e-05 8.70315669038125e-05 2.5154170851646e-06 2.73511391107465e-05 1.11970503026325e-05 2.86428651701902e-05 3.81118846163657e-06 2.5154170851646e-06 1.16565877857272e-05 -4.95187145841484e-06 4.09871324833127e-06 -1.22552668582721e-06 6.05791690435014e-06 2.73511391107465e-05 -4.95187145841484e-06 5.83684310178555e-05 5.50926387251565e-06 2.36650685355149e-05 -3.20167797451624e-06 1.11970503026325e-05 4.09871324833127e-06 5.50926387251565e-06 2.46274503909293e-05 8.31118163485221e-06 1.35152603511927e-05 2.86428651701902e-05 -1.22552668582721e-06 2.36650685355149e-05 8.31118163485221e-06 6.11451146368069e-05 820 835 0 458 0 820 835 0 461 0 0 0 0 0 0 0 0 0 2036 0 0 0 0 0 637 +934 932 0.981054016893507 0.162320681472571 0.105759218526778 -0.0306554939594621 -0.163519751957654 0.986536342093177 0.00270858803095517 -0.0703275766427299 -0.103895652733028 -0.0199509923486124 0.99438807879393 0.19864729543026 3.19474749601248e-05 9.64163628209528e-06 1.22044196080553e-06 9.27953440080761e-06 -2.017661811846e-07 3.2015814529368e-05 9.64163628209528e-06 7.61604776917551e-05 -4.57502652410222e-06 3.32995118466395e-05 1.2884158765808e-06 3.74832944587312e-05 1.22044196080553e-06 -4.57502652410222e-06 1.24363636011835e-05 -1.07025807138194e-05 5.40805376184149e-06 -6.87318305608059e-06 9.27953440080761e-06 3.32995118466395e-05 -1.07025807138194e-05 9.50087352816161e-05 1.39154831882022e-05 3.29678461171286e-05 -2.017661811846e-07 1.2884158765808e-06 5.40805376184149e-06 1.39154831882022e-05 2.1435493443517e-05 2.85793504773409e-06 3.2015814529368e-05 3.74832944587312e-05 -6.87318305608059e-06 3.29678461171286e-05 2.85793504773409e-06 8.12754928223873e-05 1573 1571 0 338 0 1573 1571 0 341 0 0 0 0 0 0 0 0 0 3011 0 0 0 0 0 1035 +933 882 0.947541421257986 0.317582616708537 -0.0361460449420751 0.00780525697649948 -0.319527011921658 0.944062945866832 -0.0815330785243382 -0.0615729570190659 0.00823065324338837 0.0888056068376176 0.996014970038799 0.283176518648955 2.55734095709553e-05 -1.66455536034867e-05 6.76774748148053e-06 5.0254324409786e-06 3.81177485883255e-06 2.027661331917e-05 -1.66455536034867e-05 8.74794968938925e-05 -1.2348676174956e-05 4.36052399205112e-05 1.87494769323422e-05 5.2909478175173e-06 6.76774748148053e-06 -1.2348676174956e-05 1.2959283171283e-05 -9.79313749697509e-06 2.86768508401538e-06 -5.81637605294565e-07 5.0254324409786e-06 4.36052399205112e-05 -9.79313749697509e-06 9.19202611237719e-05 2.17691320668924e-05 2.16607209264573e-05 3.81177485883255e-06 1.87494769323422e-05 2.86768508401538e-06 2.17691320668924e-05 3.42963495056529e-05 9.06262313803205e-06 2.027661331917e-05 5.2909478175173e-06 -5.81637605294565e-07 2.16607209264573e-05 9.06262313803205e-06 5.02183122058005e-05 693 700 0 300 0 693 700 0 301 0 0 0 0 0 0 0 0 0 1571 0 0 0 0 0 1092 +934 936 0.995193541417997 -0.096998133344865 -0.013460209787312 0.0403083419724567 0.0968389939175776 0.995227579582461 -0.0120114152150383 0.0872171989384622 0.0145610568619876 0.0106502096715732 0.99983726108653 -0.278556563757182 3.0573541830622e-05 -9.1694389732108e-07 2.65001372328852e-06 2.75499792623932e-06 -2.01144302125888e-06 1.93656647338315e-05 -9.1694389732108e-07 4.95834293921881e-05 -1.04512827762536e-06 2.34598702460265e-05 -4.91651648824473e-07 -3.3149340038621e-05 2.65001372328852e-06 -1.04512827762536e-06 9.79059994402658e-06 -1.21015057576187e-06 5.99323858628622e-06 2.10846094298957e-06 2.75499792623932e-06 2.34598702460265e-05 -1.21015057576187e-06 0.000143785393232162 9.30040218184294e-07 -6.24202638971926e-05 -2.01144302125888e-06 -4.91651648824473e-07 5.99323858628622e-06 9.30040218184294e-07 1.69613119116367e-05 -3.00558645048729e-06 1.93656647338315e-05 -3.3149340038621e-05 2.10846094298957e-06 -6.24202638971926e-05 -3.00558645048729e-06 0.000169928898627539 2689 2689 0 0 0 2693 2693 0 0 0 0 0 0 0 0 274 264 0 3698 0 0 0 0 0 755 +933 880 0.947360924026782 0.317647742244852 -0.040089792639408 0.012826971989115 -0.320009980217051 0.943370507554959 -0.0874396822785952 -0.059343444333693 0.0100445103716084 0.0956660719495007 0.995362803448646 0.285535397685079 3.02177755430617e-05 -1.54754802260121e-05 5.53911764208877e-06 6.75362354891242e-06 6.21589563099685e-07 2.4381434415965e-05 -1.54754802260121e-05 7.1720142045668e-05 -5.57757077044701e-06 1.12360026144665e-05 9.82611518101379e-06 3.93700808768466e-06 5.53911764208877e-06 -5.57757077044701e-06 1.07430220964945e-05 -3.12898808891572e-06 4.43666483292742e-06 1.74832415817619e-06 6.75362354891242e-06 1.12360026144665e-05 -3.12898808891572e-06 5.25173046674297e-05 2.90357042179508e-06 1.29063359874641e-05 6.21589563099685e-07 9.82611518101379e-06 4.43666483292742e-06 2.90357042179508e-06 2.88714979246513e-05 4.68261435176102e-06 2.4381434415965e-05 3.93700808768466e-06 1.74832415817619e-06 1.29063359874641e-05 4.68261435176102e-06 5.45324951868556e-05 666 673 0 295 0 666 673 0 296 0 0 0 0 0 0 0 0 0 1538 0 0 0 0 0 1364 +934 931 0.957219931965949 0.237911513474068 0.164706143187141 -0.0284107731454111 -0.239250940630279 0.97088418955405 -0.0119531536216336 -0.0922394877122553 -0.162754383211731 -0.0279643027886301 0.986270251257187 0.284227747052298 3.95588799289474e-05 5.34944255439003e-06 -2.18624394622739e-06 5.92764813756463e-07 -3.52363691681092e-06 2.5450731137523e-05 5.34944255439003e-06 7.89698355344594e-05 3.95733689557214e-06 5.36709829234262e-06 1.20375286204341e-06 4.28984642376634e-05 -2.18624394622739e-06 3.95733689557214e-06 1.17545777682916e-05 -5.79535090214358e-06 5.77890424562519e-06 -7.66291649836861e-06 5.92764813756463e-07 5.36709829234262e-06 -5.79535090214358e-06 5.6085123223694e-05 6.82104713412623e-06 6.14611143097853e-06 -3.52363691681092e-06 1.20375286204341e-06 5.77890424562519e-06 6.82104713412623e-06 2.18318399511004e-05 -5.99216284529094e-07 2.5450731137523e-05 4.28984642376634e-05 -7.66291649836861e-06 6.14611143097853e-06 -5.99216284529094e-07 9.15079402416828e-05 1293 1299 0 442 0 1293 1299 0 442 0 0 0 0 0 0 0 0 0 2521 0 0 0 0 0 866 +934 857 0.92870571440106 0.363002572318936 0.075728650645925 -0.12888586270934 -0.357452054622183 0.930699731270744 -0.0776275650716004 -0.0589306492208829 -0.098659640609505 0.0450238015098841 0.994102174131212 0.192989702226828 3.10148277306361e-05 4.75094400093555e-06 1.56519213828215e-06 9.56573973180919e-06 3.49410662810353e-06 2.07622713147474e-05 4.75094400093555e-06 6.44918849057446e-05 -1.03733076958161e-06 1.33684357624124e-05 1.11990061052492e-05 2.79721540931142e-05 1.56519213828215e-06 -1.03733076958161e-06 1.11608731207621e-05 -5.26549814489889e-06 6.1402910221305e-06 -5.18508704573423e-06 9.56573973180919e-06 1.33684357624124e-05 -5.26549814489889e-06 4.42077856773574e-05 5.12422830286831e-06 1.83751228618646e-05 3.49410662810353e-06 1.11990061052492e-05 6.1402910221305e-06 5.12422830286831e-06 2.71804502253402e-05 1.44903146480502e-05 2.07622713147474e-05 2.79721540931142e-05 -5.18508704573423e-06 1.83751228618646e-05 1.44903146480502e-05 8.93621508007593e-05 1490 1483 0 658 0 1490 1483 0 660 0 0 0 0 0 0 0 0 0 2284 0 0 0 0 0 1271 +934 860 0.933472599241482 0.348822935146555 0.0833754543081744 -0.0652002987020309 -0.340743436459534 0.935107848119565 -0.0972996551635428 -0.0842454793190711 -0.111905392967003 0.06241692319347 0.991756679193017 0.30247820867584 2.57068715513699e-05 1.20440751828334e-05 2.63596506798688e-06 1.02718216240944e-05 4.51811120507358e-06 1.60258737928327e-05 1.20440751828334e-05 6.79013565696326e-05 -3.40749353245056e-06 1.24848030484734e-05 1.10342166513419e-05 6.07746622184244e-06 2.63596506798688e-06 -3.40749353245056e-06 1.05162954129057e-05 -5.9548929677951e-06 6.83366097164667e-06 -3.68111086530037e-06 1.02718216240944e-05 1.24848030484734e-05 -5.9548929677951e-06 3.62902555517521e-05 -2.27383333901994e-06 8.88513418543941e-06 4.51811120507358e-06 1.10342166513419e-05 6.83366097164667e-06 -2.27383333901994e-06 2.26372801582375e-05 2.43692578497154e-06 1.60258737928327e-05 6.07746622184244e-06 -3.68111086530037e-06 8.88513418543941e-06 2.43692578497154e-06 4.22833404159375e-05 1223 1230 0 500 0 1223 1230 0 500 0 0 0 0 0 0 0 0 0 1896 0 0 0 0 0 1144 +934 858 0.926042500391605 0.373915683800973 0.0513064213926005 -0.102292802867129 -0.37056473160474 0.926574267727178 -0.0643576419436787 -0.0754329898240202 -0.0716035415267397 0.0405855613918832 0.996607116695107 0.237268504599898 3.70648731615362e-05 6.5348815001062e-06 8.93950728473551e-07 9.77111057848455e-06 1.00434029369883e-05 3.44712847589849e-05 6.5348815001062e-06 5.92579705516482e-05 -1.95039343315863e-06 1.38174081930953e-05 7.13583001472345e-06 2.17045667104517e-05 8.93950728473551e-07 -1.95039343315863e-06 1.10501540832581e-05 -4.53072344725254e-06 4.26103627371538e-06 -1.48511402429435e-06 9.77111057848455e-06 1.38174081930953e-05 -4.53072344725254e-06 4.97679786343311e-05 8.15258072451779e-06 9.97004467806237e-06 1.00434029369883e-05 7.13583001472345e-06 4.26103627371538e-06 8.15258072451779e-06 2.57504467031441e-05 1.03326449185353e-05 3.44712847589849e-05 2.17045667104517e-05 -1.48511402429435e-06 9.97004467806237e-06 1.03326449185353e-05 6.31272717951938e-05 1272 1280 0 566 0 1272 1280 0 561 0 0 0 0 0 0 0 0 0 2144 0 0 0 0 0 1303 +934 859 0.927718161958174 0.363381318087051 0.08539923675458 -0.0774481812620434 -0.358225842313562 0.931007096710767 -0.0700002269491076 -0.086037688703835 -0.104944070207356 0.0343482683625364 0.993884771283275 0.279264331189482 7.80422276087487e-05 0.000109721713164986 -6.71267247685092e-06 4.9028967163457e-05 2.89186147823194e-05 0.000116600272659982 0.000109721713164986 0.000326244529930242 -1.91303596131736e-05 0.000102447817722915 6.74939473014124e-05 0.000246939797580371 -6.71267247685092e-06 -1.91303596131736e-05 1.23580919622906e-05 -1.13087470078221e-05 8.71461462306236e-07 -2.01113456623479e-05 4.9028967163457e-05 0.000102447817722915 -1.13087470078221e-05 9.02050690203619e-05 3.01999452312026e-05 0.000102601430577407 2.89186147823194e-05 6.74939473014124e-05 8.71461462306236e-07 3.01999452312026e-05 4.25731040933884e-05 6.30303806655749e-05 0.000116600272659982 0.000246939797580371 -2.01113456623479e-05 0.000102601430577407 6.30303806655749e-05 0.000284185846479216 1215 1212 0 551 0 1215 1212 0 545 0 0 0 0 0 0 0 0 0 2117 0 0 0 0 0 719 +934 861 0.936170645574573 0.347350532782171 0.054149143487495 -0.0422872025273812 -0.341114638251178 0.934795254499501 -0.0989880585524409 -0.0845179119282372 -0.085001917244586 0.0741986491868642 0.993614228221189 0.333994033082343 3.01162372527028e-05 1.18680433969863e-05 1.21564360942177e-06 4.97122437375992e-06 5.94395391140541e-07 2.45486639543202e-05 1.18680433969863e-05 7.50722677829374e-05 1.05845179972041e-06 -2.93604022875525e-06 1.1031582381488e-06 2.46630986717013e-05 1.21564360942177e-06 1.05845179972041e-06 9.42850362813079e-06 -2.99174940195422e-06 5.04961459928434e-06 -4.1849308700684e-06 4.97122437375992e-06 -2.93604022875525e-06 -2.99174940195422e-06 2.98632889156986e-05 -4.24305115688563e-06 1.01455325132141e-05 5.94395391140541e-07 1.1031582381488e-06 5.04961459928434e-06 -4.24305115688563e-06 1.95531517175039e-05 4.7440774490882e-07 2.45486639543202e-05 2.46630986717013e-05 -4.1849308700684e-06 1.01455325132141e-05 4.7440774490882e-07 6.74686965669478e-05 1076 1078 0 470 0 1076 1078 0 469 0 0 0 0 0 0 0 0 0 1646 0 0 0 0 0 1458 +934 863 0.937634983232523 0.346662196976055 0.0258061893018191 -0.0252154037000438 -0.344655809609009 0.936746991441807 -0.0609708694991512 -0.0888463313709558 -0.0453101657611728 0.0482741671337672 0.997805889773275 0.364706358649056 5.18437760717378e-05 -3.45174120687781e-06 -1.20045337710529e-06 1.30616725351274e-05 8.22116961583563e-06 3.35702857464576e-05 -3.45174120687781e-06 9.66848063078233e-05 -2.95482565203696e-07 4.18738884182389e-05 2.48434915937252e-05 9.83676026755495e-06 -1.20045337710529e-06 -2.95482565203696e-07 1.16304581323952e-05 -5.73792849419461e-06 5.47825955987481e-06 -5.8562412287458e-06 1.30616725351274e-05 4.18738884182389e-05 -5.73792849419461e-06 7.67859094397425e-05 1.99582004247145e-05 3.33455529779947e-05 8.22116961583563e-06 2.48434915937252e-05 5.47825955987481e-06 1.99582004247145e-05 3.50703253586491e-05 1.63913751658621e-05 3.35702857464576e-05 9.83676026755495e-06 -5.8562412287458e-06 3.33455529779947e-05 1.63913751658621e-05 7.32844244764871e-05 932 931 0 417 0 932 931 0 419 0 0 0 0 0 0 0 0 0 1782 0 0 0 0 0 1357 +934 862 0.937427932888902 0.34770456330723 0.01817710909271 -0.0503533790693735 -0.346072685331057 0.936219609842683 -0.0610453815924316 -0.0880692038288702 -0.0382435237313645 0.0509350449233376 0.997969465510476 0.341752056186356 2.64246903722795e-05 -4.98467241670732e-07 2.89480904889066e-06 8.87713942345036e-06 -2.32556287899911e-07 1.37182112537685e-05 -4.98467241670732e-07 4.90539503439504e-05 -2.49794524258311e-06 1.09218658459399e-05 1.1338195319591e-05 1.02727280574114e-05 2.89480904889066e-06 -2.49794524258311e-06 1.04430184372846e-05 -7.69905306302651e-06 5.47986597061966e-06 -3.82633829954145e-06 8.87713942345036e-06 1.09218658459399e-05 -7.69905306302651e-06 5.97287533329082e-05 7.33564586696828e-06 1.97384824881376e-05 -2.32556287899911e-07 1.1338195319591e-05 5.47986597061966e-06 7.33564586696828e-06 2.74248336725054e-05 3.88639385245695e-06 1.37182112537685e-05 1.02727280574114e-05 -3.82633829954145e-06 1.97384824881376e-05 3.88639385245695e-06 5.17906523099395e-05 969 964 0 401 0 969 964 0 402 0 0 0 0 0 0 0 0 0 1708 0 0 0 0 0 1359 +934 865 0.933665660077179 0.358052160325551 0.00819058476857748 -0.00287115852887622 -0.356421948906771 0.931169734683309 -0.0767223536351384 -0.0965171929160868 -0.0350974291101796 0.0687137227635237 0.997018853770496 0.377731017873412 5.67161381542948e-05 1.71174209849364e-05 -3.84974140758095e-06 1.48721907322454e-05 1.2834893522465e-05 4.66416837515536e-05 1.71174209849364e-05 0.000105220305774023 -1.94452285311936e-06 2.9083828647258e-05 2.50953417338126e-05 4.14847293800403e-05 -3.84974140758095e-06 -1.94452285311936e-06 1.2830757963444e-05 -8.10217385798674e-06 4.90541101122324e-06 -7.44017473284226e-06 1.48721907322454e-05 2.9083828647258e-05 -8.10217385798674e-06 5.99559799488032e-05 1.31133868702639e-05 3.30815456815302e-05 1.2834893522465e-05 2.50953417338126e-05 4.90541101122324e-06 1.31133868702639e-05 3.38635048577673e-05 2.42187741082628e-05 4.66416837515536e-05 4.14847293800403e-05 -7.44017473284226e-06 3.30815456815302e-05 2.42187741082628e-05 9.47357687412962e-05 818 825 0 392 0 818 825 0 391 0 0 0 0 0 0 0 0 0 1577 0 0 0 0 0 650 +934 869 0.915549310097609 0.400461415071757 0.037418121525787 -0.0147983783963108 -0.395747484901787 0.913546077158416 -0.0939015074553127 -0.10720188689155 -0.0717871086874453 0.0711633328842574 0.994878078499623 0.365818499672462 3.4265931937382e-05 6.47724097058373e-06 3.22273541223314e-06 9.47351268365036e-07 4.18136689936678e-06 3.74363235774858e-05 6.47724097058373e-06 7.91421811099563e-05 1.60211277046143e-06 -3.35047689211558e-06 1.92343710332218e-06 4.46747666187278e-05 3.22273541223314e-06 1.60211277046143e-06 1.27972640562554e-05 -6.97272988409288e-06 5.29070694826736e-06 -8.81544283402048e-07 9.47351268365036e-07 -3.35047689211558e-06 -6.97272988409288e-06 4.86583222261776e-05 5.65389085266141e-06 2.94179364312857e-06 4.18136689936678e-06 1.92343710332218e-06 5.29070694826736e-06 5.65389085266141e-06 2.47912062829858e-05 4.25563499309897e-06 3.74363235774858e-05 4.46747666187278e-05 -8.81544283402048e-07 2.94179364312857e-06 4.25563499309897e-06 9.61990964158725e-05 804 813 0 461 0 804 813 0 457 0 0 0 0 0 0 0 0 0 1419 0 0 0 0 0 564 +934 868 0.918897595451202 0.391577183826535 0.0479011292192416 0.00878675623577962 -0.385270465170279 0.916874238610604 -0.10444280367599 -0.103911388601409 -0.0848167303158724 0.0775173508235707 0.993376656953353 0.380411388372258 3.07907732443671e-05 3.92132380899942e-06 4.4946300412651e-06 8.37632408481797e-06 1.09864566671213e-05 2.5580446138845e-05 3.92132380899942e-06 8.03905790904842e-05 -7.71861210030531e-06 2.81771429704157e-05 2.17666659216362e-05 1.31043065263211e-05 4.4946300412651e-06 -7.71861210030531e-06 1.27845713443193e-05 -7.73994272064569e-06 5.54950234329673e-06 -3.14105654876043e-06 8.37632408481797e-06 2.81771429704157e-05 -7.73994272064569e-06 5.59917585596038e-05 1.15517822913687e-05 2.27540958479528e-05 1.09864566671213e-05 2.17666659216362e-05 5.54950234329673e-06 1.15517822913687e-05 3.60577263562097e-05 1.9638184032869e-05 2.5580446138845e-05 1.31043065263211e-05 -3.14105654876043e-06 2.27540958479528e-05 1.9638184032869e-05 7.27725667374799e-05 784 790 0 437 0 784 790 0 436 0 0 0 0 0 0 0 0 0 1440 0 0 0 0 0 612 +934 870 0.916617537890444 0.399003753081631 0.0246636221677433 -0.0190852893193364 -0.395420257878841 0.913999174617404 -0.0908203086194685 -0.110763126165133 -0.0587801742995928 0.0734949918394321 0.995561840009867 0.373259152096271 2.0588589357895e-05 -5.40561035279054e-06 5.55547291293176e-06 2.25543666580885e-06 2.52550638883877e-06 1.68464437295761e-05 -5.40561035279054e-06 4.00373820263067e-05 -3.98379257345753e-06 3.08371454750706e-06 -1.18236823479068e-06 -6.28806325591617e-06 5.55547291293176e-06 -3.98379257345753e-06 1.05509194143281e-05 -6.33521641262688e-06 6.82398889509709e-06 1.61755044595269e-06 2.25543666580885e-06 3.08371454750706e-06 -6.33521641262688e-06 4.56522165349545e-05 -3.83674676287297e-07 2.37468158756875e-06 2.52550638883877e-06 -1.18236823479068e-06 6.82398889509709e-06 -3.83674676287297e-07 2.42388019418979e-05 1.57173808516986e-06 1.68464437295761e-05 -6.28806325591617e-06 1.61755044595269e-06 2.37468158756875e-06 1.57173808516986e-06 4.92822188492859e-05 764 770 0 424 0 764 770 0 426 0 0 0 0 0 0 0 0 0 1439 0 0 0 0 0 1401 +934 867 0.927221744786229 0.373585748437361 0.0263348544722988 -0.0100371651633594 -0.36957336446195 0.924110495526148 -0.0971355771007249 -0.100639155704319 -0.0606247826870744 0.0803335585102082 0.994922688002054 0.373829493987792 4.58662475330846e-05 4.88725239564664e-05 -2.52609311375103e-06 2.85330990713281e-05 1.9123509686607e-05 5.12404647891726e-05 4.88725239564664e-05 0.000167544165903251 -1.37165813894166e-05 5.94118861620117e-05 3.07117239316777e-05 6.60972273598886e-05 -2.52609311375103e-06 -1.37165813894166e-05 1.1620208157581e-05 -9.55745143342757e-06 3.08075364105719e-06 -9.82487932174412e-06 2.85330990713281e-05 5.94118861620117e-05 -9.55745143342757e-06 6.9073888741047e-05 1.31448263219415e-05 4.91591292593233e-05 1.9123509686607e-05 3.07117239316777e-05 3.08075364105719e-06 1.31448263219415e-05 3.1460327365605e-05 2.76301119316291e-05 5.12404647891726e-05 6.60972273598886e-05 -9.82487932174412e-06 4.91591292593233e-05 2.76301119316291e-05 0.000112364044363866 743 751 0 414 0 743 751 0 412 0 0 0 0 0 0 0 0 0 1496 0 0 0 0 0 1400 +934 871 0.917030439685234 0.398454982804912 0.0169940980532509 -0.00164700940078615 -0.395860104403202 0.914583593586402 -0.0826536634667211 -0.111246908805239 -0.0484762873226972 0.0690686399208845 0.996433426048568 0.387463897159281 5.7228429347867e-05 2.72037512060178e-05 -1.1696113509312e-06 3.03771293256903e-05 2.42582347168621e-05 6.84114497326533e-05 2.72037512060178e-05 0.000207843114668295 -9.20573508866175e-06 9.10738339123183e-05 5.28968553746898e-05 0.00012058897238521 -1.1696113509312e-06 -9.20573508866175e-06 1.35799934379891e-05 -1.26220700272765e-05 2.28695066070674e-06 -1.16118529930976e-05 3.03771293256903e-05 9.10738339123183e-05 -1.26220700272765e-05 0.000100342241756488 3.71474553889698e-05 8.94087640073471e-05 2.42582347168621e-05 5.28968553746898e-05 2.28695066070674e-06 3.71474553889698e-05 4.41216136061417e-05 5.48682039896802e-05 6.84114497326533e-05 0.00012058897238521 -1.16118529930976e-05 8.94087640073471e-05 5.48682039896802e-05 0.000172622275897643 725 734 0 444 0 725 734 0 441 0 0 0 0 0 0 0 0 0 1455 0 0 0 0 0 618 +934 930 0.932221013347926 0.302515759707479 0.198615702806128 -0.0330404939554791 -0.307895600139374 0.951411827606057 -0.00397915897115047 -0.106611855447402 -0.190169087097194 -0.0574434454042378 0.980069369428874 0.353835661553761 2.75045363461134e-05 3.50927197109814e-06 2.28311228234096e-06 8.24466936483334e-07 -2.69680197514021e-06 1.88025748113597e-05 3.50927197109814e-06 4.77823323511758e-05 1.49865092630441e-06 -2.69689663248896e-06 1.21913733009921e-06 7.76077259119983e-06 2.28311228234096e-06 1.49865092630441e-06 1.09915866041917e-05 -7.48025259014697e-06 6.99754113504254e-06 -3.3878205071916e-06 8.24466936483334e-07 -2.69689663248896e-06 -7.48025259014697e-06 4.2948293180855e-05 -3.08216507763078e-06 4.27832746916469e-06 -2.69680197514021e-06 1.21913733009921e-06 6.99754113504254e-06 -3.08216507763078e-06 1.83874726097979e-05 -4.89128052626153e-06 1.88025748113597e-05 7.76077259119983e-06 -3.3878205071916e-06 4.27832746916469e-06 -4.89128052626153e-06 4.50458006849363e-05 1024 1034 0 518 0 1024 1034 0 522 0 0 0 0 0 0 0 0 0 2195 0 0 0 0 0 914 +934 864 0.941010358636743 0.338315957977309 0.00646664644498478 -0.0202888626163812 -0.337300265457224 0.939366496231698 -0.0617990022562601 -0.0903504613803805 -0.026982139663763 0.0559722997140448 0.998067665944492 0.371458057747224 6.26768192614126e-05 8.89743923946484e-05 -6.72071071085565e-06 8.07862562784947e-05 4.24135918760644e-05 9.22376341248588e-05 8.89743923946484e-05 0.00040211044368292 -2.17598564604975e-05 0.00024314093668805 0.000147180089244236 0.00021774421869854 -6.72071071085565e-06 -2.17598564604975e-05 1.21971097733244e-05 -2.08826736063388e-05 -3.3864885436932e-06 -2.15927976166803e-05 8.07862562784947e-05 0.00024314093668805 -2.08826736063388e-05 0.000221284726401062 0.000104154301779379 0.00018270083864774 4.24135918760644e-05 0.000147180089244236 -3.3864885436932e-06 0.000104154301779379 8.62191755568688e-05 0.000101069250245192 9.22376341248588e-05 0.00021774421869854 -2.15927976166803e-05 0.00018270083864774 0.000101069250245192 0.000226995380425276 802 805 0 364 0 802 805 0 364 0 0 0 0 0 0 0 0 0 1743 0 0 0 0 0 1013 +934 866 0.932925562015341 0.359660396496244 0.0171550263924499 -0.0156545140883583 -0.357279413933145 0.930565259032433 -0.0799982441150399 -0.0981576198610082 -0.0447360717760169 0.0685032690757618 0.996647372949924 0.367876599215753 1.95247567797915e-05 -3.91523755077049e-06 5.83172821320553e-06 4.39205206710072e-06 3.00218685496808e-06 1.49447987979107e-05 -3.91523755077049e-06 3.93538324762073e-05 -5.22917606794769e-06 7.06185671407891e-06 3.32624741418224e-06 -6.58985746405073e-06 5.83172821320553e-06 -5.22917606794769e-06 1.09997646962682e-05 -4.8448950461081e-06 8.28610590852127e-06 2.96104562880592e-06 4.39205206710072e-06 7.06185671407891e-06 -4.8448950461081e-06 4.07181344051159e-05 -4.49991889811861e-06 6.19584904701131e-06 3.00218685496808e-06 3.32624741418224e-06 8.28610590852127e-06 -4.49991889811861e-06 2.49739098466725e-05 5.83740303114884e-06 1.49447987979107e-05 -6.58985746405073e-06 2.96104562880592e-06 6.19584904701131e-06 5.83740303114884e-06 4.21097383287953e-05 769 773 0 379 0 769 773 0 373 0 0 0 0 0 0 0 0 0 1643 0 0 0 0 0 1137 +934 875 0.921772456166838 0.387706928063796 -0.00434476506717034 0.00599084010253455 -0.386496555721519 0.917885859049968 -0.0900331170820174 -0.100168787085481 -0.0309184648318271 0.0846692842029282 0.995929295103326 0.394511919569303 4.45860193084685e-05 1.00932075158627e-05 -2.88514865892211e-06 1.11156535174456e-05 7.55244207571088e-06 3.87652703564849e-05 1.00932075158627e-05 8.21597405908978e-05 -4.57269666514514e-08 1.07356766721343e-05 8.58088817505604e-06 1.16312113533822e-05 -2.88514865892211e-06 -4.57269666514514e-08 1.22752717372693e-05 -9.77357859891493e-06 3.46446852325737e-06 -5.72682374052658e-06 1.11156535174456e-05 1.07356766721343e-05 -9.77357859891493e-06 6.17191049374755e-05 9.15125270355008e-06 1.84817875873673e-05 7.55244207571088e-06 8.58088817505604e-06 3.46446852325737e-06 9.15125270355008e-06 2.99068315951848e-05 6.31135165407844e-06 3.87652703564849e-05 1.16312113533822e-05 -5.72682374052658e-06 1.84817875873673e-05 6.31135165407844e-06 8.11190675394132e-05 643 645 0 354 0 643 645 0 357 0 0 0 0 0 0 0 0 0 1368 0 0 0 0 0 1171 +934 887 0.919572252248829 0.390666402585936 0.0420313547792485 -0.00450790205647962 -0.387312487603791 0.919254693199874 -0.0704261739424229 -0.102809165919597 -0.0661506601643509 0.0484826868125934 0.996631084824898 0.389994190454181 2.76875587174057e-05 2.54715160902197e-07 5.04415663006951e-06 4.96505665503483e-06 6.6074283283501e-06 3.07134877965398e-05 2.54715160902197e-07 6.77049468791893e-05 -3.19885932513674e-06 1.69450745973537e-05 1.20591696058612e-05 1.54006233317938e-05 5.04415663006951e-06 -3.19885932513674e-06 9.83030535501894e-06 -6.96348375223195e-06 5.65398853843425e-06 -1.84014250396199e-06 4.96505665503483e-06 1.69450745973537e-05 -6.96348375223195e-06 5.53297544329543e-05 9.34114516457569e-06 2.33309367417231e-05 6.6074283283501e-06 1.20591696058612e-05 5.65398853843425e-06 9.34114516457569e-06 2.52424070795233e-05 1.23724927221549e-05 3.07134877965398e-05 1.54006233317938e-05 -1.84014250396199e-06 2.33309367417231e-05 1.23724927221549e-05 7.74931829984335e-05 736 742 0 427 0 736 742 0 430 0 0 0 0 0 0 0 0 0 1515 0 0 0 0 0 1099 +934 874 0.924562216118988 0.381019366349061 -0.00299182086786698 0.0121984202317398 -0.379774575226049 0.920847707590155 -0.0883785688831312 -0.0978863563253965 -0.0309189349269918 0.082847703003259 0.996082465245757 0.393845625194873 4.32132778642109e-05 1.82072480488096e-05 -1.31808838842004e-06 1.47120948041134e-05 1.49356610192458e-05 4.68596039103015e-05 1.82072480488096e-05 0.00011247222646177 -3.67284957478716e-06 2.12984982402545e-05 2.36248964463414e-05 4.00062117903965e-05 -1.31808838842004e-06 -3.67284957478716e-06 1.15283232100198e-05 -8.09652169553382e-06 2.056017614038e-06 -5.58775692936288e-06 1.47120948041134e-05 2.12984982402545e-05 -8.09652169553382e-06 7.19798871340076e-05 1.69570158257217e-05 2.89593792417295e-05 1.49356610192458e-05 2.36248964463414e-05 2.056017614038e-06 1.69570158257217e-05 3.26113121511473e-05 2.24711429397704e-05 4.68596039103015e-05 4.00062117903965e-05 -5.58775692936288e-06 2.89593792417295e-05 2.24711429397704e-05 0.000107157705640488 667 673 0 361 0 667 673 0 362 0 0 0 0 0 0 0 0 0 1365 0 0 0 0 0 779 +934 876 0.922227429680774 0.386623364467182 0.00435223993714175 0.012962240290953 -0.384570322367486 0.918379318425781 -0.0931938551727855 -0.101566245746927 -0.0400279289816673 0.084272187202393 0.995638470211735 0.401382625395782 4.10080759378186e-05 1.71525752464285e-05 -8.4878442038432e-07 2.30618689629347e-05 1.56190511625197e-05 3.85227436308164e-05 1.71525752464285e-05 0.000122125532931401 -5.83382195982292e-06 4.19354434475705e-05 3.03845771771805e-05 3.7818937330516e-05 -8.4878442038432e-07 -5.83382195982292e-06 1.08496450577571e-05 -7.97927918831539e-06 3.8670110282445e-06 -4.30178420774835e-06 2.30618689629347e-05 4.19354434475705e-05 -7.97927918831539e-06 7.08283271615979e-05 2.03219692989899e-05 3.99034526210199e-05 1.56190511625197e-05 3.03845771771805e-05 3.8670110282445e-06 2.03219692989899e-05 3.7602165466824e-05 2.57681432598367e-05 3.85227436308164e-05 3.7818937330516e-05 -4.30178420774835e-06 3.99034526210199e-05 2.57681432598367e-05 8.88618610469639e-05 647 651 0 373 0 647 651 0 369 0 0 0 0 0 0 0 0 0 1357 0 0 0 0 0 1113 +934 877 0.922289555814768 0.386495552028011 -0.00177862237731745 0.0163294478687017 -0.384819211895593 0.917841219134701 -0.0973738702803824 -0.0999863066985782 -0.0360020748159431 0.0904913516303579 0.9952462840368 0.393446956094927 5.47527917421312e-05 3.00214176909161e-05 -4.26642427030305e-06 2.20831871003888e-05 1.91749085291859e-05 5.94027767076814e-05 3.00214176909161e-05 0.000165320314731469 -7.00862156714855e-06 5.88753722268386e-05 3.70931355373403e-05 8.75067392611037e-05 -4.26642427030305e-06 -7.00862156714855e-06 1.25834565415305e-05 -1.09110046239454e-05 2.77993002925952e-06 -1.09929103394294e-05 2.20831871003888e-05 5.88753722268386e-05 -1.09110046239454e-05 8.44146729990106e-05 1.81275732683142e-05 5.60260056581113e-05 1.91749085291859e-05 3.70931355373403e-05 2.77993002925952e-06 1.81275732683142e-05 3.43995000036706e-05 3.36577008665716e-05 5.94027767076814e-05 8.75067392611037e-05 -1.09929103394294e-05 5.60260056581113e-05 3.36577008665716e-05 0.000138376424590245 629 637 0 358 0 629 637 0 355 0 0 0 0 0 0 0 0 0 1306 0 0 0 0 0 851 +934 884 0.919659682298038 0.392062202993574 0.0226560751079524 0.00650199269449845 -0.388689830258354 0.916954589497387 -0.090080500961139 -0.10069777530347 -0.0560917517038233 0.0740372189071386 0.995676757591184 0.395844457385283 2.90354186526423e-05 -2.41832230994098e-06 2.75419023898032e-06 6.51070044816763e-06 4.43863271070692e-06 2.20369858244834e-05 -2.41832230994098e-06 6.17768785686461e-05 -8.00812373330772e-07 1.27504410154037e-05 1.64784702855342e-05 1.61235370187516e-05 2.75419023898032e-06 -8.00812373330772e-07 1.02879500242944e-05 -5.83866135862291e-06 6.29690469680985e-06 -3.29050664669653e-06 6.51070044816763e-06 1.27504410154037e-05 -5.83866135862291e-06 5.30123618785803e-05 1.04669007888666e-05 3.03541777400383e-05 4.43863271070692e-06 1.64784702855342e-05 6.29690469680985e-06 1.04669007888666e-05 3.39426827584072e-05 2.00967991465815e-05 2.20369858244834e-05 1.61235370187516e-05 -3.29050664669653e-06 3.03541777400383e-05 2.00967991465815e-05 7.67666436768384e-05 683 691 0 401 0 683 691 0 403 0 0 0 0 0 0 0 0 0 1383 0 0 0 0 0 1132 +934 872 0.921612842878355 0.388035743135484 0.0076177352913558 0.00278249073609456 -0.385944512320006 0.918363643484588 -0.0874931525079872 -0.104804986991812 -0.0409463215899737 0.0776947898832704 0.99613599391511 0.386857300058574 3.43657333601956e-05 3.96405744706605e-06 2.27048903561798e-07 1.3330563267794e-05 7.47832417688857e-06 3.06570049376682e-05 3.96405744706605e-06 6.37896662752134e-05 -2.15853612023896e-06 1.46475205679972e-05 6.84283149008484e-06 2.09226158407663e-05 2.27048903561798e-07 -2.15853612023896e-06 1.21189776225661e-05 -7.65052894542704e-06 6.24961612911373e-06 -5.48073760533395e-06 1.3330563267794e-05 1.46475205679972e-05 -7.65052894542704e-06 5.09152771955708e-05 4.4795405443361e-06 2.58051625444371e-05 7.47832417688857e-06 6.84283149008484e-06 6.24961612911373e-06 4.4795405443361e-06 2.70541840707477e-05 1.18918789757238e-05 3.06570049376682e-05 2.09226158407663e-05 -5.48073760533395e-06 2.58051625444371e-05 1.18918789757238e-05 6.89564898354257e-05 716 722 0 414 0 716 722 0 417 0 0 0 0 0 0 0 0 0 1420 0 0 0 0 0 1038 +934 885 0.919657122298434 0.391661459482988 0.0288457719851611 0.00707808384520287 -0.387931704072467 0.917422556374988 -0.0885711354212806 -0.10271209047032 -0.0611536620424006 0.0702648860387504 0.995652085524238 0.400171738746104 3.02286565385704e-05 -7.66079058226733e-06 3.58227559269219e-06 3.22491223074706e-06 4.4101248895213e-06 2.38966319876185e-05 -7.66079058226733e-06 6.53345135650501e-05 -2.77386562370613e-06 1.7187338737194e-05 1.74965035391415e-05 1.68112813580921e-05 3.58227559269219e-06 -2.77386562370613e-06 1.15451863041188e-05 -7.01664262897699e-06 6.7702509285007e-06 -3.4940345026742e-06 3.22491223074706e-06 1.7187338737194e-05 -7.01664262897699e-06 5.78659970605405e-05 8.67886498273676e-06 2.40828671912531e-05 4.4101248895213e-06 1.74965035391415e-05 6.7702509285007e-06 8.67886498273676e-06 3.24594988879364e-05 1.58905448039371e-05 2.38966319876185e-05 1.68112813580921e-05 -3.4940345026742e-06 2.40828671912531e-05 1.58905448039371e-05 6.89217589898894e-05 683 693 0 425 0 683 693 0 418 0 0 0 0 0 0 0 0 0 1397 0 0 0 0 0 1293 +934 878 0.920736016774766 0.390181945397751 0.00179913850614034 0.0105952368318495 -0.388005403163511 0.916067243281743 -0.101353899294053 -0.0990980765948845 -0.0411945934518036 0.0926221100591756 0.99484880770825 0.395817430599777 2.76196025228484e-05 -9.22540219361697e-06 3.53890162995003e-06 3.25743945480266e-06 3.99249241178014e-06 2.00838214626508e-05 -9.22540219361697e-06 4.56492533098405e-05 -1.89146273925502e-06 8.10451563089132e-06 6.5056544191429e-06 -6.59517915311444e-07 3.53890162995003e-06 -1.89146273925502e-06 1.01407591381876e-05 -4.68270627456328e-06 5.08760308527163e-06 -1.54809042091356e-06 3.25743945480266e-06 8.10451563089132e-06 -4.68270627456328e-06 4.47281092345503e-05 1.95050705077022e-06 1.60234469151116e-05 3.99249241178014e-06 6.5056544191429e-06 5.08760308527163e-06 1.95050705077022e-06 2.47436589213754e-05 1.16382793912238e-05 2.00838214626508e-05 -6.59517915311444e-07 -1.54809042091356e-06 1.60234469151116e-05 1.16382793912238e-05 6.1702423566016e-05 665 669 0 344 0 665 669 0 342 0 0 0 0 0 0 0 0 0 1335 0 0 0 0 0 1184 +934 873 0.926073951558131 0.377294456791335 0.00599409042649093 0.00144564437630518 -0.375043215991913 0.922066734663912 -0.0955799297168266 -0.0984756644972516 -0.0415887290494988 0.0862660402520125 0.995403711021456 0.391304094648689 2.60126008200313e-05 -8.13133008807508e-06 4.44603243500169e-06 7.215180718304e-06 9.20614433421689e-06 2.42686641905022e-05 -8.13133008807508e-06 0.000100641258000174 -5.23400379214453e-06 4.34915803783054e-05 2.43014474486562e-05 2.97873081752271e-05 4.44603243500169e-06 -5.23400379214453e-06 1.09837899067665e-05 -6.59627525431281e-06 7.39945225576904e-06 -9.29886138134878e-07 7.215180718304e-06 4.34915803783054e-05 -6.59627525431281e-06 7.60834946936636e-05 1.72816435187373e-05 3.88473663868519e-05 9.20614433421689e-06 2.43014474486562e-05 7.39945225576904e-06 1.72816435187373e-05 3.70002111841606e-05 2.53040074053227e-05 2.42686641905022e-05 2.97873081752271e-05 -9.29886138134878e-07 3.88473663868519e-05 2.53040074053227e-05 8.13388097829713e-05 667 672 0 392 0 667 672 0 395 0 0 0 0 0 0 0 0 0 1385 0 0 0 0 0 1076 +934 883 0.919960471723786 0.391754332713883 0.0141870809418104 5.57860682487595e-06 -0.389003730715425 0.916779012377611 -0.090511545967426 -0.101625255008004 -0.048464708347725 0.0777482171103164 0.995794349643006 0.38930185720342 4.61466650289441e-05 2.23874003086847e-06 5.93336775394214e-07 1.60673860917977e-05 1.17159821755095e-05 4.23285146090178e-05 2.23874003086847e-06 9.04517045545865e-05 -3.63238114921551e-06 4.41039724195461e-05 2.83405078275691e-05 4.11331217975915e-05 5.93336775394214e-07 -3.63238114921551e-06 1.07216666106405e-05 -8.0024618065338e-06 4.43005026945238e-06 -4.99419452861784e-06 1.60673860917977e-05 4.41039724195461e-05 -8.0024618065338e-06 7.64666381101666e-05 1.74192816114205e-05 4.96992934753902e-05 1.17159821755095e-05 2.83405078275691e-05 4.43005026945238e-06 1.74192816114205e-05 3.76778062708226e-05 3.29498395779722e-05 4.23285146090178e-05 4.11331217975915e-05 -4.99419452861784e-06 4.96992934753902e-05 3.29498395779722e-05 0.000116151698185827 668 674 0 386 0 668 674 0 387 0 0 0 0 0 0 0 0 0 1337 0 0 0 0 0 1095 +934 889 0.917063514569173 0.387085141724819 0.0957058164476614 -0.0130406378012919 -0.385698671994006 0.92202219250763 -0.0333408300059111 -0.108900531300517 -0.101148626624867 -0.00633794756209093 0.994851137483696 0.392954347739595 2.85407105231987e-05 3.77137992427023e-06 5.24744010694253e-06 6.45300589525083e-06 3.78178700815488e-06 3.05856708455964e-05 3.77137992427023e-06 7.31900039662491e-05 -3.43577032555066e-06 2.33598878453907e-05 1.3027772824128e-05 3.13634060496903e-05 5.24744010694253e-06 -3.43577032555066e-06 1.03610641895433e-05 -4.89405599369257e-06 5.0576787159049e-06 -8.46058216282415e-09 6.45300589525083e-06 2.33598878453907e-05 -4.89405599369257e-06 5.54687996804703e-05 1.10268989155501e-05 2.52588997159419e-05 3.78178700815488e-06 1.3027772824128e-05 5.0576787159049e-06 1.10268989155501e-05 2.78706099720496e-05 1.34023885455492e-05 3.05856708455964e-05 3.13634060496903e-05 -8.46058216282415e-09 2.52588997159419e-05 1.34023885455492e-05 7.37010206057306e-05 747 755 0 537 0 747 755 0 539 0 0 0 0 0 0 0 0 0 1726 0 0 0 0 0 1282 +934 882 0.919974456727775 0.391558674261267 0.0181329418240331 0.00370704023154205 -0.388471636040088 0.916942156976902 -0.0911420251633922 -0.10319848353255 -0.0523143093309305 0.0768042015081591 0.995672801511582 0.395558536257085 2.63712019155767e-05 -1.4139108662748e-06 4.99049846916719e-06 3.16032766642252e-06 3.05243609082261e-06 2.10825046678924e-05 -1.4139108662748e-06 6.56567875778511e-05 -5.29948900190784e-06 1.74153559960124e-05 1.34216371927765e-05 1.23575633702852e-05 4.99049846916719e-06 -5.29948900190784e-06 1.14720547913329e-05 -7.86934237510216e-06 7.15965611791337e-06 2.46915562596362e-07 3.16032766642252e-06 1.74153559960124e-05 -7.86934237510216e-06 5.41363731935078e-05 1.21677193644834e-06 1.19601065318397e-05 3.05243609082261e-06 1.34216371927765e-05 7.15965611791337e-06 1.21677193644834e-06 3.02021151579087e-05 1.04842731789639e-05 2.10825046678924e-05 1.23575633702852e-05 2.46915562596362e-07 1.19601065318397e-05 1.04842731789639e-05 5.68424138899552e-05 711 713 0 392 0 711 713 0 394 0 0 0 0 0 0 0 0 0 1343 0 0 0 0 0 1161 +934 879 0.919689302047072 0.392342913644386 0.0154475180273104 0.0136375389425261 -0.388976969263819 0.915754318855463 -0.100453695202813 -0.100493486648038 -0.0535584268113238 0.0863774600842128 0.994821807816302 0.401783017670028 3.01978357800941e-05 -9.18681685751489e-06 6.46657430280478e-06 7.00076814611832e-06 1.13716337403266e-05 2.5750380853163e-05 -9.18681685751489e-06 6.18168455455483e-05 -8.01097386214698e-06 2.83832068961954e-05 1.0467509277786e-05 1.4696808897898e-06 6.46657430280478e-06 -8.01097386214698e-06 1.18499528611173e-05 -7.7608038293542e-06 7.25762678817912e-06 2.27634198585694e-06 7.00076814611832e-06 2.83832068961954e-05 -7.7608038293542e-06 7.41197436427779e-05 1.2965453330217e-05 2.2723333901995e-05 1.13716337403266e-05 1.0467509277786e-05 7.25762678817912e-06 1.2965453330217e-05 3.26573762401749e-05 2.28289906735906e-05 2.5750380853163e-05 1.4696808897898e-06 2.27634198585694e-06 2.2723333901995e-05 2.28289906735906e-05 7.15482432812045e-05 643 648 0 396 0 643 648 0 397 0 0 0 0 0 0 0 0 0 1335 0 0 0 0 0 1305 +934 886 0.919509216963206 0.391753397438221 0.03212593213158 0.0108568213511735 -0.38786504478991 0.917555980547524 -0.0874741652809187 -0.100788728627687 -0.0637456425948674 0.0679727751168347 0.995648630237135 0.398865758315163 3.50189242702975e-05 1.38730847851791e-05 4.63167695761465e-06 1.29384686109406e-05 1.2786433766764e-05 3.53338879936699e-05 1.38730847851791e-05 0.000139552111557667 -5.67031175610478e-06 4.54124261677897e-05 2.97640655995224e-05 3.82924835694349e-05 4.63167695761465e-06 -5.67031175610478e-06 1.22109938726258e-05 -9.76928941674444e-06 4.71627501988637e-06 -3.6477597096802e-06 1.29384686109406e-05 4.54124261677897e-05 -9.76928941674444e-06 7.82708424809449e-05 1.94980532941428e-05 3.40798097479823e-05 1.2786433766764e-05 2.97640655995224e-05 4.71627501988637e-06 1.94980532941428e-05 3.98829394625037e-05 2.5287457807186e-05 3.53338879936699e-05 3.82924835694349e-05 -3.6477597096802e-06 3.40798097479823e-05 2.5287457807186e-05 9.18268933826203e-05 696 704 0 439 0 696 704 0 442 0 0 0 0 0 0 0 0 0 1382 0 0 0 0 0 1277 +934 888 0.918111953768104 0.388766902229294 0.0770112724161501 -0.00577238931960567 -0.385883853586056 0.921194971205191 -0.0499347230676421 -0.108590058807922 -0.0903553644765555 0.0161282595869925 0.995778985193503 0.398111094455921 2.44706495416937e-05 3.65624453047737e-06 4.26710115966173e-06 5.01027473813059e-06 3.76865969166912e-06 2.30238582942679e-05 3.65624453047737e-06 6.93447010572385e-05 -8.85009863514427e-07 1.41816143164876e-05 6.50228401601745e-06 1.63412114912923e-05 4.26710115966173e-06 -8.85009863514427e-07 1.07681173145184e-05 -6.92979360822963e-06 6.17513662298537e-06 -9.93571538623452e-07 5.01027473813059e-06 1.41816143164876e-05 -6.92979360822963e-06 5.25634767603431e-05 5.46939424319767e-06 1.66940182219238e-05 3.76865969166912e-06 6.50228401601745e-06 6.17513662298537e-06 5.46939424319767e-06 2.3731011111835e-05 8.44609218903706e-06 2.30238582942679e-05 1.63412114912923e-05 -9.93571538623452e-07 1.66940182219238e-05 8.44609218903706e-06 6.71290705470897e-05 747 758 0 520 0 747 758 0 515 0 0 0 0 0 0 0 0 0 1642 0 0 0 0 0 1172 +934 881 0.919889035134007 0.391841657749387 0.0162566384113845 0.00786605851121381 -0.388813796902734 0.916630853384049 -0.092799299364324 -0.0987095921266301 -0.0512639676410817 0.0790442526477546 0.995552114027715 0.39675725059411 3.32593991371938e-05 -1.43748692730698e-05 3.16894875799254e-06 6.13545422770043e-06 6.56223397044701e-06 2.15842941931907e-05 -1.43748692730698e-05 6.23598342426689e-05 -5.29995332204721e-06 3.20691505371175e-05 1.93923271794707e-05 2.24789778840412e-05 3.16894875799254e-06 -5.29995332204721e-06 1.02092420855127e-05 -5.37997991288179e-06 3.29246591674478e-06 -3.51484173435109e-06 6.13545422770043e-06 3.20691505371175e-05 -5.37997991288179e-06 7.3562833865085e-05 2.36440037316994e-05 3.58153503111397e-05 6.56223397044701e-06 1.93923271794707e-05 3.29246591674478e-06 2.36440037316994e-05 3.53880999471944e-05 2.48500687198429e-05 2.15842941931907e-05 2.24789778840412e-05 -3.51484173435109e-06 3.58153503111397e-05 2.48500687198429e-05 6.60677512984038e-05 634 639 0 369 0 634 639 0 370 0 0 0 0 0 0 0 0 0 1364 0 0 0 0 0 1180 +934 880 0.919789516554857 0.392073387650653 0.0163004273540207 0.0130890979452008 -0.388857230154207 0.916249064716461 -0.0963208490567305 -0.0972494214113751 -0.0527000929086596 0.0822563681568291 0.995216855818402 0.400303132770931 2.52903436165422e-05 -7.3166022343569e-06 4.8496219243223e-06 3.04032060034085e-06 9.4361554594102e-06 1.89139614511417e-05 -7.3166022343569e-06 6.54928778933099e-05 -8.63662347853775e-06 2.38739002258018e-05 1.26011688294476e-05 1.52838341985686e-05 4.8496219243223e-06 -8.63662347853775e-06 1.17915088459284e-05 -9.36998322007899e-06 3.95173391459975e-06 -3.57170376121103e-06 3.04032060034085e-06 2.38739002258018e-05 -9.36998322007899e-06 6.90147341790081e-05 1.86484063662482e-05 2.97207831146562e-05 9.4361554594102e-06 1.26011688294476e-05 3.95173391459975e-06 1.86484063662482e-05 3.31276088327792e-05 1.81972968671624e-05 1.89139614511417e-05 1.52838341985686e-05 -3.57170376121103e-06 2.97207831146562e-05 1.81972968671624e-05 6.47802350144122e-05 652 660 0 375 0 652 660 0 375 0 0 0 0 0 0 0 0 0 1340 0 0 0 0 0 604 +934 890 0.916025158235692 0.385061569310631 0.11236323829131 -0.0211327302010772 -0.385544397676842 0.922508175406964 -0.0182806927471469 -0.110877875744501 -0.110695198176236 -0.0265754425616791 0.99349902815925 0.394977485433537 2.23880368720781e-05 1.00619078851492e-06 6.30748465257914e-06 4.12860944915517e-06 2.79456230493753e-07 1.38902372138262e-05 1.00619078851492e-06 4.06211166608938e-05 -6.28514215666637e-07 3.68186314971563e-06 -9.79494609696016e-07 5.24721941436539e-06 6.30748465257914e-06 -6.28514215666637e-07 1.14401378441278e-05 -6.97373013769361e-06 7.36547037916393e-06 4.18670614015581e-08 4.12860944915517e-06 3.68186314971563e-06 -6.97373013769361e-06 3.61761094894985e-05 -4.37829144484755e-06 5.51307764193606e-06 2.79456230493753e-07 -9.79494609696016e-07 7.36547037916393e-06 -4.37829144484755e-06 2.26048039134475e-05 3.99188807639675e-07 1.38902372138262e-05 5.24721941436539e-06 4.18670614015581e-08 5.51307764193606e-06 3.99188807639675e-07 3.91106068157481e-05 776 786 0 589 0 776 786 0 590 0 0 0 0 0 0 0 0 0 1775 0 0 0 0 0 682 +934 899 0.914326742896376 0.382146882707528 0.134053598465026 -0.0317327034250231 -0.385680802235972 0.922632178243349 0.000427149329677812 -0.117320258014412 -0.123518929768359 -0.0520924534539448 0.990973990719246 0.392867123123374 3.50450982481525e-05 8.22283298749768e-06 3.16902852558431e-06 8.9549900670024e-06 5.54215637723268e-06 3.47910988491149e-05 8.22283298749768e-06 0.000126970893126644 1.3210127288404e-06 3.4844776883898e-05 2.34511715016193e-05 6.20083279916573e-05 3.16902852558431e-06 1.3210127288404e-06 1.06457790404083e-05 -5.23432762554899e-06 7.90847368098692e-06 -8.18831287809182e-07 8.9549900670024e-06 3.4844776883898e-05 -5.23432762554899e-06 3.59529856337205e-05 1.89076160297353e-06 3.17876604716565e-05 5.54215637723268e-06 2.34511715016193e-05 7.90847368098692e-06 1.89076160297353e-06 2.11216125057818e-05 1.79009988618818e-05 3.47910988491149e-05 6.20083279916573e-05 -8.18831287809182e-07 3.17876604716565e-05 1.79009988618818e-05 0.000113695453975246 768 784 0 604 0 768 784 0 598 0 0 0 0 0 0 0 0 0 2020 0 0 0 0 0 1054 +935 938 0.990952179642683 -0.132408974359999 0.0219463247572277 0.0900662715215017 0.132052435412237 0.99109737406068 0.0169749648518745 0.141076891057218 -0.023998582523005 -0.0139233127867831 0.999615030598244 -0.370844356518722 2.91839443722545e-05 -6.62102407323949e-06 5.09066751073235e-06 8.28708326202942e-06 1.23931231454542e-06 8.35788352459163e-06 -6.62102407323949e-06 3.72402436259752e-05 -1.92986069752451e-06 6.08540766117963e-06 -1.16737089836107e-06 -1.25549447398401e-05 5.09066751073235e-06 -1.92986069752451e-06 9.68030706641281e-06 2.4345397304644e-06 5.83146929508447e-06 7.84164564575895e-07 8.28708326202942e-06 6.08540766117963e-06 2.4345397304644e-06 9.72014340923247e-05 1.5518256322475e-06 3.49701576469411e-05 1.23931231454542e-06 -1.16737089836107e-06 5.83146929508447e-06 1.5518256322475e-06 1.61725958289789e-05 -2.5458997850573e-06 8.35788352459163e-06 -1.25549447398401e-05 7.84164564575895e-07 3.49701576469411e-05 -2.5458997850573e-06 0.000189754063820086 1916 1990 0 0 38 1912 1986 0 0 38 0 0 0 0 0 287 268 0 3251 0 0 0 0 0 505 +935 937 0.995759247481305 -0.0873711174635256 0.0288064036047498 0.0444760156470887 0.0873980372380601 0.996173417150823 0.000325651634307976 0.0894190076689521 -0.0287246260619627 0.00219335250862294 0.999584956400592 -0.242082284480393 3.30256220576634e-05 -4.02950951101393e-06 3.14708113629643e-06 4.22817060889355e-06 -3.41270140328969e-07 8.45047917933944e-06 -4.02950951101393e-06 3.18924515717312e-05 -1.35978552679663e-06 5.49218089436137e-06 -1.97953101594975e-07 -5.03691435815908e-06 3.14708113629643e-06 -1.35978552679663e-06 9.44648117257871e-06 3.16437672966269e-06 4.25799166982856e-06 -1.51479264564854e-06 4.22817060889355e-06 5.49218089436137e-06 3.16437672966269e-06 6.8016444109524e-05 1.32810281819705e-06 2.34876338266509e-05 -3.41270140328969e-07 -1.97953101594975e-07 4.25799166982856e-06 1.32810281819705e-06 1.43751631707857e-05 3.06169702809531e-07 8.45047917933944e-06 -5.03691435815908e-06 -1.51479264564854e-06 2.34876338266509e-05 3.06169702809531e-07 8.42491890059718e-05 2551 2552 0 0 0 2549 2550 0 0 0 0 0 0 0 0 211 197 0 3749 0 0 0 0 0 696 +934 900 0.912221554379207 0.381513969108905 0.149328252855085 -0.0222896697157063 -0.385184284996977 0.922827827407934 -0.00467627553936844 -0.120441436400454 -0.139588331594552 -0.0532530969646057 0.988776620550025 0.405914309676196 2.7472113221599e-05 9.43082393291592e-06 5.74550988285111e-06 -4.82138431176505e-07 2.69399291498758e-06 2.44783155201165e-05 9.43082393291592e-06 8.6624859109056e-05 7.18429144804052e-08 4.62902677987877e-06 2.77769198145327e-06 3.98957562543198e-05 5.74550988285111e-06 7.18429144804052e-08 1.18791255208053e-05 -6.93208756672621e-06 6.98260001082973e-06 -1.18165327168212e-06 -4.82138431176505e-07 4.62902677987877e-06 -6.93208756672621e-06 3.5451655076766e-05 1.06329375671419e-06 8.2875671648334e-06 2.69399291498758e-06 2.77769198145327e-06 6.98260001082973e-06 1.06329375671419e-06 2.01498274124923e-05 5.05441104636687e-06 2.44783155201165e-05 3.98957562543198e-05 -1.18165327168212e-06 8.2875671648334e-06 5.05441104636687e-06 7.97203144785811e-05 805 818 0 618 0 805 818 0 611 0 0 0 0 0 0 0 0 0 1899 0 0 0 0 0 703 +935 932 0.969634775489177 0.20925832640124 0.126567590613892 -0.0553104651525515 -0.211510049859132 0.97736560630858 0.00446882687624312 -0.108575939646686 -0.122767670706263 -0.0311034473461404 0.991947919294428 0.331466333885683 2.59994657290101e-05 2.47387494052814e-06 2.48472041448282e-06 9.47545164123652e-06 1.40995302861023e-06 7.80642537454261e-06 2.47387494052814e-06 3.36426836478838e-05 -5.81884084467752e-07 1.67185907456499e-05 5.67827909015664e-06 -2.63241025097864e-06 2.48472041448282e-06 -5.81884084467752e-07 9.76490669463989e-06 -5.543848543742e-06 4.42408902704064e-06 -1.28172494168793e-06 9.47545164123652e-06 1.67185907456499e-05 -5.543848543742e-06 0.00010677239520284 2.24743886572511e-05 -1.95109365483346e-06 1.40995302861023e-06 5.67827909015664e-06 4.42408902704064e-06 2.24743886572511e-05 2.10349010656847e-05 -1.52943045177226e-07 7.80642537454261e-06 -2.63241025097864e-06 -1.28172494168793e-06 -1.95109365483346e-06 -1.52943045177226e-07 5.42305229065862e-05 1523 1529 0 431 0 1523 1529 0 428 0 0 0 0 0 0 0 0 0 2695 0 0 0 0 0 855 +935 931 0.940006432993316 0.283573053850472 0.189668735064849 -0.0450109497563063 -0.28623365988779 0.958060372805575 -0.0138063031577652 -0.129588042964985 -0.185629194574624 -0.041311562419744 0.981751066682393 0.419661218315204 3.40427439858759e-05 5.2656887973182e-06 4.15655363712569e-07 1.44359237986281e-05 -7.16027130599931e-07 1.6848698314838e-05 5.2656887973182e-06 4.21639424171037e-05 -7.47518573994058e-07 6.17396441834948e-06 5.16662155052885e-06 1.71803586069006e-05 4.15655363712569e-07 -7.47518573994058e-07 1.02366259791836e-05 -3.1087841101755e-06 6.75719976201562e-06 -2.23716994365132e-06 1.44359237986281e-05 6.17396441834948e-06 -3.1087841101755e-06 4.1933159963458e-05 5.19465480982479e-07 8.34637649207805e-06 -7.16027130599931e-07 5.16662155052885e-06 6.75719976201562e-06 5.19465480982479e-07 1.84290777941018e-05 4.06143009428868e-06 1.6848698314838e-05 1.71803586069006e-05 -2.23716994365132e-06 8.34637649207805e-06 4.06143009428868e-06 6.58647560394618e-05 1234 1242 0 538 0 1234 1242 0 529 0 0 0 0 0 0 0 0 0 2272 0 0 0 0 0 780 +935 858 0.904022589017039 0.41988724703156 0.0802362656607832 -0.0988264413105694 -0.415899490440991 0.907291983464235 -0.0620392665370823 -0.107751709571679 -0.0988472174512479 0.0227146763523636 0.994843339968838 0.381930497448856 3.6986801726232e-05 1.63095450556608e-05 -7.33790656960653e-08 9.0571881391734e-06 5.12356854504709e-06 2.6814245665063e-05 1.63095450556608e-05 0.000104235274670695 -5.8829267054103e-06 2.09454690200924e-05 1.58263796347581e-05 6.64796223624202e-05 -7.33790656960653e-08 -5.8829267054103e-06 1.19751887298193e-05 -8.16777958704975e-06 3.20237202007535e-06 -7.92615344547632e-06 9.0571881391734e-06 2.09454690200924e-05 -8.16777958704975e-06 6.51410277501514e-05 1.48230219027472e-05 3.05932792623316e-05 5.12356854504709e-06 1.58263796347581e-05 3.20237202007535e-06 1.48230219027472e-05 3.14916632272921e-05 2.11180991105389e-05 2.6814245665063e-05 6.64796223624202e-05 -7.92615344547632e-06 3.05932792623316e-05 2.11180991105389e-05 0.000130666162432014 1091 1100 0 629 0 1091 1100 0 623 0 0 0 0 0 0 0 0 0 1768 0 0 0 0 0 1031 +934 898 0.9128158456021 0.38212310172662 0.144045711996402 -0.0219823392148792 -0.385605059428034 0.922655106637985 -0.00403637688415326 -0.117627590648238 -0.134446904617495 -0.0518602865560487 0.989562802714966 0.399512732603818 3.2056292363415e-05 1.15881168274491e-05 1.65769434805608e-06 4.39575977757812e-06 4.34871668044653e-06 2.58882852659265e-05 1.15881168274491e-05 9.64488959418396e-05 1.879795927287e-06 1.44945431603023e-05 5.4189293025515e-06 3.91122172418591e-05 1.65769434805608e-06 1.879795927287e-06 1.17016927180784e-05 -4.10915196020426e-06 6.17215868238458e-06 -4.84386703642499e-06 4.39575977757812e-06 1.44945431603023e-05 -4.10915196020426e-06 4.01652588235944e-05 2.80566334187009e-06 1.79956016518327e-05 4.34871668044653e-06 5.4189293025515e-06 6.17215868238458e-06 2.80566334187009e-06 1.93560632781374e-05 5.9125743504769e-06 2.58882852659265e-05 3.91122172418591e-05 -4.84386703642499e-06 1.79956016518327e-05 5.9125743504769e-06 7.80448209804394e-05 786 798 0 620 0 786 798 0 614 0 0 0 0 0 0 0 0 0 1981 0 0 0 0 0 780 +935 861 0.917144524913445 0.393161990566852 0.0653419436105314 -0.0633688297661808 -0.387204225369564 0.917816594001147 -0.0876674833224351 -0.117308186083369 -0.0944394423810678 0.0551030756822546 0.994004448065052 0.45992574468574 4.00247360665866e-05 9.20066740549382e-06 -5.5530610207095e-07 1.53884248657378e-05 -4.69015466248688e-07 3.51776021821401e-05 9.20066740549382e-06 6.34025119640705e-05 -1.26532390827584e-06 1.80151674487024e-05 8.58150989971843e-06 2.86196680324729e-05 -5.5530610207095e-07 -1.26532390827584e-06 1.11209563990304e-05 -9.27116042684236e-06 3.96890756625368e-06 -9.1096117066654e-06 1.53884248657378e-05 1.80151674487024e-05 -9.27116042684236e-06 6.46355436385292e-05 9.19460923021348e-06 3.2813637278773e-05 -4.69015466248688e-07 8.58150989971843e-06 3.96890756625368e-06 9.19460923021348e-06 3.57238039281536e-05 1.61515872082561e-05 3.51776021821401e-05 2.86196680324729e-05 -9.1096117066654e-06 3.2813637278773e-05 1.61515872082561e-05 0.000108649099729436 942 951 0 497 0 942 951 0 495 0 0 0 0 0 0 0 0 0 1445 0 0 0 0 0 842 +935 856 0.905181065493342 0.396880059912777 0.152096866226657 -0.163310523513984 -0.381706372609601 0.916486380307754 -0.119803838918507 -0.0556563238643846 -0.186942461151979 0.0503878234697814 0.981077766267496 0.292036364480928 2.89811682798823e-05 -4.82692423051247e-06 7.53682486596508e-06 -1.92838249274775e-06 5.42702623575991e-07 6.10004842381977e-06 -4.82692423051247e-06 4.24532493293098e-05 -4.0650222156991e-06 7.19122560359089e-06 9.8398308232571e-06 2.12054703645906e-05 7.53682486596508e-06 -4.0650222156991e-06 1.02065267452114e-05 -2.49711927980451e-06 3.95534405738941e-06 4.1255441274427e-07 -1.92838249274775e-06 7.19122560359089e-06 -2.49711927980451e-06 5.35981336450794e-05 9.73823891101988e-06 6.85416343209788e-06 5.42702623575991e-07 9.8398308232571e-06 3.95534405738941e-06 9.73823891101988e-06 2.70325383132869e-05 1.84295711855157e-05 6.10004842381977e-06 2.12054703645906e-05 4.1255441274427e-07 6.85416343209788e-06 1.84295711855157e-05 9.42088219000936e-05 1558 1563 0 685 0 1558 1563 0 674 0 0 0 0 0 0 0 0 0 2196 0 0 0 0 0 1057 +935 860 0.910863889592525 0.396559683732496 0.114312693408736 -0.0532292021077946 -0.387345974920621 0.917042307832868 -0.0948498885469084 -0.120219924385954 -0.142443217982363 0.0421167767350456 0.988906520743128 0.449984214063261 3.02540836385261e-05 2.11546208864019e-05 -8.09732845456013e-07 1.99646555013098e-05 8.64192368124007e-07 2.29265080739995e-05 2.11546208864019e-05 0.00014923064900901 -1.24830246340888e-05 8.10439638180286e-05 5.24410187031595e-05 0.000118357797174786 -8.09732845456013e-07 -1.24830246340888e-05 1.25753090290379e-05 -1.4297278083942e-05 2.71551422783834e-06 -1.42547811227185e-05 1.99646555013098e-05 8.10439638180286e-05 -1.4297278083942e-05 0.000100483933492623 3.46565633248692e-05 9.21094546250168e-05 8.64192368124007e-07 5.24410187031595e-05 2.71551422783834e-06 3.46565633248692e-05 5.03298536478967e-05 5.93641449727352e-05 2.29265080739995e-05 0.000118357797174786 -1.42547811227185e-05 9.21094546250168e-05 5.93641449727352e-05 0.000174683599225037 1004 1014 0 595 0 1004 1014 0 585 0 0 0 0 0 0 0 0 0 1560 0 0 0 0 0 1220 +934 937 0.990728755468593 -0.135841032155674 -0.00193573514058088 0.0548153642084232 0.135832544891313 0.990723761812979 -0.00399343554957251 0.133658221224145 0.00246025120725096 0.00369347560169137 0.999990152652503 -0.395683225744175 4.75913166823745e-05 3.1102818338309e-05 -6.07236905837199e-07 3.93696006060375e-05 -7.61694416143072e-06 4.09792521559873e-05 3.1102818338309e-05 0.000186027213630039 7.10463594867713e-07 9.03134572301467e-05 -1.15949784729731e-05 2.70636327998645e-05 -6.07236905837199e-07 7.10463594867713e-07 1.0253542192788e-05 -1.20015644663979e-06 5.81639212087142e-06 -7.01763015053202e-06 3.93696006060375e-05 9.03134572301467e-05 -1.20015644663979e-06 0.000139802285607238 -1.15885255694711e-05 6.92214620087493e-05 -7.61694416143072e-06 -1.15949784729731e-05 5.81639212087142e-06 -1.15885255694711e-05 1.8749997694574e-05 -1.21498305096627e-05 4.09792521559873e-05 2.70636327998645e-05 -7.01763015053202e-06 6.92214620087493e-05 -1.21498305096627e-05 0.000208112513110993 1943 1944 0 0 0 1947 1948 0 0 0 0 0 0 0 0 335 321 0 3082 0 0 0 0 0 623 +935 939 0.983256781444279 -0.182202763421209 -0.00287310729219259 0.156979393249274 0.182215609766996 0.983245217334056 0.0051297316641852 0.201571293536554 0.00189031771911215 -0.00556736844297242 0.999982715404392 -0.441262180676981 4.33086481600973e-05 2.94527297297746e-06 1.3602308631745e-06 2.87602692915847e-05 -3.52688223608095e-06 4.00407441035092e-05 2.94527297297746e-06 5.84585106000478e-05 -5.40286504733664e-07 2.91491968449771e-05 -6.36105955146584e-06 2.82478355814751e-05 1.3602308631745e-06 -5.40286504733664e-07 1.00288696706386e-05 9.99338126611771e-07 5.52018062127067e-06 -2.69790052850189e-06 2.87602692915847e-05 2.91491968449771e-05 9.99338126611771e-07 0.000100059697630223 -7.96861068187068e-06 7.67548823474758e-05 -3.52688223608095e-06 -6.36105955146584e-06 5.52018062127067e-06 -7.96861068187068e-06 1.94903839802827e-05 -1.29711234493438e-05 4.00407441035092e-05 2.82478355814751e-05 -2.69790052850189e-06 7.67548823474758e-05 -1.29711234493438e-05 0.000198530658682846 2010 2067 0 0 196 2007 2064 0 0 196 0 0 0 0 0 383 355 0 2791 0 0 0 0 0 217 +935 857 0.906659943377739 0.409244273276105 0.102405428884349 -0.133802444477007 -0.403169101702318 0.91202741425167 -0.0752374314152141 -0.0922195376101668 -0.124187046453406 0.026928060534061 0.99189336979791 0.335725502978793 3.03150119908505e-05 7.37865657252076e-06 1.33102925400232e-06 7.29354813853787e-06 -2.85537097168384e-06 1.08750517891694e-05 7.37865657252076e-06 3.57699472147001e-05 -1.72153388382068e-06 1.15021497475655e-05 9.34763417956265e-08 -1.97836573700612e-06 1.33102925400232e-06 -1.72153388382068e-06 1.01042925368953e-05 -6.71071223044097e-06 6.93905423122602e-06 -1.62502304191836e-06 7.29354813853787e-06 1.15021497475655e-05 -6.71071223044097e-06 4.64087022518791e-05 1.15137522275735e-06 -7.10177369872552e-07 -2.85537097168384e-06 9.34763417956265e-08 6.93905423122602e-06 1.15137522275735e-06 2.52601833734432e-05 -3.06142341105765e-07 1.08750517891694e-05 -1.97836573700612e-06 -1.62502304191836e-06 -7.10177369872552e-07 -3.06142341105765e-07 5.22035803732609e-05 1347 1351 0 696 0 1347 1351 0 682 0 0 0 0 0 0 0 0 0 1908 0 0 0 0 0 968 +935 859 0.904903765832837 0.409740360714955 0.115160806625905 -0.0746185426878065 -0.404453333969038 0.912092273070638 -0.0671206827003857 -0.120052172589367 -0.13253933462516 0.0141605863584389 0.991076587641493 0.421552890040114 3.65820738215685e-05 1.43885626586944e-05 -6.80714399845185e-07 1.20202566479464e-05 2.72541154469686e-06 3.72885350878557e-05 1.43885626586944e-05 6.60571725310991e-05 -5.49492459760027e-07 1.26277183179088e-05 9.77347630147052e-06 2.89438418878201e-05 -6.80714399845185e-07 -5.49492459760027e-07 1.20954723040016e-05 -6.83990593447925e-06 5.10952440605536e-06 -7.81752978380479e-06 1.20202566479464e-05 1.26277183179088e-05 -6.83990593447925e-06 5.61074364114761e-05 8.37856231719654e-06 1.81083889110968e-05 2.72541154469686e-06 9.77347630147052e-06 5.10952440605536e-06 8.37856231719654e-06 2.84224481768523e-05 1.03925571641098e-05 3.72885350878557e-05 2.89438418878201e-05 -7.81752978380479e-06 1.81083889110968e-05 1.03925571641098e-05 8.45037802012958e-05 1162 1168 0 635 0 1162 1168 0 627 0 0 0 0 0 0 0 0 0 1752 0 0 0 0 0 1191 +935 864 0.922473161690257 0.384947315878506 0.0293058007758738 -0.0231887443114061 -0.383203746034523 0.922222173723305 -0.0515863481763385 -0.125997956795146 -0.046884485560684 0.0363569290644252 0.998238457845977 0.505417815751507 3.49771413927969e-05 -3.91522611422587e-06 2.16736425404883e-06 1.11510489740249e-05 4.37451159432816e-06 2.66350989563024e-05 -3.91522611422587e-06 6.59020675351426e-05 -2.2310120547104e-06 2.22948170985654e-05 1.42594653840342e-05 -2.64150605652902e-06 2.16736425404883e-06 -2.2310120547104e-06 1.07631542559929e-05 -4.51967635433432e-06 5.36036876220632e-06 -1.71500966818337e-07 1.11510489740249e-05 2.22948170985654e-05 -4.51967635433432e-06 6.46253444108726e-05 1.11629779672494e-05 2.04295855060491e-05 4.37451159432816e-06 1.42594653840342e-05 5.36036876220632e-06 1.11629779672494e-05 2.99060260957105e-05 1.18411655085252e-05 2.66350989563024e-05 -2.64150605652902e-06 -1.71500966818337e-07 2.04295855060491e-05 1.18411655085252e-05 7.49777327027126e-05 765 769 0 437 0 765 769 0 432 0 0 0 0 0 0 0 0 0 1433 0 0 0 0 0 1318 +935 863 0.919129149072578 0.393077171787009 0.0263048350126965 -0.0516229732057397 -0.391701978605191 0.918963025112454 -0.0455688318145723 -0.11940201694613 -0.0420852382896616 0.0315799856886029 0.998614809234276 0.481768953826083 5.69362385872608e-05 1.48604401683502e-05 3.86688985694885e-07 2.28122762486625e-05 1.34020566279771e-05 5.3885002477463e-05 1.48604401683502e-05 9.08393470754338e-05 -8.18506478601058e-07 2.91063952960691e-05 1.55350621865635e-05 2.09226056035811e-05 3.86688985694885e-07 -8.18506478601058e-07 1.45066128969203e-05 -1.07450431196717e-05 7.60076682750657e-06 -4.80005436220845e-06 2.28122762486625e-05 2.91063952960691e-05 -1.07450431196717e-05 7.65026563735889e-05 1.0833722863239e-05 2.96974895594256e-05 1.34020566279771e-05 1.55350621865635e-05 7.60076682750657e-06 1.0833722863239e-05 3.37710495092449e-05 1.84207695178846e-05 5.3885002477463e-05 2.09226056035811e-05 -4.80005436220845e-06 2.96974895594256e-05 1.84207695178846e-05 0.000103153532302934 764 768 0 467 0 764 768 0 463 0 0 0 0 0 0 0 0 0 1512 0 0 0 0 0 384 +935 862 0.917729213813782 0.394809506179273 0.0435722841174902 -0.0477529810540466 -0.392519851681805 0.918229253235028 -0.0527560853280145 -0.120715152074974 -0.0608379499032525 0.0313128142127369 0.997656379480254 0.481552402016043 3.62520362979639e-05 1.17849387819471e-05 3.05302275347152e-08 1.29513099545614e-05 -2.05970882419752e-06 9.05122978598644e-06 1.17849387819471e-05 6.84255469236949e-05 -1.43472161612187e-07 2.27211147308069e-05 1.81631776444388e-05 3.34626864185639e-05 3.05302275347152e-08 -1.43472161612187e-07 1.05226886437898e-05 -5.5644447891648e-06 5.26930106052639e-06 -1.29936798546336e-06 1.29513099545614e-05 2.27211147308069e-05 -5.5644447891648e-06 6.45452276645383e-05 1.27042116163362e-05 2.59953301470086e-05 -2.05970882419752e-06 1.81631776444388e-05 5.26930106052639e-06 1.27042116163362e-05 3.46600937077132e-05 1.499369016491e-05 9.05122978598644e-06 3.34626864185639e-05 -1.29936798546336e-06 2.59953301470086e-05 1.499369016491e-05 7.9315164818496e-05 866 870 0 477 0 866 870 0 471 0 0 0 0 0 0 0 0 0 1451 0 0 0 0 0 774 +935 866 0.912329894541103 0.407752731597947 0.0373078195695293 -0.0170381270070936 -0.404298028808227 0.911506902385351 -0.0754868916146615 -0.134532721033632 -0.0647863213062896 0.0537854699549461 0.996448621752935 0.500666250908338 4.51190486287317e-05 5.67989672149361e-06 3.00224362449631e-06 1.88939956696994e-05 1.34174781429547e-05 4.27114258889125e-05 5.67989672149361e-06 0.000142527180816574 -1.26056862352842e-05 8.11696076068955e-05 5.34377479638652e-05 9.4028530988046e-05 3.00224362449631e-06 -1.26056862352842e-05 1.34817013015345e-05 -1.06214382904231e-05 3.35693085995408e-06 -6.61611851625329e-06 1.88939956696994e-05 8.11696076068955e-05 -1.06214382904231e-05 0.000111188991583119 4.16696847837408e-05 9.17741506954739e-05 1.34174781429547e-05 5.34377479638652e-05 3.35693085995408e-06 4.16696847837408e-05 5.58464200820153e-05 6.15507805145357e-05 4.27114258889125e-05 9.4028530988046e-05 -6.61611851625329e-06 9.17741506954739e-05 6.15507805145357e-05 0.000184889222182296 707 716 0 456 0 707 716 0 454 0 0 0 0 0 0 0 0 0 1325 0 0 0 0 0 531 +935 867 0.905363867073309 0.421442096854719 0.0519887218227356 -0.00477487441193052 -0.415565359277085 0.904528538451023 -0.0955696358503222 -0.139210682003457 -0.0873023502946575 0.0649205832256141 0.994064191844106 0.515936676754566 7.48388093146126e-05 -5.41442902782825e-06 -2.14839374631595e-06 -1.17013822560884e-06 3.73627017967023e-06 7.84370313931368e-06 -5.41442902782825e-06 9.18370589167132e-05 -4.83882350263769e-06 3.2825606535709e-05 1.85373992211326e-05 2.59045453188278e-05 -2.14839374631595e-06 -4.83882350263769e-06 1.34931188829346e-05 -4.38595621508814e-06 4.10894609576758e-06 -2.59559472321115e-06 -1.17013822560884e-06 3.2825606535709e-05 -4.38595621508814e-06 7.51832200054991e-05 1.50004326738798e-05 5.66735268304548e-05 3.73627017967023e-06 1.85373992211326e-05 4.10894609576758e-06 1.50004326738798e-05 4.00540454919575e-05 3.51804240590109e-05 7.84370313931368e-06 2.59045453188278e-05 -2.59559472321115e-06 5.66735268304548e-05 3.51804240590109e-05 0.000127553226721936 737 746 0 461 0 737 746 0 449 0 0 0 0 0 0 0 0 0 1265 0 0 0 0 0 707 +935 868 0.8974359513041 0.436219492353844 0.0657363506551758 -0.00221244013105843 -0.429494610967184 0.898000101804748 -0.0955520607250847 -0.140399112223896 -0.100712921003481 0.0575184461648363 0.993251496799139 0.514352109048985 4.309850916076e-05 7.72526423229845e-06 5.27554888921377e-06 -9.59469334101638e-07 7.51453004443367e-06 2.80789965868849e-05 7.72526423229845e-06 6.55161456938602e-05 -2.40871182126515e-07 5.71671874339167e-06 1.39586396128639e-05 7.2362406988402e-06 5.27554888921377e-06 -2.40871182126515e-07 1.17352890333514e-05 -4.95074258713153e-06 6.02790185104403e-06 -1.50979845612374e-06 -9.59469334101638e-07 5.71671874339167e-06 -4.95074258713153e-06 5.88072429300263e-05 7.74267692180021e-06 1.36321067252227e-05 7.51453004443367e-06 1.39586396128639e-05 6.02790185104403e-06 7.74267692180021e-06 3.38590063817664e-05 1.76711599109188e-05 2.80789965868849e-05 7.2362406988402e-06 -1.50979845612374e-06 1.36321067252227e-05 1.76711599109188e-05 8.98806608073336e-05 742 751 0 501 0 742 751 0 489 0 0 0 0 0 0 0 0 0 1252 0 0 0 0 0 1215 +935 869 0.893442934458847 0.445359343343913 0.0584361032397148 -0.0258307030775992 -0.439761843894455 0.893778834947357 -0.0881414479952209 -0.145169951259054 -0.091483569672989 0.0530513854335984 0.994392431077119 0.499438371877439 2.85480524806607e-05 -1.00850997105699e-05 2.59877451551512e-06 3.15567684972049e-06 -4.0837608409874e-06 8.60532778363193e-06 -1.00850997105699e-05 4.83131445644582e-05 -2.90714215042999e-06 1.76803833685655e-05 1.21595863819003e-05 1.45345238037053e-05 2.59877451551512e-06 -2.90714215042999e-06 1.01487661015527e-05 -6.95265623808939e-06 3.80198370143936e-06 -4.35940196758474e-06 3.15567684972049e-06 1.76803833685655e-05 -6.95265623808939e-06 7.29891897443873e-05 1.9061149175775e-05 3.96831271203083e-05 -4.0837608409874e-06 1.21595863819003e-05 3.80198370143936e-06 1.9061149175775e-05 3.83399617532563e-05 2.41751808106619e-05 8.60532778363193e-06 1.45345238037053e-05 -4.35940196758474e-06 3.96831271203083e-05 2.41751808106619e-05 7.73928842779688e-05 736 748 0 511 0 736 748 0 510 0 0 0 0 0 0 0 0 0 1162 0 0 0 0 0 1110 +935 870 0.893067817716647 0.44659318265744 0.0546296820668359 -0.00576192250737512 -0.441612317014039 0.893316142415072 -0.0834555639975351 -0.144928184864769 -0.0860722627814386 0.0504063379403149 0.995012947993708 0.51897664662621 3.89007259309627e-05 -6.66240341968633e-06 3.28566676653519e-06 1.39872137733365e-07 -1.09440608316668e-06 2.93314776365322e-05 -6.66240341968633e-06 9.1729596268764e-05 -6.3068202337796e-06 4.01793589916347e-05 2.70667564245757e-05 6.60508651642034e-05 3.28566676653519e-06 -6.3068202337796e-06 1.30033939244258e-05 -9.64385113025654e-06 2.63329318313399e-06 -9.51355063853604e-06 1.39872137733365e-07 4.01793589916347e-05 -9.64385113025654e-06 8.95770410559381e-05 2.99574554787021e-05 6.26343370976839e-05 -1.09440608316668e-06 2.70667564245757e-05 2.63329318313399e-06 2.99574554787021e-05 4.65320661494414e-05 4.81370764488239e-05 2.93314776365322e-05 6.60508651642034e-05 -9.51355063853604e-06 6.26343370976839e-05 4.81370764488239e-05 0.000161209723328188 654 668 0 490 0 654 668 0 487 0 0 0 0 0 0 0 0 0 1194 0 0 0 0 0 565 +935 871 0.895979882201531 0.442876484003669 0.0328705127230798 -0.0173400283966093 -0.439792900311474 0.895144286926253 -0.0727936152345224 -0.147705734046908 -0.0616624320453828 0.0507653966776425 0.99680520613328 0.512838021453878 3.50265994652659e-05 7.71493805647609e-06 3.31804531862655e-06 2.16959723978841e-06 5.96181780808327e-06 3.10789520964556e-05 7.71493805647609e-06 0.000112290782497684 -2.15655402800751e-06 2.84045855951351e-05 3.13113724410371e-05 5.68481300605815e-05 3.31804531862655e-06 -2.15655402800751e-06 1.03948014807206e-05 -7.44006869170328e-06 4.81239209871746e-06 -5.27361929790498e-06 2.16959723978841e-06 2.84045855951351e-05 -7.44006869170328e-06 7.29248023894018e-05 2.09639553609271e-05 5.0183715884588e-05 5.96181780808327e-06 3.13113724410371e-05 4.81239209871746e-06 2.09639553609271e-05 3.85832291744429e-05 3.39950185748966e-05 3.10789520964556e-05 5.68481300605815e-05 -5.27361929790498e-06 5.0183715884588e-05 3.39950185748966e-05 0.000142007097714763 653 663 0 489 0 653 663 0 488 0 0 0 0 0 0 0 0 0 1297 0 0 0 0 0 1141 +935 873 0.905111571269703 0.424424002366158 0.0252449949332535 0.0022057354357687 -0.420980945416236 0.902922353258104 -0.0866387187307092 -0.13191734305815 -0.0595658219966856 0.067790045009117 0.995919887665429 0.524994478797098 4.27606825366221e-05 8.58697709395182e-06 5.07782015014706e-06 1.98090830163247e-05 1.62602410061406e-05 4.6815779565822e-05 8.58697709395182e-06 0.000112188662561023 -1.11655911308276e-05 6.09609075763634e-05 4.93573700961979e-05 8.01886279148049e-05 5.07782015014706e-06 -1.11655911308276e-05 1.41807648708799e-05 -1.00310731055845e-05 6.07702765646982e-06 -4.49552146453774e-06 1.98090830163247e-05 6.09609075763634e-05 -1.00310731055845e-05 9.4166420081473e-05 3.71237601115355e-05 7.9881158328023e-05 1.62602410061406e-05 4.93573700961979e-05 6.07702765646982e-06 3.71237601115355e-05 6.34525879337812e-05 6.68425262353873e-05 4.6815779565822e-05 8.01886279148049e-05 -4.49552146453774e-06 7.9881158328023e-05 6.68425262353873e-05 0.000166329323704647 663 668 0 415 0 663 668 0 414 0 0 0 0 0 0 0 0 0 1111 0 0 0 0 0 913 +935 872 0.900949310077561 0.433526160122097 0.0185851865892397 -0.0172645151058658 -0.431111960828891 0.899157088437104 -0.0752263753186191 -0.140923287687462 -0.0493236038934257 0.0597628547100876 0.996993271439615 0.509947780101797 4.26678395152688e-05 1.93235913990998e-05 3.14386413722527e-06 7.47168217021001e-06 9.36168072055524e-06 4.48464674642465e-05 1.93235913990998e-05 8.07188960093697e-05 -1.77026480887382e-06 1.71052839068179e-05 1.3882834030031e-05 2.97823715172766e-05 3.14386413722527e-06 -1.77026480887382e-06 1.11857113316537e-05 -6.69658495635911e-06 6.00330365891847e-06 1.03764973641781e-07 7.47168217021001e-06 1.71052839068179e-05 -6.69658495635911e-06 6.96487540394281e-05 8.95608190105777e-06 1.49534595531853e-05 9.36168072055524e-06 1.3882834030031e-05 6.00330365891847e-06 8.95608190105777e-06 3.25036520430676e-05 1.59315642991859e-05 4.48464674642465e-05 2.97823715172766e-05 1.03764973641781e-07 1.49534595531853e-05 1.59315642991859e-05 0.000100441593054806 659 667 0 437 0 659 667 0 436 0 0 0 0 0 0 0 0 0 1263 0 0 0 0 0 1225 +935 876 0.900928576026879 0.433679982974834 0.0157915567670426 0.00329897829880206 -0.43111386434391 0.898577917285574 -0.0818447465460081 -0.137098768584775 -0.0496843724790785 0.0669283118991299 0.996519976818174 0.525260512808416 4.20417221893044e-05 1.34453683592571e-05 -1.22303840066972e-06 2.19472138453796e-05 1.45038101657185e-05 3.44302512310841e-05 1.34453683592571e-05 8.9883585411018e-05 -4.6652547080392e-06 3.21026764527178e-05 2.31775784116926e-05 1.98158327912696e-05 -1.22303840066972e-06 -4.6652547080392e-06 1.21475301257909e-05 -6.32226491954716e-06 4.71247375963642e-06 -4.74669489394746e-06 2.19472138453796e-05 3.21026764527178e-05 -6.32226491954716e-06 6.50622414838937e-05 1.50643242726602e-05 3.74269278173361e-05 1.45038101657185e-05 2.31775784116926e-05 4.71247375963642e-06 1.50643242726602e-05 3.93454982125329e-05 2.51800434333094e-05 3.44302512310841e-05 1.98158327912696e-05 -4.74669489394746e-06 3.74269278173361e-05 2.51800434333094e-05 9.23393207519143e-05 582 590 0 400 0 582 590 0 399 0 0 0 0 0 0 0 0 0 1195 0 0 0 0 0 664 +935 875 0.900602986785502 0.434383119851439 0.0150188342145352 0.00284124025248868 -0.432063387262634 0.898482792658667 -0.077781107496753 -0.137776064504161 -0.0472809642474929 0.0635608093435919 0.996857328776498 0.524863158620159 4.25863135279619e-05 1.36872633531816e-05 2.19871839634862e-06 7.59936573715191e-06 1.1724471689595e-05 4.05344846035108e-05 1.36872633531816e-05 7.35964371621494e-05 -3.14792227909594e-06 2.90694653995536e-05 1.86462393438604e-05 4.30008106490123e-05 2.19871839634862e-06 -3.14792227909594e-06 1.13068905252065e-05 -4.69782830931247e-06 2.8029652686395e-06 -1.96350406010737e-06 7.59936573715191e-06 2.90694653995536e-05 -4.69782830931247e-06 7.50240804737079e-05 1.88883972566254e-05 3.91493683453901e-05 1.1724471689595e-05 1.86462393438604e-05 2.8029652686395e-06 1.88883972566254e-05 3.91137759362045e-05 3.82414988065445e-05 4.05344846035108e-05 4.30008106490123e-05 -1.96350406010737e-06 3.91493683453901e-05 3.82414988065445e-05 0.000149251786000153 636 642 0 389 0 636 642 0 388 0 0 0 0 0 0 0 0 0 1204 0 0 0 0 0 1182 +935 887 0.896998167549613 0.436281940343092 0.071079926442723 -0.00043872342586268 -0.432249110976081 0.899374042509162 -0.0654754741954243 -0.139871185094488 -0.0924932077129094 0.0280071453596253 0.995319348920627 0.531011146168318 3.19542108640769e-05 1.01834372739012e-05 -5.25315199265956e-07 2.24677084848171e-05 1.08742423770057e-05 3.83340143439173e-05 1.01834372739012e-05 0.000102678432108599 -4.93973537599296e-06 5.55644401701913e-05 3.74937344207203e-05 5.98783692743514e-05 -5.25315199265956e-07 -4.93973537599296e-06 1.08464809761953e-05 -9.83677197174233e-06 4.04887051517352e-06 -9.07743222818886e-06 2.24677084848171e-05 5.55644401701913e-05 -9.83677197174233e-06 9.08522927226488e-05 2.80411888486759e-05 7.63531104862139e-05 1.08742423770057e-05 3.74937344207203e-05 4.04887051517352e-06 2.80411888486759e-05 4.46727024893131e-05 4.99157081633897e-05 3.83340143439173e-05 5.98783692743514e-05 -9.07743222818886e-06 7.63531104862139e-05 4.99157081633897e-05 0.000145569435866599 650 661 0 501 0 650 661 0 494 0 0 0 0 0 0 0 0 0 1278 0 0 0 0 0 1200 +935 865 0.915040597101424 0.40298497101187 0.0174303985849823 -0.0235357993494288 -0.401214735811705 0.913772467487179 -0.0636129973349491 -0.132445294869899 -0.041562500211287 0.0512151423014168 0.997822412944925 0.501984591879829 4.6809978205225e-05 -3.15179319700681e-06 3.6301449946061e-06 3.02004850236915e-06 9.00599175140885e-06 3.78980583111101e-05 -3.15179319700681e-06 8.23474452243315e-05 -7.3897006593056e-07 2.73012823009768e-05 2.66448109014603e-05 3.59298491007897e-05 3.6301449946061e-06 -7.3897006593056e-07 1.16202283586804e-05 -8.0828630844318e-06 6.54534332200074e-06 -1.56798152390638e-06 3.02004850236915e-06 2.73012823009768e-05 -8.0828630844318e-06 9.56829356791525e-05 2.30084084873068e-05 3.43189132499645e-05 9.00599175140885e-06 2.66448109014603e-05 6.54534332200074e-06 2.30084084873068e-05 4.31637611815985e-05 3.28326272792698e-05 3.78980583111101e-05 3.59298491007897e-05 -1.56798152390638e-06 3.43189132499645e-05 3.28326272792698e-05 0.000129617019159705 764 775 0 450 0 764 775 0 439 0 0 0 0 0 0 0 0 0 1372 0 0 0 0 0 1150 +935 877 0.901512214028865 0.432511292200611 0.0144813699535825 0.00683387842081552 -0.429848900942721 0.898830210801466 -0.0856397951242691 -0.137085939242594 -0.0500564712610658 0.0709805203527658 0.996220916973409 0.527039312263833 3.79297520655541e-05 1.55749002039433e-06 1.51145595335779e-06 -5.05593192456717e-06 -4.9298685703071e-06 9.90728860529739e-06 1.55749002039433e-06 6.67228495389346e-05 -2.75068449661661e-06 1.00622891100391e-05 1.29762671105859e-05 6.27275025378878e-06 1.51145595335779e-06 -2.75068449661661e-06 1.13314711431607e-05 -9.6309982599193e-06 4.18958078879028e-06 -5.30407449845005e-06 -5.05593192456717e-06 1.00622891100391e-05 -9.6309982599193e-06 9.09071713185635e-05 1.96150543904375e-05 3.39342372019225e-05 -4.9298685703071e-06 1.29762671105859e-05 4.18958078879028e-06 1.96150543904375e-05 4.33039994820862e-05 2.63155762320168e-05 9.90728860529739e-06 6.27275025378878e-06 -5.30407449845005e-06 3.39342372019225e-05 2.63155762320168e-05 8.46323328076098e-05 584 593 0 408 0 584 593 0 400 0 0 0 0 0 0 0 0 0 1103 0 0 0 0 0 1081 +935 888 0.896155911553884 0.433978776784452 0.0925581087085184 -0.0207649016740287 -0.431717042891495 0.900923042716546 -0.0442500393150469 -0.143405285633111 -0.102591310860375 -0.000303978668599991 0.994723544776597 0.525679362186985 4.59067476261874e-05 -6.30226292289495e-06 9.71211156529876e-06 -1.43669371000484e-06 -2.54292245271727e-06 1.85130372386184e-05 -6.30226292289495e-06 0.000117865220469128 -1.61469274132912e-06 4.42517449614125e-05 2.46483775814032e-05 8.06700102385889e-05 9.71211156529876e-06 -1.61469274132912e-06 1.45683438069104e-05 -6.01139831234112e-06 6.74393452446528e-06 3.14340543323916e-06 -1.43669371000484e-06 4.42517449614125e-05 -6.01139831234112e-06 7.20911851750708e-05 2.02126301525744e-05 6.48519989765329e-05 -2.54292245271727e-06 2.46483775814032e-05 6.74393452446528e-06 2.02126301525744e-05 4.22196499305757e-05 4.0983662203074e-05 1.85130372386184e-05 8.06700102385889e-05 3.14340543323916e-06 6.48519989765329e-05 4.0983662203074e-05 0.000168357228452351 681 692 0 558 0 681 692 0 557 0 0 0 0 0 0 0 0 0 1375 0 0 0 0 0 735 +935 884 0.898330155290235 0.437861151894281 0.0357846860826866 -0.00782303581427926 -0.434080948504742 0.89720892902925 -0.0811780008093932 -0.13666233738355 -0.067651032818771 0.057391195596536 0.99605702067028 0.522661497689047 3.75454805879415e-05 -3.188396892271e-07 3.39694118494257e-06 -1.00678211675228e-06 3.03518038758215e-06 1.75770067034884e-05 -3.188396892271e-07 6.16193242496369e-05 1.27534021679608e-06 1.32021312345432e-05 7.80181077491864e-06 9.5477033345711e-06 3.39694118494257e-06 1.27534021679608e-06 1.2420653583048e-05 -5.14709743020899e-06 7.82743367605232e-06 1.6110243198516e-06 -1.00678211675228e-06 1.32021312345432e-05 -5.14709743020899e-06 5.39862074432202e-05 -1.69106380251125e-06 4.33967355236156e-06 3.03518038758215e-06 7.80181077491864e-06 7.82743367605232e-06 -1.69106380251125e-06 2.44950340232464e-05 1.16334306962819e-05 1.75770067034884e-05 9.5477033345711e-06 1.6110243198516e-06 4.33967355236156e-06 1.16334306962819e-05 8.3910661913911e-05 631 641 0 430 0 631 641 0 429 0 0 0 0 0 0 0 0 0 1229 0 0 0 0 0 560 +935 878 0.899511972013051 0.436497214942295 0.0186653034481778 0.00356573069750641 -0.433399719520215 0.896892794745233 -0.0880227121479729 -0.132118527198331 -0.0551624448786615 0.0710879461069603 0.995943577012926 0.526517789003726 4.12340663134597e-05 -1.25643458992799e-05 5.19050902350763e-06 -9.55916265409725e-06 -1.93301775098287e-07 1.03046648966167e-05 -1.25643458992799e-05 7.3402165194764e-05 -4.54136602691604e-06 3.77545701400967e-05 1.89920613783608e-05 9.70968781649474e-06 5.19050902350763e-06 -4.54136602691604e-06 1.17272145062898e-05 -6.64570928682949e-06 3.98359576155039e-06 4.87570647624863e-07 -9.55916265409725e-06 3.77545701400967e-05 -6.64570928682949e-06 9.44754704522577e-05 2.31107679787888e-05 3.80997314590202e-05 -1.93301775098287e-07 1.89920613783608e-05 3.98359576155039e-06 2.31107679787888e-05 4.12464236306785e-05 2.64550245848804e-05 1.03046648966167e-05 9.70968781649474e-06 4.87570647624863e-07 3.80997314590202e-05 2.64550245848804e-05 9.37563941307302e-05 572 579 0 395 0 572 579 0 393 0 0 0 0 0 0 0 0 0 1173 0 0 0 0 0 1139 +935 882 0.898423662683652 0.437869942161669 0.0332390746175172 -0.00701046822814826 -0.434073349478463 0.896984532558566 -0.0836604782632648 -0.137460895390692 -0.0664473445868263 0.0607343568503581 0.995939801541907 0.520218800746023 3.17481250475786e-05 1.13091365650548e-05 2.92274464865091e-06 1.5023906410683e-05 1.69235747780489e-05 2.99223803579566e-05 1.13091365650548e-05 0.000130562532704465 -1.4792557070781e-05 7.44628036487327e-05 5.19637596876818e-05 8.39799449590593e-05 2.92274464865091e-06 -1.4792557070781e-05 1.32387924997759e-05 -1.46857750242051e-05 -9.46573049422448e-07 -8.43644975119147e-06 1.5023906410683e-05 7.44628036487327e-05 -1.46857750242051e-05 0.000132111724510891 5.69170663304677e-05 9.43569574691953e-05 1.69235747780489e-05 5.19637596876818e-05 -9.46573049422448e-07 5.69170663304677e-05 6.78631710215986e-05 6.98813203566399e-05 2.99223803579566e-05 8.39799449590593e-05 -8.43644975119147e-06 9.43569574691953e-05 6.98813203566399e-05 0.000163188392263579 633 642 0 449 0 633 642 0 447 0 0 0 0 0 0 0 0 0 1131 0 0 0 0 0 1041 +935 874 0.904170637711029 0.42712093116678 0.0065702405172172 -0.00316962882465229 -0.425601289621589 0.902058126650755 -0.0717960891398036 -0.132802084459028 -0.0365923513001319 0.0621196128654424 0.997397690755185 0.519056351790341 4.22490769373294e-05 6.1988577969889e-06 2.87788038436151e-06 -3.91015997595257e-06 1.37186112455945e-06 2.71059539007761e-05 6.1988577969889e-06 6.42282880373716e-05 -2.93267882513497e-06 1.17627735853208e-05 9.59209831234892e-06 7.84322671282396e-06 2.87788038436151e-06 -2.93267882513497e-06 1.0648795577998e-05 -6.49618092181431e-06 4.41787689111967e-06 -8.84679672219873e-07 -3.91015997595257e-06 1.17627735853208e-05 -6.49618092181431e-06 7.19065822659087e-05 1.52047885238464e-05 5.81900468409808e-06 1.37186112455945e-06 9.59209831234892e-06 4.41787689111967e-06 1.52047885238464e-05 3.4990455277962e-05 9.3995853559091e-06 2.71059539007761e-05 7.84322671282396e-06 -8.84679672219873e-07 5.81900468409808e-06 9.3995853559091e-06 7.80631081881638e-05 630 637 0 385 0 630 637 0 383 0 0 0 0 0 0 0 0 0 1230 0 0 0 0 0 1142 +935 886 0.898048122455813 0.437536599980717 0.0455114648292431 -0.00617269349439752 -0.43334107539854 0.897711848369077 -0.0795546960915036 -0.140626221156109 -0.0756642724542198 0.0517219583454506 0.995791020696052 0.528171068606524 3.09975956629712e-05 -2.93230312220917e-06 7.6772846033215e-06 -1.58802247596018e-06 3.51059953622364e-07 1.55732808725763e-05 -2.93230312220917e-06 5.14915620136909e-05 -5.36526580831422e-06 1.34252232512416e-05 6.72905621738979e-06 2.55820141863815e-06 7.6772846033215e-06 -5.36526580831422e-06 1.24359290237173e-05 -9.20934228776527e-06 5.00694310836783e-06 -1.50268561711587e-06 -1.58802247596018e-06 1.34252232512416e-05 -9.20934228776527e-06 6.73069088575374e-05 1.11272578971212e-05 1.77617764465852e-05 3.51059953622364e-07 6.72905621738979e-06 5.00694310836783e-06 1.11272578971212e-05 3.59354486813985e-05 1.42217745006251e-05 1.55732808725763e-05 2.55820141863815e-06 -1.50268561711587e-06 1.77617764465852e-05 1.42217745006251e-05 7.1066891825364e-05 627 634 0 447 0 627 634 0 446 0 0 0 0 0 0 0 0 0 1237 0 0 0 0 0 1028 +935 879 0.898577023536266 0.438524073539277 0.0159990530727211 -0.00773507973711748 -0.435720575378825 0.895968364672227 -0.0859550446345085 -0.135033710127876 -0.0520280017322451 0.0702661115552411 0.996170547949826 0.514877748508606 3.87671455424436e-05 8.72915681715824e-07 6.30582694142073e-06 1.15259579975575e-05 1.26451339770904e-05 3.95480768013709e-05 8.72915681715824e-07 7.72774291824741e-05 -1.0898168423793e-05 3.8155910007543e-05 2.08307608925936e-05 3.40967614349337e-05 6.30582694142073e-06 -1.0898168423793e-05 1.44693322426532e-05 -8.73678642176167e-06 7.223943950094e-06 -1.38110428314572e-06 1.15259579975575e-05 3.8155910007543e-05 -8.73678642176167e-06 7.91584383924195e-05 2.1196615298966e-05 4.44691133192915e-05 1.26451339770904e-05 2.08307608925936e-05 7.223943950094e-06 2.1196615298966e-05 4.2759191942587e-05 3.44464613327765e-05 3.95480768013709e-05 3.40967614349337e-05 -1.38110428314572e-06 4.44691133192915e-05 3.44464613327765e-05 0.000110484082377045 568 574 0 401 0 568 574 0 399 0 0 0 0 0 0 0 0 0 1111 0 0 0 0 0 732 +935 885 0.898292685075801 0.437447146525695 0.041355119826157 -0.0100170764303666 -0.433365369648543 0.89756962815251 -0.0810136964194751 -0.140975089611649 -0.0725583098527645 0.0548521340942437 0.995854675671414 0.527103188550109 3.69252487750456e-05 1.92830789701236e-06 4.12760973269899e-06 1.18026321020706e-06 8.20070837307976e-06 2.76757719626071e-05 1.92830789701236e-06 9.60593407724517e-05 4.83185621398807e-08 2.7208212749834e-05 2.50786306633293e-05 4.96032174613833e-05 4.12760973269899e-06 4.83185621398807e-08 1.30083625524603e-05 -7.71234700273086e-06 6.23089484584848e-06 2.63583626543369e-06 1.18026321020706e-06 2.7208212749834e-05 -7.71234700273086e-06 7.72556534355093e-05 1.90456459819727e-05 3.07597113533855e-05 8.20070837307976e-06 2.50786306633293e-05 6.23089484584848e-06 1.90456459819727e-05 4.51282366976442e-05 3.50771996239149e-05 2.76757719626071e-05 4.96032174613833e-05 2.63583626543369e-06 3.07597113533855e-05 3.50771996239149e-05 0.000132135287359625 626 632 0 447 0 626 632 0 446 0 0 0 0 0 0 0 0 0 1158 0 0 0 0 0 532 +935 881 0.897936836143181 0.438836873698151 0.0336398064799308 0.00421147157807809 -0.434887798986259 0.896413121621778 -0.0855343070188058 -0.134219856322517 -0.0676907718234978 0.0621748636277852 0.995767164422891 0.52755732841871 2.96984837098691e-05 -3.84920244507084e-06 6.37689952892492e-06 5.50763529456701e-06 1.12799096629369e-05 2.58657503367863e-05 -3.84920244507084e-06 4.94953161595362e-05 -5.85291950317253e-06 1.93787241792586e-05 6.84121959970186e-06 4.53758366581118e-06 6.37689952892492e-06 -5.85291950317253e-06 1.29706383559591e-05 -3.08878892057107e-06 6.11737412203846e-06 -3.1411588369682e-07 5.50763529456701e-06 1.93787241792586e-05 -3.08878892057107e-06 6.30141565922529e-05 1.61339214368407e-05 2.48802128424279e-05 1.12799096629369e-05 6.84121959970186e-06 6.11737412203846e-06 1.61339214368407e-05 3.69468178376683e-05 1.783777982094e-05 2.58657503367863e-05 4.53758366581118e-06 -3.1411588369682e-07 2.48802128424279e-05 1.783777982094e-05 7.32431538834399e-05 620 631 0 433 0 620 631 0 430 0 0 0 0 0 0 0 0 0 1195 0 0 0 0 0 595 +935 889 0.894553544917757 0.431614977660132 0.116114022988264 -0.0217430475992007 -0.431457419377028 0.901704958216397 -0.0277968270218299 -0.14462516472013 -0.11669811712102 -0.0252325065621576 0.992846851268109 0.526335261730194 3.93603185764599e-05 2.06398103826672e-05 4.15339167740485e-06 1.05024959367521e-05 8.07676600061454e-06 5.66337244549656e-05 2.06398103826672e-05 0.000104026212549667 -8.3915828773612e-06 2.84133895741676e-05 1.7546077871953e-05 7.68415200779795e-05 4.15339167740485e-06 -8.3915828773612e-06 1.27974448906133e-05 -8.86043730279666e-06 5.83835524484085e-06 -5.5608863067284e-06 1.05024959367521e-05 2.84133895741676e-05 -8.86043730279666e-06 5.93543049441878e-05 6.30271205693423e-06 3.98839821683948e-05 8.07676600061454e-06 1.7546077871953e-05 5.83835524484085e-06 6.30271205693423e-06 2.65779688462147e-05 2.5709003805464e-05 5.66337244549656e-05 7.68415200779795e-05 -5.5608863067284e-06 3.98839821683948e-05 2.5709003805464e-05 0.000178384882659755 737 750 0 597 0 737 750 0 590 0 0 0 0 0 0 0 0 0 1500 0 0 0 0 0 1101 +935 880 0.899117334568734 0.436963117564128 0.0255196505981692 -0.0102541059100312 -0.433595809746325 0.897128639204452 -0.0845865148211998 -0.133763910049383 -0.0598555966342644 0.0649879881809395 0.996089287636279 0.523632400207743 3.50882119030223e-05 -1.39486394130161e-05 7.83873326669e-06 -8.96011025117684e-06 -1.76161719268649e-07 1.29254577785817e-05 -1.39486394130161e-05 8.3650881472819e-05 -9.50282909849815e-06 4.67625555097643e-05 3.02883958907112e-05 4.2448766736814e-05 7.83873326669e-06 -9.50282909849815e-06 1.10082032289945e-05 -8.38855062412994e-06 2.24200713321401e-06 -3.68906496974314e-06 -8.96011025117684e-06 4.67625555097643e-05 -8.38855062412994e-06 9.77817540461053e-05 3.824719626857e-05 6.57722172783645e-05 -1.76161719268649e-07 3.02883958907112e-05 2.24200713321401e-06 3.824719626857e-05 5.10850622792993e-05 4.68311949268835e-05 1.29254577785817e-05 4.2448766736814e-05 -3.68906496974314e-06 6.57722172783645e-05 4.68311949268835e-05 0.00012519320070613 593 602 0 397 0 593 602 0 395 0 0 0 0 0 0 0 0 0 1215 0 0 0 0 0 1105 +935 890 0.893295663629516 0.429567333933223 0.132267769914688 -0.0319715575454548 -0.431348314025653 0.902037102545709 -0.0163614674821192 -0.14782372446131 -0.126338787899557 -0.0424378516002413 0.991078977389606 0.525035765559495 4.25554174212927e-05 2.87194194782666e-06 6.02900669165261e-06 5.47511428031777e-06 -5.58416213543454e-06 3.15380552153837e-05 2.87194194782666e-06 6.79334669414814e-05 -3.14949735539821e-06 8.01738359037423e-06 6.1920239528433e-06 3.79101987055141e-05 6.02900669165261e-06 -3.14949735539821e-06 1.20266703316156e-05 -4.62067192482385e-06 7.40340041764336e-06 4.41725461473796e-06 5.47511428031777e-06 8.01738359037423e-06 -4.62067192482385e-06 3.65713541288925e-05 -4.98561771064324e-06 8.57555405780358e-06 -5.58416213543454e-06 6.1920239528433e-06 7.40340041764336e-06 -4.98561771064324e-06 2.47521102519268e-05 8.58677774484877e-06 3.15380552153837e-05 3.79101987055141e-05 4.41725461473796e-06 8.57555405780358e-06 8.58677774484877e-06 0.000104460968763683 729 743 0 638 0 729 743 0 637 0 0 0 0 0 0 0 0 0 1540 0 0 0 0 0 962 +936 938 0.99614074414404 -0.084374746736245 0.0241768477960158 0.0884419811064914 0.0839433052343672 0.996301774863105 0.0183383453713111 0.0956138367399903 -0.0256347296160318 -0.0162380884904024 0.999539486523514 -0.225868223631314 2.7890117250051e-05 -2.84351898463591e-06 1.09121407170996e-06 1.52545864428886e-05 -1.14624568771955e-06 1.43077355024501e-05 -2.84351898463591e-06 4.45110798951025e-05 6.01445846797513e-08 2.07347825852512e-05 -1.28552533513219e-06 -7.30908652365226e-06 1.09121407170996e-06 6.01445846797513e-08 8.98945719512938e-06 1.45043958151316e-06 4.82279803911126e-06 -3.48525181642819e-06 1.52545864428886e-05 2.07347825852512e-05 1.45043958151316e-06 7.99013641211137e-05 -3.06718075004478e-06 4.23742089652599e-05 -1.14624568771955e-06 -1.28552533513219e-06 4.82279803911126e-06 -3.06718075004478e-06 1.55036296293094e-05 -6.37350670535612e-06 1.43077355024501e-05 -7.30908652365226e-06 -3.48525181642819e-06 4.23742089652599e-05 -6.37350670535612e-06 0.000110735991616207 2568 2673 0 0 53 2557 2662 0 0 53 0 0 0 0 0 179 160 0 3411 0 0 0 0 0 571 +935 883 0.898076017454908 0.438130183861174 0.0387480175248445 -0.001895338554738 -0.433963067847885 0.89698405840936 -0.0842357091946479 -0.13901825621499 -0.0716625607718795 0.0588348616829141 0.995692189601972 0.528819332276165 4.53904126854391e-05 1.76004301857783e-05 -2.6545095886349e-07 1.98980626479951e-05 1.50808578741774e-05 2.6114031471198e-05 1.76004301857783e-05 0.000117877530903559 -7.07810731185296e-06 6.02197590801927e-05 2.83390905034889e-05 1.65223536943959e-05 -2.6545095886349e-07 -7.07810731185296e-06 1.23058431593259e-05 -1.31303442883454e-05 4.63036102956113e-06 -6.34023857665368e-06 1.98980626479951e-05 6.02197590801927e-05 -1.31303442883454e-05 0.000100750108126572 2.1041541337159e-05 4.64776399152258e-05 1.50808578741774e-05 2.83390905034889e-05 4.63036102956113e-06 2.1041541337159e-05 4.39577000628377e-05 2.91644860186091e-05 2.6114031471198e-05 1.65223536943959e-05 -6.34023857665368e-06 4.64776399152258e-05 2.91644860186091e-05 8.65374445720091e-05 642 653 0 438 0 642 653 0 437 0 0 0 0 0 0 0 0 0 1109 0 0 0 0 0 1041 +936 939 0.990944792979344 -0.134257469307381 -0.00183008259440432 0.152296857049129 0.134263596106968 0.990938425595516 0.00378463191137828 0.154351153834943 0.00130538406212717 -0.00399607475622126 0.999991163640456 -0.286746614209233 2.95472443517525e-05 -2.0712340051496e-06 1.39007904637559e-06 5.17158633562215e-06 -3.17376624646181e-07 5.94283858819398e-06 -2.0712340051496e-06 3.07603026934658e-05 -2.22310979033214e-07 2.79675810796197e-06 -2.48143826784354e-06 1.28080689570335e-05 1.39007904637559e-06 -2.22310979033214e-07 9.36961810003204e-06 2.39064474492662e-06 2.91972252853328e-06 5.75349366988319e-07 5.17158633562215e-06 2.79675810796197e-06 2.39064474492662e-06 6.63278157312177e-05 -4.47870888304749e-07 4.56032135629061e-05 -3.17376624646181e-07 -2.48143826784354e-06 2.91972252853328e-06 -4.47870888304749e-07 1.46066490657519e-05 -6.89406023695569e-06 5.94283858819398e-06 1.28080689570335e-05 5.75349366988319e-07 4.56032135629061e-05 -6.89406023695569e-06 0.000139637431563814 2334 2402 0 0 290 2326 2394 0 0 290 0 0 0 0 0 286 258 0 3295 0 0 0 0 0 280 +936 855 0.89522798620173 0.430554318125675 0.114846993275966 -0.235019556924014 -0.419032961411467 0.901071944246929 -0.111717181050163 -0.0481539155314443 -0.151585718232064 0.0518876713140409 0.987081273043753 0.337757079381744 2.75576684983412e-05 1.563103864204e-05 4.69947902944729e-06 -8.8708371020882e-06 3.95418097340445e-07 2.45322599965453e-05 1.563103864204e-05 5.80701109907807e-05 -6.32949632193019e-07 -1.56157079081948e-05 -3.93646899760448e-07 2.60280666104991e-05 4.69947902944729e-06 -6.32949632193019e-07 1.07890475907326e-05 -4.62597239960913e-06 6.08909194127333e-06 -3.1463830258419e-06 -8.8708371020882e-06 -1.56157079081948e-05 -4.62597239960913e-06 5.5223267533516e-05 8.97294248686376e-06 -2.09735238853246e-05 3.95418097340445e-07 -3.93646899760448e-07 6.08909194127333e-06 8.97294248686376e-06 2.12823268453919e-05 -3.98151169390618e-06 2.45322599965453e-05 2.60280666104991e-05 -3.1463830258419e-06 -2.09735238853246e-05 -3.98151169390618e-06 9.86116847907833e-05 1602 1621 0 734 0 1602 1621 0 729 0 0 0 0 0 0 0 0 0 2090 0 0 0 0 0 1129 +936 933 0.982886507559708 0.170499262943418 0.0697432046355092 -0.0585667693161747 -0.170619582737242 0.98532771477735 -0.00427229191597008 -0.112886881508077 -0.0694483350675074 -0.00770037839310523 0.997555829479711 0.354099855585927 3.38996541670166e-05 2.53178549099354e-07 1.53566902282099e-06 8.66017611305292e-06 4.94256427458513e-07 7.61773689071767e-06 2.53178549099354e-07 6.76786670809603e-05 -2.31591243638056e-07 1.85074013469098e-05 6.75507385864754e-06 1.0139368305002e-05 1.53566902282099e-06 -2.31591243638056e-07 1.10296054591268e-05 -2.07529789514614e-06 7.12322010476932e-06 -1.5388298642423e-06 8.66017611305292e-06 1.85074013469098e-05 -2.07529789514614e-06 6.82368072676546e-05 5.60326608306061e-06 2.5315684912909e-05 4.94256427458513e-07 6.75507385864754e-06 7.12322010476932e-06 5.60326608306061e-06 1.70373927170812e-05 5.09281238425564e-06 7.61773689071767e-06 1.0139368305002e-05 -1.5388298642423e-06 2.5315684912909e-05 5.09281238425564e-06 8.78659707946106e-05 1774 1779 0 374 0 1774 1779 0 367 0 0 0 0 0 0 0 0 0 2719 0 0 0 0 0 725 +936 857 0.8873759649553 0.452699254499971 0.0873343105246782 -0.165807309035938 -0.447354873362559 0.891255529684949 -0.074412351694926 -0.12545868648009 -0.111523603324225 0.0269623029649043 0.993395953344088 0.451867783146964 4.22601045820303e-05 2.98762839081578e-06 2.92057811858061e-06 -2.78763357143986e-06 2.25858207256149e-06 1.4557877788243e-05 2.98762839081578e-06 3.73851976575018e-05 -4.38366415984723e-07 3.86319793774569e-06 2.6699296770926e-06 -4.2427124373504e-07 2.92057811858061e-06 -4.38366415984723e-07 1.10960791093839e-05 -5.81884947591178e-06 6.48955322029648e-06 -7.07827350391622e-07 -2.78763357143986e-06 3.86319793774569e-06 -5.81884947591178e-06 4.85663909646472e-05 6.24436292855933e-06 -4.80278055096589e-06 2.25858207256149e-06 2.6699296770926e-06 6.48955322029648e-06 6.24436292855933e-06 2.66733423670262e-05 8.05907139510118e-06 1.4557877788243e-05 -4.2427124373504e-07 -7.07827350391622e-07 -4.80278055096589e-06 8.05907139510118e-06 8.43896876104818e-05 1262 1273 0 706 0 1262 1273 0 701 0 0 0 0 0 0 0 0 0 1664 0 0 0 0 0 792 +936 932 0.957369962595951 0.257175640941733 0.131542557468053 -0.057015214232065 -0.25937370430786 0.965776935450828 -0.000438708132418342 -0.144894920486306 -0.127153593078001 -0.0336986744162945 0.991310427217397 0.469702527092393 3.13308563991692e-05 2.39116842158148e-06 3.31933512185958e-06 2.3023543207486e-06 -5.55308193098331e-07 4.83197513997922e-06 2.39116842158148e-06 2.98606181164971e-05 9.06399222585686e-07 -9.22412158558127e-07 1.09119297763005e-06 -9.1724262309024e-06 3.31933512185958e-06 9.06399222585686e-07 1.05422476707098e-05 -4.62399400382947e-06 6.35764025729533e-06 -1.35336301834796e-06 2.3023543207486e-06 -9.22412158558127e-07 -4.62399400382947e-06 7.68294142483383e-05 1.08361218888413e-05 -2.4535760712701e-06 -5.55308193098331e-07 1.09119297763005e-06 6.35764025729533e-06 1.08361218888413e-05 1.97788914225757e-05 -1.65428812680156e-06 4.83197513997922e-06 -9.1724262309024e-06 -1.35336301834796e-06 -2.4535760712701e-06 -1.65428812680156e-06 4.46644843441461e-05 1434 1447 0 540 0 1434 1447 0 535 0 0 0 0 0 0 0 0 0 2397 0 0 0 0 0 804 +936 940 0.990215138972026 -0.138984006247368 0.0125468943584873 0.244073996686936 0.139492726456463 0.988363142534376 -0.0606636443458077 0.214722837791956 -0.00396961161245551 0.0618202595190601 0.998079404504793 -0.287936267315278 6.71566552163285e-05 1.70533924206958e-05 -8.19343649806275e-07 1.4276862159665e-06 2.62155839196779e-06 3.61694313532248e-05 1.70533924206958e-05 7.19580544026579e-05 2.98401080944464e-07 2.3964501902618e-05 6.03343504968186e-07 6.72589399088239e-05 -8.19343649806275e-07 2.98401080944464e-07 1.22776917458425e-05 1.33278176452804e-06 3.45474075416187e-06 -5.90156625715702e-06 1.4276862159665e-06 2.3964501902618e-05 1.33278176452804e-06 0.000141688299119305 -3.10153746517294e-06 0.000127707882966746 2.62155839196779e-06 6.03343504968186e-07 3.45474075416187e-06 -3.10153746517294e-06 1.50625019884782e-05 3.8901237919452e-06 3.61694313532248e-05 6.72589399088239e-05 -5.90156625715702e-06 0.000127707882966746 3.8901237919452e-06 0.00031682837318231 2258 2318 0 0 449 2242 2302 0 0 449 0 0 0 0 0 299 266 0 3859 0 0 0 0 0 146 +936 859 0.883836792918115 0.453003365320457 0.116706788545319 -0.0862476151976335 -0.447815433666895 0.891466953710892 -0.0689057893877727 -0.156435970536299 -0.1352547997446 0.00863837078168752 0.99077319185386 0.565968800062174 5.29120176691842e-05 1.12529122166825e-05 -1.2986416535709e-06 -9.97199925625168e-07 -3.75724294577629e-07 2.09302560887527e-05 1.12529122166825e-05 0.000212235234943391 -8.52078937110836e-06 7.02088285649147e-05 5.19847031355717e-05 0.000263237558694017 -1.2986416535709e-06 -8.52078937110836e-06 1.30891637184366e-05 -8.54941822169709e-06 2.8131984697233e-06 -2.20278992569212e-05 -9.97199925625168e-07 7.02088285649147e-05 -8.54941822169709e-06 8.66356205649693e-05 3.27339816127002e-05 0.000134869010356171 -3.75724294577629e-07 5.19847031355717e-05 2.8131984697233e-06 3.27339816127002e-05 4.73523042985611e-05 0.000106593313451839 2.09302560887527e-05 0.000263237558694017 -2.20278992569212e-05 0.000134869010356171 0.000106593313451839 0.000562087763437221 921 928 0 674 0 921 928 0 668 0 0 0 0 0 0 0 0 0 1504 0 0 0 0 0 584 +936 858 0.884221411972446 0.462521795978208 0.0650083291167138 -0.136783861818413 -0.459106118131055 0.886278284972472 -0.0610931573982435 -0.143653611527974 -0.0858723873203021 0.0241741562695692 0.996012822841436 0.501446260511723 3.72043859486955e-05 -2.28673485941589e-06 2.58374321666738e-06 7.41467668606741e-06 4.68982388021556e-06 2.19612777052727e-05 -2.28673485941589e-06 6.65137388501273e-05 -6.04524624603564e-06 1.12500652473432e-05 1.03184972257962e-05 5.03421860748736e-05 2.58374321666738e-06 -6.04524624603564e-06 1.27566629675434e-05 -4.54627324228018e-06 5.64745022920248e-06 -1.34143911331603e-06 7.41467668606741e-06 1.12500652473432e-05 -4.54627324228018e-06 5.47065920215345e-05 9.20787164837396e-06 2.45192876953778e-05 4.68982388021556e-06 1.03184972257962e-05 5.64745022920248e-06 9.20787164837396e-06 3.15624347027472e-05 2.57168045357675e-05 2.19612777052727e-05 5.03421860748736e-05 -1.34143911331603e-06 2.45192876953778e-05 2.57168045357675e-05 0.000156942880837229 962 977 0 660 0 962 977 0 656 0 0 0 0 0 0 0 0 0 1585 0 0 0 0 0 757 +936 862 0.897635633012365 0.438498309826764 0.0443790786921199 -0.0630683876010301 -0.436201036305536 0.898290697559103 -0.0529384416540255 -0.15852885583866 -0.0630787307455276 0.0281612314690117 0.997611156097245 0.617291846188923 4.27994639761086e-05 2.95552004568456e-05 -2.59967889581617e-07 1.70209425204398e-05 4.04718784312823e-06 3.93938670754257e-05 2.95552004568456e-05 0.000130177714001702 -1.73744898822014e-06 4.6807568323776e-05 2.75560169286725e-05 0.000116149660835682 -2.59967889581617e-07 -1.73744898822014e-06 1.12246821343869e-05 -8.72832601373795e-06 6.13181809311903e-06 -7.94106922170359e-06 1.70209425204398e-05 4.6807568323776e-05 -8.72832601373795e-06 6.97285376784545e-05 1.40586692946187e-05 8.13977105214464e-05 4.04718784312823e-06 2.75560169286725e-05 6.13181809311903e-06 1.40586692946187e-05 3.36038367545896e-05 5.03333989241272e-05 3.93938670754257e-05 0.000116149660835682 -7.94106922170359e-06 8.13977105214464e-05 5.03333989241272e-05 0.000260317686906586 713 719 0 528 0 713 719 0 522 0 0 0 0 0 0 0 0 0 1261 0 0 0 0 0 1044 +936 860 0.892971953842943 0.439607555078595 0.0966761975241921 -0.0949283422390483 -0.431108330154268 0.89706062212531 -0.0970971055374457 -0.158705475933711 -0.129409031066286 0.0450270779639487 0.990568455447938 0.568153540066008 3.90662937406271e-05 1.64038257698804e-05 -5.79925769652705e-07 6.97625099272125e-06 3.93468917811576e-07 2.62891312696415e-05 1.64038257698804e-05 8.69049936386826e-05 -5.19470458220262e-06 1.27858421721289e-05 1.38844179356526e-05 5.54667926756027e-05 -5.79925769652705e-07 -5.19470458220262e-06 1.19345949458106e-05 -9.30104082811665e-06 6.42986761341593e-06 -1.02063597139107e-05 6.97625099272125e-06 1.27858421721289e-05 -9.30104082811665e-06 5.27060941081686e-05 1.23253740295043e-06 3.13687553533253e-05 3.93468917811576e-07 1.38844179356526e-05 6.42986761341593e-06 1.23253740295043e-06 2.71679399596901e-05 2.43122670293092e-05 2.62891312696415e-05 5.54667926756027e-05 -1.02063597139107e-05 3.13687553533253e-05 2.43122670293092e-05 0.000157180239863725 921 937 0 594 0 921 937 0 590 0 0 0 0 0 0 0 0 0 1265 0 0 0 0 0 1121 +936 865 0.89412707077218 0.447387983463161 0.0195134201288941 -0.0387526123601927 -0.445482966259929 0.893068940859029 -0.0630301011040511 -0.173550928847287 -0.0456257392774694 0.0476640233897436 0.997820842030114 0.644191444292983 5.20615081402358e-05 -1.52324761571694e-05 1.58461481896599e-06 -7.11356152715e-06 -1.09870610846385e-05 -1.66673234836662e-05 -1.52324761571694e-05 7.58722398580035e-05 -4.2559159033561e-06 3.00553601466916e-05 2.54080897397226e-05 4.22249986432339e-05 1.58461481896599e-06 -4.2559159033561e-06 1.20126302754607e-05 -1.04090797075249e-05 5.00838020534952e-06 -8.21555079560096e-06 -7.11356152715e-06 3.00553601466916e-05 -1.04090797075249e-05 9.57815421359978e-05 2.62895201907327e-05 8.37707472822421e-05 -1.09870610846385e-05 2.54080897397226e-05 5.00838020534952e-06 2.62895201907327e-05 4.96389381983117e-05 5.7602985429409e-05 -1.66673234836662e-05 4.22249986432339e-05 -8.21555079560096e-06 8.37707472822421e-05 5.7602985429409e-05 0.000170655448752035 593 602 0 456 0 593 602 0 451 0 0 0 0 0 0 0 0 0 1129 0 0 0 0 0 744 +936 856 0.886737660829641 0.44061223458423 0.139846986385361 -0.184825567487796 -0.426517326793378 0.896476223839465 -0.120055612261839 -0.0870476132940826 -0.178267469863144 0.04681066999334 0.982867982164119 0.420946812041607 3.59903611707072e-05 4.74484218584089e-06 7.57996661749903e-06 -3.17727951731193e-06 2.75090985387377e-06 1.06546968417178e-05 4.74484218584089e-06 5.83272477747396e-05 -4.0231370759275e-06 2.13905717668432e-05 1.25194142355773e-05 2.55384528392357e-05 7.57996661749903e-06 -4.0231370759275e-06 1.14750591905683e-05 -4.94711479897753e-06 6.05304381017341e-06 -2.29353464138654e-06 -3.17727951731193e-06 2.13905717668432e-05 -4.94711479897753e-06 6.12642513173457e-05 1.43287428388003e-05 1.53744042530301e-05 2.75090985387377e-06 1.25194142355773e-05 6.05304381017341e-06 1.43287428388003e-05 2.94249921250347e-05 1.66141307706611e-05 1.06546968417178e-05 2.55384528392357e-05 -2.29353464138654e-06 1.53744042530301e-05 1.66141307706611e-05 0.000146718672072853 1445 1462 0 717 0 1445 1462 0 711 0 0 0 0 0 0 0 0 0 1913 0 0 0 0 0 846 +936 867 0.884874699366351 0.463994339737744 0.0413039842224245 -0.0344270641217108 -0.459158782359711 0.883719909884516 -0.0906219259100723 -0.178197537524243 -0.0785492138933191 0.0612239623435017 0.9950284656389 0.647056524803169 5.17100112171002e-05 2.96262719138517e-05 -1.53053876458e-06 2.6677179781461e-05 1.30518763453868e-05 6.29964659115039e-05 2.96262719138517e-05 0.000127830800466969 -8.10150967603539e-06 4.27963743460869e-05 2.15015541220061e-05 7.28620907464189e-05 -1.53053876458e-06 -8.10150967603539e-06 1.28743797279956e-05 -8.61625827857847e-06 6.58359414111951e-06 -8.23782580843027e-06 2.6677179781461e-05 4.27963743460869e-05 -8.61625827857847e-06 7.53603455757014e-05 1.51543369007859e-05 6.78235841084262e-05 1.30518763453868e-05 2.15015541220061e-05 6.58359414111951e-06 1.51543369007859e-05 4.12246649025246e-05 4.57387540792472e-05 6.29964659115039e-05 7.28620907464189e-05 -8.23782580843027e-06 6.78235841084262e-05 4.57387540792472e-05 0.000225289853643344 543 552 0 461 0 543 552 0 457 0 0 0 0 0 0 0 0 0 1019 0 0 0 0 0 532 +936 866 0.89246821211764 0.450006625728444 0.0315361246833347 -0.0468700297951571 -0.446935024874417 0.891533992420739 -0.0735949991428887 -0.174802092445788 -0.0612337643791906 0.0515865986360643 0.996789470721433 0.636983023452685 6.16095917768558e-05 7.14849197580283e-06 6.32383069092521e-07 -4.23922825700659e-06 1.20868019028054e-06 1.55050494815034e-05 7.14849197580283e-06 0.000106419296200168 -1.07726988681074e-05 3.19203663800914e-05 2.65427795317686e-05 4.28243128477284e-05 6.32383069092521e-07 -1.07726988681074e-05 1.39508634015203e-05 -7.63106802977136e-06 6.79662230547463e-06 -2.82267672018031e-06 -4.23922825700659e-06 3.19203663800914e-05 -7.63106802977136e-06 7.18451035826463e-05 1.38790457163643e-05 6.8016354190733e-05 1.20868019028054e-06 2.65427795317686e-05 6.79662230547463e-06 1.38790457163643e-05 5.11280717615691e-05 5.87411007918331e-05 1.55050494815034e-05 4.28243128477284e-05 -2.82267672018031e-06 6.8016354190733e-05 5.87411007918331e-05 0.000219176943524273 553 562 0 452 0 553 562 0 448 0 0 0 0 0 0 0 0 0 1165 0 0 0 0 0 397 +936 868 0.875695579338054 0.479491817311946 0.0569635801076245 -0.022296799134496 -0.473821526107549 0.876020053184923 -0.0899000990822485 -0.178371333328481 -0.0930076003609561 0.0517345488892338 0.994320432620352 0.657402813084282 3.53807246475535e-05 2.65157605662562e-07 3.61137888008939e-06 2.52171489442395e-06 -3.78199126056956e-06 2.38986620605942e-06 2.65157605662562e-07 0.000142044165633151 -1.20948097987024e-05 7.86374594162292e-05 6.10022037008192e-05 0.000164172485783179 3.61137888008939e-06 -1.20948097987024e-05 1.3602448601394e-05 -1.68982494228095e-05 6.96901894514705e-07 -2.08473044116371e-05 2.52171489442395e-06 7.86374594162292e-05 -1.68982494228095e-05 0.0001432598646004 6.57765403725872e-05 0.000184699107470936 -3.78199126056956e-06 6.10022037008192e-05 6.96901894514705e-07 6.57765403725872e-05 7.86220737794301e-05 0.000146039137400469 2.38986620605942e-06 0.000164172485783179 -2.08473044116371e-05 0.000184699107470936 0.000146039137400469 0.000467771253579247 549 561 0 497 0 549 561 0 492 0 0 0 0 0 0 0 0 0 1018 0 0 0 0 0 859 +936 869 0.870682610288555 0.488321534848152 0.0587696413520838 -0.041319103217595 -0.482623733213866 0.871266712238899 -0.0892672856265435 -0.184654700808267 -0.0947951701291714 0.0493598495537102 0.994272337426832 0.642745040051774 3.88049906324822e-05 -6.70541881542605e-07 1.70154322486152e-06 2.52946191878505e-06 -9.79377180461158e-07 2.50003564398808e-05 -6.70541881542605e-07 6.61275186548879e-05 1.3389047915384e-06 -2.9371181493625e-06 8.44564276982659e-06 2.31348047241154e-05 1.70154322486152e-06 1.3389047915384e-06 1.21099852518501e-05 -8.59212248232584e-06 8.68505263894152e-06 -3.96939881002872e-06 2.52946191878505e-06 -2.9371181493625e-06 -8.59212248232584e-06 4.53842873432651e-05 -8.39275167255922e-06 1.73962073135031e-05 -9.79377180461158e-07 8.44564276982659e-06 8.68505263894152e-06 -8.39275167255922e-06 3.02592665199198e-05 1.93114399710536e-05 2.50003564398808e-05 2.31348047241154e-05 -3.96939881002872e-06 1.73962073135031e-05 1.93114399710536e-05 0.000149891412800751 651 663 0 506 0 651 663 0 503 0 0 0 0 0 0 0 0 0 986 0 0 0 0 0 831 +936 871 0.873708370438314 0.485588747165228 0.0289353080600597 -0.0414577221148315 -0.482729242230716 0.872833210040956 -0.0716565847983168 -0.187414819847163 -0.0600513290559394 0.0486390386017672 0.99700956956416 0.651009230499305 4.65782844822673e-05 2.35845039725937e-06 2.3194711180686e-06 1.23069484946947e-06 4.89463358848066e-06 2.27404707968351e-05 2.35845039725937e-06 8.3539966469422e-05 -6.13368067957228e-06 2.33883147928869e-05 1.17007776441335e-05 1.03196077387345e-05 2.3194711180686e-06 -6.13368067957228e-06 1.30618650608672e-05 -8.54434092337068e-06 7.83229264452026e-06 -4.2858308532733e-07 1.23069484946947e-06 2.33883147928869e-05 -8.54434092337068e-06 6.62195173327263e-05 1.04474719987944e-05 2.31392477788609e-05 4.89463358848066e-06 1.17007776441335e-05 7.83229264452026e-06 1.04474719987944e-05 3.62270600384986e-05 3.15950527970313e-05 2.27404707968351e-05 1.03196077387345e-05 -4.2858308532733e-07 2.31392477788609e-05 3.15950527970313e-05 0.00013378073676177 556 562 0 475 0 556 562 0 472 0 0 0 0 0 0 0 0 0 1077 0 0 0 0 0 785 +936 863 0.898913957133442 0.436751263258607 0.0346703289962262 -0.0626511082779826 -0.434994358036022 0.899134910155769 -0.0483355129900006 -0.162406549770514 -0.0522838995057283 0.0283680697473053 0.998229255467544 0.628649852888507 5.17782447410819e-05 4.75108038328385e-06 3.40009648015868e-07 -6.63981522649787e-07 3.14391513612015e-06 2.6198387169932e-05 4.75108038328385e-06 7.20553991634681e-05 -2.18050006834827e-06 3.50262527740773e-06 -6.19798996147104e-08 -5.21011365372356e-06 3.40009648015868e-07 -2.18050006834827e-06 1.1450146576791e-05 -5.60140870952291e-06 7.01234041810948e-06 -7.68364189226352e-07 -6.63981522649787e-07 3.50262527740773e-06 -5.60140870952291e-06 5.57920744318813e-05 3.92688257841381e-07 4.57041739215161e-06 3.14391513612015e-06 -6.19798996147104e-08 7.01234041810948e-06 3.92688257841381e-07 2.35844904332408e-05 6.98484462350478e-06 2.6198387169932e-05 -5.21011365372356e-06 -7.68364189226352e-07 4.57041739215161e-06 6.98484462350478e-06 8.55733658822837e-05 640 645 0 519 0 640 645 0 516 0 0 0 0 0 0 0 0 0 1278 0 0 0 0 0 862 +936 872 0.879038533211247 0.476640149757866 0.0102676564325844 -0.0453845686901914 -0.474718609359793 0.877075042969701 -0.0733594637875812 -0.181650955358984 -0.0439715710126765 0.0596115478619384 0.997252708346375 0.634873586716319 4.17320451905638e-05 7.85515927591788e-06 1.18989690262914e-07 8.92723479669325e-06 5.09369013622125e-06 2.06052613362638e-05 7.85515927591788e-06 8.0893982506378e-05 -5.39371612985895e-06 2.29478165442852e-05 1.73731590778523e-05 3.06624325861978e-05 1.18989690262914e-07 -5.39371612985895e-06 1.27260533662705e-05 -1.18967920419183e-05 7.00838836339058e-06 -7.14477458293672e-06 8.92723479669325e-06 2.29478165442852e-05 -1.18967920419183e-05 7.8489940821366e-05 8.587167845033e-06 6.33143174045658e-05 5.09369013622125e-06 1.73731590778523e-05 7.00838836339058e-06 8.587167845033e-06 4.27984528112512e-05 5.79151969366589e-05 2.06052613362638e-05 3.06624325861978e-05 -7.14477458293672e-06 6.33143174045658e-05 5.79151969366589e-05 0.00022675602673399 563 567 0 447 0 563 567 0 445 0 0 0 0 0 0 0 0 0 1085 0 0 0 0 0 955 +936 864 0.9033123422223 0.428722541977171 0.0149597590052801 -0.0619382838473624 -0.427534976756006 0.902578002266716 -0.0506635319975297 -0.166739771122113 -0.0352229476209 0.0393691735353451 0.998603731284857 0.625278306716902 5.1159457267349e-05 -1.03694592506836e-05 2.88781470951116e-06 -7.60541553204352e-06 -2.24741640479659e-06 1.34222214269893e-05 -1.03694592506836e-05 7.6345713771848e-05 -3.17459367681285e-06 3.84164953487462e-05 1.66864956424914e-05 2.05239476878639e-05 2.88781470951116e-06 -3.17459367681285e-06 1.18095819988752e-05 -7.51459518262947e-06 6.77594810477925e-06 -2.88513280603761e-06 -7.60541553204352e-06 3.84164953487462e-05 -7.51459518262947e-06 0.000104297912647089 1.91929574398912e-05 7.58199707022192e-05 -2.24741640479659e-06 1.66864956424914e-05 6.77594810477925e-06 1.91929574398912e-05 3.54044524687121e-05 3.64663392383462e-05 1.34222214269893e-05 2.05239476878639e-05 -2.88513280603761e-06 7.58199707022192e-05 3.64663392383462e-05 0.00017942733171452 616 624 0 456 0 616 624 0 451 0 0 0 0 0 0 0 0 0 1299 0 0 0 0 0 1006 +936 861 0.896603775196505 0.437487144844885 0.0686051630625938 -0.0706501520602412 -0.431264249571424 0.897818162432699 -0.0890712874475722 -0.155045958340727 -0.10056250466735 0.0502746984221916 0.993659719095822 0.606528358606118 4.30307422626303e-05 1.89930425047009e-05 1.22729820098818e-06 6.96892010017777e-06 -2.69338046574994e-06 2.30161560626275e-05 1.89930425047009e-05 0.000149020148475549 -4.20832587284771e-06 3.33914678712726e-05 4.11103802867637e-05 0.00015831485973937 1.22729820098818e-06 -4.20832587284771e-06 1.17407874747232e-05 -1.07852511449935e-05 3.62255674396823e-06 -1.63428027521926e-05 6.96892010017777e-06 3.33914678712726e-05 -1.07852511449935e-05 8.38253731112508e-05 2.30051554335665e-05 0.000102956405841702 -2.69338046574994e-06 4.11103802867637e-05 3.62255674396823e-06 2.30051554335665e-05 4.759979201873e-05 8.85837084081426e-05 2.30161560626275e-05 0.00015831485973937 -1.63428027521926e-05 0.000102956405841702 8.85837084081426e-05 0.000391126578964118 837 848 0 540 0 837 848 0 538 0 0 0 0 0 0 0 0 0 1200 0 0 0 0 0 955 +936 873 0.884141307832072 0.466808251833053 0.0196011174569856 -0.026408029478387 -0.463664113887092 0.881806409685335 -0.0862151108052176 -0.172311552474255 -0.0575303161671417 0.067138006065322 0.996083706755251 0.658723748839025 3.92476852294124e-05 -3.35423294420107e-07 3.57202086951546e-06 5.92320388318028e-06 3.47904570296704e-06 2.28481729213918e-05 -3.35423294420107e-07 6.57826372333984e-05 -4.85426657550125e-06 3.00427271184796e-05 1.79541920130234e-05 2.9692596853533e-05 3.57202086951546e-06 -4.85426657550125e-06 1.16546723866451e-05 -4.79172397726203e-06 7.70253302799755e-06 -7.69013916217043e-07 5.92320388318028e-06 3.00427271184796e-05 -4.79172397726203e-06 6.91314784545232e-05 1.50357967568858e-05 4.92214303855615e-05 3.47904570296704e-06 1.79541920130234e-05 7.70253302799755e-06 1.50357967568858e-05 4.11683640869158e-05 3.8196215229821e-05 2.28481729213918e-05 2.9692596853533e-05 -7.69013916217043e-07 4.92214303855615e-05 3.8196215229821e-05 0.000152388176050394 499 509 0 445 0 499 509 0 442 0 0 0 0 0 0 0 0 0 977 0 0 0 0 0 532 +936 874 0.883054064297707 0.469236029378227 -0.00575050090488138 -0.0411676687258684 -0.468436680397896 0.880686884553584 -0.070410850251231 -0.174086704552658 -0.02797491707049 0.0648703330395145 0.997501500703754 0.636751391736603 4.5196495683035e-05 1.27349737531491e-05 -2.36572798408217e-06 2.83563102905813e-06 6.36860398369561e-06 4.44612623206676e-05 1.27349737531491e-05 0.000122169094943192 -5.14856795436795e-06 4.18774982290125e-05 3.14493974240885e-05 9.14893965798065e-05 -2.36572798408217e-06 -5.14856795436795e-06 1.19286678753304e-05 -9.30134960768559e-06 3.95571176491214e-06 -1.2527025983242e-05 2.83563102905813e-06 4.18774982290125e-05 -9.30134960768559e-06 9.25001557069771e-05 2.21623847544109e-05 7.76245344240563e-05 6.36860398369561e-06 3.14493974240885e-05 3.95571176491214e-06 2.21623847544109e-05 4.33316830636931e-05 5.47781417431385e-05 4.44612623206676e-05 9.14893965798065e-05 -1.2527025983242e-05 7.76245344240563e-05 5.47781417431385e-05 0.000270445148570421 501 511 0 448 0 501 511 0 445 0 0 0 0 0 0 0 0 0 1004 0 0 0 0 0 901 +936 875 0.878924527016567 0.476960870564981 6.13074179200744e-05 -0.0336920379004458 -0.47570955850683 0.876627949127567 -0.0722762392050957 -0.177159470693812 -0.0345266817684628 0.063496194833163 0.997384650717951 0.636736214183984 4.49358663800472e-05 2.67695436604399e-05 -7.55343690268532e-07 5.52870489250486e-06 1.38869019881744e-05 4.13747732582294e-05 2.67695436604399e-05 0.000105317822541715 -4.33138206954875e-06 2.65675041174654e-05 2.48958524724658e-05 3.4353134675385e-05 -7.55343690268532e-07 -4.33138206954875e-06 1.10961703501031e-05 -6.89097445445449e-06 5.1103740444714e-06 -5.3350672656073e-06 5.52870489250486e-06 2.65675041174654e-05 -6.89097445445449e-06 6.18677294514515e-05 7.04560417313195e-06 2.94466880734094e-05 1.38869019881744e-05 2.48958524724658e-05 5.1103740444714e-06 7.04560417313195e-06 3.79145807361469e-05 3.59127357637535e-05 4.13747732582294e-05 3.4353134675385e-05 -5.3350672656073e-06 2.94466880734094e-05 3.59127357637535e-05 0.000158711278301613 520 524 0 431 0 520 524 0 427 0 0 0 0 0 0 0 0 0 1029 0 0 0 0 0 1045 +936 870 0.871823062062587 0.487672049273685 0.0458314391331845 -0.0464715865159559 -0.482799564455776 0.871341898564025 -0.0875664111869035 -0.18804894952415 -0.0826385443792899 0.0542150178829149 0.995103815096107 0.647113610876438 4.67835726385968e-05 1.35110297017695e-05 1.20892476499136e-08 1.20339211049358e-05 5.3596826627583e-06 3.65558737553955e-05 1.35110297017695e-05 7.59256458520625e-05 -6.33298906161566e-06 2.25394535697934e-05 7.62624543547882e-06 2.45529510885878e-05 1.20892476499136e-08 -6.33298906161566e-06 1.2782789556396e-05 -8.84385754074715e-06 6.84014547245461e-06 -4.56532665591822e-06 1.20339211049358e-05 2.25394535697934e-05 -8.84385754074715e-06 5.76049050203748e-05 6.57711262204912e-06 3.02384454627932e-05 5.3596826627583e-06 7.62624543547882e-06 6.84014547245461e-06 6.57711262204912e-06 3.49225180086584e-05 2.82622440489962e-05 3.65558737553955e-05 2.45529510885878e-05 -4.56532665591822e-06 3.02384454627932e-05 2.82622440489962e-05 0.000151417387347531 559 569 0 503 0 559 569 0 498 0 0 0 0 0 0 0 0 0 1001 0 0 0 0 0 484 +936 887 0.875698583623601 0.479129637922395 0.0598897378853362 -0.0322897342941041 -0.475651399056942 0.877316795380705 -0.0638042876153673 -0.178313576707719 -0.0831127981408009 0.0273866866795762 0.996163757711513 0.657749582983161 4.51068374577566e-05 1.82235165183162e-05 6.98176727953625e-07 1.32698482164126e-05 5.56606226078659e-06 4.64917075288888e-05 1.82235165183162e-05 0.00011897864774201 -5.02866642837114e-06 3.90012108520524e-05 2.41029454318771e-05 6.33817476477472e-05 6.98176727953625e-07 -5.02866642837114e-06 1.20049102855904e-05 -8.87836986234688e-06 5.32704932207204e-06 -8.00768327682092e-06 1.32698482164126e-05 3.90012108520524e-05 -8.87836986234688e-06 6.12881864334156e-05 8.24050808995616e-06 4.92779271547567e-05 5.56606226078659e-06 2.41029454318771e-05 5.32704932207204e-06 8.24050808995616e-06 3.26157251652517e-05 3.20940312112272e-05 4.64917075288888e-05 6.33817476477472e-05 -8.00768327682092e-06 4.92779271547567e-05 3.20940312112272e-05 0.000196894736103923 566 577 0 518 0 566 577 0 511 0 0 0 0 0 0 0 0 0 1119 0 0 0 0 0 1029 +936 877 0.879731254729658 0.475386291949305 0.00898848588310272 -0.0219126154998684 -0.472879291672382 0.876750392081103 -0.0877150243291241 -0.180403805971765 -0.0495791786862912 0.072915179574094 0.996105055517976 0.661544737560223 5.35784876079162e-05 2.94736082403737e-05 -2.10345201837635e-06 1.86279273964016e-05 7.97195431787182e-06 3.59620152506622e-05 2.94736082403737e-05 0.000109460716772103 -2.78169837748735e-06 2.21615245685212e-05 2.31333718927768e-05 2.3326371408077e-05 -2.10345201837635e-06 -2.78169837748735e-06 1.23772931217214e-05 -8.87684108097521e-06 7.20998897207806e-06 -5.83800182972727e-06 1.86279273964016e-05 2.21615245685212e-05 -8.87684108097521e-06 7.37675446324582e-05 8.81131699365931e-06 5.41308604048954e-05 7.97195431787182e-06 2.31333718927768e-05 7.20998897207806e-06 8.81131699365931e-06 4.47646896129927e-05 3.90226852432715e-05 3.59620152506622e-05 2.3326371408077e-05 -5.83800182972727e-06 5.41308604048954e-05 3.90226852432715e-05 0.00014234923494648 488 494 0 431 0 488 494 0 428 0 0 0 0 0 0 0 0 0 898 0 0 0 0 0 588 +936 885 0.875837778738031 0.480595686649767 0.0439996739632417 -0.022360891331877 -0.476255962526886 0.875455385091605 -0.0822078273140662 -0.182835015173334 -0.0780284787293839 0.0510456137953985 0.995643461194533 0.667252517770127 5.33824326611388e-05 2.29663684957444e-05 4.04945912322812e-06 5.46550955021187e-06 9.72373113044762e-06 4.6865685854027e-05 2.29663684957444e-05 0.000104897344572838 -1.76183770515491e-06 1.7076404744091e-05 2.07318835173993e-05 2.94020808781523e-05 4.04945912322812e-06 -1.76183770515491e-06 1.27115524943027e-05 -9.47332822442984e-06 8.1056002374629e-06 -3.50784953263799e-06 5.46550955021187e-06 1.7076404744091e-05 -9.47332822442984e-06 7.01318128983635e-05 4.98211042579562e-06 1.93386845298217e-05 9.72373113044762e-06 2.07318835173993e-05 8.1056002374629e-06 4.98211042579562e-06 3.95043820693057e-05 3.01899345208625e-05 4.6865685854027e-05 2.94020808781523e-05 -3.50784953263799e-06 1.93386845298217e-05 3.01899345208625e-05 0.000191123489662002 548 557 0 473 0 548 557 0 469 0 0 0 0 0 0 0 0 0 949 0 0 0 0 0 1072 +936 884 0.876331795318595 0.480513218157952 0.0339062190339385 -0.0281571293672396 -0.476777025246817 0.875255473854066 -0.0813112764952689 -0.178566667392583 -0.0687477469484223 0.0550899506623775 0.996111863510084 0.66166019755586 5.80012088768989e-05 3.95505661692986e-05 2.99566636223719e-06 1.17092195589364e-05 1.31519987094368e-05 4.56594521774233e-05 3.95505661692986e-05 0.000128735079933735 -4.84458617491124e-06 3.24040075520668e-05 3.02740282928155e-05 6.08699058936606e-05 2.99566636223719e-06 -4.84458617491124e-06 1.17216150044425e-05 -7.14978907037925e-06 7.17840529747111e-06 -1.06507180232171e-06 1.17092195589364e-05 3.24040075520668e-05 -7.14978907037925e-06 6.40821546412485e-05 1.0251487648981e-05 4.75623497924636e-05 1.31519987094368e-05 3.02740282928155e-05 7.17840529747111e-06 1.0251487648981e-05 4.72018348418945e-05 5.17650054021011e-05 4.56594521774233e-05 6.08699058936606e-05 -1.06507180232171e-06 4.75623497924636e-05 5.17650054021011e-05 0.00019736368771884 512 519 0 463 0 512 519 0 459 0 0 0 0 0 0 0 0 0 993 0 0 0 0 0 1084 +936 876 0.879684193028368 0.475545854834812 0.00344390555277725 -0.0320358085146995 -0.473930545444349 0.877248818712464 -0.0763174171628503 -0.176691663621887 -0.0393135934614237 0.0655030534938248 0.997077625539825 0.647878484722162 4.19564335063004e-05 1.54032921845363e-05 -1.37633610285221e-06 5.45765081504436e-06 7.95398687743272e-06 3.09048771645706e-05 1.54032921845363e-05 6.55004003089942e-05 -4.48212096645009e-07 -1.46583492428598e-06 7.41004141139966e-06 6.69247535287193e-06 -1.37633610285221e-06 -4.48212096645009e-07 1.30581416996725e-05 -9.60900626589298e-06 6.68260189989918e-06 -2.9672038059267e-06 5.45765081504436e-06 -1.46583492428598e-06 -9.60900626589298e-06 6.47825760876266e-05 -3.83475545568147e-06 1.01262129617824e-05 7.95398687743272e-06 7.41004141139966e-06 6.68260189989918e-06 -3.83475545568147e-06 3.14565202187477e-05 1.47453686151373e-05 3.09048771645706e-05 6.69247535287193e-06 -2.9672038059267e-06 1.01262129617824e-05 1.47453686151373e-05 0.00012442819044271 501 504 0 434 0 501 504 0 430 0 0 0 0 0 0 0 0 0 1012 0 0 0 0 0 715 +936 882 0.876228647762561 0.480788938255471 0.032639756300714 -0.025350396103027 -0.476950518726818 0.874923841979311 -0.0838240623113731 -0.178044238078207 -0.0688589829028347 0.0578814960703167 0.995945868451819 0.664179034214784 5.58413949891752e-05 9.84060454280883e-06 1.06774664925867e-06 5.60440065023634e-06 1.06729695630697e-05 4.19184887435407e-05 9.84060454280883e-06 7.4788486822256e-05 -8.31474723705331e-06 1.44895799780823e-05 7.06719711589618e-06 2.31393470458753e-05 1.06774664925867e-06 -8.31474723705331e-06 1.47312159450967e-05 -7.97077113514217e-06 8.94472156750835e-06 -8.06322862037414e-07 5.60440065023634e-06 1.44895799780823e-05 -7.97077113514217e-06 5.85112070850663e-05 4.54231388106088e-07 2.43331313191591e-05 1.06729695630697e-05 7.06719711589618e-06 8.94472156750835e-06 4.54231388106088e-07 3.40815299285928e-05 3.81698452879037e-05 4.19184887435407e-05 2.31393470458753e-05 -8.06322862037414e-07 2.43331313191591e-05 3.81698452879037e-05 0.000197362601385046 534 543 0 468 0 534 543 0 464 0 0 0 0 0 0 0 0 0 928 0 0 0 0 0 478 +936 879 0.876320599499894 0.481294373536017 0.0204434071210883 -0.0247956465833607 -0.477849253738564 0.873855657677849 -0.089645860171623 -0.178173917775589 -0.0610106350863733 0.0687896470915947 0.995763871035383 0.658524793333118 6.15850928632709e-05 1.79633284155127e-05 -1.43122432436285e-07 2.03743203950998e-05 1.99349055343758e-05 5.31074462268467e-05 1.79633284155127e-05 0.000114649926083861 -1.36657144806424e-05 6.04896074358943e-05 3.17840673341852e-05 6.9866493280318e-05 -1.43122432436285e-07 -1.36657144806424e-05 1.54943809594539e-05 -1.5110747233783e-05 5.10040929750196e-06 -1.30432287341503e-05 2.03743203950998e-05 6.04896074358943e-05 -1.5110747233783e-05 0.000107463163281484 2.45410852606392e-05 9.02891544225621e-05 1.99349055343758e-05 3.17840673341852e-05 5.10040929750196e-06 2.45410852606392e-05 4.93189134897283e-05 6.6211573908774e-05 5.31074462268467e-05 6.9866493280318e-05 -1.30432287341503e-05 9.02891544225621e-05 6.6211573908774e-05 0.00022571972538961 480 486 0 443 0 480 486 0 437 0 0 0 0 0 0 0 0 0 969 0 0 0 0 0 514 +936 886 0.876470920442049 0.480227878373942 0.0343498246273576 -0.0342826187652324 -0.476874312655394 0.875738072965387 -0.0753240830565874 -0.178402080150373 -0.0662541738225887 0.049638819399056 0.996567294295651 0.651019271436038 4.22247874075367e-05 1.53164204356496e-05 7.06585603831402e-06 7.38747507280913e-06 7.86539751762326e-06 3.93082771744378e-05 1.53164204356496e-05 9.34551574636987e-05 -8.45552310710204e-06 2.74224251470959e-05 1.49280220296739e-05 3.52960132614201e-05 7.06585603831402e-06 -8.45552310710204e-06 1.37462722105562e-05 -1.16113815223234e-05 5.03865301232868e-06 -3.38275545760055e-06 7.38747507280913e-06 2.74224251470959e-05 -1.16113815223234e-05 8.65280600580927e-05 1.45095243854754e-05 3.81294913672698e-05 7.86539751762326e-06 1.49280220296739e-05 5.03865301232868e-06 1.45095243854754e-05 3.9767539623089e-05 3.50247904797899e-05 3.93082771744378e-05 3.52960132614201e-05 -3.38275545760055e-06 3.81294913672698e-05 3.50247904797899e-05 0.000154894875583846 530 539 0 486 0 530 539 0 479 0 0 0 0 0 0 0 0 0 1028 0 0 0 0 0 1024 +936 888 0.875309252199278 0.475927741850393 0.0855949621854351 -0.0527757200067279 -0.47381575150237 0.87948337000688 -0.0448066458194143 -0.182413498965773 -0.096604071563182 -0.00133656968695942 0.995321991588093 0.655741373134678 4.90468190396437e-05 7.80633425183139e-07 4.98179183942627e-06 7.39239949552422e-06 5.88965729001192e-06 4.81237819346757e-05 7.80633425183139e-07 6.67103815973144e-05 -6.1948974477214e-06 2.95009289346681e-05 1.54428613420488e-05 3.25139154181562e-05 4.98179183942627e-06 -6.1948974477214e-06 1.56572506054989e-05 -1.34756578185448e-05 4.29260988351763e-06 -5.74312113761224e-06 7.39239949552422e-06 2.95009289346681e-05 -1.34756578185448e-05 7.22244388414075e-05 1.55842734655309e-05 3.4776913390498e-05 5.88965729001192e-06 1.54428613420488e-05 4.29260988351763e-06 1.55842734655309e-05 4.36084024704517e-05 2.18213273990372e-05 4.81237819346757e-05 3.25139154181562e-05 -5.74312113761224e-06 3.4776913390498e-05 2.18213273990372e-05 0.000168615595707918 592 604 0 603 0 592 604 0 598 0 0 0 0 0 0 0 0 0 1202 0 0 0 0 0 436 +936 878 0.877797733474254 0.47896553476075 0.00794705095061721 -0.0277956525892295 -0.476614419557923 0.874912893355027 -0.0858261272026144 -0.172400016693311 -0.0480607342528887 0.0715503008553023 0.996278435112689 0.653911004316634 3.76999752175147e-05 7.13169307531416e-06 -2.93602955412584e-07 2.87737290486209e-06 7.19325150452518e-08 8.4590092790337e-06 7.13169307531416e-06 5.0784152858429e-05 -2.25920735130462e-06 5.05039287170716e-06 4.4586976718631e-06 -6.7564876349179e-06 -2.93602955412584e-07 -2.25920735130462e-06 1.19675444073437e-05 -6.32983327150148e-06 8.16631297828296e-06 1.52384068273908e-06 2.87737290486209e-06 5.05039287170716e-06 -6.32983327150148e-06 5.45038665922256e-05 -3.08949657190387e-06 4.13651488299681e-06 7.19325150452518e-08 4.4586976718631e-06 8.16631297828296e-06 -3.08949657190387e-06 3.16408387742534e-05 8.50005034179514e-06 8.4590092790337e-06 -6.7564876349179e-06 1.52384068273908e-06 4.13651488299681e-06 8.50005034179514e-06 6.52363356683496e-05 485 492 0 428 0 485 492 0 426 0 0 0 0 0 0 0 0 0 961 0 0 0 0 0 1061 +936 883 0.876359388593692 0.480826578922516 0.0282846782792406 -0.0306419807166686 -0.477365301417181 0.874872945365218 -0.0819737669676911 -0.179217640349426 -0.0641606657273333 0.0583363563282698 0.996233044274163 0.659111705633279 4.1171940560822e-05 1.46239010082826e-06 1.62734471253517e-07 1.6449371965439e-05 2.75919831815474e-06 2.26825131836893e-05 1.46239010082826e-06 6.68695563783171e-05 -3.21155873034954e-06 1.75789431649662e-05 1.28650463621188e-05 2.32861707677502e-06 1.62734471253517e-07 -3.21155873034954e-06 1.16750219367324e-05 -1.00659482842142e-05 7.42488572887961e-06 -1.84904334417836e-06 1.6449371965439e-05 1.75789431649662e-05 -1.00659482842142e-05 6.92452364158621e-05 -2.56783805156914e-07 3.37737207442814e-05 2.75919831815474e-06 1.28650463621188e-05 7.42488572887961e-06 -2.56783805156914e-07 3.45127974413122e-05 1.92923249752471e-05 2.26825131836893e-05 2.32861707677502e-06 -1.84904334417836e-06 3.37737207442814e-05 1.92923249752471e-05 0.000123514469750692 526 535 0 467 0 526 535 0 461 0 0 0 0 0 0 0 0 0 939 0 0 0 0 0 1028 +937 941 0.997166203809812 -0.075098059570921 -0.00445459630167147 0.292087619931603 0.0743491199438367 0.992795397205532 -0.0939654598833392 0.204311295379391 0.0114791264086362 0.0933679856063782 0.995565492029882 -0.212909988286365 5.5394582460267e-05 3.15337105262124e-05 1.3574706421491e-06 4.18287780032254e-05 -2.29636794202692e-06 1.88942063245946e-05 3.15337105262124e-05 0.000130315454485249 -1.00167653443671e-05 0.000218464299600838 -2.42826787076278e-06 0.000180054187426686 1.3574706421491e-06 -1.00167653443671e-05 1.28917302099055e-05 -2.33324021317351e-05 5.67597638387917e-06 -2.14598630096283e-05 4.18287780032254e-05 0.000218464299600838 -2.33324021317351e-05 0.000611527764625698 6.58015569276727e-06 0.000516431522704625 -2.29636794202692e-06 -2.42826787076278e-06 5.67597638387917e-06 6.58015569276727e-06 1.69602397323516e-05 3.15236741103269e-05 1.88942063245946e-05 0.000180054187426686 -2.14598630096283e-05 0.000516431522704625 3.15236741103269e-05 0.000834995258025093 2690 2737 0 0 769 2667 2714 0 0 769 0 0 0 0 0 78 43 0 3877 0 0 0 0 0 157 +937 939 0.995273338839017 -0.0954024797119722 -0.0181479437138762 0.133599284797073 0.0953796036671144 0.995438707423032 -0.00212390401547905 0.106381666947668 0.0182677913426738 0.000382921362056813 0.999833056650305 -0.15987439091573 4.6324006074657e-05 1.51350617413313e-05 2.37447883473097e-06 1.71978976815872e-05 -3.42140407801719e-06 4.96976869531822e-05 1.51350617413313e-05 5.05851722217799e-05 1.723857407198e-06 1.54560987248756e-05 -2.94247069167218e-06 3.45664782007613e-05 2.37447883473097e-06 1.723857407198e-06 9.67954637194414e-06 9.7339043281124e-07 5.18271586502924e-06 -1.39262783609868e-06 1.71978976815872e-05 1.54560987248756e-05 9.7339043281124e-07 8.05026180365742e-05 -3.50912685944644e-06 6.80531091122392e-05 -3.42140407801719e-06 -2.94247069167218e-06 5.18271586502924e-06 -3.50912685944644e-06 1.52419138349756e-05 -1.19640399583351e-05 4.96976869531822e-05 3.45664782007613e-05 -1.39262783609868e-06 6.80531091122392e-05 -1.19640399583351e-05 0.000227833193932766 2933 3023 0 0 392 2919 3009 0 0 392 0 0 0 0 0 205 173 0 3797 0 0 0 0 0 352 +937 855 0.880898834928727 0.464235488946442 0.0922098336614362 -0.278878036590225 -0.452445467551954 0.883140578271083 -0.123918593853834 -0.0881857313603145 -0.138961654829331 0.0674398236480118 0.987998749327862 0.461962706244659 3.77557730908424e-05 2.5616623337938e-05 7.03994537196792e-06 -2.6467179303084e-06 6.80228039112988e-06 3.33118336380002e-05 2.5616623337938e-05 9.14239319586605e-05 -2.07473040633794e-06 -5.89471418146466e-06 7.72527619266372e-06 4.27800755623738e-05 7.03994537196792e-06 -2.07473040633794e-06 1.33349805663564e-05 -4.32253996129151e-06 6.73726706677273e-06 -7.51921276715833e-06 -2.6467179303084e-06 -5.89471418146466e-06 -4.32253996129151e-06 3.80964737095526e-05 -2.47730842019438e-06 -1.62537288932016e-06 6.80228039112988e-06 7.72527619266372e-06 6.73726706677273e-06 -2.47730842019438e-06 2.34755881881752e-05 1.64917787536519e-05 3.33118336380002e-05 4.27800755623738e-05 -7.51921276715833e-06 -1.62537288932016e-06 1.64917787536519e-05 0.000235574612923355 1307 1331 0 740 0 1448 1472 0 721 0 0 0 0 0 0 0 0 0 1551 0 0 0 0 0 905 +937 854 0.885343488930519 0.452711693046235 0.105919920636048 -0.349416621646253 -0.446092475938471 0.891324017376822 -0.0808888061373533 -0.0354965856355822 -0.131028277556486 0.0243642981933279 0.991079195349255 0.362784251981652 4.85640864764383e-05 -2.35805937200141e-06 5.79013355994147e-06 -1.20448885235142e-06 1.98135750146015e-06 -2.38939629209488e-06 -2.35805937200141e-06 6.02574497976712e-05 -7.44401133337506e-06 3.05515892245754e-05 1.85177829177391e-05 4.30610458571274e-05 5.79013355994147e-06 -7.44401133337506e-06 1.27667133666243e-05 -6.99621398672101e-06 6.34704317777992e-06 -1.36422307374685e-06 -1.20448885235142e-06 3.05515892245754e-05 -6.99621398672101e-06 5.51273614894278e-05 1.60091114480904e-05 5.04957920053507e-05 1.98135750146015e-06 1.85177829177391e-05 6.34704317777992e-06 1.60091114480904e-05 2.93680997962917e-05 3.94954582875643e-05 -2.38939629209488e-06 4.30610458571274e-05 -1.36422307374685e-06 5.04957920053507e-05 3.94954582875643e-05 0.000244770704975072 1506 1527 0 802 0 1621 1642 0 790 0 0 0 0 0 0 0 0 0 2212 0 0 0 0 0 845 +937 858 0.865175229378723 0.497702199809632 0.0613542400664153 -0.156153134693315 -0.493677982365628 0.866817444815613 -0.0700683030387807 -0.185988991473955 -0.0880560741623029 0.0303321227081907 0.99565359946878 0.646520610921408 7.30419028488593e-05 2.14407051559452e-05 -4.80036321229572e-07 2.63715512561913e-06 3.44443274200924e-06 2.51891890324014e-05 2.14407051559452e-05 0.000134537327983989 -5.77584853505122e-06 1.59426061112325e-05 1.5190952227689e-05 4.87185144641979e-05 -4.80036321229572e-07 -5.77584853505122e-06 1.32251052168274e-05 -6.09941571656411e-06 5.77897406707212e-06 -5.1592409552246e-06 2.63715512561913e-06 1.59426061112325e-05 -6.09941571656411e-06 5.46185522641889e-05 6.19281660973968e-06 5.62383783501437e-05 3.44443274200924e-06 1.5190952227689e-05 5.77897406707212e-06 6.19281660973968e-06 2.93175283881277e-05 4.0009825142673e-05 2.51891890324014e-05 4.87185144641979e-05 -5.1592409552246e-06 5.62383783501437e-05 4.0009825142673e-05 0.000342897472394568 657 678 0 654 0 669 690 0 645 0 0 0 0 0 0 0 0 0 1074 0 0 0 0 0 458 +937 933 0.976507089618052 0.208811236155906 0.0532143926088091 -0.0967806683985763 -0.208347983178759 0.977952094745638 -0.014171036940276 -0.156620755520699 -0.0550001984635117 0.00275100666329081 0.998482553744087 0.50713895516226 6.44942505517707e-05 6.54508757551714e-05 -4.83947082727268e-06 3.04684377524038e-05 4.12805623164232e-06 4.70584462511927e-05 6.54508757551714e-05 0.000147023670677791 -2.38806602634119e-06 3.53498438849878e-05 1.2014633465946e-05 4.81309181501657e-05 -4.83947082727268e-06 -2.38806602634119e-06 1.18888444259467e-05 -5.39875558593332e-06 6.54152270307404e-06 -8.46440860555788e-06 3.04684377524038e-05 3.53498438849878e-05 -5.39875558593332e-06 7.91049360812666e-05 7.98504978392602e-06 6.01779500991828e-05 4.12805623164232e-06 1.2014633465946e-05 6.54152270307404e-06 7.98504978392602e-06 2.00242276034367e-05 2.09640645448044e-05 4.70584462511927e-05 4.81309181501657e-05 -8.46440860555788e-06 6.01779500991828e-05 2.09640645448044e-05 0.000212855972559848 1353 1362 0 433 0 1354 1363 0 425 0 0 0 0 0 0 0 0 0 2100 0 0 0 0 0 634 +937 857 0.871081933649544 0.486340802270191 0.0684754621492881 -0.208291689103632 -0.480619061358945 0.872800786781194 -0.0849947319107211 -0.1650133601174 -0.101101843345304 0.0411267630785047 0.994025656927861 0.583878319104375 6.74075394245811e-05 6.8419296955211e-05 -4.38787499723548e-06 9.62277051838435e-06 6.61854733903423e-06 4.08091737559424e-05 6.8419296955211e-05 0.000152565913293003 -8.79780212150659e-06 2.75437687352347e-05 2.37502498433204e-05 8.15977405627972e-05 -4.38787499723548e-06 -8.79780212150659e-06 1.2965901624786e-05 -9.73181441680753e-06 3.7359146325484e-06 -1.57556761646001e-05 9.62277051838435e-06 2.75437687352347e-05 -9.73181441680753e-06 5.15412638021967e-05 1.35249066037945e-05 5.18054066077273e-05 6.61854733903423e-06 2.37502498433204e-05 3.7359146325484e-06 1.35249066037945e-05 3.53637057624266e-05 5.25483921610778e-05 4.08091737559424e-05 8.15977405627972e-05 -1.57556761646001e-05 5.18054066077273e-05 5.25483921610778e-05 0.000286215481143241 904 915 0 750 0 982 993 0 742 0 0 0 0 0 0 0 0 0 1181 0 0 0 0 0 539 +937 940 0.994130331363903 -0.10319565065692 -0.0324891050629551 0.196194010847768 0.100947548169794 0.992795516466527 -0.0645496320862453 0.161261369379822 0.0389162791233166 0.0608910516369809 0.997385483677068 -0.203564996311443 6.10238639279961e-05 1.72794058311377e-05 3.28739961634822e-06 -1.82812579980048e-05 5.78766865552555e-06 1.00318067842201e-05 1.72794058311377e-05 3.49045725910586e-05 3.68351826298046e-06 -3.10899405295056e-06 9.2279689388284e-07 6.05706495900065e-06 3.28739961634822e-06 3.68351826298046e-06 1.17151614709896e-05 4.11417866925541e-06 5.160344255403e-06 -2.23277061879792e-06 -1.82812579980048e-05 -3.10899405295056e-06 4.11417866925541e-06 8.81128788482628e-05 -3.12133025741056e-06 2.46723698000049e-05 5.78766865552555e-06 9.2279689388284e-07 5.160344255403e-06 -3.12133025741056e-06 1.5151269970395e-05 3.67493599947356e-06 1.00318067842201e-05 6.05706495900065e-06 -2.23277061879792e-06 2.46723698000049e-05 3.67493599947356e-06 0.00014251030404177 2840 2919 0 0 629 2823 2902 0 0 629 0 0 0 0 0 207 174 0 3859 0 0 0 0 0 222 +937 859 0.869644974541992 0.486246308006007 0.0853354920556829 -0.14785892740426 -0.480910249551501 0.873459654565527 -0.0761154630977416 -0.197045905784898 -0.11154797232658 0.0251547171877889 0.993440632384759 0.673853020044152 4.89200179718398e-05 -5.00683679950989e-06 3.76084812342571e-06 -5.87396601536161e-06 -3.22344786487171e-06 7.92243480334487e-06 -5.00683679950989e-06 3.68328347214876e-05 5.47416648619058e-09 3.84524509870193e-06 4.92315333702617e-06 -1.19492293422212e-05 3.76084812342571e-06 5.47416648619058e-09 1.17213137866589e-05 -3.36686789580993e-06 5.43572994324078e-06 -3.960755303398e-06 -5.87396601536161e-06 3.84524509870193e-06 -3.36686789580993e-06 5.04967651318574e-05 3.59984292406065e-06 8.67650222055644e-06 -3.22344786487171e-06 4.92315333702617e-06 5.43572994324078e-06 3.59984292406065e-06 2.63590494626523e-05 5.74161574974626e-06 7.92243480334487e-06 -1.19492293422212e-05 -3.960755303398e-06 8.67650222055644e-06 5.74161574974626e-06 9.24568753805541e-05 728 735 0 722 0 737 744 0 713 0 0 0 0 0 0 0 0 0 1092 0 0 0 0 0 649 +937 861 0.881482145314178 0.471070315356991 0.0328935477226214 -0.140724677172168 -0.466081679126234 0.879107962356523 -0.0996847977588946 -0.202231744951754 -0.075875528829691 0.0725392894287421 0.994475216188914 0.696211139542886 6.41357582460434e-05 1.53917465379671e-05 -3.11062903136311e-06 2.41105908469801e-06 -4.86090606138577e-06 -1.01269745832737e-05 1.53917465379671e-05 4.07411770075989e-05 5.50072847712693e-06 -8.25338896799939e-06 2.86746330681604e-07 -2.45073403667489e-05 -3.11062903136311e-06 5.50072847712693e-06 1.31082710590554e-05 -9.32268480821397e-06 7.90263596391084e-06 -5.20032645479756e-06 2.41105908469801e-06 -8.25338896799939e-06 -9.32268480821397e-06 4.52202684811987e-05 -7.66380197384847e-06 5.71490498789744e-06 -4.86090606138577e-06 2.86746330681604e-07 7.90263596391084e-06 -7.66380197384847e-06 2.59220557018109e-05 -3.25729265674327e-06 -1.01269745832737e-05 -2.45073403667489e-05 -5.20032645479756e-06 5.71490498789744e-06 -3.25729265674327e-06 6.13362425426825e-05 633 647 0 549 0 635 649 0 539 0 0 0 0 0 0 0 0 0 785 0 0 0 0 0 539 +937 862 0.881262851088512 0.472128372230512 0.0216930271357848 -0.123746790954364 -0.470147796404763 0.880411780109681 -0.0619366368141497 -0.204793624949515 -0.0483408401570808 0.0443835282404333 0.997844309295713 0.733106714886465 6.54361689103884e-05 5.2698131397117e-05 2.37452867857462e-07 1.25807959763291e-05 5.14727064679932e-06 3.17497190440116e-05 5.2698131397117e-05 0.00016502447242247 -8.41606695662244e-07 4.00777366043711e-05 4.33232964802272e-05 5.48097201033371e-05 2.37452867857462e-07 -8.41606695662244e-07 1.32547610471812e-05 -6.57751896517064e-06 9.87013422328106e-06 3.29804164922031e-06 1.25807959763291e-05 4.00777366043711e-05 -6.57751896517064e-06 6.36841135912128e-05 1.45670492609444e-05 4.17563142727506e-05 5.14727064679932e-06 4.33232964802272e-05 9.87013422328106e-06 1.45670492609444e-05 5.08215540659435e-05 5.43621738665679e-05 3.17497190440116e-05 5.48097201033371e-05 3.29804164922031e-06 4.17563142727506e-05 5.43621738665679e-05 0.000270841584027567 544 552 0 508 0 544 552 0 503 0 0 0 0 0 0 0 0 0 788 0 0 0 0 0 863 +937 864 0.886360626804972 0.462970915066092 -0.00477190242603213 -0.111055049161843 -0.462462236817206 0.884798181584361 -0.0571039174053263 -0.21312481667938 -0.0222152823057512 0.0528214886942206 0.998356835787787 0.752574500110612 6.63048676712692e-05 5.65950707579359e-06 -1.48114102004317e-06 -1.44511601355654e-06 -3.79139413031857e-06 1.66575179574895e-05 5.65950707579359e-06 0.000102464219771721 -2.28077203873704e-06 1.11409583709886e-05 7.0414909932138e-06 -1.9575393017576e-05 -1.48114102004317e-06 -2.28077203873704e-06 1.26000672987154e-05 -1.18680559787659e-05 8.37966935723472e-06 -3.26469648588429e-06 -1.44511601355654e-06 1.11409583709886e-05 -1.18680559787659e-05 9.05957991149263e-05 5.80276255359933e-06 3.71726208610432e-05 -3.79139413031857e-06 7.0414909932138e-06 8.37966935723472e-06 5.80276255359933e-06 3.37831582265373e-05 1.92509004211296e-05 1.66575179574895e-05 -1.9575393017576e-05 -3.26469648588429e-06 3.71726208610432e-05 1.92509004211296e-05 0.000197226826251874 444 454 0 471 0 444 454 0 465 0 0 0 0 0 0 0 0 0 791 0 0 0 0 0 817 +937 865 0.877279859559905 0.479743591545491 -0.0150377651793042 -0.117459636524173 -0.479531966976888 0.874679949387113 -0.0705980083814993 -0.220132277852 -0.02071571041097 0.0691452999934989 0.997391491256557 0.732399308168964 7.598293450946e-05 4.92885971909557e-06 7.94876089603657e-07 -3.38466116449108e-06 -2.84127218891851e-06 -5.02062080362772e-06 4.92885971909557e-06 6.00170298714409e-05 -1.1053906335834e-06 3.7190568956256e-06 6.73437049961502e-06 -1.31626682426613e-05 7.94876089603657e-07 -1.1053906335834e-06 1.26037225943109e-05 -9.0731995759997e-06 1.02108169650269e-05 -2.14852102234193e-06 -3.38466116449108e-06 3.7190568956256e-06 -9.0731995759997e-06 6.28833213810121e-05 -4.45323410483824e-06 2.98302394646874e-05 -2.84127218891851e-06 6.73437049961502e-06 1.02108169650269e-05 -4.45323410483824e-06 3.35637717179715e-05 2.09831913093346e-05 -5.02062080362772e-06 -1.31626682426613e-05 -2.14852102234193e-06 2.98302394646874e-05 2.09831913093346e-05 0.000153911330962008 417 427 0 476 0 417 427 0 470 0 0 0 0 0 0 0 0 0 752 0 0 0 0 0 808 +937 863 0.881753370020684 0.471477691655121 0.0148250034983557 -0.113109559499014 -0.469922223961257 0.880710466842724 -0.059347931901436 -0.208959403535862 -0.0410377616893762 0.0453636403436685 0.998127267561755 0.725028407490272 0.000109394869678526 0.000120322597136525 -4.53297513342249e-06 2.61873717739098e-05 2.81643987403151e-05 -6.82369527117811e-05 0.000120322597136525 0.000418650277455354 -1.0147763220769e-05 6.58726342572264e-05 4.70290723560175e-05 -0.000399247795034456 -4.53297513342249e-06 -1.0147763220769e-05 1.44719732922268e-05 -9.22188287197836e-06 5.08427778308966e-06 5.15376337145003e-06 2.61873717739098e-05 6.58726342572264e-05 -9.22188287197836e-06 8.12491905754618e-05 1.15673055414269e-05 -4.61898364040519e-05 2.81643987403151e-05 4.70290723560175e-05 5.08427778308966e-06 1.15673055414269e-05 4.46315858945108e-05 6.51813622382001e-06 -6.82369527117811e-05 -0.000399247795034456 5.15376337145003e-06 -4.61898364040519e-05 6.51813622382001e-06 0.000874590948068563 412 417 0 513 0 412 417 0 507 0 0 0 0 0 0 0 0 0 894 0 0 0 0 0 343 +937 866 0.875183364595744 0.483772890373104 -0.00422715920277828 -0.114316888542315 -0.48265179462207 0.872489189869792 -0.0762224291691689 -0.218800355770659 -0.0331861941621454 0.0687488479933082 0.997081878491744 0.735793936423634 0.000119176782706887 1.91955705307011e-05 -2.74891402807012e-06 -1.00132729098026e-05 1.55157091425189e-05 -8.07791592442573e-06 1.91955705307011e-05 0.000133974910445789 -1.28037979197363e-05 3.92082094403406e-05 3.35291717723672e-05 4.6247404651956e-05 -2.74891402807012e-06 -1.28037979197363e-05 1.5906435984998e-05 -7.73767271187358e-06 6.12780226388123e-06 -3.6574089792194e-06 -1.00132729098026e-05 3.92082094403406e-05 -7.73767271187358e-06 7.53790200175799e-05 1.60300118448332e-05 7.87996121965839e-05 1.55157091425189e-05 3.35291717723672e-05 6.12780226388123e-06 1.60300118448332e-05 5.19223500048682e-05 6.6452249758857e-05 -8.07791592442573e-06 4.6247404651956e-05 -3.6574089792194e-06 7.87996121965839e-05 6.6452249758857e-05 0.000321170800840193 375 383 0 473 0 375 383 0 469 0 0 0 0 0 0 0 0 0 776 0 0 0 0 0 395 +937 856 0.873500319683086 0.473944291105853 0.111238484535333 -0.235362104270281 -0.459740537805507 0.878233270592207 -0.131700266982338 -0.127881533895423 -0.160111927762582 0.0638993846064762 0.985028445901469 0.518374046048631 3.35987777199879e-05 1.61537903445104e-06 7.76260968259129e-06 -7.41767359419604e-06 -6.30511370748195e-07 2.5780524508224e-06 1.61537903445104e-06 4.02528859481182e-05 1.08621901479018e-07 6.02036456445329e-06 -9.48375016683778e-07 -2.53598146239342e-05 7.76260968259129e-06 1.08621901479018e-07 1.10099383730649e-05 -5.64044582601643e-06 6.62201157287158e-06 4.33198034859736e-08 -7.41767359419604e-06 6.02036456445329e-06 -5.64044582601643e-06 5.38989391977e-05 6.95242133905054e-07 -8.41567145754168e-06 -6.30511370748195e-07 -9.48375016683778e-07 6.62201157287158e-06 6.95242133905054e-07 2.40502878948669e-05 5.92944499129153e-06 2.5780524508224e-06 -2.53598146239342e-05 4.33198034859736e-08 -8.41567145754168e-06 5.92944499129153e-06 7.75849491156327e-05 1170 1190 0 734 0 1288 1308 0 714 0 0 0 0 0 0 0 0 0 1428 0 0 0 0 0 886 +937 860 0.878748293560307 0.472532282416818 0.0671913583640123 -0.160241125686171 -0.464669245039664 0.879154222325713 -0.105689857986186 -0.200277324659742 -0.109013436232043 0.061653024587797 0.992126491572551 0.660167795195937 5.61860129250115e-05 1.49246755192995e-05 -1.97111415455465e-07 -5.01048247614658e-06 -1.49053200348914e-05 -2.9624260354514e-05 1.49246755192995e-05 0.000134152713583766 -1.02244022454393e-05 2.290725679559e-05 7.69335214397114e-06 1.24363004859414e-05 -1.97111415455465e-07 -1.02244022454393e-05 1.28712257901055e-05 -1.00218313935674e-05 6.64761713273772e-06 -8.65207193178872e-06 -5.01048247614658e-06 2.290725679559e-05 -1.00218313935674e-05 7.91087937345053e-05 1.55911075430267e-05 3.90917331573211e-05 -1.49053200348914e-05 7.69335214397114e-06 6.64761713273772e-06 1.55911075430267e-05 3.90662567473756e-05 4.48317149142608e-05 -2.9624260354514e-05 1.24363004859414e-05 -8.65207193178872e-06 3.90917331573211e-05 4.48317149142608e-05 0.000307510069511498 697 714 0 620 0 706 723 0 613 0 0 0 0 0 0 0 0 0 919 0 0 0 0 0 818 +937 870 0.8532990615998 0.521006551806999 0.0208058753019792 -0.0968565503639602 -0.517334862278735 0.85092271101578 -0.0910778795789514 -0.231880086318706 -0.065156363802339 0.0669530645432809 0.995626403529115 0.76018763653689 8.26301461289383e-05 6.8003580675815e-05 -3.96287257201551e-06 3.25212714536189e-05 3.84022366028419e-05 0.000129989618506053 6.8003580675815e-05 0.000187803892303991 -1.72892228009122e-05 6.9035455152989e-05 6.29590631276724e-05 0.000189549141403848 -3.96287257201551e-06 -1.72892228009122e-05 1.37352232908586e-05 -1.08989186892383e-05 3.16184812544379e-06 -1.38253492930227e-05 3.25212714536189e-05 6.9035455152989e-05 -1.08989186892383e-05 8.11904508563242e-05 2.32211524499661e-05 0.000100854879058406 3.84022366028419e-05 6.29590631276724e-05 3.16184812544379e-06 2.32211524499661e-05 6.57131982165243e-05 0.000130916058399155 0.000129989618506053 0.000189549141403848 -1.38253492930227e-05 0.000100854879058406 0.000130916058399155 0.000493125094609708 400 415 0 535 0 400 415 0 531 0 0 0 0 0 0 0 0 0 615 0 0 0 0 0 450 +937 874 0.864151578512922 0.50299551745904 -0.0154129416315606 -0.076410310578265 -0.502525013291302 0.860910885740242 -0.0793792027582081 -0.222956897055315 -0.0266582139349614 0.0763410520628609 0.996725329967957 0.783372630961829 7.17787486368895e-05 2.07143872580956e-05 -1.33219614400122e-06 3.79670219542065e-08 2.42524751799573e-06 2.85620758008678e-05 2.07143872580956e-05 8.90178421171386e-05 -7.71373053481506e-07 1.03623837707833e-05 1.58142389020643e-05 5.30651189324268e-05 -1.33219614400122e-06 -7.71373053481506e-07 1.17482855368179e-05 -7.3728935582337e-06 7.19274763295065e-06 -4.14326004373272e-06 3.79670219542065e-08 1.03623837707833e-05 -7.3728935582337e-06 6.14714538742067e-05 -1.83388359902956e-06 4.65539043801348e-05 2.42524751799573e-06 1.58142389020643e-05 7.19274763295065e-06 -1.83388359902956e-06 4.38654184146999e-05 6.54895527977545e-05 2.85620758008678e-05 5.30651189324268e-05 -4.14326004373272e-06 4.65539043801348e-05 6.54895527977545e-05 0.0004054449223639 342 354 0 427 0 342 354 0 423 0 0 0 0 0 0 0 0 0 529 0 0 0 0 0 725 +937 872 0.86080578698279 0.508933557789549 0.000175649113652428 -0.0856715469292339 -0.507039644577184 0.857632083873366 -0.0858953289653768 -0.230111699861056 -0.0438656576832251 0.0738501351840302 0.996304151155318 0.786857949460877 6.6700465945997e-05 2.78375160953787e-05 1.16218501080529e-06 4.61359672089537e-06 8.97269115064973e-06 5.61146106487673e-05 2.78375160953787e-05 0.000115295857172983 -2.96651389918889e-06 2.46722005597321e-05 1.98404808732237e-05 4.75323618568289e-05 1.16218501080529e-06 -2.96651389918889e-06 1.25506060988435e-05 -6.98668280254644e-06 5.95812495517549e-06 -1.05387145858681e-05 4.61359672089537e-06 2.46722005597321e-05 -6.98668280254644e-06 6.0976008867647e-05 8.3471907299831e-06 6.30489720721067e-05 8.97269115064973e-06 1.98404808732237e-05 5.95812495517549e-06 8.3471907299831e-06 4.27465822765056e-05 7.53398444144454e-05 5.61146106487673e-05 4.75323618568289e-05 -1.05387145858681e-05 6.30489720721067e-05 7.53398444144454e-05 0.000452954661249283 348 360 0 480 0 348 360 0 475 0 0 0 0 0 0 0 0 0 628 0 0 0 0 0 805 +937 871 0.855402995456099 0.517956847427935 0.00253368649357535 -0.100967062557498 -0.516099232240268 0.852729359459954 -0.0805867358566012 -0.23597324234754 -0.0439010005095317 0.0676265015916944 0.996744379686553 0.764314399468195 6.59564390277514e-05 1.258413274576e-05 5.86695840502164e-06 -2.06755124827769e-05 -6.83019084728456e-06 2.37249028720544e-06 1.258413274576e-05 0.000122867391106378 -2.83146376292307e-06 1.57450975720873e-05 1.25775174726972e-05 3.8811121308611e-05 5.86695840502164e-06 -2.83146376292307e-06 1.40380419704648e-05 -1.16687120772911e-05 8.96433643363128e-06 -6.4914330326815e-06 -2.06755124827769e-05 1.57450975720873e-05 -1.16687120772911e-05 7.88211831684614e-05 5.56848486549721e-06 3.88755656169517e-05 -6.83019084728456e-06 1.25775174726972e-05 8.96433643363128e-06 5.56848486549721e-06 3.60609141124737e-05 3.32341546495441e-05 2.37249028720544e-06 3.8811121308611e-05 -6.4914330326815e-06 3.88755656169517e-05 3.32341546495441e-05 0.000245082417148625 364 378 0 504 0 364 378 0 497 0 0 0 0 0 0 0 0 0 660 0 0 0 0 0 815 +937 867 0.867886457908392 0.496503477854153 0.0160434615327955 -0.0924778696094686 -0.49263969221971 0.864386688969767 -0.100706432672163 -0.226363277982933 -0.0638688486579611 0.0794981031887786 0.99478682226922 0.764149379389699 9.13040065346392e-05 -1.34498612912113e-07 -4.58342496765518e-06 7.16588641193896e-06 3.25018283448707e-06 -1.64222598681221e-05 -1.34498612912113e-07 6.42757913923618e-05 -5.1254241046013e-06 1.55617331613929e-05 -3.0248093905954e-08 -2.02862139739223e-05 -4.58342496765518e-06 -5.1254241046013e-06 1.60504506909187e-05 -1.2585921276414e-05 7.27196815787183e-06 -1.00193291202768e-06 7.16588641193896e-06 1.55617331613929e-05 -1.2585921276414e-05 7.76852326788007e-05 4.26742284630883e-06 2.75828300920762e-05 3.25018283448707e-06 -3.0248093905954e-08 7.27196815787183e-06 4.26742284630883e-06 3.81790908470294e-05 1.17727318518081e-05 -1.64222598681221e-05 -2.02862139739223e-05 -1.00193291202768e-06 2.75828300920762e-05 1.17727318518081e-05 0.000127142037989341 408 421 0 494 0 408 421 0 489 0 0 0 0 0 0 0 0 0 633 0 0 0 0 0 422 +937 868 0.859204387833331 0.511277917482886 0.0190449736758714 -0.104544942308561 -0.507205115452524 0.856065397525199 -0.0994736448453336 -0.226879653418033 -0.0671624209416461 0.0758084840528244 0.994857920991168 0.746495987174356 5.74437887085116e-05 2.33341607451826e-05 -1.31654462279698e-06 7.01330138736477e-06 -9.42258509541414e-07 3.44759744654368e-05 2.33341607451826e-05 9.84334618869142e-05 -6.65514684870854e-06 1.99905896584631e-05 1.9146151101967e-05 6.85500889901328e-05 -1.31654462279698e-06 -6.65514684870854e-06 1.28549599280338e-05 -9.29185260285073e-06 7.8248614230489e-06 -6.91607545324091e-06 7.01330138736477e-06 1.99905896584631e-05 -9.29185260285073e-06 6.4107115939565e-05 8.9853903204271e-07 5.51327841928149e-05 -9.42258509541414e-07 1.9146151101967e-05 7.8248614230489e-06 8.9853903204271e-07 3.97367161678717e-05 5.9086771346051e-05 3.44759744654368e-05 6.85500889901328e-05 -6.91607545324091e-06 5.51327841928149e-05 5.9086771346051e-05 0.00035643376497325 411 424 0 509 0 411 424 0 504 0 0 0 0 0 0 0 0 0 668 0 0 0 0 0 817 +937 886 0.858332972158478 0.512825169856583 0.0165787233271938 -0.0865811710914626 -0.509595960379494 0.855803705762603 -0.0889492797491832 -0.228964071576762 -0.059803562356221 0.0678996492226852 0.995898173291297 0.784985642278434 5.61695246181886e-05 1.26804441616406e-05 3.08038082211774e-06 -5.65412095924859e-06 -2.19581377088308e-06 1.37848730446232e-05 1.26804441616406e-05 6.42488247893698e-05 -2.77216567770731e-06 6.71538664894922e-07 -9.20242014172886e-07 -1.21216530056018e-05 3.08038082211774e-06 -2.77216567770731e-06 1.38279060492453e-05 -1.13390818157032e-05 1.1038521991725e-05 1.17969581618435e-06 -5.65412095924859e-06 6.71538664894922e-07 -1.13390818157032e-05 7.00201524281201e-05 -7.21853401681929e-06 8.63042196242359e-06 -2.19581377088308e-06 -9.20242014172886e-07 1.1038521991725e-05 -7.21853401681929e-06 3.20078513254133e-05 1.14834102566831e-05 1.37848730446232e-05 -1.21216530056018e-05 1.17969581618435e-06 8.63042196242359e-06 1.14834102566831e-05 0.00012813500741723 351 363 0 523 0 351 363 0 517 0 0 0 0 0 0 0 0 0 570 0 0 0 0 0 833 +937 869 0.853444470224807 0.520579380874513 0.0250927170909605 -0.110387121275013 -0.516399954442682 0.851138528963645 -0.0943095518237586 -0.229521676256421 -0.0704529864114661 0.0675300875307516 0.995226639506698 0.747386428762429 7.10758415971534e-05 1.25178897327043e-06 -6.80384005425709e-07 -5.1004047109085e-06 -7.43065477763657e-06 1.84795802778272e-05 1.25178897327043e-06 9.07064931837186e-05 -3.78877514877775e-07 1.68145266209403e-05 1.21089557666869e-05 -8.25407709776139e-06 -6.80384005425709e-07 -3.78877514877775e-07 1.31484004416013e-05 -7.79829598916807e-06 9.97589962999636e-06 9.74874908151799e-07 -5.1004047109085e-06 1.68145266209403e-05 -7.79829598916807e-06 5.67946614869322e-05 1.17937488628206e-06 1.50299645814343e-05 -7.43065477763657e-06 1.21089557666869e-05 9.97589962999636e-06 1.17937488628206e-06 4.18725883742782e-05 3.37750586094701e-05 1.84795802778272e-05 -8.25407709776139e-06 9.74874908151799e-07 1.50299645814343e-05 3.37750586094701e-05 0.000173447261689181 422 438 0 532 0 422 438 0 525 0 0 0 0 0 0 0 0 0 603 0 0 0 0 0 829 +937 887 0.857885109551649 0.512443002350063 0.0378854609581263 -0.0900573605845101 -0.508819773656672 0.857471601742025 -0.0764518812190962 -0.228446307120936 -0.0716629384377235 0.0463100588254814 0.996353251465589 0.776528087395584 7.54374254427708e-05 -5.91806672569371e-06 1.7521517997435e-06 -1.27633917002913e-05 -8.97773065239724e-06 -1.86793178884672e-05 -5.91806672569371e-06 7.89077856196648e-05 -3.8524796537172e-06 2.04306035767625e-05 1.15360499847791e-05 1.32335678341036e-06 1.7521517997435e-06 -3.8524796537172e-06 1.22570249560851e-05 -6.03531556446944e-06 8.12381458918828e-06 9.61250323144068e-07 -1.27633917002913e-05 2.04306035767625e-05 -6.03531556446944e-06 6.58242560458227e-05 6.12732384539644e-06 4.51510362215425e-05 -8.97773065239724e-06 1.15360499847791e-05 8.12381458918828e-06 6.12732384539644e-06 3.82853102396344e-05 4.49196139853499e-05 -1.86793178884672e-05 1.32335678341036e-06 9.61250323144068e-07 4.51510362215425e-05 4.49196139853499e-05 0.000214731191023194 419 435 0 541 0 419 435 0 536 0 0 0 0 0 0 0 0 0 666 0 0 0 0 0 819 +937 877 0.861604116909595 0.507457196486639 -0.0112044392254364 -0.0720868379787909 -0.506178240195193 0.857373912052637 -0.0932392840194164 -0.226005072496173 -0.0377085517798462 0.0860067942983376 0.995580683047431 0.791545200830906 5.87450888263713e-05 1.68251278139679e-05 5.50976576007802e-07 3.63531471279424e-06 -4.49438295228689e-06 -5.23361412966778e-06 1.68251278139679e-05 6.68141404233955e-05 -5.85992502701724e-07 4.94045145540912e-06 7.63435748097433e-06 -2.66240135292393e-05 5.50976576007802e-07 -5.85992502701724e-07 1.25581525870247e-05 -7.07829004866098e-06 6.121776422506e-06 -3.0930968179206e-06 3.63531471279424e-06 4.94045145540912e-06 -7.07829004866098e-06 6.06998819221796e-05 -8.35652402748493e-06 1.40369086633941e-05 -4.49438295228689e-06 7.63435748097433e-06 6.121776422506e-06 -8.35652402748493e-06 4.49582605994782e-05 1.6355251286771e-05 -5.23361412966778e-06 -2.66240135292393e-05 -3.0930968179206e-06 1.40369086633941e-05 1.6355251286771e-05 0.000116908715585306 311 323 0 438 0 311 323 0 434 0 0 0 0 0 0 0 0 0 495 0 0 0 0 0 708 +937 885 0.858499585013759 0.512700452430132 0.010803175882224 -0.0892839641625973 -0.51008147312274 0.855907089749211 -0.0850878633764551 -0.225295275773125 -0.0528711008788249 0.0675373955299853 0.996314883406289 0.781090516741195 5.08455075947766e-05 2.44319130104151e-05 2.90260219696143e-06 1.27877941803866e-06 4.48155729983599e-06 3.22732413481961e-05 2.44319130104151e-05 0.000105037453529943 1.46592619793273e-06 -4.61616540863853e-06 1.39444800304833e-05 3.11382220326374e-06 2.90260219696143e-06 1.46592619793273e-06 1.31707410682788e-05 -9.22538340063063e-06 9.01010944482887e-06 -4.18099165587329e-06 1.27877941803866e-06 -4.61616540863853e-06 -9.22538340063063e-06 6.54363156521512e-05 -3.96346469140475e-06 1.93114588978659e-05 4.48155729983599e-06 1.39444800304833e-05 9.01010944482887e-06 -3.96346469140475e-06 3.56450374404293e-05 1.82116473928018e-05 3.22732413481961e-05 3.11382220326374e-06 -4.18099165587329e-06 1.93114588978659e-05 1.82116473928018e-05 0.000201238577678198 373 379 0 486 0 373 379 0 480 0 0 0 0 0 0 0 0 0 561 0 0 0 0 0 891 +937 878 0.859182279991221 0.511467142237439 -0.0143934763193141 -0.0771661787247337 -0.5104987953024 0.854975078921164 -0.0916983883094399 -0.220954208879676 -0.0345946490643527 0.0861334826604483 0.995682797592133 0.778040934646203 5.95834751027863e-05 3.68914508671861e-05 -4.85835858605725e-07 3.30618483696034e-06 5.49801295746275e-06 3.74228866232665e-05 3.68914508671861e-05 8.29909797681262e-05 -3.20300934971861e-06 7.06356696130939e-06 6.29823392497182e-06 2.10197781269577e-06 -4.85835858605725e-07 -3.20300934971861e-06 1.24881485087592e-05 -7.50481078881592e-06 7.74101751593583e-06 -9.48267736823501e-07 3.30618483696034e-06 7.06356696130939e-06 -7.50481078881592e-06 5.90834295235773e-05 -3.94497345595934e-06 6.84469306429895e-06 5.49801295746275e-06 6.29823392497182e-06 7.74101751593583e-06 -3.94497345595934e-06 3.53158741915011e-05 2.76381226966139e-05 3.74228866232665e-05 2.10197781269577e-06 -9.48267736823501e-07 6.84469306429895e-06 2.76381226966139e-05 0.000161524925099944 313 324 0 434 0 313 324 0 425 0 0 0 0 0 0 0 0 0 545 0 0 0 0 0 896 +937 873 0.866540683710771 0.498980465435239 -0.0112133219030595 -0.0938139021584042 -0.497886738587704 0.862635141305658 -0.0892715437475334 -0.21947544195576 -0.034871750924915 0.082940388825952 0.995944201694468 0.763596650908477 5.85030927617292e-05 -3.37527207408868e-06 4.67780562292293e-06 -1.30798616689603e-05 -4.28142188728065e-06 1.96618769910989e-05 -3.37527207408868e-06 6.15988760182534e-05 -5.70884839039211e-06 1.43386949803977e-05 7.13858088992328e-06 -8.89946654937497e-06 4.67780562292293e-06 -5.70884839039211e-06 1.40467733482799e-05 -9.56477666113513e-06 7.83522543725513e-06 7.23144766234369e-07 -1.30798616689603e-05 1.43386949803977e-05 -9.56477666113513e-06 8.20924328610695e-05 3.19044290717279e-06 1.76509969170459e-05 -4.28142188728065e-06 7.13858088992328e-06 7.83522543725513e-06 3.19044290717279e-06 4.58040155291476e-05 3.14119820237089e-05 1.96618769910989e-05 -8.89946654937497e-06 7.23144766234369e-07 1.76509969170459e-05 3.14119820237089e-05 0.000140490974077849 345 356 0 468 0 345 356 0 462 0 0 0 0 0 0 0 0 0 564 0 0 0 0 0 585 +937 888 0.856479556310424 0.511326829773263 0.0706232452973088 -0.0938993122330659 -0.508296776628037 0.85928813153837 -0.0570814669296859 -0.229524142953814 -0.0898730020186641 0.0129915415298523 0.995868497019979 0.782106905625193 5.95483868452701e-05 2.74617930062031e-05 -4.9723557042074e-06 1.95465188130674e-05 1.90807329477074e-06 2.55781555384812e-05 2.74617930062031e-05 9.27751043281182e-05 -4.26216529852199e-06 1.66993995320999e-05 1.34290424224483e-05 1.26640768273644e-05 -4.9723557042074e-06 -4.26216529852199e-06 1.36297026650307e-05 -9.38481192930948e-06 6.93991145091062e-06 -2.91544137456311e-06 1.95465188130674e-05 1.66993995320999e-05 -9.38481192930948e-06 5.12955456408177e-05 5.54143595058564e-07 2.27554193874733e-05 1.90807329477074e-06 1.34290424224483e-05 6.93991145091062e-06 5.54143595058564e-07 3.52419133188964e-05 2.56461090251929e-05 2.55781555384812e-05 1.26640768273644e-05 -2.91544137456311e-06 2.27554193874733e-05 2.56461090251929e-05 0.000178697732978735 402 419 0 650 0 402 419 0 645 0 0 0 0 0 0 0 0 0 743 0 0 0 0 0 387 +937 875 0.860368010275583 0.509555826999862 -0.0109428545142541 -0.0742350430884253 -0.508483335608653 0.856695068121723 -0.0867078869781425 -0.22772228314393 -0.034807819563023 0.0801649513590728 0.996173677764508 0.787612517826535 8.72361757586565e-05 5.24962679504049e-05 3.13200924212952e-06 -1.61183004138134e-05 1.76494770135976e-05 7.55032315641768e-05 5.24962679504049e-05 9.7938047047469e-05 2.28442631237992e-06 -1.24598098704558e-05 1.85949503896132e-05 3.59711180526582e-05 3.13200924212952e-06 2.28442631237992e-06 1.30777690772355e-05 -1.20087764133116e-05 8.21655376121796e-06 1.65432574821806e-06 -1.61183004138134e-05 -1.24598098704558e-05 -1.20087764133116e-05 8.63325177846947e-05 -3.15702368611892e-06 -5.96660655310829e-06 1.76494770135976e-05 1.85949503896132e-05 8.21655376121796e-06 -3.15702368611892e-06 4.3929942534646e-05 4.67244271138931e-05 7.55032315641768e-05 3.59711180526582e-05 1.65432574821806e-06 -5.96660655310829e-06 4.67244271138931e-05 0.000307599685316991 329 337 0 464 0 329 337 0 459 0 0 0 0 0 0 0 0 0 564 0 0 0 0 0 865 +937 876 0.860878318469981 0.508683327429256 -0.011392681150562 -0.0742747939395158 -0.507643800103574 0.857172654810222 -0.0869069160769097 -0.224761791830754 -0.034442604499384 0.0805997037283414 0.996151291096991 0.782900045258788 0.000100856074739091 5.73728263368994e-05 -1.06401202840475e-06 -5.13481008817236e-06 2.00861049256289e-05 0.000112144574911467 5.73728263368994e-05 9.31089304143439e-05 7.07707136476427e-07 -1.0716610746794e-05 1.71164626024535e-05 8.10125729372044e-05 -1.06401202840475e-06 7.07707136476427e-07 1.35847704681483e-05 -6.04910155585784e-06 8.99395657085285e-06 4.20740655939413e-07 -5.13481008817236e-06 -1.0716610746794e-05 -6.04910155585784e-06 6.00461562883865e-05 -1.00207247919652e-05 7.91787070820167e-06 2.00861049256289e-05 1.71164626024535e-05 8.99395657085285e-06 -1.00207247919652e-05 5.02059152879108e-05 7.97754751558492e-05 0.000112144574911467 8.10125729372044e-05 4.20740655939413e-07 7.91787070820167e-06 7.97754751558492e-05 0.000410679574648692 324 335 0 458 0 324 335 0 454 0 0 0 0 0 0 0 0 0 598 0 0 0 0 0 566 +937 884 0.858317780309175 0.513093475080793 0.00506693542938507 -0.0887254365442866 -0.510946444496779 0.855550448575248 -0.0834695201782747 -0.221750877076784 -0.0471626850511096 0.0690544406407496 0.996497448750654 0.777057387736378 6.75211714884902e-05 5.24499547240707e-05 1.3832490077194e-06 1.66377379402441e-05 1.93429463360717e-05 7.48269242077693e-05 5.24499547240707e-05 0.000136545804501211 -3.04241730075358e-06 2.67281312825847e-05 3.43503013956073e-05 7.4342199773609e-05 1.3832490077194e-06 -3.04241730075358e-06 1.2089561894597e-05 -6.46849978309015e-06 7.39511772503479e-06 -3.90351431706567e-06 1.66377379402441e-05 2.67281312825847e-05 -6.46849978309015e-06 6.4835602317391e-05 1.13012771457371e-05 5.6548352535806e-05 1.93429463360717e-05 3.43503013956073e-05 7.39511772503479e-06 1.13012771457371e-05 4.91838699474506e-05 7.23497243051244e-05 7.48269242077693e-05 7.4342199773609e-05 -3.90351431706567e-06 5.6548352535806e-05 7.23497243051244e-05 0.000305783735011635 374 388 0 482 0 374 388 0 478 0 0 0 0 0 0 0 0 0 641 0 0 0 0 0 901 +938 940 0.997818604409021 -0.0577668726917406 -0.0319534210163865 0.149319144282628 0.0553211639846671 0.99581473371406 -0.072750154181126 0.108238656707537 0.0360222363355718 0.0708237568716336 0.996838198481565 -0.112486555248016 4.56804446248858e-05 1.64600966330697e-05 4.29598224707743e-06 -6.11609176352762e-06 1.87581173377912e-06 2.31738321621881e-06 1.64600966330697e-05 2.89308161162421e-05 2.17466963300415e-06 9.43736381733403e-07 -1.56098692292781e-06 4.09961688880714e-06 4.29598224707743e-06 2.17466963300415e-06 1.03636307494731e-05 3.78300104573427e-06 3.44231069608697e-06 -2.28527562891314e-06 -6.11609176352762e-06 9.43736381733403e-07 3.78300104573427e-06 6.72923400996322e-05 -3.19985339325094e-06 2.69024947238984e-05 1.87581173377912e-06 -1.56098692292781e-06 3.44231069608697e-06 -3.19985339325094e-06 1.34694873690731e-05 -3.56153203228636e-07 2.31738321621881e-06 4.09961688880714e-06 -2.28527562891314e-06 2.69024947238984e-05 -3.56153203228636e-07 0.000126021774107925 2974 3053 0 0 431 2948 3027 0 0 578 0 0 0 0 0 82 49 0 3859 0 0 0 0 0 252 +938 855 0.859290726290595 0.50420639094136 0.0859962966927672 -0.340749529404244 -0.49073998139683 0.860099028363633 -0.139297997353064 -0.129140377937696 -0.144200271739067 0.0774956562771346 0.986509353675147 0.544554635850123 4.51444651669082e-05 2.84127359269037e-05 9.2570059817017e-06 -1.73601149753353e-05 -1.41781642618352e-06 -2.54353566934637e-06 2.84127359269037e-05 5.70803115946565e-05 1.07746548939766e-06 -1.14238114681112e-05 -6.42347374711962e-06 -2.16526731343716e-05 9.2570059817017e-06 1.07746548939766e-06 1.40006094402144e-05 -8.66757634350194e-06 7.55387291086505e-06 -4.40008440473293e-06 -1.73601149753353e-05 -1.14238114681112e-05 -8.66757634350194e-06 5.71197663552371e-05 7.00104869985621e-06 -1.13622753417361e-06 -1.41781642618352e-06 -6.42347374711962e-06 7.55387291086505e-06 7.00104869985621e-06 2.69319255230094e-05 2.82185260864866e-06 -2.54353566934637e-06 -2.16526731343716e-05 -4.40008440473293e-06 -1.13622753417361e-06 2.82185260864866e-06 0.000110339946070434 997 1022 0 776 0 1037 1062 0 765 0 0 0 0 0 0 0 0 0 1214 0 202 202 0 0 677 +938 860 0.85487404716133 0.513015170092764 0.0774970886207965 -0.198055492296654 -0.502158217134755 0.855679747892778 -0.125097138297388 -0.25563887438909 -0.13048941893522 0.0680264970496355 0.989113192331952 0.790876526534406 5.98784907496197e-05 3.31223849053929e-05 -3.85532148536807e-06 1.0879323775425e-05 -8.91653520880165e-06 -1.91363719249831e-05 3.31223849053929e-05 0.000130751695474647 -1.12372819034539e-05 3.23284510474291e-05 3.30811688012854e-05 0.00011188783753803 -3.85532148536807e-06 -1.12372819034539e-05 1.41998316835271e-05 -1.21916039739972e-05 5.69716172351093e-06 -1.56707187843875e-05 1.0879323775425e-05 3.23284510474291e-05 -1.21916039739972e-05 6.46983108945143e-05 9.47210340304812e-06 8.96763439497171e-05 -8.91653520880165e-06 3.30811688012854e-05 5.69716172351093e-06 9.47210340304812e-06 4.40474940886882e-05 9.71592995804092e-05 -1.91363719249831e-05 0.00011188783753803 -1.56707187843875e-05 8.96763439497171e-05 9.71592995804092e-05 0.000536439595574471 581 598 0 674 0 588 605 0 667 0 0 0 0 0 0 0 0 0 506 0 0 0 0 0 615 +938 861 0.858917122584279 0.510918808003835 0.034976394317923 -0.192082175488943 -0.504484003181437 0.855889507756567 -0.113793853288536 -0.252994847516514 -0.0880753487962087 0.0800944576120086 0.992888518814808 0.785213222389487 7.54377992142195e-05 1.84274799817522e-05 2.84947416287671e-08 -1.39715564527524e-05 -4.99534861089525e-06 5.88027123775759e-06 1.84274799817522e-05 4.79965245545077e-05 2.73213532278286e-06 -1.02278487130012e-05 2.08390127914789e-07 -1.41444782176122e-05 2.84947416287671e-08 2.73213532278286e-06 1.20029793069803e-05 -6.14301154404986e-06 8.11935834261903e-06 -3.14335769242361e-06 -1.39715564527524e-05 -1.02278487130012e-05 -6.14301154404986e-06 5.18871639204478e-05 -4.83334146025614e-06 5.74722185170758e-07 -4.99534861089525e-06 2.08390127914789e-07 8.11935834261903e-06 -4.83334146025614e-06 2.89126623481802e-05 -7.68511977666169e-06 5.88027123775759e-06 -1.41444782176122e-05 -3.14335769242361e-06 5.74722185170758e-07 -7.68511977666169e-06 0.000108357791055469 516 530 0 583 0 516 530 0 575 0 0 0 0 0 0 0 0 0 467 0 0 0 0 0 459 +938 863 0.859681273204073 0.510738454256966 0.00971287009225113 -0.177044930779664 -0.508907894055011 0.857938594902659 -0.0703855293717773 -0.261630414017708 -0.0442816425928178 0.0555661652415947 0.997472574765655 0.83028962639706 0.000107061759256072 4.87371818189728e-05 -3.64635364189858e-06 3.61546937613575e-06 1.67725016892678e-05 9.72472640769914e-06 4.87371818189728e-05 0.000110320779340501 -3.45720853823239e-06 6.92289083092736e-06 8.37335168499951e-06 -2.4832283593476e-05 -3.64635364189858e-06 -3.45720853823239e-06 1.46625434725616e-05 -8.19647634568566e-06 8.93835372350714e-06 -4.26598242596642e-06 3.61546937613575e-06 6.92289083092736e-06 -8.19647634568566e-06 6.35989376271208e-05 -6.28176533760043e-06 2.07360355265752e-05 1.67725016892678e-05 8.37335168499951e-06 8.93835372350714e-06 -6.28176533760043e-06 4.19639241226622e-05 4.29763844505807e-05 9.72472640769914e-06 -2.4832283593476e-05 -4.26598242596642e-06 2.07360355265752e-05 4.29763844505807e-05 0.000238920100161024 356 362 0 550 0 356 362 0 540 0 0 0 0 0 0 0 0 0 534 0 0 0 0 0 328 +938 858 0.842917089344879 0.535997794102352 0.0468737155319439 -0.241873546969837 -0.530970260775675 0.842752994192308 -0.0885323271563112 -0.235682289537367 -0.0869560961759948 0.0497368625600054 0.994969789410974 0.697423929370324 7.07914817702865e-05 4.31672552959157e-05 -3.70770224409114e-06 -2.53672049325791e-06 -7.85659239127582e-06 -4.85895542304717e-05 4.31672552959157e-05 0.000152934969386475 -1.14972338695162e-05 3.01661367927632e-05 2.03205962270677e-05 3.7244523357162e-05 -3.70770224409114e-06 -1.14972338695162e-05 1.2867260404696e-05 -8.62561078995798e-06 5.08642076340636e-06 -3.81178089143492e-06 -2.53672049325791e-06 3.01661367927632e-05 -8.62561078995798e-06 6.53686927111483e-05 1.95804534196384e-05 6.6241324376464e-05 -7.85659239127582e-06 2.03205962270677e-05 5.08642076340636e-06 1.95804534196384e-05 4.2183376389214e-05 6.15461810747672e-05 -4.85895542304717e-05 3.7244523357162e-05 -3.81178089143492e-06 6.6241324376464e-05 6.15461810747672e-05 0.00036066652062499 525 547 0 696 0 538 560 0 684 0 0 0 0 0 0 0 0 0 803 0 16 16 0 0 622 +938 862 0.858894225366384 0.511835654822066 0.0180269821419344 -0.182259223287295 -0.509433628968558 0.857426751737661 -0.0727787268405355 -0.255441160430029 -0.0527075640511334 0.0533256772809364 0.997185180813637 0.812305461914699 7.2378777864215e-05 3.45454751595582e-05 -6.06850151534991e-07 8.72225422384344e-06 -5.9307436373223e-06 2.69719409590717e-06 3.45454751595582e-05 0.000118649200277298 -4.68578788064501e-07 4.93253014214548e-06 1.1159145977411e-05 -1.67640524383375e-05 -6.06850151534991e-07 -4.68578788064501e-07 1.42172931584627e-05 -7.11898667846997e-06 1.09725578280706e-05 2.55241614717082e-06 8.72225422384344e-06 4.93253014214548e-06 -7.11898667846997e-06 5.78508664444101e-05 -7.76211998087791e-06 8.37024170161592e-06 -5.9307436373223e-06 1.1159145977411e-05 1.09725578280706e-05 -7.76211998087791e-06 3.4147074146363e-05 1.9901177214063e-05 2.69719409590717e-06 -1.67640524383375e-05 2.55241614717082e-06 8.37024170161592e-06 1.9901177214063e-05 0.00019738926194281 432 441 0 558 0 432 441 0 551 0 0 0 0 0 0 0 0 0 512 0 0 0 0 0 674 +938 854 0.862951310888105 0.493350373297457 0.109180786788528 -0.397980717558981 -0.484023572000488 0.86913154169399 -0.101644207806039 -0.0751457036071734 -0.145038673409509 0.0348679279551971 0.988811413170237 0.461594392187183 4.26436845293388e-05 1.46708584448039e-05 3.05780798063966e-06 8.61021876318295e-06 8.0556976419737e-06 1.14818143675655e-05 1.46708584448039e-05 8.01419184822859e-05 -7.3614966576009e-06 2.35249991189235e-05 1.43415952445019e-05 5.23150591290745e-05 3.05780798063966e-06 -7.3614966576009e-06 1.31619065230817e-05 -8.36372048079201e-06 6.10996485698171e-06 -3.50001754404923e-06 8.61021876318295e-06 2.35249991189235e-05 -8.36372048079201e-06 4.9776259820735e-05 8.6287779259737e-06 4.6026701799916e-05 8.0556976419737e-06 1.43415952445019e-05 6.10996485698171e-06 8.6287779259737e-06 2.73570984156263e-05 4.26309469924798e-05 1.14818143675655e-05 5.23150591290745e-05 -3.50001754404923e-06 4.6026701799916e-05 4.26309469924798e-05 0.000296425529713986 1122 1146 0 851 0 1164 1188 0 840 0 0 0 0 0 0 0 0 0 1780 0 217 217 0 0 664 +938 853 0.870454161689645 0.480211555569279 0.10819618428998 -0.458138439825913 -0.4755374887089 0.877124366879446 -0.0672081978538609 -0.0130984899981001 -0.127175662882531 0.00705031375641212 0.991855152654018 0.385258853834122 3.42870625061413e-05 8.87337209237133e-06 2.02685406066004e-06 -2.67518933809852e-06 -4.33476740533813e-07 5.93705724378035e-06 8.87337209237133e-06 5.56145382770656e-05 1.2484846352293e-06 3.05385010235107e-06 1.47560198664263e-07 7.72873238856803e-06 2.02685406066004e-06 1.2484846352293e-06 9.8924626527184e-06 -4.04246816937174e-06 4.99325210107717e-06 -4.17819545819948e-06 -2.67518933809852e-06 3.05385010235107e-06 -4.04246816937174e-06 3.32039951467162e-05 3.63932713843134e-06 1.45550708684783e-05 -4.33476740533813e-07 1.47560198664263e-07 4.99325210107717e-06 3.63932713843134e-06 1.77865186375342e-05 1.21373927378865e-05 5.93705724378035e-06 7.72873238856803e-06 -4.17819545819948e-06 1.45550708684783e-05 1.21373927378865e-05 0.00015802287574816 1188 1212 0 798 0 1239 1263 0 781 0 0 0 0 0 0 0 0 0 2186 0 226 226 0 0 710 +938 934 0.98311145577472 0.1818475396811 -0.0205751752469168 -0.159597766087104 -0.181941311469722 0.983305502393112 -0.00276552781697518 -0.171466615293771 0.0197287786035593 0.00646229644627535 0.999784483786107 0.44102783968939 0.000118469334616237 9.15975657951329e-06 5.01540297677818e-07 1.13501428193302e-05 7.44093747770648e-06 2.18371456737036e-05 9.15975657951329e-06 0.000100985512414379 5.43213696205019e-06 1.05781747458648e-05 2.79080788640075e-06 6.45670087104352e-05 5.01540297677818e-07 5.43213696205019e-06 1.30473480189114e-05 -9.67317025097247e-07 6.47780621877907e-06 2.7415010224254e-06 1.13501428193302e-05 1.05781747458648e-05 -9.67317025097247e-07 0.000105578361677018 8.40855301503359e-06 5.27511557591951e-05 7.44093747770648e-06 2.79080788640075e-06 6.47780621877907e-06 8.40855301503359e-06 1.75223245038914e-05 3.82176756277848e-07 2.18371456737036e-05 6.45670087104352e-05 2.7415010224254e-06 5.27511557591951e-05 3.82176756277848e-07 0.000306301249377033 1320 1323 0 316 0 1357 1360 0 302 0 0 0 0 0 0 0 0 0 2509 0 32 32 0 0 331 +938 866 0.85235008969778 0.522963850366904 -0.00285233266106609 -0.172695229107715 -0.521134733385673 0.848886917127936 -0.0883718936544462 -0.271942754698577 -0.043793997890468 0.0768102411039818 0.996083466688569 0.815137078264531 0.000126445479871323 4.48326789051202e-06 5.47945548303707e-06 -3.85538413937942e-05 1.6277310387726e-05 7.14174914780386e-05 4.48326789051202e-06 0.000186460433150573 -1.9680177930428e-05 8.75084986764352e-05 5.45637622982477e-05 0.000130896475041711 5.47945548303707e-06 -1.9680177930428e-05 1.90397863475306e-05 -1.96596038344849e-05 6.52618945344032e-06 -4.68350449296684e-06 -3.85538413937942e-05 8.75084986764352e-05 -1.96596038344849e-05 0.000133008806912788 2.86326738588933e-05 8.57134572263534e-05 1.6277310387726e-05 5.45637622982477e-05 6.52618945344032e-06 2.86326738588933e-05 6.7214370955321e-05 0.000100215665722331 7.14174914780386e-05 0.000130896475041711 -4.68350449296684e-06 8.57134572263534e-05 0.000100215665722331 0.000435444284822404 327 339 0 530 0 327 339 0 523 0 0 0 0 0 0 0 0 0 553 0 0 0 0 0 381 +938 865 0.854321598667194 0.519464639679113 -0.0170614821682729 -0.177876935962744 -0.518924387361446 0.850669789549152 -0.0841331643880678 -0.273850280381544 -0.0291905164784299 0.0807303986825932 0.996308444446935 0.818559358911311 8.27128212966791e-05 -8.01350394759481e-06 2.22043917186916e-06 -2.04420656328e-05 -2.85670934878432e-06 -1.50977678778607e-05 -8.01350394759481e-06 7.23893372082403e-05 -5.75347242448375e-06 2.36057082202371e-05 1.04716058922783e-05 -6.93994679287666e-06 2.22043917186916e-06 -5.75347242448375e-06 1.32274115746861e-05 -9.13321085485532e-06 8.28909320494541e-06 -2.89099693539119e-06 -2.04420656328e-05 2.36057082202371e-05 -9.13321085485532e-06 9.09921993192573e-05 3.20874596031074e-06 4.54172653074527e-05 -2.85670934878432e-06 1.04716058922783e-05 8.28909320494541e-06 3.20874596031074e-06 3.75350398790366e-05 2.87071855778199e-05 -1.50977678778607e-05 -6.93994679287666e-06 -2.89099693539119e-06 4.54172653074527e-05 2.87071855778199e-05 0.000155776737713659 321 331 0 499 0 321 331 0 489 0 0 0 0 0 0 0 0 0 448 0 0 0 0 0 608 +938 868 0.834919867302675 0.550022328028334 0.0196023940776521 -0.160974682507031 -0.544453647036718 0.830627318937173 -0.116741095007976 -0.284708614585563 -0.0804924928903339 0.0867968646065995 0.992968913351653 0.841180543675949 8.93556388369283e-05 2.1730873728716e-05 -6.26353225568326e-07 -1.44404560906182e-05 -4.0034202226283e-06 -1.20268327232503e-05 2.1730873728716e-05 7.58897772047202e-05 -3.04215722153131e-06 3.89065044610614e-07 1.14911861627582e-05 3.37050284761542e-05 -6.26353225568326e-07 -3.04215722153131e-06 1.27485621049521e-05 -8.17837353161321e-06 8.14693108599159e-06 -5.23194487746492e-06 -1.44404560906182e-05 3.89065044610614e-07 -8.17837353161321e-06 6.46751513259089e-05 -7.45360598976988e-06 4.45308217710448e-05 -4.0034202226283e-06 1.14911861627582e-05 8.14693108599159e-06 -7.45360598976988e-06 3.55691264906346e-05 3.94767678961492e-05 -1.20268327232503e-05 3.37050284761542e-05 -5.23194487746492e-06 4.45308217710448e-05 3.94767678961492e-05 0.000331339821180719 349 359 0 537 0 349 359 0 531 0 0 0 0 0 0 0 0 0 345 0 0 0 0 0 613 +938 859 0.845545854163261 0.52623814105599 0.0901422620376129 -0.200525866261851 -0.518145764178026 0.849526418248889 -0.0991455080252413 -0.254021635565924 -0.128752380838921 0.0371252420214383 0.990981604689592 0.771022483594749 6.0767241684499e-05 3.07460961603005e-06 -2.60310903823333e-06 2.17249613271647e-06 -9.11116525479067e-06 5.72122339187089e-06 3.07460961603005e-06 4.60641771876779e-05 7.1937870245403e-07 1.02316307784127e-06 2.03077210721741e-06 -2.04869995369253e-05 -2.60310903823333e-06 7.1937870245403e-07 1.20504807030154e-05 -5.31301788169045e-06 7.76282764935389e-06 -2.23636812730152e-06 2.17249613271647e-06 1.02316307784127e-06 -5.31301788169045e-06 4.67349549169441e-05 -3.68527539810629e-06 6.51771279379945e-06 -9.11116525479067e-06 2.03077210721741e-06 7.76282764935389e-06 -3.68527539810629e-06 2.73730319649396e-05 5.89343669777637e-06 5.72122339187089e-06 -2.04869995369253e-05 -2.23636812730152e-06 6.51771279379945e-06 5.89343669777637e-06 0.000108210206833093 571 580 0 712 0 578 587 0 701 0 0 0 0 0 0 0 0 0 731 0 5 5 0 0 581 +938 869 0.829221170781853 0.558346522131852 0.0253260962337023 -0.174097260957174 -0.552548515065435 0.825748163563104 -0.113270070500305 -0.284512631048092 -0.0841569273806771 0.0799320436084694 0.993241400656667 0.82046955223506 8.77565744132736e-05 3.73044288716757e-05 -5.17496632391005e-07 -3.47933482289331e-06 -1.01428183100134e-05 -2.06062859333458e-06 3.73044288716757e-05 0.000108993699683964 -2.9567914252285e-06 -3.39468055555234e-06 3.25287213445087e-06 -7.87782273039026e-07 -5.17496632391005e-07 -2.9567914252285e-06 1.40639192050609e-05 -9.11413208962551e-06 9.18484963561548e-06 -1.03963993598488e-07 -3.47933482289331e-06 -3.39468055555234e-06 -9.11413208962551e-06 5.60944275601323e-05 -7.30032705228188e-06 3.2284033999058e-05 -1.01428183100134e-05 3.25287213445087e-06 9.18484963561548e-06 -7.30032705228188e-06 3.76496756838376e-05 4.12814888069577e-05 -2.06062859333458e-06 -7.87782273039026e-07 -1.03963993598488e-07 3.2284033999058e-05 4.12814888069577e-05 0.000271837285631265 335 349 0 560 0 335 349 0 554 0 0 0 0 0 0 0 0 0 327 0 0 0 0 0 616 +938 857 0.847938877574221 0.5258954035049 0.0665859179601035 -0.269718878758159 -0.518158759315845 0.848787210504621 -0.10522248537289 -0.214582074864943 -0.11185329696721 0.0547201595045445 0.992216984384647 0.667177090760571 6.82646499547319e-05 4.60926208487819e-05 -3.01027967094071e-06 4.31568042583799e-06 7.11179652222749e-06 5.60135030159503e-06 4.60926208487819e-05 9.44174799922537e-05 -4.93499971421631e-06 6.4110780594011e-06 1.68269812450019e-05 3.4285567879355e-05 -3.01027967094071e-06 -4.93499971421631e-06 1.39673578927477e-05 -1.04828489669143e-05 3.80753235800844e-06 -1.11333483118777e-05 4.31568042583799e-06 6.4110780594011e-06 -1.04828489669143e-05 6.07140138952175e-05 1.57266040489629e-05 5.72258445491096e-05 7.11179652222749e-06 1.68269812450019e-05 3.80753235800844e-06 1.57266040489629e-05 3.68233868212182e-05 5.31095964844001e-05 5.60135030159503e-06 3.4285567879355e-05 -1.11333483118777e-05 5.72258445491096e-05 5.31095964844001e-05 0.000247174872234232 726 741 0 747 0 750 765 0 738 0 0 0 0 0 0 0 0 0 833 0 73 73 0 0 412 +938 856 0.852594577862018 0.512634360059997 0.101432236917882 -0.308779364527475 -0.496161385068513 0.855034656204603 -0.150796606911332 -0.171969018428044 -0.164031599904355 0.0782416102528179 0.983347285885238 0.608115202859607 5.81949181194306e-05 1.92567741622004e-05 4.65704239496068e-06 -6.05136767306436e-06 -1.21870605906998e-06 -5.94045451266869e-06 1.92567741622004e-05 6.54909864377026e-05 -8.75679238883776e-07 -1.37858825062746e-06 3.16877114905938e-06 -2.26077179142972e-06 4.65704239496068e-06 -8.75679238883776e-07 1.12857984104599e-05 -7.81609302577985e-06 5.21662117429389e-06 1.19156671472737e-06 -6.05136767306436e-06 -1.37858825062746e-06 -7.81609302577985e-06 5.75092855753316e-05 8.56558794331458e-06 -1.88257972627717e-06 -1.21870605906998e-06 3.16877114905938e-06 5.21662117429389e-06 8.56558794331458e-06 2.88140324766837e-05 1.70500321101142e-05 -5.94045451266869e-06 -2.26077179142972e-06 1.19156671472737e-06 -1.88257972627717e-06 1.70500321101142e-05 0.00016388928360871 935 958 0 749 0 969 992 0 736 0 0 0 0 0 0 0 0 0 1074 0 149 149 0 0 712 +938 864 0.86439655343771 0.50273824672092 -0.00853543724618494 -0.176559806283337 -0.502228037526455 0.862453485976121 -0.0627772478686512 -0.261776118696861 -0.0241991059201478 0.0585511725895486 0.997991063818236 0.803712823176017 0.00011520749042146 1.16342506677531e-05 -3.52596537024347e-06 -1.82105344406439e-05 3.33346295547749e-06 8.42531027468207e-06 1.16342506677531e-05 8.46228342801792e-05 -8.99188309266893e-07 9.87464307224093e-06 7.09943269861057e-06 -8.9053852588749e-06 -3.52596537024347e-06 -8.99188309266893e-07 1.21010471116984e-05 -6.67212142621627e-06 7.9490553729162e-06 -3.86433126387267e-06 -1.82105344406439e-05 9.87464307224093e-06 -6.67212142621627e-06 7.61955791419749e-05 -8.61620142115125e-06 2.16981497167844e-05 3.33346295547749e-06 7.09943269861057e-06 7.9490553729162e-06 -8.61620142115125e-06 3.43291134345979e-05 2.08459991783202e-05 8.42531027468207e-06 -8.9053852588749e-06 -3.86433126387267e-06 2.16981497167844e-05 2.08459991783202e-05 0.000170809834087149 368 376 0 509 0 368 376 0 501 0 0 0 0 0 0 0 0 0 661 0 0 0 0 0 603 +938 867 0.844768617311754 0.534986565984568 0.0124642457143365 -0.157098082532297 -0.530465519950628 0.84024444129076 -0.112230169845227 -0.279801845811958 -0.070514646341716 0.0881966728171675 0.993604061764687 0.848856796550082 8.69132807081938e-05 1.90590339965632e-05 -5.288091326155e-06 -2.96022327096369e-06 1.78372281491842e-06 -1.73107287077352e-05 1.90590339965632e-05 9.57465967885087e-05 -3.8471923977126e-06 2.0030807816454e-05 8.27719555809822e-06 3.83363138277057e-06 -5.288091326155e-06 -3.8471923977126e-06 1.40087106031609e-05 -1.05276001452547e-05 8.57036536717844e-06 -3.22424794552488e-06 -2.96022327096369e-06 2.0030807816454e-05 -1.05276001452547e-05 7.92278600544906e-05 -6.88392654802962e-06 4.0811913324833e-05 1.78372281491842e-06 8.27719555809822e-06 8.57036536717844e-06 -6.88392654802962e-06 3.35172031642385e-05 1.4908262598807e-05 -1.73107287077352e-05 3.83363138277057e-06 -3.22424794552488e-06 4.0811913324833e-05 1.4908262598807e-05 0.000190526938121502 322 336 0 525 0 322 336 0 522 0 0 0 0 0 0 0 0 0 350 0 0 0 0 0 409 +938 870 0.828838142375899 0.558951673720155 0.0245022486377744 -0.153566391995466 -0.553359349298424 0.825436438232282 -0.111571129699523 -0.291526597600556 -0.0825879185286429 0.0789158595203856 0.993454338572873 0.859206860828505 6.81654773547672e-05 6.67560351345155e-06 2.86494814685881e-06 -1.13259782414595e-06 -2.1822646476391e-06 3.67996697119292e-06 6.67560351345155e-06 7.89627156961476e-05 -9.64264373754518e-06 1.09892751243481e-05 1.50994014477588e-06 -2.44516001989857e-05 2.86494814685881e-06 -9.64264373754518e-06 1.4924541658897e-05 -1.0223103168774e-05 9.32395139109661e-06 3.52965461959919e-06 -1.13259782414595e-06 1.09892751243481e-05 -1.0223103168774e-05 8.08708919909127e-05 5.33750300868045e-06 2.98896291248816e-05 -2.1822646476391e-06 1.50994014477588e-06 9.32395139109661e-06 5.33750300868045e-06 3.84102531163599e-05 3.38431622950436e-05 3.67996697119292e-06 -2.44516001989857e-05 3.52965461959919e-06 2.98896291248816e-05 3.38431622950436e-05 0.000224021204928151 348 360 0 557 0 348 360 0 552 0 0 0 0 0 0 0 0 0 283 0 0 0 0 0 392 +938 871 0.83079217790981 0.556577764980709 0.00235555788592514 -0.162744515747416 -0.553832736053176 0.827100111294379 -0.0957846875689388 -0.292716777569397 -0.0552599095161045 0.0782725841269158 0.995399289217331 0.853661767100174 6.81532575652368e-05 1.75197574250309e-05 2.88380139963649e-06 -1.52126084817435e-05 -3.72866092786198e-06 -6.28036875870068e-06 1.75197574250309e-05 8.1319674667437e-05 -1.88310087550565e-06 -6.82439134387104e-07 2.02314285798064e-06 -2.94042495459723e-05 2.88380139963649e-06 -1.88310087550565e-06 1.5714649571175e-05 -1.19301177043066e-05 1.24208791471849e-05 -2.30495871270915e-06 -1.52126084817435e-05 -6.82439134387104e-07 -1.19301177043066e-05 7.55100934981946e-05 -6.7673713375242e-06 3.15548064067712e-05 -3.72866092786198e-06 2.02314285798064e-06 1.24208791471849e-05 -6.7673713375242e-06 3.47580864470292e-05 2.28825104853509e-05 -6.28036875870068e-06 -2.94042495459723e-05 -2.30495871270915e-06 3.15548064067712e-05 2.28825104853509e-05 0.000176448806227757 307 318 0 536 0 307 318 0 530 0 0 0 0 0 0 0 0 0 352 0 0 0 0 0 614 +938 873 0.843069915628617 0.537631137257297 -0.0136336940475455 -0.159674859087768 -0.535901410231725 0.837686952694538 -0.105310245451178 -0.276907430806108 -0.0451972994061038 0.0960902156141011 0.994345953172049 0.841846735832241 0.000131664668613907 4.01804814151914e-05 3.00295957735884e-07 -1.81039772963619e-05 5.08594606448005e-07 2.38582315383411e-05 4.01804814151914e-05 9.05398731916459e-05 -3.99120588667662e-06 2.56369134177005e-06 1.58539064682386e-05 1.99471277915712e-05 3.00295957735884e-07 -3.99120588667662e-06 1.33039645582967e-05 -7.14883295979948e-06 9.18708283426631e-06 -9.07502133707077e-07 -1.81039772963619e-05 2.56369134177005e-06 -7.14883295979948e-06 7.13692021624442e-05 -3.86933139372575e-06 4.3448316013792e-05 5.08594606448005e-07 1.58539064682386e-05 9.18708283426631e-06 -3.86933139372575e-06 5.04820161493983e-05 4.75735849748829e-05 2.38582315383411e-05 1.99471277915712e-05 -9.07502133707077e-07 4.3448316013792e-05 4.75735849748829e-05 0.000245149563314873 305 316 0 493 0 305 316 0 484 0 0 0 0 0 0 0 0 0 330 0 0 0 0 0 650 +938 874 0.840622364601656 0.541394403742547 -0.0156888408677096 -0.137824202118144 -0.540241054460874 0.836060823078375 -0.0956133002699619 -0.282576026763845 -0.0386476804805103 0.0888504344939438 0.99529490960404 0.880556218647093 7.09918246414182e-05 2.35885244301141e-05 -4.10596844927288e-08 3.96759932244587e-06 5.02306867093582e-06 3.38631081201105e-05 2.35885244301141e-05 8.10287050213502e-05 6.75679653502354e-07 1.1383808175484e-05 2.24613956399287e-05 2.31697483919678e-05 -4.10596844927288e-08 6.75679653502354e-07 1.35823235802591e-05 -1.17378822701818e-05 8.72160534084268e-06 -8.8362853877445e-06 3.96759932244587e-06 1.1383808175484e-05 -1.17378822701818e-05 8.32679531510952e-05 4.41866501339201e-07 6.83073107386568e-05 5.02306867093582e-06 2.24613956399287e-05 8.72160534084268e-06 4.41866501339201e-07 5.6568422617663e-05 4.66600056387831e-05 3.38631081201105e-05 2.31697483919678e-05 -8.8362853877445e-06 6.83073107386568e-05 4.66600056387831e-05 0.000314703181463185 271 281 0 447 0 271 281 0 444 0 0 0 0 0 0 0 0 0 214 0 0 0 0 0 598 +938 876 0.83683845832537 0.54741925569984 -0.00579250866645893 -0.127850252909265 -0.544841708044015 0.831773306495476 -0.106304655482546 -0.288342375870822 -0.0533751612952789 0.0921158243225167 0.994316733775554 0.887427039278009 9.26838168574204e-05 2.85993380863958e-05 -9.1688612381504e-06 1.22472353056317e-05 4.23503968779834e-06 -2.65416077515921e-06 2.85993380863958e-05 7.21623835278312e-05 -1.64856729074757e-07 4.20771098313028e-06 -5.43255228067798e-07 -3.97120807514869e-05 -9.1688612381504e-06 -1.64856729074757e-07 1.51696390576477e-05 -9.64655940446889e-06 8.40155683583607e-06 5.64413952250075e-07 1.22472353056317e-05 4.20771098313028e-06 -9.64655940446889e-06 7.05396857314702e-05 -1.69402199823721e-05 1.08188953848784e-05 4.23503968779834e-06 -5.43255228067798e-07 8.40155683583607e-06 -1.69402199823721e-05 4.84552719409838e-05 9.33466517797029e-06 -2.65416077515921e-06 -3.97120807514869e-05 5.64413952250075e-07 1.08188953848784e-05 9.33466517797029e-06 0.000178739951316379 249 256 0 475 0 249 256 0 472 0 0 0 0 0 0 0 0 0 264 0 0 0 0 0 428 +938 872 0.836884188452115 0.547350747548953 -0.00565811598037988 -0.152533047319624 -0.545215457010592 0.832611972493465 -0.0974546494389709 -0.284272361831785 -0.0486308601155209 0.0846431474966803 0.9952238828657 0.872091824129588 0.000106336290731249 6.12814549587709e-05 2.20009663605358e-06 -1.14707122972919e-05 -3.45847026458367e-06 1.98651834733148e-05 6.12814549587709e-05 0.000103605268945112 1.23508716512854e-06 9.98027071932346e-07 4.69300496578115e-06 -1.08257323654918e-05 2.20009663605358e-06 1.23508716512854e-06 1.38455586771836e-05 -9.9477151343136e-06 9.15872284321013e-06 -1.5022254073453e-06 -1.14707122972919e-05 9.98027071932346e-07 -9.9477151343136e-06 7.16004259444836e-05 8.08171000285157e-07 3.64801470462886e-05 -3.45847026458367e-06 4.69300496578115e-06 9.15872284321013e-06 8.08171000285157e-07 4.43111017218206e-05 5.01522427206739e-05 1.98651834733148e-05 -1.08257323654918e-05 -1.5022254073453e-06 3.64801470462886e-05 5.01522427206739e-05 0.00036852934137594 270 278 0 502 0 270 278 0 495 0 0 0 0 0 0 0 0 0 336 0 0 0 0 0 612 +938 877 0.837531789179355 0.546298824938443 -0.00990434171993868 -0.12945969205843 -0.543845185327162 0.831749153678189 -0.111470891949789 -0.290302709274862 -0.0526584894437114 0.0987468441343492 0.993718342521166 0.891608338734503 8.53034507786007e-05 2.46890347147761e-05 -2.10143933741635e-06 -1.09682097257252e-05 -1.40441267281673e-05 -4.55285055554032e-05 2.46890347147761e-05 6.702855355013e-05 -1.08425764198335e-06 1.70216321375301e-06 4.03882558227627e-07 -4.79741906516475e-05 -2.10143933741635e-06 -1.08425764198335e-06 1.27200041373116e-05 -8.92513690097306e-06 9.46988130210875e-06 -3.41523632584215e-06 -1.09682097257252e-05 1.70216321375301e-06 -8.92513690097306e-06 7.95005340464804e-05 -8.50751493171733e-06 4.06278120533148e-05 -1.40441267281673e-05 4.03882558227627e-07 9.46988130210875e-06 -8.50751493171733e-06 4.02710358445778e-05 1.7926440185747e-05 -4.55285055554032e-05 -4.79741906516475e-05 -3.41523632584215e-06 4.06278120533148e-05 1.7926440185747e-05 0.000188916932018423 253 261 0 449 0 253 261 0 443 0 0 0 0 0 0 0 0 0 164 0 0 0 0 0 647 +938 886 0.833779949900216 0.55188972085686 0.0151238605167558 -0.143175412267795 -0.54785992463893 0.830457998380582 -0.100940655339379 -0.282573794113044 -0.0682678410308906 0.075876537468803 0.994777489161635 0.865386722325284 7.69064950527524e-05 1.35119115959993e-05 -1.94548772981186e-06 -1.19899575513407e-06 -6.31743603489726e-06 6.02415093712107e-06 1.35119115959993e-05 7.04378884992216e-05 -6.36501158837642e-06 5.73801485891636e-06 9.1559420456807e-06 1.5071113137766e-05 -1.94548772981186e-06 -6.36501158837642e-06 1.46913106711664e-05 -7.76884541500611e-06 8.70233226810481e-06 8.76166916291437e-07 -1.19899575513407e-06 5.73801485891636e-06 -7.76884541500611e-06 6.25745470168193e-05 -2.69880357645192e-06 2.95174579763391e-05 -6.31743603489726e-06 9.1559420456807e-06 8.70233226810481e-06 -2.69880357645192e-06 3.54982165538796e-05 3.29731903134189e-05 6.02415093712107e-06 1.5071113137766e-05 8.76166916291437e-07 2.95174579763391e-05 3.29731903134189e-05 0.000230449505245251 278 288 0 521 0 278 288 0 517 0 0 0 0 0 0 0 0 0 336 0 0 0 0 0 603 +938 885 0.834284387101919 0.551280759728817 0.00768670220534318 -0.152969635103578 -0.547990512198455 0.830677057252257 -0.0983972819502932 -0.279423603220761 -0.0606296955167171 0.0778790761857721 0.995117525478273 0.857636790145136 9.02276235934117e-05 7.76186547093744e-05 1.36439910700663e-07 2.58105713955391e-06 8.4262740892906e-06 1.04923619119527e-05 7.76186547093744e-05 0.00018207201887966 -8.22079311620427e-06 1.1383377079498e-05 6.61008503785176e-06 -2.91273904890722e-05 1.36439910700663e-07 -8.22079311620427e-06 1.38935052662089e-05 -7.7638576106178e-06 7.04066971630587e-06 2.31311863198161e-06 2.58105713955391e-06 1.1383377079498e-05 -7.7638576106178e-06 6.81218990530785e-05 1.75570532642859e-06 8.85712969947158e-06 8.4262740892906e-06 6.61008503785176e-06 7.04066971630587e-06 1.75570532642859e-06 4.61548948371339e-05 2.51862503265656e-05 1.04923619119527e-05 -2.91273904890722e-05 2.31311863198161e-06 8.85712969947158e-06 2.51862503265656e-05 0.000222534618746846 303 315 0 521 0 303 315 0 515 0 0 0 0 0 0 0 0 0 281 0 0 0 0 0 620 +938 875 0.836165126262486 0.548369697512903 -0.0108883640666616 -0.134789482301411 -0.546366265929265 0.831041647656502 -0.104181012256928 -0.287222427586924 -0.0480810261636771 0.0930615640851479 0.994498748220969 0.882740715360804 0.000126326704395536 6.88210291644937e-05 2.47487764143821e-06 -3.39932367827598e-05 1.27341763574003e-05 0.000137647777609446 6.88210291644937e-05 0.000109206147819788 2.8860235046003e-06 -1.60192588099108e-05 1.56354307326405e-05 0.000148045404149311 2.47487764143821e-06 2.8860235046003e-06 1.41823471370918e-05 -1.08931911758069e-05 7.27807761847557e-06 -1.61462782789698e-06 -3.39932367827598e-05 -1.60192588099108e-05 -1.08931911758069e-05 9.87232782703194e-05 -1.77175976010432e-06 -3.08480927735011e-06 1.27341763574003e-05 1.56354307326405e-05 7.27807761847557e-06 -1.77175976010432e-06 4.83190638723261e-05 9.26143583807774e-05 0.000137647777609446 0.000148045404149311 -1.61462782789698e-06 -3.08480927735011e-06 9.26143583807774e-05 0.000856679392853147 255 262 0 468 0 255 262 0 459 0 0 0 0 0 0 0 0 0 254 0 0 0 0 0 648 +938 878 0.835230896592367 0.549586764041677 -0.0185401771218228 -0.144702706814289 -0.548309992228382 0.82978171828541 -0.104011789821271 -0.276065754880493 -0.0417792029605935 0.0970396248421767 0.994403242859991 0.863320536456278 5.63617589345803e-05 2.36204895578152e-05 -1.86595893794783e-06 3.25569157187291e-06 -6.5881139865977e-06 -7.60648999730538e-06 2.36204895578152e-05 8.10691757933943e-05 -4.57077077238569e-06 1.69734799226356e-05 1.57397826158902e-06 -3.36868907328739e-05 -1.86595893794783e-06 -4.57077077238569e-06 1.30863867797492e-05 -9.36983578475501e-06 8.02513878929442e-06 -3.41759771869713e-06 3.25569157187291e-06 1.69734799226356e-05 -9.36983578475501e-06 8.47350620837273e-05 1.02457606579956e-07 4.93019165314314e-05 -6.5881139865977e-06 1.57397826158902e-06 8.02513878929442e-06 1.02457606579956e-07 3.24774137750276e-05 2.60394548243831e-05 -7.60648999730538e-06 -3.36868907328739e-05 -3.41759771869713e-06 4.93019165314314e-05 2.60394548243831e-05 0.000201890604325713 232 240 0 445 0 232 240 0 441 0 0 0 0 0 0 0 0 0 297 0 0 0 0 0 669 +938 887 0.833730254734994 0.551048886829618 0.0351992423691155 -0.15176111220419 -0.546424098700693 0.832547391138622 -0.0910249738665724 -0.282933482669593 -0.079464247927333 0.0566565603625325 0.995226339818852 0.853558800650455 7.37319992204628e-05 1.69768806958676e-05 6.99849550046139e-06 -2.6776819316985e-05 -5.48832860432076e-06 -9.43714977194389e-06 1.69768806958676e-05 8.27012281340482e-05 -2.7269786818147e-06 1.85644953077085e-06 8.83717581629248e-06 -2.97418013900238e-05 6.99849550046139e-06 -2.7269786818147e-06 1.34184884090725e-05 -1.06049980945228e-05 7.77541496239938e-06 1.6155079574095e-06 -2.6776819316985e-05 1.85644953077085e-06 -1.06049980945228e-05 9.7740560203199e-05 6.31099992416561e-06 2.1780247229478e-06 -5.48832860432076e-06 8.83717581629248e-06 7.77541496239938e-06 6.31099992416561e-06 3.30841263228682e-05 2.21986999177227e-07 -9.43714977194389e-06 -2.97418013900238e-05 1.6155079574095e-06 2.1780247229478e-06 2.21986999177227e-07 0.000119516474525369 330 342 0 559 0 330 342 0 552 0 0 0 0 0 0 0 0 0 394 0 0 0 0 0 602 +938 884 0.834000089055491 0.551724593793803 0.00661997420667285 -0.146397861979921 -0.548330809663544 0.830087037872944 -0.101433883535252 -0.279693057089641 -0.0614587229704272 0.0809659320849478 0.99482025673609 0.860096029580133 0.000193332491526372 0.000156790978237104 4.58616396205148e-06 -1.55748064793983e-05 3.63460844737635e-05 0.000194874552171355 0.000156790978237104 0.000199902200870682 1.68328730354113e-06 -1.20569475621552e-05 3.46010205394504e-05 0.000153383725349873 4.58616396205148e-06 1.68328730354113e-06 1.43127800023061e-05 -8.81099036408012e-06 9.79238934464468e-06 5.6628893735104e-06 -1.55748064793983e-05 -1.20569475621552e-05 -8.81099036408012e-06 7.95626942970562e-05 -9.14988705097361e-06 -1.45093127480377e-05 3.63460844737635e-05 3.46010205394504e-05 9.79238934464468e-06 -9.14988705097361e-06 4.82812246706355e-05 8.63232424060579e-05 0.000194874552171355 0.000153383725349873 5.6628893735104e-06 -1.45093127480377e-05 8.63232424060579e-05 0.000645259553076134 300 310 0 521 0 300 310 0 513 0 0 0 0 0 0 0 0 0 346 0 0 0 0 0 568 +939 855 0.830912562003134 0.547291112006449 0.100283363645882 -0.41446500750549 -0.534101711023368 0.835062580599031 -0.1319312274073 -0.154023273259129 -0.155947672593398 0.0560617980627736 0.986173107629016 0.613119295648092 4.6154932815304e-05 8.27556839590562e-06 5.96690174502187e-06 -4.77069387922989e-06 3.13337741804385e-06 -9.32645879599552e-06 8.27556839590562e-06 4.62302512675883e-05 -4.26691478629434e-06 3.02446764571961e-06 2.791446383199e-06 -1.1678064645903e-05 5.96690174502187e-06 -4.26691478629434e-06 1.23516642030846e-05 -7.26906285972696e-06 5.95059661551205e-06 -2.03124248896119e-06 -4.77069387922989e-06 3.02446764571961e-06 -7.26906285972696e-06 4.53777983573315e-05 3.53074582268668e-06 6.17419780814732e-06 3.13337741804385e-06 2.791446383199e-06 5.95059661551205e-06 3.53074582268668e-06 2.3265525467924e-05 8.41716547236783e-06 -9.32645879599552e-06 -1.1678064645903e-05 -2.03124248896119e-06 6.17419780814732e-06 8.41716547236783e-06 8.70577921475902e-05 904 929 0 814 0 937 962 0 802 0 0 0 0 0 0 0 0 0 929 0 290 290 0 0 466 +939 860 0.82506574460001 0.556744233242119 0.09644882497613 -0.262825759116419 -0.546216389544469 0.829567090034936 -0.116043521680335 -0.284897283218455 -0.14461733257337 0.0430616056669245 0.988550213816552 0.860699672995394 8.05418029259479e-05 2.5620235602898e-05 -5.4542478619367e-06 -8.24169562924292e-06 -1.10640927187458e-05 -3.79684367922142e-05 2.5620235602898e-05 6.69991294813973e-05 -3.00211777132443e-06 -9.44685817143285e-06 5.97667762274146e-07 -2.67096641830159e-05 -5.4542478619367e-06 -3.00211777132443e-06 1.37997761208994e-05 -8.73998572872415e-06 9.1753437284024e-06 1.32658878542485e-06 -8.24169562924292e-06 -9.44685817143285e-06 -8.73998572872415e-06 5.66058971258078e-05 -6.89343562684578e-06 1.49916252093699e-05 -1.10640927187458e-05 5.97667762274146e-07 9.1753437284024e-06 -6.89343562684578e-06 2.63706932937522e-05 4.30913627163763e-06 -3.79684367922142e-05 -2.67096641830159e-05 1.32658878542485e-06 1.49916252093699e-05 4.30913627163763e-06 0.000126389823226076 541 558 0 699 0 547 564 0 691 0 0 0 0 0 0 0 0 0 259 0 5 5 0 0 411 +939 861 0.830860612394159 0.554463601061898 0.0473366440453408 -0.271153623052281 -0.547822044958966 0.829915573158204 -0.105504258143765 -0.2851713502941 -0.0977836889720311 0.0617272753891071 0.993291545138716 0.842452852533989 9.85458457090253e-05 6.94384954704395e-05 -7.88141857399969e-06 2.25341267165594e-06 9.92242559706933e-06 7.06201554608841e-05 6.94384954704395e-05 0.000137622223170694 -8.10772952557055e-06 3.0009391254017e-05 4.2851702300567e-05 0.000209388854955073 -7.88141857399969e-06 -8.10772952557055e-06 1.24831757605627e-05 -9.83389919959821e-06 5.50691198103103e-06 -1.96991520823916e-05 2.25341267165594e-06 3.0009391254017e-05 -9.83389919959821e-06 8.08277239828306e-05 1.39718474400515e-05 0.000137413541017711 9.92242559706933e-06 4.2851702300567e-05 5.50691198103103e-06 1.39718474400515e-05 5.73408063458191e-05 0.000145035240102234 7.06201554608841e-05 0.000209388854955073 -1.96991520823916e-05 0.000137413541017711 0.000145035240102234 0.000906380109420752 485 499 0 603 0 490 504 0 599 0 0 0 0 0 0 0 0 0 258 0 3 3 0 0 385 +939 858 0.813173906426361 0.578581321457509 0.0631811076808142 -0.312138187982616 -0.574386877238512 0.815289941651271 -0.0733622948009241 -0.262083190223617 -0.0939569750656276 0.0233659047064167 0.995302025183194 0.760387732162752 0.000120279306977469 3.73198042253497e-05 -8.06396370038898e-06 -1.54197902099414e-05 -9.90592787567026e-06 -9.9002262953004e-05 3.73198042253497e-05 0.000105666925484299 -8.58453215000866e-06 1.72538541360684e-05 1.14337538576273e-05 5.1003692746812e-05 -8.06396370038898e-06 -8.58453215000866e-06 1.38970223262754e-05 -7.20592719826381e-06 6.39397351181035e-06 -1.19178965514536e-06 -1.54197902099414e-05 1.72538541360684e-05 -7.20592719826381e-06 6.95657020386666e-05 1.04079322393356e-05 0.000119214595004809 -9.90592787567026e-06 1.14337538576273e-05 6.39397351181035e-06 1.04079322393356e-05 3.9341683964459e-05 7.90586961335922e-05 -9.9002262953004e-05 5.1003692746812e-05 -1.19178965514536e-06 0.000119214595004809 7.90586961335922e-05 0.000624585318321045 479 500 0 728 0 489 510 0 718 0 0 0 0 0 0 0 0 0 660 0 41 41 0 0 389 +939 857 0.817664907264688 0.569281144093806 0.0856917639395721 -0.337965550430086 -0.561940115806956 0.821580915146066 -0.0960630319874312 -0.24258048660369 -0.125089590592879 0.0303937303896623 0.991679794832136 0.722247478794533 0.000110705142065612 0.000142194915276101 -1.36881189160836e-05 5.97940659302608e-06 2.00254057597492e-05 0.000112078993123399 0.000142194915276101 0.000298534632276621 -2.6671749596969e-05 3.26036625939375e-05 6.26825771250437e-05 0.000350316022296753 -1.36881189160836e-05 -2.6671749596969e-05 1.50579791890903e-05 -8.10714187974857e-06 -1.59694715255376e-06 -4.36021944944234e-05 5.97940659302608e-06 3.26036625939375e-05 -8.10714187974857e-06 7.47221020642589e-05 3.46292105058029e-05 0.000148374466921158 2.00254057597492e-05 6.26825771250437e-05 -1.59694715255376e-06 3.46292105058029e-05 6.31795816042405e-05 0.000197281280633104 0.000112078993123399 0.000350316022296753 -4.36021944944234e-05 0.000148374466921158 0.000197281280633104 0.00111949385726677 643 656 0 790 0 666 679 0 780 0 0 0 0 0 0 0 0 0 617 0 128 128 0 0 391 +939 862 0.83069110893774 0.555267084308546 0.0403825038262125 -0.24868773806406 -0.552421615577813 0.831096279251223 -0.0641040814392641 -0.287102472441406 -0.0691566350698713 0.030942522493464 0.997125829636137 0.892010684850979 6.34103564150967e-05 2.15853598739385e-05 -1.52607318815586e-06 8.74202750738574e-06 -1.15265822289094e-05 -1.32539118030604e-06 2.15853598739385e-05 6.58207636845001e-05 -2.74972487809904e-06 3.35688054975107e-06 2.08285088460211e-08 -1.88721178965158e-05 -1.52607318815586e-06 -2.74972487809904e-06 1.48612586939054e-05 -1.29547509370302e-05 8.78008846901981e-06 -2.37172326519858e-06 8.74202750738574e-06 3.35688054975107e-06 -1.29547509370302e-05 7.73806285746731e-05 5.28751637302293e-06 2.32885085058241e-05 -1.15265822289094e-05 2.08285088460211e-08 8.78008846901981e-06 5.28751637302293e-06 3.57730668615553e-05 1.04221413145218e-05 -1.32539118030604e-06 -1.88721178965158e-05 -2.37172326519858e-06 2.32885085058241e-05 1.04221413145218e-05 0.000133819585622667 433 442 0 576 0 433 442 0 568 0 0 0 0 0 0 0 0 0 307 0 0 0 0 0 455 +939 863 0.832287772741068 0.553922386702531 0.0216114056804546 -0.258075360640613 -0.552199700748143 0.831863906590234 -0.0554791078343488 -0.289994526733652 -0.0487088681799789 0.0342407713436179 0.998225934214504 0.882846288361443 0.000134672824531825 5.40394597773081e-05 -2.37142292553458e-06 -2.80157050148464e-05 1.13654935346386e-05 1.51762906581005e-05 5.40394597773081e-05 7.69391788657048e-05 1.0978350544133e-07 -9.40924930069638e-06 3.08560290253264e-06 -3.0806535899617e-05 -2.37142292553458e-06 1.0978350544133e-07 1.37392192849371e-05 -6.95450537575216e-06 8.74090963462954e-06 -4.8317196845524e-06 -2.80157050148464e-05 -9.40924930069638e-06 -6.95450537575216e-06 7.26554128040177e-05 -9.11185356127317e-06 1.39705055634498e-05 1.13654935346386e-05 3.08560290253264e-06 8.74090963462954e-06 -9.11185356127317e-06 3.40433697942754e-05 2.81371689444476e-05 1.51762906581005e-05 -3.0806535899617e-05 -4.8317196845524e-06 1.39705055634498e-05 2.81371689444476e-05 0.000242164592308871 344 349 0 580 0 344 349 0 571 0 0 0 0 0 0 0 0 0 385 0 0 0 0 0 342 +939 866 0.822881587744407 0.566911100476621 0.0384408208501065 -0.21388347946819 -0.562019133083258 0.822008788747035 -0.0918479464711917 -0.317800888142597 -0.0836683129959389 0.0539755072140918 0.995030782449164 0.925940303321179 0.000106431489294187 5.23111851847464e-05 -4.07427132441556e-06 -1.30180122732727e-05 1.45226775562767e-05 6.02225568409512e-05 5.23111851847464e-05 0.000166004063704743 -1.08327176203926e-05 2.5113018784178e-05 2.03214105870515e-05 1.15138536388607e-05 -4.07427132441556e-06 -1.08327176203926e-05 1.61083010719432e-05 -8.60542652536543e-06 8.35670679674424e-06 -7.16201115256313e-06 -1.30180122732727e-05 2.5113018784178e-05 -8.60542652536543e-06 9.67395088864955e-05 -5.54082472757223e-07 4.59286588594217e-05 1.45226775562767e-05 2.03214105870515e-05 8.35670679674424e-06 -5.54082472757223e-07 4.51000231737954e-05 4.38437073171479e-05 6.02225568409512e-05 1.15138536388607e-05 -7.16201115256313e-06 4.59286588594217e-05 4.38437073171479e-05 0.00051024784684298 332 343 0 536 0 332 343 0 532 0 0 0 0 0 0 0 0 0 173 0 0 0 0 0 418 +939 853 0.842514329978684 0.523876633013918 0.125390897447024 -0.529709066602128 -0.520770158152474 0.851652217480075 -0.0590503415664771 -0.0345494112582345 -0.137724529980743 -0.0155490785344746 0.99034851441213 0.45021087235157 4.04679907675775e-05 2.21586033307937e-05 7.0593071699323e-06 -6.38633082478581e-06 -4.46908191783286e-06 -7.99096570241866e-06 2.21586033307937e-05 5.13254480397633e-05 3.42381709733015e-06 3.13784923730213e-06 -7.13987458837527e-07 2.35367128094209e-05 7.0593071699323e-06 3.42381709733015e-06 1.29294561353583e-05 -5.23363823245344e-06 2.97195564225586e-06 -1.04396392930777e-05 -6.38633082478581e-06 3.13784923730213e-06 -5.23363823245344e-06 4.86701865570784e-05 1.05383119312217e-05 3.18675594025354e-05 -4.46908191783286e-06 -7.13987458837527e-07 2.97195564225586e-06 1.05383119312217e-05 2.37007598033896e-05 2.55634976777385e-05 -7.99096570241866e-06 2.35367128094209e-05 -1.04396392930777e-05 3.18675594025354e-05 2.55634976777385e-05 0.000206890124157664 1020 1046 0 856 0 1057 1083 0 835 0 0 0 0 0 0 0 0 0 1949 0 336 336 0 0 491 +939 854 0.83359732634332 0.536679744133987 0.130730064444053 -0.456036799645804 -0.528727564313672 0.843749139653606 -0.0923826394336758 -0.0978952643064182 -0.159883270695217 0.0078893326763778 0.98710440085217 0.543366326090541 4.54287795894498e-05 4.52456769089734e-06 1.70073653202878e-06 3.63660665445872e-07 3.19022236140533e-06 -1.45448746256179e-05 4.52456769089734e-06 5.22496062800775e-05 -3.66133503771686e-06 1.20813272795323e-05 6.73437150472093e-06 2.65338125776918e-05 1.70073653202878e-06 -3.66133503771686e-06 1.14845463740135e-05 -7.02660233461126e-06 5.65805170300276e-06 -1.76559050667726e-06 3.63660665445872e-07 1.20813272795323e-05 -7.02660233461126e-06 4.05736545538399e-05 3.40353202800116e-06 2.23999979843904e-05 3.19022236140533e-06 6.73437150472093e-06 5.65805170300276e-06 3.40353202800116e-06 2.28700328605248e-05 2.19129527081298e-05 -1.45448746256179e-05 2.65338125776918e-05 -1.76559050667726e-06 2.23999979843904e-05 2.19129527081298e-05 0.000180813058063295 977 1001 0 884 0 1007 1031 0 868 0 0 0 0 0 0 0 0 0 1504 0 328 328 0 0 444 +939 942 0.997452122781528 0.0635018346220584 0.032508149105373 0.287413961279216 -0.061235449407682 0.995904490718701 -0.0665166528184031 0.101360835128623 -0.0365989411658812 0.0643565254341586 0.997255611736318 -0.0934965998159568 4.40331721005727e-05 -3.10454360319506e-06 3.19490644173246e-06 1.00258923747635e-05 2.15024721490347e-06 -8.11890326010806e-06 -3.10454360319506e-06 3.27253457878146e-05 -2.90800274569468e-06 -1.74720701594419e-06 -1.54304246278087e-06 2.44227181566925e-06 3.19490644173246e-06 -2.90800274569468e-06 1.11490958727371e-05 4.80428292314391e-06 5.9803816361578e-06 -2.84703073028286e-07 1.00258923747635e-05 -1.74720701594419e-06 4.80428292314391e-06 5.25457967487771e-05 3.30381486183595e-06 4.07166627843643e-06 2.15024721490347e-06 -1.54304246278087e-06 5.9803816361578e-06 3.30381486183595e-06 1.18636551060593e-05 5.66663916311227e-06 -8.11890326010806e-06 2.44227181566925e-06 -2.84703073028286e-07 4.07166627843643e-06 5.66663916311227e-06 0.000128734428338179 2995 2964 0 372 382 2995 2964 0 323 524 0 0 0 0 0 0 0 0 3492 0 0 0 0 0 517 +939 865 0.826192621712618 0.563352646462205 0.00628868441422747 -0.240684344660748 -0.561269622226965 0.824002183360494 -0.0774390920810576 -0.309283702234733 -0.0488074071512827 0.0604499589840157 0.99697725122793 0.89792843654733 7.70260102977007e-05 3.32841947412652e-05 -6.90710873237675e-08 -1.91922808808035e-05 -7.47840967247996e-06 -2.10536363007254e-05 3.32841947412652e-05 4.96515385181491e-05 -1.98131037723262e-06 -2.40906411064815e-06 1.99187970831276e-06 -1.77377188112463e-05 -6.90710873237675e-08 -1.98131037723262e-06 1.45148681705729e-05 -1.11174537741521e-05 1.00340003151003e-05 -4.46686767203741e-08 -1.91922808808035e-05 -2.40906411064815e-06 -1.11174537741521e-05 7.73584188476001e-05 -9.91404790103486e-06 2.83736873884283e-05 -7.47840967247996e-06 1.99187970831276e-06 1.00340003151003e-05 -9.91404790103486e-06 3.72282450878726e-05 1.39030954526715e-05 -2.10536363007254e-05 -1.77377188112463e-05 -4.46686767203741e-08 2.83736873884283e-05 1.39030954526715e-05 0.000173043011927705 296 306 0 511 0 296 306 0 503 0 0 0 0 0 0 0 0 0 205 0 0 0 0 0 408 +939 852 0.855355025531785 0.505851648149321 0.111722380757547 -0.578576251529042 -0.504828857446044 0.862321124080108 -0.0393713557671159 0.0341551846133358 -0.116256634164423 -0.0227241948115821 0.992959216676559 0.392331043239065 5.11685492193346e-05 2.8281450297233e-05 3.12770880855062e-06 -8.98747143353581e-06 -2.40263659488281e-06 -2.93851110635581e-05 2.8281450297233e-05 6.10594951610322e-05 3.16010279966399e-07 3.70723918496626e-06 2.06771598184606e-06 2.62687202081784e-05 3.12770880855062e-06 3.16010279966399e-07 1.21084934993883e-05 -4.41057816163899e-06 4.00220825217311e-06 -3.90278482833069e-06 -8.98747143353581e-06 3.70723918496626e-06 -4.41057816163899e-06 4.86668309948132e-05 1.18381874908735e-05 2.25106786720103e-05 -2.40263659488281e-06 2.06771598184606e-06 4.00220825217311e-06 1.18381874908735e-05 2.16766357774482e-05 2.09580093915832e-05 -2.93851110635581e-05 2.62687202081784e-05 -3.90278482833069e-06 2.25106786720103e-05 2.09580093915832e-05 0.000222364744626021 1199 1223 0 739 0 1236 1260 0 723 0 0 0 0 0 0 0 0 0 2454 0 320 320 0 0 377 +939 873 0.813997383260001 0.580839939022476 0.0057641375970502 -0.228263075271507 -0.577494314733043 0.810297124353213 -0.0995936078065608 -0.312696490461779 -0.0625186092046572 0.0777401794523278 0.995011501441986 0.907966715818864 0.000127713554080778 1.78513158228601e-05 -4.27259862085598e-06 -2.70156984786813e-05 -2.18137662513508e-05 -4.137715584572e-05 1.78513158228601e-05 8.62424216966723e-05 -6.79197789133641e-06 1.78530669231429e-05 5.786099464313e-06 2.08023406689317e-05 -4.27259862085598e-06 -6.79197789133641e-06 1.39314099322327e-05 -1.02103960204622e-05 1.19351057265846e-05 -3.14861102950655e-06 -2.70156984786813e-05 1.78530669231429e-05 -1.02103960204622e-05 0.000107538243506915 -1.25553972495692e-06 7.95839026617828e-05 -2.18137662513508e-05 5.786099464313e-06 1.19351057265846e-05 -1.25553972495692e-06 5.37799890482377e-05 3.82784404320929e-05 -4.137715584572e-05 2.08023406689317e-05 -3.14861102950655e-06 7.95839026617828e-05 3.82784404320929e-05 0.000223016865080229 278 290 0 503 0 278 290 0 496 0 0 0 0 0 0 0 0 0 90 0 0 0 0 0 457 +939 874 0.811319353466677 0.584599863938926 -0.00197630286216962 -0.214669598235613 -0.582705513477259 0.808408926293729 -0.083242371733534 -0.313736557179407 -0.0470658183145397 0.0686877497899707 0.996527371312586 0.932938775487103 0.000127952088599041 6.13047716803694e-05 -3.02176293016253e-06 -1.24282719014638e-05 -9.04402373597093e-06 -1.03669979240011e-05 6.13047716803694e-05 8.34352775438297e-05 -8.68719104952166e-07 5.94645688553949e-06 9.79136152729819e-06 1.98861907324542e-05 -3.02176293016253e-06 -8.68719104952166e-07 1.49551799148509e-05 -1.18486738331341e-05 8.72446840321066e-06 -1.02514218568961e-05 -1.24282719014638e-05 5.94645688553949e-06 -1.18486738331341e-05 8.56605673762764e-05 5.93512445645034e-06 8.9021723442825e-05 -9.04402373597093e-06 9.79136152729819e-06 8.72446840321066e-06 5.93512445645034e-06 4.81945515060183e-05 4.35300702816222e-05 -1.03669979240011e-05 1.98861907324542e-05 -1.02514218568961e-05 8.9021723442825e-05 4.35300702816222e-05 0.000268791067987018 269 279 0 455 0 269 279 0 451 0 0 0 0 0 0 0 0 0 89 0 0 0 0 0 405 +939 872 0.806930363489534 0.590533388703754 0.0115631009988179 -0.22352850234673 -0.58749914213478 0.804494916949809 -0.0873652481986764 -0.316624315391789 -0.0608945520514352 0.0637043595680879 0.996109235025193 0.930914891984883 0.000117494237284661 5.75861615142284e-05 -2.81422002211473e-06 -1.80202951985778e-05 -8.12549336610207e-07 -2.7097884608966e-06 5.75861615142284e-05 7.87750129899924e-05 -2.91341657416539e-06 -7.1133545816425e-07 7.66258396131041e-06 -2.12295263198848e-05 -2.81422002211473e-06 -2.91341657416539e-06 1.36431070046673e-05 -1.2887335615438e-05 9.73136051972608e-06 -4.32364530980664e-06 -1.80202951985778e-05 -7.1133545816425e-07 -1.2887335615438e-05 8.68387293822791e-05 -5.07966285332698e-06 3.96841771336055e-05 -8.12549336610207e-07 7.66258396131041e-06 9.73136051972608e-06 -5.07966285332698e-06 4.27201429816385e-05 3.45649100491517e-05 -2.7097884608966e-06 -2.12295263198848e-05 -4.32364530980664e-06 3.96841771336055e-05 3.45649100491517e-05 0.000227815026872289 276 286 0 504 0 276 286 0 501 0 0 0 0 0 0 0 0 0 123 0 0 0 0 0 399 +939 867 0.815069531956407 0.578611675940528 0.0294989244152563 -0.228238688362273 -0.573149425836472 0.812719068538891 -0.104821044149542 -0.316807855520757 -0.0846250184028686 0.0685291478027511 0.994053500653633 0.914426647489881 9.69256368907544e-05 3.39543663687223e-06 -6.8469160171973e-06 5.31450437584797e-07 2.12929160395017e-06 -3.54001798131455e-05 3.39543663687223e-06 8.11060409413888e-05 -9.54019347285538e-07 1.50947384209483e-05 1.42671266329452e-06 2.03182640200546e-06 -6.8469160171973e-06 -9.54019347285538e-07 1.41181514669427e-05 -1.16747794098353e-05 9.36918398263108e-06 9.66240338787393e-08 5.31450437584797e-07 1.50947384209483e-05 -1.16747794098353e-05 8.12291549708761e-05 -1.47371516425969e-05 3.2922881442583e-05 2.12929160395017e-06 1.42671266329452e-06 9.36918398263108e-06 -1.47371516425969e-05 4.35444211682786e-05 2.27402292633623e-05 -3.54001798131455e-05 2.03182640200546e-06 9.66240338787393e-08 3.2922881442583e-05 2.27402292633623e-05 0.000192702606748007 305 318 0 534 0 305 318 0 529 0 0 0 0 0 0 0 0 0 113 0 0 0 0 0 397 +939 869 0.798011165301208 0.600954240111988 0.0450797221157315 -0.239216789324301 -0.594835868864245 0.797468085231129 -0.101068996978874 -0.314518979627489 -0.0966874819567037 0.0538391523820653 0.993857573550483 0.893714827610231 8.87222240846604e-05 5.52157570713512e-05 -2.58393276701165e-06 -3.8898763905119e-06 1.66681181020936e-07 -2.25789378071772e-05 5.52157570713512e-05 0.000132889749410089 -8.44349263638216e-06 2.41573123194638e-05 1.64754437328599e-05 -4.55517781856079e-05 -2.58393276701165e-06 -8.44349263638216e-06 1.54595739676474e-05 -1.50700125864992e-05 4.97933722864973e-06 -4.60660968101278e-06 -3.8898763905119e-06 2.41573123194638e-05 -1.50700125864992e-05 0.000102452174099985 7.46355934115538e-06 3.84986784954512e-05 1.66681181020936e-07 1.64754437328599e-05 4.97933722864973e-06 7.46355934115538e-06 4.72696826344419e-05 3.01525132243932e-05 -2.25789378071772e-05 -4.55517781856079e-05 -4.60660968101278e-06 3.84986784954512e-05 3.01525132243932e-05 0.000281206261616908 319 334 0 583 0 319 334 0 578 0 0 0 0 0 0 0 0 0 133 0 0 0 0 0 416 +939 871 0.800586058013753 0.599018414203034 0.0154564924766706 -0.242447663285902 -0.595595458628021 0.798313612364308 -0.0892268231840978 -0.326767994690662 -0.0657876384716454 0.0622279339166238 0.995891395115347 0.909816142010039 0.000101218793496712 5.20215325005635e-05 -4.98953341430499e-06 -1.38803383327905e-05 -7.27703071623864e-06 -4.11288140970962e-05 5.20215325005635e-05 0.000159120379456459 -9.20267239263593e-06 5.08099296446813e-05 3.52948948580918e-05 5.42965765096259e-05 -4.98953341430499e-06 -9.20267239263593e-06 1.61453090230436e-05 -1.21071859906251e-05 7.84542218599881e-06 7.76341305819659e-07 -1.38803383327905e-05 5.08099296446813e-05 -1.21071859906251e-05 0.000107125975784358 1.73782264476613e-05 9.22946492999474e-05 -7.27703071623864e-06 3.52948948580918e-05 7.84542218599881e-06 1.73782264476613e-05 4.91274518838555e-05 6.64876975729892e-05 -4.11288140970962e-05 5.42965765096259e-05 7.76341305819659e-07 9.22946492999474e-05 6.64876975729892e-05 0.000409401010544718 277 289 0 542 0 277 289 0 538 0 0 0 0 0 0 0 0 0 211 0 0 0 0 0 411 +939 876 0.807430377165193 0.58996179988947 -0.00112280989116373 -0.214488552764454 -0.587963249862904 0.804535654444461 -0.0837949732279615 -0.313006137419235 -0.048532492636654 0.0683187777905871 0.996482384068917 0.920672726604713 9.79336786098437e-05 4.87665359933893e-05 -1.56451431416683e-06 -5.84419479932627e-06 7.52635231772497e-06 1.18477136705099e-05 4.87665359933893e-05 6.2333192550794e-05 1.55464493973839e-07 -5.16440891405955e-06 6.10093163510502e-06 3.58334978103179e-07 -1.56451431416683e-06 1.55464493973839e-07 1.39978055055414e-05 -1.11385785021258e-05 9.9468682842941e-06 -2.22612582621237e-06 -5.84419479932627e-06 -5.16440891405955e-06 -1.11385785021258e-05 8.3662376792519e-05 -1.50603020811998e-05 3.57084694456741e-05 7.52635231772497e-06 6.10093163510502e-06 9.9468682842941e-06 -1.50603020811998e-05 4.0729240419379e-05 3.27805743101545e-05 1.18477136705099e-05 3.58334978103179e-07 -2.22612582621237e-06 3.57084694456741e-05 3.27805743101545e-05 0.000260515869165779 249 257 0 485 0 249 257 0 481 0 0 0 0 0 0 0 0 0 156 0 0 0 0 0 411 +939 875 0.806929161761114 0.590620350594239 -0.00573841122988494 -0.227347781348385 -0.588799923894798 0.803598093136023 -0.08686054529893 -0.315992008095649 -0.0466902293952949 0.0734690831036122 0.996203953167688 0.904890103433025 0.00011843891977437 3.05090947412572e-05 1.58430750343887e-06 -4.28455646482592e-05 -1.08879403105249e-05 -2.19331048390196e-05 3.05090947412572e-05 4.88694009774901e-05 3.50805549125199e-06 -1.92638269324643e-05 8.36499320803343e-06 4.21861249975499e-06 1.58430750343887e-06 3.50805549125199e-06 1.37709291212987e-05 -7.71053332440506e-06 6.24588254755013e-06 -7.24452589122527e-07 -4.28455646482592e-05 -1.92638269324643e-05 -7.71053332440506e-06 8.68895653964068e-05 -5.60359223276245e-06 1.89509947625372e-05 -1.08879403105249e-05 8.36499320803343e-06 6.24588254755013e-06 -5.60359223276245e-06 4.91721879027859e-05 2.89071309581938e-05 -2.19331048390196e-05 4.21861249975499e-06 -7.24452589122527e-07 1.89509947625372e-05 2.89071309581938e-05 0.00029959106374533 256 265 0 478 0 256 265 0 474 0 0 0 0 0 0 0 0 0 143 0 0 0 0 0 365 +939 886 0.803665967059596 0.594150822597436 0.0332537726724957 -0.215621437098164 -0.589304521467279 0.802388613612508 -0.0943010801805474 -0.318941764898698 -0.0827115129131683 0.0561899702063174 0.994988187306678 0.932943733650686 8.74086433330631e-05 2.42867177522808e-05 4.93921202943996e-06 -2.35763598872914e-05 -1.39603262926636e-05 1.1184370071998e-05 2.42867177522808e-05 7.71475239334553e-05 -3.59566888917528e-06 6.71955592698712e-06 4.31498189097933e-06 6.21666347265462e-06 4.93921202943996e-06 -3.59566888917528e-06 1.67209505630831e-05 -1.36296954635117e-05 1.00526053542981e-05 1.84162141664874e-06 -2.35763598872914e-05 6.71955592698712e-06 -1.36296954635117e-05 9.86669749093952e-05 -9.92349094942518e-07 1.53595215305405e-05 -1.39603262926636e-05 4.31498189097933e-06 1.00526053542981e-05 -9.92349094942518e-07 4.40718474067407e-05 7.88563237827909e-06 1.1184370071998e-05 6.21666347265462e-06 1.84162141664874e-06 1.53595215305405e-05 7.88563237827909e-06 0.000218765620896231 272 282 0 538 0 272 282 0 532 0 0 0 0 0 0 0 0 0 106 0 0 0 0 0 364 +939 877 0.807903720884143 0.589304787035818 -0.00338315802537935 -0.217655297845315 -0.586842898232681 0.80397686439182 -0.0961073062600501 -0.319662102361402 -0.0539165148671785 0.0796308325924391 0.995365229413411 0.916750302776782 0.000132147512141188 6.15186042880533e-05 -3.563720953426e-06 -1.15023709831596e-05 -2.56805925813652e-06 -1.2331791119172e-05 6.15186042880533e-05 8.49823445841013e-05 -1.08148592620608e-06 -2.92113922440558e-07 1.25182321615523e-05 3.06435370746152e-05 -3.563720953426e-06 -1.08148592620608e-06 1.57803499688401e-05 -1.11085691302906e-05 1.11595326520865e-05 -2.17387748370199e-06 -1.15023709831596e-05 -2.92113922440558e-07 -1.11085691302906e-05 8.4102574492338e-05 -5.9145391859288e-06 4.9920774582731e-05 -2.56805925813652e-06 1.25182321615523e-05 1.11595326520865e-05 -5.9145391859288e-06 5.41606805326248e-05 5.24382758881971e-05 -1.2331791119172e-05 3.06435370746152e-05 -2.17387748370199e-06 4.9920774582731e-05 5.24382758881971e-05 0.000370566520197567 250 260 0 464 0 250 260 0 462 0 0 0 0 0 0 0 0 0 81 0 0 0 0 0 466 +939 868 0.804485913821689 0.592757010028406 0.037967637859984 -0.231346327836907 -0.586262496832607 0.80268581061991 -0.109506959765377 -0.319624839612014 -0.0953871022207902 0.0658378044260537 0.993260632582545 0.910831249158489 0.000101607453316813 4.79209495356545e-05 -6.88882731566893e-06 4.65484527526445e-06 1.11649121976312e-06 1.149399430197e-05 4.79209495356545e-05 0.000130910392052498 -1.02293734541982e-05 3.86404383477645e-05 3.43039990697031e-05 0.000114094881760071 -6.88882731566893e-06 -1.02293734541982e-05 1.50882353177366e-05 -1.14130029960587e-05 6.13648272311766e-06 -5.93121275860317e-06 4.65484527526445e-06 3.86404383477645e-05 -1.14130029960587e-05 8.62077829668194e-05 1.24428303814737e-05 9.05423428665905e-05 1.11649121976312e-06 3.43039990697031e-05 6.13648272311766e-06 1.24428303814737e-05 5.11154794690558e-05 8.70168367449266e-05 1.149399430197e-05 0.000114094881760071 -5.93121275860317e-06 9.05423428665905e-05 8.70168367449266e-05 0.000501435401612969 325 336 0 549 0 325 336 0 543 0 0 0 0 0 0 0 0 0 122 0 0 0 0 0 410 +939 870 0.798194027642339 0.601024063909923 0.0406985114875407 -0.226078421486735 -0.595115145650277 0.797214606075384 -0.101424036981972 -0.324466975528089 -0.0934037346884494 0.0567357599867287 0.994010460651687 0.930701327986496 8.02906358464159e-05 3.83519905847719e-05 -4.50655754199911e-08 -4.60135362453963e-06 1.9108920447164e-06 3.35149325623106e-05 3.83519905847719e-05 7.19237379924792e-05 -5.61321307902144e-06 -8.66209408940796e-07 4.79823863652685e-06 4.22945895039176e-06 -4.50655754199911e-08 -5.61321307902144e-06 1.3271367186783e-05 -8.29816175794152e-06 8.78344199860899e-06 -9.20465316340967e-07 -4.60135362453963e-06 -8.66209408940796e-07 -8.29816175794152e-06 6.43004021933831e-05 -7.40785215789769e-06 2.03969778992917e-05 1.9108920447164e-06 4.79823863652685e-06 8.78344199860899e-06 -7.40785215789769e-06 3.68018633041911e-05 3.02796139466774e-05 3.35149325623106e-05 4.22945895039176e-06 -9.20465316340967e-07 2.03969778992917e-05 3.02796139466774e-05 0.000211295221654604 333 345 0 562 0 333 345 0 560 0 0 0 0 0 0 0 0 0 94 0 0 0 0 0 409 +939 887 0.803346096201047 0.593451034695676 0.0495067584999139 -0.226048352200189 -0.58910485680268 0.804113770123776 -0.0797277391427891 -0.314629651716693 -0.0871235755122082 0.0348842961224384 0.995586544944241 0.920250962455613 7.87295273558822e-05 3.80571884192471e-05 -1.61344619621913e-06 -6.20890171430998e-07 1.853373003592e-06 1.04040553331139e-06 3.80571884192471e-05 0.000150744009765029 -8.31393186379902e-06 4.90218088506938e-05 3.90374118901301e-05 6.46999014429486e-05 -1.61344619621913e-06 -8.31393186379902e-06 1.32077804710826e-05 -1.31982953006631e-05 4.84569462619162e-06 -9.33364945754324e-06 -6.20890171430998e-07 4.90218088506938e-05 -1.31982953006631e-05 0.000102394406299759 2.44622014888027e-05 9.90917192678352e-05 1.853373003592e-06 3.90374118901301e-05 4.84569462619162e-06 2.44622014888027e-05 5.47295021223079e-05 7.83819746578892e-05 1.04040553331139e-06 6.46999014429486e-05 -9.33364945754324e-06 9.90917192678352e-05 7.83819746578892e-05 0.00036397091252507 322 334 0 581 0 322 334 0 575 0 0 0 0 0 0 0 0 0 247 0 0 0 0 0 372 +939 885 0.803955765336447 0.593995280303583 0.0287181886503195 -0.217752734633092 -0.590041644286895 0.802767782288632 -0.0861089178111554 -0.311683300992335 -0.0742023273860391 0.0522828336689849 0.995871738686281 0.926912277925298 8.88529144068206e-05 5.32311951419528e-05 1.85481742984047e-06 -7.42183099855314e-06 -3.25465096614436e-06 -1.75247104871326e-06 5.32311951419528e-05 0.000118434151437322 -2.21458404304229e-06 3.3927093568336e-06 1.46582137417926e-05 9.39374468065288e-06 1.85481742984047e-06 -2.21458404304229e-06 1.37584978021258e-05 -9.5536020943663e-06 1.15306602242826e-05 3.401246486161e-06 -7.42183099855314e-06 3.3927093568336e-06 -9.5536020943663e-06 7.10344630010678e-05 -5.70448838450734e-07 3.92859881249429e-05 -3.25465096614436e-06 1.46582137417926e-05 1.15306602242826e-05 -5.70448838450734e-07 4.56201075054594e-05 6.0926366101251e-05 -1.75247104871326e-06 9.39374468065288e-06 3.401246486161e-06 3.92859881249429e-05 6.0926366101251e-05 0.000429592885850941 315 327 0 536 0 315 327 0 534 0 0 0 0 0 0 0 0 0 120 0 0 0 0 0 374 +939 878 0.805577930527662 0.592483269786232 -0.00278798676202714 -0.219195472057757 -0.590177579968113 0.802009885281591 -0.0920356888038048 -0.310219114030852 -0.0522936128963264 0.0757873270014533 0.995751805981904 0.925384532865379 0.000128048118789249 4.38806399295537e-05 -4.86693948343511e-06 -2.3032270590628e-05 -1.42699897395825e-05 -4.22350364647293e-05 4.38806399295537e-05 8.42583287546672e-05 -3.36369390451178e-06 5.69122856081126e-07 1.16702248552358e-05 -5.97684197671844e-06 -4.86693948343511e-06 -3.36369390451178e-06 1.35079817977515e-05 -7.18905044816431e-06 1.13983385261102e-05 5.98208574532679e-06 -2.3032270590628e-05 5.69122856081126e-07 -7.18905044816431e-06 8.98162468368878e-05 -1.56120689020451e-06 5.85436488360482e-05 -1.42699897395825e-05 1.16702248552358e-05 1.13983385261102e-05 -1.56120689020451e-06 5.34184504814666e-05 4.11016335940261e-05 -4.22350364647293e-05 -5.97684197671844e-06 5.98208574532679e-06 5.85436488360482e-05 4.11016335940261e-05 0.000306420803383238 233 241 0 448 0 233 241 0 444 0 0 0 0 0 0 0 0 0 92 0 0 0 0 0 403 +940 854 0.830327626585147 0.541180617334747 0.132964551481431 -0.550588733563775 -0.541825864086228 0.839784069511813 -0.0344593906125813 -0.106974329590268 -0.130310266428585 -0.0434310489783487 0.990521568895878 0.58528856076803 8.01529641090142e-05 4.38022121201643e-05 -6.01312544647272e-06 -2.12933908252789e-06 8.60029062075042e-06 -2.68874910272451e-05 4.38022121201643e-05 8.60573697031946e-05 -1.19624594766692e-05 1.52805919144913e-05 1.57145152614902e-05 6.87139543338243e-05 -6.01312544647272e-06 -1.19624594766692e-05 1.40054596935245e-05 -3.33516099161307e-06 4.2365319997745e-06 3.61975040920523e-06 -2.12933908252789e-06 1.52805919144913e-05 -3.33516099161307e-06 4.14055298562449e-05 8.51369983400056e-06 5.94353821397924e-05 8.60029062075042e-06 1.57145152614902e-05 4.2365319997745e-06 8.51369983400056e-06 2.72113005479533e-05 6.01344468195692e-05 -2.68874910272451e-05 6.87139543338243e-05 3.61975040920523e-06 5.94353821397924e-05 6.01344468195692e-05 0.000488409964884897 840 864 0 864 0 860 884 0 847 0 0 0 0 0 0 0 0 0 1614 0 308 308 0 0 254 +940 858 0.809279705139178 0.582892863780556 0.0728166753123764 -0.397073728757881 -0.58296009064587 0.812188213589267 -0.0225352705959723 -0.26220602558011 -0.0722764938552247 -0.0242118784974938 0.997090714717381 0.825186695024537 8.14613843431511e-05 4.22104238014253e-05 -6.46166493280802e-07 -2.51740746742156e-05 -4.61698212220611e-06 -4.54718631120148e-05 4.22104238014253e-05 0.000101743997733317 -5.12850947776861e-06 -9.55323454495126e-06 4.6952637188526e-06 6.13704612602277e-06 -6.46166493280802e-07 -5.12850947776861e-06 1.46241541012949e-05 -8.40832695843447e-06 6.03787617203525e-06 -5.56195957117641e-06 -2.51740746742156e-05 -9.55323454495126e-06 -8.40832695843447e-06 6.71597666663772e-05 6.26061627727202e-06 4.7597594411914e-05 -4.61698212220611e-06 4.6952637188526e-06 6.03787617203525e-06 6.26061627727202e-06 3.32768680305588e-05 3.70123595210542e-05 -4.54718631120148e-05 6.13704612602277e-06 -5.56195957117641e-06 4.7597594411914e-05 3.70123595210542e-05 0.000280206947530551 409 429 0 717 0 416 436 0 709 0 0 0 0 0 0 0 0 0 684 0 26 26 0 0 249 +940 855 0.825151635440692 0.552903492945617 0.115855539436349 -0.493310959677864 -0.547305643115412 0.833244192552449 -0.0784897992839954 -0.162189036108313 -0.139933239595091 0.0013575957249063 0.990160009993471 0.662952290503085 6.06909140615296e-05 5.5157653084912e-05 5.32508516990821e-07 -1.44091384540127e-05 4.74605730019906e-06 5.33131642411467e-05 5.5157653084912e-05 0.00012666573292088 -1.16847044741253e-05 1.42849404827341e-07 2.0730693229288e-05 0.000113096172291264 5.32508516990821e-07 -1.16847044741253e-05 1.41286705360544e-05 -2.84726725733878e-06 8.2233359271317e-07 -2.32436864391365e-05 -1.44091384540127e-05 1.42849404827341e-07 -2.84726725733878e-06 5.57162440271256e-05 1.18545706097904e-05 1.34619936220758e-05 4.74605730019906e-06 2.0730693229288e-05 8.2233359271317e-07 1.18545706097904e-05 3.96004014917673e-05 9.04015364475402e-05 5.33131642411467e-05 0.000113096172291264 -2.32436864391365e-05 1.34619936220758e-05 9.04015364475402e-05 0.000534026747791125 785 810 0 806 0 807 832 0 790 0 0 0 0 0 0 0 0 0 1029 0 295 295 0 0 289 +940 861 0.826090831715638 0.55986804490809 0.0642005455285077 -0.33842774443049 -0.557848063779885 0.828574189131722 -0.047648198725057 -0.279143545837296 -0.0798716188166873 0.00354759009784392 0.996798845862143 0.93597297879728 0.00010185933970616 4.48850931499033e-05 -6.09543256291269e-06 -1.45223401925969e-05 -8.66183509095539e-06 -1.90390462893496e-05 4.48850931499033e-05 6.57475633121418e-05 -1.27257091739575e-06 -1.31382952072613e-05 9.23458713938121e-08 -4.2275401649199e-05 -6.09543256291269e-06 -1.27257091739575e-06 1.49125444263679e-05 -7.24871555164321e-06 8.89498219653962e-06 -3.1345154186406e-06 -1.45223401925969e-05 -1.31382952072613e-05 -7.24871555164321e-06 4.7968084077392e-05 -8.80787114371152e-06 1.31612425806375e-05 -8.66183509095539e-06 9.23458713938121e-08 8.89498219653962e-06 -8.80787114371152e-06 2.5697556532769e-05 1.72980775300091e-06 -1.90390462893496e-05 -4.2275401649199e-05 -3.1345154186406e-06 1.31612425806375e-05 1.72980775300091e-06 0.00010187643203886 439 454 0 596 0 439 454 0 591 0 0 0 0 0 0 0 0 0 254 0 0 0 0 0 243 +940 867 0.811344551731952 0.583100178126842 0.0414029062183322 -0.305589113412679 -0.581110115916044 0.812211921684933 -0.0512135475524782 -0.307610942321032 -0.0634905627232902 0.0174921851497723 0.997829129612764 0.982269716774376 0.000106061205309551 6.26564121501901e-06 -6.02971210558725e-06 -3.89099996794518e-05 -3.5433738531536e-06 -5.35270972670181e-05 6.26564121501901e-06 6.85356863892261e-05 -2.94743487963294e-07 5.12810384962017e-06 -2.07795808162532e-06 -3.0260616048443e-05 -6.02971210558725e-06 -2.94743487963294e-07 1.54512001924649e-05 -5.13477475861286e-06 7.73632663127904e-06 3.9250301485558e-06 -3.89099996794518e-05 5.12810384962017e-06 -5.13477475861286e-06 7.63804821388339e-05 -8.30601144921216e-06 4.01962340442016e-05 -3.5433738531536e-06 -2.07795808162532e-06 7.73632663127904e-06 -8.30601144921216e-06 4.58506385052723e-05 6.79421063108542e-06 -5.35270972670181e-05 -3.0260616048443e-05 3.9250301485558e-06 4.01962340442016e-05 6.79421063108542e-06 0.000176212202678038 319 333 0 533 0 319 333 0 524 0 0 0 0 0 0 0 0 0 146 0 0 0 0 0 264 +940 859 0.810977021700483 0.573348415550569 0.116566996441815 -0.355710749800022 -0.573084466133857 0.818561109042063 -0.0391395636140817 -0.281004127603876 -0.117857816668589 -0.0350614481942802 0.992411320925267 0.902086852986842 9.78742894924271e-05 3.57595815984763e-05 -6.25738064207405e-06 -2.08589684390277e-06 1.03920332460231e-05 -3.35373264752723e-05 3.57595815984763e-05 8.01936049294644e-05 -8.01353116900161e-06 5.08994923892331e-06 8.80407209171958e-06 -1.9175636675241e-05 -6.25738064207405e-06 -8.01353116900161e-06 1.46695040106936e-05 -4.45534217585001e-06 4.69714895709094e-06 1.68138006587927e-06 -2.08589684390277e-06 5.08994923892331e-06 -4.45534217585001e-06 5.33790975195368e-05 7.28296052888043e-06 2.0378795820963e-05 1.03920332460231e-05 8.80407209171958e-06 4.69714895709094e-06 7.28296052888043e-06 3.88155960410293e-05 9.06440198795983e-06 -3.35373264752723e-05 -1.9175636675241e-05 1.68138006587927e-06 2.0378795820963e-05 9.06440198795983e-06 0.000261786437012776 479 489 0 737 0 483 493 0 726 0 0 0 0 0 0 0 0 0 522 0 9 9 0 0 245 +940 852 0.852884944863933 0.510598908675482 0.108977177811929 -0.672001259956509 -0.51528699708131 0.856823646023032 0.018235960482639 0.0153454616918682 -0.0840629613050328 -0.0717076988558814 0.993876966460851 0.428381962055699 6.1714835430436e-05 2.34041518901813e-05 -4.11576826124543e-06 -6.7363371732692e-06 2.88806580581178e-06 -1.10324368918465e-05 2.34041518901813e-05 5.52131454211067e-05 -5.03389292930679e-06 -5.80593376452484e-06 -1.54012889437715e-06 -5.32511679550994e-06 -4.11576826124543e-06 -5.03389292930679e-06 1.16458642058624e-05 -2.30786842597121e-06 5.2295700381551e-06 2.92933787892187e-06 -6.7363371732692e-06 -5.80593376452484e-06 -2.30786842597121e-06 4.12192299340794e-05 4.97188716956998e-06 1.29630989703197e-05 2.88806580581178e-06 -1.54012889437715e-06 5.2295700381551e-06 4.97188716956998e-06 1.68919993825158e-05 8.11052804733777e-06 -1.10324368918465e-05 -5.32511679550994e-06 2.92933787892187e-06 1.29630989703197e-05 8.11052804733777e-06 0.000186371844887562 1117 1141 0 731 0 1141 1165 0 717 0 0 0 0 0 0 0 0 0 2723 0 354 354 0 0 234 +940 851 0.863714674356214 0.49132996751032 0.112213298356509 -0.757569591115063 -0.497512350116019 0.866784649566913 0.0341442931863945 0.0769026562451115 -0.0804886500307597 -0.0853184288502264 0.993097348156139 0.367001986983491 5.42381388641377e-05 2.84739875105227e-05 -7.21357871552462e-07 4.04112981164395e-06 4.22629611726662e-06 -1.54633935903836e-05 2.84739875105227e-05 0.000104359325742869 -2.38271237030956e-06 1.57587928677552e-05 7.98784310250735e-06 2.838137127909e-05 -7.21357871552462e-07 -2.38271237030956e-06 1.06710159469685e-05 -4.18743031469462e-06 4.67945546909278e-06 -2.77456914660478e-07 4.04112981164395e-06 1.57587928677552e-05 -4.18743031469462e-06 4.27912405974136e-05 5.71051904140708e-06 2.8817100614842e-05 4.22629611726662e-06 7.98784310250735e-06 4.67945546909278e-06 5.71051904140708e-06 1.66250578384736e-05 1.21988259203031e-05 -1.54633935903836e-05 2.838137127909e-05 -2.77456914660478e-07 2.8817100614842e-05 1.21988259203031e-05 0.000226477945567314 1047 1064 0 604 0 1079 1096 0 586 0 0 0 0 0 0 0 0 0 3234 0 407 407 0 0 265 +940 856 0.818833890970364 0.560865948180249 0.122231121937928 -0.464394623803469 -0.554690958622891 0.827906614521706 -0.0829974581130447 -0.200575536077141 -0.147746402393943 0.00016063336605332 0.989025264983948 0.72213266980369 4.90001393251706e-05 3.90240663528646e-05 -2.6867217206494e-07 1.00307072510408e-05 1.26614187652542e-05 2.23195908361189e-05 3.90240663528646e-05 0.000125047501455015 -1.47090267451773e-05 3.59062686867802e-05 3.36967032112537e-05 0.000119551896680724 -2.6867217206494e-07 -1.47090267451773e-05 1.46035773718447e-05 -7.62207300577189e-06 1.02503599305274e-06 -1.67017739353005e-05 1.00307072510408e-05 3.59062686867802e-05 -7.62207300577189e-06 5.19243056474397e-05 2.02743606295191e-05 7.71560394060217e-05 1.26614187652542e-05 3.36967032112537e-05 1.02503599305274e-06 2.02743606295191e-05 4.26424976350794e-05 9.64180039214978e-05 2.23195908361189e-05 0.000119551896680724 -1.67017739353005e-05 7.71560394060217e-05 9.64180039214978e-05 0.000508146201452982 689 712 0 781 0 705 728 0 766 0 0 0 0 0 0 0 0 0 927 0 205 205 0 0 288 +940 943 0.993493793685497 0.111883366609437 0.0212648579712626 0.281030250270354 -0.112150463294817 0.993621063576811 0.011809132027602 0.05712989405432 -0.0198079653462323 -0.0141171630516108 0.999704131338976 -0.133685026549651 4.37045497256427e-05 1.60183360405127e-05 7.54922599458947e-06 -3.26146671542686e-06 2.26746443740274e-06 3.47396707898475e-06 1.60183360405127e-05 2.78543977573885e-05 -1.30762468353819e-06 -5.22181079080442e-06 2.48693165367921e-07 -1.05134958212373e-05 7.54922599458947e-06 -1.30762468353819e-06 1.45289155856775e-05 3.87798981820131e-07 3.89868353246499e-06 -2.83985757181796e-06 -3.26146671542686e-06 -5.22181079080442e-06 3.87798981820131e-07 7.30576419745406e-05 6.42158094816956e-06 3.24642997198198e-05 2.26746443740274e-06 2.48693165367921e-07 3.89868353246499e-06 6.42158094816956e-06 1.40996043797846e-05 6.7241752927324e-06 3.47396707898475e-06 -1.05134958212373e-05 -2.83985757181796e-06 3.24642997198198e-05 6.7241752927324e-06 0.000141262426709092 3209 3178 0 538 86 3209 3178 0 496 200 0 0 0 0 0 0 0 0 3311 0 0 0 0 0 945 +940 863 0.828656114589588 0.558646430375254 0.0352591772773374 -0.332762422794302 -0.558997039700735 0.829169644205297 0.000103606350624552 -0.282653326814384 -0.0291779601600807 -0.0197956297562704 0.999378196521942 0.961378775046923 0.000209408546137689 4.23185990710115e-05 -8.37900958463027e-06 -7.40334144180936e-05 1.80297921254306e-05 -0.000128498816959846 4.23185990710115e-05 0.000138872059374465 -3.90687371631507e-06 2.89212845244341e-05 2.0579507422304e-05 -2.21343729487334e-05 -8.37900958463027e-06 -3.90687371631507e-06 1.49966415641018e-05 -4.85264998597482e-06 6.96982547779282e-06 2.48839160320747e-06 -7.40334144180936e-05 2.89212845244341e-05 -4.85264998597482e-06 0.000126407222973409 5.87318690554669e-06 0.000143417228175023 1.80297921254306e-05 2.0579507422304e-05 6.96982547779282e-06 5.87318690554669e-06 5.50854652373373e-05 4.63181186812333e-05 -0.000128498816959846 -2.21343729487334e-05 2.48839160320747e-06 0.000143417228175023 4.63181186812333e-05 0.000471107952824268 284 289 0 566 0 284 289 0 556 0 0 0 0 0 0 0 0 0 417 0 0 0 0 0 223 +940 853 0.836119657310669 0.527731138073697 0.149678871475335 -0.596553507189567 -0.532346266843034 0.846459390512395 -0.0106748485548671 -0.0524190509740926 -0.13233053629822 -0.0707555377396342 0.98867703677298 0.547589737363436 5.32007192482123e-05 3.06541666298997e-05 7.1727763859986e-06 -1.94470293663715e-05 -4.74184131313174e-06 1.4756743808685e-06 3.06541666298997e-05 0.000100770202354339 4.73091829013356e-06 1.72150314062836e-05 1.38784778673963e-05 0.000105829752634824 7.1727763859986e-06 4.73091829013356e-06 1.34628691861094e-05 -4.49979291296128e-06 3.82579247149288e-06 -1.44281913892694e-05 -1.94470293663715e-05 1.72150314062836e-05 -4.49979291296128e-06 7.19321095333723e-05 2.02348660315201e-05 9.01659015940224e-05 -4.74184131313174e-06 1.38784778673963e-05 3.82579247149288e-06 2.02348660315201e-05 2.81534749584703e-05 5.95069934960031e-05 1.4756743808685e-06 0.000105829752634824 -1.44281913892694e-05 9.01659015940224e-05 5.95069934960031e-05 0.000531931373909199 951 973 0 822 0 978 1000 0 806 0 0 0 0 0 0 0 0 0 1854 0 338 338 0 0 269 +940 860 0.823109041762782 0.561099629096022 0.0875140651361884 -0.376265628195822 -0.557818898723864 0.82774759477051 -0.0605969931442975 -0.278636272693354 -0.106440507302669 0.00106093352359146 0.994318506729714 0.879396309555324 7.82178593835749e-05 3.72448825775867e-05 -8.77182336756304e-06 -2.43640591533477e-06 1.38029429385311e-06 -3.34050443807342e-05 3.72448825775867e-05 9.27417886821304e-05 -8.90540781971946e-06 1.19728610855314e-05 1.29546778430127e-05 4.51891961608503e-05 -8.77182336756304e-06 -8.90540781971946e-06 1.72155018668086e-05 -1.05891761915831e-05 8.0939728543879e-06 -5.41900415440644e-06 -2.43640591533477e-06 1.19728610855314e-05 -1.05891761915831e-05 4.99200297988027e-05 -2.14113750276671e-06 5.5690747509929e-05 1.38029429385311e-06 1.29546778430127e-05 8.0939728543879e-06 -2.14113750276671e-06 3.43869019558164e-05 3.85505859907524e-05 -3.34050443807342e-05 4.51891961608503e-05 -5.41900415440644e-06 5.5690747509929e-05 3.85505859907524e-05 0.000345586355186123 485 502 0 676 0 488 505 0 664 0 0 0 0 0 0 0 0 0 455 0 8 8 0 0 261 +940 944 0.991329852623178 0.127224929386463 0.0328472318577603 0.413265759113358 -0.126689233820287 0.991780693597126 -0.0179135100422372 0.0694674021640102 -0.0348562954448224 0.0135968066329578 0.999299837644963 -0.122098088546066 5.16560568820346e-05 1.72513592136559e-05 4.65264131138958e-06 5.53382780924909e-06 3.45975196249982e-06 3.42459952713796e-06 1.72513592136559e-05 3.11312332325118e-05 1.90669023123703e-06 3.80248915314988e-06 -1.64000111035336e-06 9.80344390843762e-07 4.65264131138958e-06 1.90669023123703e-06 1.15639725212022e-05 3.37997351908362e-06 4.78576481003674e-06 -4.44258076331775e-06 5.53382780924909e-06 3.80248915314988e-06 3.37997351908362e-06 7.25085497239061e-05 7.59727118861807e-06 3.47502282007565e-05 3.45975196249982e-06 -1.64000111035336e-06 4.78576481003674e-06 7.59727118861807e-06 1.42998099634314e-05 1.76737472574297e-05 3.42459952713796e-06 9.80344390843762e-07 -4.44258076331775e-06 3.47502282007565e-05 1.76737472574297e-05 0.000176822646276921 3251 3219 0 752 110 3251 3219 0 702 251 0 0 0 0 0 0 0 0 3088 0 0 0 0 0 996 +940 868 0.800417938626058 0.597624568283262 0.046647603473879 -0.313063043384813 -0.595573149369042 0.801667334245226 -0.0512065323449439 -0.307061557286626 -0.067998141711763 0.0132045669522722 0.997598061413188 0.970555343556288 0.000121729631789833 4.67101704793591e-05 -1.00371802329574e-05 -3.94406011295744e-06 -5.597383659652e-06 -4.30154464807568e-05 4.67101704793591e-05 6.99255355801071e-05 -6.14166273001717e-06 -1.12114353168606e-05 2.71455212899323e-06 -4.10953531861178e-05 -1.00371802329574e-05 -6.14166273001717e-06 1.82785108355598e-05 -1.22018841441689e-05 9.85415375614492e-06 2.86560041042448e-06 -3.94406011295744e-06 -1.12114353168606e-05 -1.22018841441689e-05 6.38766893688441e-05 -1.38076953289772e-05 1.30733221089783e-05 -5.597383659652e-06 2.71455212899323e-06 9.85415375614492e-06 -1.38076953289772e-05 3.75571993911383e-05 -8.41517559296532e-07 -4.30154464807568e-05 -4.10953531861178e-05 2.86560041042448e-06 1.30733221089783e-05 -8.41517559296532e-07 0.00014161710249143 275 288 0 554 0 275 288 0 550 0 0 0 0 0 0 0 0 0 178 0 0 0 0 0 272 +940 865 0.822228112536504 0.568746789183338 0.0216337871927742 -0.310137217727974 -0.568346575033314 0.822491477291351 -0.022134598053566 -0.29960540699267 -0.030382587160421 0.00590419992332499 0.999520904644172 0.982024377527132 0.000134985775966005 4.09680045031729e-05 -6.74152120619692e-06 -1.24585239770334e-05 1.15693707449859e-05 -3.09829628037432e-05 4.09680045031729e-05 0.000201969812384454 -9.58229455181336e-06 9.1434035761494e-05 5.75524544956136e-05 0.000119674709269292 -6.74152120619692e-06 -9.58229455181336e-06 1.94183589379677e-05 -1.90350806802094e-05 3.54643776010712e-06 -1.58887044643401e-05 -1.24585239770334e-05 9.1434035761494e-05 -1.90350806802094e-05 0.000159667937842614 4.76096409557745e-05 0.000207841281735612 1.15693707449859e-05 5.75524544956136e-05 3.54643776010712e-06 4.76096409557745e-05 8.89639620147525e-05 0.000161826256001677 -3.09829628037432e-05 0.000119674709269292 -1.58887044643401e-05 0.000207841281735612 0.000161826256001677 0.000671537014688636 279 288 0 512 0 279 288 0 504 0 0 0 0 0 0 0 0 0 214 0 0 0 0 0 265 +940 874 0.807445229906863 0.58976883375293 0.0143151470255362 -0.283886135221058 -0.589355740722561 0.807486588241374 -0.0250044133637886 -0.303152863806627 -0.0263061129400616 0.0117529802184232 0.999584841760803 1.0140742017704 8.38819145998693e-05 2.13570513442826e-05 -2.12565183800565e-06 -2.20275848381992e-05 -3.80088642635726e-06 -1.14765251555017e-05 2.13570513442826e-05 8.99454580245108e-05 -2.6849538931223e-06 1.5990064855405e-06 1.07853882751406e-05 -1.73516728099074e-05 -2.12565183800565e-06 -2.6849538931223e-06 1.56367085319456e-05 -1.05322161271723e-05 9.53630147244327e-06 -5.65551559149838e-06 -2.20275848381992e-05 1.5990064855405e-06 -1.05322161271723e-05 8.58862794591748e-05 -1.18426066206666e-05 5.87495091303529e-05 -3.80088642635726e-06 1.07853882751406e-05 9.53630147244327e-06 -1.18426066206666e-05 4.19411947571472e-05 1.66987568190364e-05 -1.14765251555017e-05 -1.73516728099074e-05 -5.65551559149838e-06 5.87495091303529e-05 1.66987568190364e-05 0.000184499448850518 239 252 0 460 0 239 252 0 452 0 0 0 0 0 0 0 0 0 108 0 0 0 0 0 264 +940 870 0.793925080475014 0.605870457065848 0.0510289706692564 -0.302530805911434 -0.604256835335361 0.795551016757328 -0.0444100966771791 -0.314266721492777 -0.0675029150721478 0.00442368525130673 0.997709270010838 0.995921303834939 0.000134062476579831 1.73895119387443e-05 -2.42129743604117e-06 -4.61628756759878e-05 -9.99123607796407e-06 -4.06019338831092e-05 1.73895119387443e-05 9.98225551573373e-05 -9.00861205742222e-06 1.18733163074119e-05 8.52207123244346e-06 -8.19787997092504e-06 -2.42129743604117e-06 -9.00861205742222e-06 1.60910990716626e-05 -1.01996333718037e-05 8.8116725040759e-06 8.25554545216013e-07 -4.61628756759878e-05 1.18733163074119e-05 -1.01996333718037e-05 0.000110425380070983 1.67644586068369e-05 5.55773568029406e-05 -9.99123607796407e-06 8.52207123244346e-06 8.8116725040759e-06 1.67644586068369e-05 5.06427547828428e-05 5.69016281778846e-05 -4.06019338831092e-05 -8.19787997092504e-06 8.25554545216013e-07 5.55773568029406e-05 5.69016281778846e-05 0.000211694134857254 290 303 0 571 0 290 303 0 564 0 0 0 0 0 0 0 0 0 121 0 0 0 0 0 268 +940 878 0.80139480509852 0.598002438097118 0.0126273667487823 -0.284706037850596 -0.597144966209112 0.801103641967716 -0.0406305815510889 -0.305561513373516 -0.0344130163197665 0.0250207684926627 0.999094442708902 1.01261985701769 0.000123830877175056 3.39402691908447e-05 -4.24922142496979e-06 -1.85481033789177e-05 -1.61865417956693e-05 -6.70720218366126e-05 3.39402691908447e-05 7.69829341505709e-05 -3.73831022690729e-06 6.50925288067705e-06 2.68210246655957e-06 -2.00502148944591e-05 -4.24922142496979e-06 -3.73831022690729e-06 1.47757487516046e-05 -1.26853956936049e-05 1.13770851811858e-05 3.081582735203e-06 -1.85481033789177e-05 6.50925288067705e-06 -1.26853956936049e-05 0.000111967671269962 -1.88713797729397e-05 3.90580097901036e-05 -1.61865417956693e-05 2.68210246655957e-06 1.13770851811858e-05 -1.88713797729397e-05 4.53606205105171e-05 2.11229502027303e-05 -6.70720218366126e-05 -2.00502148944591e-05 3.081582735203e-06 3.90580097901036e-05 2.11229502027303e-05 0.000213803850622322 198 209 0 449 0 198 209 0 442 0 0 0 0 0 0 0 0 0 86 0 0 0 0 0 235 +940 869 0.794335557535236 0.605635788853979 0.0472896742894753 -0.32788418942077 -0.604073025385562 0.795716751210849 -0.0439389558818221 -0.307151800338582 -0.064240190198348 0.00633585840036213 0.997914352467991 0.950800717455508 0.00013182258612049 7.3702870251904e-05 -1.02545234972085e-05 -3.87564239054315e-05 -6.28562028159601e-06 -3.53345456118761e-05 7.3702870251904e-05 0.000158706555055919 -7.05964035401755e-06 -2.33562995624944e-05 2.63457978524675e-05 8.86846292900034e-05 -1.02545234972085e-05 -7.05964035401755e-06 1.68337324345016e-05 -1.35905150304974e-05 8.66151836920807e-06 -1.11059432305801e-05 -3.87564239054315e-05 -2.33562995624944e-05 -1.35905150304974e-05 0.000114459597515532 7.63981094933612e-08 9.84298628643569e-05 -6.28562028159601e-06 2.63457978524675e-05 8.66151836920807e-06 7.63981094933612e-08 4.95038537787627e-05 9.87096136400516e-05 -3.53345456118761e-05 8.86846292900034e-05 -1.11059432305801e-05 9.84298628643569e-05 9.87096136400516e-05 0.000584200104037215 293 308 0 575 0 293 308 0 569 0 0 0 0 0 0 0 0 0 190 0 0 0 0 0 267 +940 871 0.796969958545232 0.603631425465644 0.0216330156641446 -0.32671126094147 -0.603106196007474 0.797223292368763 -0.0264185246012069 -0.313823931199813 -0.0331933956353601 0.00800776467087774 0.99941686707358 0.96179710443511 0.000132092254877273 3.93511809289656e-05 -8.24034649570961e-06 -4.64398811437442e-05 -1.17557339797881e-05 -0.000113768991403093 3.93511809289656e-05 0.000114160909574728 -3.00250083400445e-06 -1.21320335500747e-05 7.21333071270065e-06 -6.62457292315242e-06 -8.24034649570961e-06 -3.00250083400445e-06 1.84292369489648e-05 -9.94164114975889e-06 9.36248031338722e-06 -7.28805756041718e-07 -4.64398811437442e-05 -1.21320335500747e-05 -9.94164114975889e-06 0.000110683329034362 1.36682518784084e-05 0.000175068485506441 -1.17557339797881e-05 7.21333071270065e-06 9.36248031338722e-06 1.36682518784084e-05 5.3553132494883e-05 9.57963063667808e-05 -0.000113768991403093 -6.62457292315242e-06 -7.28805756041718e-07 0.000175068485506441 9.57963063667808e-05 0.000660637459268852 229 240 0 537 0 229 240 0 533 0 0 0 0 0 0 0 0 0 300 0 0 0 0 0 268 +940 875 0.802533112672097 0.59637489471775 0.0166609728175907 -0.282073719593 -0.59550207569633 0.802432879973496 -0.0384545313169104 -0.311966943031471 -0.0363026294667223 0.0209393908181113 0.999121444573165 1.01452220507444 0.000147706504721469 3.79332424355074e-05 -4.07971558496965e-06 -5.90087860002723e-05 -1.51127091404788e-05 -5.52817706110099e-05 3.79332424355074e-05 7.9414568931252e-05 1.26296408186952e-06 -1.4973312971461e-05 1.25113357898772e-05 8.01730902294651e-06 -4.07971558496965e-06 1.26296408186952e-06 1.68253334126678e-05 -9.04317848257793e-06 7.48469375581207e-06 -3.92312687659346e-06 -5.90087860002723e-05 -1.4973312971461e-05 -9.04317848257793e-06 0.000137027461960282 3.20252070998917e-06 6.79887700489632e-05 -1.51127091404788e-05 1.25113357898772e-05 7.48469375581207e-06 3.20252070998917e-06 4.58039380884977e-05 2.57465038297964e-05 -5.52817706110099e-05 8.01730902294651e-06 -3.92312687659346e-06 6.79887700489632e-05 2.57465038297964e-05 0.000286299982545653 217 228 0 474 0 217 228 0 471 0 0 0 0 0 0 0 0 0 89 0 0 0 0 0 237 +940 876 0.803279885109558 0.59531941928683 0.0183361718569032 -0.274946688418413 -0.59459098220449 0.803329372005442 -0.0335184121706473 -0.308192795522187 -0.0346841470916363 0.0160221438432259 0.999269883888829 1.01194426194637 0.000108320465150588 4.69510853561028e-05 -6.31639234719366e-06 -1.14024412043301e-05 -6.331957202003e-06 -5.21856894138961e-07 4.69510853561028e-05 9.38811230992278e-05 -2.10338234877836e-06 1.06696702579248e-05 1.76380013347131e-05 4.36881559394185e-05 -6.31639234719366e-06 -2.10338234877836e-06 1.63178353790884e-05 -1.3219271984727e-05 1.22328755545851e-05 -4.34864091662461e-06 -1.14024412043301e-05 1.06696702579248e-05 -1.3219271984727e-05 0.00010011958127213 -6.49365996394752e-06 7.3450089827162e-05 -6.331957202003e-06 1.76380013347131e-05 1.22328755545851e-05 -6.49365996394752e-06 5.95371069591264e-05 6.62625107584093e-05 -5.21856894138961e-07 4.36881559394185e-05 -4.34864091662461e-06 7.3450089827162e-05 6.62625107584093e-05 0.000389019662777003 202 212 0 487 0 202 212 0 483 0 0 0 0 0 0 0 0 0 108 0 0 0 0 0 262 +940 886 0.80019811238577 0.598582866663235 0.0371689745819616 -0.305325951025233 -0.597494293386705 0.801028160647644 -0.0368029240655505 -0.307008100851905 -0.0518029951312943 0.00724138016377284 0.998631069068428 0.97468690705458 0.000105895903031079 2.88113453676367e-05 -2.87857165358917e-06 -2.63892042631672e-05 -1.87588646217433e-06 -2.1827257434822e-05 2.88113453676367e-05 0.000123294374810479 -8.87890769999783e-06 1.21061727609007e-05 8.11305808810935e-06 -3.524406949288e-05 -2.87857165358917e-06 -8.87890769999783e-06 1.69225249812669e-05 -1.10325530391352e-05 6.95015613549873e-06 8.22681372006789e-08 -2.63892042631672e-05 1.21061727609007e-05 -1.10325530391352e-05 8.92200029003726e-05 -8.01517253695634e-06 1.88150645867272e-05 -1.87588646217433e-06 8.11305808810935e-06 6.95015613549873e-06 -8.01517253695634e-06 4.42770265769717e-05 2.59258458231415e-05 -2.1827257434822e-05 -3.524406949288e-05 8.22681372006789e-08 1.88150645867272e-05 2.59258458231415e-05 0.000226916525373115 233 243 0 539 0 233 243 0 529 0 0 0 0 0 0 0 0 0 191 0 0 0 0 0 232 +940 872 0.803408846504271 0.595272479518824 0.0135978118161582 -0.317175415302168 -0.594629542820777 0.803304665863457 -0.033426345997637 -0.308883498496631 -0.0308209695407206 0.0187693614572091 0.999348677342928 0.982934857831307 9.42757536184891e-05 4.20556407298836e-05 -8.69737721472189e-06 1.790759408943e-05 2.07778266872784e-05 3.55653889727122e-05 4.20556407298836e-05 0.000115089731110315 -6.54322736905652e-06 2.49076421359025e-05 1.30100319651044e-05 2.7160919471382e-06 -8.69737721472189e-06 -6.54322736905652e-06 1.65985236566009e-05 -1.38674592574554e-05 6.99209362636848e-06 -1.24167147919193e-05 1.790759408943e-05 2.49076421359025e-05 -1.38674592574554e-05 8.77267112281325e-05 -4.48322939444623e-06 7.07444865992542e-05 2.07778266872784e-05 1.30100319651044e-05 6.99209362636848e-06 -4.48322939444623e-06 5.8542460563664e-05 5.96867719726709e-05 3.55653889727122e-05 2.7160919471382e-06 -1.24167147919193e-05 7.07444865992542e-05 5.96867719726709e-05 0.000272721254197932 219 231 0 500 0 219 231 0 496 0 0 0 0 0 0 0 0 0 197 0 0 0 0 0 260 +940 877 0.804216404046417 0.594168437353531 0.0141366019790401 -0.2846515654764 -0.593262844637131 0.80396548387359 -0.040971916149513 -0.310802784487132 -0.0357095594443433 0.0245635663690644 0.999060287756211 1.00709748343685 0.000114670273461525 5.39936408583128e-05 -7.5685969660938e-06 3.19676337860416e-06 -4.63054940492198e-06 -2.08538838159574e-05 5.39936408583128e-05 8.97960471419511e-05 -2.54692903773769e-06 2.44188764863111e-06 1.33728032872129e-05 2.71655639521114e-05 -7.5685969660938e-06 -2.54692903773769e-06 1.75073513069393e-05 -1.20495629186664e-05 9.64290501594807e-06 -7.71387017815298e-06 3.19676337860416e-06 2.44188764863111e-06 -1.20495629186664e-05 8.47021626942462e-05 -5.17514199743016e-06 7.31059290201069e-05 -4.63054940492198e-06 1.33728032872129e-05 9.64290501594807e-06 -5.17514199743016e-06 6.81329330712051e-05 5.40936486412774e-05 -2.08538838159574e-05 2.71655639521114e-05 -7.71387017815298e-06 7.31059290201069e-05 5.40936486412774e-05 0.000309845762978479 217 229 0 462 0 217 229 0 459 0 0 0 0 0 0 0 0 0 83 0 0 0 0 0 284 +940 887 0.799801952596903 0.59751483807632 0.0573834026597478 -0.308855633865769 -0.597545115303981 0.801621326051002 -0.0185225483285765 -0.301869418101072 -0.0570672567987359 -0.0194748016385878 0.998180374633064 0.972188962641549 8.28301721108956e-05 4.56768313323854e-05 -2.58923597974267e-06 -1.20798053016417e-05 -1.53996189195418e-06 -3.42425445772098e-05 4.56768313323854e-05 0.000144583169058013 -3.35078157525085e-06 1.92163674936306e-05 3.07325702296334e-05 6.22092055388875e-05 -2.58923597974267e-06 -3.35078157525085e-06 1.47844228068839e-05 -6.80380720554587e-06 9.42618319828155e-06 4.04520174457105e-06 -1.20798053016417e-05 1.92163674936306e-05 -6.80380720554587e-06 7.01864596911543e-05 1.00896157341834e-05 9.84115393883717e-05 -1.53996189195418e-06 3.07325702296334e-05 9.42618319828155e-06 1.00896157341834e-05 4.91972280175817e-05 8.60899895207953e-05 -3.42425445772098e-05 6.22092055388875e-05 4.04520174457105e-06 9.84115393883717e-05 8.60899895207953e-05 0.000594300763472367 288 302 0 575 0 288 302 0 567 0 0 0 0 0 0 0 0 0 319 0 0 0 0 0 236 +941 860 0.839202076189729 0.538588919880833 0.0752452702862174 -0.464768886927553 -0.537608584754513 0.842489807452207 -0.0344664175305875 -0.297309859881216 -0.0819566038650855 -0.011528214117553 0.996569222564173 0.935052140885534 0.00010448349104451 4.71334598191827e-05 -1.00570375845498e-05 -3.77056048594832e-06 5.63372318739276e-06 -3.4647465388273e-05 4.71334598191827e-05 0.000425012942994171 -3.35528792822767e-05 0.000274710443600204 0.000202593810509414 0.000840176530919085 -1.00570375845498e-05 -3.35528792822767e-05 1.95182727682656e-05 -3.44271879043738e-05 -1.36138105774989e-05 -7.57868657429106e-05 -3.77056048594832e-06 0.000274710443600204 -3.44271879043738e-05 0.000320754923725355 0.000187575248196982 0.00073347188608043 5.63372318739276e-06 0.000202593810509414 -1.36138105774989e-05 0.000187575248196982 0.000168662020965014 0.000531600692583025 -3.4647465388273e-05 0.000840176530919085 -7.57868657429106e-05 0.00073347188608043 0.000531600692583025 0.00238453591360402 416 433 0 608 0 416 433 0 596 0 0 0 0 0 0 0 0 0 428 0 10 10 0 0 167 +941 858 0.824472693164218 0.562151245676 0.0650442557914423 -0.480476286771936 -0.563286916696279 0.826260691788639 -0.001057678476145 -0.285714329694401 -0.0543380870600039 -0.0357665512718365 0.997881819708516 0.886840087306087 0.000216991849446718 -1.20560018344268e-05 -7.50321934243779e-06 -8.33829712926949e-05 -6.79274082176595e-07 -0.000276541411263855 -1.20560018344268e-05 0.000218001487736085 -1.45650281707682e-05 8.03772119992422e-05 6.25100649213752e-05 0.000295781832474038 -7.50321934243779e-06 -1.45650281707682e-05 1.8401208391111e-05 -8.06317949486679e-06 2.72857266545158e-06 -1.22447999212427e-05 -8.33829712926949e-05 8.03772119992422e-05 -8.06317949486679e-06 0.000140069334835621 2.7407783902001e-05 0.000312584535642153 -6.79274082176595e-07 6.25100649213752e-05 2.72857266545158e-06 2.7407783902001e-05 5.74957265620375e-05 0.000137074788434634 -0.000276541411263855 0.000295781832474038 -1.22447999212427e-05 0.000312584535642153 0.000137074788434634 0.00119319007707462 387 408 0 647 0 387 408 0 637 0 0 0 0 0 0 0 0 0 569 0 16 16 0 0 183 +941 859 0.829077327526874 0.551345729312017 0.092998235199902 -0.457609558425743 -0.553125200178398 0.833062004746895 -0.00775945711317618 -0.296809847125643 -0.0817514397946831 -0.045006477494732 0.99563603745295 0.941424109383187 0.000210100010636274 6.86145162214611e-05 -7.93672683963142e-06 -7.36208172388037e-05 -1.81004241063467e-06 -0.000122630065186851 6.86145162214611e-05 0.00012346140237649 -7.28316737354408e-06 -1.52141207574927e-05 1.32812326373146e-05 9.70301073991011e-06 -7.93672683963142e-06 -7.28316737354408e-06 1.72245440872421e-05 -3.35148609686262e-06 5.1163192717035e-06 -4.31527264671136e-07 -7.36208172388037e-05 -1.52141207574927e-05 -3.35148609686262e-06 9.7904352386625e-05 1.26237380535562e-05 8.49919365686678e-05 -1.81004241063467e-06 1.32812326373146e-05 5.1163192717035e-06 1.26237380535562e-05 3.92223663711453e-05 3.79637894184214e-05 -0.000122630065186851 9.70301073991011e-06 -4.31527264671136e-07 8.49919365686678e-05 3.79637894184214e-05 0.000473171995909374 469 479 0 668 0 469 479 0 660 0 0 0 0 0 0 0 0 0 519 0 13 13 0 0 187 +941 855 0.843321823233105 0.529113052641617 0.0940621070519997 -0.587462994882899 -0.527575762977247 0.848440415524755 -0.0425755284542225 -0.186446472233769 -0.102333361020576 -0.0137200156140784 0.994655540573611 0.699328317462414 7.11805085437717e-05 2.95575920648819e-05 8.86902580683489e-06 -5.387682588637e-06 -5.95442320482698e-06 -2.07816234718527e-05 2.95575920648819e-05 0.000120676080053794 -5.28035571361718e-06 2.40362055610809e-05 7.59111386680362e-06 -1.27867668371788e-05 8.86902580683489e-06 -5.28035571361718e-06 1.59151817363786e-05 -7.85508746485603e-06 2.39469402348076e-06 -3.69088783326258e-06 -5.387682588637e-06 2.40362055610809e-05 -7.85508746485603e-06 6.59548275017287e-05 1.375730599862e-05 7.86967468383144e-06 -5.95442320482698e-06 7.59111386680362e-06 2.39469402348076e-06 1.375730599862e-05 3.35774322853606e-05 3.69216692687999e-05 -2.07816234718527e-05 -1.27867668371788e-05 -3.69088783326258e-06 7.86967468383144e-06 3.69216692687999e-05 0.000293949633865167 704 728 0 711 0 714 738 0 701 0 0 0 0 0 0 0 0 0 1040 0 241 241 0 0 199 +941 851 0.878151442942675 0.467590808177211 0.101038999232378 -0.842030498580529 -0.475356938973585 0.876629718089725 0.0745393716876725 0.0383196182805254 -0.0537198643646869 -0.113486446195628 0.992086187134226 0.429503129068599 4.94548168880364e-05 2.60812312226706e-05 1.2282843128509e-06 -5.48004813398138e-06 1.93289331955912e-06 2.03819344725388e-05 2.60812312226706e-05 0.000144462450920546 -5.9177472754461e-06 5.45113235350014e-05 2.5776057720344e-05 0.000243173929873304 1.2282843128509e-06 -5.9177472754461e-06 1.14407485303615e-05 -8.48911175399053e-06 1.95341760084279e-06 -1.30689103856964e-05 -5.48004813398138e-06 5.45113235350014e-05 -8.48911175399053e-06 0.00011941043480358 4.15346316744516e-05 0.000194195741210327 1.93289331955912e-06 2.5776057720344e-05 1.95341760084279e-06 4.15346316744516e-05 3.29433634166689e-05 9.34232470879974e-05 2.03819344725388e-05 0.000243173929873304 -1.30689103856964e-05 0.000194195741210327 9.34232470879974e-05 0.000822489583814046 1000 1017 0 542 0 1016 1033 0 529 0 0 0 0 0 0 0 0 0 2966 0 590 632 0 0 171 +941 861 0.843479244027808 0.535791131386048 0.0383487734137051 -0.452182763948321 -0.535501852088675 0.844335268970043 -0.0183226630947351 -0.293993063517439 -0.0421963423044655 -0.00508105317264465 0.999096417566784 0.964772654720578 0.000134593465923528 3.08646006323846e-05 -5.4365235888637e-06 -2.47920899585945e-05 6.91557262655847e-07 -3.91519864906517e-05 3.08646006323846e-05 5.58140907141982e-05 2.74213044039681e-06 -2.47365617099178e-06 -7.38822834763332e-06 -1.33898657362754e-05 -5.4365235888637e-06 2.74213044039681e-06 1.46112732619867e-05 -6.21973541075757e-06 7.32022509945175e-06 -1.15399156014694e-06 -2.47920899585945e-05 -2.47365617099178e-06 -6.21973541075757e-06 5.10632910107666e-05 -1.76596332707235e-05 4.07142394333952e-05 6.91557262655847e-07 -7.38822834763332e-06 7.32022509945175e-06 -1.76596332707235e-05 3.3773735331965e-05 1.00563405546021e-05 -3.91519864906517e-05 -1.33898657362754e-05 -1.15399156014694e-06 4.07142394333952e-05 1.00563405546021e-05 0.000201402963531989 406 421 0 543 0 406 421 0 538 0 0 0 0 0 0 0 0 0 254 0 2 2 0 0 182 +941 854 0.848052031875462 0.51805071096806 0.111495345631054 -0.649401280446688 -0.520972782357745 0.853566530597878 -0.00339674631553679 -0.138266724171326 -0.0969283821918523 -0.0552054228186924 0.993759150909857 0.616651979486506 8.51143263682951e-05 2.82785353023747e-05 -8.48429046544111e-06 -6.28558385735875e-06 1.01693759905485e-05 -2.46773995302056e-05 2.82785353023747e-05 4.7380754500672e-05 -8.12011230692128e-06 4.74868078837265e-06 9.23304810328638e-06 -1.29705813273857e-05 -8.48429046544111e-06 -8.12011230692128e-06 1.37294687203653e-05 -2.54879414296284e-06 3.84325215582827e-06 6.31585545007113e-06 -6.28558385735875e-06 4.74868078837265e-06 -2.54879414296284e-06 5.10544218046659e-05 6.75050761475066e-06 2.10095492034592e-05 1.01693759905485e-05 9.23304810328638e-06 3.84325215582827e-06 6.75050761475066e-06 2.24504833072282e-05 1.29773620707614e-05 -2.46773995302056e-05 -1.29705813273857e-05 6.31585545007113e-06 2.10095492034592e-05 1.29773620707614e-05 0.00015310976847767 788 812 0 763 0 798 822 0 744 0 0 0 0 0 0 0 0 0 1637 0 282 282 0 0 174 +941 867 0.828518684216581 0.559576184877505 0.0207673595327316 -0.409614078210911 -0.559104943587815 0.828732780419403 -0.0245691007973682 -0.323962440326382 -0.0309588752975922 0.00874482568500431 0.999482404079255 1.02229324294546 0.00018476651851659 1.3439996950407e-05 -1.21463857263683e-05 -2.52094655655772e-05 2.01255354778275e-05 -1.90383280757619e-05 1.3439996950407e-05 0.000101291846054036 -5.70846660418931e-06 4.79300348730993e-05 2.56732161551399e-05 4.37813785586628e-05 -1.21463857263683e-05 -5.70846660418931e-06 1.66160113603201e-05 -1.23132014250712e-05 2.88544232430004e-06 -9.41643536583761e-06 -2.52094655655772e-05 4.79300348730993e-05 -1.23132014250712e-05 0.000133941153671673 2.48757650383005e-05 0.000122770706735261 2.01255354778275e-05 2.56732161551399e-05 2.88544232430004e-06 2.48757650383005e-05 7.60149130598025e-05 9.9166855015365e-05 -1.90383280757619e-05 4.37813785586628e-05 -9.41643536583761e-06 0.000122770706735261 9.9166855015365e-05 0.00045082321428274 291 305 0 468 0 291 305 0 465 0 0 0 0 0 0 0 0 0 95 0 0 0 0 0 182 +941 850 0.892829493580901 0.437064250731378 0.108767348614789 -0.9584801122235 -0.446751297508994 0.89005027341618 0.0906851088427046 0.093503545993985 -0.0571731892245154 -0.129558293923631 0.98992215598475 0.338396686728915 4.94551466459329e-05 4.66104395692888e-05 2.15225019524986e-06 2.84897016442439e-05 1.25105741737525e-05 6.87391104706522e-05 4.66104395692888e-05 0.000223962200958967 -3.0270583420406e-06 0.000152407822998813 5.50132339295772e-05 0.000337424645008625 2.15225019524986e-06 -3.0270583420406e-06 1.20602497460908e-05 -8.81393910784027e-06 1.82600531110512e-06 -1.30397281088006e-05 2.84897016442439e-05 0.000152407822998813 -8.81393910784027e-06 0.000179476377714332 5.79302799392217e-05 0.000329866556752098 1.25105741737525e-05 5.50132339295772e-05 1.82600531110512e-06 5.79302799392217e-05 3.57047311330783e-05 0.000119883960879269 6.87391104706522e-05 0.000337424645008625 -1.30397281088006e-05 0.000329866556752098 0.000119883960879269 0.00092526352505077 1070 1085 0 344 0 1079 1094 0 330 0 0 0 0 0 0 0 0 0 3467 0 820 822 0 0 205 +941 849 0.910678085706914 0.399877921360908 0.103745227462621 -1.04222876097682 -0.409576882249408 0.906745670217161 0.100294900514861 0.150437197153732 -0.0539648194664447 -0.133828014819435 0.989534163487771 0.345666128367325 5.84582102826092e-05 1.61670640785226e-05 -9.9099142709091e-07 1.63882299865107e-05 8.78633179818167e-06 -2.36460615517815e-05 1.61670640785226e-05 4.81237900054175e-05 -2.27875580675947e-06 1.48831925195192e-05 4.14503455871129e-06 -1.98399751798534e-05 -9.9099142709091e-07 -2.27875580675947e-06 1.11333784898458e-05 -6.90918837579668e-06 4.30281984798676e-06 2.22874005974543e-06 1.63882299865107e-05 1.48831925195192e-05 -6.90918837579668e-06 8.41831189870582e-05 2.26382738147022e-05 2.29119534113054e-05 8.78633179818167e-06 4.14503455871129e-06 4.30281984798676e-06 2.26382738147022e-05 2.18682546849451e-05 7.20875702247999e-06 -2.36460615517815e-05 -1.98399751798534e-05 2.22874005974543e-06 2.29119534113054e-05 7.20875702247999e-06 9.57363600753325e-05 1213 1220 0 169 0 1224 1231 0 155 0 0 0 0 0 0 0 0 0 3512 0 679 679 0 0 157 +941 943 0.996284338641846 0.0861200002617688 0.000928510577181525 0.192511558478133 -0.086103695504229 0.995740127514971 0.0329810866555944 0.0333772164017677 0.00191577595089148 -0.0329384882983684 0.999455544679764 -0.0486107484262864 5.42412033603225e-05 1.36866470733533e-05 3.96914846714441e-06 3.16934580286727e-06 2.75266123582897e-06 -1.33113808702333e-05 1.36866470733533e-05 2.45245728031391e-05 -4.77281950302379e-07 -1.043346938111e-06 -1.4180867814864e-06 9.36045021677451e-07 3.96914846714441e-06 -4.77281950302379e-07 1.12641343299311e-05 2.70931381377503e-06 4.83264694253522e-06 -2.6049994055536e-06 3.16934580286727e-06 -1.043346938111e-06 2.70931381377503e-06 6.30970290994322e-05 3.85214645279821e-06 2.72819675686449e-05 2.75266123582897e-06 -1.4180867814864e-06 4.83264694253522e-06 3.85214645279821e-06 1.45009245536084e-05 1.01109378403934e-05 -1.33113808702333e-05 9.36045021677451e-07 -2.6049994055536e-06 2.72819675686449e-05 1.01109378403934e-05 0.00019508906946701 3274 3243 0 385 2 3274 3243 0 347 49 0 0 0 0 0 0 0 0 3465 0 0 0 0 0 1652 +941 944 0.995064008896791 0.0984753350923294 0.0122566951785841 0.313418530696219 -0.0985920943265962 0.995084324394233 0.009315915476682 0.0453103113717761 -0.0112790573428294 -0.0104783454479501 0.999881486548346 -0.0855521533728879 6.25546616481048e-05 2.62232543280522e-05 3.20694788852382e-06 8.03932267033916e-06 1.56351577272453e-06 -8.60295226774202e-06 2.62232543280522e-05 4.16240098450764e-05 1.0917850834016e-06 1.07091540869209e-05 3.68520949015338e-06 2.97112917560926e-05 3.20694788852382e-06 1.0917850834016e-06 1.2028738583671e-05 3.28303107429751e-06 5.16159264660404e-06 -6.58064736733383e-06 8.03932267033916e-06 1.07091540869209e-05 3.28303107429751e-06 0.000136382701774557 1.55927216738356e-05 0.000102254209746656 1.56351577272453e-06 3.68520949015338e-06 5.16159264660404e-06 1.55927216738356e-05 1.78880265543575e-05 4.27050356178543e-05 -8.60295226774202e-06 2.97112917560926e-05 -6.58064736733383e-06 0.000102254209746656 4.27050356178543e-05 0.000435543210698166 3227 3194 0 566 17 3227 3194 0 524 67 0 0 0 0 0 0 0 0 3268 0 0 0 0 0 1598 +941 868 0.817674077801573 0.575168821928176 0.0242884493762139 -0.42148411054065 -0.574479120480088 0.817965162630094 -0.0301120051797838 -0.323882574126094 -0.037186591989199 0.0106685990306634 0.999251388976243 0.998521193961512 0.00038683914656844 0.000123796376366747 -1.83648431283274e-05 -0.000147675244211644 5.01051784064509e-05 -4.0621180822135e-05 0.000123796376366747 0.000118254010036809 -1.14737954338336e-05 -4.29052782590224e-05 1.45371550066858e-05 -2.81355791474654e-05 -1.83648431283274e-05 -1.14737954338336e-05 2.13248622850134e-05 -6.72467842647581e-06 4.43469988496333e-06 5.44096934617478e-06 -0.000147675244211644 -4.29052782590224e-05 -6.72467842647581e-06 0.000157935679829219 -1.55198627691357e-05 6.08003843708052e-05 5.01051784064509e-05 1.45371550066858e-05 4.43469988496333e-06 -1.55198627691357e-05 6.81985990164496e-05 4.95115954240228e-05 -4.0621180822135e-05 -2.81355791474654e-05 5.44096934617478e-06 6.08003843708052e-05 4.95115954240228e-05 0.000490970131283634 259 270 0 491 0 259 270 0 487 0 0 0 0 0 0 0 0 0 151 0 0 0 0 0 173 +941 874 0.824147330140761 0.566309358751703 -0.00865380910873695 -0.396824053781473 -0.566372413428542 0.824096904680185 -0.00930489138388652 -0.321050086375033 0.0018621302273403 0.0125698801415451 0.999919262032812 1.05244414938765 0.000301797785492385 7.13130141486794e-05 -1.26125361025936e-06 -0.00013949895702625 1.27119716986793e-05 1.52344035696009e-05 7.13130141486794e-05 8.63173664529591e-05 1.42832754447899e-06 -2.61057293884464e-05 1.14749306070361e-05 2.43800712178012e-05 -1.26125361025936e-06 1.42832754447899e-06 1.99726093398567e-05 -9.9282141705454e-06 7.64173439429297e-06 3.79246707364605e-06 -0.00013949895702625 -2.61057293884464e-05 -9.9282141705454e-06 0.00016450833638054 -2.35995882941066e-06 1.96931288403098e-05 1.27119716986793e-05 1.14749306070361e-05 7.64173439429297e-06 -2.35995882941066e-06 6.45134676391329e-05 3.83748146911217e-05 1.52344035696009e-05 2.43800712178012e-05 3.79246707364605e-06 1.96931288403098e-05 3.83748146911217e-05 0.000403276301026661 211 224 0 406 0 211 224 0 400 0 0 0 0 0 0 0 0 0 72 0 0 0 0 0 170 +941 870 0.812303667649835 0.582747695144793 0.0238301348308605 -0.413446443650021 -0.582644601057316 0.812641679889928 -0.011780023957421 -0.323136867839053 -0.0262301426108915 -0.0043155427360528 0.99964661541442 1.03302240261491 0.000166656015095662 7.78916568823197e-05 -7.60954819076907e-06 -3.66205223603671e-05 7.33318121416834e-06 4.79622026549462e-06 7.78916568823197e-05 0.000137491406740943 -1.15687317231814e-05 2.6584111111306e-06 2.00207008886219e-05 5.32398265051845e-05 -7.60954819076907e-06 -1.15687317231814e-05 1.86404988277709e-05 -9.26070107160481e-06 8.70723411753223e-06 2.23599323458625e-06 -3.66205223603671e-05 2.6584111111306e-06 -9.26070107160481e-06 9.20917699892349e-05 1.06960026888596e-05 6.78406704540045e-05 7.33318121416834e-06 2.00207008886219e-05 8.70723411753223e-06 1.06960026888596e-05 5.34039672058255e-05 7.38206368461529e-05 4.79622026549462e-06 5.32398265051845e-05 2.23599323458625e-06 6.78406704540045e-05 7.38206368461529e-05 0.000448635858111746 285 297 0 483 0 285 297 0 477 0 0 0 0 0 0 0 0 0 117 0 0 0 0 0 170 +941 878 0.818159079617159 0.57488914657278 -0.0108715037057371 -0.392241486120897 -0.574977115469518 0.818127476847982 -0.00829146022764517 -0.310693870388959 0.00412760540220511 0.0130345993100733 0.999906526678604 1.03386993881677 0.000163686240685039 3.0703030234117e-05 -4.17417249016275e-06 -5.40151810592357e-05 1.96180366034609e-06 -9.16965624015568e-05 3.0703030234117e-05 9.42300021501285e-05 -6.03133335536174e-06 1.64636558718141e-05 2.03295300382346e-05 1.06750314217347e-06 -4.17417249016275e-06 -6.03133335536174e-06 1.89632365630914e-05 -1.38788372152703e-05 9.34521138962516e-06 -6.07692884358357e-06 -5.40151810592357e-05 1.64636558718141e-05 -1.38788372152703e-05 0.000167535474274454 1.71918315857685e-05 0.000171089216615948 1.96180366034609e-06 2.03295300382346e-05 9.34521138962516e-06 1.71918315857685e-05 6.22608891564106e-05 8.7599732992913e-05 -9.16965624015568e-05 1.06750314217347e-06 -6.07692884358357e-06 0.000171089216615948 8.7599732992913e-05 0.000548120888145254 180 190 0 409 0 180 190 0 405 0 0 0 0 0 0 0 0 0 113 0 0 0 0 0 175 +941 877 0.82169573541957 0.569776550844228 -0.0130690665828742 -0.408621231966209 -0.569926248683785 0.821496941174994 -0.0180789021059647 -0.324900319982152 0.000435263736856486 0.0223037608529151 0.99975114543435 1.01593992227898 0.000204752679296422 7.60038108362126e-05 -6.79729619749233e-06 -3.05368760724864e-05 1.46999891018659e-05 -7.18263440255177e-05 7.60038108362126e-05 0.000142834693290775 5.29795159112846e-06 3.71282534245807e-05 2.78602762478611e-05 7.10379291865082e-05 -6.79729619749233e-06 5.29795159112846e-06 1.78200965292836e-05 -1.1990455169066e-05 5.30967521017107e-06 -3.96582861445805e-06 -3.05368760724864e-05 3.71282534245807e-05 -1.1990455169066e-05 0.00013557103875956 7.65258373329958e-06 0.000159102272023755 1.46999891018659e-05 2.78602762478611e-05 5.30967521017107e-06 7.65258373329958e-06 7.55923063034259e-05 6.01720548761351e-05 -7.18263440255177e-05 7.10379291865082e-05 -3.96582861445805e-06 0.000159102272023755 6.01720548761351e-05 0.000536794579520199 193 204 0 421 0 193 204 0 413 0 0 0 0 0 0 0 0 0 103 0 0 0 0 0 197 +942 946 0.996783513337401 0.0458726844229206 0.065713958658593 0.466138139533723 -0.0448784462013124 0.998855726013912 -0.0165276639539913 0.0653557101452968 -0.0663969321979866 0.0135253625849844 0.997701614693311 -0.102668175361746 4.74612534275059e-05 1.23012582616697e-05 1.98151585273435e-06 -5.98018222481195e-08 4.15879537786465e-06 -2.29336435215932e-05 1.23012582616697e-05 4.39660744987685e-05 -5.10343058484967e-06 4.08445339593565e-06 4.58247984853044e-06 -1.70144757824193e-05 1.98151585273435e-06 -5.10343058484967e-06 1.5051983145331e-05 2.65063529201461e-06 4.29753643352855e-06 8.80288316926816e-06 -5.98018222481195e-08 4.08445339593565e-06 2.65063529201461e-06 0.000106529412421916 4.30058186770376e-06 1.14139962760732e-05 4.15879537786465e-06 4.58247984853044e-06 4.29753643352855e-06 4.30058186770376e-06 1.45401639278412e-05 3.00154375133215e-06 -2.29336435215932e-05 -1.70144757824193e-05 8.80288316926816e-06 1.14139962760732e-05 3.00154375133215e-06 0.000179108845716114 3028 3052 0 614 224 3028 3052 0 568 224 0 0 0 0 0 0 0 0 3205 0 0 0 0 0 2331 +942 858 0.84672452784206 0.529261842602905 0.0542169338419205 -0.570001011875466 -0.526751156306519 0.848278362018822 -0.0543786710062855 -0.36867167366171 -0.0747716074481909 0.0174849219398502 0.997047383139022 0.931684035465425 0.000274959978082798 9.25332385648386e-05 -1.43967865307706e-05 -5.3284124282863e-05 3.5925604453812e-05 -0.000118914763771829 9.25332385648386e-05 0.00015747459885126 -6.17453368166788e-07 -6.83152016885679e-06 1.19275456640813e-05 -1.84276537129822e-05 -1.43967865307706e-05 -6.17453368166788e-07 1.80317621163487e-05 -2.72509317641345e-06 4.9688087709021e-06 6.45107696642786e-06 -5.3284124282863e-05 -6.83152016885679e-06 -2.72509317641345e-06 8.4862543813715e-05 -5.02806976057423e-06 5.74051674237712e-05 3.5925604453812e-05 1.19275456640813e-05 4.9688087709021e-06 -5.02806976057423e-06 4.76076178929277e-05 2.26169703977629e-05 -0.000118914763771829 -1.84276537129822e-05 6.45107696642786e-06 5.74051674237712e-05 2.26169703977629e-05 0.000378000409106014 405 426 0 555 0 412 433 0 550 0 0 0 0 0 0 0 0 0 223 0 6 6 0 0 105 +942 857 0.852519330854885 0.517869066177752 0.070869039889938 -0.609226889345859 -0.514974806586793 0.855388402351569 -0.0557819836804471 -0.346151859803202 -0.0895083186057794 0.0110594492907003 0.99592467058596 0.868625478186398 0.000105790753062246 5.39241769320388e-05 -6.33614933488782e-06 1.4863073322891e-06 7.70715289695517e-06 -2.22156172819671e-06 5.39241769320388e-05 0.000139351742030766 -2.73631661407582e-06 4.55533459812279e-06 3.88285434859813e-06 7.1352781312597e-05 -6.33614933488782e-06 -2.73631661407582e-06 1.59688476357526e-05 -3.3537882539186e-06 7.17970989075223e-06 5.96736066885852e-06 1.4863073322891e-06 4.55533459812279e-06 -3.3537882539186e-06 4.02945533032945e-05 -6.30758022382078e-06 2.56558969404871e-05 7.70715289695517e-06 3.88285434859813e-06 7.17970989075223e-06 -6.30758022382078e-06 3.09286480100491e-05 4.82631292814134e-05 -2.22156172819671e-06 7.1352781312597e-05 5.96736066885852e-06 2.56558969404871e-05 4.82631292814134e-05 0.000509480587785269 545 558 0 617 0 558 571 0 609 0 0 0 0 0 0 0 0 0 368 0 46 46 0 0 143 +942 860 0.861737403188871 0.502419591763792 0.0705917966707582 -0.563091010641871 -0.49780167247749 0.864160671900843 -0.0736194812430607 -0.383414141560128 -0.0979905241536908 0.0282999461446126 0.994784886407256 0.975325123466932 0.000176451300126711 2.15790981713351e-05 -8.80626126715552e-06 -4.20282005551754e-05 -2.41348130836845e-05 -9.39095470593571e-05 2.15790981713351e-05 0.000132585674794236 -4.2229550081892e-06 2.32002497680313e-05 8.34336639799766e-06 2.39334534371214e-05 -8.80626126715552e-06 -4.2229550081892e-06 1.84236177792529e-05 -3.60825679521789e-06 1.14638034724159e-05 7.94522367229247e-06 -4.20282005551754e-05 2.32002497680313e-05 -3.60825679521789e-06 9.41075502098459e-05 1.4814504764717e-05 9.6782550982482e-05 -2.41348130836845e-05 8.34336639799766e-06 1.14638034724159e-05 1.4814504764717e-05 4.6711847196432e-05 6.42336205642874e-05 -9.39095470593571e-05 2.39334534371214e-05 7.94522367229247e-06 9.6782550982482e-05 6.42336205642874e-05 0.000383208416713796 438 453 0 522 0 444 459 0 516 0 0 0 0 0 0 0 0 0 149 0 2 2 0 0 140 +942 853 0.87662961526069 0.472000657537122 0.0934660202021009 -0.807875952748421 -0.474009306439314 0.880519466321994 -0.000804261743171899 -0.154509087698055 -0.0826782622992037 -0.0435987237491551 0.995622145309469 0.549460408092118 7.70982181345047e-05 4.18524123770823e-05 -1.8328054542743e-06 -3.9094873534092e-06 5.85902226694495e-06 -3.69856604716265e-05 4.18524123770823e-05 0.000300629172067562 -1.17168247376251e-05 5.66333966266836e-05 5.18162123166379e-05 0.000453729226539622 -1.8328054542743e-06 -1.17168247376251e-05 1.39211239224896e-05 -3.91713321734522e-06 4.21386703360201e-06 -8.75138521852958e-06 -3.9094873534092e-06 5.66333966266836e-05 -3.91713321734522e-06 6.9402645046261e-05 2.47042600012299e-05 0.000167615311651199 5.85902226694495e-06 5.18162123166379e-05 4.21386703360201e-06 2.47042600012299e-05 3.68264424282297e-05 0.000148521917528333 -3.69856604716265e-05 0.000453729226539622 -8.75138521852958e-06 0.000167615311651199 0.000148521917528333 0.00164844466708087 869 893 0 634 0 878 902 0 618 0 0 0 0 0 0 0 0 0 1773 0 338 338 0 0 128 +942 854 0.867964497454546 0.483913930884219 0.111646489665648 -0.727570680197236 -0.484052982666474 0.874600701153916 -0.0276825488849812 -0.204900279931464 -0.111042069190775 -0.030015346695685 0.993362339648816 0.67992256965409 9.6891080512069e-05 4.10992425626856e-05 -9.48083486284101e-06 -6.33024431371237e-06 1.74194046490698e-05 -1.93461877142891e-05 4.10992425626856e-05 9.97964312087304e-05 -1.20681926647602e-05 -1.14177456120104e-06 1.62452283145071e-05 4.69299229616963e-05 -9.48083486284101e-06 -1.20681926647602e-05 1.5056069613548e-05 -2.77917528392705e-06 1.48912870321278e-06 1.86155313947073e-06 -6.33024431371237e-06 -1.14177456120104e-06 -2.77917528392705e-06 3.95670080204192e-05 3.23565215181056e-06 4.34499114694458e-05 1.74194046490698e-05 1.62452283145071e-05 1.48912870321278e-06 3.23565215181056e-06 2.84390138610259e-05 3.99499301446341e-05 -1.93461877142891e-05 4.69299229616963e-05 1.86155313947073e-06 4.34499114694458e-05 3.99499301446341e-05 0.000349536427277914 728 752 0 649 0 746 770 0 635 0 0 0 0 0 0 0 0 0 1338 0 217 217 0 0 122 +942 869 0.834338820089202 0.550676676194174 0.0251779980914912 -0.523690523494224 -0.548177597926467 0.833636851975415 -0.0674605081517265 -0.408932409666167 -0.0581382354713965 0.0424829062595386 0.997404205050297 1.01708298873499 0.000265456302791211 0.000198395714991564 -6.49169091098979e-06 -3.96759505740056e-05 -5.79376699005906e-06 -0.000365942953001042 0.000198395714991564 0.000438631143375857 -1.61843124814883e-05 2.2944966498563e-05 2.71602977671818e-05 -0.000502068659014679 -6.49169091098979e-06 -1.61843124814883e-05 1.89165429676118e-05 -1.2940826378352e-05 6.1480723449478e-06 2.92669271464734e-05 -3.96759505740056e-05 2.2944966498563e-05 -1.2940826378352e-05 0.000132621980583024 3.10638560191139e-05 4.88316255145768e-05 -5.79376699005906e-06 2.71602977671818e-05 6.1480723449478e-06 3.10638560191139e-05 6.41331410114244e-05 3.07927438798619e-05 -0.000365942953001042 -0.000502068659014679 2.92669271464734e-05 4.88316255145768e-05 3.07927438798619e-05 0.00111296787204301 241 258 0 451 0 241 258 0 446 0 0 0 0 0 0 0 0 0 79 0 0 0 0 0 129 +942 871 0.835612235288888 0.549318597381447 0.00112730048674405 -0.514253852159461 -0.548359814186846 0.834271509691249 -0.057380853099727 -0.414598311357066 -0.0324608444202446 0.0473299766360025 0.998351725040409 1.04292600078063 0.000446029140877861 5.14389347772627e-05 -2.94381360025482e-05 -0.000149875721721425 0.000110084191030512 -9.95258867028932e-05 5.14389347772627e-05 0.000112133817375599 1.41126034868343e-06 -3.6880583517871e-06 3.1286405648921e-05 -1.99273228625483e-05 -2.94381360025482e-05 1.41126034868343e-06 2.45984432621014e-05 -6.88349681819071e-06 -5.0223630659267e-06 2.64749515882344e-06 -0.000149875721721425 -3.6880583517871e-06 -6.88349681819071e-06 0.00020983408957383 -7.2336047023823e-06 0.00015029331809557 0.000110084191030512 3.1286405648921e-05 -5.0223630659267e-06 -7.2336047023823e-06 0.000138890499322275 4.84767022265447e-05 -9.95258867028932e-05 -1.99273228625483e-05 2.64749515882344e-06 0.00015029331809557 4.84767022265447e-05 0.000407631382518422 217 232 0 428 0 217 232 0 425 0 0 0 0 0 0 0 0 0 52 0 0 0 0 0 132 +943 854 0.887218424151792 0.442732598214923 0.129735555355787 -0.814693819808531 -0.441889085230664 0.896314210966273 -0.0368085801670488 -0.272543332743093 -0.132580180266953 -0.0246714753869871 0.990865184625341 0.726568193827412 0.000110939415534167 1.48824355392992e-05 -8.83953869681983e-06 -2.4638962355743e-05 1.15029789875363e-05 -1.12161252492444e-05 1.48824355392992e-05 6.78975647460472e-05 -3.47077982899464e-06 -6.27737411309754e-06 1.6570028492879e-06 -3.05829794501842e-06 -8.83953869681983e-06 -3.47077982899464e-06 1.65700433683563e-05 -5.5193028488648e-07 2.98113932942639e-06 6.23021073243614e-07 -2.4638962355743e-05 -6.27737411309754e-06 -5.5193028488648e-07 5.06824916847975e-05 3.27901122124043e-06 1.29226738854985e-05 1.15029789875363e-05 1.6570028492879e-06 2.98113932942639e-06 3.27901122124043e-06 2.61220958417364e-05 6.46753972467236e-06 -1.12161252492444e-05 -3.05829794501842e-06 6.23021073243614e-07 1.29226738854985e-05 6.46753972467236e-06 0.000142913726785759 783 807 0 566 0 783 807 0 558 0 0 0 0 0 0 0 0 0 1195 0 247 247 0 0 85 +943 851 0.915137569461318 0.391360606916292 0.0967476320875252 -1.04064943344198 -0.395950300346108 0.917673120422835 0.0331572572635739 -0.104553469673567 -0.0758062571049277 -0.068650705805021 0.994756498835878 0.500830059709742 6.15391211238513e-05 1.38935078507562e-05 -1.66235733678784e-06 1.38397738436255e-05 8.01159451683155e-06 4.65807109309108e-06 1.38935078507562e-05 0.000132203104340639 -1.67952445919616e-06 7.31625055532294e-05 3.41715752074393e-05 0.000105372919513327 -1.66235733678784e-06 -1.67952445919616e-06 1.20632807779858e-05 -6.49107728423501e-06 3.20754907750351e-06 3.94817530307764e-06 1.38397738436255e-05 7.31625055532294e-05 -6.49107728423501e-06 0.000103937936633132 3.84519108884505e-05 6.73649330055044e-05 8.01159451683155e-06 3.41715752074393e-05 3.20754907750351e-06 3.84519108884505e-05 3.40011963269374e-05 3.18780433143352e-05 4.65807109309108e-06 0.000105372919513327 3.94817530307764e-06 6.73649330055044e-05 3.18780433143352e-05 0.000594845121105264 1012 1027 0 325 0 1012 1027 0 313 0 0 0 0 0 0 0 0 0 2205 0 992 992 0 0 78 +943 856 0.877594155853988 0.463722194348431 0.12161506518356 -0.726386304397377 -0.455242717830912 0.885622223758108 -0.091800569974635 -0.362607761969477 -0.150274966221426 0.0251992709104576 0.988323039938223 0.827041801069426 6.16492455031245e-05 5.41610506807616e-06 7.36726480127524e-06 -1.58677381284861e-05 1.1985160310997e-05 1.42576991047035e-05 5.41610506807616e-06 8.80121974760976e-05 -2.38775767058024e-07 6.21261084804621e-06 -8.48913462933879e-06 -2.60722228114689e-05 7.36726480127524e-06 -2.38775767058024e-07 1.60885186863108e-05 -5.5163162950175e-06 5.74008128190111e-06 -2.8919598941498e-06 -1.58677381284861e-05 6.21261084804621e-06 -5.5163162950175e-06 6.26787048243756e-05 5.31358122375358e-06 -8.18662188924425e-06 1.1985160310997e-05 -8.48913462933879e-06 5.74008128190111e-06 5.31358122375358e-06 3.56037531705594e-05 2.96401216984094e-05 1.42576991047035e-05 -2.60722228114689e-05 -2.8919598941498e-06 -8.18662188924425e-06 2.96401216984094e-05 0.000184709329337243 600 623 0 535 0 600 623 0 527 0 0 0 0 0 0 0 0 0 621 0 128 128 0 0 93 +944 854 0.894526598599362 0.431627374073903 0.116275424524376 -0.934973833286283 -0.433008605438686 0.901274396701446 -0.0144225332896 -0.292439179913619 -0.111021223260695 -0.0374469197733592 0.993112287802938 0.726095084829754 9.27728084972777e-05 1.88856082879678e-05 -3.53393234682095e-07 -1.67327361916441e-05 8.71866474807777e-06 1.20767079106718e-05 1.88856082879678e-05 6.32924394032665e-05 -4.644149861788e-06 -7.24852373048769e-06 1.26571785982251e-06 1.02258450019092e-05 -3.53393234682095e-07 -4.644149861788e-06 1.57374132226084e-05 -5.30707964819191e-08 4.83138522190765e-06 -3.3655333454907e-07 -1.67327361916441e-05 -7.24852373048769e-06 -5.30707964819191e-08 5.7607706432491e-05 9.3215650089408e-06 2.21513318317526e-05 8.71866474807777e-06 1.26571785982251e-06 4.83138522190765e-06 9.3215650089408e-06 2.68003185052279e-05 2.30892492700179e-05 1.20767079106718e-05 1.02258450019092e-05 -3.3655333454907e-07 2.21513318317526e-05 2.30892492700179e-05 0.000221060164662971 823 847 0 532 0 823 847 0 520 0 0 0 0 0 0 0 0 0 1177 0 250 250 0 0 0 +944 861 0.890256773725519 0.453524287101459 0.0419356393172108 -0.727318973011065 -0.450941687183739 0.890618530398035 -0.0587386420640338 -0.444467637393582 -0.063988058227395 0.0333819460301131 0.997392186696653 1.04738351616249 0.000179098829344847 3.34470351016521e-05 -2.2424455862884e-05 -3.59957814303213e-05 4.25058464668265e-05 4.31929303341796e-05 3.34470351016521e-05 0.00011511549061532 -6.71159303303336e-06 1.31495446181153e-05 3.42181719129433e-05 0.000110655137521443 -2.2424455862884e-05 -6.71159303303336e-06 1.88111552305388e-05 -3.07361645052092e-06 -2.0037077901034e-06 -2.91843927802948e-05 -3.59957814303213e-05 1.31495446181153e-05 -3.07361645052092e-06 8.83358810965063e-05 -6.32232555801247e-06 8.71465061379132e-05 4.25058464668265e-05 3.42181719129433e-05 -2.0037077901034e-06 -6.32232555801247e-06 8.61873496277518e-05 0.000123912910735104 4.31929303341796e-05 0.000110655137521443 -2.91843927802948e-05 8.71465061379132e-05 0.000123912910735104 0.00055156872544884 392 406 0 398 0 392 406 0 392 0 0 0 0 0 0 0 0 0 110 0 0 0 0 0 0 +944 948 0.999628828897357 -0.0213795192141169 0.0168855143680087 0.540498510581554 0.0211158273710354 0.999654644197353 0.0156433426447492 0.0969248320008778 -0.0172141300022875 -0.0152809846815447 0.999735047517805 -0.0901398252305415 5.19480510463042e-05 2.03896920558949e-07 3.93530865344337e-06 6.63388983425659e-06 3.50560906588094e-06 1.32174733511435e-05 2.03896920558949e-07 2.67548436671672e-05 -2.31085581989303e-06 -9.26940285344298e-07 -1.84428345338259e-07 -7.14894956104546e-06 3.93530865344337e-06 -2.31085581989303e-06 1.41859877178688e-05 8.38532089756963e-06 5.77300280615398e-06 -3.84247738168677e-06 6.63388983425659e-06 -9.26940285344298e-07 8.38532089756963e-06 0.000225716545721577 5.03049765668472e-06 3.98240656010102e-05 3.50560906588094e-06 -1.84428345338259e-07 5.77300280615398e-06 5.03049765668472e-06 1.24749251659735e-05 7.79752927367641e-06 1.32174733511435e-05 -7.14894956104546e-06 -3.84247738168677e-06 3.98240656010102e-05 7.79752927367641e-06 0.000234472157604804 3014 3024 0 522 774 3014 3024 0 480 774 0 0 0 0 0 0 0 0 3287 0 0 0 0 0 2038 +944 851 0.920205078120167 0.379097796815455 0.0975062800619797 -1.15429137271933 -0.385552036414392 0.920831187973383 0.0584769225613229 -0.131221522607136 -0.0676183511967927 -0.0914045059348574 0.993515462826941 0.53923378824588 8.07857056802673e-05 3.46134552694322e-06 1.51859250223698e-06 -7.96926099314588e-07 5.72490104572751e-06 -1.0366129498648e-05 3.46134552694322e-06 6.44138706706252e-05 -6.26407752399753e-07 1.58236987253639e-05 6.53191722219928e-06 4.92415115848713e-05 1.51859250223698e-06 -6.26407752399753e-07 1.48787041085133e-05 -4.2915302660391e-06 2.77439150596638e-06 8.11776862470703e-06 -7.96926099314588e-07 1.58236987253639e-05 -4.2915302660391e-06 7.81456871914777e-05 2.33721745011606e-05 3.13339682898644e-05 5.72490104572751e-06 6.53191722219928e-06 2.77439150596638e-06 2.33721745011606e-05 2.64084849506811e-05 1.14478454422385e-05 -1.0366129498648e-05 4.92415115848713e-05 8.11776862470703e-06 3.13339682898644e-05 1.14478454422385e-05 0.000432654428492961 1037 1052 0 275 0 1037 1052 0 261 0 0 0 0 0 0 0 0 0 1977 0 840 840 0 0 0 +944 850 0.931720134810071 0.346990047804056 0.107217056079909 -1.26196451743442 -0.356250408354631 0.93059757972283 0.0841058330983696 -0.0816134559919083 -0.0705920458455672 -0.116559218163775 0.990671848658468 0.474318814993477 8.07551591319831e-05 3.84306926253107e-05 6.95634723863581e-06 8.06237595380319e-06 8.33293956258085e-06 -3.41683789918205e-06 3.84306926253107e-05 7.72842221380105e-05 7.61433133828159e-06 -1.49058060541918e-06 -2.65678904900484e-06 -2.01908033103936e-05 6.95634723863581e-06 7.61433133828159e-06 1.58350570239244e-05 -5.20580227934347e-06 1.81261220327096e-06 -4.12324951978251e-06 8.06237595380319e-06 -1.49058060541918e-06 -5.20580227934347e-06 7.38039416777534e-05 1.89311780545318e-05 3.22796274442502e-05 8.33293956258085e-06 -2.65678904900484e-06 1.81261220327096e-06 1.89311780545318e-05 2.33941561849014e-05 1.19711656287873e-05 -3.41683789918205e-06 -2.01908033103936e-05 -4.12324951978251e-06 3.22796274442502e-05 1.19711656287873e-05 0.000295198381401336 1096 1111 0 153 0 1096 1111 0 143 0 0 0 0 0 0 0 0 0 2129 0 887 887 0 0 0 +945 857 0.879612159006023 0.473811381347809 0.0422519187025136 -0.957477989359928 -0.472982700544494 0.880611865683456 -0.0284623787330085 -0.42474491471643 -0.0506933399412575 0.0050514277966874 0.99870149111875 0.895403337702515 0.000143058433277622 3.82763989494494e-05 -1.03731296543421e-05 -3.04530729469047e-05 9.24287990287782e-07 -0.000109854887057607 3.82763989494494e-05 0.000155337222146308 -2.00524231945959e-06 -3.62615621280788e-06 -1.2608696287537e-05 -8.9558410647022e-05 -1.03731296543421e-05 -2.00524231945959e-06 1.7587420295845e-05 -3.10503122700247e-06 5.80826392089257e-06 1.10518205460213e-05 -3.04530729469047e-05 -3.62615621280788e-06 -3.10503122700247e-06 7.39114088789311e-05 1.00903643761483e-05 4.77984316367817e-05 9.24287990287782e-07 -1.2608696287537e-05 5.80826392089257e-06 1.00903643761483e-05 4.04731214810853e-05 1.57917600222839e-05 -0.000109854887057607 -8.9558410647022e-05 1.10518205460213e-05 4.77984316367817e-05 1.57917600222839e-05 0.000409171137304284 472 483 0 468 0 472 483 0 458 0 0 0 0 0 0 0 0 0 376 0 10 10 0 0 0 +945 861 0.889238083316592 0.45714604340283 0.0165265295985445 -0.887512747576809 -0.455477112343024 0.888182497444464 -0.0606007538317357 -0.466967342365207 -0.042381969174332 0.0463610422062767 0.998025261431019 1.03797403917488 0.00032552747829838 -0.000106231865981013 -1.47975183507912e-05 -0.000134416733979092 -4.51459364877323e-06 -0.000663506775882975 -0.000106231865981013 0.000343823043556586 1.976820505548e-05 0.000113697206839711 3.07142756146605e-06 0.000745321875944591 -1.47975183507912e-05 1.976820505548e-05 2.10616958693515e-05 -3.5012550028767e-06 2.72772799450869e-06 3.33566508105155e-05 -0.000134416733979092 0.000113697206839711 -3.5012550028767e-06 0.000173522535821992 2.42876819081595e-05 0.000475135431955835 -4.51459364877323e-06 3.07142756146605e-06 2.72772799450869e-06 2.42876819081595e-05 8.03608349425984e-05 5.52866676838793e-05 -0.000663506775882975 0.000745321875944591 3.33566508105155e-05 0.000475135431955835 5.52866676838793e-05 0.00298230441237342 353 368 0 334 0 354 369 0 329 0 0 0 0 0 0 0 0 0 58 0 0 0 0 0 0 +945 949 0.999938062476869 -0.0104325050819395 0.00387737639644318 0.53645330613966 0.0101840967374035 0.998185485151682 0.059346620848581 0.099584178150633 -0.00448947476299808 -0.0593034574895707 0.998229905656074 -0.0572579326557117 0.000121365051821631 -1.30167065506012e-06 -7.09334949801813e-06 -3.66338239852728e-05 1.2517576096013e-05 3.4709351117602e-06 -1.30167065506012e-06 3.96347691263899e-05 6.52569726889027e-06 -2.80133604418894e-06 -4.20294276512668e-06 3.12460594828266e-06 -7.09334949801813e-06 6.52569726889027e-06 2.31872448175028e-05 3.0669075886385e-06 -4.75585210229808e-06 -1.0325885412641e-06 -3.66338239852728e-05 -2.80133604418894e-06 3.0669075886385e-06 0.00057322016343993 -1.53604580551343e-05 0.000155280449212865 1.2517576096013e-05 -4.20294276512668e-06 -4.75585210229808e-06 -1.53604580551343e-05 1.96230376841614e-05 2.13105380487099e-06 3.4709351117602e-06 3.12460594828266e-06 -1.0325885412641e-06 0.000155280449212865 2.13105380487099e-06 0.00037466453975188 3199 3203 0 561 1009 3199 3203 0 502 1065 0 0 0 0 0 0 0 0 3253 0 0 0 0 0 1699 +946 856 0.885631522889641 0.46228773017207 0.044123238735732 -1.15628408165764 -0.45849537177032 0.88552559095875 -0.0750094782167778 -0.412335771769335 -0.0737482184826987 0.0462004576764322 0.996206162388647 0.835576434928841 0.000140973118348435 6.80493508626894e-05 -2.40601632326814e-06 -3.20757106202695e-06 2.40152581442146e-05 -1.54406296294222e-05 6.80493508626894e-05 0.000192478767022965 -2.03441344065626e-05 3.23235633868462e-05 2.87672679773214e-05 3.25933665881445e-05 -2.40601632326814e-06 -2.03441344065626e-05 2.18758286683809e-05 -8.56613296668844e-06 -5.36168519977752e-06 -2.21526612759881e-05 -3.20757106202695e-06 3.23235633868462e-05 -8.56613296668844e-06 0.000102929989768998 5.48702107167713e-05 0.000151104654263271 2.40152581442146e-05 2.87672679773214e-05 -5.36168519977752e-06 5.48702107167713e-05 9.30310880519223e-05 0.00018645739662344 -1.54406296294222e-05 3.25933665881445e-05 -2.21526612759881e-05 0.000151104654263271 0.00018645739662344 0.000742776189108021 472 491 0 369 0 476 495 0 364 0 0 0 0 0 0 0 0 0 438 0 69 69 0 0 0 +946 851 0.917905401291017 0.396778353669153 0.00407582388878142 -1.46209781263607 -0.396476094311239 0.916694890013161 0.0497713297337325 -0.163214784668862 0.0160118993402355 -0.0473013391285538 0.998752322848945 0.431558620000174 8.75705235921076e-05 6.66093500334426e-06 -4.88963225332973e-06 -9.67913865994462e-06 3.04693419200875e-07 -3.93062423669171e-06 6.66093500334426e-06 0.000202394281225418 -2.48470461409812e-06 3.71445253331293e-05 1.32822769254227e-05 -0.000170422968422593 -4.88963225332973e-06 -2.48470461409812e-06 1.35054785003883e-05 -2.1524149387288e-06 6.37985463782891e-06 2.31865185327441e-06 -9.67913865994462e-06 3.71445253331293e-05 -2.1524149387288e-06 4.47887131785461e-05 4.6257855094887e-06 -7.64578935362718e-06 3.04693419200875e-07 1.32822769254227e-05 6.37985463782891e-06 4.6257855094887e-06 1.48205566873216e-05 -8.75828768537566e-07 -3.93062423669171e-06 -0.000170422968422593 2.31865185327441e-06 -7.64578935362718e-06 -8.75828768537566e-07 0.000279843264091129 797 813 0 187 0 814 830 0 179 0 0 0 0 0 0 0 0 0 1651 0 532 532 0 0 0 +947 853 0.898491369615122 0.433566104560451 0.0688018292156462 -1.44206513008935 -0.435447687074279 0.90009810867476 0.0144466806492267 -0.29704018669765 -0.0556648052974529 -0.0429398152813487 0.997525739875819 0.612207082205665 8.40047524980137e-05 1.75965941136183e-05 -5.34579936141549e-06 -2.24319823772379e-05 -1.58363090631027e-06 -2.05418714551774e-05 1.75965941136183e-05 0.000146776355727177 3.55969131596859e-06 1.75855800880192e-05 5.14933019175839e-06 4.48781154578087e-05 -5.34579936141549e-06 3.55969131596859e-06 1.96584495707373e-05 -7.80528197290612e-07 1.84076190326371e-06 -8.34936814785292e-06 -2.24319823772379e-05 1.75855800880192e-05 -7.80528197290612e-07 0.000107663937275589 3.42773482835508e-05 -1.10599835811238e-05 -1.58363090631027e-06 5.14933019175839e-06 1.84076190326371e-06 3.42773482835508e-05 3.57131464886862e-05 6.5402446434655e-06 -2.05418714551774e-05 4.48781154578087e-05 -8.34936814785292e-06 -1.10599835811238e-05 6.5402446434655e-06 0.000512426904253232 692 716 0 328 0 699 723 0 319 0 0 0 0 0 0 0 0 0 1090 0 430 430 0 0 0 +947 856 0.884003835582787 0.463487533553084 0.0609633079466695 -1.2863665989021 -0.459807374768568 0.885599859359829 -0.0654986046438278 -0.431261473097077 -0.0843468836612167 0.0298696391462984 0.995988658506668 0.828701686488856 9.1951152638014e-05 1.98491793463204e-05 3.9953356729488e-06 -2.64465793481127e-05 7.13704559093376e-07 -5.255310490276e-05 1.98491793463204e-05 0.000107606475580536 -1.71107701393988e-05 4.06814166021463e-06 6.99351632414719e-06 -5.2675921249642e-05 3.9953356729488e-06 -1.71107701393988e-05 2.21346118363474e-05 -5.63173641239825e-06 8.0449695488515e-07 1.13726647493059e-05 -2.64465793481127e-05 4.06814166021463e-06 -5.63173641239825e-06 5.30946729659611e-05 6.04880516119043e-06 2.42009198913822e-05 7.13704559093376e-07 6.99351632414719e-06 8.0449695488515e-07 6.04880516119043e-06 2.88449968234177e-05 1.27734891430275e-05 -5.255310490276e-05 -5.2675921249642e-05 1.13726647493059e-05 2.42009198913822e-05 1.27734891430275e-05 0.000203723005609786 503 522 0 351 0 506 525 0 344 0 0 0 0 0 0 0 0 0 567 0 133 133 0 0 0 +948 856 0.877764153717269 0.47029782776101 0.0913785732668354 -1.41686858863099 -0.463042617555481 0.881739354084498 -0.090151238405362 -0.46877107687721 -0.122970015761469 0.0368193517314856 0.991727135134306 0.898570816732662 7.95469942682644e-05 3.44967027329141e-05 -3.61798683019748e-07 -3.07460429951585e-05 5.92428413360052e-06 -2.10857343318824e-05 3.44967027329141e-05 9.2654394045118e-05 -8.08284503857659e-06 -1.63106563478456e-05 -4.48161863092118e-07 -1.91878968791791e-05 -3.61798683019748e-07 -8.08284503857659e-06 1.64857208572119e-05 1.56351102006451e-06 5.27570570786426e-06 7.62827854066826e-06 -3.07460429951585e-05 -1.63106563478456e-05 1.56351102006451e-06 7.76511249009854e-05 1.4436586291694e-05 3.34477351078139e-05 5.92428413360052e-06 -4.48161863092118e-07 5.27570570786426e-06 1.4436586291694e-05 3.16536575421513e-05 2.14739747133246e-05 -2.10857343318824e-05 -1.91878968791791e-05 7.62827854066826e-06 3.34477351078139e-05 2.14739747133246e-05 0.000199080003473719 488 507 0 322 0 492 511 0 315 0 0 0 0 0 0 0 0 0 364 0 109 109 0 0 0 +948 952 0.991400184329389 0.0374151843572216 0.125402466048991 0.584673880568204 -0.0433351083105375 0.998054909504625 0.0448159123685786 0.0838000708012802 -0.123481751280775 -0.0498648332317401 0.991093212320316 -0.104545794181865 6.68835971618801e-05 -4.17200651962123e-06 9.13755444873234e-06 2.89252170591148e-05 1.62155404976862e-07 -1.97706035218409e-05 -4.17200651962123e-06 7.14982431753555e-05 -2.45502072033878e-06 3.12250173417274e-05 5.2576739202893e-07 -6.88258117559987e-05 9.13755444873234e-06 -2.45502072033878e-06 1.57900294275468e-05 -2.25143683109961e-06 3.23793515097003e-06 2.32566832171273e-06 2.89252170591148e-05 3.12250173417274e-05 -2.25143683109961e-06 0.000407359883437006 -9.15473514885273e-07 -9.94650395180597e-05 1.62155404976862e-07 5.2576739202893e-07 3.23793515097003e-06 -9.15473514885273e-07 1.34328244001196e-05 1.03012477174589e-06 -1.97706035218409e-05 -6.88258117559987e-05 2.32566832171273e-06 -9.94650395180597e-05 1.03012477174589e-06 0.0004519492096549 2979 2977 0 864 917 2979 2977 0 789 1017 0 0 0 0 0 0 0 0 2952 0 0 0 0 0 1790 +949 951 0.99510394540163 -0.00756296441081902 0.0985440988361589 0.300883876502378 0.00329099951731661 0.99905055474676 0.0434414362373907 0.0467052795189417 -0.0987790826455024 -0.0429044360120366 0.994184038396414 -0.0369038294928405 3.67949735096289e-05 1.72618902827557e-05 2.10778060426483e-06 6.55416969328157e-06 -1.05656515151393e-06 9.32788724060038e-05 1.72618902827557e-05 0.000112946442072246 4.74716520698246e-08 -1.92894536572409e-05 -4.19752376021442e-06 0.00017430592492775 2.10778060426483e-06 4.74716520698246e-08 1.49702102632827e-05 -3.45777644244628e-06 3.36264339445842e-06 3.46291666845481e-07 6.55416969328157e-06 -1.92894536572409e-05 -3.45777644244628e-06 0.000364008261710472 -8.39474769848912e-06 3.11193088772336e-05 -1.05656515151393e-06 -4.19752376021442e-06 3.36264339445842e-06 -8.39474769848912e-06 1.28244335852891e-05 -1.94609405910872e-05 9.32788724060038e-05 0.00017430592492775 3.46291666845481e-07 3.11193088772336e-05 -1.94609405910872e-05 0.000941363108565581 2912 2904 0 312 431 2912 2904 0 245 504 0 0 0 0 0 0 0 0 3508 0 0 0 0 0 2767 +949 853 0.895292235927837 0.435296455157953 0.0947037930299242 -1.68128063777181 -0.434055960367371 0.900228309628862 -0.0344153136310104 -0.379661358831264 -0.100235899541498 -0.0102949827431714 0.994910437061258 0.683760643266506 7.84324766452431e-05 4.32101743148335e-06 2.30601032730288e-06 -1.66372558577145e-05 -2.73305098802855e-06 -1.64382602403844e-05 4.32101743148335e-06 0.000149042575036001 -4.33350234308862e-06 -3.03923638261217e-05 -1.49623168836237e-05 -0.000100033222185027 2.30601032730288e-06 -4.33350234308862e-06 1.8235218621592e-05 -2.61715123569249e-06 5.70504627771792e-06 9.7466650589009e-06 -1.66372558577145e-05 -3.03923638261217e-05 -2.61715123569249e-06 0.000129301050399721 3.81525405026277e-05 -0.000150897369008238 -2.73305098802855e-06 -1.49623168836237e-05 5.70504627771792e-06 3.81525405026277e-05 3.1888720641896e-05 -6.58398286183266e-05 -1.64382602403844e-05 -0.000100033222185027 9.7466650589009e-06 -0.000150897369008238 -6.58398286183266e-05 0.000508108997602637 563 587 0 270 0 570 594 0 260 0 0 0 0 0 0 0 0 0 717 0 368 368 0 0 0 +949 861 0.884467387565823 0.465861139181221 0.026283822653165 -1.47621603124531 -0.459679123709653 0.87962858891662 -0.122264666956897 -0.628906375528454 -0.080078358861891 0.0960569860100254 0.992149440296499 1.10986677208043 0.000266692007678648 0.000120264218430804 -3.47664488415286e-05 -0.000144403075060893 2.94119460005187e-05 -3.0050058878794e-05 0.000120264218430804 0.0001530025804892 -8.46946494716501e-06 -7.9949219401667e-05 -5.94230078352195e-06 -6.85949696933142e-05 -3.47664488415286e-05 -8.46946494716501e-06 4.16135125711968e-05 3.99423902200341e-05 -2.64329689939059e-06 -1.5722087766348e-05 -0.000144403075060893 -7.9949219401667e-05 3.99423902200341e-05 0.000247604552523804 -2.08915537427102e-05 -4.94573114048784e-05 2.94119460005187e-05 -5.94230078352195e-06 -2.64329689939059e-06 -2.08915537427102e-05 6.48993920027472e-05 6.77395393359151e-06 -3.0050058878794e-05 -6.85949696933142e-05 -1.5722087766348e-05 -4.94573114048784e-05 6.77395393359151e-06 0.000188921857486452 307 322 0 222 0 308 323 0 219 0 0 0 0 0 0 0 0 0 27 0 20 20 0 0 0 +950 856 0.88733657221685 0.459192985381492 0.0421379850358756 -1.72864283275044 -0.449827497490607 0.882081750111426 -0.139953594529409 -0.592612663831722 -0.101434856473444 0.105231118481168 0.98926102803831 0.8637079330236 9.65323681832067e-05 2.81252857859184e-05 -9.73372923803567e-06 -4.27227034504924e-05 1.3889493523911e-07 -6.45403489561507e-05 2.81252857859184e-05 7.06243100259675e-05 -6.92271742018548e-06 -1.14907254471298e-05 -6.7244215131587e-07 -6.5166536911692e-05 -9.73372923803567e-06 -6.92271742018548e-06 2.13364804946265e-05 1.06305324701824e-05 2.21147728852445e-07 2.10507281723487e-05 -4.27227034504924e-05 -1.14907254471298e-05 1.06305324701824e-05 8.11763778271974e-05 -2.94226312964854e-06 4.25368345810281e-05 1.3889493523911e-07 -6.7244215131587e-07 2.21147728852445e-07 -2.94226312964854e-06 2.82711734243056e-05 -1.74722973672344e-06 -6.45403489561507e-05 -6.5166536911692e-05 2.10507281723487e-05 4.25368345810281e-05 -1.74722973672344e-06 0.000163089048296928 439 458 0 235 0 440 459 0 230 0 0 0 0 0 0 0 0 0 199 0 149 149 0 0 55 +950 858 0.873432573478649 0.486583327990359 0.0187671124121783 -1.68462271347271 -0.484050754503598 0.871791774660348 -0.0753257505708246 -0.647207183870414 -0.0530132686311867 0.0567077292473174 0.996982360321711 0.966773721983857 0.000254110898855106 0.000129272825499295 -9.53432538155741e-06 -4.5113717109841e-05 2.84855729498396e-05 -0.000152021716936266 0.000129272825499295 0.000840610011445125 -4.65119623734838e-05 -0.000330774175481628 -0.000150786836452506 -0.000864748795807637 -9.53432538155741e-06 -4.65119623734838e-05 2.91933295422648e-05 2.22386297134884e-05 1.69954206062701e-06 4.63854489258712e-05 -4.5113717109841e-05 -0.000330774175481628 2.22386297134884e-05 0.000231556505445781 7.22133649853483e-05 0.000385166733730938 2.84855729498396e-05 -0.000150786836452506 1.69954206062701e-06 7.22133649853483e-05 9.70113917096529e-05 0.000178806596392712 -0.000152021716936266 -0.000864748795807637 4.63854489258712e-05 0.000385166733730938 0.000178806596392712 0.00112561958990282 235 253 0 267 0 237 255 0 263 0 0 0 0 0 0 0 0 0 81 0 33 33 0 0 58 +950 854 0.894938314218297 0.443949631381253 0.0446557783557934 -1.78990452388622 -0.439231793534188 0.89416485487655 -0.0868599093502844 -0.486183062751721 -0.0784910523107752 0.0581200232282174 0.995219180686897 0.680617041494592 0.000109669436138087 2.49071035733245e-05 -9.34841073816704e-06 -3.77230339157998e-05 -6.30353324892145e-06 -4.47777315113023e-05 2.49071035733245e-05 9.42047409431325e-05 -9.43580157677421e-06 8.40295182188917e-07 8.35998259778682e-06 -4.34989128023676e-05 -9.34841073816704e-06 -9.43580157677421e-06 1.95807576497726e-05 3.60902717824462e-06 3.24655342514707e-06 1.82245879463178e-05 -3.77230339157998e-05 8.40295182188917e-07 3.60902717824462e-06 0.000119758603932109 3.13031962895218e-05 4.06892187256995e-05 -6.30353324892145e-06 8.35998259778682e-06 3.24655342514707e-06 3.13031962895218e-05 3.3908019295322e-05 9.77795323904261e-06 -4.47777315113023e-05 -4.34989128023676e-05 1.82245879463178e-05 4.06892187256995e-05 9.77795323904261e-06 0.000256523113207657 537 558 0 239 0 539 560 0 233 0 0 0 0 0 0 0 0 0 493 0 314 314 0 0 37 +950 952 0.996879587020839 0.0346059656986158 0.07094727703886 0.294110906265749 -0.0335392502699603 0.999306548736907 -0.0161722089666182 0.0353226990052565 -0.071457733468754 0.0137422265152786 0.997348957756467 -0.0608651985809512 4.56352472741201e-05 1.08665545628725e-06 3.28081150963509e-06 5.11948961043701e-06 -6.10162214567551e-07 1.22811503992865e-05 1.08665545628725e-06 3.85102553093346e-05 1.72269890739848e-07 2.10410353206906e-05 -6.39881649680771e-07 -3.73814815648057e-05 3.28081150963509e-06 1.72269890739848e-07 1.37162525025494e-05 -8.587037253646e-07 4.50777073447718e-06 -8.24128668884186e-07 5.11948961043701e-06 2.10410353206906e-05 -8.587037253646e-07 0.000280106890501436 2.56564248957768e-06 -1.05454224713525e-05 -6.10162214567551e-07 -6.39881649680771e-07 4.50777073447718e-06 2.56564248957768e-06 1.27341996964196e-05 4.25604725989342e-06 1.22811503992865e-05 -3.73814815648057e-05 -8.24128668884186e-07 -1.05454224713525e-05 4.25604725989342e-06 0.000218106318607902 3008 3006 0 421 300 3008 3006 0 357 362 0 0 0 0 0 0 0 0 3403 0 0 0 0 0 2790 +951 856 0.889224826706971 0.457450035343533 -0.00432119568619064 -1.89097618545636 -0.452381733127602 0.877889258691781 -0.157038902842776 -0.61719329602684 -0.0680439203781256 0.141597721160323 0.9875829637361 0.743120436054134 0.00016201251576759 -7.66187483362886e-06 9.65434718494425e-07 -3.42323962363696e-05 1.56779420017336e-06 -2.9322100922032e-05 -7.66187483362886e-06 0.000140077444615573 -1.69239478052376e-05 -2.97619448895355e-05 -1.88001157787388e-05 -7.40043340453543e-05 9.65434718494425e-07 -1.69239478052376e-05 2.75370558691257e-05 1.67749233521699e-05 1.95656555757289e-06 8.55375949505862e-07 -3.42323962363696e-05 -2.97619448895355e-05 1.67749233521699e-05 0.000147848823463443 2.25310887881703e-05 -1.46907809148048e-05 1.56779420017336e-06 -1.88001157787388e-05 1.95656555757289e-06 2.25310887881703e-05 4.70581894798762e-05 3.59908150166923e-05 -2.9322100922032e-05 -7.40043340453543e-05 8.55375949505862e-07 -1.46907809148048e-05 3.59908150166923e-05 0.000365591206564073 444 463 0 187 0 448 467 0 181 0 0 0 0 0 0 0 0 0 174 0 201 201 0 0 163 +951 954 0.993396818819757 0.114615863023891 -0.00509551784179834 0.442880067711864 -0.114728506502478 0.992272002783037 -0.0472614249536783 0.0203681950518349 -0.000360769314706784 0.0475339503537189 0.998869557754801 -0.0782509147592409 5.68612481455772e-05 1.11837221859184e-05 -1.7941550859486e-07 5.08784759915695e-07 2.23444445494727e-06 1.74156316354644e-05 1.11837221859184e-05 8.03662511318372e-05 2.73424087868644e-06 8.40854573453376e-06 -3.00184891359161e-07 1.39931037641239e-05 -1.7941550859486e-07 2.73424087868644e-06 1.37766931649166e-05 3.71425418210463e-06 3.44649560663357e-06 3.03355486578688e-06 5.08784759915695e-07 8.40854573453376e-06 3.71425418210463e-06 0.000201279748403268 1.13382801737693e-05 4.46949158400539e-05 2.23444445494727e-06 -3.00184891359161e-07 3.44649560663357e-06 1.13382801737693e-05 1.37312894944147e-05 1.02181842421927e-05 1.74156316354644e-05 1.39931037641239e-05 3.03355486578688e-06 4.46949158400539e-05 1.02181842421927e-05 0.000636445063775693 3194 3209 0 914 315 3194 3209 0 833 381 0 0 0 0 0 0 0 0 2889 0 0 0 0 0 2798 +951 953 0.995796702640505 0.0895948465731868 0.0190181617888041 0.304284199399474 -0.088019202892426 0.993527093316787 -0.0718090159219479 0.022549745550678 -0.0253287767663574 0.0698332178338055 0.997237070487503 -0.0408868695697619 4.92181127039292e-05 1.09505774132926e-07 -1.76822324736327e-07 2.25812714225492e-05 3.52911616833745e-06 3.44995870902592e-06 1.09505774132926e-07 6.01003852413612e-05 -1.23755554894908e-06 6.02765731394817e-07 9.27456000556006e-07 -5.04446712990068e-06 -1.76822324736327e-07 -1.23755554894908e-06 1.69479159290012e-05 8.67028457050793e-06 4.47663031234028e-07 -5.35354939766676e-07 2.25812714225492e-05 6.02765731394817e-07 8.67028457050793e-06 0.00037416016575283 2.16785835972486e-05 2.788488067091e-05 3.52911616833745e-06 9.27456000556006e-07 4.47663031234028e-07 2.16785835972486e-05 1.55182876321116e-05 7.82501930116062e-06 3.44995870902592e-06 -5.04446712990068e-06 -5.35354939766676e-07 2.788488067091e-05 7.82501930116062e-06 0.000183114358182705 3320 3329 0 623 158 3320 3329 0 543 216 0 0 0 0 0 0 0 0 3202 0 0 0 0 0 3146 +954 854 0.941755699684983 0.336288979080824 0.00243406237110215 -2.3429942305104 -0.335577932504575 0.940188544420745 -0.0585914000170344 -0.783054823287642 -0.0219921196523605 0.0543619673004833 0.998279080810781 0.666398255674819 8.00114523034739e-05 -2.65532236065432e-05 7.09829899732716e-06 -3.38892586473438e-05 -1.17405864195312e-05 5.82834604816046e-05 -2.65532236065432e-05 0.000715422351444351 -5.42421413648094e-05 -0.00014705598340835 -0.000115547163521558 -0.000667218731528143 7.09829899732716e-06 -5.42421413648094e-05 2.03707604713733e-05 9.73328008798058e-06 1.32132498807747e-05 5.68573729218409e-05 -3.38892586473438e-05 -0.00014705598340835 9.73328008798058e-06 0.000230977194171052 0.000101580391136917 0.000115011102870351 -1.17405864195312e-05 -0.000115547163521558 1.32132498807747e-05 0.000101580391136917 7.31146053694301e-05 0.000127471543413916 5.82834604816046e-05 -0.000667218731528143 5.68573729218409e-05 0.000115011102870351 0.000127471543413916 0.00119165933647709 492 509 0 72 0 495 512 0 69 0 0 0 0 0 0 0 0 0 312 0 193 193 0 0 592 +954 855 0.939916901841721 0.340403460993841 -0.0261094116301967 -2.30716817561713 -0.341178628361246 0.93377339729556 -0.108001787265982 -0.831135997682203 -0.0123839081795437 0.11042067852772 0.993807784519561 0.75799908051093 7.40089209847175e-05 2.68750535987226e-06 -2.49441650098071e-06 -8.66475968514285e-06 -2.85639257953393e-06 -3.01041603245058e-05 2.68750535987226e-06 0.000622695154135191 -8.2786794002358e-05 -5.16451153692813e-05 -0.000122439612226198 -0.000890314211455101 -2.49441650098071e-06 -8.2786794002358e-05 3.01662716879869e-05 5.56066226131303e-06 2.08153078803125e-05 0.000118889254193609 -8.66475968514285e-06 -5.16451153692813e-05 5.56066226131303e-06 0.000353141195097716 0.00014968713435957 1.87915744681505e-06 -2.85639257953393e-06 -0.000122439612226198 2.08153078803125e-05 0.00014968713435957 0.000110204621293877 0.000154335124951449 -3.01041603245058e-05 -0.000890314211455101 0.000118889254193609 1.87915744681505e-06 0.000154335124951449 0.00145936460754064 378 393 0 72 0 381 396 0 70 0 0 0 0 0 0 0 0 0 170 0 156 156 0 0 601 +955 858 0.924518217531928 0.379875282776512 -0.0309973383865659 -2.39752964786528 -0.381083552232098 0.922697161299163 -0.0583547320157677 -0.946229122923605 0.00643363581127664 0.0657625886498638 0.997814557051718 0.88692576489942 0.000102138638923157 4.85539629561334e-05 9.33295418084882e-06 -2.03524522685114e-05 -6.38954960508175e-06 -0.000118380978413756 4.85539629561334e-05 0.00214893261600384 -0.000132543857736121 -0.000562729502457627 -0.000475905491420813 -0.00315950078424767 9.33295418084882e-06 -0.000132543857736121 2.83465843808078e-05 2.92645394509674e-05 2.59689966536587e-05 0.000174264277272473 -2.03524522685114e-05 -0.000562729502457627 2.92645394509674e-05 0.000266488449664074 0.000179252971680275 0.00110851538369233 -6.38954960508175e-06 -0.000475905491420813 2.59689966536587e-05 0.000179252971680275 0.000179134892788619 0.000901786447189756 -0.000118380978413756 -0.00315950078424767 0.000174264277272473 0.00110851538369233 0.000901786447189756 0.00554929089373439 205 223 0 124 0 207 225 0 119 0 0 0 0 0 0 0 0 0 127 0 28 28 0 0 448 +955 860 0.935851442830295 0.352112956287525 -0.0140905275598361 -2.39319339311781 -0.351931283147679 0.93182301256562 -0.08860160943888 -0.95589443736368 -0.0180678967919114 0.087876841474823 0.995967475291199 0.921347109498582 9.98601423121825e-05 5.77550339096979e-05 2.68541449717779e-06 -2.38096961497896e-05 -2.67237540841834e-06 -4.34853220498575e-05 5.77550339096979e-05 0.00122404282864926 -0.000121543308319234 -0.000197184608581219 -0.000181110882986218 -0.00124299914023697 2.68541449717779e-06 -0.000121543308319234 3.19218921494936e-05 1.65911283789488e-05 1.59776350726837e-05 0.000105820112243924 -2.38096961497896e-05 -0.000197184608581219 1.65911283789488e-05 0.000265345430141313 0.000185739303413468 0.000769712070553959 -2.67237540841834e-06 -0.000181110882986218 1.59776350726837e-05 0.000185739303413468 0.000198943442059259 0.00071336222189221 -4.34853220498575e-05 -0.00124299914023697 0.000105820112243924 0.000769712070553959 0.00071336222189221 0.00320049238545295 291 306 0 100 0 292 307 0 96 0 0 0 0 0 0 0 0 0 116 0 38 38 0 0 441 +955 859 0.929294109697076 0.369303815962496 -0.00521048921493039 -2.34278861296981 -0.368836999097654 0.927198285223332 -0.0652886512002689 -0.955358243631011 -0.0192801913620455 0.0625941801963424 0.99785281621419 0.916063806210702 0.000107389096505528 -0.000144538539318334 1.65039262871022e-05 4.82434858099796e-05 6.23292603413947e-05 0.000364525691190021 -0.000144538539318334 0.00179745790849226 -0.000152280721692926 -0.000540562358645605 -0.000543014878740098 -0.003666635533561 1.65039262871022e-05 -0.000152280721692926 2.94360303890436e-05 4.36456019212023e-05 4.96588103230652e-05 0.000318014782455302 4.82434858099796e-05 -0.000540562358645605 4.36456019212023e-05 0.000217721564518606 0.000181612694643715 0.00125088316495417 6.23292603413947e-05 -0.000543014878740098 4.96588103230652e-05 0.000181612694643715 0.000217100790713224 0.00128123812117848 0.000364525691190021 -0.003666635533561 0.000318014782455302 0.00125088316495417 0.00128123812117848 0.00856624983981853 250 263 0 126 0 250 263 0 123 0 0 0 0 0 0 0 0 0 142 0 41 41 0 0 392 +955 857 0.929403040354488 0.3660095476369 -0.0474025275535644 -2.41609246357492 -0.368714831059024 0.926431843874442 -0.0759829718589397 -0.929375582179821 0.0161047178475599 0.0880968199995513 0.99598172090105 0.831942060223279 8.08554353956002e-05 -6.0968793596421e-06 -1.29245604515866e-06 -2.35715365907647e-05 3.3713892387174e-06 0.000112440637435521 -6.0968793596421e-06 0.000566080135046981 -3.09118553641907e-05 -0.000303425123894243 -0.000212108942427041 -0.000785003991748872 -1.29245604515866e-06 -3.09118553641907e-05 1.75384853170607e-05 1.44186325207839e-05 1.61830122449838e-05 4.74099008953464e-05 -2.35715365907647e-05 -0.000303425123894243 1.44186325207839e-05 0.000265938206023752 0.000134934410758697 0.000279688561838299 3.3713892387174e-06 -0.000212108942427041 1.61830122449838e-05 0.000134934410758697 0.00011546563737215 0.000313720187090516 0.000112440637435521 -0.000785003991748872 4.74099008953464e-05 0.000279688561838299 0.000313720187090516 0.00199000657739392 305 314 0 114 0 305 314 0 110 0 0 0 0 0 0 0 0 0 138 0 69 69 0 0 495 +957 959 0.998702242632856 -0.0205573211611212 -0.0465964280474742 0.300486327473097 0.0216660981015138 0.999490995263047 0.0234164596200906 0.038926693329766 0.0460913305640063 -0.0243956335183629 0.998639295397531 -0.00997044228792016 5.88804770295689e-05 -2.30311196044235e-05 5.01126395479833e-06 9.44100330419663e-06 2.0332230484938e-07 2.20152814005339e-05 -2.30311196044235e-05 6.81121445040555e-05 -2.22287381969985e-06 -9.26006265982769e-06 -5.93364941547266e-07 -2.77283623670565e-05 5.01126395479833e-06 -2.22287381969985e-06 1.34842727714139e-05 -4.75764383567936e-06 3.2507613923795e-06 -1.76044070988333e-06 9.44100330419663e-06 -9.26006265982769e-06 -4.75764383567936e-06 0.000117450576787795 6.91968872256899e-06 6.06621567837589e-05 2.0332230484938e-07 -5.93364941547266e-07 3.2507613923795e-06 6.91968872256899e-06 1.20902711842867e-05 4.46946008478314e-06 2.20152814005339e-05 -2.77283623670565e-05 -1.76044070988333e-06 6.06621567837589e-05 4.46946008478314e-06 0.000221186881311694 3140 3129 0 265 427 3140 3129 0 200 486 0 0 0 0 0 0 0 0 3511 0 0 0 0 0 3336 +958 931 0.948621496140774 0.315909394244236 0.0178468957491016 -2.84211574789417 -0.316134054106713 0.948644388643842 0.0115361921189536 -0.831161293158766 -0.0132859660429131 -0.0165854913340326 0.999774176793697 0.908969915703066 0.000223205337288162 4.02024239715633e-05 -1.65525092343664e-05 -0.000117895966696942 -2.09524288305662e-05 -0.000120445320637234 4.02024239715633e-05 0.00010652886214722 1.38965618288111e-06 -0.000110679026168947 -3.61638940603939e-05 -3.40420896925425e-05 -1.65525092343664e-05 1.38965618288111e-06 2.0672577413306e-05 4.54678736535621e-06 2.32469762901675e-06 3.33289507977933e-06 -0.000117895966696942 -0.000110679026168947 4.54678736535621e-06 0.000679704465348808 0.00021853596127704 -5.0331617488872e-05 -2.09524288305662e-05 -3.61638940603939e-05 2.32469762901675e-06 0.00021853596127704 9.50208422747355e-05 -2.63969642176362e-05 -0.000120445320637234 -3.40420896925425e-05 3.33289507977933e-06 -5.0331617488872e-05 -2.63969642176362e-05 0.000354400173420866 477 477 0 0 0 474 474 0 0 0 0 0 0 0 0 10 20 0 213 0 73 73 0 0 97 +959 961 0.99790118031456 0.00445949413641432 0.0646014492008934 0.274109216181274 -0.0058371539840495 0.999759220598367 0.0211525048614137 0.0387319642977236 -0.0644915650312102 -0.0214851981743926 0.99768693701944 0.0268138189010433 4.95966146954408e-05 -1.7205230262766e-05 5.56958034206488e-06 2.49969422554877e-05 3.02035155510885e-06 8.98769075294482e-06 -1.7205230262766e-05 8.85095643798043e-05 -4.62434025788345e-06 -1.51374875289764e-05 1.0390435487307e-06 -5.30725342020732e-05 5.56958034206488e-06 -4.62434025788345e-06 1.48025337102279e-05 1.94202494321164e-06 1.44562227047693e-06 -1.50330205165039e-06 2.49969422554877e-05 -1.51374875289764e-05 1.94202494321164e-06 0.000237956636999419 5.22388617076296e-06 8.84804431967879e-05 3.02035155510885e-06 1.0390435487307e-06 1.44562227047693e-06 5.22388617076296e-06 1.25436910677141e-05 4.52230268316864e-06 8.98769075294482e-06 -5.30725342020732e-05 -1.50330205165039e-06 8.84804431967879e-05 4.52230268316864e-06 0.000270134254541372 3138 3119 0 325 329 3138 3119 0 243 392 0 0 0 0 0 0 0 0 3469 0 0 0 0 0 3458 +960 964 0.993153636587455 0.113260743419829 0.0285982190547228 0.60443155026946 -0.11281058486958 0.99347282715932 -0.0168971487965015 0.0137389804425478 -0.0303253371703842 0.0135552829574131 0.999448161852053 -0.0371317428887443 6.37067948556639e-05 -1.35430334319089e-05 -3.99142793642836e-06 -1.91957007102372e-05 2.48145560585579e-06 -6.90980821072636e-07 -1.35430334319089e-05 6.36208644573725e-05 2.16726989701006e-06 3.52658286781957e-05 4.57780201429581e-06 -1.60473054298128e-05 -3.99142793642836e-06 2.16726989701006e-06 1.51558221128599e-05 3.16961211249544e-06 2.02267637112331e-06 -1.94504475559834e-06 -1.91957007102372e-05 3.52658286781957e-05 3.16961211249544e-06 0.000162715842290312 9.70639103556146e-06 8.84573684777991e-06 2.48145560585579e-06 4.57780201429581e-06 2.02267637112331e-06 9.70639103556146e-06 1.6035747985625e-05 7.47786912583394e-06 -6.90980821072636e-07 -1.60473054298128e-05 -1.94504475559834e-06 8.84573684777991e-06 7.47786912583394e-06 0.000235110907608756 2955 2965 0 1322 569 2955 2965 0 1175 639 0 0 0 0 0 0 0 0 2480 0 0 0 0 0 3227 +960 963 0.996332717821252 0.0819320811954246 0.0246627141633762 0.465168191648307 -0.0809620175282996 0.995990551184438 -0.0380522491985167 0.0251824652097078 -0.0276815302442867 0.035915957766779 0.998971359379752 -0.0529831482223979 6.99402789438773e-05 -1.59299785099134e-06 -2.95282383639519e-06 3.93570924096534e-06 6.72607120989993e-06 -8.23977631423748e-06 -1.59299785099134e-06 2.90744343107677e-05 -2.26113116841396e-06 7.52141643075056e-06 2.18900484212932e-06 -8.35222372225795e-06 -2.95282383639519e-06 -2.26113116841396e-06 1.41627341472245e-05 -4.57495087783498e-06 7.64175438254293e-07 5.56208551276888e-07 3.93570924096534e-06 7.52141643075056e-06 -4.57495087783498e-06 0.000537163497163368 5.44544752560333e-05 5.6971296784064e-06 6.72607120989993e-06 2.18900484212932e-06 7.64175438254293e-07 5.44544752560333e-05 2.11173726497626e-05 6.55748243196616e-06 -8.23977631423748e-06 -8.35222372225795e-06 5.56208551276888e-07 5.6971296784064e-06 6.55748243196616e-06 0.000214138734973041 3101 3102 0 916 404 3101 3102 0 817 469 0 0 0 0 0 0 0 0 2900 0 0 0 0 0 3384 +961 963 0.997413821976553 0.0662232959600225 -0.0279310365421144 0.333293553857421 -0.0671743841430389 0.99714076502068 -0.0346106464686411 0.0135035393334003 0.025559144060964 0.0363973873535598 0.999010490609937 -0.0191814319926448 6.64329818678832e-05 -1.42359459665498e-06 -4.43634669548048e-06 7.58707271339607e-06 3.15411387709908e-06 6.02717889404181e-05 -1.42359459665498e-06 6.73946551711999e-05 -1.61014159786531e-06 1.61009688618436e-06 -1.43480863970157e-06 -8.90346944885366e-05 -4.43634669548048e-06 -1.61014159786531e-06 1.34898464248396e-05 3.66287616159354e-06 3.91511458985258e-06 1.12779188741733e-06 7.58707271339607e-06 1.61009688618436e-06 3.66287616159354e-06 0.00023966988612396 1.54797545823708e-05 2.29690397853487e-05 3.15411387709908e-06 -1.43480863970157e-06 3.91511458985258e-06 1.54797545823708e-05 1.4672710529897e-05 2.49130967240286e-05 6.02717889404181e-05 -8.90346944885366e-05 1.12779188741733e-06 2.29690397853487e-05 2.49130967240286e-05 0.000656654290095297 3128 3129 0 633 220 3128 3129 0 549 269 0 0 0 0 0 0 0 0 3233 0 0 0 0 0 3580 +961 965 0.992841886515196 0.118488326138522 -0.0150168222283753 0.596839133376002 -0.118572538581172 0.992933575904022 -0.00484426845548572 -0.00498989757287099 0.0143367177332795 0.00659017536517112 0.999875506307307 -0.00741755101780863 5.20296635690949e-05 -6.62380784360936e-06 -3.60101178698105e-06 1.15108804922129e-05 9.51289517891413e-07 1.95588873994145e-05 -6.62380784360936e-06 0.000231706922947122 5.36070444101263e-06 4.02691036309579e-05 4.67826995871972e-06 -8.95055894833088e-05 -3.60101178698105e-06 5.36070444101263e-06 1.39449336373523e-05 -3.22427833215358e-06 2.48285228763884e-06 -4.56558023129674e-06 1.15108804922129e-05 4.02691036309579e-05 -3.22427833215358e-06 0.000140733270459197 1.45655615848077e-05 3.69335613925953e-06 9.51289517891413e-07 4.67826995871972e-06 2.48285228763884e-06 1.45655615848077e-05 1.61541913140723e-05 8.30321095288268e-06 1.95588873994145e-05 -8.95055894833088e-05 -4.56558023129674e-06 3.69335613925953e-06 8.30321095288268e-06 0.00025881235933769 3072 3128 0 1185 515 3072 3128 0 1082 574 0 0 0 0 0 0 0 0 2500 0 0 0 0 0 3284 +963 966 0.998179870714957 0.0441650350248816 0.0410657446142491 0.451550153631941 -0.0456450313118064 0.998314995930922 0.0358287596210993 0.00871524414224585 -0.0394141702439104 -0.0376379938452262 0.998513847977729 -0.0148298238342715 6.9856358634452e-05 -3.99116942328212e-05 -9.47285893910865e-06 -1.67405557768963e-05 5.52090030585631e-06 1.48347477905727e-05 -3.99116942328212e-05 0.000100483522123786 9.44055113942489e-06 2.96885531254782e-05 -2.33637539907607e-06 -6.65021690007963e-06 -9.47285893910865e-06 9.44055113942489e-06 1.49657858529118e-05 3.72012936345297e-06 2.6955741705991e-06 -3.92737966456417e-06 -1.67405557768963e-05 2.96885531254782e-05 3.72012936345297e-06 0.000232721351960836 2.3683130986859e-05 -7.77346419344055e-05 5.52090030585631e-06 -2.33637539907607e-06 2.6955741705991e-06 2.3683130986859e-05 1.80244163250208e-05 -1.15149042066982e-05 1.48347477905727e-05 -6.65021690007963e-06 -3.92737966456417e-06 -7.77346419344055e-05 -1.15149042066982e-05 0.000354372447761003 3116 3170 0 458 482 3116 3170 0 380 558 0 0 0 0 0 0 0 0 3042 0 0 0 0 0 3299 +964 967 0.997598356086363 -0.0152139892092684 0.0675725866467038 0.435692087279573 0.0153068891114324 0.999882475232797 -0.000857244461214058 0.0342872941165607 -0.0675516030862062 0.00188951175604503 0.99771399241757 0.0787448278483313 3.90433472274255e-05 -2.01321837830178e-05 4.16383521343016e-07 -2.35118207306475e-05 -7.75439694705211e-07 2.47610496950969e-05 -2.01321837830178e-05 5.24365639034456e-05 -3.18491492663972e-08 3.45306453089199e-06 4.82038547611246e-07 -2.64595116613587e-05 4.16383521343016e-07 -3.18491492663972e-08 1.2464243369644e-05 2.95276914223732e-06 2.93284182855903e-06 -4.93998421617061e-06 -2.35118207306475e-05 3.45306453089199e-06 2.95276914223732e-06 0.000283674878273005 2.89452333233302e-05 0.000115519707811885 -7.75439694705211e-07 4.82038547611246e-07 2.93284182855903e-06 2.89452333233302e-05 1.62913473509564e-05 2.49614255660928e-05 2.47610496950969e-05 -2.64595116613587e-05 -4.93998421617061e-06 0.000115519707811885 2.49614255660928e-05 0.000287975447624691 3207 3225 0 80 656 3207 3225 0 25 726 0 0 0 0 0 0 0 0 3286 0 0 0 0 0 3075 +964 968 0.997205205621979 -0.0555749389542826 0.0499319941586012 0.569413395644803 0.055889655527858 0.998424790582148 -0.00492787540134009 0.0507491784658412 -0.0495794744365466 0.00770478495621607 0.998740462784689 0.0154121423865396 6.62512430270802e-05 -3.97396252814054e-05 2.52810917066861e-06 -2.11763502904329e-05 3.38710164758227e-06 3.18014600970257e-05 -3.97396252814054e-05 8.02469715362787e-05 -6.11079859567241e-06 2.81708360091796e-05 6.20732427730235e-06 0.000108091392764493 2.52810917066861e-06 -6.11079859567241e-06 1.5258244049464e-05 -1.04607000384011e-06 2.58753579113713e-06 -5.06268053658066e-07 -2.11763502904329e-05 2.81708360091796e-05 -1.04607000384011e-06 0.000260766134389433 1.34483509799175e-05 2.40928496111358e-05 3.38710164758227e-06 6.20732427730235e-06 2.58753579113713e-06 1.34483509799175e-05 1.65121669121175e-05 4.87284907853459e-05 3.18014600970257e-05 0.000108091392764493 -5.06268053658066e-07 2.40928496111358e-05 4.87284907853459e-05 0.00156563269230083 3151 3155 0 102 1027 3151 3155 0 55 1109 0 0 0 0 0 0 0 0 3148 0 0 0 0 0 2696 +963 965 0.996257393312442 0.050096400369014 0.0704383201131755 0.287978902683452 -0.0531705038377761 0.997682086271406 0.0424658951956884 0.00244723821777641 -0.0681476616762143 -0.04605220302224 0.996611805471349 0.0254184916032479 5.69482409512145e-05 -2.50331448673674e-05 7.62197564558e-06 -2.11303983898148e-05 -6.81214591227427e-08 -1.01532510798872e-05 -2.50331448673674e-05 5.47387896196546e-05 5.21742481976173e-07 4.84170646323545e-05 6.78080353770273e-06 5.89031402855384e-05 7.62197564558e-06 5.21742481976173e-07 1.30463662767125e-05 -3.46598608381437e-06 2.15308950198501e-06 -6.99794367501364e-06 -2.11303983898148e-05 4.84170646323545e-05 -3.46598608381437e-06 0.00037164315003216 5.30697813085417e-05 0.000527344411714658 -6.81214591227427e-08 6.78080353770273e-06 2.15308950198501e-06 5.30697813085417e-05 2.10609614066545e-05 9.19383318625592e-05 -1.01532510798872e-05 5.89031402855384e-05 -6.99794367501364e-06 0.000527344411714658 9.19383318625592e-05 0.00119166841455675 3056 3112 0 382 205 3056 3112 0 322 268 0 0 0 0 0 0 0 0 3309 0 0 0 0 0 3589 +965 969 0.994424310243212 -0.105366524670843 -0.0042645839305908 0.582686540260646 0.105286415081175 0.994313960227782 -0.0159536608807638 0.0827840199597433 0.00592131713953277 0.015415705463343 0.999863637716864 0.0689752863579109 5.46192277830151e-05 -2.53018381208366e-05 -7.66543519442981e-06 -9.96324318343345e-06 -5.60882064060233e-07 3.08820245557606e-05 -2.53018381208366e-05 4.5457855398836e-05 9.23635289233559e-07 9.76527541959442e-06 -3.41838815758957e-07 -4.16390281443445e-05 -7.66543519442981e-06 9.23635289233559e-07 1.20936802972565e-05 -1.91767985938542e-06 5.70581408343482e-06 -2.25314508518562e-06 -9.96324318343345e-06 9.76527541959442e-06 -1.91767985938542e-06 0.000131462949078335 -5.06253651635239e-07 -2.57604475190822e-05 -5.60882064060233e-07 -3.41838815758957e-07 5.70581408343482e-06 -5.06253651635239e-07 1.1332798430077e-05 2.31640109040676e-07 3.08820245557606e-05 -4.16390281443445e-05 -2.25314508518562e-06 -2.57604475190822e-05 2.31640109040676e-07 8.45180334143797e-05 3123 3121 0 122 1226 3123 3121 0 122 1315 0 0 0 0 0 0 0 0 3099 0 0 0 0 0 2486 +967 970 0.995364270229741 -0.0902553030491016 -0.0332257403458593 0.415876123597097 0.0901975091088369 0.995918635972142 -0.00323726334270006 0.0650997957730285 0.0333823141884579 0.000225377247154643 0.999442629821502 0.0368588385262058 4.12103850962903e-05 -1.17378224820657e-05 -1.31760808511335e-06 -7.11878969451295e-06 2.80544053566399e-06 1.84717236686766e-05 -1.17378224820657e-05 3.17300342480607e-05 -7.21943312926043e-07 -2.5790710651852e-06 -8.75268418538576e-07 3.12053835866272e-05 -1.31760808511335e-06 -7.21943312926043e-07 1.17935083089139e-05 4.14935007833698e-06 3.91046186836233e-06 -1.21724207130067e-06 -7.11878969451295e-06 -2.5790710651852e-06 4.14935007833698e-06 0.000297605312074706 6.64071609988986e-06 2.42550999581577e-06 2.80544053566399e-06 -8.75268418538576e-07 3.91046186836233e-06 6.64071609988986e-06 1.12300022901289e-05 1.06384045829538e-05 1.84717236686766e-05 3.12053835866272e-05 -1.21724207130067e-06 2.42550999581577e-06 1.06384045829538e-05 0.000751228064142339 3150 3140 0 181 838 3150 3140 0 141 915 0 0 0 0 0 0 0 0 2933 0 0 0 0 0 2884 +968 970 0.998401958868726 -0.0493228957041791 -0.0275822494812386 0.288775142264391 0.0491910848574335 0.998774584423 -0.00543752528389842 0.0377165514999468 0.0278166442555421 0.0040720351200519 0.999604748304219 -0.00224788419922049 9.46614992842081e-05 4.43008541889359e-05 2.40073703852811e-06 -4.87642493862296e-05 1.58356711493107e-06 7.00852586007252e-05 4.43008541889359e-05 0.000728130174172678 -5.11161227397604e-06 -0.000285107568243989 9.7021861202324e-06 0.00100207459426704 2.40073703852811e-06 -5.11161227397604e-06 1.22960423102525e-05 1.20038109729946e-06 4.38658634041422e-06 -1.66960709333997e-05 -4.87642493862296e-05 -0.000285107568243989 1.20038109729946e-06 0.000464491149828608 -1.93646804099195e-07 -0.000776845776428837 1.58356711493107e-06 9.7021861202324e-06 4.38658634041422e-06 -1.93646804099195e-07 1.1341605899069e-05 4.86636732397056e-05 7.00852586007252e-05 0.00100207459426704 -1.66960709333997e-05 -0.000776845776428837 4.86636732397056e-05 0.0045568358396726 3037 3027 0 155 479 3037 3027 0 116 540 0 0 0 0 0 0 0 0 3129 0 0 0 0 0 3266 +965 968 0.996134696944557 -0.0749166500805716 0.0458602342327248 0.44392882318385 0.075766414625338 0.996979333380474 -0.0170780334654563 0.0577530305788524 -0.0444422766968185 0.0204866872122131 0.998801872089291 0.0755440745001295 4.10210330182244e-05 -2.42533531724141e-05 6.0729220965956e-06 -1.95105476732727e-05 5.32344999263062e-07 2.28954861836475e-05 -2.42533531724141e-05 3.64705834342479e-05 -4.73346807566438e-06 5.83009660210381e-06 2.1876719529275e-07 -2.62370294742225e-05 6.0729220965956e-06 -4.73346807566438e-06 1.30749359653345e-05 -8.17024920779963e-07 2.16751118789973e-06 1.02301498023658e-05 -1.95105476732727e-05 5.83009660210381e-06 -8.17024920779963e-07 0.000145915384429821 2.95046290608901e-06 6.64287084380457e-05 5.32344999263062e-07 2.1876719529275e-07 2.16751118789973e-06 2.95046290608901e-06 1.27363235124294e-05 6.38488286028985e-06 2.28954861836475e-05 -2.62370294742225e-05 1.02301498023658e-05 6.64287084380457e-05 6.38488286028985e-06 0.000216091034543478 3200 3204 0 54 856 3200 3204 0 54 934 0 0 0 0 0 0 0 0 3251 0 0 0 0 0 2866 +966 969 0.995078450552676 -0.0981738300022654 0.0134453095305229 0.428219429096887 0.0983427779640126 0.99507359915399 -0.0125391502521072 0.0651245534343589 -0.0121480561410536 0.0137996872939317 0.999830982397817 0.0575706296199939 4.51599689529676e-05 -1.45675811181563e-05 3.95168587541395e-06 4.79068459590019e-06 2.56157470466531e-06 1.81357094594404e-05 -1.45675811181563e-05 4.92335546833687e-05 2.34251235204756e-07 -1.25160316600827e-05 2.37480838805368e-07 -2.63698160440179e-05 3.95168587541395e-06 2.34251235204756e-07 1.12122876456458e-05 -3.29354147756566e-06 4.40239893813859e-06 -6.0120505185892e-07 4.79068459590019e-06 -1.25160316600827e-05 -3.29354147756566e-06 0.000166254603310235 5.03438075542525e-06 3.27472307268546e-05 2.56157470466531e-06 2.37480838805368e-07 4.40239893813859e-06 5.03438075542525e-06 1.04765309301037e-05 3.63011303822577e-06 1.81357094594404e-05 -2.63698160440179e-05 -6.0120505185892e-07 3.27472307268546e-05 3.63011303822577e-06 0.000145673223880695 3106 3104 0 122 895 3106 3104 0 120 975 0 0 0 0 0 0 0 0 3099 0 0 0 0 0 2829 +972 975 0.997316968563256 0.0444405022692709 -0.0581713501119932 0.415911720416344 -0.0459118099616946 0.998652210319473 -0.024204721235177 -0.0235561573292285 0.0570172773976309 0.0268105311787424 0.998013138939601 -0.0131002979261251 9.38323366308744e-05 1.39371516468663e-06 -1.87271640320325e-06 -4.27070116715524e-06 3.49174040526773e-06 1.93189532436033e-05 1.39371516468663e-06 2.34653694203422e-05 1.59885189242141e-07 7.42214062167376e-06 1.15994466268232e-06 -1.0459654975523e-05 -1.87271640320325e-06 1.59885189242141e-07 1.19104188051692e-05 -9.58795538200296e-07 5.24817620753833e-06 -2.32407575423612e-06 -4.27070116715524e-06 7.42214062167376e-06 -9.58795538200296e-07 0.000416824987264802 2.14005452587938e-05 0.000114888961820807 3.49174040526773e-06 1.15994466268232e-06 5.24817620753833e-06 2.14005452587938e-05 1.4253032992661e-05 8.96111570477534e-06 1.93189532436033e-05 -1.0459654975523e-05 -2.32407575423612e-06 0.000114888961820807 8.96111570477534e-06 0.00014109678927534 3342 3341 0 233 347 3342 3341 0 148 416 0 0 0 0 0 0 0 0 2049 0 0 0 0 0 3415 +976 978 0.997525756735632 -0.0284148668568941 0.06430365456573 0.318973976624499 0.0284340223026823 0.99959548076122 0.000617428081346989 0.0186774828301648 -0.0642951866370595 0.00121251113399046 0.997930187333791 0.019876412131291 9.71320301666653e-05 4.23189779309369e-05 8.42066795387002e-07 -7.18940028450782e-05 2.03244306453983e-06 2.27007471235556e-05 4.23189779309369e-05 0.000362689223892302 -1.39068918091626e-06 -8.45552928091584e-05 6.16725146411383e-06 0.000246857534088279 8.42066795387002e-07 -1.39068918091626e-06 1.42023487692891e-05 1.59303272906685e-06 3.47279077571468e-06 -4.73400321642385e-06 -7.18940028450782e-05 -8.45552928091584e-05 1.59303272906685e-06 0.000319725573039088 7.09808496197087e-06 0.000105457795855168 2.03244306453983e-06 6.16725146411383e-06 3.47279077571468e-06 7.09808496197087e-06 1.35039939207615e-05 2.77273652843638e-05 2.27007471235556e-05 0.000246857534088279 -4.73400321642385e-06 0.000105457795855168 2.77273652843638e-05 0.00118731960681759 3182 3185 0 320 467 3182 3185 0 257 534 0 0 0 0 0 0 0 0 1954 0 0 0 0 0 3268 +976 980 0.994509806899432 -0.103685021944822 -0.0141301169548138 0.551859725890779 0.104226799657828 0.993515541107191 0.0454273465169685 0.0556183776502233 0.00932835537176282 -0.0466506784815349 0.998867706947857 -0.0152990102391923 8.57264373806517e-05 -1.488051332637e-05 -6.08265492704675e-09 -8.0909213890459e-06 2.83672936140381e-06 2.41713095878346e-05 -1.488051332637e-05 3.028083982587e-05 5.50099698434811e-07 4.22183301499647e-05 -4.82036102749016e-07 -1.84220392345186e-05 -6.08265492704675e-09 5.50099698434811e-07 1.13997091065477e-05 2.72398897199121e-06 4.97436939175564e-06 1.43340011620063e-07 -8.0909213890459e-06 4.22183301499647e-05 2.72398897199121e-06 0.000888440551442739 -1.51380031563115e-05 0.00013610072908609 2.83672936140381e-06 -4.82036102749016e-07 4.97436939175564e-06 -1.51380031563115e-05 1.17479432748092e-05 -2.92739339307198e-06 2.41713095878346e-05 -1.84220392345186e-05 1.43340011620063e-07 0.00013610072908609 -2.92739339307198e-06 0.000105525159385328 3260 3239 0 461 1111 3260 3239 0 391 1200 0 0 0 0 0 0 0 0 1703 0 0 0 0 0 2588 +978 980 0.996153161200847 -0.0736013945927355 -0.0475574825191927 0.302301500698335 0.0757420998092238 0.996116148915371 0.0448971289338215 0.0345037419425384 0.0440682850363892 -0.0483265205039125 0.997858974840602 0.0016592430055161 0.000113077356494796 -1.76625968223874e-05 -7.63067069218875e-07 -2.07052266984107e-05 9.93333363825301e-06 -1.04763167868356e-06 -1.76625968223874e-05 0.000353258396198431 1.41951263874277e-05 0.000198937047870846 -3.91059268330597e-06 6.79283228342012e-05 -7.63067069218875e-07 1.41951263874277e-05 1.36958340319318e-05 -5.0866651956315e-06 1.95657121917245e-06 -8.88543474921125e-08 -2.07052266984107e-05 0.000198937047870846 -5.0866651956315e-06 0.000612654488268952 -1.13490810739203e-05 0.000182062480685067 9.93333363825301e-06 -3.91059268330597e-06 1.95657121917245e-06 -1.13490810739203e-05 1.63409559942933e-05 -2.00893041531063e-05 -1.04763167868356e-06 6.79283228342012e-05 -8.88543474921125e-08 0.000182062480685067 -2.00893041531063e-05 0.000361049209652255 3088 3067 0 128 558 3088 3067 0 68 625 0 0 0 0 0 0 0 0 2369 0 0 0 0 0 3162 +978 981 0.99496446159156 -0.0946651041798495 -0.0329277727828025 0.398581402222106 0.0959296976189387 0.994615324367339 0.0392154261533884 0.0529449687153004 0.0290381350047935 -0.0421767066551091 0.998688095518902 0.0109771050299676 9.88552138746484e-05 -4.89837293060794e-06 -2.29016325561668e-07 6.56757056705946e-06 2.12515963503992e-06 3.56213261433744e-05 -4.89837293060794e-06 3.4266055220649e-05 1.57247339313354e-07 -2.38348108453688e-05 3.95054521232033e-07 -1.73898287524556e-05 -2.29016325561668e-07 1.57247339313354e-07 1.65455198422019e-05 -5.56096965821709e-06 2.72565295643778e-06 -1.57627689727784e-06 6.56757056705946e-06 -2.38348108453688e-05 -5.56096965821709e-06 0.000478754999082841 -1.01995199566527e-05 -6.71609043113902e-05 2.12515963503992e-06 3.95054521232033e-07 2.72565295643778e-06 -1.01995199566527e-05 1.56155660518072e-05 3.52787071446027e-06 3.56213261433744e-05 -1.73898287524556e-05 -1.57627689727784e-06 -6.71609043113902e-05 3.52787071446027e-06 0.000103579194180925 3327 3300 0 216 789 3327 3300 0 148 858 0 0 0 0 0 0 0 0 2194 0 0 0 0 0 2917 +979 981 0.998722886998896 -0.043689907300959 -0.0253729577429167 0.280290482013322 0.0441805884641229 0.998840748795033 0.0191111001656441 0.0242605633585779 0.0245085819164233 -0.0202076853353145 0.999495362103214 -0.00062054625445556 0.000113617044744295 8.95406116679584e-05 -1.70676345467939e-06 -3.9258076466875e-06 8.47832843477914e-06 8.90951207282542e-05 8.95406116679584e-05 0.000280320815472808 1.4020884753902e-06 -3.82505100249629e-05 1.53443026696641e-05 -6.56827989217235e-06 -1.70676345467939e-06 1.4020884753902e-06 1.39909734786223e-05 -8.35190032712433e-06 3.08599092160736e-06 -2.39112455254107e-06 -3.9258076466875e-06 -3.82505100249629e-05 -8.35190032712433e-06 0.000204604330159754 -3.98541363749867e-06 3.24627876777168e-05 8.47832843477914e-06 1.53443026696641e-05 3.08599092160736e-06 -3.98541363749867e-06 1.45037410127294e-05 -5.09600482256834e-06 8.90951207282542e-05 -6.56827989217235e-06 -2.39112455254107e-06 3.24627876777168e-05 -5.09600482256834e-06 0.00033514626933249 3179 3152 0 205 414 3179 3152 0 142 474 0 0 0 0 0 0 0 0 2266 0 0 0 0 0 3310 +983 985 0.997458601762002 0.0135337248514494 -0.0699512406082835 0.272778568563525 -0.0158463774978222 0.999342444710269 -0.0326124289297712 -0.00683758870122374 0.0694638761601253 0.033638021525472 0.997017178095073 0.0211541624208019 5.38565976136959e-05 2.7551779461281e-06 -5.95976653427408e-06 1.9165296227801e-05 3.31814012205626e-06 -1.3369836704653e-05 2.7551779461281e-06 5.56645697170053e-05 -9.22088800640382e-07 -3.87355904504362e-06 1.05827886602649e-06 -5.69965115230909e-05 -5.95976653427408e-06 -9.22088800640382e-07 1.48292503674097e-05 -1.07954252903671e-06 2.60798536983188e-06 8.43318007134346e-07 1.9165296227801e-05 -3.87355904504362e-06 -1.07954252903671e-06 0.000253887210607738 6.09904141591038e-06 -8.57540512130525e-05 3.31814012205626e-06 1.05827886602649e-06 2.60798536983188e-06 6.09904141591038e-06 1.47872545581669e-05 -5.46304535878581e-06 -1.3369836704653e-05 -5.69965115230909e-05 8.43318007134346e-07 -8.57540512130525e-05 -5.46304535878581e-06 0.000297167625230946 3151 3128 0 418 229 3151 3128 0 336 269 0 0 0 0 0 0 0 0 2828 0 0 0 0 0 3535 +983 986 0.998979526708822 0.018570255556006 -0.0411709949503511 0.410910848867057 -0.0191444872753433 0.999724262532978 -0.0135973346600832 -0.0119761680265426 0.0409071365849704 0.0143716565321716 0.999059588645712 0.00611919483377688 5.71670168400267e-05 1.09345224649031e-06 -5.04973628656806e-06 2.96058410443709e-05 7.6917398574247e-06 5.44802450825576e-06 1.09345224649031e-06 6.19790237461157e-05 -4.97331376041973e-07 -6.98285712245017e-06 2.20520814014187e-06 1.44634754984453e-05 -5.04973628656806e-06 -4.97331376041973e-07 1.39915152089305e-05 -2.90993632033495e-06 1.47720448350922e-06 -2.67929222596443e-06 2.96058410443709e-05 -6.98285712245017e-06 -2.90993632033495e-06 0.000428130055573894 9.6315327282214e-06 -8.45902292969414e-07 7.6917398574247e-06 2.20520814014187e-06 1.47720448350922e-06 9.6315327282214e-06 1.58946814951234e-05 -7.52821573671059e-07 5.44802450825576e-06 1.44634754984453e-05 -2.67929222596443e-06 -8.45902292969414e-07 -7.52821573671059e-07 0.000260424375421945 3407 3385 0 684 415 3407 3385 0 595 464 0 0 0 0 0 0 0 0 2590 0 0 0 0 0 3352 +983 987 0.999924333793705 -0.00929104989212018 -0.00806244870480066 0.608341981549283 0.00925121370349981 0.999944884054935 -0.0049642620170291 -0.013815404371122 0.00810812754139853 0.0048892989542136 0.999955175507137 0.00384692165055054 5.67741261689717e-05 1.16385396998689e-05 -4.11389831502639e-06 9.02094871376959e-06 9.99601366226139e-06 -1.84368830776183e-05 1.16385396998689e-05 9.99535697148578e-05 -3.21866172026512e-06 3.87547302286433e-05 4.08224456502937e-06 -0.000111366486152777 -4.11389831502639e-06 -3.21866172026512e-06 1.61139177675864e-05 -5.52716945951359e-06 -1.07335153524034e-06 4.70656059650849e-06 9.02094871376959e-06 3.87547302286433e-05 -5.52716945951359e-06 0.000248447088724828 7.80744525563368e-06 -5.04628786802087e-05 9.99601366226139e-06 4.08224456502937e-06 -1.07335153524034e-06 7.80744525563368e-06 1.75902497783539e-05 -8.88244293906571e-06 -1.84368830776183e-05 -0.000111366486152777 4.70656059650849e-06 -5.04628786802087e-05 -8.88244293906571e-06 0.000329535301390466 3186 3161 0 1036 806 3186 3161 0 926 868 0 0 0 0 0 0 0 0 2400 0 0 0 0 0 2922 +984 986 0.999943338723666 0.00506982381348507 -0.00936035408879413 0.313564247635577 -0.00490367583673732 0.999831519317526 0.0176886105303945 -0.00809986625845701 0.00944845518884351 -0.0176417081289767 0.999799728360053 0.0059000302812819 3.93403136893909e-05 -5.25981786178703e-06 3.8324874124568e-06 -1.15000835532606e-05 -1.02473636281882e-06 5.01348008956103e-06 -5.25981786178703e-06 4.40797506650566e-05 4.16507737652433e-07 2.78678897368472e-05 1.20681947668732e-06 -7.23538828127936e-06 3.8324874124568e-06 4.16507737652433e-07 1.58209294455906e-05 -1.20780832777612e-05 1.17205008584857e-06 2.06539621248013e-06 -1.15000835532606e-05 2.78678897368472e-05 -1.20780832777612e-05 0.000555785310904245 2.69802059255121e-06 1.43049679219068e-05 -1.02473636281882e-06 1.20681947668732e-06 1.17205008584857e-06 2.69802059255121e-06 1.45981519180435e-05 -7.5086009035689e-06 5.01348008956103e-06 -7.23538828127936e-06 2.06539621248013e-06 1.43049679219068e-05 -7.5086009035689e-06 0.000129190812883057 3326 3304 0 460 300 3326 3304 0 376 362 0 0 0 0 0 0 0 0 2997 0 0 0 0 0 3454 +986 989 0.995260898087033 -0.0953339984437654 0.0191617713094722 0.465793234575622 0.0954301903209264 0.995427399703163 -0.00416781663600626 0.0182182176931656 -0.0186768175636037 0.00597667641116266 0.999807709424553 0.0396637539336335 7.81176702869828e-05 3.04149016431056e-06 -7.21463781994244e-06 -1.21875885491275e-05 1.61338048831425e-06 3.2738102074469e-05 3.04149016431056e-06 9.96279113462252e-05 -4.059683526613e-06 -2.89954759841013e-06 1.45132866376125e-06 -3.85203290146838e-05 -7.21463781994244e-06 -4.059683526613e-06 1.46854934418334e-05 -1.23521920769438e-06 4.2745761404824e-06 4.16065263800146e-07 -1.21875885491275e-05 -2.89954759841013e-06 -1.23521920769438e-06 0.000175110259668923 -6.21267821012148e-06 -4.43596565990919e-05 1.61338048831425e-06 1.45132866376125e-06 4.2745761404824e-06 -6.21267821012148e-06 1.25370636306399e-05 5.10005710856356e-06 3.2738102074469e-05 -3.85203290146838e-05 4.16065263800146e-07 -4.43596565990919e-05 5.10005710856356e-06 0.000145010466093665 3204 3158 0 460 822 3204 3158 0 363 877 0 0 0 0 0 0 0 0 3270 0 0 0 0 0 2891 +987 989 0.99753193189888 -0.0676948185580152 0.0186401819327144 0.289523806001304 0.0680165613064493 0.997535851020253 -0.0172038750677017 0.00925360987984416 -0.0174296365462198 0.0184292558096213 0.999678233383207 0.0254424696145753 8.17572118511631e-05 3.71585550232189e-05 -4.37356553336606e-06 -1.65170075368598e-05 4.10209156502599e-06 1.07958371984768e-05 3.71585550232189e-05 0.000267025864425762 -6.81568437382893e-06 0.000140536007322962 -2.02085409667292e-06 -2.78394319114806e-05 -4.37356553336606e-06 -6.81568437382893e-06 1.45851004488642e-05 -6.34552789083481e-06 3.4887740613647e-06 2.28932014728536e-06 -1.65170075368598e-05 0.000140536007322962 -6.34552789083481e-06 0.000270677372968614 -1.4030356758217e-05 5.90973110530125e-05 4.10209156502599e-06 -2.02085409667292e-06 3.4887740613647e-06 -1.4030356758217e-05 1.37393213295935e-05 -1.08374088823293e-05 1.07958371984768e-05 -2.78394319114806e-05 2.28932014728536e-06 5.90973110530125e-05 -1.08374088823293e-05 0.000596582868049388 3200 3154 0 222 464 3200 3154 0 136 507 0 0 0 0 0 0 0 0 3528 0 0 0 0 0 3265 +985 987 0.998973321731509 -0.0228846262325048 0.0390972678190266 0.321444550332815 0.0217848988467098 0.999361318010531 0.0283262112978877 -0.00374991373569508 -0.0397205318563683 -0.0274453993676992 0.99883383473058 0.019911597439824 9.85872147438677e-05 1.63011329946866e-05 -4.136255796945e-06 -9.76904499155531e-08 1.05849902486353e-05 7.17545330420673e-05 1.63011329946866e-05 5.51355542252981e-05 9.03528427127346e-07 7.91500725337109e-08 2.35589077761236e-06 -1.85162327881005e-05 -4.136255796945e-06 9.03528427127346e-07 1.41485395515857e-05 -5.00332901777557e-06 1.40138006306915e-06 -9.04426749445774e-06 -9.76904499155531e-08 7.91500725337109e-08 -5.00332901777557e-06 0.000164525586538672 7.85867792435541e-07 -1.07064536264473e-05 1.05849902486353e-05 2.35589077761236e-06 1.40138006306915e-06 7.85867792435541e-07 1.40997279652124e-05 1.88936706021758e-06 7.17545330420673e-05 -1.85162327881005e-05 -9.04426749445774e-06 -1.07064536264473e-05 1.88936706021758e-06 0.000403658110903746 3177 3152 0 402 393 3177 3152 0 317 446 0 0 0 0 0 0 0 0 3187 0 0 0 0 0 3345 +987 990 0.994742040310753 -0.101547884053209 -0.0132778192003278 0.463793283532845 0.101567843994117 0.994828263724491 0.000835919434901728 0.0160383408242057 0.0131242639712566 -0.00218012367333054 0.999911496461553 -0.00180880463304455 5.26028328713927e-05 6.49190706145694e-06 -2.5877753623562e-06 1.03750436062384e-05 -1.59440990257956e-06 -7.32315999049771e-06 6.49190706145694e-06 6.83847866310201e-05 -2.4809780149694e-06 -2.16536380943024e-05 6.69927626739589e-06 -5.9008649439566e-05 -2.5877753623562e-06 -2.4809780149694e-06 1.16608151050643e-05 5.90942568213277e-06 3.59949484890078e-06 2.52829101945716e-06 1.03750436062384e-05 -2.16536380943024e-05 5.90942568213277e-06 0.000237150967579097 -2.5127075758591e-05 1.89085081252188e-07 -1.59440990257956e-06 6.69927626739589e-06 3.59949484890078e-06 -2.5127075758591e-05 1.48602391279344e-05 -3.55419130935245e-06 -7.32315999049771e-06 -5.9008649439566e-05 2.52829101945716e-06 1.89085081252188e-07 -3.55419130935245e-06 0.000100744024365069 3314 3255 0 458 823 3314 3255 0 364 867 0 0 0 0 0 0 0 0 3299 0 0 0 0 0 2896 +1006 1009 0.995862817202904 0.0144060221683584 0.0897202086376322 0.419369014746261 -0.0145847207431905 0.999892744196817 0.00133642186495083 0.0126433724750261 -0.0896913331015803 -0.00263943703140215 0.995966112946931 -0.0362979903249288 3.59105641613019e-05 2.95772966793586e-05 2.52059172197106e-06 1.78586598954481e-05 7.42267792128086e-07 4.9580367870835e-05 2.95772966793586e-05 9.9614378815528e-05 -4.16949723565769e-06 0.000185459318870069 -3.20388418277436e-05 0.000439226793386887 2.52059172197106e-06 -4.16949723565769e-06 1.13764289025945e-05 8.83587665807318e-06 2.56374081676205e-06 1.93729665553531e-05 1.78586598954481e-05 0.000185459318870069 8.83587665807318e-06 0.00113528682482726 -0.00019705600596186 0.00214550185328467 7.42267792128086e-07 -3.20388418277436e-05 2.56374081676205e-06 -0.00019705600596186 4.81396978068213e-05 -0.000427052059576662 4.9580367870835e-05 0.000439226793386887 1.93729665553531e-05 0.00214550185328467 -0.000427052059576662 0.00594713684703392 2313 2301 0 0 290 2313 2301 0 0 274 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3595 +1006 1010 0.998232815885096 0.0137982266658989 0.0578001231053045 0.588954614037479 -0.0153194113612094 0.999545642930654 0.0259581072863778 0.00446175472967486 -0.0574156853626074 -0.026797698394107 0.997990642458696 -0.0333786679874156 8.26592849493179e-05 0.000210294464281887 4.40446089886342e-06 0.000114368820504419 -1.16364392821427e-05 2.21548376578017e-05 0.000210294464281887 0.000919676765516339 1.2708415148532e-05 0.000506329852409431 -6.7341168552902e-05 0.000204589036809201 4.40446089886342e-06 1.2708415148532e-05 1.19153894221606e-05 1.93210539222745e-05 1.07915386901392e-06 1.68800320200256e-05 0.000114368820504419 0.000506329852409431 1.93210539222745e-05 0.000899437174371601 -0.000138408986065341 0.000706039632161324 -1.16364392821427e-05 -6.7341168552902e-05 1.07915386901392e-06 -0.000138408986065341 3.71972042050351e-05 -0.000148212595563137 2.21548376578017e-05 0.000204589036809201 1.68800320200256e-05 0.000706039632161324 -0.000148212595563137 0.00114239969685088 2173 2160 0 0 473 2173 2160 0 0 456 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3450 +1015 1017 0.996805057443993 0.0708224946592839 -0.0369303629052533 0.286758630256759 -0.0721348535715158 0.996762790186359 -0.0355035632031672 -0.00287763948481825 0.0342963606566932 0.0380540976787129 0.998686960611565 -0.0380999377096767 4.05509889129639e-05 1.12736732966852e-05 1.56546477210948e-06 -6.24767287249618e-06 -2.30657834064952e-06 -1.08334579288626e-06 1.12736732966852e-05 2.1982833595099e-05 -3.23315401061455e-07 -5.07205947231106e-06 -2.19109393851559e-07 -1.41079588944575e-05 1.56546477210948e-06 -3.23315401061455e-07 1.34357506332277e-05 -4.93874726566091e-06 4.78431475758091e-06 3.92317812845759e-08 -6.24767287249618e-06 -5.07205947231106e-06 -4.93874726566091e-06 0.000438976462217495 -7.66438039127394e-07 -3.89439577667095e-05 -2.30657834064952e-06 -2.19109393851559e-07 4.78431475758091e-06 -7.66438039127394e-07 1.19268911105531e-05 -4.82239581005534e-07 -1.08334579288626e-06 -1.41079588944575e-05 3.92317812845759e-08 -3.89439577667095e-05 -4.82239581005534e-07 8.61532425190377e-05 2471 2463 0 0 68 2469 2462 0 0 58 0 0 0 0 0 0 0 0 0 0 17 12 0 0 3883 +1014 1018 0.990913223488466 0.133863331133801 -0.0130993165264509 0.566840904848418 -0.134047316432082 0.990871045449453 -0.0143488064753217 -0.0394894734738265 0.0110589544286569 0.0159743503051384 0.999811242014848 -0.0538069005517456 4.18389361689494e-05 1.80387673716657e-05 -4.05562974491937e-06 -1.26056266887433e-05 1.7630731479443e-06 -2.19607693648627e-05 1.80387673716657e-05 3.53746170208164e-05 -2.46286875310665e-06 5.95043190771282e-06 -8.60503803920782e-07 -1.74575238047239e-05 -4.05562974491937e-06 -2.46286875310665e-06 1.04559555960325e-05 -1.60280777248722e-07 4.90197291195806e-06 1.27572271496268e-06 -1.26056266887433e-05 5.95043190771282e-06 -1.60280777248722e-07 0.000258288559656992 -2.71641328427963e-06 1.42940786383712e-05 1.7630731479443e-06 -8.60503803920782e-07 4.90197291195806e-06 -2.71641328427963e-06 1.07566216975764e-05 -2.49015393123426e-06 -2.19607693648627e-05 -1.74575238047239e-05 1.27572271496268e-06 1.42940786383712e-05 -2.49015393123426e-06 0.000162502444687786 2424 2418 0 0 106 2424 2418 0 0 89 0 0 0 0 0 0 0 0 0 0 1 0 0 0 3859 +1021 1047 0.999005007270039 0.0434698463646477 0.00996834521990342 3.56371846642736 -0.0422539013926639 0.994060074238111 -0.100295446670429 -0.501143545117593 -0.0142689616471656 0.0997744519541737 0.994907762292946 0.0357582537075262 7.0291392123062e-05 8.05111927304487e-05 -1.02669552883897e-05 -8.69361979291118e-06 -2.70596568530425e-06 -0.000126603061090249 8.05111927304487e-05 0.000370454321364199 -2.21725001141298e-05 8.99032481318576e-05 -1.98142416869076e-05 -0.000539292459676883 -1.02669552883897e-05 -2.21725001141298e-05 1.45352822426415e-05 2.70467964980876e-09 7.40520219631226e-06 3.36630883114038e-05 -8.69361979291118e-06 8.99032481318576e-05 2.70467964980876e-09 0.000605084293409149 -2.37277818830153e-06 -0.000253204487921097 -2.70596568530425e-06 -1.98142416869076e-05 7.40520219631226e-06 -2.37277818830153e-06 1.49332548927462e-05 6.21854992390665e-05 -0.000126603061090249 -0.000539292459676883 3.36630883114038e-05 -0.000253204487921097 6.21854992390665e-05 0.00132007808772062 2617 2579 0 3759 3805 2617 2579 0 3759 3805 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1022 1048 0.999908808360552 0.00619930234078053 0.0119976503311826 3.54798422783393 -0.00468446129343084 0.992469082554102 -0.122405784163209 -0.537813181222135 -0.0126661274812818 0.122338419250485 0.992407618063223 -0.030882684188948 5.40903229405722e-05 1.85589470159311e-05 5.8110544009706e-06 -4.6931396437308e-07 6.23897488052779e-06 -2.20956267897666e-05 1.85589470159311e-05 0.000105171264546942 -1.3277503378753e-06 8.7025365850296e-06 -2.73623198195623e-06 -8.72034733671254e-05 5.8110544009706e-06 -1.3277503378753e-06 1.19964234177115e-05 -2.10618855443467e-06 6.10562109957244e-06 5.55853761488376e-07 -4.6931396437308e-07 8.7025365850296e-06 -2.10618855443467e-06 0.000158568459331879 -1.58276858189892e-06 -2.912737714289e-05 6.23897488052779e-06 -2.73623198195623e-06 6.10562109957244e-06 -1.58276858189892e-06 1.25727606258624e-05 7.22487402115216e-06 -2.20956267897666e-05 -8.72034733671254e-05 5.55853761488376e-07 -2.912737714289e-05 7.22487402115216e-06 0.000190413425512327 2613 2563 0 3773 3827 2613 2563 0 3773 3827 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1024 1050 0.995371266831381 -0.0959296906186169 0.0057909951050939 3.44914047886576 0.0960375870482961 0.990627354687446 -0.0971299439868824 -0.593584364129882 0.00358092731449811 0.097236508589986 0.995254861006365 0.0849207372287386 5.28571661218821e-05 2.08424966470453e-05 -1.10764695911251e-06 -1.82651826836933e-06 9.66268281811456e-07 -7.09555817685895e-06 2.08424966470453e-05 7.58702203300351e-05 -6.40064148608333e-06 1.18279220940388e-05 2.00740740912171e-06 -5.05556147098369e-05 -1.10764695911251e-06 -6.40064148608333e-06 1.2813860295856e-05 3.43414938651303e-07 4.27709186176855e-06 5.6214415672992e-06 -1.82651826836933e-06 1.18279220940388e-05 3.43414938651303e-07 0.000130808094825631 4.16833871523858e-06 2.70142926803834e-05 9.66268281811456e-07 2.00740740912171e-06 4.27709186176855e-06 4.16833871523858e-06 1.58101529481001e-05 4.9894051138978e-07 -7.09555817685895e-06 -5.05556147098369e-05 5.6214415672992e-06 2.70142926803834e-05 4.9894051138978e-07 0.000211479327301433 2846 2759 0 3754 3835 2846 2759 0 3754 3835 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1024 1027 0.995122071925867 0.086458014173553 0.0475086702732874 0.477628812148026 -0.0859058579477546 0.996211147155038 -0.0135474667116697 -0.0319303948636715 -0.0484999539817353 0.00940011006367977 0.998778950716604 0.0266847907499793 3.87051612806273e-05 7.06783707674039e-05 7.57492241194232e-06 8.62095413201618e-05 7.51489340967128e-06 -5.75615946186429e-05 7.06783707674039e-05 0.000554489768759368 1.43027525850698e-05 0.000781449288922902 6.33383196291637e-05 -0.000402794790423255 7.57492241194232e-06 1.43027525850698e-05 1.01800187131237e-05 1.78513410421079e-05 7.18501682874124e-06 -1.73010798143e-05 8.62095413201618e-05 0.000781449288922902 1.78513410421079e-05 0.00141168162239572 0.000102145657979935 -0.00057633935327582 7.51489340967128e-06 6.33383196291637e-05 7.18501682874124e-06 0.000102145657979935 1.81733268404595e-05 -5.07281481568325e-05 -5.75615946186429e-05 -0.000402794790423255 -1.73010798143e-05 -0.00057633935327582 -5.07281481568325e-05 0.000820636722117695 2382 2382 0 0 184 2382 2382 0 0 179 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3741 +1023 1049 0.999209123941555 -0.0351106037005896 0.0186647298327448 3.50419740729371 0.0368069221771352 0.99430215630909 -0.100042353225722 -0.582698151594661 -0.015045833702242 0.100650223382137 0.994808099796805 -0.0235021143407997 5.36638068443314e-05 1.02258691858875e-05 2.46762762154063e-06 2.55081941565796e-06 5.90987233742894e-06 -2.00468781995253e-05 1.02258691858875e-05 4.81632777429394e-05 1.27152035605705e-06 1.40485042896749e-05 -1.85487649608922e-07 -2.80125446270549e-05 2.46762762154063e-06 1.27152035605705e-06 1.25099318396654e-05 -3.2713969825667e-06 5.07845023502308e-06 -1.14261459285955e-07 2.55081941565796e-06 1.40485042896749e-05 -3.2713969825667e-06 0.000105588398097737 6.19753388640772e-06 -1.97652082009202e-07 5.90987233742894e-06 -1.85487649608922e-07 5.07845023502308e-06 6.19753388640772e-06 1.30551825665047e-05 -2.53348293621798e-06 -2.00468781995253e-05 -2.80125446270549e-05 -1.14261459285955e-07 -1.97652082009202e-07 -2.53348293621798e-06 0.000105165437348866 2898 2832 0 3782 3830 2898 2832 0 3782 3830 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1026 1052 0.929677639966073 -0.363540494786883 -0.0594793611029909 3.32627444925457 0.355954225494643 0.928119018358731 -0.109048966585359 -0.342627559261481 0.094847641507952 0.0802084559814842 0.992255273853178 0.262821415980431 7.76013636168227e-05 -6.51885027498989e-07 -3.2441267590936e-06 3.83047150243732e-06 -9.86795507455591e-06 2.39088487637309e-06 -6.51885027498989e-07 5.37068475444214e-05 -4.25084807397673e-06 7.92892615273702e-06 8.7449202531247e-07 6.40148099817089e-06 -3.2441267590936e-06 -4.25084807397673e-06 1.22917524716901e-05 2.38244771112355e-06 4.12129230510296e-06 3.85156174994758e-07 3.83047150243732e-06 7.92892615273702e-06 2.38244771112355e-06 9.43138390917558e-05 7.00464187123892e-07 0.000139002271640595 -9.86795507455591e-06 8.7449202531247e-07 4.12129230510296e-06 7.00464187123892e-07 2.05882005091632e-05 -2.4236852532676e-05 2.39088487637309e-06 6.40148099817089e-06 3.85156174994758e-07 0.000139002271640595 -2.4236852532676e-05 0.000514988733581039 2832 2676 0 3020 3779 2832 2676 0 3020 3779 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1027 1054 0.861495801374637 -0.507359108887844 0.0202908561279312 3.37566712414978 0.507408926346926 0.858708894672974 -0.0717998305915821 -0.151277975259772 0.0190043594296591 0.0721510141165917 0.997212648076936 0.22956899147954 0.000113560749127312 5.48911767735044e-07 1.29770584548439e-06 3.65706484935576e-05 2.21028298821854e-05 -2.60849082336128e-05 5.48911767735044e-07 9.90005068985008e-05 -3.99370433634246e-06 -8.86360740443939e-06 6.01220793425238e-06 -7.38587229493348e-05 1.29770584548439e-06 -3.99370433634246e-06 1.30791689723187e-05 1.92381110223831e-06 7.61125894388814e-06 2.291544868088e-06 3.65706484935576e-05 -8.86360740443939e-06 1.92381110223831e-06 0.000134863469581921 -2.31309241534566e-05 -2.79256805637694e-05 2.21028298821854e-05 6.01220793425238e-06 7.61125894388814e-06 -2.31309241534566e-05 4.98549056085805e-05 -4.0093642406097e-07 -2.60849082336128e-05 -7.38587229493348e-05 2.291544868088e-06 -2.79256805637694e-05 -4.0093642406097e-07 0.000165651500216546 2730 2697 0 1797 3748 2730 2697 0 1797 3748 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1025 1051 0.972321651532906 -0.226561816594411 -0.0570994677887914 3.41624730867923 0.220222569155123 0.970312654473804 -0.099976860336368 -0.499772716483417 0.0780552752543969 0.0846350744634941 0.99335002802412 0.181399686770064 5.92375095755312e-05 5.86410489957876e-06 -4.32387445875857e-07 -1.9912860913765e-05 -5.81157471049336e-07 1.24020283883023e-05 5.86410489957876e-06 3.94185867235881e-05 -9.8430276058557e-07 1.59665343138923e-06 3.90117254172396e-06 1.15237172073211e-05 -4.32387445875857e-07 -9.8430276058557e-07 1.51028314549285e-05 -4.19906630119704e-06 2.41667283444113e-06 -3.46124708224152e-06 -1.9912860913765e-05 1.59665343138923e-06 -4.19906630119704e-06 9.54242530626573e-05 1.15693747742282e-05 -1.8040554654475e-05 -5.81157471049336e-07 3.90117254172396e-06 2.41667283444113e-06 1.15693747742282e-05 2.57133423565888e-05 2.26421545664978e-05 1.24020283883023e-05 1.15237172073211e-05 -3.46124708224152e-06 -1.8040554654475e-05 2.26421545664978e-05 0.000355733718202177 2466 2348 0 3589 3792 2466 2348 0 3589 3792 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1027 1053 0.887462243423897 -0.460795459165906 0.00884936772344839 3.30979079374578 0.459783349478546 0.883862465339452 -0.0859442488265278 -0.19722783641885 0.0317810956279463 0.0803410678056265 0.996260646008131 0.154633924483846 6.53069343348179e-05 -9.14939711950881e-06 -3.27555319339399e-06 -6.15089977848363e-06 7.37843808537214e-06 6.9113461156479e-06 -9.14939711950881e-06 5.75116016045497e-05 -4.8613062215187e-07 -7.89779759316029e-06 4.16421022723689e-06 -3.3871097620914e-05 -3.27555319339399e-06 -4.8613062215187e-07 1.34502548330291e-05 6.8691147295088e-07 2.83161492897734e-06 7.37048224633111e-07 -6.15089977848363e-06 -7.89779759316029e-06 6.8691147295088e-07 0.000140325443214648 -2.78002871370521e-05 3.03992767015199e-05 7.37843808537214e-06 4.16421022723689e-06 2.83161492897734e-06 -2.78002871370521e-05 4.15524579884644e-05 -5.00280924674344e-06 6.9113461156479e-06 -3.3871097620914e-05 7.37048224633111e-07 3.03992767015199e-05 -5.00280924674344e-06 0.000208998954833012 2960 2781 0 2127 3744 2960 2781 0 2127 3744 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1029 1056 0.797785238883514 -0.602938132640341 -0.00207866008599829 3.15906546049886 0.600620079047228 0.795010879760354 -0.0849306876692386 0.0528646551259289 0.0528605076108429 0.06650796396558 0.996384693511636 0.285580119666433 8.00904778561869e-05 -1.9002356800315e-05 2.76260037828502e-06 5.34736293924383e-06 -7.58760734709881e-06 5.73337283836605e-06 -1.9002356800315e-05 0.00036861284320792 -1.01381099514003e-05 -5.61061726850626e-05 3.10214872610319e-05 -0.000330537974755873 2.76260037828502e-06 -1.01381099514003e-05 1.27693018142382e-05 6.80631675354504e-06 7.42313440886082e-06 9.10401897303719e-06 5.34736293924383e-06 -5.61061726850626e-05 6.80631675354504e-06 7.17355013702054e-05 -2.49447649084636e-05 5.15821465648582e-05 -7.58760734709881e-06 3.10214872610319e-05 7.42313440886082e-06 -2.49447649084636e-05 3.73680572336736e-05 -2.71640460336672e-05 5.73337283836605e-06 -0.000330537974755873 9.10401897303719e-06 5.15821465648582e-05 -2.71640460336672e-05 0.000428765880966257 2047 2017 0 1452 3712 2047 2017 0 1452 3712 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1030 1056 0.793492657470917 -0.60769283179225 -0.0328454673898466 3.04713810774536 0.602950088001705 0.792330615741137 -0.0930773159153564 0.0684823255970183 0.0825868870855274 0.0540519893027711 0.995116972287145 0.369192249888898 7.37320254382418e-05 -1.64176821951909e-06 -3.65266259902399e-07 -5.69472737915416e-06 -2.13180592510232e-06 -6.73753757738454e-06 -1.64176821951909e-06 5.83227989863953e-05 -2.02574911797116e-07 -6.02233852151068e-06 5.65406916377191e-06 -6.05473869373734e-05 -3.65266259902399e-07 -2.02574911797116e-07 1.02109040356972e-05 5.56351761976845e-06 5.93496267653965e-06 -1.00588977589523e-06 -5.69472737915416e-06 -6.02233852151068e-06 5.56351761976845e-06 3.16920813117723e-05 -4.26028090019469e-08 2.89045158333125e-05 -2.13180592510232e-06 5.65406916377191e-06 5.93496267653965e-06 -4.26028090019469e-08 1.92574071129394e-05 -1.7099804524482e-05 -6.73753757738454e-06 -6.05473869373734e-05 -1.00588977589523e-06 2.89045158333125e-05 -1.7099804524482e-05 0.000187788420507644 2181 2155 0 1445 3724 2181 2155 0 1445 3724 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1029 1032 0.998980309127825 -0.041529327297429 0.0177103627602323 0.469500685223037 0.0418386432518756 0.99897167515798 -0.0174676891116816 -0.0036058041644078 -0.016966729375996 0.0181908550179231 0.999690563568547 0.0291812360474565 3.49948791915512e-05 -4.19822475805338e-05 -3.51318766798899e-06 -1.78969518387158e-05 -3.41235982912098e-06 2.18838469378325e-05 -4.19822475805338e-05 0.000575760345862881 1.09201440184737e-05 0.000543506060844124 2.71398092212988e-05 0.000201752601050472 -3.51318766798899e-06 1.09201440184737e-05 1.01102278935199e-05 9.36929519713455e-06 6.73399976267673e-06 2.16701397830874e-06 -1.78969518387158e-05 0.000543506060844124 9.36929519713455e-06 0.00130722993920652 4.88159984848399e-05 0.000559611994004714 -3.41235982912098e-06 2.71398092212988e-05 6.73399976267673e-06 4.88159984848399e-05 1.25159450172385e-05 -1.86422537175711e-06 2.18838469378325e-05 0.000201752601050472 2.16701397830874e-06 0.000559611994004714 -1.86422537175711e-06 0.00132717171041491 2700 2704 0 0 545 2700 2704 0 0 550 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3346 +1031 1034 0.997603044238524 -0.0334991529991284 -0.0605472780095944 0.432546937217717 0.0340450294385279 0.999388229623672 0.00800640120101441 -0.00919749543441857 0.0602420293197357 -0.0100485440737863 0.998133219898745 0.0170273230237909 3.7474600506572e-05 -5.03865893652102e-06 -7.32420208022025e-06 -1.96876666442037e-05 -4.63557206283583e-06 2.92477559114532e-05 -5.03865893652102e-06 5.06287668978202e-05 3.76093745071401e-06 4.52457322086033e-06 -4.19143060186471e-06 5.28045219595664e-05 -7.32420208022025e-06 3.76093745071401e-06 1.12184138383017e-05 -5.28267845229738e-06 5.57172275069235e-06 8.94256067890976e-07 -1.96876666442037e-05 4.52457322086033e-06 -5.28267845229738e-06 0.000272098217947869 6.89009591759098e-07 6.99968831892128e-05 -4.63557206283583e-06 -4.19143060186471e-06 5.57172275069235e-06 6.89009591759098e-07 1.29311160804494e-05 -4.7200633987959e-05 2.92477559114532e-05 5.28045219595664e-05 8.94256067890976e-07 6.99968831892128e-05 -4.7200633987959e-05 0.00104158985188939 2896 2901 0 0 481 2896 2901 0 0 481 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3420 +1031 1035 0.999646737318643 -0.0241198188522031 -0.0111640004804876 0.571319350681437 0.0242475338316445 0.999640418323575 0.011449504659651 -0.00849305776203999 0.010883826132141 -0.0117161594562818 0.999872128792637 0.0365996542094044 3.28903672459832e-05 -5.13744204934727e-06 -5.73148055692094e-06 7.02646993520213e-06 -2.15995777380114e-06 7.52088364498696e-06 -5.13744204934727e-06 3.60029715734069e-05 -8.69553631439593e-07 1.15879655001157e-05 -3.57263670662412e-06 3.92830676032836e-05 -5.73148055692094e-06 -8.69553631439593e-07 1.07434311522533e-05 -3.41399869037615e-06 5.85834969726855e-06 5.42606212912637e-06 7.02646993520213e-06 1.15879655001157e-05 -3.41399869037615e-06 0.000268903607349508 5.49054185982004e-06 5.71869619561753e-05 -2.15995777380114e-06 -3.57263670662412e-06 5.85834969726855e-06 5.49054185982004e-06 1.23031351466832e-05 -2.06548660370198e-05 7.52088364498696e-06 3.92830676032836e-05 5.42606212912637e-06 5.71869619561753e-05 -2.06548660370198e-05 0.000492717958676907 3022 3025 0 0 614 3022 3025 0 0 614 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3297 +1032 1062 0.514669451111524 -0.857272957801517 -0.014086586343062 2.97039753849789 0.857367534229549 0.514702689697143 0.00143264359479268 0.186220169177937 0.00602223726744173 -0.0128147196912331 0.999899752784013 0.737117572967197 7.56059004460613e-05 7.16691848644282e-07 -6.97898974171511e-06 -6.12324907523737e-06 -4.25929555050203e-06 1.76413629894682e-05 7.16691848644282e-07 3.02827916473503e-05 -3.04983400846868e-06 -3.22954802508814e-06 4.44232294083457e-07 2.8521563158225e-06 -6.97898974171511e-06 -3.04983400846868e-06 1.86642684211712e-05 1.06397193275493e-05 2.25951464442786e-06 -1.69858931967211e-06 -6.12324907523737e-06 -3.22954802508814e-06 1.06397193275493e-05 5.96006274858282e-05 -3.27058749144488e-05 -1.44853822022471e-05 -4.25929555050203e-06 4.44232294083457e-07 2.25951464442786e-06 -3.27058749144488e-05 9.66712622711865e-05 2.11294848421594e-05 1.76413629894682e-05 2.8521563158225e-06 -1.69858931967211e-06 -1.44853822022471e-05 2.11294848421594e-05 0.000140323171110654 611 643 0 491 2621 611 643 0 491 2621 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1033 1062 0.523018144091074 -0.852163389619236 0.0164188411339881 2.83253622629014 0.852300875873241 0.523042574639503 -0.0031116073315789 0.156831759620567 -0.00593615508847576 0.0156212197710242 0.999860360028155 0.680683847961895 9.38525403496572e-05 4.02440536408524e-06 -1.95064881355954e-06 2.5209558571648e-06 -8.74498893366108e-06 4.02067453864463e-05 4.02440536408524e-06 7.06960809954154e-05 -5.003730456409e-06 1.8723269701049e-05 -3.20561716002896e-05 0.000136330379233488 -1.95064881355954e-06 -5.003730456409e-06 1.76282788176954e-05 3.02425523537261e-06 1.06965425768732e-05 -1.37938845387477e-07 2.5209558571648e-06 1.8723269701049e-05 3.02425523537261e-06 0.000104627789921194 -9.79931989967778e-05 8.81043439197421e-05 -8.74498893366108e-06 -3.20561716002896e-05 1.06965425768732e-05 -9.79931989967778e-05 0.000181790350930988 -0.000119977887789323 4.02067453864463e-05 0.000136330379233488 -1.37938845387477e-07 8.81043439197421e-05 -0.000119977887789323 0.000697506817492756 611 643 0 437 2661 611 643 0 437 2661 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1034 1062 0.522986058606803 -0.852340966484882 -0.000677756991164232 2.66112995216512 0.852278195701618 0.52295688352116 -0.0117462806637549 0.161536510771237 0.0103662738974315 0.0055655035220729 0.999930780372336 0.687539509125298 0.000101452339584644 -7.92074904020365e-06 1.53027056952843e-06 1.72100464181548e-05 -2.89077996164778e-05 2.07074220305742e-06 -7.92074904020365e-06 3.63170387332715e-05 -4.49550322501677e-06 -3.45908605983836e-06 2.58357653496923e-06 2.29599666586003e-05 1.53027056952843e-06 -4.49550322501677e-06 1.61522207160032e-05 5.32722073458379e-06 6.46625287843369e-06 3.14449267750155e-06 1.72100464181548e-05 -3.45908605983836e-06 5.32722073458379e-06 6.84602143882021e-05 -3.96928473077759e-05 1.73872723080888e-05 -2.89077996164778e-05 2.58357653496923e-06 6.46625287843369e-06 -3.96928473077759e-05 8.79396717000061e-05 -1.77610160801083e-05 2.07074220305742e-06 2.29599666586003e-05 3.14449267750155e-06 1.73872723080888e-05 -1.77610160801083e-05 0.000253592842646821 616 654 0 413 2853 616 654 0 413 2853 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1034 1038 0.99401490881822 0.107535715440003 0.0192465828632468 0.559176609029743 -0.106914190350545 0.993789790065818 -0.0308416773639944 -0.057125306775338 -0.0224436393838572 0.0285993542889332 0.999338961506787 0.00222384666126419 3.17529674878126e-05 4.12876131672621e-06 5.10773735469819e-06 -2.21611676252971e-06 2.41963236720031e-06 1.28699674323115e-05 4.12876131672621e-06 8.58918546956759e-05 -1.17117403964167e-06 6.60256252127174e-05 1.15498905200493e-05 0.000156767270431326 5.10773735469819e-06 -1.17117403964167e-06 9.54314656369703e-06 -3.75189464213906e-06 5.49861736004675e-06 -3.08094495542352e-06 -2.21611676252971e-06 6.60256252127174e-05 -3.75189464213906e-06 0.00034452744077948 4.3170005218079e-05 0.00036771455334887 2.41963236720031e-06 1.15498905200493e-05 5.49861736004675e-06 4.3170005218079e-05 1.63866568095219e-05 4.39669875837505e-05 1.28699674323115e-05 0.000156767270431326 -3.08094495542352e-06 0.00036771455334887 4.39669875837505e-05 0.00112313533411638 3338 3234 0 133 236 3338 3234 0 133 241 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3684 +1035 1062 0.513389194516842 -0.857601342484538 -0.0308459449857948 2.52769220771691 0.857989559416892 0.513665664276961 -0.00122526507951265 0.198087151959773 0.0168952917984683 -0.0258364608959191 0.999523399627752 0.737169179684234 8.59949417400533e-05 -8.48112405562398e-06 -8.6954825001339e-06 1.1887600828862e-05 -1.42148254249918e-05 -3.20656677512672e-05 -8.48112405562398e-06 3.52507883303445e-05 -1.48578681494776e-06 -1.29125607895955e-06 -5.99351624182483e-06 -3.48062913377142e-06 -8.6954825001339e-06 -1.48578681494776e-06 1.72976271466344e-05 8.72831884321473e-06 5.11088285132726e-06 5.45556776765332e-06 1.1887600828862e-05 -1.29125607895955e-06 8.72831884321473e-06 4.82255955945694e-05 -4.90403658712115e-06 -5.60520984433419e-06 -1.42148254249918e-05 -5.99351624182483e-06 5.11088285132726e-06 -4.90403658712115e-06 6.0611319062606e-05 -2.74613523729579e-05 -3.20656677512672e-05 -3.48062913377142e-06 5.45556776765332e-06 -5.60520984433419e-06 -2.74613523729579e-05 0.000314298875059025 616 654 0 293 2407 616 654 0 293 2407 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1035 1038 0.995365606936099 0.0950230737278493 -0.0147622487461363 0.39746630243169 -0.0954164254938607 0.995022789306437 -0.0287289837413779 -0.0488304031640824 0.0119588575836328 0.0300044033460015 0.999478224627803 -0.00385825284311989 3.22730422352596e-05 -3.43499401719074e-06 -4.66503904723919e-06 -5.63320819027968e-07 -2.37533788290114e-06 5.12863694441735e-06 -3.43499401719074e-06 2.56329696555315e-05 2.10860271015983e-06 6.70802074853214e-06 8.18699351514567e-07 -5.50536636133993e-06 -4.66503904723919e-06 2.10860271015983e-06 9.87211610553436e-06 -4.65725714289192e-06 5.3847041824783e-06 -1.39797057987803e-07 -5.63320819027968e-07 6.70802074853214e-06 -4.65725714289192e-06 0.000314689620395013 3.92882397470071e-05 5.10933074498768e-05 -2.37533788290114e-06 8.18699351514567e-07 5.3847041824783e-06 3.92882397470071e-05 1.65455223402748e-05 3.49990221973323e-06 5.12863694441735e-06 -5.50536636133993e-06 -1.39797057987803e-07 5.10933074498768e-05 3.49990221973323e-06 0.000192733340033117 3377 3273 0 133 98 3377 3273 0 133 109 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3815 +1034 1036 0.998686737667718 0.0319507401634123 0.0400493471809662 0.26798054414719 -0.0322662368741465 0.999452970114766 0.00725606551473874 -0.0168956910905689 -0.039795602327304 -0.00853877812001365 0.999171356326643 -0.0144008312241106 3.67454893699498e-05 -1.08602559872721e-06 -5.37512985034522e-06 1.19805941274184e-05 1.4174057073666e-06 -2.9964715037756e-06 -1.08602559872721e-06 4.54440297866658e-05 1.22330547223686e-06 4.07213371654389e-06 -5.62546161847474e-06 7.37417645067516e-05 -5.37512985034522e-06 1.22330547223686e-06 1.03851639132935e-05 -4.3489322338532e-06 5.56576044730066e-06 1.76596174019399e-06 1.19805941274184e-05 4.07213371654389e-06 -4.3489322338532e-06 0.000200327125499799 1.96316356772409e-05 -0.000178654232547022 1.4174057073666e-06 -5.62546161847474e-06 5.56576044730066e-06 1.96316356772409e-05 1.53098150936352e-05 -6.31337710415674e-05 -2.9964715037756e-06 7.37417645067516e-05 1.76596174019399e-06 -0.000178654232547022 -6.31337710415674e-05 0.000971942782954042 3103 3059 0 0 154 3103 3059 0 0 159 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3744 +1036 1149 0.254048913488064 -0.964034415369272 -0.0780819796058019 2.43802938986024 0.957874063648258 0.261959097086415 -0.117706030617138 0.288822846903377 0.133926949287686 -0.0448896139134332 0.989973986939655 0.825805127503465 5.50890303920693e-05 -2.17812124628433e-05 -6.04159959449311e-06 2.58523149160443e-06 -2.36081144772245e-05 -8.84680339230428e-06 -2.17812124628433e-05 8.13904778408968e-05 -8.33112475537773e-06 -1.62931998285781e-05 2.4686942461214e-05 -2.95204882594413e-05 -6.04159959449311e-06 -8.33112475537773e-06 1.54091261416879e-05 9.34033164304671e-06 4.27141401697702e-06 7.87574886741365e-06 2.58523149160443e-06 -1.62931998285781e-05 9.34033164304671e-06 2.369657746972e-05 -9.77400468480894e-06 2.43619817072389e-05 -2.36081144772245e-05 2.4686942461214e-05 4.27141401697702e-06 -9.77400468480894e-06 6.72467473205638e-05 -4.18265920590659e-06 -8.84680339230428e-06 -2.95204882594413e-05 7.87574886741365e-06 2.43619817072389e-05 -4.18265920590659e-06 0.000333463857171625 0 0 0 158 1874 0 0 0 147 1874 0 0 0 0 0 0 0 0 0 0 0 0 0 56 0 +1036 1040 0.989405337945336 0.143641110824025 -0.0210786272445788 0.539924021613647 -0.144116443400103 0.989291353221505 -0.0230882910339508 -0.104753023015827 0.017536475899696 0.0258814551832716 0.99951119167852 0.00520126303643538 3.50988740217375e-05 -3.83485934243136e-07 -4.12100152195471e-06 4.73083948394331e-06 -3.6712799436579e-06 1.84926596178777e-05 -3.83485934243136e-07 3.04135396861878e-05 3.88019054715971e-06 -4.87005340085369e-06 -1.2105826567821e-06 -4.06778175304487e-06 -4.12100152195471e-06 3.88019054715971e-06 1.12394181685552e-05 -3.51423304199493e-06 5.27494737562744e-06 -1.04691183396205e-06 4.73083948394331e-06 -4.87005340085369e-06 -3.51423304199493e-06 0.0001240535193625 1.81861232402384e-05 4.48396847706693e-05 -3.6712799436579e-06 -1.2105826567821e-06 5.27494737562744e-06 1.81861232402384e-05 1.57369922564748e-05 6.06238351058492e-06 1.84926596178777e-05 -4.06778175304487e-06 -1.04691183396205e-06 4.48396847706693e-05 6.06238351058492e-06 0.00022965821734021 3427 3373 0 737 95 3427 3373 0 737 105 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3804 +1037 1149 0.217570384762982 -0.974067843540886 -0.0620883552181578 2.3073141216103 0.967341862838235 0.223669499796555 -0.119254665575032 0.39264135145996 0.130049406283697 -0.0341143817233545 0.990920461432143 0.822273937332791 4.5319144974612e-05 -5.101057878132e-06 -1.26646589409699e-06 -1.40034529344547e-07 -8.29529682331269e-06 2.69722641484056e-06 -5.101057878132e-06 3.87234753016422e-05 -2.57191507613194e-06 -5.63927611722464e-06 8.81028907899786e-06 -2.28351983746167e-05 -1.26646589409699e-06 -2.57191507613194e-06 1.24015347409043e-05 5.05212582683402e-06 3.06070010928046e-06 3.8185557073654e-06 -1.40034529344547e-07 -5.63927611722464e-06 5.05212582683402e-06 2.91945846376768e-05 -2.68476470148968e-05 1.34736147493597e-05 -8.29529682331269e-06 8.81028907899786e-06 3.06070010928046e-06 -2.68476470148968e-05 0.000128699717346788 -3.02199743373419e-05 2.69722641484056e-06 -2.28351983746167e-05 3.8185557073654e-06 1.34736147493597e-05 -3.02199743373419e-05 0.000118111323792269 0 0 0 74 1786 0 0 0 71 1786 0 0 0 0 0 0 0 0 0 0 0 0 0 56 0 +1037 1040 0.994528869623282 0.103929819546574 -0.0105318609396799 0.397720001861521 -0.104152998851805 0.99428376205596 -0.0234936872802733 -0.0751833454129609 0.00802996363703275 0.0244620751544909 0.999668508338201 -0.0137102839437378 3.81597007497632e-05 -1.21697434159415e-05 -4.18134636124522e-06 1.14319486864726e-05 1.3466017752065e-06 8.85043271203728e-06 -1.21697434159415e-05 3.72444152281182e-05 2.95615818219673e-06 1.13980453450694e-06 1.44670365128665e-06 -2.26278728795083e-05 -4.18134636124522e-06 2.95615818219673e-06 1.06722389572597e-05 -2.77691747638125e-06 5.34959636294917e-06 -1.2842899546574e-06 1.14319486864726e-05 1.13980453450694e-06 -2.77691747638125e-06 0.000143753111737113 2.41451679018277e-05 -7.71897490787605e-06 1.3466017752065e-06 1.44670365128665e-06 5.34959636294917e-06 2.41451679018277e-05 1.73070350859175e-05 -6.4808557516787e-06 8.85043271203728e-06 -2.26278728795083e-05 -1.2842899546574e-06 -7.71897490787605e-06 -6.4808557516787e-06 0.000105585963694951 3367 3313 0 737 68 3367 3313 0 737 84 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3826 +1038 1042 0.994958167708511 0.0973528441946642 0.0240970586863343 0.50051517520094 -0.097135738546593 0.995220656093687 -0.0100246686458102 -0.115656829663376 -0.0249578205605204 0.00763344035542263 0.999659360873097 -0.00334761082844668 4.01572403160941e-05 -9.64003169769555e-06 -4.80279073838581e-06 -1.11816203702541e-06 -3.85489092244624e-07 2.83915345611635e-06 -9.64003169769555e-06 2.35656566780625e-05 4.11189216427334e-07 5.21602256966151e-08 -1.78587102724038e-07 -3.26370969118635e-06 -4.80279073838581e-06 4.11189216427334e-07 9.71241574539483e-06 -2.67948608427933e-06 6.27109467472483e-06 -3.81053335354047e-07 -1.11816203702541e-06 5.21602256966151e-08 -2.67948608427933e-06 0.000161860345314775 3.05872057816154e-05 -1.66590445357127e-05 -3.85489092244624e-07 -1.78587102724038e-07 6.27109467472483e-06 3.05872057816154e-05 1.76975258249806e-05 -3.54231150052046e-06 2.83915345611635e-06 -3.26370969118635e-06 -3.81053335354047e-07 -1.66590445357127e-05 -3.54231150052046e-06 0.000135112552945124 3443 3432 0 1367 190 3443 3432 0 1367 207 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3672 +1039 1150 0.201691040651295 -0.979099182862122 -0.0261823268584584 2.04051817477991 0.973522482594723 0.203335247924615 -0.104444975149804 0.561670696242986 0.107585779746236 -0.00442346811459027 0.994185964961402 0.64084248293931 7.26965632428531e-05 -1.34188275795252e-05 -9.05534905224305e-06 6.53434103736854e-07 -1.89615736832644e-05 1.60238076147975e-05 -1.34188275795252e-05 4.6273488963033e-05 -1.42474775617254e-06 1.41404680829211e-06 3.04376257725433e-06 3.50955752442852e-05 -9.05534905224305e-06 -1.42474775617254e-06 1.47119226425062e-05 8.40880578355826e-06 7.88162578031513e-06 1.80952654544983e-06 6.53434103736854e-07 1.41404680829211e-06 8.40880578355826e-06 2.69007833367989e-05 -1.35559848509231e-06 4.64663002573198e-05 -1.89615736832644e-05 3.04376257725433e-06 7.88162578031513e-06 -1.35559848509231e-06 4.38328680650528e-05 -2.67733083486397e-05 1.60238076147975e-05 3.50955752442852e-05 1.80952654544983e-06 4.64663002573198e-05 -2.67733083486397e-05 0.000364453919471037 4 103 0 125 2763 4 103 0 117 2763 0 0 0 0 0 0 0 0 38 0 0 0 0 1 0 +1039 1151 0.272858793229849 -0.961034506206619 -0.0442804340239546 2.0676159648306 0.956576051264883 0.275922374202647 -0.0939632990100841 0.533966113908042 0.102519935152314 -0.0167188903511427 0.994590439126474 0.513771547311157 4.33957668663238e-05 -6.37732857893155e-06 -2.40989228457339e-06 6.93979201704e-07 -6.54562346862668e-06 2.58101514827177e-05 -6.37732857893155e-06 4.13910121812559e-05 -2.44775354446126e-06 3.86808797700829e-06 -5.08821586175374e-06 2.19566888768259e-05 -2.40989228457339e-06 -2.44775354446126e-06 1.18887474028621e-05 6.65446941974123e-06 8.89102491464371e-06 -2.01746286716431e-07 6.93979201704e-07 3.86808797700829e-06 6.65446941974123e-06 3.63346552951896e-05 -3.29761068927979e-05 3.48133416545491e-05 -6.54562346862668e-06 -5.08821586175374e-06 8.89102491464371e-06 -3.29761068927979e-05 9.80219715993655e-05 -2.44081129281391e-05 2.58101514827177e-05 2.19566888768259e-05 -2.01746286716431e-07 3.48133416545491e-05 -2.44081129281391e-05 0.000283359715565272 377 460 0 315 2943 377 460 0 297 2943 0 0 0 0 0 0 0 0 79 0 0 0 0 0 0 +1039 1149 0.155341190086153 -0.98766755467983 -0.0195426737009658 2.02534963329734 0.982836370105191 0.156513573448865 -0.0976533200906057 0.590391416230442 0.0995077095559386 -0.00403766752366868 0.995028599076378 0.753593726712448 6.73593651001628e-05 -2.31717645646243e-05 -5.8857059252713e-07 3.93729933004954e-06 -8.05848130682741e-06 -6.66297292481334e-06 -2.31717645646243e-05 6.56911331647982e-05 -4.72931206944682e-06 1.24251573440629e-06 6.23688927074685e-06 9.95181451209995e-05 -5.8857059252713e-07 -4.72931206944682e-06 1.26788405389152e-05 6.57188025415744e-06 5.86847642063888e-06 -3.97393173784393e-06 3.93729933004954e-06 1.24251573440629e-06 6.57188025415744e-06 2.27392237347911e-05 -5.03483507507783e-06 2.71340748991421e-05 -8.05848130682741e-06 6.23688927074685e-06 5.86847642063888e-06 -5.03483507507783e-06 7.06495131973146e-05 3.98728903431216e-05 -6.66297292481334e-06 9.95181451209995e-05 -3.97393173784393e-06 2.71340748991421e-05 3.98728903431216e-05 0.000539129357403892 0 0 0 63 2290 0 0 0 59 2290 0 0 0 0 0 0 0 0 29 0 0 0 0 42 0 +1039 1042 0.997313943780991 0.0647717883366949 0.034198142868766 0.36747514615215 -0.0638673317270602 0.997595522272335 -0.02690981011181 -0.0776362122059527 -0.0358589107206533 0.0246533847139579 0.999052725907934 -0.00909938045123274 4.07234599388613e-05 -2.22622036041621e-05 1.73505608619046e-06 -2.33710719856643e-05 -3.12910629482139e-06 2.61622764447557e-05 -2.22622036041621e-05 6.19461665214033e-05 -2.06944354512904e-06 -2.19019524760112e-05 -6.34854987708383e-06 7.00436123191309e-05 1.73505608619046e-06 -2.06944354512904e-06 1.01020927178069e-05 -2.26726015653619e-06 5.69459834492343e-06 -4.6954769495107e-07 -2.33710719856643e-05 -2.19019524760112e-05 -2.26726015653619e-06 0.000265571390743786 5.23599782162572e-05 -0.000234405940497516 -3.12910629482139e-06 -6.34854987708383e-06 5.69459834492343e-06 5.23599782162572e-05 2.31091870081039e-05 -4.83347078532923e-05 2.61622764447557e-05 7.00436123191309e-05 -4.6954769495107e-07 -0.000234405940497516 -4.83347078532923e-05 0.000740030724001954 3354 3343 0 1071 148 3354 3343 0 886 178 0 0 0 0 0 0 0 0 164 0 0 0 0 0 3700 +1039 1043 0.999284106594666 0.0377698556210347 0.00217078641640611 0.504149523813238 -0.0376813311055437 0.998778690479275 -0.0319569199175879 -0.0960239720354026 -0.00337514346566856 0.0318522440476481 0.999486889836838 -0.0186068294520389 5.23866822878188e-05 -0.000134133054253333 2.2223280459987e-07 1.72158206223402e-05 2.30895439960197e-06 7.70778446014308e-05 -0.000134133054253333 0.000938423303536414 8.8031780317936e-06 -0.00010646129619455 -8.75061756391797e-06 -0.00036727685646001 2.2223280459987e-07 8.8031780317936e-06 9.84908896016239e-06 -5.45850318222253e-06 4.98884042017894e-06 -5.22595748832625e-06 1.72158206223402e-05 -0.00010646129619455 -5.45850318222253e-06 0.000127447694215602 1.53479303247349e-05 8.92250304969518e-05 2.30895439960197e-06 -8.75061756391797e-06 4.98884042017894e-06 1.53479303247349e-05 1.35991300036198e-05 1.66586514323491e-05 7.70778446014308e-05 -0.00036727685646001 -5.22595748832625e-06 8.92250304969518e-05 1.66586514323491e-05 0.000605421799912577 3331 3318 0 1404 374 3331 3318 0 1193 399 0 0 0 0 0 0 0 0 121 0 0 0 0 0 3471 +1040 1042 0.999522977236489 0.0270830263327033 -0.014843438313536 0.236389102384105 -0.0275471159109676 0.999107923551558 -0.0320080224550335 -0.0455860287135389 0.0139633227167951 0.0324016478154477 0.999377385594426 0.0262112097631662 5.59438312533398e-05 -7.52984428876597e-05 -6.76481074899099e-06 -1.13795578339161e-06 -4.72784828907363e-06 5.43964563706971e-05 -7.52984428876597e-05 0.000353625163850531 6.83534446663633e-06 5.90393475730259e-05 1.58365540171039e-05 -0.000156874727708729 -6.76481074899099e-06 6.83534446663633e-06 1.05429026388545e-05 -4.34696072113696e-06 6.80060153891987e-06 -4.40657906483051e-06 -1.13795578339161e-06 5.90393475730259e-05 -4.34696072113696e-06 0.000135572743684055 2.51296438239335e-05 -1.59103971949562e-05 -4.72784828907363e-06 1.58365540171039e-05 6.80060153891987e-06 2.51296438239335e-05 1.79749721245618e-05 -3.26032694671104e-06 5.43964563706971e-05 -0.000156874727708729 -4.40657906483051e-06 -1.59103971949562e-05 -3.26032694671104e-06 0.000298970656177862 3260 3249 0 530 111 3260 3249 0 401 143 0 0 0 0 0 0 0 0 770 0 0 0 0 0 3728 +1041 1044 0.994499674944645 -0.0724414605366633 -0.0756480755228516 0.393753038766056 0.0671152808004103 0.995235431284469 -0.0707246449202804 -0.0256014959970593 0.0804110416427873 0.0652584945530674 0.994623241871307 0.0637719831515026 2.8471443202469e-05 -1.73036784344489e-05 -1.32427130236043e-06 -9.85458381777045e-06 -3.25819479110944e-06 1.64474928361405e-05 -1.73036784344489e-05 2.88394094742207e-05 9.53678652833528e-07 2.27585846999724e-06 1.54555696477592e-06 1.12656939060561e-05 -1.32427130236043e-06 9.53678652833528e-07 9.71068873702721e-06 -5.7460268092791e-06 4.42628007909674e-06 -4.03871486791234e-06 -9.85458381777045e-06 2.27585846999724e-06 -5.7460268092791e-06 0.0001781012031647 2.54934246658078e-05 7.80661428875628e-05 -3.25819479110944e-06 1.54555696477592e-06 4.42628007909674e-06 2.54934246658078e-05 1.50770198848199e-05 2.40927219788258e-05 1.64474928361405e-05 1.12656939060561e-05 -4.03871486791234e-06 7.80661428875628e-05 2.40927219788258e-05 0.000313959800569872 3389 3372 0 504 567 3389 3372 0 386 612 0 0 0 0 0 0 0 0 1396 0 0 0 0 0 3240 +1042 1044 0.996264888752949 -0.077268678441893 -0.0385463716829078 0.27544150867403 0.0749812010894493 0.995518507467102 -0.0576256954288378 0.000388332455425109 0.0428262877361219 0.0545202037992976 0.997593833409382 0.0327549629737692 5.0598136602885e-05 -2.59388566800077e-05 6.84594667583561e-06 9.59175024254487e-06 4.33947703540074e-06 5.99745579245868e-05 -2.59388566800077e-05 7.39223176050162e-05 -3.93851528809315e-06 2.55914398344959e-05 6.86245989103377e-06 3.53926828951854e-05 6.84594667583561e-06 -3.93851528809315e-06 1.09763355286781e-05 -5.29937222886255e-06 4.10851523092889e-06 -6.09239446867036e-06 9.59175024254487e-06 2.55914398344959e-05 -5.29937222886255e-06 0.000228803984990147 3.62701812626837e-05 0.000212809988435351 4.33947703540074e-06 6.86245989103377e-06 4.10851523092889e-06 3.62701812626837e-05 2.10171961431137e-05 9.34614529838968e-05 5.99745579245868e-05 3.53926828951854e-05 -6.09239446867036e-06 0.000212809988435351 9.34614529838968e-05 0.00112057404266754 3196 3179 0 178 458 3196 3179 0 93 507 0 0 0 0 0 0 0 0 1929 0 0 0 0 0 3339 +1042 1045 0.989197118133404 -0.138488013625453 -0.0480638279649496 0.357582112296742 0.134542514761204 0.987879831544579 -0.0774063960482967 -0.000151311138768042 0.0582011443040358 0.0701035556126138 0.995840408043463 0.00792631874874555 2.77428073475755e-05 -1.91468058170296e-05 -1.42653820654479e-06 -2.7695579647984e-06 -1.63047589316489e-06 8.53207760129928e-06 -1.91468058170296e-05 2.90503727659007e-05 1.92128406122623e-06 1.98764739163506e-05 2.8128213206236e-06 -4.76718250182391e-06 -1.42653820654479e-06 1.92128406122623e-06 1.02740962732759e-05 -1.10759325061344e-06 5.43013445210309e-06 -2.74187950894276e-06 -2.7695579647984e-06 1.98764739163506e-05 -1.10759325061344e-06 0.000190645441570005 1.52287881381868e-05 3.1282737945337e-05 -1.63047589316489e-06 2.8128213206236e-06 5.43013445210309e-06 1.52287881381868e-05 1.22255389755421e-05 9.14333007369528e-06 8.53207760129928e-06 -4.76718250182391e-06 -2.74187950894276e-06 3.1282737945337e-05 9.14333007369528e-06 0.000134267644586669 3350 3315 0 179 731 3350 3315 0 59 780 0 0 0 0 0 0 0 0 2602 0 0 0 0 0 3026 +1044 1145 0.157042503901635 -0.984718067029116 0.0752859909594465 1.37896945103303 0.984777571279254 0.161890225849194 0.063282619097439 0.799368642612972 -0.0745036044338751 0.0642018943718804 0.995151912868293 0.856489276101852 0.000156434029520236 -9.048633956515e-05 -1.10973705391327e-05 4.09441492204972e-05 -3.22575480052661e-05 -6.60602535102413e-05 -9.048633956515e-05 8.88511620111064e-05 2.34983045426156e-07 -2.88393567230435e-05 2.24765316575538e-05 3.83113013082944e-05 -1.10973705391327e-05 2.34983045426156e-07 2.16963753757427e-05 7.45890359558102e-06 1.16662869697269e-05 4.94615514348046e-06 4.09441492204972e-05 -2.88393567230435e-05 7.45890359558102e-06 4.11443946807137e-05 -2.87690267861832e-06 -4.60748872261316e-05 -3.22575480052661e-05 2.24765316575538e-05 1.16662869697269e-05 -2.87690267861832e-06 5.4205602803539e-05 2.27297016999008e-05 -6.60602535102413e-05 3.83113013082944e-05 4.94615514348046e-06 -4.60748872261316e-05 2.27297016999008e-05 0.000315373317306961 0 0 0 0 1933 0 0 0 0 1933 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1044 1071 0.142074324361678 -0.989053430467765 -0.0398522024124017 1.3618347524781 0.989381216879079 0.143137856493075 -0.025226211079754 0.811133558362447 0.030654429435974 -0.0358450236227323 0.998887100846457 0.814842408035777 0.000130360013903291 -2.86570347628337e-05 -6.68966264989086e-06 2.30446826689181e-05 2.123510883577e-06 2.49425373302809e-05 -2.86570347628337e-05 7.12030015716758e-05 1.73559690477081e-06 9.87751059595522e-06 -3.7195789514994e-05 2.56669260310405e-05 -6.68966264989086e-06 1.73559690477081e-06 2.21711108059279e-05 4.638442587461e-06 7.92594606991406e-06 -1.5164118310333e-06 2.30446826689181e-05 9.87751059595522e-06 4.638442587461e-06 5.42629015007571e-05 -4.8523815039349e-05 4.83807505740905e-05 2.123510883577e-06 -3.7195789514994e-05 7.92594606991406e-06 -4.8523815039349e-05 0.000153170465813881 -9.71514658648291e-05 2.49425373302809e-05 2.56669260310405e-05 -1.5164118310333e-06 4.83807505740905e-05 -9.71514658648291e-05 0.00023653397391137 0 0 0 0 1625 0 0 0 0 1625 0 0 0 0 0 0 0 0 44 0 0 0 0 0 0 +1045 1146 0.219923352543371 -0.97477818588969 0.0379632364227537 1.28286372761838 0.973766821368762 0.221692646177271 0.0512888704525365 0.732075379421686 -0.0584114424360685 0.0256877197221712 0.997962045594928 0.854352646943361 0.000134527501012267 -5.54667791512068e-05 -3.31463379159303e-06 1.38300865800878e-05 -4.62267916137125e-06 4.66120406531827e-05 -5.54667791512068e-05 7.89277137020991e-05 -3.97196799885745e-06 -2.75001482102788e-06 -1.35075865505665e-06 2.32667040594405e-05 -3.31463379159303e-06 -3.97196799885745e-06 1.76872615925983e-05 9.90039702643836e-06 9.13481517295791e-06 -6.20613271176396e-07 1.38300865800878e-05 -2.75001482102788e-06 9.90039702643836e-06 2.78088126397105e-05 8.88284790462171e-06 2.5599294827859e-05 -4.62267916137125e-06 -1.35075865505665e-06 9.13481517295791e-06 8.88284790462171e-06 5.82442185913586e-05 -1.59966807563397e-05 4.66120406531827e-05 2.32667040594405e-05 -6.20613271176396e-07 2.5599294827859e-05 -1.59966807563397e-05 0.000304054101740508 0 0 0 0 1803 0 0 0 0 1803 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1046 1048 0.997703650868277 -0.0676110862984835 -0.00402070312890773 0.19032442439522 0.0675443804625482 0.997605080595698 -0.0148949601403044 -0.0060606146602782 0.00501813830442396 0.0145891802096533 0.9998809799715 -0.00272397520612251 3.77947611352999e-05 -8.67587723047672e-06 3.81719336285666e-06 -1.41341690774809e-05 3.06323427043675e-06 6.7757457717668e-06 -8.67587723047672e-06 2.29198359080035e-05 -1.6335422164628e-06 5.21642265407903e-06 -3.36921344728782e-07 -8.61333885176881e-06 3.81719336285666e-06 -1.6335422164628e-06 1.02928309924914e-05 -9.80065161798483e-07 4.25907853780351e-06 -9.76202937621428e-07 -1.41341690774809e-05 5.21642265407903e-06 -9.80065161798483e-07 0.000173989421242161 -5.14310057871907e-07 3.58664152839453e-06 3.06323427043675e-06 -3.36921344728782e-07 4.25907853780351e-06 -5.14310057871907e-07 1.04352189576913e-05 5.73285667651696e-06 6.7757457717668e-06 -8.61333885176881e-06 -9.76202937621428e-07 3.58664152839453e-06 5.73285667651696e-06 7.01407629435518e-05 3742 3692 0 84 325 3742 3692 0 4 359 0 0 0 0 0 0 0 0 3627 0 0 0 0 0 3464 +1047 1050 0.985700004254581 -0.168117205671151 -0.0114937709148194 0.314210032893183 0.168152012825908 0.985758785842447 0.0021252569305527 0.0256480990875045 0.0109727934052458 -0.00402756647977463 0.999931685923162 0.0251329603176798 3.79487715296298e-05 -1.00464109668976e-06 4.04385695346953e-06 -1.01542493558441e-05 3.39738454823147e-06 7.79894248564497e-06 -1.00464109668976e-06 2.50951929154946e-05 -3.4385880190919e-06 -5.20138579190083e-06 -3.26928393450302e-07 -5.92260509116425e-06 4.04385695346953e-06 -3.4385880190919e-06 1.14002638752984e-05 4.48023834830001e-06 4.33592355359776e-06 1.72995732282437e-06 -1.01542493558441e-05 -5.20138579190083e-06 4.48023834830001e-06 0.000144436321473957 -1.4090306593917e-05 9.81384357216913e-06 3.39738454823147e-06 -3.26928393450302e-07 4.33592355359776e-06 -1.4090306593917e-05 1.28361261214477e-05 5.18254757648692e-06 7.79894248564497e-06 -5.92260509116425e-06 1.72995732282437e-06 9.81384357216913e-06 5.18254757648692e-06 0.000110010389858854 3656 3569 0 18 772 3633 3569 0 0 820 0 0 0 0 0 0 0 0 3663 0 0 0 0 0 3011 +1047 1146 0.284096407855281 -0.958766021200931 -0.00754636563264558 1.05132377209257 0.958021410185566 0.283541931420478 0.0424140395671562 0.656957517824979 -0.0385254288721757 -0.0192792561288239 0.999071619861826 0.863522895766154 0.000101125446224633 -3.86854911167223e-05 -2.86192748916466e-06 1.42996318237688e-05 -1.21997911144744e-05 4.20165245945326e-05 -3.86854911167223e-05 9.05125333188738e-05 -5.36970866026635e-06 -5.42836195710247e-06 -8.81552106182576e-06 -3.99780084129695e-05 -2.86192748916466e-06 -5.36970866026635e-06 1.6166607123066e-05 1.11566025373653e-05 3.82191056324022e-06 5.88212856263612e-06 1.42996318237688e-05 -5.42836195710247e-06 1.11566025373653e-05 3.34882842903066e-05 -1.69787215816586e-05 4.8544418578939e-05 -1.21997911144744e-05 -8.81552106182576e-06 3.82191056324022e-06 -1.69787215816586e-05 8.15810915260736e-05 -8.6658460205236e-05 4.20165245945326e-05 -3.99780084129695e-05 5.88212856263612e-06 4.8544418578939e-05 -8.6658460205236e-05 0.000573294958962856 0 0 0 0 1510 0 0 0 0 1510 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1048 1051 0.97421119986752 -0.225608940709322 0.00362545510321766 0.312275934346029 0.225474078150164 0.973989962293437 0.0224720589613559 0.0389547036832889 -0.00860105429710847 -0.0210750853769634 0.999740897753679 0.0647012739410915 3.39471762988332e-05 7.88885423673054e-06 8.18817250649054e-06 4.48823035051553e-06 8.38731361996804e-08 -1.3914063766854e-05 7.88885423673054e-06 5.04133634302709e-05 4.37172899773304e-07 1.44694190195202e-05 -2.90659270981088e-06 8.70129734103982e-08 8.18817250649054e-06 4.37172899773304e-07 1.20274764407825e-05 3.71638498691789e-06 4.47239648794722e-06 -3.44946102328822e-06 4.48823035051553e-06 1.44694190195202e-05 3.71638498691789e-06 8.96956683785578e-05 -9.15386550292132e-06 4.24111579722965e-05 8.38731361996804e-08 -2.90659270981088e-06 4.47239648794722e-06 -9.15386550292132e-06 1.29881290209836e-05 -4.33990158649672e-06 -1.3914063766854e-05 8.70129734103982e-08 -3.44946102328822e-06 4.24111579722965e-05 -4.33990158649672e-06 0.000150402883008964 3250 3187 0 0 921 3134 3132 0 0 961 0 0 0 0 0 2 0 0 3513 0 0 0 0 0 2831 +1049 1145 0.376554375604469 -0.925671928010143 0.036582562883323 0.893452079167334 0.922912305922498 0.378267035533382 0.0717420755596309 0.570517837875329 -0.0802476030168211 0.00674770500027702 0.996752120984593 0.832917068817239 0.000119790814941536 4.20504803567997e-06 -3.45679875284814e-06 2.90731945758463e-06 3.02505367396902e-05 -1.8289204068557e-05 4.20504803567997e-06 8.97099255857625e-05 2.4666163102848e-07 3.45639648484758e-06 -6.95064173863933e-06 -7.23948404279809e-05 -3.45679875284814e-06 2.4666163102848e-07 1.39447233946273e-05 6.53540183570093e-06 7.16615160853257e-06 1.69937522602845e-06 2.90731945758463e-06 3.45639648484758e-06 6.53540183570093e-06 3.8280077498974e-05 -2.3979730195221e-05 -9.18364074618253e-06 3.02505367396902e-05 -6.95064173863933e-06 7.16615160853257e-06 -2.3979730195221e-05 0.000138167461811174 4.83790569161159e-06 -1.8289204068557e-05 -7.23948404279809e-05 1.69937522602845e-06 -9.18364074618253e-06 4.83790569161159e-06 0.000121148064159031 0 0 0 0 1675 0 0 0 0 1675 0 0 0 0 0 0 0 0 8 0 0 0 0 0 0 +1049 1052 0.961124522739692 -0.276060898133276 -0.00548017428987959 0.271969143186444 0.276107435298538 0.961057552550072 0.0115353742605192 0.0504840891829824 0.00208229711191711 -0.0126000479489329 0.999918448089854 0.0698898584132116 3.24081961373246e-05 3.66336402031375e-06 7.46443705755744e-06 -1.11221042189765e-05 4.04805312009472e-06 1.43642657449453e-06 3.66336402031375e-06 2.9947195976735e-05 -8.7127115902212e-07 3.39917228158134e-06 -2.44214483321182e-06 -1.42701681368245e-05 7.46443705755744e-06 -8.7127115902212e-07 1.18358443413393e-05 3.10097742782568e-07 4.53553366709777e-06 1.23264538174681e-06 -1.11221042189765e-05 3.39917228158134e-06 3.10097742782568e-07 9.77144577442356e-05 -1.8936369107355e-05 1.85329597891069e-05 4.04805312009472e-06 -2.44214483321182e-06 4.53553366709777e-06 -1.8936369107355e-05 1.85674843699399e-05 -1.59048513002172e-06 1.43642657449453e-06 -1.42701681368245e-05 1.23264538174681e-06 1.85329597891069e-05 -1.59048513002172e-06 9.52413445555291e-05 3355 3337 0 0 1002 3233 3215 0 0 1026 0 0 0 0 0 181 43 0 2800 0 0 0 0 0 2756 +1052 1153 0.807934680162369 -0.589140387686367 -0.0124561706670737 0.839547643931487 0.589043430053488 0.806852001261232 0.0449186550507196 0.029228207466227 -0.0164131076201513 -0.0436285646967917 0.998912988323181 0.179922645667314 4.78758330594716e-05 2.70808875161794e-05 -3.95546114894677e-06 1.7468238808585e-06 -9.43751746609123e-07 -4.77913375867191e-06 2.70808875161794e-05 3.68868282721042e-05 -3.53803804677688e-06 2.33884452108672e-06 -2.15334401639241e-06 -3.38623557838736e-07 -3.95546114894677e-06 -3.53803804677688e-06 1.26556733662035e-05 4.13820365335931e-06 4.57209493108821e-06 2.71939956580554e-06 1.7468238808585e-06 2.33884452108672e-06 4.13820365335931e-06 2.42160700404301e-05 -1.0138994125986e-05 2.02991448287868e-05 -9.43751746609123e-07 -2.15334401639241e-06 4.57209493108821e-06 -1.0138994125986e-05 3.72914401024451e-05 -2.71863141702668e-05 -4.77913375867191e-06 -3.38623557838736e-07 2.71939956580554e-06 2.02991448287868e-05 -2.71863141702668e-05 0.000178194740658493 1089 1084 0 0 1491 1089 1084 0 0 1458 0 0 0 0 0 0 0 0 1069 0 0 0 0 0 1580 +1052 1104 0.611860731171251 -0.787898993949643 0.0695817575498309 0.729953598401442 0.785319001649512 0.615630307272984 0.0653711741915757 0.323895766958022 -0.094342521159846 0.0146458219336709 0.995432061268418 0.811227113897359 8.93583363727434e-05 2.53655300329658e-05 -3.6057920492819e-06 7.55813158427083e-06 -1.73339584240878e-06 8.91920057323154e-05 2.53655300329658e-05 5.94620715293808e-05 -2.35948227668439e-07 -7.79621038452681e-06 -1.06570275891897e-06 4.35009029344644e-05 -3.6057920492819e-06 -2.35948227668439e-07 2.2578091251656e-05 8.97293337230918e-06 5.20022395172143e-06 -9.63207368546696e-06 7.55813158427083e-06 -7.79621038452681e-06 8.97293337230918e-06 2.98725641026878e-05 1.04788028545166e-05 1.6264631351105e-05 -1.73339584240878e-06 -1.06570275891897e-06 5.20022395172143e-06 1.04788028545166e-05 4.68627885336075e-05 -1.36037066807603e-05 8.91920057323154e-05 4.35009029344644e-05 -9.63207368546696e-06 1.6264631351105e-05 -1.36037066807603e-05 0.00117032198676238 0 0 0 0 1230 0 0 0 0 1211 0 0 0 0 0 0 0 0 32 0 0 0 0 0 463 +1052 1103 0.613216937208918 -0.787288150920691 0.0643611322149727 0.720534591905762 0.785133653861665 0.61642980409517 0.05982843970071 0.319835630644434 -0.086776341787061 0.0138442783513575 0.99613161904589 0.768952182485965 9.37057249700791e-05 4.67212382374544e-05 -6.4075137367327e-06 9.78668660158948e-06 9.74382500420133e-06 -4.03622291087909e-06 4.67212382374544e-05 7.75399803994284e-05 -4.39950616433337e-07 2.75552202690538e-06 6.75839077748824e-06 -8.91706483356061e-05 -6.4075137367327e-06 -4.39950616433337e-07 2.01673667391381e-05 6.67826713874249e-06 7.39576424834215e-06 -3.61068445562782e-06 9.78668660158948e-06 2.75552202690538e-06 6.67826713874249e-06 2.88579980167382e-05 1.10014012433581e-06 1.47250450259739e-05 9.74382500420133e-06 6.75839077748824e-06 7.39576424834215e-06 1.10014012433581e-06 8.62987093758913e-05 -1.29159897195711e-05 -4.03622291087909e-06 -8.91706483356061e-05 -3.61068445562782e-06 1.47250450259739e-05 -1.29159897195711e-05 0.000253320380958881 0 0 0 0 1261 0 0 0 0 1243 0 0 0 0 0 0 0 0 29 0 0 0 0 0 485 +1053 1057 0.981602921001662 -0.190855153222096 -0.0054786831971407 0.311189844257875 0.190905176191099 0.980555180312963 0.0454615449018057 0.0727182916068809 -0.00330441892769742 -0.0456710942499061 0.998951065851359 0.19753321968591 4.76294282102965e-05 1.97441142956309e-05 -3.35619503147945e-08 1.35209150680762e-05 -6.44514589409841e-06 1.08888126895482e-05 1.97441142956309e-05 6.09456666024793e-05 -2.98094824067629e-06 1.51728625724549e-05 -1.26699156541386e-05 2.37641763743815e-05 -3.35619503147945e-08 -2.98094824067629e-06 1.22560815522859e-05 1.76060434972793e-06 5.41209392618592e-06 7.26847310894903e-09 1.35209150680762e-05 1.51728625724549e-05 1.76060434972793e-06 5.67626104384283e-05 -2.11517378003026e-05 9.88850641436554e-05 -6.44514589409841e-06 -1.26699156541386e-05 5.41209392618592e-06 -2.11517378003026e-05 2.94187987764274e-05 -6.00168662658147e-05 1.08888126895482e-05 2.37641763743815e-05 7.26847310894903e-09 9.88850641436554e-05 -6.00168662658147e-05 0.000474279535334273 2032 2002 0 0 573 2032 2002 0 0 540 0 0 0 0 0 0 0 0 1241 0 0 0 0 0 2873 +1053 1153 0.852511690900131 -0.521831159973532 -0.0302664394879646 0.729925521198417 0.52267011978868 0.850320896542254 0.0614029216215751 -0.030642462791882 -0.00630577185500246 -0.0681660720905685 0.997654060211783 0.140574567433853 6.32456682061312e-05 4.55154007813135e-05 -5.28252845590786e-06 8.71814301998342e-06 -7.10039678014004e-06 9.12938383155833e-06 4.55154007813135e-05 5.69242104366156e-05 -4.65551303155501e-06 9.79559363257517e-06 -7.81300449287483e-06 3.53727715652289e-05 -5.28252845590786e-06 -4.65551303155501e-06 1.3036203288642e-05 5.84445928627781e-06 4.8675855167641e-06 -7.03461484502426e-06 8.71814301998342e-06 9.79559363257517e-06 5.84445928627781e-06 4.24222229154333e-05 -3.47060135854309e-05 4.73965819411823e-05 -7.10039678014004e-06 -7.81300449287483e-06 4.8675855167641e-06 -3.47060135854309e-05 7.22956903754257e-05 -5.21140082271418e-05 9.12938383155833e-06 3.53727715652289e-05 -7.03461484502426e-06 4.73965819411823e-05 -5.21140082271418e-05 0.000445466811932698 1089 1084 0 0 985 1089 1084 0 0 945 0 0 0 0 0 0 0 0 1114 0 0 0 0 0 1956 +1053 1156 0.917680081374039 -0.397248011739959 -0.00756871309973716 0.87389865665592 0.396777577728575 0.915265568276898 0.0696885452467754 -0.230056741259478 -0.020756253543976 -0.0669548855231355 0.997540085030873 -0.0312225015419723 4.84715901106642e-05 2.65102341209685e-05 2.45957638991739e-06 -1.59273663022605e-06 1.9667794446082e-06 -2.99822325066024e-05 2.65102341209685e-05 4.9662974253253e-05 2.7571003729744e-06 2.31577217257503e-07 2.04116744707254e-07 -4.70276361215397e-06 2.45957638991739e-06 2.7571003729744e-06 1.30629476577669e-05 5.48385934426063e-06 4.42308153606767e-06 1.8702270251758e-06 -1.59273663022605e-06 2.31577217257503e-07 5.48385934426063e-06 3.06772396188001e-05 -1.3594923467211e-05 1.81022925967468e-05 1.9667794446082e-06 2.04116744707254e-07 4.42308153606767e-06 -1.3594923467211e-05 3.66240578150008e-05 -2.31531472037064e-05 -2.99822325066024e-05 -4.70276361215397e-06 1.8702270251758e-06 1.81022925967468e-05 -2.31531472037064e-05 0.000174532350484514 1790 1779 0 128 1016 1790 1779 0 17 966 0 0 0 0 0 0 0 0 1222 0 0 0 0 0 2403 +1053 1103 0.676225799433514 -0.735152637441526 0.0476368328425967 0.635714370594834 0.732691626954961 0.677875607750187 0.0603956969279004 0.269323206165841 -0.0766919029011344 -0.00593801987899001 0.997037156754611 0.756263442519984 9.50184702113475e-05 5.08377046844626e-05 -3.92549097510338e-06 1.24282918532206e-05 -3.49501467904002e-06 -3.69246861841365e-05 5.08377046844626e-05 8.43216671488027e-05 -3.76449460079958e-07 3.57640610670446e-06 4.76991604793922e-07 -6.30236573248849e-05 -3.92549097510338e-06 -3.76449460079958e-07 1.59606655790226e-05 6.53640737861851e-06 8.33933887631151e-06 1.19771643502994e-06 1.24282918532206e-05 3.57640610670446e-06 6.53640737861851e-06 3.36508417471804e-05 -1.31572716316282e-05 6.66965495379959e-06 -3.49501467904002e-06 4.76991604793922e-07 8.33933887631151e-06 -1.31572716316282e-05 8.40114474495687e-05 -2.33115924672289e-05 -3.69246861841365e-05 -6.30236573248849e-05 1.19771643502994e-06 6.66965495379959e-06 -2.33115924672289e-05 0.000148495244313077 0 0 0 0 973 0 0 0 0 946 0 0 0 0 0 0 0 0 52 0 0 0 0 0 730 +1054 1056 0.996398533148709 -0.0841416728853576 -0.0104948569858645 0.141346888059429 0.0844521608202461 0.995852087329648 0.0338593073463511 0.0334793674019475 0.00760234647273787 -0.0346236775232913 0.99937150513854 0.0659775475092093 3.47630107511867e-05 2.57190364496365e-05 2.08363995868682e-06 -2.53430255222234e-07 -3.26355523263964e-07 1.0083664084526e-05 2.57190364496365e-05 4.13374757772729e-05 3.95432322595081e-07 3.34992235890762e-07 8.08898129638716e-07 4.87551930002409e-05 2.08363995868682e-06 3.95432322595081e-07 1.14442137348354e-05 9.55432982680054e-07 2.65820851852862e-06 8.5513923305308e-08 -2.53430255222234e-07 3.34992235890762e-07 9.55432982680054e-07 7.8846463582948e-05 -3.42973243856554e-05 -1.12708899613135e-05 -3.26355523263964e-07 8.08898129638716e-07 2.65820851852862e-06 -3.42973243856554e-05 3.79668138158266e-05 1.25405085450156e-05 1.0083664084526e-05 4.87551930002409e-05 8.5513923305308e-08 -1.12708899613135e-05 1.25405085450156e-05 0.000322749032174165 2633 2583 0 0 331 2633 2583 0 0 298 0 0 0 0 0 0 0 0 1424 0 0 0 0 0 3589 +1054 1057 0.990473652422646 -0.136125742030056 -0.0207780223628359 0.194328232788627 0.137111403312073 0.988895504434701 0.0573249020115377 0.0681247060703642 0.0127438980825314 -0.059627708874356 0.998139333658411 0.127678900399605 5.08249941843841e-05 3.24870224916223e-05 1.61543540921512e-06 2.72684773535976e-06 -4.23280362674848e-06 1.6826044746033e-05 3.24870224916223e-05 5.48113842814128e-05 -4.66887772836368e-07 -1.5717431590772e-05 1.06519632279229e-05 5.51996434430931e-05 1.61543540921512e-06 -4.66887772836368e-07 1.16519582670845e-05 3.92844534686146e-06 -4.46423028317033e-07 -2.41525166461431e-06 2.72684773535976e-06 -1.5717431590772e-05 3.92844534686146e-06 8.52459050070834e-05 -4.94132080648044e-05 -4.83201226655714e-05 -4.23280362674848e-06 1.06519632279229e-05 -4.46423028317033e-07 -4.94132080648044e-05 5.54629008497034e-05 4.23223611090723e-05 1.6826044746033e-05 5.51996434430931e-05 -2.41525166461431e-06 -4.83201226655714e-05 4.23223611090723e-05 0.000366775828200137 1978 1950 0 0 339 1978 1950 0 0 309 0 0 0 0 0 0 0 0 1263 0 0 0 0 0 3007 +1054 1058 0.979667279648243 -0.200020487869245 -0.0156149165594994 0.26566041976751 0.200572513569341 0.978268100958184 0.0525565357319576 0.0857367882716855 0.00476319085145846 -0.0546198414517769 0.998495861249658 0.157496768610917 4.28142197246648e-05 2.51337060386218e-05 4.30363059951199e-06 2.77938586184962e-06 -2.54329726685699e-06 -1.57534408825662e-05 2.51337060386218e-05 4.75961907721681e-05 4.05943283438574e-06 -7.47208248701555e-07 9.57680275217493e-07 7.87291349656282e-06 4.30363059951199e-06 4.05943283438574e-06 1.18519075440923e-05 4.18343438245319e-06 3.67216744347633e-06 -4.16259455505299e-06 2.77938586184962e-06 -7.47208248701555e-07 4.18343438245319e-06 1.81680440430005e-05 2.53456723326336e-06 -5.72080564856061e-06 -2.54329726685699e-06 9.57680275217493e-07 3.67216744347633e-06 2.53456723326336e-06 1.42770261857953e-05 5.06194692490145e-06 -1.57534408825662e-05 7.87291349656282e-06 -4.16259455505299e-06 -5.72080564856061e-06 5.06194692490145e-06 0.000217157643579189 1676 1670 0 0 394 1676 1670 0 0 360 0 0 0 0 0 0 0 0 1142 0 0 0 0 0 2830 +1054 1151 0.799708059345006 -0.597743201972385 -0.0563035017955794 0.611040660626619 0.599872779897125 0.799387389753413 0.0336518802107776 0.0355597075288611 0.0248931267047635 -0.0606866179567286 0.997846414356355 0.313644107975214 9.65545971027618e-05 7.25307772757488e-05 -8.86632801498601e-07 -1.26173491090971e-05 3.39046400229291e-05 4.46164800283457e-05 7.25307772757488e-05 8.24214643061758e-05 -5.0258307321424e-07 -8.04788429865461e-06 2.55969396192761e-05 2.30637919712415e-05 -8.86632801498601e-07 -5.0258307321424e-07 1.38798848185727e-05 5.04638868974957e-06 6.91684524452959e-06 1.87079044147051e-06 -1.26173491090971e-05 -8.04788429865461e-06 5.04638868974957e-06 2.8395317017417e-05 -2.82455475303841e-05 -2.35607143618503e-05 3.39046400229291e-05 2.55969396192761e-05 6.91684524452959e-06 -2.82455475303841e-05 0.00010893802075503 0.000123064218137439 4.46164800283457e-05 2.30637919712415e-05 1.87079044147051e-06 -2.35607143618503e-05 0.000123064218137439 0.000572773226026455 271 334 0 0 1185 271 334 0 0 1144 0 0 0 0 0 0 0 0 684 0 0 0 0 0 1571 +1054 1156 0.937871235694594 -0.346933048272438 0.00591652542372029 0.792403475237135 0.345620222613817 0.93556061538254 0.0726154023979635 -0.288542610068318 -0.0307279510717974 -0.0660590263433917 0.997342467792028 -0.0296159841360886 2.35734400863904e-05 1.22926842627776e-05 1.63472044109799e-06 -1.38528728262644e-06 3.22610094764358e-06 -2.01176073044026e-05 1.22926842627776e-05 2.67933039953794e-05 2.00775583164775e-06 -2.16692670183572e-06 4.85229603049358e-07 1.06220433312581e-05 1.63472044109799e-06 2.00775583164775e-06 1.12981233364405e-05 4.67878116215997e-06 3.77356549204534e-06 -4.28180675221234e-07 -1.38528728262644e-06 -2.16692670183572e-06 4.67878116215997e-06 2.73932074578896e-05 -9.30495493007518e-06 2.76825015073618e-06 3.22610094764358e-06 4.85229603049358e-07 3.77356549204534e-06 -9.30495493007518e-06 3.15683522910809e-05 -7.52405212053367e-06 -2.01176073044026e-05 1.06220433312581e-05 -4.28180675221234e-07 2.76825015073618e-06 -7.52405212053367e-06 0.00014243833967659 1853 1831 0 248 816 1853 1831 0 228 765 0 0 0 0 0 0 0 0 1100 0 0 0 0 0 2692 +1054 1155 0.921999384334062 -0.387178985009631 -0.00309335651403636 0.754995694114458 0.385825599786733 0.91804745321758 0.0912550282993983 -0.225581277961943 -0.0324921811643811 -0.0853305760418149 0.995822750772221 -0.0141737838276646 3.42576392494549e-05 1.81067576002157e-05 -3.99979149907657e-07 -2.7190611735229e-06 5.74163949703278e-06 -2.09027207786694e-05 1.81067576002157e-05 3.84053373966358e-05 -3.71466015980301e-07 5.17382865364186e-07 -9.20454838302036e-07 5.15193201695386e-06 -3.99979149907657e-07 -3.71466015980301e-07 1.21924535165575e-05 5.59683081648045e-06 5.25158257721831e-06 1.4680628840904e-06 -2.7190611735229e-06 5.17382865364186e-07 5.59683081648045e-06 1.59922422019264e-05 2.6150614192559e-06 3.79228198618036e-06 5.74163949703278e-06 -9.20454838302036e-07 5.25158257721831e-06 2.6150614192559e-06 1.92720415279664e-05 -6.56279202598156e-06 -2.09027207786694e-05 5.15193201695386e-06 1.4680628840904e-06 3.79228198618036e-06 -6.56279202598156e-06 0.000128647530838425 1616 1588 0 34 794 1616 1588 0 34 737 0 0 0 0 0 0 0 0 1158 0 0 0 0 0 2557 +1054 1158 0.974248740354885 -0.224215587352632 -0.0238067701512364 0.874622203782452 0.225258959732388 0.972501563091724 0.0591532826175926 -0.425542714711766 0.00988903317830299 -0.0629926993569017 0.997964992798109 -0.116459565360824 3.4528635837297e-05 2.56620002764465e-05 6.53936815198378e-07 -3.50448975200685e-06 3.33319142821852e-06 -2.81570498676164e-05 2.56620002764465e-05 3.68321360452942e-05 -1.26240150916167e-07 1.09865625526745e-06 -1.1161799946749e-07 -2.11300251864579e-05 6.53936815198378e-07 -1.26240150916167e-07 1.07019857862493e-05 5.03913254395905e-06 4.81863475260514e-06 -1.20884555954914e-07 -3.50448975200685e-06 1.09865625526745e-06 5.03913254395905e-06 4.74102577476327e-05 -2.35288235680817e-05 -1.10613347810245e-05 3.33319142821852e-06 -1.1161799946749e-07 4.81863475260514e-06 -2.35288235680817e-05 3.654305501018e-05 9.83747335831136e-06 -2.81570498676164e-05 -2.11300251864579e-05 -1.20884555954914e-07 -1.10613347810245e-05 9.83747335831136e-06 0.000108394629894226 2376 2358 0 726 619 2376 2358 0 718 561 0 0 0 0 0 0 0 0 861 0 0 0 0 0 3038 +1054 1103 0.715698636077974 -0.696332401028046 0.0538205313485851 0.572385776785596 0.693079219002214 0.717627039731912 0.0682101754351512 0.233578539304098 -0.0861200238237868 -0.0115160376922155 0.996218210219258 0.728322168435028 0.00011402187702696 4.59058584399067e-05 -3.11652565896328e-06 7.37635825316499e-06 1.78773997991432e-05 -3.44894578359099e-05 4.59058584399067e-05 7.54864522446902e-05 -1.60077759982731e-06 -1.06106454873506e-06 3.32827863256485e-06 -7.34453008064091e-05 -3.11652565896328e-06 -1.60077759982731e-06 1.42409634755653e-05 9.21623288788407e-06 3.26134192304253e-06 -6.18198564835266e-07 7.37635825316499e-06 -1.06106454873506e-06 9.21623288788407e-06 2.46310407339513e-05 -1.00492380523979e-05 4.07955403484979e-06 1.78773997991432e-05 3.32827863256485e-06 3.26134192304253e-06 -1.00492380523979e-05 8.11139881960378e-05 -3.91219622910945e-06 -3.44894578359099e-05 -7.34453008064091e-05 -6.18198564835266e-07 4.07955403484979e-06 -3.91219622910945e-06 0.000122532577421092 0 0 0 0 799 0 0 0 0 770 0 0 0 0 0 0 0 0 70 0 0 0 0 0 845 +1054 1153 0.879881954149286 -0.474562790888464 -0.024452081027704 0.664388450556157 0.475158998866918 0.878045235178068 0.0571007073238084 -0.0862752572892473 -0.00562783779272833 -0.0618605082847156 0.998068937978001 0.142033197896697 2.23201198920062e-05 1.64022809950591e-05 5.0350213771197e-09 -2.16368286450334e-06 4.55206468539352e-06 5.89613013655246e-06 1.64022809950591e-05 2.16757860648996e-05 -6.32376963579218e-07 3.24425047691512e-07 9.58502023129578e-08 9.62702615813969e-06 5.0350213771197e-09 -6.32376963579218e-07 1.22167928971615e-05 3.28274904452797e-06 4.07987207225142e-06 -6.18328085362477e-06 -2.16368286450334e-06 3.24425047691512e-07 3.28274904452797e-06 2.27726538652041e-05 -9.27861632560903e-06 1.49679439508875e-05 4.55206468539352e-06 9.58502023129578e-08 4.07987207225142e-06 -9.27861632560903e-06 3.40422106496178e-05 -1.3192113307404e-05 5.89613013655246e-06 9.62702615813969e-06 -6.18328085362477e-06 1.49679439508875e-05 -1.3192113307404e-05 0.000171033419817739 1086 1081 0 0 1088 1086 1081 0 0 1042 0 0 0 0 0 0 0 0 1049 0 0 0 0 0 2103 +1054 1157 0.955433351699679 -0.294572586169235 0.0193417149572321 0.829286339542849 0.293023105129658 0.95428244933416 0.0590124288008081 -0.355098140036728 -0.0358409028916926 -0.0507148732657938 0.998069852920898 -0.0959324208451687 3.50375230887856e-05 1.04937294587938e-05 -1.60382476327654e-06 4.73060901676358e-06 -1.57604540889803e-06 -1.08906008760802e-05 1.04937294587938e-05 2.57581110783731e-05 2.83620378173579e-07 -1.01409502199925e-07 1.47282765682412e-06 -1.06777708032755e-05 -1.60382476327654e-06 2.83620378173579e-07 1.23460726374129e-05 3.84087261664106e-06 4.67692637520028e-06 4.51722168026874e-07 4.73060901676358e-06 -1.01409502199925e-07 3.84087261664106e-06 2.83124840133593e-05 -8.78079292250942e-06 1.03227392549121e-05 -1.57604540889803e-06 1.47282765682412e-06 4.67692637520028e-06 -8.78079292250942e-06 2.75733981427932e-05 -1.26160281843489e-05 -1.08906008760802e-05 -1.06777708032755e-05 4.51722168026874e-07 1.03227392549121e-05 -1.26160281843489e-05 0.000102240500508378 2132 2109 0 466 656 2132 2109 0 451 591 0 0 0 0 0 0 0 0 1058 0 0 0 0 0 2847 +1055 1153 0.899929547680464 -0.435752201317017 -0.0157107688866411 0.608143743536617 0.436020583667073 0.899018457486906 0.0406431263129365 -0.142231793289057 -0.00358606054886627 -0.0434261688989327 0.999050202955037 0.0785778324728965 2.96509681705141e-05 2.12291805675328e-05 -2.51782368993607e-06 -2.36635824439311e-06 3.68441615537803e-06 -4.31052785534721e-07 2.12291805675328e-05 3.68422227809585e-05 -2.82209691733594e-06 2.88518284374096e-06 -4.22803698349433e-06 4.68457323705002e-05 -2.51782368993607e-06 -2.82209691733594e-06 1.18008222888844e-05 3.87849081817964e-06 2.00839877496716e-06 9.77998781939083e-07 -2.36635824439311e-06 2.88518284374096e-06 3.87849081817964e-06 3.28377717202585e-05 -2.10714421453552e-05 2.75141017921569e-05 3.68441615537803e-06 -4.22803698349433e-06 2.00839877496716e-06 -2.10714421453552e-05 5.03727819235488e-05 -2.16024075680165e-05 -4.31052785534721e-07 4.68457323705002e-05 9.77998781939083e-07 2.75141017921569e-05 -2.16024075680165e-05 0.000331558632333603 1089 1084 0 0 804 1089 1084 0 0 756 0 0 0 0 0 0 0 0 900 0 0 0 0 0 2258 +1055 1058 0.987449664906699 -0.157472763793089 -0.0120618381274761 0.201943336973033 0.157819258176976 0.986761280299801 0.037353145109426 0.0577218496267307 0.00602005183669164 -0.0387879409670431 0.999229330339848 0.124460980187256 2.22602261768487e-05 1.40431677387375e-05 2.51416314634174e-06 -1.69349553538189e-06 1.93729957975307e-06 1.63476330701944e-06 1.40431677387375e-05 2.90500163779e-05 2.09694436048668e-06 -3.95429261671389e-06 4.2877032231216e-06 4.47957314018093e-05 2.51416314634174e-06 2.09694436048668e-06 1.0050449851053e-05 2.90735058107774e-06 1.82974027187538e-06 9.96522283932949e-07 -1.69349553538189e-06 -3.95429261671389e-06 2.90735058107774e-06 4.09820503662878e-05 -1.91606025467657e-05 -1.84602253485719e-05 1.93729957975307e-06 4.2877032231216e-06 1.82974027187538e-06 -1.91606025467657e-05 3.21685752590114e-05 1.83543423943711e-05 1.63476330701944e-06 4.47957314018093e-05 9.96522283932949e-07 -1.84602253485719e-05 1.83543423943711e-05 0.000332469284692101 1975 1930 0 0 360 1975 1930 0 0 316 0 0 0 0 0 0 0 0 1168 0 0 0 0 0 3042 +1055 1059 0.97442384965837 -0.224714352774522 0.00127313553494281 0.286219517701902 0.224506217010411 0.973735953734075 0.0378847057434343 0.0607615219526922 -0.00975293497553934 -0.0366299339710003 0.999281305837672 0.213480680336355 2.35777412410895e-05 1.55702764093115e-05 -2.79987849965959e-07 6.12826042729692e-06 -5.97591173614729e-06 -1.02934202864044e-05 1.55702764093115e-05 2.19531840112826e-05 -5.77013998772634e-07 -2.74689329448969e-06 1.64865508002214e-07 -9.51906523970451e-06 -2.79987849965959e-07 -5.77013998772634e-07 1.0971629481257e-05 2.29104840242484e-06 3.91503581009392e-06 -4.11229918230881e-07 6.12826042729692e-06 -2.74689329448969e-06 2.29104840242484e-06 4.52365740824721e-05 -2.40467230265457e-05 7.2420608102142e-06 -5.97591173614729e-06 1.64865508002214e-07 3.91503581009392e-06 -2.40467230265457e-05 3.90614078580462e-05 -3.95423040431053e-06 -1.02934202864044e-05 -9.51906523970451e-06 -4.11229918230881e-07 7.2420608102142e-06 -3.95423040431053e-06 7.72454204785712e-05 1628 1595 0 0 374 1628 1595 0 0 325 0 0 0 0 0 0 0 0 1036 0 0 0 0 0 2770 +1055 1157 0.967877702196914 -0.250699841241904 0.0190353143211637 0.73665501864727 0.249795367427051 0.967454715215854 0.0404184168244623 -0.399828867343664 -0.0285486952767674 -0.0343651510675532 0.999001505699615 -0.133407431921098 2.98084788150994e-05 1.24381318803305e-05 3.56485683981726e-07 -2.56402653674705e-06 4.17782584248306e-06 -2.79116431665986e-05 1.24381318803305e-05 3.33791242766591e-05 1.59148441148386e-06 8.63844669518983e-06 -1.06005803437613e-05 7.04530684111495e-06 3.56485683981726e-07 1.59148441148386e-06 1.14580685866822e-05 4.47036967215534e-06 4.19735813082342e-06 1.27080740808546e-06 -2.56402653674705e-06 8.63844669518983e-06 4.47036967215534e-06 3.68371629798883e-05 -1.56451292572445e-05 2.19422174362872e-05 4.17782584248306e-06 -1.06005803437613e-05 4.19735813082342e-06 -1.56451292572445e-05 3.44780306516565e-05 -2.36779283152553e-05 -2.79116431665986e-05 7.04530684111495e-06 1.27080740808546e-06 2.19422174362872e-05 -2.36779283152553e-05 0.000132449639646099 2101 2093 0 322 504 2101 2093 0 322 435 0 0 0 0 0 0 0 0 725 0 0 0 0 0 3074 +1055 1106 0.744032047421661 -0.664779613284397 0.0669654998561018 0.515423134416151 0.661626504593969 0.747029362989122 0.0647881104125739 0.192725430324573 -0.0930950096852497 -0.0038982808406674 0.995649598291583 0.682411193309794 7.8188202047845e-05 5.0084276742212e-05 7.26941087046613e-07 -2.82346233725262e-07 -3.58304801807133e-06 -3.22589882794189e-06 5.0084276742212e-05 6.83960121580774e-05 2.9677283719844e-06 -1.22110594312861e-06 -9.09684450059078e-06 2.25613283584766e-05 7.26941087046613e-07 2.9677283719844e-06 1.67543472866053e-05 4.16998095320525e-06 1.93811580509288e-06 6.05608815814281e-06 -2.82346233725262e-07 -1.22110594312861e-06 4.16998095320525e-06 2.98653491870738e-05 -1.73495056923273e-05 1.30153864799729e-05 -3.58304801807133e-06 -9.09684450059078e-06 1.93811580509288e-06 -1.73495056923273e-05 0.000100245956658174 -4.68445387127662e-05 -3.22589882794189e-06 2.25613283584766e-05 6.05608815814281e-06 1.30153864799729e-05 -4.68445387127662e-05 0.000425092745359954 0 0 0 0 679 0 0 0 0 646 0 0 0 0 0 0 0 0 118 0 0 0 0 0 904 +1056 1152 0.887145548583101 -0.460858755642201 -0.0241243233503175 0.480830764195411 0.461303984785117 0.887059018871066 0.0180258331534057 -0.10293986152456 0.0130923355655685 -0.0271201841332916 0.999546440322817 0.115120297432664 2.39745939249337e-05 1.85320541472371e-05 7.50425624544809e-07 8.60552748854291e-07 -1.88201378750327e-06 -7.64294465429702e-06 1.85320541472371e-05 2.66142414854617e-05 7.45214139210677e-07 6.16315687005788e-06 -1.23612134378249e-05 9.97684871881634e-06 7.50425624544809e-07 7.45214139210677e-07 1.01488923357501e-05 1.36830272016787e-06 1.23753271553177e-06 2.08325914533817e-06 8.60552748854291e-07 6.16315687005788e-06 1.36830272016787e-06 5.00938836401792e-05 -5.5323961394871e-05 2.94521129162871e-05 -1.88201378750327e-06 -1.23612134378249e-05 1.23753271553177e-06 -5.5323961394871e-05 0.000120574065248509 -3.99129206873782e-05 -7.64294465429702e-06 9.97684871881634e-06 2.08325914533817e-06 2.94521129162871e-05 -3.99129206873782e-05 0.000144249257334456 754 781 0 0 890 754 781 0 0 843 0 0 0 0 0 0 0 0 836 0 0 0 0 0 2221 +1056 1153 0.916791138720994 -0.399098406381316 -0.014644793838004 0.509602688748074 0.399366249035591 0.916244330752338 0.0316689989649532 -0.169160152357451 0.000779162310503572 -0.0348824940062166 0.999391116889679 0.0110628625463076 2.46527858019418e-05 1.38955143735534e-05 -1.85396993737101e-07 1.26160396422765e-06 -3.75978632721413e-06 -4.92803657875746e-06 1.38955143735534e-05 3.67156339336908e-05 7.97463818414946e-07 3.72945300300357e-06 -9.77517782513991e-06 3.79329108076811e-05 -1.85396993737101e-07 7.97463818414946e-07 1.11079842153083e-05 1.05767941632518e-06 5.63293845548519e-07 3.70406538087869e-06 1.26160396422765e-06 3.72945300300357e-06 1.05767941632518e-06 2.39202647366912e-05 -6.36135818560862e-06 3.42516358584183e-05 -3.75978632721413e-06 -9.77517782513991e-06 5.63293845548519e-07 -6.36135818560862e-06 3.60998403451473e-05 -4.53159346386012e-05 -4.92803657875746e-06 3.79329108076811e-05 3.70406538087869e-06 3.42516358584183e-05 -4.53159346386012e-05 0.000268091862101211 1089 1084 0 0 750 1089 1084 0 0 693 0 0 0 0 0 0 0 0 926 0 0 0 0 0 2660 +1056 1060 0.968280724124498 -0.249557421290411 0.0123908340243551 0.261929637271109 0.249032046584918 0.967911539534589 0.0336198068035812 0.0526370973369519 -0.0203833035268147 -0.0294676961207181 0.999357881753414 0.22569037919889 3.68319179570546e-05 3.87423541165093e-05 -9.94776435225996e-07 1.69070482397982e-06 1.71996691246771e-06 9.46908130125432e-05 3.87423541165093e-05 6.345885232543e-05 -2.15983643122318e-07 9.72338504092629e-06 -1.2103832566962e-05 0.0002000161978454 -9.94776435225996e-07 -2.15983643122318e-07 1.22443598842984e-05 2.2270740430755e-06 6.70997519094422e-07 -4.91972632672389e-07 1.69070482397982e-06 9.72338504092629e-06 2.2270740430755e-06 5.94419622856543e-05 -4.27643269466028e-05 4.25178978238528e-05 1.71996691246771e-06 -1.2103832566962e-05 6.70997519094422e-07 -4.27643269466028e-05 6.59140233493448e-05 -4.85925014644441e-05 9.46908130125432e-05 0.0002000161978454 -4.91972632672389e-07 4.25178978238528e-05 -4.85925014644441e-05 0.00121801179107159 1334 1327 0 0 264 1334 1327 0 0 223 0 0 0 0 0 0 0 0 906 0 0 0 0 0 2697 +1056 1103 0.77164034409816 -0.632933949675454 0.0629745560389527 0.448452607890536 0.632964490950743 0.77386780225099 0.0220131286892564 0.133289904343976 -0.0626668377656013 0.0228744396095898 0.997772332477208 0.661844625779743 4.14198183813395e-05 2.6335564422143e-05 -1.179863597556e-06 -5.04827387751706e-07 1.1843187147058e-05 -2.92112635382946e-05 2.6335564422143e-05 3.66703952451349e-05 3.29476111787376e-07 1.22611960159652e-07 -9.71649977072586e-07 -2.45540981519196e-05 -1.179863597556e-06 3.29476111787376e-07 1.40700480827645e-05 3.36543357384699e-06 4.86368991634965e-06 2.78880490987391e-06 -5.04827387751706e-07 1.22611960159652e-07 3.36543357384699e-06 2.17516974835254e-05 -1.231899352707e-06 -6.36064039206543e-06 1.1843187147058e-05 -9.71649977072586e-07 4.86368991634965e-06 -1.231899352707e-06 5.31482587212309e-05 2.91872416647802e-07 -2.92112635382946e-05 -2.45540981519196e-05 2.78880490987391e-06 -6.36064039206543e-06 2.91872416647802e-07 7.41916734589188e-05 0 0 0 0 612 0 0 0 0 574 0 0 0 0 0 0 0 0 89 0 0 0 0 0 1089 +1056 1156 0.963771365420241 -0.266154315176264 0.0175110167910962 0.612773588955441 0.265212615210207 0.963214358955823 0.0433632036948916 -0.369641805783047 -0.0284081665963631 -0.0371480714758653 0.998905899900615 -0.156330332125169 2.45439420198246e-05 1.20419706095611e-05 -4.6538044386643e-07 -3.10254191494835e-06 2.01496248573983e-06 -4.69698755640928e-06 1.20419706095611e-05 2.18673134285694e-05 -1.0736511565383e-07 -6.13373424639404e-07 -2.34534867376822e-06 -8.15363411745827e-06 -4.6538044386643e-07 -1.0736511565383e-07 1.07047959214164e-05 4.40962916664519e-06 4.06965724770966e-06 9.88710265989486e-07 -3.10254191494835e-06 -6.13373424639404e-07 4.40962916664519e-06 1.56710018382517e-05 4.03812357793452e-06 4.10153324149937e-06 2.01496248573983e-06 -2.34534867376822e-06 4.06965724770966e-06 4.03812357793452e-06 1.6730844113024e-05 -6.33205568801571e-06 -4.69698755640928e-06 -8.15363411745827e-06 9.88710265989486e-07 4.10153324149937e-06 -6.33205568801571e-06 9.37713319360942e-05 1830 1814 0 0 434 1830 1814 0 0 380 0 0 0 0 0 0 0 0 658 0 0 0 0 0 3058 +1056 1155 0.950926198093217 -0.308621724755744 0.0221810006259661 0.590440825054248 0.307062984246447 0.950088642325306 0.0551715092246306 -0.309857362558488 -0.0381010431044238 -0.0456530692642613 0.998230488304734 -0.0818728295675284 3.94489543420206e-05 1.28169185163634e-05 -1.78225108606738e-06 1.95838332065596e-06 1.56888171007289e-06 -8.39986955807524e-06 1.28169185163634e-05 3.60004985752483e-05 1.64772233340744e-06 -5.12210550779388e-06 -8.97995599417745e-07 -3.61139459218877e-06 -1.78225108606738e-06 1.64772233340744e-06 1.39200390177735e-05 -1.75757813824638e-07 8.35805984020079e-07 2.99596192504285e-06 1.95838332065596e-06 -5.12210550779388e-06 -1.75757813824638e-07 2.03318524600982e-05 4.04700375238006e-06 5.48613813048345e-06 1.56888171007289e-06 -8.97995599417745e-07 8.35805984020079e-07 4.04700375238006e-06 2.29488791150096e-05 -8.10283619889031e-06 -8.39986955807524e-06 -3.61139459218877e-06 2.99596192504285e-06 5.48613813048345e-06 -8.10283619889031e-06 0.000119719581141654 1614 1589 0 0 463 1614 1589 0 0 415 0 0 0 0 0 0 0 0 747 0 0 0 0 0 2881 +1056 1157 0.977059240367412 -0.210986823294918 0.0289793238115454 0.646878105479377 0.210377230575917 0.977356336507067 0.0227159051039628 -0.438681605603455 -0.033115882411058 -0.0160981950977005 0.999321863288667 -0.198269003559102 4.93467518211963e-05 3.40128145572669e-05 -1.32884998907654e-06 4.52874225127425e-06 -1.56560165340072e-07 -3.02426057203785e-05 3.40128145572669e-05 4.66330865784013e-05 -1.46784449678206e-06 8.18204494048314e-07 1.2526423989641e-06 -3.77907111272116e-05 -1.32884998907654e-06 -1.46784449678206e-06 1.22681115903772e-05 3.66444326842582e-06 4.42458321403284e-06 9.21142734936507e-07 4.52874225127425e-06 8.18204494048314e-07 3.66444326842582e-06 2.992232826307e-05 -9.6440384715052e-06 7.72843819503249e-06 -1.56560165340072e-07 1.2526423989641e-06 4.42458321403284e-06 -9.6440384715052e-06 3.09341230290577e-05 -9.09342189508422e-06 -3.02426057203785e-05 -3.77907111272116e-05 9.21142734936507e-07 7.72843819503249e-06 -9.09342189508422e-06 7.54044831670452e-05 2022 2010 0 59 278 2022 2010 0 59 216 0 0 0 0 0 0 0 0 714 0 0 0 0 0 3209 +1057 1061 0.959680748999765 -0.2807291850828 0.0142823192093356 0.276738368631493 0.280314367595213 0.959566233993559 0.0256222149533052 0.0115435034095508 -0.0208977347802537 -0.020585607160463 0.999569666135827 0.279267775872084 3.36970568132852e-05 2.15591684618921e-05 -2.80152577749681e-06 1.5674422245789e-06 -2.14947372825372e-06 1.52081268837264e-05 2.15591684618921e-05 3.04609062249374e-05 -1.63895024906353e-06 1.04332068075689e-05 -1.66290211725777e-05 1.72885574592358e-05 -2.80152577749681e-06 -1.63895024906353e-06 1.31408001504361e-05 5.62197501523361e-06 -2.95267468153617e-07 6.31340316629693e-06 1.5674422245789e-06 1.04332068075689e-05 5.62197501523361e-06 8.16294068964138e-05 -8.07029959426828e-05 6.47849461433601e-05 -2.14947372825372e-06 -1.66290211725777e-05 -2.95267468153617e-07 -8.07029959426828e-05 0.000130792970957395 -9.03538836719214e-05 1.52081268837264e-05 1.72885574592358e-05 6.31340316629693e-06 6.47849461433601e-05 -9.03538836719214e-05 0.000260847551942638 1059 1029 0 0 364 1059 1029 0 0 320 0 0 0 0 0 0 0 0 812 0 0 0 0 0 2647 +1057 1060 0.979822442665346 -0.198402125471424 0.0241780366807503 0.193307688938127 0.198220392623458 0.98010929194138 0.00971863150695466 0.0222652908273122 -0.0256253155593563 -0.00472995333878601 0.99966042771728 0.184221885086299 4.07711181851584e-05 2.11166632646665e-05 -3.77723796609884e-06 6.26358092912872e-06 -3.42418895534276e-06 1.72225536094373e-05 2.11166632646665e-05 3.40374874213573e-05 -2.00616535861059e-06 8.50528367267363e-06 -8.79519662075711e-06 2.21902184349776e-05 -3.77723796609884e-06 -2.00616535861059e-06 1.17350705706877e-05 2.194402436993e-06 5.84590378891801e-06 -5.04659472663306e-07 6.26358092912872e-06 8.50528367267363e-06 2.194402436993e-06 4.14484201311003e-05 -1.95575810786564e-05 5.46194267494043e-05 -3.42418895534276e-06 -8.79519662075711e-06 5.84590378891801e-06 -1.95575810786564e-05 3.58676518274336e-05 -4.80795202040191e-05 1.72225536094373e-05 2.21902184349776e-05 -5.04659472663306e-07 5.46194267494043e-05 -4.80795202040191e-05 0.000291187579307716 1350 1331 0 0 190 1350 1331 0 0 158 0 0 0 0 0 0 0 0 983 0 0 0 0 0 3143 +1057 1153 0.936326999948019 -0.351124567135827 0.0018131525088399 0.447790989657934 0.351113456363359 0.936321379315778 0.00464923614958826 -0.218725338306955 -0.00333015448852325 -0.00371658309170118 0.999987548463082 -0.0211156030250843 5.92265496911367e-05 4.08085926692902e-05 -2.06793707264395e-06 -4.89423548699939e-05 7.02417542146854e-05 5.93777303705545e-05 4.08085926692902e-05 6.70344497997487e-05 -1.60596884717673e-06 4.01485044238609e-05 -5.95464745299626e-05 8.53038964623637e-05 -2.06793707264395e-06 -1.60596884717673e-06 1.11677462887412e-05 6.65355175458558e-06 -5.32823550427382e-06 -5.38036789408516e-06 -4.89423548699939e-05 4.01485044238609e-05 6.65355175458558e-06 0.000789708607243398 -0.00110178590188357 1.8100474016018e-05 7.02417542146854e-05 -5.95464745299626e-05 -5.32823550427382e-06 -0.00110178590188357 0.00160034469622028 -5.44462873050643e-06 5.93777303705545e-05 8.53038964623637e-05 -5.38036789408516e-06 1.8100474016018e-05 -5.44462873050643e-06 0.000477576056103069 1089 1084 0 0 422 1089 1084 0 0 389 0 0 0 0 0 0 0 0 920 0 0 0 0 0 2781 +1057 1155 0.96535445407229 -0.259382186851171 0.0284896322737711 0.492614637592664 0.258313278641159 0.965374974750816 0.0364061561073938 -0.342779299469869 -0.0369462864229327 -0.0277855946340049 0.998930894832265 -0.145771413735329 2.65406278262051e-05 1.27212967453228e-05 1.68940491148789e-06 -1.43631355892331e-06 -2.25310615031888e-07 -1.28997724182877e-05 1.27212967453228e-05 2.44442089662299e-05 1.37685769731777e-06 -5.66745941992945e-07 -1.30686840003621e-06 -2.84413312176259e-06 1.68940491148789e-06 1.37685769731777e-06 1.16372134472872e-05 4.11887399040147e-06 5.66449528788614e-06 9.78538246366542e-07 -1.43631355892331e-06 -5.66745941992945e-07 4.11887399040147e-06 3.23989798848829e-05 -1.4784048868716e-05 1.81635664710191e-05 -2.25310615031888e-07 -1.30686840003621e-06 5.66449528788614e-06 -1.4784048868716e-05 3.85307346210839e-05 -2.45940076058571e-05 -1.28997724182877e-05 -2.84413312176259e-06 9.78538246366542e-07 1.81635664710191e-05 -2.45940076058571e-05 0.000108817040132934 1615 1588 0 0 238 1615 1588 0 0 212 0 0 0 0 0 0 0 0 775 0 0 0 0 0 3055 +1057 1156 0.975240813270135 -0.217649187909577 0.0391687009550621 0.522783664341777 0.216762515371975 0.975886891104163 0.0256668599689396 -0.410982397292545 -0.0438105930320528 -0.0165410632473274 0.998902910780036 -0.188370650048525 2.51054689237795e-05 1.36289254280398e-05 5.89955880600068e-07 8.75426493954501e-07 -1.84591243573546e-06 -1.41713796124603e-05 1.36289254280398e-05 2.54220140007084e-05 -1.8153014242142e-07 -2.28174590711554e-06 2.21704954273396e-06 -1.27372349428562e-05 5.89955880600068e-07 -1.8153014242142e-07 1.06221564351824e-05 4.64191862087445e-06 5.37835371147593e-06 1.02272751589145e-06 8.75426493954501e-07 -2.28174590711554e-06 4.64191862087445e-06 2.28596939508474e-05 -2.42312713523788e-06 3.64911432778955e-06 -1.84591243573546e-06 2.21704954273396e-06 5.37835371147593e-06 -2.42312713523788e-06 2.48931111335996e-05 -2.86727823669435e-06 -1.41713796124603e-05 -1.27372349428562e-05 1.02272751589145e-06 3.64911432778955e-06 -2.86727823669435e-06 4.93949572293784e-05 1851 1834 0 0 215 1851 1834 0 0 178 0 0 0 0 0 0 0 0 703 0 0 0 0 0 3165 +1058 1151 0.903643795851249 -0.425984197515268 -0.0443323097392902 0.341228941757297 0.426480844134739 0.904494494540434 0.00194908495595234 -0.136221347663518 0.0392680506985988 -0.0206681594080885 0.999014938517445 0.103346785738843 0.000143960209320889 0.000147429832056408 -1.15641269476842e-05 -8.1540538926985e-06 3.92552365427825e-05 0.000139259440837094 0.000147429832056408 0.000187918998328213 -1.02621587779118e-05 5.09963397174561e-06 2.34834099022767e-05 0.000199849330493046 -1.15641269476842e-05 -1.02621587779118e-05 1.19778400836833e-05 4.74519947825895e-06 1.36055325609128e-06 -8.8610082548229e-06 -8.1540538926985e-06 5.09963397174561e-06 4.74519947825895e-06 5.25875651968012e-05 -7.3897298102674e-05 9.78737054952198e-07 3.92552365427825e-05 2.34834099022767e-05 1.36055325609128e-06 -7.3897298102674e-05 0.000195939518213795 7.00993517689263e-05 0.000139259440837094 0.000199849330493046 -8.8610082548229e-06 9.78737054952198e-07 7.00993517689263e-05 0.00048539835711003 377 460 0 0 638 377 460 0 0 638 0 0 0 0 0 0 0 0 977 0 0 0 0 0 2473 +1058 1060 0.990806109875102 -0.134268444804024 0.016590279204311 0.124183900740981 0.134072712766039 0.990893911874458 0.0124001250675098 0.00497583867775894 -0.0181041521680391 -0.0100618159416362 0.999785476757006 0.12564709998655 2.74056346001575e-05 7.83867143005929e-06 3.50914894887407e-07 1.98981083543624e-06 -4.47209126348355e-06 8.86306531674456e-06 7.83867143005929e-06 2.98952976024425e-05 2.8603482237983e-06 -1.15172249261551e-05 6.07139465065477e-06 1.40445205732119e-05 3.50914894887407e-07 2.8603482237983e-06 1.25829271841098e-05 2.24359152295936e-07 2.41602158466714e-06 1.88898225482722e-06 1.98981083543624e-06 -1.15172249261551e-05 2.24359152295936e-07 6.50287882270702e-05 -4.7219996352964e-05 5.59966228166359e-06 -4.47209126348355e-06 6.07139465065477e-06 2.41602158466714e-06 -4.7219996352964e-05 7.05141717664329e-05 -9.36174453432201e-06 8.86306531674456e-06 1.40445205732119e-05 1.88898225482722e-06 5.59966228166359e-06 -9.36174453432201e-06 0.000175421932529738 1402 1366 0 0 164 1402 1366 0 0 144 0 0 0 0 0 0 0 0 1101 0 0 0 0 0 3305 +1058 1061 0.975960739499528 -0.217859029420568 0.0061707580946746 0.165235369029065 0.217485735951117 0.97534733727277 0.0373835034837381 0.0220514381338357 -0.0141629662619029 -0.0351427798394756 0.999281939900756 0.18555973535436 5.01630211273309e-05 4.38986867925944e-05 -4.59079609112614e-06 4.41341765122769e-07 2.68594174216227e-06 3.36465973782905e-05 4.38986867925944e-05 7.07107245182484e-05 -3.63420661692179e-06 3.30205353859288e-06 -7.75288021868676e-06 6.54040604323053e-05 -4.59079609112614e-06 -3.63420661692179e-06 1.23241705983324e-05 2.20555030743361e-06 2.2321816104217e-06 8.4790500121907e-07 4.41341765122769e-07 3.30205353859288e-06 2.20555030743361e-06 4.77270748688207e-05 -3.87944570135739e-05 3.31327067124174e-05 2.68594174216227e-06 -7.75288021868676e-06 2.2321816104217e-06 -3.87944570135739e-05 7.25590673852385e-05 -4.95653227318065e-05 3.36465973782905e-05 6.54040604323053e-05 8.4790500121907e-07 3.31327067124174e-05 -4.95653227318065e-05 0.000325177439277269 1059 1029 0 0 229 1059 1029 0 0 219 0 0 0 0 0 0 0 0 1008 0 0 0 0 0 2738 +1058 1062 0.951907768116871 -0.303183556265454 0.0441738860526197 0.222371903260973 0.301585817168902 0.952626220380204 0.0393608832051847 0.0201872150079122 -0.05401477465771 -0.0241457129602509 0.998248159860221 0.264107352873593 6.06851410244665e-05 4.33519080666925e-05 -3.00720855097013e-06 4.56024233909137e-06 -6.04571643880759e-06 5.98998257294933e-05 4.33519080666925e-05 5.44919213655286e-05 -1.88594211688408e-06 -1.47956831854649e-07 -4.62248881718858e-06 6.26300721611606e-05 -3.00720855097013e-06 -1.88594211688408e-06 1.50900086090637e-05 2.55115774245508e-06 2.96907386544119e-06 1.31654322386633e-06 4.56024233909137e-06 -1.47956831854649e-07 2.55115774245508e-06 5.62877168555088e-05 -5.51462683533192e-05 3.74411146386494e-05 -6.04571643880759e-06 -4.62248881718858e-06 2.96907386544119e-06 -5.51462683533192e-05 0.000112720389449943 -6.97154343886322e-05 5.98998257294933e-05 6.26300721611606e-05 1.31654322386633e-06 3.74411146386494e-05 -6.97154343886322e-05 0.000412834785591063 589 621 0 0 376 589 621 0 0 360 0 0 0 0 0 0 0 0 791 0 0 0 0 0 2190 +1058 1155 0.980206713741239 -0.195848055666028 0.028954057201662 0.398198447281815 0.194750884385493 0.980160895587126 0.0368335688321428 -0.377954412651451 -0.0355934174766779 -0.0304656832137446 0.998901872447264 -0.177667990361092 3.94279306336912e-05 2.26362028077408e-05 -1.18945846105604e-06 1.27937904733904e-06 -2.1620737933078e-07 6.4131531838587e-06 2.26362028077408e-05 5.17793309010499e-05 -1.32647224064219e-06 -7.10025864219024e-06 7.61245977761847e-06 2.09886263467981e-05 -1.18945846105604e-06 -1.32647224064219e-06 1.15323202710878e-05 3.04502069627441e-06 5.82097541634023e-06 -4.00900770809717e-07 1.27937904733904e-06 -7.10025864219024e-06 3.04502069627441e-06 2.53128821201006e-05 -5.26526048370155e-06 -1.00009496121324e-07 -2.1620737933078e-07 7.61245977761847e-06 5.82097541634023e-06 -5.26526048370155e-06 2.80138419837314e-05 -1.26233417381254e-05 6.4131531838587e-06 2.09886263467981e-05 -4.00900770809717e-07 -1.00009496121324e-07 -1.26233417381254e-05 0.000269264775623044 1610 1585 0 0 202 1610 1585 0 0 181 0 0 0 0 0 0 0 0 817 0 0 0 0 0 3145 +1058 1156 0.987701970027094 -0.153062081019647 0.0318875800043173 0.417769476147317 0.152369888076174 0.98805295773836 0.0231250926945862 -0.44292621145148 -0.0350461925499898 -0.0179819926152241 0.999223905002945 -0.236344446417381 3.71521375634399e-05 2.78053807155305e-05 -1.01928965092992e-06 -1.94516702167588e-06 6.54624093330361e-07 -2.8915321013545e-05 2.78053807155305e-05 3.853581618883e-05 -1.47524488958777e-06 -4.70951223850067e-06 2.92266105526629e-06 -2.09171622625318e-05 -1.01928965092992e-06 -1.47524488958777e-06 1.04246900977955e-05 4.16092230252594e-06 4.61372580746845e-06 2.66853394051383e-06 -1.94516702167588e-06 -4.70951223850067e-06 4.16092230252594e-06 3.19657397335525e-05 -1.25664567882033e-05 2.98986124201507e-06 6.54624093330361e-07 2.92266105526629e-06 4.61372580746845e-06 -1.25664567882033e-05 3.41533206135372e-05 -1.32642456572243e-06 -2.8915321013545e-05 -2.09171622625318e-05 2.66853394051383e-06 2.98986124201507e-06 -1.32642456572243e-06 8.13258364304221e-05 1829 1817 0 0 135 1829 1817 0 0 105 0 0 0 0 0 0 0 0 783 0 0 0 0 0 3315 +1058 1106 0.840073168467945 -0.538880127315609 0.0623320142827242 0.316617700688838 0.540027552188771 0.841645254440055 -0.00187311386160387 0.0582077587000871 -0.0514520601845268 0.0352345577927139 0.998053711700888 0.553952667729415 5.4939013999999e-05 9.29670301297155e-06 -6.1659033433275e-06 5.59200331067572e-07 1.50099475697541e-05 -6.68813502877423e-06 9.29670301297155e-06 8.43264859055062e-05 -6.98521776382126e-07 2.63782130774057e-07 -2.10748110382104e-05 7.94351697234889e-05 -6.1659033433275e-06 -6.98521776382126e-07 1.52468735479051e-05 2.43896992909098e-06 4.27097640284542e-06 -4.54778010535871e-07 5.59200331067572e-07 2.63782130774057e-07 2.43896992909098e-06 2.34730860335465e-05 -3.02473457210613e-06 6.94747423907074e-06 1.50099475697541e-05 -2.10748110382104e-05 4.27097640284542e-06 -3.02473457210613e-06 7.79155476083403e-05 -4.75538838015826e-05 -6.68813502877423e-06 7.94351697234889e-05 -4.54778010535871e-07 6.94747423907074e-06 -4.75538838015826e-05 0.000343089831791856 0 0 0 0 522 0 0 0 0 502 0 0 0 0 0 0 0 0 280 0 0 0 0 0 1442 +1059 1061 0.988568678733436 -0.150749401019828 -0.0025662266834643 0.0953914449223023 0.150747471802107 0.987967413786717 0.0345772908258974 0.0176167668674661 -0.00267715754123972 -0.0345688788905425 0.999398731958246 0.135013390939153 4.04248594088707e-05 2.83324097237468e-05 -3.71615359942662e-06 -6.07691934516152e-08 -1.03644488176369e-06 -1.76154540980853e-06 2.83324097237468e-05 4.13054174527281e-05 -2.8700142906947e-06 -1.71254905962597e-06 -5.54429564902476e-07 -1.35129176108562e-06 -3.71615359942662e-06 -2.8700142906947e-06 1.09011576974347e-05 3.21535803126701e-06 3.74240220822877e-06 4.58303045711093e-06 -6.07691934516152e-08 -1.71254905962597e-06 3.21535803126701e-06 4.49769199917903e-05 -3.16302553344993e-05 4.60709457208293e-06 -1.03644488176369e-06 -5.54429564902476e-07 3.74240220822877e-06 -3.16302553344993e-05 6.02586051922947e-05 -2.03279759316522e-06 -1.76154540980853e-06 -1.35129176108562e-06 4.58303045711093e-06 4.60709457208293e-06 -2.03279759316522e-06 0.000128268577275294 1059 1029 0 0 215 1059 1029 0 0 201 0 0 0 0 0 0 0 0 1135 0 0 0 0 0 2800 +1059 1062 0.970922071887249 -0.236856945877879 0.0347723670689048 0.147405062916807 0.23581221574289 0.971283629568504 0.0316339981453592 0.0143679408732446 -0.0412665630819905 -0.022514398096226 0.998894475232376 0.207383922136764 4.29458851687303e-05 3.09980705789973e-05 -2.04088398164123e-06 -7.80123189571457e-06 1.06611943638204e-05 2.56771667856252e-05 3.09980705789973e-05 4.58129469955458e-05 -9.55615700273104e-07 3.06103115119538e-06 -8.28180157461679e-06 3.06490078535657e-05 -2.04088398164123e-06 -9.55615700273104e-07 1.38282519875969e-05 3.09146309800731e-06 1.13772790640364e-06 5.78073000249391e-06 -7.80123189571457e-06 3.06103115119538e-06 3.09146309800731e-06 5.40313830892922e-05 -5.54871078673624e-05 1.11651491491344e-05 1.06611943638204e-05 -8.28180157461679e-06 1.13772790640364e-06 -5.54871078673624e-05 0.000113520958830335 -2.59125777004769e-05 2.56771667856252e-05 3.06490078535657e-05 5.78073000249391e-06 1.11651491491344e-05 -2.59125777004769e-05 0.000231815019153347 616 654 0 0 330 616 654 0 0 317 0 0 0 0 0 0 0 0 985 0 0 0 0 0 2320 +1059 1153 0.97460184909264 -0.223173993956081 -0.0185635170939788 0.270017095643295 0.223468571949449 0.974585243721701 0.0156652504221169 -0.26635824412908 0.0145956533283413 -0.019415744683245 0.999704954355191 -0.140579942987445 3.7741010199143e-05 3.12394368116807e-05 -1.35833974620995e-06 -5.01467792573225e-06 9.01026907966612e-06 1.53903494404889e-05 3.12394368116807e-05 4.92032703771252e-05 -2.41925015436005e-06 -2.58332312738874e-06 4.70477081837233e-06 3.39059674859773e-05 -1.35833974620995e-06 -2.41925015436005e-06 1.01674185767422e-05 3.07057911207132e-06 3.55670577686604e-06 -8.68698060806057e-07 -5.01467792573225e-06 -2.58332312738874e-06 3.07057911207132e-06 2.39034078317115e-05 -1.2004483867941e-05 3.2799593784659e-06 9.01026907966612e-06 4.70477081837233e-06 3.55670577686604e-06 -1.2004483867941e-05 4.08158144531015e-05 3.68258452946981e-06 1.53903494404889e-05 3.39059674859773e-05 -8.68698060806057e-07 3.2799593784659e-06 3.68258452946981e-06 0.000178491431587511 1089 1084 0 0 267 1089 1084 0 0 252 0 0 0 0 0 0 0 0 1037 0 0 0 0 0 3130 +1059 1063 0.94807171854559 -0.312931895168291 0.05686515172224 0.176480917567913 0.309638992342639 0.948969370484617 0.0598400225857617 0.0260105992112039 -0.0726891389070421 -0.0391249647720044 0.99658693861426 0.26406039177806 2.89365364573176e-05 1.80325902644431e-05 -4.66737148421268e-07 -1.85323098983104e-06 -4.1654379727686e-07 2.51678436061907e-05 1.80325902644431e-05 2.65587240963306e-05 -6.59269869712273e-07 -2.9471847136658e-06 2.3166850581366e-06 1.2485937898478e-05 -4.66737148421268e-07 -6.59269869712273e-07 1.23475535249716e-05 2.65993436965297e-06 3.2376771592435e-06 4.53583127206114e-06 -1.85323098983104e-06 -2.9471847136658e-06 2.65993436965297e-06 3.05124192416927e-05 -1.75723510766931e-05 -1.31308068908799e-05 -4.1654379727686e-07 2.3166850581366e-06 3.2376771592435e-06 -1.75723510766931e-05 5.88397724563134e-05 -8.78846400579447e-06 2.51678436061907e-05 1.2485937898478e-05 4.53583127206114e-06 -1.31308068908799e-05 -8.78846400579447e-06 0.000227992534634675 256 363 0 0 450 256 363 0 0 431 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2272 +1059 1105 0.874859938651331 -0.480856364534318 0.0582858853396598 0.246084489953963 0.481651689181974 0.876362618597707 0.000459382978589932 0.0448202833543316 -0.0513004683325637 0.0276715993648473 0.998299826974567 0.483306425002729 4.49042082732602e-05 1.71015658073862e-05 -2.34341794403524e-06 -6.62978954281614e-07 4.85151731318834e-06 -5.42295760200199e-06 1.71015658073862e-05 5.06130035701547e-05 2.44216137858196e-06 4.86379534092441e-07 -1.74357205168267e-05 1.56739300465278e-05 -2.34341794403524e-06 2.44216137858196e-06 1.65918266262761e-05 2.12584672953703e-06 -1.355864851766e-06 1.49434329424023e-05 -6.62978954281614e-07 4.86379534092441e-07 2.12584672953703e-06 2.07402796464172e-05 2.2404517003418e-06 3.8918031875632e-06 4.85151731318834e-06 -1.74357205168267e-05 -1.355864851766e-06 2.2404517003418e-06 6.9209610526858e-05 -5.08545106973549e-05 -5.42295760200199e-06 1.56739300465278e-05 1.49434329424023e-05 3.8918031875632e-06 -5.08545106973549e-05 0.000198351587066598 0 0 0 0 516 0 0 0 0 497 0 0 0 0 0 0 0 0 412 0 0 0 0 0 1544 +1059 1154 0.985606755144679 -0.168956082939055 -0.00575901476541023 0.271760896363321 0.169054200967009 0.985027268451132 0.0337928623100733 -0.319309684572712 -3.67230638670347e-05 -0.0342800590080059 0.999412265386924 -0.229154594006788 3.54988900018362e-05 -3.61084931690082e-06 -2.74534829930115e-06 7.91424723198226e-06 -1.09131539152059e-05 -1.68066403138143e-05 -3.61084931690082e-06 6.28866719755653e-05 2.80516702303781e-06 1.25186089967489e-05 -1.54939899366291e-05 7.77272227048066e-05 -2.74534829930115e-06 2.80516702303781e-06 1.119745327997e-05 5.02702828270561e-06 2.9638334815661e-06 4.6256568691449e-06 7.91424723198226e-06 1.25186089967489e-05 5.02702828270561e-06 6.42389350279368e-05 -5.83793771897842e-05 8.67575209187025e-05 -1.09131539152059e-05 -1.54939899366291e-05 2.9638334815661e-06 -5.83793771897842e-05 9.72476073462905e-05 -0.000107049756049049 -1.68066403138143e-05 7.77272227048066e-05 4.6256568691449e-06 8.67575209187025e-05 -0.000107049756049049 0.000319478369497572 1335 1317 0 0 160 1335 1317 0 0 157 0 0 0 0 0 0 0 0 934 0 0 0 0 0 3328 +1059 1106 0.874980999674296 -0.480616623395139 0.0584457998937933 0.24731664855925 0.481438443686156 0.876479905319884 2.26163451723092e-05 0.0451141232940002 -0.0512374389487071 0.0281182660685525 0.998290582928275 0.498563623116615 4.33698712564133e-05 2.68753450704521e-05 -2.24614074852499e-06 4.37954948131753e-07 2.55373270791505e-06 -1.60653812424637e-05 2.68753450704521e-05 6.31784271109785e-05 1.28544308805277e-06 4.17646279810161e-06 -1.90130401265816e-05 4.13618782630353e-05 -2.24614074852499e-06 1.28544308805277e-06 1.60813068406729e-05 1.12560926558676e-06 -1.49114901736222e-06 3.54741724631023e-06 4.37954948131753e-07 4.17646279810161e-06 1.12560926558676e-06 2.56785525066177e-05 -1.42584115559602e-06 6.46736831030537e-06 2.55373270791505e-06 -1.90130401265816e-05 -1.49114901736222e-06 -1.42584115559602e-06 8.07555010704486e-05 -1.47738597830684e-05 -1.60653812424637e-05 4.13618782630353e-05 3.54741724631023e-06 6.46736831030537e-06 -1.47738597830684e-05 0.000323527828005753 0 0 0 0 485 0 0 0 0 470 0 0 0 0 0 0 0 0 393 0 0 0 0 0 1530 +1059 1112 0.873951624642588 -0.481533872900222 0.0658307453572742 0.256146991984589 0.482500536753098 0.875894588513776 0.00137907405728262 0.0369929849982627 -0.0583248644880843 0.0305581259568767 0.997829850786421 0.49854841488809 7.20226365417753e-05 2.21766353285198e-05 -7.73494497015654e-06 7.23855620934551e-06 2.86038055602778e-06 3.2896195205212e-05 2.21766353285198e-05 7.45313970243421e-05 -1.81528301164115e-07 1.62313492232553e-06 -3.18362450294438e-05 8.86047718516704e-05 -7.73494497015654e-06 -1.81528301164115e-07 1.6177193232209e-05 3.12709230610352e-07 -1.42043660823871e-06 1.29331247585508e-06 7.23855620934551e-06 1.62313492232553e-06 3.12709230610352e-07 2.62576563080341e-05 4.1619082755352e-07 3.66380407190145e-05 2.86038055602778e-06 -3.18362450294438e-05 -1.42043660823871e-06 4.1619082755352e-07 0.000102759821085348 -0.000148308307701211 3.2896195205212e-05 8.86047718516704e-05 1.29331247585508e-06 3.66380407190145e-05 -0.000148308307701211 0.00069053621086056 0 0 0 0 487 0 0 0 0 474 0 0 0 0 0 0 0 0 329 0 0 0 0 0 1538 +1059 1155 0.991618965532412 -0.128529047748565 0.0131191112990634 0.305228699382761 0.127884280117141 0.990908793158624 0.0417776799240823 -0.399145875609915 -0.0183694881624552 -0.0397498116444053 0.999040797154392 -0.27393242956233 4.34596001232806e-05 2.6246080075159e-05 -3.59854095086823e-07 6.05850627557849e-07 -5.6455430681984e-06 2.88927147689258e-06 2.6246080075159e-05 5.38332094109903e-05 -3.99466312269667e-08 6.48814085155371e-06 -6.28097890287868e-06 2.10950189493769e-05 -3.59854095086823e-07 -3.99466312269667e-08 1.09343463355415e-05 4.34993643248651e-06 4.15544478821548e-06 3.65060749854086e-06 6.05850627557849e-07 6.48814085155371e-06 4.34993643248651e-06 2.59057539866117e-05 -4.78982153763626e-06 3.5671668780747e-05 -5.6455430681984e-06 -6.28097890287868e-06 4.15544478821548e-06 -4.78982153763626e-06 3.06730467509729e-05 -4.87390592112873e-05 2.88927147689258e-06 2.10950189493769e-05 3.65060749854086e-06 3.5671668780747e-05 -4.87390592112873e-05 0.000332486105224495 1613 1588 0 0 133 1613 1588 0 0 119 0 0 0 0 0 0 0 0 830 0 0 0 0 0 3277 +1060 1063 0.96587443763443 -0.250951966573889 0.0641067952488017 0.11593040236404 0.247599346873238 0.967248933500175 0.0558933276046434 0.0249530184555134 -0.0760337698152614 -0.0381131357339123 0.996376562717233 0.188988760466269 3.45162386553706e-05 2.90554140397638e-05 9.79798532164744e-07 -3.28576444593987e-06 1.28443043708884e-06 1.45565241523395e-05 2.90554140397638e-05 4.06546081389144e-05 1.18822180202376e-06 -1.25138608273242e-07 -6.39137541038715e-06 2.06524257707861e-05 9.79798532164744e-07 1.18822180202376e-06 1.32203415565789e-05 2.25249207524543e-06 3.51564172145944e-06 3.92552831575936e-06 -3.28576444593987e-06 -1.25138608273242e-07 2.25249207524543e-06 3.31640198053508e-05 -2.6390733597933e-05 3.19178065304162e-06 1.28443043708884e-06 -6.39137541038715e-06 3.51564172145944e-06 -2.6390733597933e-05 8.12110768753558e-05 -2.37915872769016e-05 1.45565241523395e-05 2.06524257707861e-05 3.92552831575936e-06 3.19178065304162e-06 -2.37915872769016e-05 0.000233352263603471 256 363 0 0 407 256 363 0 0 401 0 0 0 0 0 0 0 0 997 0 0 0 0 0 2444 +1060 1148 0.905582927326128 -0.423075692171779 -0.0304387980841869 0.192599310168713 0.423058596149084 0.906072780110518 -0.00731719667378968 -0.0238907756051219 0.0306754944508825 -0.00625106680229006 0.999509848978001 0.275734682505875 7.59634728011688e-05 2.31477205359336e-05 -1.06536254531516e-05 5.23114661185088e-06 2.99599587267458e-06 0.00011154878763742 2.31477205359336e-05 6.49130458051177e-05 -1.89131144131838e-06 -3.82835767207875e-06 1.26612075991178e-07 1.28976045946432e-05 -1.06536254531516e-05 -1.89131144131838e-06 1.69903969255867e-05 -1.15873613820034e-06 -1.10933248292781e-06 -6.37982095450202e-08 5.23114661185088e-06 -3.82835767207875e-06 -1.15873613820034e-06 2.74251587403035e-05 -2.55958726304354e-05 2.31986896367877e-05 2.99599587267458e-06 1.26612075991178e-07 -1.10933248292781e-06 -2.55958726304354e-05 0.000123077691802725 -2.08150564014765e-05 0.00011154878763742 1.28976045946432e-05 -6.37982095450202e-08 2.31986896367877e-05 -2.08150564014765e-05 0.000458386998355729 0 0 0 0 564 0 0 0 0 553 0 0 0 0 0 0 0 0 745 0 0 0 0 0 1761 +1060 1149 0.908654224600182 -0.415031636610905 -0.0457847215598716 0.187939979651638 0.414470247989246 0.909806754415243 -0.0215889590331471 -0.0617098735079256 0.0506153499244452 0.00064049393115077 0.998718016318696 0.178098145363938 5.1342392893051e-05 4.33200839354788e-05 -5.20704021584332e-06 -7.62643711668119e-07 4.87295099614903e-06 1.02342190044169e-05 4.33200839354788e-05 8.54176371092221e-05 -3.40842358016398e-06 -1.73756989477408e-06 1.05878066395014e-05 2.65814492354426e-05 -5.20704021584332e-06 -3.40842358016398e-06 1.16826353354141e-05 2.39017544101729e-06 -4.27573434793966e-07 2.39836263473853e-06 -7.62643711668119e-07 -1.73756989477408e-06 2.39017544101729e-06 2.6914394366374e-05 -2.81742065602144e-05 8.93398732515127e-06 4.87295099614903e-06 1.05878066395014e-05 -4.27573434793966e-07 -2.81742065602144e-05 0.000119293075014287 -9.93403471638557e-06 1.02342190044169e-05 2.65814492354426e-05 2.39836263473853e-06 8.93398732515127e-06 -9.93403471638557e-06 0.000117863773901581 0 0 0 0 703 0 0 0 0 676 0 0 0 0 0 0 0 0 976 0 0 0 0 0 1928 +1060 1062 0.984048717736211 -0.17377603399528 0.038079011680857 0.0720193450715471 0.172557598383485 0.984437659936606 0.0332621246865571 0.031326955173287 -0.0432665732620879 -0.0261607283425231 0.998720992034685 0.128289905505077 3.41696756418105e-05 2.42952045347787e-05 -3.05997833739303e-06 1.33040178367596e-06 -2.09711228649637e-06 1.33461027399042e-05 2.42952045347787e-05 3.91334711637392e-05 -3.0224855406311e-06 -5.2146169260964e-07 5.36606988024218e-07 8.66851220992123e-06 -3.05997833739303e-06 -3.0224855406311e-06 1.32135386413571e-05 2.89724990857594e-06 2.99855859347492e-06 3.26974488703354e-06 1.33040178367596e-06 -5.2146169260964e-07 2.89724990857594e-06 2.63864617094316e-05 -1.23032168482358e-05 2.06516780708874e-05 -2.09711228649637e-06 5.36606988024218e-07 2.99855859347492e-06 -1.23032168482358e-05 4.7074069364289e-05 -3.10435034676965e-05 1.33461027399042e-05 8.66851220992123e-06 3.26974488703354e-06 2.06516780708874e-05 -3.10435034676965e-05 0.00015559683538415 616 654 0 0 326 616 654 0 0 306 0 0 0 0 0 0 0 0 1100 0 0 0 0 0 2618 +1060 1064 0.949447456821319 -0.309200275388648 0.0542652415005595 0.144101321870788 0.305989320290938 0.950135878837904 0.0601028086932183 0.0260926093450359 -0.0701431579230595 -0.0404598744994146 0.99671607589728 0.253530668956195 3.81598867599625e-05 2.46582721639783e-05 -4.05314517854401e-06 4.4999102114512e-06 -9.82836658679899e-06 4.1343509735148e-05 2.46582721639783e-05 4.05584115318728e-05 -2.18802534510032e-06 3.25863249869049e-06 -6.91908186720388e-06 1.7448638516373e-05 -4.05314517854401e-06 -2.18802534510032e-06 1.52120738061258e-05 -1.18359486129397e-06 4.57807389736451e-07 -1.26756630385596e-06 4.4999102114512e-06 3.25863249869049e-06 -1.18359486129397e-06 3.91694442854003e-05 -4.51426815264323e-05 2.39374830683408e-05 -9.82836658679899e-06 -6.91908186720388e-06 4.57807389736451e-07 -4.51426815264323e-05 0.00012688304442431 -7.19519709170305e-05 4.1343509735148e-05 1.7448638516373e-05 -1.26756630385596e-06 2.39374830683408e-05 -7.19519709170305e-05 0.000268331386671814 0 92 0 0 548 0 92 0 0 533 0 0 0 0 0 0 0 0 845 0 0 0 0 0 2119 +1060 1146 0.908434669556874 -0.417804231408079 0.0136409444173699 0.18797024338202 0.418012319159159 0.908191427097828 -0.0213080448936953 0.0337679185543535 -0.00348599745775409 0.0250590495333331 0.999679894695402 0.375853046276586 4.37089739482558e-05 2.56077265223992e-05 -8.40857474400093e-06 2.54147158192229e-06 6.01154435915008e-06 7.51444022174684e-06 2.56077265223992e-05 6.85638313166262e-05 -4.37490968502301e-06 -2.24416622718739e-06 2.1595096465976e-07 1.12144784230194e-05 -8.40857474400093e-06 -4.37490968502301e-06 1.48277407759214e-05 8.06932866780157e-07 1.34684040174686e-06 -4.50357802172245e-07 2.54147158192229e-06 -2.24416622718739e-06 8.06932866780157e-07 2.22500001655891e-05 -3.81239393213947e-06 1.6606463179088e-05 6.01154435915008e-06 2.1595096465976e-07 1.34684040174686e-06 -3.81239393213947e-06 6.67427899114437e-05 -3.18783382112578e-05 7.51444022174684e-06 1.12144784230194e-05 -4.50357802172245e-07 1.6606463179088e-05 -3.18783382112578e-05 0.000234997641587044 0 0 0 0 491 0 0 0 0 478 0 0 0 0 0 0 0 0 491 0 0 0 0 0 1678 +1060 1147 0.912592315462951 -0.408535908084649 -0.0165432029371671 0.19105862491994 0.408533214023664 0.912735970188652 -0.00369618225684675 0.0190566098829037 0.0166095995576302 -0.00338534034201773 0.999856320014683 0.320106849744297 9.51039053360081e-05 4.29955689194126e-05 -6.31644294149965e-06 2.84871947958012e-05 -3.62500675014435e-05 0.000118614607506835 4.29955689194126e-05 9.40748296703707e-05 5.16358937455158e-06 6.93224817446354e-06 -1.78015707944437e-05 2.60161737793871e-05 -6.31644294149965e-06 5.16358937455158e-06 1.9095649401475e-05 -1.53084227877243e-06 -2.46396348234106e-06 -5.84349523440763e-06 2.84871947958012e-05 6.93224817446354e-06 -1.53084227877243e-06 4.2369418144221e-05 -3.66618514270199e-05 0.000109575900042913 -3.62500675014435e-05 -1.78015707944437e-05 -2.46396348234106e-06 -3.66618514270199e-05 0.000144040579929892 -0.000207571941123103 0.000118614607506835 2.60161737793871e-05 -5.84349523440763e-06 0.000109575900042913 -0.000207571941123103 0.000728560532125494 0 0 0 0 505 0 0 0 0 494 0 0 0 0 0 0 0 0 693 0 0 0 0 0 1732 +1060 1153 0.987131489572176 -0.15937331441863 -0.0130984329688001 0.191939741984173 0.159468829602331 0.987180922970589 0.00659679529769122 -0.272998427020011 0.0118791700164742 -0.00860069614377181 0.999892450889376 -0.203722988595905 4.37292067964578e-05 2.86310764943608e-05 -2.7018476066413e-06 5.56659247646985e-06 -3.34487630822226e-06 -3.48961738890552e-06 2.86310764943608e-05 4.54786996085099e-05 -1.9425089883772e-06 4.94773359478659e-06 1.41676494759088e-06 1.46542603852077e-05 -2.7018476066413e-06 -1.9425089883772e-06 1.17179489841025e-05 3.91887385739399e-06 3.89924008486521e-06 7.69570959669517e-07 5.56659247646985e-06 4.94773359478659e-06 3.91887385739399e-06 2.18145955413236e-05 -2.5500915780455e-06 2.14897465814313e-05 -3.34487630822226e-06 1.41676494759088e-06 3.89924008486521e-06 -2.5500915780455e-06 3.1404087428508e-05 -2.07668392049253e-05 -3.48961738890552e-06 1.46542603852077e-05 7.69570959669517e-07 2.14897465814313e-05 -2.07668392049253e-05 0.000200133119860664 1089 1084 0 0 219 1089 1084 0 0 202 0 0 0 0 0 0 0 0 1133 0 0 0 0 0 3099 +1060 1150 0.926318700683013 -0.371394161116832 -0.0632458840815638 0.157120412011533 0.37141128850137 0.928391883118697 -0.0119233440389413 -0.0748709878629125 0.0631452257790399 -0.0124454187411933 0.997926746817456 0.0650216210600426 7.80739682151455e-05 6.40921467009839e-05 -4.29252563344713e-06 4.52104328738834e-06 4.7797965532682e-06 6.55649420638798e-05 6.40921467009839e-05 7.90601704937091e-05 -2.75250906231396e-06 5.344395512423e-06 4.59463667405469e-07 5.51422165493489e-05 -4.29252563344713e-06 -2.75250906231396e-06 1.2244161018422e-05 3.15506935489026e-06 1.56470642430402e-06 1.89666555205883e-06 4.52104328738834e-06 5.344395512423e-06 3.15506935489026e-06 2.47072511239891e-05 -1.62884178518548e-05 3.06465404244429e-05 4.7797965532682e-06 4.59463667405469e-07 1.56470642430402e-06 -1.62884178518548e-05 7.31567763133869e-05 -1.81892034969087e-05 6.55649420638798e-05 5.51422165493489e-05 1.89666555205883e-06 3.06465404244429e-05 -1.81892034969087e-05 0.000311481387889386 23 155 0 0 763 23 155 0 0 760 0 0 0 0 0 0 0 0 1090 0 0 0 0 0 2366 +1060 1145 0.906052246908031 -0.421079270906714 0.0419711029826254 0.185976269572991 0.422108548442326 0.906338895617108 -0.019343723102669 0.0359339538162703 -0.0298948023044114 0.0352427851372595 0.998931552655611 0.395933580500086 6.37010254581584e-05 3.84639248006652e-05 -6.50725854118792e-06 3.79995624496032e-06 -4.61057344052304e-06 3.78852306898471e-05 3.84639248006652e-05 6.73720112363871e-05 -2.86316451486298e-06 -1.43836605565613e-06 2.50845631620022e-06 3.59962679349361e-05 -6.50725854118792e-06 -2.86316451486298e-06 1.36706198334793e-05 2.17208893906648e-06 1.99008931452532e-06 4.92384835818051e-06 3.79995624496032e-06 -1.43836605565613e-06 2.17208893906648e-06 2.23987798246696e-05 -3.06996625027009e-06 3.5743750961818e-05 -4.61057344052304e-06 2.50845631620022e-06 1.99008931452532e-06 -3.06996625027009e-06 6.64739002237329e-05 -8.66638129871158e-05 3.78852306898471e-05 3.59962679349361e-05 4.92384835818051e-06 3.5743750961818e-05 -8.66638129871158e-05 0.000422277978148817 0 0 0 0 502 0 0 0 0 480 0 0 0 0 0 0 0 0 481 0 0 0 0 0 1665 +1060 1141 0.905011255528115 -0.422160192244425 0.0523010463717095 0.189291880455364 0.423241291545561 0.905948487554078 -0.0111421285813596 0.031643717775777 -0.042678290714027 0.0322197141922186 0.998569203169766 0.414816508053424 4.87543023767799e-05 3.28251714872887e-05 -4.71294992715358e-06 -4.25692521102296e-06 9.49956373276984e-06 1.13497156236741e-05 3.28251714872887e-05 5.66075095410517e-05 -2.97993616472025e-06 -4.21317769256853e-07 -1.29041280399465e-05 3.03320494934043e-05 -4.71294992715358e-06 -2.97993616472025e-06 1.51004321306904e-05 9.50193244753568e-07 2.39610996947963e-06 -1.77181476978465e-07 -4.25692521102296e-06 -4.21317769256853e-07 9.50193244753568e-07 2.69236336829746e-05 -5.44532180556072e-06 1.75104772728623e-05 9.49956373276984e-06 -1.29041280399465e-05 2.39610996947963e-06 -5.44532180556072e-06 7.66995733454135e-05 -4.34325431909249e-05 1.13497156236741e-05 3.03320494934043e-05 -1.77181476978465e-07 1.75104772728623e-05 -4.34325431909249e-05 0.000212863308167863 0 0 0 0 478 0 0 0 0 462 0 0 0 0 0 0 0 0 476 0 0 0 0 0 1453 +1061 1149 0.940567457888561 -0.336251947418254 -0.0476181164944879 0.105154243800218 0.335136148694155 0.941692481390076 -0.029983867860078 -0.0365124517051131 0.0549237562398988 0.0122432982007878 0.998415485982498 0.0954515982462797 6.26645651045302e-05 8.49439279174789e-06 -8.14870688617138e-06 9.82165743600169e-06 -1.47878629243938e-05 5.61084367547433e-05 8.49439279174789e-06 6.40647375794155e-05 -1.58436115213577e-06 1.76766781870416e-06 6.60770012110166e-06 -3.92251945543322e-07 -8.14870688617138e-06 -1.58436115213577e-06 1.44326263006595e-05 3.15278160237299e-06 1.52141611972209e-06 -1.67437263115424e-06 9.82165743600169e-06 1.76766781870416e-06 3.15278160237299e-06 2.24854762193847e-05 -1.13003087108061e-05 2.01282786873207e-05 -1.47878629243938e-05 6.60770012110166e-06 1.52141611972209e-06 -1.13003087108061e-05 8.20334309219935e-05 -2.45838065454426e-05 5.61084367547433e-05 -3.92251945543322e-07 -1.67437263115424e-06 2.01282786873207e-05 -2.45838065454426e-05 0.000167910014023306 0 0 0 0 630 0 0 0 0 614 0 0 0 0 0 0 0 0 1003 0 0 0 0 0 2124 +1061 1152 0.989548482792215 -0.141924027153475 -0.0255219654447855 0.0979640584516923 0.141665904389141 0.989845835969622 -0.0116615842494152 -0.193067045486221 0.0269178702209481 0.00792411068443847 0.999606240843178 -0.199857261887164 3.84119456879338e-05 2.90574333180221e-05 2.03236281240499e-06 -4.05432845458358e-07 -1.09722640152568e-07 -2.26102360746743e-06 2.90574333180221e-05 4.87839444353682e-05 3.415234331944e-07 5.59682361957595e-06 -4.62492972500729e-06 1.03237850082859e-05 2.03236281240499e-06 3.415234331944e-07 1.04242812562423e-05 2.68192463250697e-06 3.3133840300956e-06 -7.57203328349677e-07 -4.05432845458358e-07 5.59682361957595e-06 2.68192463250697e-06 3.1775259970621e-05 -2.06882635960531e-05 1.68766962491066e-05 -1.09722640152568e-07 -4.62492972500729e-06 3.3133840300956e-06 -2.06882635960531e-05 6.09951756441729e-05 -1.88911333900891e-05 -2.26102360746743e-06 1.03237850082859e-05 -7.57203328349677e-07 1.68766962491066e-05 -1.88911333900891e-05 0.000107862286712209 754 781 0 0 208 754 781 0 0 165 0 0 0 0 0 0 0 0 1419 0 0 0 0 0 3241 +1061 1063 0.983504341298651 -0.166872742420034 0.0698047167741809 0.0625538216199807 0.165360594702884 0.98586493004299 0.0269483474602545 0.0243298166313806 -0.0733149668636292 -0.0149608672391399 0.99719661455765 0.12820165324243 4.4333467985845e-05 1.59166843304592e-05 -3.23241696756199e-06 -3.72889009827956e-06 5.75152347697176e-06 2.82604185869419e-05 1.59166843304592e-05 4.18017320385757e-05 4.81825194619769e-08 -5.25118954408533e-07 3.76092620816269e-06 -4.63649370869873e-06 -3.23241696756199e-06 4.81825194619769e-08 1.6369312513833e-05 -1.90746553276134e-06 -2.87006202750076e-07 -8.91603790087774e-07 -3.72889009827956e-06 -5.25118954408533e-07 -1.90746553276134e-06 3.50918733444817e-05 -2.00215561256787e-05 -1.13420033910845e-05 5.75152347697176e-06 3.76092620816269e-06 -2.87006202750076e-07 -2.00215561256787e-05 7.04190719461336e-05 -3.3613656337653e-06 2.82604185869419e-05 -4.63649370869873e-06 -8.91603790087774e-07 -1.13420033910845e-05 -3.3613656337653e-06 0.000156321412752877 256 363 0 0 342 256 363 0 0 315 0 0 0 0 0 0 0 0 1099 0 0 0 0 0 2790 +1061 1151 0.974879624674243 -0.219407189908085 -0.0383432185874444 0.13020138330343 0.218786785342391 0.975572971887116 -0.0197413039813333 -0.174548386822019 0.0417379917407361 0.0108564054814748 0.999069606436645 -0.107840277419024 6.14025173877796e-05 4.91774261697209e-05 -1.43804293392265e-06 9.9116354103269e-06 -1.326734794757e-05 2.76172724491357e-05 4.91774261697209e-05 8.25941825953882e-05 8.68139346845884e-07 3.07291324041074e-06 2.77724857343075e-06 4.11820266452015e-05 -1.43804293392265e-06 8.68139346845884e-07 1.23987153041964e-05 3.05547035507176e-06 1.83945317640238e-06 2.25136556654298e-06 9.9116354103269e-06 3.07291324041074e-06 3.05547035507176e-06 3.37829791898952e-05 -3.08739266757358e-05 2.02399932925308e-05 -1.326734794757e-05 2.77724857343075e-06 1.83945317640238e-06 -3.08739266757358e-05 0.000107039077884842 -2.72784854699846e-05 2.76172724491357e-05 4.11820266452015e-05 2.25136556654298e-06 2.02399932925308e-05 -2.72784854699846e-05 0.000198305631798841 377 460 0 0 505 377 460 0 0 464 0 0 0 0 0 0 0 0 1262 0 0 0 0 0 3070 +1062 1149 0.964065875610676 -0.251550262922875 -0.0854368345999096 0.0553513786244577 0.250146877332182 0.967833357248244 -0.0269282817600998 -0.040101975836159 0.0894624348203078 0.00458888014942804 0.995979625762995 0.0406649407036353 4.43615401379085e-05 9.85382867701043e-06 -9.05673994537162e-06 7.82637941655744e-06 1.35844663108027e-06 2.15994135813884e-05 9.85382867701043e-06 6.1836299775115e-05 -2.19210212940739e-06 1.01058763865753e-06 1.04112883648472e-05 -4.92698179824592e-06 -9.05673994537162e-06 -2.19210212940739e-06 1.52172291885726e-05 -1.66238848711181e-06 1.55397968161508e-06 -1.40466035792183e-06 7.82637941655744e-06 1.01058763865753e-06 -1.66238848711181e-06 2.60240637017691e-05 -1.65350931679422e-05 4.40124833941711e-06 1.35844663108027e-06 1.04112883648472e-05 1.55397968161508e-06 -1.65350931679422e-05 8.70746043030455e-05 4.1149587950155e-06 2.15994135813884e-05 -4.92698179824592e-06 -1.40466035792183e-06 4.40124833941711e-06 4.1149587950155e-06 6.61654097214619e-05 0 0 0 0 397 0 0 0 0 444 0 0 0 0 0 0 0 0 1101 0 0 0 0 0 2501 +1062 1064 0.989363256981011 -0.140259990057935 0.0385678742592094 0.0415453578053441 0.13885791424043 0.989624044077764 0.0369151870639941 0.0295309600076142 -0.0433454194664641 -0.0311670751293755 0.998573877106324 0.105275454762716 3.09116826403442e-05 1.66997577833811e-05 -1.00471733976019e-06 -4.24300269136794e-06 5.15290274306373e-06 2.01234365396697e-05 1.66997577833811e-05 4.22925189694077e-05 1.03838909708507e-06 1.94774952083031e-06 9.63321736404848e-06 -5.86817585361656e-06 -1.00471733976019e-06 1.03838909708507e-06 1.44076617701241e-05 3.10038618067149e-06 8.78360662222617e-07 -2.99596321748317e-06 -4.24300269136794e-06 1.94774952083031e-06 3.10038618067149e-06 3.35616660644041e-05 -2.05988957436962e-05 -1.00769970516587e-05 5.15290274306373e-06 9.63321736404848e-06 8.78360662222617e-07 -2.05988957436962e-05 8.1878598190758e-05 2.10681847690439e-06 2.01234365396697e-05 -5.86817585361656e-06 -2.99596321748317e-06 -1.00769970516587e-05 2.10681847690439e-06 9.15256558622876e-05 0 101 0 0 310 0 101 0 0 354 0 0 0 0 0 0 0 0 1162 0 0 0 0 0 2651 +1062 1150 0.974365377983616 -0.205293629671651 -0.0920143239016814 0.0638597907138498 0.203637950199252 0.978670108640916 -0.027136759044249 -0.109415338679979 0.0956226721310978 0.00770351017509158 0.995387844262472 -0.0676785242268001 3.12812702461061e-05 1.21293379160329e-05 -8.85161782908594e-06 -2.17134049529779e-06 1.8605187015921e-05 1.05914862091834e-06 1.21293379160329e-05 6.32651356253046e-05 1.66837225280602e-06 -4.44605664124132e-06 3.9779493855841e-06 -1.79186922472533e-05 -8.85161782908594e-06 1.66837225280602e-06 1.85070920948647e-05 -3.42920265681793e-06 -8.01188671783403e-06 -4.91523699378568e-06 -2.17134049529779e-06 -4.44605664124132e-06 -3.42920265681793e-06 4.03668725675502e-05 -5.39192743171307e-05 -1.52871240127413e-06 1.8605187015921e-05 3.9779493855841e-06 -8.01188671783403e-06 -5.39192743171307e-05 0.000177875764451335 2.58391751356038e-05 1.05914862091834e-06 -1.79186922472533e-05 -4.91523699378568e-06 -1.52871240127413e-06 2.58391751356038e-05 7.29779931666378e-05 23 155 0 0 298 23 155 0 0 348 0 0 0 0 0 0 0 0 1199 0 0 0 0 0 3003 +1062 1148 0.963413688490805 -0.261072210778428 -0.0606247935073236 0.073443559371773 0.260717934392376 0.965316064096072 -0.0138222676952789 -0.0179666667179157 0.0621306970403045 -0.00248940903257782 0.998064917391627 0.116332780779541 4.06031790415411e-05 1.86868308866189e-05 -5.76551280355994e-06 -1.06871838311055e-06 2.24378398848743e-06 3.76436927557942e-06 1.86868308866189e-05 7.41886219317008e-05 -1.47445868966012e-07 3.16074704437803e-06 6.86509884308733e-06 -3.28242519048147e-06 -5.76551280355994e-06 -1.47445868966012e-07 1.45085556113912e-05 3.03891224658264e-06 4.19637504661754e-06 -4.09584881105493e-07 -1.06871838311055e-06 3.16074704437803e-06 3.03891224658264e-06 2.08167070421336e-05 5.11885727036016e-06 6.048714356301e-06 2.24378398848743e-06 6.86509884308733e-06 4.19637504661754e-06 5.11885727036016e-06 4.70971262608884e-05 -3.40711574133207e-06 3.76436927557942e-06 -3.28242519048147e-06 -4.09584881105493e-07 6.048714356301e-06 -3.40711574133207e-06 5.94345163116498e-05 0 0 0 0 353 0 0 0 0 393 0 0 0 0 0 0 0 0 971 0 0 0 0 0 2287 +1062 1151 0.988442038948131 -0.133144678561763 -0.0724902076886705 0.0476635544293008 0.133393460794755 0.991062141257813 -0.00142013473917763 -0.142216428550707 0.0720313838355195 -0.00826599880014852 0.997368113088932 -0.161434085377644 5.00493557941617e-05 2.99903802293207e-05 -1.08763458825299e-06 -2.58672955976993e-06 6.43363844643128e-06 4.33237771734172e-05 2.99903802293207e-05 5.38937875008494e-05 -2.17915346880516e-06 3.50882732488172e-06 1.0530641737403e-05 3.02649352162612e-05 -1.08763458825299e-06 -2.17915346880516e-06 1.40451055448818e-05 1.62568106782479e-06 1.48033359314299e-06 -2.59885444585506e-06 -2.58672955976993e-06 3.50882732488172e-06 1.62568106782479e-06 3.07780592229889e-05 -1.4615224634203e-05 3.92569004681514e-06 6.43363844643128e-06 1.0530641737403e-05 1.48033359314299e-06 -1.4615224634203e-05 8.14611169269046e-05 9.31910665811658e-06 4.33237771734172e-05 3.02649352162612e-05 -2.59885444585506e-06 3.92569004681514e-06 9.31910665811658e-06 0.000217880388007782 377 460 0 0 96 377 460 0 0 150 0 0 0 0 0 0 0 0 1245 0 0 0 0 0 3012 +1062 1105 0.96523324610585 -0.261239391140333 0.00887474667761086 0.0835314086540073 0.261380278275639 0.964346313126103 -0.0414311294637342 0.00471550790936004 0.00226511379688004 0.0423103873383316 0.999101946941736 0.272704896408662 4.09854237758512e-05 2.18035746644845e-05 -3.95555177858487e-06 -1.34876684604981e-06 -4.69777446244186e-06 2.40204539985545e-05 2.18035746644845e-05 5.18969212639431e-05 -1.05568976685419e-06 5.10503655063524e-07 -1.89011917078043e-06 7.74255234540992e-06 -3.95555177858487e-06 -1.05568976685419e-06 1.49044888928514e-05 1.34898327477413e-06 1.58713866757851e-06 3.9461147873316e-06 -1.34876684604981e-06 5.10503655063524e-07 1.34898327477413e-06 2.05689249350333e-05 -8.72713279473031e-07 -2.88104416115873e-07 -4.69777446244186e-06 -1.89011917078043e-06 1.58713866757851e-06 -8.72713279473031e-07 5.11649817410818e-05 -6.63853363736595e-06 2.40204539985545e-05 7.74255234540992e-06 3.9461147873316e-06 -2.88104416115873e-07 -6.63853363736595e-06 8.44373785813401e-05 0 0 0 0 279 0 0 0 0 312 0 0 0 0 0 0 0 0 624 0 0 0 0 0 1900 +1062 1106 0.965236219018024 -0.26117071447592 0.010435487335379 0.0857563130659048 0.261378496099891 0.964377498195581 -0.0407102290658163 0.00437522791140011 0.000568570442653113 0.0420225995646371 0.999116498639414 0.268088323747883 3.0931845534192e-05 2.01778683288464e-05 -5.94631462633439e-06 -7.26435401632198e-07 1.21035354822606e-06 3.29521562716993e-06 2.01778683288464e-05 4.9742261875159e-05 -3.35732914858974e-06 2.9574874949301e-06 -3.96170058878722e-06 -3.20264851764009e-06 -5.94631462633439e-06 -3.35732914858974e-06 1.37214621436517e-05 3.23861215805018e-06 3.2132569036711e-06 3.01395936777948e-07 -7.26435401632198e-07 2.9574874949301e-06 3.23861215805018e-06 2.14982605291132e-05 1.21671759907582e-06 3.76188190744474e-06 1.21035354822606e-06 -3.96170058878722e-06 3.2132569036711e-06 1.21671759907582e-06 5.07214357509584e-05 -3.47931616335846e-06 3.29521562716993e-06 -3.20264851764009e-06 3.01395936777948e-07 3.76188190744474e-06 -3.47931616335846e-06 6.11514975688383e-05 0 0 0 0 275 0 0 0 0 307 0 0 0 0 0 0 0 0 641 0 0 0 0 0 1893 +1062 1110 0.965330837747896 -0.260930332328883 0.0071927299186798 0.0849298830066779 0.261006468169628 0.964513684722749 -0.0398619562510702 0.00314009305404494 0.00346370705478974 0.0403573246546883 0.999179307772211 0.270028487516698 4.64848635517977e-05 9.6349861877555e-06 -8.88568129265439e-06 6.48731738447234e-06 -1.19121753385179e-05 4.21531450585951e-05 9.6349861877555e-06 6.66131093961112e-05 -3.04635576433418e-06 2.70840467104305e-06 6.85607974989018e-06 -1.28989464713194e-05 -8.88568129265439e-06 -3.04635576433418e-06 1.51820177390647e-05 -3.58485880883785e-07 1.64411481028885e-06 -4.28671640078938e-06 6.48731738447234e-06 2.70840467104305e-06 -3.58485880883785e-07 2.32221383007498e-05 -1.17157942105765e-06 1.17331979775953e-05 -1.19121753385179e-05 6.85607974989018e-06 1.64411481028885e-06 -1.17157942105765e-06 6.20049905145383e-05 -1.55119900493337e-05 4.21531450585951e-05 -1.28989464713194e-05 -4.28671640078938e-06 1.17331979775953e-05 -1.55119900493337e-05 0.000120816994863063 0 0 0 0 276 0 0 0 0 311 0 0 0 0 0 0 0 0 617 0 0 0 0 0 1864 +1062 1101 0.965340928511757 -0.260677544420615 0.0128105259415041 0.0833436708932971 0.260987551612404 0.964451170844057 -0.041466094111831 0.00628256400216787 -0.00154584715362555 0.0433723055920111 0.999057782845522 0.274611196970987 5.57373592310745e-05 4.19725987652058e-05 -5.50151911350057e-06 3.55832406458366e-06 -1.09326801140676e-05 1.78126183748429e-05 4.19725987652058e-05 8.39807076480828e-05 -2.02687970138573e-07 2.90843268882262e-06 -1.42324324689081e-05 3.00976934929007e-06 -5.50151911350057e-06 -2.02687970138573e-07 1.41425449871665e-05 1.60158022131142e-06 9.04898414618476e-07 2.07919549640171e-06 3.55832406458366e-06 2.90843268882262e-06 1.60158022131142e-06 2.31223959462203e-05 -7.13839131556779e-06 1.06769994106822e-05 -1.09326801140676e-05 -1.42324324689081e-05 9.04898414618476e-07 -7.13839131556779e-06 7.77928580959355e-05 -2.13043760674937e-05 1.78126183748429e-05 3.00976934929007e-06 2.07919549640171e-06 1.06769994106822e-05 -2.13043760674937e-05 8.2446078581821e-05 0 0 0 0 280 0 0 0 0 304 0 0 0 0 0 0 0 0 543 0 0 0 0 0 1882 +1062 1112 0.965407829002222 -0.260698209782004 0.00491600627289599 0.0914495085591299 0.260571309583406 0.963907725902336 -0.0546304728862572 -0.013614274095762 0.00950349005396276 0.054021656418935 0.998494538950789 0.287352655541929 5.63420286962229e-05 3.77616668819997e-05 -3.36394299041069e-06 3.08323518531869e-06 -1.61720976437711e-06 3.16717873254481e-05 3.77616668819997e-05 6.91814950162168e-05 -3.69250482183013e-06 9.58371303892213e-06 -8.52105108167917e-06 2.16575455076412e-05 -3.36394299041069e-06 -3.69250482183013e-06 1.4293476496043e-05 2.12940384751946e-06 2.1124022543467e-06 5.44257135665616e-07 3.08323518531869e-06 9.58371303892213e-06 2.12940384751946e-06 2.2651225156983e-05 -1.76875063875568e-06 6.17008006202465e-06 -1.61720976437711e-06 -8.52105108167917e-06 2.1124022543467e-06 -1.76875063875568e-06 6.73742550817423e-05 -1.26179948650878e-05 3.16717873254481e-05 2.16575455076412e-05 5.44257135665616e-07 6.17008006202465e-06 -1.26179948650878e-05 0.000103934949071384 0 0 0 0 279 0 0 0 0 302 0 0 0 0 0 0 0 0 539 0 0 0 0 0 1990 +1062 1109 0.96553898938192 -0.260215871244453 0.00470747658848794 0.0844745925102865 0.260184862624226 0.964677985260953 -0.0412337484844861 0.00731737203588061 0.00618847675551956 0.0410376059896215 0.999138437680228 0.269603305251242 4.32504810713143e-05 2.70002381927462e-05 -4.44609813321934e-06 4.10071051492578e-06 -3.02463418095603e-06 9.99611494034852e-06 2.70002381927462e-05 6.35089919708198e-05 -1.57201068837556e-06 5.06316955598472e-06 -9.25367162423269e-06 7.40505560405745e-07 -4.44609813321934e-06 -1.57201068837556e-06 1.40774121301246e-05 1.68133279633123e-06 3.32234916267685e-06 -2.05759300894282e-06 4.10071051492578e-06 5.06316955598472e-06 1.68133279633123e-06 2.25887072307149e-05 -1.13722519884316e-06 6.18981481118535e-06 -3.02463418095603e-06 -9.25367162423269e-06 3.32234916267685e-06 -1.13722519884316e-06 5.03421693859363e-05 -1.85747591294361e-05 9.99611494034852e-06 7.40505560405745e-07 -2.05759300894282e-06 6.18981481118535e-06 -1.85747591294361e-05 8.29349776148697e-05 0 0 0 0 281 0 0 0 0 307 0 0 0 0 0 0 0 0 652 0 0 0 0 0 1766 +1062 1111 0.965307679557864 -0.261014053108002 0.00726277266232527 0.0881422870354131 0.261070985187302 0.964260131766099 -0.0452143669617945 -0.00500626657844182 0.00479838305504954 0.0455418748687122 0.998950906277931 0.275074307409466 6.1314604832846e-05 4.61194017073633e-05 -5.2192033148539e-06 5.99924153655651e-06 -9.59209165804661e-06 2.53069414523667e-05 4.61194017073633e-05 9.58051784192203e-05 -3.2513592049555e-06 6.94794351750422e-06 -9.43454067147003e-06 -3.29093550986638e-06 -5.2192033148539e-06 -3.2513592049555e-06 1.52778799930746e-05 2.42292609361378e-06 2.76682218261636e-06 -2.05968941469844e-06 5.99924153655651e-06 6.94794351750422e-06 2.42292609361378e-06 2.30987410926535e-05 -8.54276601999856e-06 1.88856585219355e-06 -9.59209165804661e-06 -9.43454067147003e-06 2.76682218261636e-06 -8.54276601999856e-06 7.50089086406864e-05 -1.18446426494388e-05 2.53069414523667e-05 -3.29093550986638e-06 -2.05968941469844e-06 1.88856585219355e-06 -1.18446426494388e-05 9.90198408215707e-05 0 0 0 0 270 0 0 0 0 309 0 0 0 0 0 0 0 0 549 0 0 0 0 0 1855 +1062 1134 0.965415911009026 -0.260267579657813 0.015261249938227 0.110494218501035 0.260677816830885 0.964608078890557 -0.0397282009579158 -0.0266666826209117 -0.00438116227690577 0.0423325066365434 0.99909397170585 0.263970776195445 9.07556601229159e-05 5.29187536251968e-05 -3.0941873189767e-06 -6.69714474587172e-06 7.23229872405992e-06 9.00389723389532e-05 5.29187536251968e-05 9.59331065692231e-05 6.66282454814505e-07 7.41265180898625e-06 -2.63250067270684e-05 4.98607367537523e-05 -3.0941873189767e-06 6.66282454814505e-07 1.45110020347058e-05 1.41804031929297e-06 -3.73652758914186e-07 5.75120884932085e-06 -6.69714474587172e-06 7.41265180898625e-06 1.41804031929297e-06 4.77232588396275e-05 -7.38747235265949e-05 -6.06714405238857e-06 7.23229872405992e-06 -2.63250067270684e-05 -3.73652758914186e-07 -7.38747235265949e-05 0.000256454424554938 -9.72183049524766e-06 9.00389723389532e-05 4.98607367537523e-05 5.75120884932085e-06 -6.06714405238857e-06 -9.72183049524766e-06 0.000194504910448757 0 0 0 0 265 0 0 0 0 292 0 0 0 0 0 0 0 0 577 0 0 0 0 0 1937 +1062 1133 0.965468897003433 -0.260246414781048 0.0119001055703385 0.110070148363355 0.260518058230209 0.964528028191698 -0.0426148350764933 -0.0328907171409236 -0.000387627315888628 0.0442434902132043 0.999020702147267 0.26803904448284 4.88430776222107e-05 4.65259402573247e-05 -4.40031478309494e-06 -3.41846704198664e-07 -1.58334511199742e-06 3.49440641030759e-05 4.65259402573247e-05 7.76892495340874e-05 -1.58176082559366e-06 -6.46543386302433e-06 1.61008852759552e-05 3.93029076010182e-05 -4.40031478309494e-06 -1.58176082559366e-06 1.42850601857983e-05 7.76438007812516e-07 4.19199111212447e-07 7.4940890304778e-06 -3.41846704198664e-07 -6.46543386302433e-06 7.76438007812516e-07 3.97125489461903e-05 -6.03801500420577e-05 6.6985525751563e-07 -1.58334511199742e-06 1.61008852759552e-05 4.19199111212447e-07 -6.03801500420577e-05 0.000222865889894931 -9.56089777331675e-06 3.49440641030759e-05 3.93029076010182e-05 7.4940890304778e-06 6.6985525751563e-07 -9.56089777331675e-06 0.000135829244310239 0 0 0 0 264 0 0 0 0 297 0 0 0 0 0 0 0 0 553 0 0 0 0 0 1839 +1063 1148 0.977744962781668 -0.185205819796997 -0.0985575571348887 0.0322704595781642 0.182852383487456 0.98260378186672 -0.0324778957781279 -0.0144384007652756 0.102858123685157 0.013733614765997 0.994601223716032 0.0682230397678352 3.52400125074004e-05 1.34597663578346e-05 -8.12779472946427e-06 8.44109934306208e-08 5.13640626080457e-06 1.85363807644448e-05 1.34597663578346e-05 7.65732857703135e-05 2.28743947969765e-06 -2.22200119209599e-07 -1.56292485980889e-05 -9.81885368876264e-06 -8.12779472946427e-06 2.28743947969765e-06 1.65601442513922e-05 -2.82688527813506e-06 -5.03839978726876e-06 -3.2411109840636e-06 8.44109934306208e-08 -2.22200119209599e-07 -2.82688527813506e-06 2.50733705658027e-05 -3.54820325746076e-06 6.5465712345027e-06 5.13640626080457e-06 -1.56292485980889e-05 -5.03839978726876e-06 -3.54820325746076e-06 8.3035181979701e-05 1.98663043701173e-05 1.85363807644448e-05 -9.81885368876264e-06 -3.2411109840636e-06 6.5465712345027e-06 1.98663043701173e-05 7.73818251998564e-05 0 0 0 0 67 0 0 0 0 161 0 0 0 0 0 0 0 0 1071 0 0 0 0 0 2527 +1063 1065 0.992619269774094 -0.121073265017812 -0.00694620551603754 0.0253417767291794 0.121148807152868 0.992564896497288 0.0117427750879465 0.0221649141864403 0.00547282363880719 -0.0124976293454255 0.999906924399548 0.0905013921254015 4.92977734771495e-05 3.93901105513168e-05 1.81268973616276e-07 7.08100561360199e-06 -6.6227810363027e-06 2.83504333303468e-05 3.93901105513168e-05 6.13264025764626e-05 6.67126889749128e-07 1.01314591887188e-05 -1.13570864536901e-05 8.81609814457689e-06 1.81268973616276e-07 6.67126889749128e-07 1.32075159188788e-05 -8.93557662483399e-07 -1.72217574060267e-06 2.07666746312878e-06 7.08100561360199e-06 1.01314591887188e-05 -8.93557662483399e-07 3.68936241814676e-05 -4.20055653179907e-05 1.63787018228384e-06 -6.6227810363027e-06 -1.13570864536901e-05 -1.72217574060267e-06 -4.20055653179907e-05 0.000124643304131064 -3.62445601562926e-06 2.83504333303468e-05 8.81609814457689e-06 2.07666746312878e-06 1.63787018228384e-06 -3.62445601562926e-06 9.08925118110306e-05 0 0 0 0 142 0 0 0 0 241 0 0 0 0 0 0 0 0 1203 0 0 0 0 0 2690 +1063 1149 0.978036468545077 -0.17629533576992 -0.11119631640322 0.0219871822195503 0.173861752712033 0.984272775327732 -0.0312920867400122 -0.038623944339395 0.11496415589119 0.0112720155436221 0.993305685338512 -0.0337242661177587 3.67872416417818e-05 -3.0100059730085e-06 -1.14678905414429e-05 4.89447850777188e-06 9.00391291274954e-06 1.96957321362328e-05 -3.0100059730085e-06 6.95892455109648e-05 2.2944936292237e-06 1.5305377356251e-06 2.24563866808066e-06 -1.22288647092572e-05 -1.14678905414429e-05 2.2944936292237e-06 1.50980562241251e-05 7.76578818105149e-08 -5.3606615350274e-07 -3.47130630100765e-06 4.89447850777188e-06 1.5305377356251e-06 7.76578818105149e-08 2.85672637793771e-05 -1.20606384013908e-05 2.67648710879447e-06 9.00391291274954e-06 2.24563866808066e-06 -5.3606615350274e-07 -1.20606384013908e-05 8.38845725999831e-05 6.61699614824562e-06 1.96957321362328e-05 -1.22288647092572e-05 -3.47130630100765e-06 2.67648710879447e-06 6.61699614824562e-06 5.52151538876547e-05 0 0 0 0 46 0 0 0 0 148 0 0 0 0 0 0 0 0 1116 0 0 0 0 0 2719 +1062 1136 0.96545780738291 -0.260417234228496 0.00860733873882679 0.101847462385644 0.260552042598119 0.964654555355794 -0.0394236214630554 -0.0184493039177259 0.00196348194078039 0.0403045028265505 0.999185514201729 0.271404093970626 0.000119702282076858 4.99370216139141e-05 -3.52641005968933e-06 5.33434861927846e-06 -2.71380380640469e-05 0.000171803654601535 4.99370216139141e-05 0.000100248898803677 -1.37950512025407e-06 -4.38397168227336e-06 2.03485802251821e-05 3.81217348074481e-05 -3.52641005968933e-06 -1.37950512025407e-06 1.47889684088032e-05 -3.33975339146887e-07 4.35271266915424e-06 -2.04423402305305e-06 5.33434861927846e-06 -4.38397168227336e-06 -3.33975339146887e-07 3.60505714323006e-05 -3.9013161152804e-05 2.1015894794915e-05 -2.71380380640469e-05 2.03485802251821e-05 4.35271266915424e-06 -3.9013161152804e-05 0.000151640216513902 -7.12298870653301e-05 0.000171803654601535 3.81217348074481e-05 -2.04423402305305e-06 2.1015894794915e-05 -7.12298870653301e-05 0.000371662479693876 0 0 0 0 270 0 0 0 0 297 0 0 0 0 0 0 0 0 616 0 0 0 0 0 1983 +1063 1147 0.98165325689925 -0.169511217982906 -0.0873088208432973 0.051787789236006 0.16645981516459 0.985188317836175 -0.0411716933644737 -0.0139017024439024 0.0929946942274987 0.0258829167034793 0.995330126876734 0.14753409309523 3.36672731091373e-05 9.04358585119446e-06 -4.5140536460557e-06 1.89036886415642e-06 -2.43430333803867e-06 8.09846050333029e-06 9.04358585119446e-06 8.09581384868227e-05 4.85415186659753e-06 4.92025847289923e-06 -1.94760711727599e-05 -3.38909854781326e-05 -4.5140536460557e-06 4.85415186659753e-06 1.61003336197133e-05 -9.14130554050403e-07 -2.14214335529321e-06 -1.98398354286734e-06 1.89036886415642e-06 4.92025847289923e-06 -9.14130554050403e-07 2.45376842027247e-05 -1.3694917878331e-05 1.95616616000174e-06 -2.43430333803867e-06 -1.94760711727599e-05 -2.14214335529321e-06 -1.3694917878331e-05 8.95757516835361e-05 6.52544829124832e-07 8.09846050333029e-06 -3.38909854781326e-05 -1.98398354286734e-06 1.95616616000174e-06 6.52544829124832e-07 6.53496611840988e-05 0 0 0 0 48 0 0 0 0 119 0 0 0 0 0 0 0 0 957 0 0 0 0 0 2301 +1063 1150 0.98357566507499 -0.129268372786773 -0.125970627010236 0.0133546409021804 0.125993691824316 0.99145985623185 -0.0336592201513737 -0.0828256141014526 0.129245892363245 0.0172348854878494 0.991462787011923 -0.130147566751803 3.86306459202166e-05 2.99596474259073e-05 -2.1148805920428e-06 -1.30204785123203e-06 1.32097059595791e-05 1.11506151448701e-05 2.99596474259073e-05 5.3584040904378e-05 1.58390397138117e-06 -2.23087164780692e-06 1.33350251878382e-05 4.55195519879293e-06 -2.1148805920428e-06 1.58390397138117e-06 1.74698259381722e-05 -5.34373542910332e-06 1.03931079258116e-06 -1.45517477766935e-06 -1.30204785123203e-06 -2.23087164780692e-06 -5.34373542910332e-06 3.5811097294981e-05 -1.771496078179e-05 5.25783108663727e-06 1.32097059595791e-05 1.33350251878382e-05 1.03931079258116e-06 -1.771496078179e-05 9.75719705337532e-05 2.44487524006748e-05 1.11506151448701e-05 4.55195519879293e-06 -1.45517477766935e-06 5.25783108663727e-06 2.44487524006748e-05 0.000108002519225015 23 132 0 0 4 23 155 0 0 68 0 0 0 0 0 0 0 0 1195 0 0 0 0 0 3326 +1062 1135 0.96551304041243 -0.260059442906989 0.0123957633267044 0.101386630894891 0.260343074964796 0.964824925175746 -0.0365287157930745 -0.0164886113088479 -0.00246010394492913 0.038496102588743 0.999255722012167 0.254481782515534 4.3679941284108e-05 3.55095988911568e-05 -5.86005769160331e-06 8.90801664420792e-06 -2.58315331512356e-05 3.46271398099662e-05 3.55095988911568e-05 7.22451983165636e-05 -4.80647445666927e-06 1.16604903687947e-05 -3.04800941150197e-05 2.25920893752195e-05 -5.86005769160331e-06 -4.80647445666927e-06 1.32453925407854e-05 2.60539384850214e-06 -1.45604448582554e-06 3.27077230624361e-06 8.90801664420792e-06 1.16604903687947e-05 2.60539384850214e-06 4.03798332932357e-05 -6.77697275513452e-05 2.79684266850917e-05 -2.58315331512356e-05 -3.04800941150197e-05 -1.45604448582554e-06 -6.77697275513452e-05 0.00026128623882887 -7.82081614655449e-05 3.46271398099662e-05 2.25920893752195e-05 3.27077230624361e-06 2.79684266850917e-05 -7.82081614655449e-05 0.00013428512191305 0 0 0 0 266 0 0 0 0 295 0 0 0 0 0 0 0 0 643 0 0 0 0 0 1935 +1062 1137 0.965340888684002 -0.260701984254364 0.0123062602206563 0.0908003421732747 0.260990144824153 0.964449888683762 -0.0414795916390987 -0.000427268402837376 -0.00105495945355159 0.0432537584923698 0.99906356125966 0.269484161461661 3.04338314434138e-05 1.29643674592822e-05 -6.09279802322786e-06 1.63813353640731e-06 1.19163370057462e-06 1.68265626367796e-05 1.29643674592822e-05 4.95209053528403e-05 -2.16184564957932e-06 7.76627452553465e-06 -8.50381062242531e-06 -1.29107980978578e-05 -6.09279802322786e-06 -2.16184564957932e-06 1.42127927214319e-05 2.7146677576241e-06 3.99342666485085e-06 -1.51730359684389e-07 1.63813353640731e-06 7.76627452553465e-06 2.7146677576241e-06 2.72795044276092e-05 -1.9166735586314e-05 4.56761287884778e-06 1.19163370057462e-06 -8.50381062242531e-06 3.99342666485085e-06 -1.9166735586314e-05 9.75461878138352e-05 2.3474441649257e-06 1.68265626367796e-05 -1.29107980978578e-05 -1.51730359684389e-07 4.56761287884778e-06 2.3474441649257e-06 7.46884502985701e-05 0 0 0 0 277 0 0 0 0 313 0 0 0 0 0 0 0 0 656 0 0 0 0 0 1924 +1063 1104 0.981924435064807 -0.188128378289363 -0.0207874266053563 0.0462021065732695 0.186536998626841 0.980482155556213 -0.0621183610467286 0.000239855792075848 0.0320679273722005 0.0571179124098218 0.997852289728292 0.216792206681448 7.24587133902241e-05 4.91315785918297e-05 2.21701693518543e-06 -2.23822953446949e-06 -4.16574680826385e-06 8.58237734031606e-05 4.91315785918297e-05 7.88954827887249e-05 4.7935423721502e-06 1.97881470663388e-06 1.48622114496875e-06 5.46880649608202e-05 2.21701693518543e-06 4.7935423721502e-06 1.57716928826778e-05 -1.62340383160008e-07 -9.07586330798301e-07 1.05872962574396e-05 -2.23822953446949e-06 1.97881470663388e-06 -1.62340383160008e-07 2.44774049180158e-05 1.49870685862803e-06 -3.03324291794486e-09 -4.16574680826385e-06 1.48622114496875e-06 -9.07586330798301e-07 1.49870685862803e-06 5.83141259949683e-05 -9.7327883238899e-06 8.58237734031606e-05 5.46880649608202e-05 1.05872962574396e-05 -3.03324291794486e-09 -9.7327883238899e-06 0.000241569068304096 0 0 0 0 49 0 0 0 0 108 0 0 0 0 0 0 0 0 659 0 0 0 0 0 2107 +1063 1105 0.982102717112565 -0.187000020183259 -0.022477666506495 0.0469962656615297 0.18554092850959 0.981081675489028 -0.0552567630923114 0.00180479092490904 0.0323854425307996 0.0500972900574603 0.998219136583237 0.204369456229812 4.36731915297878e-05 3.09782014877636e-05 -5.36931046718314e-07 -2.07414071116406e-06 -3.48542795765792e-06 3.50059864223447e-05 3.09782014877636e-05 5.89426293396518e-05 3.09438589020514e-06 -2.18919638075271e-06 1.42889665975477e-06 1.99771888746262e-05 -5.36931046718314e-07 3.09438589020514e-06 1.49170720359693e-05 9.89842244730305e-08 8.1635146007787e-07 4.83051539645926e-06 -2.07414071116406e-06 -2.18919638075271e-06 9.89842244730305e-08 1.91420905254967e-05 3.26703001008497e-06 -2.3744376425189e-06 -3.48542795765792e-06 1.42889665975477e-06 8.1635146007787e-07 3.26703001008497e-06 5.63945150178295e-05 2.45293258893897e-08 3.50059864223447e-05 1.99771888746262e-05 4.83051539645926e-06 -2.3744376425189e-06 2.45293258893897e-08 0.000128787352234823 0 0 0 0 57 0 0 0 0 118 0 0 0 0 0 0 0 0 700 0 0 0 0 0 2118 +1063 1109 0.982154245193141 -0.185909093518289 -0.0284753857972127 0.0487725614173648 0.183935052642096 0.9810509676506 -0.0608842777847482 -0.00152062899540519 0.039254745683058 0.0545601303061946 0.997738571531806 0.210429549522831 3.01076177658147e-05 1.76532675101857e-05 -4.80862805688547e-06 -9.9882992389978e-07 7.76418750765977e-06 -3.89061545161231e-06 1.76532675101857e-05 4.77213606327355e-05 1.0704618813193e-06 -1.20082640395948e-06 -1.26070165949615e-06 -8.34223470639165e-06 -4.80862805688547e-06 1.0704618813193e-06 1.44304009767318e-05 9.88143708367001e-07 5.63773422071148e-07 4.77423884688308e-08 -9.9882992389978e-07 -1.20082640395948e-06 9.88143708367001e-07 2.34756430534698e-05 -7.63167085266694e-06 -4.34310312568005e-07 7.76418750765977e-06 -1.26070165949615e-06 5.63773422071148e-07 -7.63167085266694e-06 7.79339033870202e-05 -8.43811518846186e-06 -3.89061545161231e-06 -8.34223470639165e-06 4.77423884688308e-08 -4.34310312568005e-07 -8.43811518846186e-06 5.19684923106799e-05 0 0 0 0 54 0 0 0 0 116 0 0 0 0 0 0 0 0 730 0 0 0 0 0 1988 +1063 1107 0.982058788945676 -0.185892041904612 -0.0316967476420903 0.0442745014856143 0.183772969085829 0.981124906358707 -0.0601781850507152 0.00118143848553094 0.0422851142594124 0.053273510107303 0.997684269813309 0.210153448578936 3.25088278332537e-05 1.80709594887717e-05 -6.5656811684095e-06 1.19049749412868e-06 1.20017912762478e-06 1.03628310742466e-05 1.80709594887717e-05 5.39479565320057e-05 -1.44070503187107e-06 1.53496162909465e-06 -4.81082939678187e-06 -1.55894589050319e-05 -6.5656811684095e-06 -1.44070503187107e-06 1.52381341727919e-05 -1.23600568999985e-06 -5.04463224391215e-07 -1.71906380047327e-06 1.19049749412868e-06 1.53496162909465e-06 -1.23600568999985e-06 2.26067675058428e-05 -1.80244594250582e-06 5.00377597839728e-06 1.20017912762478e-06 -4.81082939678187e-06 -5.04463224391215e-07 -1.80244594250582e-06 5.71568373475685e-05 2.23663612449818e-06 1.03628310742466e-05 -1.55894589050319e-05 -1.71906380047327e-06 5.00377597839728e-06 2.23663612449818e-06 6.95619359808927e-05 0 0 0 0 44 0 0 0 0 106 0 0 0 0 0 0 0 0 656 0 0 0 0 0 2064 +1063 1108 0.982115033645976 -0.186218035154485 -0.0278011523100325 0.0461643401011912 0.184280181855265 0.980985673601577 -0.0608927151952533 0.000365737892071087 0.038611853904639 0.0546804496293023 0.997757071218432 0.207106929708882 3.42244806795321e-05 1.09537767456339e-05 -6.48189801676617e-06 4.32463032546433e-06 1.06654325599244e-06 8.61933339531389e-06 1.09537767456339e-05 6.14915642654839e-05 -9.20030092475943e-07 2.04272511600884e-07 -2.44612285140903e-06 -2.70587654346837e-05 -6.48189801676617e-06 -9.20030092475943e-07 1.36371674081323e-05 -3.53430627055585e-07 1.5466331432473e-06 -3.03144961708551e-06 4.32463032546433e-06 2.04272511600884e-07 -3.53430627055585e-07 2.21964640516328e-05 -2.79148662294974e-06 3.64924395676062e-06 1.06654325599244e-06 -2.44612285140903e-06 1.5466331432473e-06 -2.79148662294974e-06 6.52084575176593e-05 -9.25002162811542e-06 8.61933339531389e-06 -2.70587654346837e-05 -3.03144961708551e-06 3.64924395676062e-06 -9.25002162811542e-06 7.70757992130078e-05 0 0 0 0 61 0 0 0 0 118 0 0 0 0 0 0 0 0 654 0 0 0 0 0 1987 +1063 1106 0.982042457691629 -0.187182176658486 -0.0235678601569468 0.0484869178193837 0.185524658838705 0.980837004802686 -0.0594926127555106 -0.00137142323633778 0.0342521861166251 0.0540518524297421 0.997950492256578 0.213553176932505 4.80587052610095e-05 2.67745270222629e-05 -2.38859292623332e-06 -6.63078953298271e-06 1.17653943213493e-05 2.99398150779415e-05 2.67745270222629e-05 7.44783425200028e-05 6.96618586160448e-06 -2.14338302989727e-06 -6.50066214018179e-06 8.85798855198741e-06 -2.38859292623332e-06 6.96618586160448e-06 1.60133439966427e-05 9.47147922385601e-07 -5.24869527460733e-07 4.39749597066106e-06 -6.63078953298271e-06 -2.14338302989727e-06 9.47147922385601e-07 2.12308784199685e-05 -8.58628779088061e-07 -4.63318429963319e-06 1.17653943213493e-05 -6.50066214018179e-06 -5.24869527460733e-07 -8.58628779088061e-07 5.56034322017492e-05 1.25826480933461e-05 2.99398150779415e-05 8.85798855198741e-06 4.39749597066106e-06 -4.63318429963319e-06 1.25826480933461e-05 9.39029680836102e-05 0 0 0 0 50 0 0 0 0 116 0 0 0 0 0 0 0 0 736 0 0 0 0 0 2117 +1063 1145 0.981943640656859 -0.185387026614402 -0.0376608143383157 0.0479853001864093 0.182445382186435 0.980684987386538 -0.0705027519570038 -0.000746383618413674 0.0500036907877796 0.0623586872675814 0.996800393774934 0.220174142053733 3.10985923147924e-05 1.2799149383431e-05 -3.14420381020584e-06 4.38035798399467e-06 -9.79498822384764e-06 1.02599936080644e-05 1.2799149383431e-05 5.47594854622791e-05 -1.22087284436154e-06 -6.79811168255697e-06 1.66307203805883e-05 -2.21166805554892e-05 -3.14420381020584e-06 -1.22087284436154e-06 1.21994495536037e-05 1.69081202201287e-06 -4.4467412040404e-06 2.06457756928415e-06 4.38035798399467e-06 -6.79811168255697e-06 1.69081202201287e-06 3.88591877052551e-05 -6.03036783091077e-05 1.19306940881796e-05 -9.79498822384764e-06 1.66307203805883e-05 -4.4467412040404e-06 -6.03036783091077e-05 0.000266572921049049 -5.1801600740113e-05 1.02599936080644e-05 -2.21166805554892e-05 2.06457756928415e-06 1.19306940881796e-05 -5.1801600740113e-05 7.52781651822897e-05 0 0 0 0 52 0 0 0 0 115 0 0 0 0 0 0 0 0 744 0 0 0 0 0 2154 +1063 1144 0.982158522350551 -0.186688364828193 -0.0226294368457797 0.0453397503407991 0.185099292825821 0.980948133888776 -0.0589831367045598 0.00658876689682292 0.0332097691886335 0.0537420976321507 0.998002453991239 0.20960865110853 2.85521434004548e-05 1.26921413277286e-05 -7.58857819982214e-06 -3.28245840013511e-06 6.7828564256053e-06 2.08880835906663e-07 1.26921413277286e-05 4.63394555861838e-05 -3.65839839271049e-06 5.03432650681362e-06 -6.16184389819215e-06 -1.10212805077588e-05 -7.58857819982214e-06 -3.65839839271049e-06 1.5000771386035e-05 2.56208834650303e-06 2.07070315581543e-06 4.43088846183699e-07 -3.28245840013511e-06 5.03432650681362e-06 2.56208834650303e-06 2.41256550593374e-05 -5.68049933192973e-06 -1.03078318766126e-07 6.7828564256053e-06 -6.16184389819215e-06 2.07070315581543e-06 -5.68049933192973e-06 6.15752522896246e-05 1.32457886832817e-05 2.08880835906663e-07 -1.10212805077588e-05 4.43088846183699e-07 -1.03078318766126e-07 1.32457886832817e-05 5.74336936643892e-05 0 0 0 0 62 0 0 0 0 124 0 0 0 0 0 0 0 0 722 0 0 0 0 0 2213 +1063 1111 0.982099812923899 -0.187190516799301 -0.0209682587558836 0.0552663251174886 0.185799915975216 0.981019576436427 -0.0554885742481738 -0.0139887159374749 0.0309572072132784 0.0505994176735556 0.998239124785565 0.20207135607612 3.66538202663386e-05 1.32197317059972e-05 -4.98534469818522e-06 -3.58081246846428e-07 6.36143547765161e-06 2.09976586496216e-05 1.32197317059972e-05 5.37566517952704e-05 6.42508629627027e-07 2.80518815743335e-06 -9.95899663422242e-06 -3.29746199909022e-06 -4.98534469818522e-06 6.42508629627027e-07 1.54251103572688e-05 2.66202831940486e-06 5.65623501930788e-07 -1.08589995047803e-06 -3.58081246846428e-07 2.80518815743335e-06 2.66202831940486e-06 2.5511684506193e-05 -9.45584293616036e-06 3.26333613932984e-06 6.36143547765161e-06 -9.95899663422242e-06 5.65623501930788e-07 -9.45584293616036e-06 8.18022343560913e-05 4.00834781001466e-06 2.09976586496216e-05 -3.29746199909022e-06 -1.08589995047803e-06 3.26333613932984e-06 4.00834781001466e-06 8.71454101587382e-05 0 0 0 0 43 0 0 0 0 110 0 0 0 0 0 0 0 0 661 0 0 0 0 0 2186 +1063 1113 0.982064848236372 -0.186126621449136 -0.0300917704098902 0.050078503737532 0.183995620191295 0.980934492201914 -0.0625550458316023 -0.0130844872676093 0.0411612148617142 0.05589635763181 0.99758776636174 0.213548748029075 2.51606473918665e-05 1.00390265855879e-05 -4.86314067708832e-06 9.82809069465304e-07 3.39384899432377e-06 1.38904094636624e-06 1.00390265855879e-05 5.05294783517704e-05 -5.93923605807878e-08 -5.31464261878094e-06 7.42940081432733e-06 6.44778763481752e-09 -4.86314067708832e-06 -5.93923605807878e-08 1.2913243036639e-05 -1.07038928984374e-06 -1.52875760139816e-06 -1.373325135791e-06 9.82809069465304e-07 -5.31464261878094e-06 -1.07038928984374e-06 1.9824407523413e-05 -1.16663626153498e-06 1.46093928467864e-06 3.39384899432377e-06 7.42940081432733e-06 -1.52875760139816e-06 -1.16663626153498e-06 6.13712158723893e-05 1.63758558750537e-06 1.38904094636624e-06 6.44778763481752e-09 -1.373325135791e-06 1.46093928467864e-06 1.63758558750537e-06 5.17792799594442e-05 0 0 0 0 40 0 0 0 0 108 0 0 0 0 0 0 0 0 681 0 0 0 0 0 2268 +1063 1110 0.982022832410253 -0.18590490941467 -0.0327188215018102 0.051221281154443 0.183647812006539 0.981028797805483 -0.0620965298671272 -0.0130313762496498 0.0436421558834467 0.0549714701627242 0.997533708552244 0.214818080281229 2.45784261446732e-05 1.32653138329785e-05 -6.72393408509041e-06 3.33850005179104e-07 1.0511411467263e-06 3.27212804229711e-06 1.32653138329785e-05 4.39136263951254e-05 -1.8408407472465e-07 -2.02240191267435e-06 -3.20016965854451e-06 -3.37499998256454e-06 -6.72393408509041e-06 -1.8408407472465e-07 1.69322303702781e-05 -2.52074619915449e-06 -3.02575057852645e-06 -4.74417267476014e-07 3.33850005179104e-07 -2.02240191267435e-06 -2.52074619915449e-06 2.05735313800923e-05 5.16216794126493e-07 7.42826584972244e-06 1.0511411467263e-06 -3.20016965854451e-06 -3.02575057852645e-06 5.16216794126493e-07 5.51629732520268e-05 -6.85564902941633e-06 3.27212804229711e-06 -3.37499998256454e-06 -4.74417267476014e-07 7.42826584972244e-06 -6.85564902941633e-06 5.25549729275587e-05 0 0 0 0 46 0 0 0 0 110 0 0 0 0 0 0 0 0 682 0 0 0 0 0 2086 +1063 1112 0.982042178063929 -0.185885308533535 -0.032246124958633 0.0521862373733135 0.183581150951799 0.980933278391699 -0.0637798115309712 -0.0169108782193781 0.0434870270157455 0.0567146842987404 0.997442892132791 0.21201280385462 3.05794737799937e-05 1.47249531578114e-05 -5.78555431692115e-06 1.29165456009264e-06 7.58872801943893e-07 9.72223983609356e-06 1.47249531578114e-05 8.30928870045339e-05 3.25868000814896e-06 4.37008179423557e-07 -1.35315641359664e-05 -6.09257221265561e-06 -5.78555431692115e-06 3.25868000814896e-06 1.48119407958496e-05 -1.49862095483028e-06 -2.75193509037456e-07 9.5546969606393e-07 1.29165456009264e-06 4.37008179423557e-07 -1.49862095483028e-06 2.50559560722203e-05 -6.33999578649694e-06 3.99122647263759e-06 7.58872801943893e-07 -1.35315641359664e-05 -2.75193509037456e-07 -6.33999578649694e-06 6.80281340457508e-05 1.43642750413688e-06 9.72223983609356e-06 -6.09257221265561e-06 9.5546969606393e-07 3.99122647263759e-06 1.43642750413688e-06 7.22491213746973e-05 0 0 0 0 43 0 0 0 0 108 0 0 0 0 0 0 0 0 682 0 0 0 0 0 2235 +1063 1135 0.98216273118308 -0.185806035243722 -0.0288528463414364 0.0713747850733996 0.183576118136802 0.980737850971596 -0.0667313758395457 -0.0494434168556784 0.0406961708864187 0.0602443768216143 0.997353716961319 0.223270594717013 3.09249181255962e-05 1.85256389406284e-05 -5.07251551568454e-06 1.20024069896712e-06 4.13175124684929e-06 7.29740347670815e-06 1.85256389406284e-05 4.33048572294179e-05 -4.05014280802877e-06 3.12099035138449e-06 4.07107529489589e-06 -9.89397071841635e-06 -5.07251551568454e-06 -4.05014280802877e-06 1.43852508886601e-05 -4.73002692009625e-08 -4.28032349666371e-07 -1.02134380973041e-06 1.20024069896712e-06 3.12099035138449e-06 -4.73002692009625e-08 3.98898775272602e-05 -5.51365395859025e-05 4.16866869348976e-06 4.13175124684929e-06 4.07107529489589e-06 -4.28032349666371e-07 -5.51365395859025e-05 0.000191245003470808 -4.93060944343079e-06 7.29740347670815e-06 -9.89397071841635e-06 -1.02134380973041e-06 4.16866869348976e-06 -4.93060944343079e-06 6.22891813431351e-05 0 0 0 0 22 0 0 0 0 90 0 0 0 0 0 0 0 0 718 0 0 0 0 0 2196 +1063 1134 0.982364744809649 -0.185945353723766 -0.0195916712818428 0.0707467297330839 0.18467104166109 0.981317903928783 -0.0539608913994802 -0.0322379884116486 0.0292594348352858 0.049391262965852 0.998350834434347 0.192392109001718 3.66491475360869e-05 1.35342445138289e-05 -5.98527272287619e-06 5.10992120712089e-06 -8.89113232862392e-06 2.26663693458605e-05 1.35342445138289e-05 6.53070551714446e-05 -2.17373089955918e-08 6.30317163608363e-06 -1.74470364994632e-05 -8.58919278769106e-06 -5.98527272287619e-06 -2.17373089955918e-08 1.39179344426828e-05 -1.55496808609908e-06 1.62308509687284e-06 -3.33376600453368e-06 5.10992120712089e-06 6.30317163608363e-06 -1.55496808609908e-06 4.29248859496588e-05 -5.44596921642417e-05 1.4905807593221e-05 -8.89113232862392e-06 -1.74470364994632e-05 1.62308509687284e-06 -5.44596921642417e-05 0.000183781312954212 -2.70219566240284e-05 2.26663693458605e-05 -8.58919278769106e-06 -3.33376600453368e-06 1.4905807593221e-05 -2.70219566240284e-05 0.000129608866302765 0 0 0 0 27 0 0 0 0 96 0 0 0 0 0 0 0 0 686 0 0 0 0 0 2229 +1063 1137 0.982162150978686 -0.186049731273629 -0.0272581488353832 0.0504949677409232 0.184108469184113 0.980963375464694 -0.0617650999480691 -0.0060445348390186 0.0382306259379037 0.0556448873655339 0.99771843009462 0.219558285696701 4.11492557719383e-05 2.66825116789922e-05 -3.2991565104208e-06 -1.41719323523702e-06 -1.02101945617433e-06 2.45870527887925e-05 2.66825116789922e-05 5.34142094352198e-05 6.34160512001007e-07 5.70490399118314e-07 -1.12470587995649e-06 9.69634387657344e-06 -3.2991565104208e-06 6.34160512001007e-07 1.46002108970568e-05 1.06314780775329e-06 2.04044040599514e-08 3.17651807882076e-06 -1.41719323523702e-06 5.70490399118314e-07 1.06314780775329e-06 3.04746016894634e-05 -3.4660189677039e-05 -1.78240270974974e-06 -1.02101945617433e-06 -1.12470587995649e-06 2.04044040599514e-08 -3.4660189677039e-05 0.000147531486131536 1.85367814884414e-06 2.45870527887925e-05 9.69634387657344e-06 3.17651807882076e-06 -1.78240270974974e-06 1.85367814884414e-06 8.40323234969005e-05 0 0 0 0 50 0 0 0 0 112 0 0 0 0 0 0 0 0 769 0 0 0 0 0 2222 +1063 1132 0.982239136331971 -0.185366584412383 -0.0290776278453324 0.061461391815018 0.183436368979323 0.981261311646463 -0.0589689477737539 -0.023329052281882 0.0394636236742916 0.0525877138612173 0.997836236442305 0.202770717597681 4.66709863497143e-05 3.27218874290723e-05 -5.83714281250656e-06 3.45184331510504e-06 -4.51246424263951e-06 4.46410349021917e-05 3.27218874290723e-05 6.49210534417324e-05 -3.27587911639338e-06 4.19321766391609e-06 -1.13420231691085e-05 2.26340264621383e-05 -5.83714281250656e-06 -3.27587911639338e-06 1.47919843110281e-05 2.20027706526165e-06 -7.42088089308884e-06 3.96519093290504e-06 3.45184331510504e-06 4.19321766391609e-06 2.20027706526165e-06 3.59252278837213e-05 -5.36361848531395e-05 1.14786384320615e-05 -4.51246424263951e-06 -1.13420231691085e-05 -7.42088089308884e-06 -5.36361848531395e-05 0.000208520919178253 -4.6443053473794e-05 4.46410349021917e-05 2.26340264621383e-05 3.96519093290504e-06 1.14786384320615e-05 -4.6443053473794e-05 0.000187281939488132 0 0 0 0 37 0 0 0 0 101 0 0 0 0 0 0 0 0 765 0 0 0 0 0 2148 +1063 1133 0.982333276734867 -0.185931373451594 -0.0212334120136867 0.0674599322355577 0.184582041195035 0.981345047487873 -0.0537714407404103 -0.0305879005627513 0.0308351015502364 0.0489021690462605 0.998327488540187 0.195592476426314 3.3997142115949e-05 1.7441206828934e-05 -6.08394619188232e-06 2.52109662577176e-06 9.30500219840748e-06 1.66284022705878e-05 1.7441206828934e-05 4.17583860821646e-05 -1.54305409349923e-06 3.49168376917027e-06 -5.70414998353567e-06 -3.60803041243163e-06 -6.08394619188232e-06 -1.54305409349923e-06 1.47540847740946e-05 -9.57146162140797e-07 2.75358260305872e-06 -2.47849854780665e-06 2.52109662577176e-06 3.49168376917027e-06 -9.57146162140797e-07 4.98202642981081e-05 -7.58537965377253e-05 4.68736660002561e-06 9.30500219840748e-06 -5.70414998353567e-06 2.75358260305872e-06 -7.58537965377253e-05 0.000252900615626026 4.52441166056901e-07 1.66284022705878e-05 -3.60803041243163e-06 -2.47849854780665e-06 4.68736660002561e-06 4.52441166056901e-07 0.000100378841670736 0 0 0 0 33 0 0 0 0 100 0 0 0 0 0 0 0 0 683 0 0 0 0 0 2015 +1063 1116 0.982029574782948 -0.186670430864808 -0.027786048520244 0.0542144859634912 0.184702430841573 0.98085719845692 -0.0616779399498339 -0.014783937480876 0.0387675933330439 0.0554374104372527 0.997709259870417 0.208109068745522 2.19796030152226e-05 1.52795359295422e-05 -1.83349514986613e-06 -9.49662755957023e-07 3.13218291621492e-06 -3.8663067924777e-06 1.52795359295422e-05 3.94107682863165e-05 1.59328212765034e-06 -3.12678492915651e-06 -2.42706345685201e-06 -6.03519905305991e-07 -1.83349514986613e-06 1.59328212765034e-06 1.16216618129493e-05 3.17881148630084e-06 2.1547670199799e-06 1.11194506748129e-06 -9.49662755957023e-07 -3.12678492915651e-06 3.17881148630084e-06 1.94789623255127e-05 9.53647215953145e-07 3.31528309853959e-06 3.13218291621492e-06 -2.42706345685201e-06 2.1547670199799e-06 9.53647215953145e-07 4.87151690592895e-05 -1.40864277562117e-05 -3.8663067924777e-06 -6.03519905305991e-07 1.11194506748129e-06 3.31528309853959e-06 -1.40864277562117e-05 4.69458959702586e-05 0 0 0 0 43 0 0 0 0 109 0 0 0 0 0 0 0 0 671 0 0 0 0 0 2170 +1063 1114 0.981789010667925 -0.186796423461362 -0.0346039696240393 0.0509166639104603 0.184311920631174 0.980730792819327 -0.0647782982890268 -0.0156272963342223 0.0460375330023834 0.0572206972870659 0.997299522388854 0.217368508215517 3.20075033303075e-05 2.12325918574189e-05 -4.95485045989915e-06 1.19262524448298e-06 6.72432427775131e-06 1.41260029110752e-05 2.12325918574189e-05 3.84805482064645e-05 -1.26703266900067e-08 -3.58862492963992e-06 7.83916138174309e-06 8.08952208018328e-06 -4.95485045989915e-06 -1.26703266900067e-08 1.69493374392445e-05 -1.8560496554886e-06 -4.76620126978207e-06 1.76443398553771e-06 1.19262524448298e-06 -3.58862492963992e-06 -1.8560496554886e-06 2.05897154820531e-05 1.01681298371042e-06 -8.31760046610638e-07 6.72432427775131e-06 7.83916138174309e-06 -4.76620126978207e-06 1.01681298371042e-06 6.88290911162718e-05 4.85528493518433e-06 1.41260029110752e-05 8.08952208018328e-06 1.76443398553771e-06 -8.31760046610638e-07 4.85528493518433e-06 7.25039096818799e-05 0 0 0 0 42 0 0 0 0 107 0 0 0 0 0 0 0 0 724 0 0 0 0 0 2145 +1063 1136 0.982168285023636 -0.186679663331471 -0.0222747209225677 0.0661645858196258 0.185122434587299 0.980966986675734 -0.0585956932274155 -0.0326221866259699 0.0327893901468223 0.0534272809600034 0.998033256731969 0.211986918023615 3.1060963658778e-05 4.73123266006919e-06 -6.64013408924423e-06 -1.36212197474446e-06 9.50777374810377e-06 1.10099613661385e-05 4.73123266006919e-06 4.59494725736992e-05 1.43590376509541e-06 6.50110916331653e-06 -1.21215260383997e-05 -1.28789706099131e-05 -6.64013408924423e-06 1.43590376509541e-06 1.5741137272052e-05 -3.14979233045545e-06 1.70114573601818e-06 -4.69776861536132e-07 -1.36212197474446e-06 6.50110916331653e-06 -3.14979233045545e-06 3.86261225578626e-05 -3.89012533431274e-05 3.92062870723999e-06 9.50777374810377e-06 -1.21215260383997e-05 1.70114573601818e-06 -3.89012533431274e-05 0.000128371803864902 5.84995212287989e-06 1.10099613661385e-05 -1.28789706099131e-05 -4.69776861536132e-07 3.92062870723999e-06 5.84995212287989e-06 6.87073743769596e-05 0 0 0 0 34 0 0 0 0 98 0 0 0 0 0 0 0 0 714 0 0 0 0 0 2169 +1064 1148 0.987904960502979 -0.124650444501824 -0.0922282803651086 0.0246945371868998 0.121864531989798 0.991919965433395 -0.0352678042627979 -0.0436701918831297 0.0958792201497011 0.0236018825543483 0.99511312235513 0.00646051740354913 3.49166781253972e-05 2.18255971669681e-05 -1.08660269687844e-05 2.9238676548827e-06 -3.09611212487845e-06 1.54707200712199e-06 2.18255971669681e-05 7.77407707690975e-05 -2.25560775255265e-06 4.71364251695081e-06 -2.2086842115765e-05 -1.4990699083899e-05 -1.08660269687844e-05 -2.25560775255265e-06 1.66425566082214e-05 -3.17136853089668e-06 -9.1974447774009e-08 6.63439808461119e-07 2.9238676548827e-06 4.71364251695081e-06 -3.17136853089668e-06 2.7768488854101e-05 -1.14129260351538e-05 4.22748604352473e-06 -3.09611212487845e-06 -2.2086842115765e-05 -9.1974447774009e-08 -1.14129260351538e-05 8.73146559484905e-05 2.4237430136939e-06 1.54707200712199e-06 -1.4990699083899e-05 6.63439808461119e-07 4.22748604352473e-06 2.4237430136939e-06 4.49408501297564e-05 0 0 0 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 1126 0 0 0 0 0 3039 +1064 1066 0.995685824724135 -0.0923748793568445 -0.00875329122262308 0.0133646385025696 0.0926000256763806 0.995242638694605 0.0302873796973826 0.0195435560328937 0.00591385560808506 -0.0309672696246892 0.999502903709558 0.0618309666305946 2.23632620902802e-05 1.87656453395475e-05 -1.70577156048079e-06 2.01813180331265e-06 1.01950728084016e-06 -3.52283597046652e-06 1.87656453395475e-05 2.93559761575102e-05 -8.9327610991868e-07 3.94869431196352e-07 6.10749425525883e-06 -5.45349256786638e-06 -1.70577156048079e-06 -8.9327610991868e-07 1.35007420356358e-05 1.30582649603679e-06 3.59620103405799e-07 -9.11246043347512e-08 2.01813180331265e-06 3.94869431196352e-07 1.30582649603679e-06 2.47644536103283e-05 -2.1071935950092e-05 -1.03524146083427e-07 1.01950728084016e-06 6.10749425525883e-06 3.59620103405799e-07 -2.1071935950092e-05 8.51854477385349e-05 8.36183335086115e-06 -3.52283597046652e-06 -5.45349256786638e-06 -9.11246043347512e-08 -1.03524146083427e-07 8.36183335086115e-06 3.71374916634998e-05 0 0 0 0 0 0 0 0 0 20 0 0 0 0 0 0 0 0 1241 0 0 0 0 0 2919 +1064 1147 0.990689884551354 -0.109040912631521 -0.0815084782100032 0.0347064652753199 0.106234098008996 0.993613748714319 -0.0380267640760214 -0.0160116446018545 0.0851344176455135 0.0290137508496096 0.995946953001914 0.0812545300159683 3.67797202700527e-05 2.31418940476467e-06 -8.81606861458857e-06 1.37886861495878e-06 4.84841973537318e-06 6.15166767545477e-06 2.31418940476467e-06 7.83090884295976e-05 9.66029840738663e-06 2.5160236279451e-06 -9.48802740238966e-06 -3.50579813081146e-05 -8.81606861458857e-06 9.66029840738663e-06 1.83580472980354e-05 1.11128228552698e-06 -2.58817531188294e-06 -6.88767084980982e-06 1.37886861495878e-06 2.5160236279451e-06 1.11128228552698e-06 2.39146295161631e-05 4.80060255156494e-06 5.41763064821142e-06 4.84841973537318e-06 -9.48802740238966e-06 -2.58817531188294e-06 4.80060255156494e-06 6.25182332592015e-05 3.99139239467271e-06 6.15166767545477e-06 -3.50579813081146e-05 -6.88767084980982e-06 5.41763064821142e-06 3.99139239467271e-06 5.30347883377775e-05 0 0 0 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 1027 0 0 0 0 0 2590 +1064 1101 0.991911757802056 -0.12538275289508 -0.0197542403166316 0.0287805639231916 0.123898132091817 0.990235060071163 -0.0639044495322415 -0.00295474914194257 0.027573857151197 0.060940061390775 0.997760487952642 0.154752532541459 5.20509228591774e-05 -1.45881421892992e-05 -1.38274994870338e-05 2.80366623971045e-06 7.19814491288599e-06 2.97843633836517e-05 -1.45881421892992e-05 8.97952501101899e-05 9.51075175266255e-06 -3.07561619531747e-06 -2.13890728368847e-06 -4.79538997883017e-05 -1.38274994870338e-05 9.51075175266255e-06 2.03608500695131e-05 -3.16785259089501e-06 -4.93700279991139e-06 -5.57573320020411e-06 2.80366623971045e-06 -3.07561619531747e-06 -3.16785259089501e-06 2.4430449127556e-05 4.5318534945768e-06 5.96247341490759e-06 7.19814491288599e-06 -2.13890728368847e-06 -4.93700279991139e-06 4.5318534945768e-06 5.13063740588652e-05 8.76237171168728e-06 2.97843633836517e-05 -4.79538997883017e-05 -5.57573320020411e-06 5.96247341490759e-06 8.76237171168728e-06 7.4489200637037e-05 0 0 0 0 0 0 0 0 0 9 0 0 0 0 0 0 0 0 680 0 0 0 0 0 2429 +1064 1107 0.991566097613802 -0.12551132146362 -0.0323045236366554 0.0246049223783032 0.123043897425978 0.989963858497328 -0.0695108493352459 -0.00510572862771941 0.0407047094223869 0.064949727124427 0.997058002112867 0.160182769401131 3.87157141690747e-05 1.74204702954364e-05 -4.36944152943128e-06 8.14375286448146e-07 2.51916535314274e-07 1.42418947945347e-05 1.74204702954364e-05 6.15911715346037e-05 1.71271490152499e-06 -3.1215754658092e-07 -4.68457246654307e-06 -1.31175622960768e-05 -4.36944152943128e-06 1.71271490152499e-06 1.57087612772998e-05 -2.75597952189946e-06 -2.87429788213782e-06 1.12475701384502e-06 8.14375286448146e-07 -3.1215754658092e-07 -2.75597952189946e-06 2.27554329251728e-05 6.33363336963339e-06 3.88243315386483e-06 2.51916535314274e-07 -4.68457246654307e-06 -2.87429788213782e-06 6.33363336963339e-06 4.67633458741535e-05 1.51642676974568e-06 1.42418947945347e-05 -1.31175622960768e-05 1.12475701384502e-06 3.88243315386483e-06 1.51642676974568e-06 5.7993167635354e-05 0 0 0 0 0 0 0 0 0 7 0 0 0 0 0 0 0 0 650 0 0 0 0 0 2412 +1064 1103 0.991571995752615 -0.12647188094857 -0.0281041023430085 0.022471624411712 0.124313822794074 0.989875284468576 -0.0685054352630402 -0.00206695691665487 0.0364835675544367 0.064434342765219 0.997254814363368 0.158362635821976 3.77300201409628e-05 1.53608730433294e-05 1.32192672713275e-06 -6.22166983716598e-06 -3.87020770378944e-06 1.294551552191e-05 1.53608730433294e-05 7.6275101890135e-05 3.63024049819792e-06 4.09429094635961e-06 -8.0549345880854e-06 -1.81166379757125e-05 1.32192672713275e-06 3.63024049819792e-06 1.81209752429482e-05 -3.7826829393932e-06 -1.90487997509424e-06 4.58920893381724e-06 -6.22166983716598e-06 4.09429094635961e-06 -3.7826829393932e-06 2.88539915051029e-05 7.33961075528975e-06 -4.74388908055437e-06 -3.87020770378944e-06 -8.0549345880854e-06 -1.90487997509424e-06 7.33961075528975e-06 5.76273281949517e-05 2.84040314619821e-06 1.294551552191e-05 -1.81166379757125e-05 4.58920893381724e-06 -4.74388908055437e-06 2.84040314619821e-06 6.26146026735987e-05 0 0 0 0 0 0 0 0 0 10 0 0 0 0 0 0 0 0 614 0 0 0 0 0 2409 +1064 1106 0.991616233559291 -0.126238072106381 -0.0275897533977905 0.0236325887783946 0.124157065053621 0.989977797956423 -0.0672977172764592 -0.00249098107380467 0.0358087774010459 0.0633080461253976 0.997351403847624 0.160948802191968 4.72843013254753e-05 3.3218974530003e-05 -2.79068857270347e-06 -2.82711321049328e-06 8.67509484489502e-06 1.81820237019655e-05 3.3218974530003e-05 8.68420322229149e-05 4.47872229162667e-06 -1.1728458884941e-06 3.58855527375836e-06 1.50354781488766e-08 -2.79068857270347e-06 4.47872229162667e-06 1.57483929100939e-05 -1.45030209319299e-06 2.89124885803586e-07 1.78150741706178e-06 -2.82711321049328e-06 -1.1728458884941e-06 -1.45030209319299e-06 2.41280056350305e-05 3.03670714943563e-06 2.26973367642902e-06 8.67509484489502e-06 3.58855527375836e-06 2.89124885803586e-07 3.03670714943563e-06 4.95661888416773e-05 6.68354198617964e-06 1.81820237019655e-05 1.50354781488766e-08 1.78150741706178e-06 2.26973367642902e-06 6.68354198617964e-06 5.85574356574712e-05 0 0 0 0 0 0 0 0 0 13 0 0 0 0 0 0 0 0 760 0 0 0 0 0 2428 +1064 1104 0.991407719453215 -0.126103136838883 -0.0347668331599124 0.0216172778768655 0.123349058386198 0.98971825012167 -0.0724071486204106 -0.00527506484506387 0.0435401378478935 0.067496549952526 0.996769016442973 0.166978820865566 3.51874493298432e-05 2.10887035384715e-05 2.64950334775419e-06 -2.85709654141319e-06 -2.94428171677581e-06 1.41424596615871e-05 2.10887035384715e-05 6.49561942736039e-05 1.09628380611834e-05 -1.69893863420235e-06 -3.06415076653351e-06 3.28001546982078e-06 2.64950334775419e-06 1.09628380611834e-05 1.68411990789114e-05 -2.36029645709733e-06 -8.84198611540226e-08 3.59857547287143e-06 -2.85709654141319e-06 -1.69893863420235e-06 -2.36029645709733e-06 2.853959881993e-05 -2.74789564612119e-07 6.02463691415517e-06 -2.94428171677581e-06 -3.06415076653351e-06 -8.84198611540226e-08 -2.74789564612119e-07 6.61146098998077e-05 -6.78030284908197e-06 1.41424596615871e-05 3.28001546982078e-06 3.59857547287143e-06 6.02463691415517e-06 -6.78030284908197e-06 5.61061205196726e-05 0 0 0 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 686 0 0 0 0 0 2495 +1064 1108 0.991613450057644 -0.125048809384319 -0.0326429308785314 0.0261089447045052 0.12261978733194 0.990117480458797 -0.0680570543338058 -0.0107657292649389 0.0408307900908885 0.063483621206489 0.997147269172947 0.159098458035721 2.97363797897088e-05 1.86080475829718e-05 -6.79480729856831e-06 4.14019439189876e-06 3.48376111929527e-06 2.30378147945963e-06 1.86080475829718e-05 5.06378655024879e-05 -1.21410968659851e-06 -2.53971942964436e-06 5.11867688334695e-06 -1.09889444591331e-05 -6.79480729856831e-06 -1.21410968659851e-06 1.56793268914554e-05 -3.12318759686917e-06 -3.2665166543534e-06 -1.72109255202818e-06 4.14019439189876e-06 -2.53971942964436e-06 -3.12318759686917e-06 2.11209598649805e-05 7.01237360341236e-06 6.48367096540423e-06 3.48376111929527e-06 5.11867688334695e-06 -3.2665166543534e-06 7.01237360341236e-06 4.25714097508211e-05 -3.65545938335099e-06 2.30378147945963e-06 -1.09889444591331e-05 -1.72109255202818e-06 6.48367096540423e-06 -3.65545938335099e-06 4.54209759018244e-05 0 0 0 0 0 0 0 0 0 9 0 0 0 0 0 0 0 0 642 0 0 0 0 0 2418 +1064 1109 0.991672748486498 -0.124385909783648 -0.0333662307809699 0.0294230185171152 0.121878612009815 0.990153733300057 -0.0688562877776657 -0.0148130956624354 0.0416024499734783 0.0642162742554712 0.997068456163844 0.160077857130287 2.90376183983724e-05 9.61737547323676e-06 -6.75834010430011e-06 1.96884887758804e-06 -2.03245111963336e-06 5.71414425130478e-06 9.61737547323676e-06 4.93442482836124e-05 2.43900926256607e-06 1.88397894517473e-07 -7.29706873301725e-06 -1.37868277516981e-05 -6.75834010430011e-06 2.43900926256607e-06 1.60569827475221e-05 -1.99710695013429e-06 -2.75691482157841e-06 3.50625729560857e-07 1.96884887758804e-06 1.88397894517473e-07 -1.99710695013429e-06 2.08145251521673e-05 -2.1386340157818e-06 3.6971923822624e-06 -2.03245111963336e-06 -7.29706873301725e-06 -2.75691482157841e-06 -2.1386340157818e-06 5.80122370967918e-05 3.39853849847008e-06 5.71414425130478e-06 -1.37868277516981e-05 3.50625729560857e-07 3.6971923822624e-06 3.39853849847008e-06 4.26165731953393e-05 0 0 0 0 0 0 0 0 0 8 0 0 0 0 0 0 0 0 761 0 0 0 0 0 2412 +1064 1105 0.991654943709649 -0.12625190928703 -0.0260945974790393 0.0273171140992276 0.124226648712462 0.989891324097297 -0.0684317632870175 -0.0113713348938176 0.0344704564211762 0.0646190519760176 0.997314476860652 0.158381171443454 3.8025254763423e-05 1.77621835733451e-05 -2.44243486867916e-06 -3.82937095640165e-06 1.60408619238731e-06 1.00059632685415e-05 1.77621835733451e-05 7.12013422878505e-05 8.64540318737381e-06 -1.06093120770954e-06 -2.78410789230035e-06 -9.26165429875866e-06 -2.44243486867916e-06 8.64540318737381e-06 1.82585410427455e-05 -1.69015217644318e-07 -4.40920217420734e-06 3.3358083748422e-06 -3.82937095640165e-06 -1.06093120770954e-06 -1.69015217644318e-07 2.45095089361e-05 2.63397989246427e-06 -2.70105540456029e-06 1.60408619238731e-06 -2.78410789230035e-06 -4.40920217420734e-06 2.63397989246427e-06 5.62252899779626e-05 1.06105080732345e-06 1.00059632685415e-05 -9.26165429875866e-06 3.3358083748422e-06 -2.70105540456029e-06 1.06105080732345e-06 6.52296170098683e-05 0 0 0 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 737 0 0 0 0 0 2437 +1064 1111 0.99151747086851 -0.125862606025789 -0.0324300688699468 0.0305155350474137 0.123419325390101 0.989973204228225 -0.0687075325590525 -0.022052038661624 0.0407526082940073 0.0641222216902843 0.997109605611508 0.16069517027085 5.5843116567105e-05 1.22182389322712e-05 -8.48874012451103e-06 4.89142021356504e-06 7.67748881812544e-06 3.17929351964406e-05 1.22182389322712e-05 9.20449706720831e-05 4.49941525833974e-06 3.57542722171427e-06 -1.56726145298671e-05 -2.29939092390838e-05 -8.48874012451103e-06 4.49941525833974e-06 1.8743725395995e-05 -4.80334948588024e-06 -7.07617650922515e-06 -1.67397275219283e-06 4.89142021356504e-06 3.57542722171427e-06 -4.80334948588024e-06 2.50946348042877e-05 6.04801744810017e-06 4.61212563306413e-06 7.67748881812544e-06 -1.56726145298671e-05 -7.07617650922515e-06 6.04801744810017e-06 5.54351301067039e-05 1.2096213519273e-05 3.17929351964406e-05 -2.29939092390838e-05 -1.67397275219283e-06 4.61212563306413e-06 1.2096213519273e-05 7.88179385729416e-05 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 659 0 0 0 0 0 2435 +1064 1112 0.991571429708228 -0.126067944790403 -0.0298826552151102 0.0338092182070814 0.123810713914432 0.989964807138156 -0.0681218595453145 -0.0243400647806501 0.0381707598349808 0.0638478967878889 0.997229381421037 0.157637126040667 3.74657288527159e-05 2.78265868899263e-05 -7.911792938695e-06 1.20460509160684e-05 -8.98135570325967e-06 1.89110772603147e-05 2.78265868899263e-05 8.07500450474516e-05 -5.00940501238296e-07 8.04708974956927e-07 1.52541536813308e-06 8.17269062824641e-06 -7.911792938695e-06 -5.00940501238296e-07 1.66074330337886e-05 -3.05984738604913e-06 -8.99114848178976e-07 -2.70830069309368e-06 1.20460509160684e-05 8.04708974956927e-07 -3.05984738604913e-06 3.3014414127127e-05 -1.00357764940018e-05 1.83317227777111e-05 -8.98135570325967e-06 1.52541536813308e-06 -8.99114848178976e-07 -1.00357764940018e-05 8.58270425399446e-05 -2.1853295114725e-05 1.89110772603147e-05 8.17269062824641e-06 -2.70830069309368e-06 1.83317227777111e-05 -2.1853295114725e-05 7.18671717664331e-05 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 719 0 0 0 0 0 2433 +1064 1110 0.991568851028624 -0.125811161971789 -0.031028457794148 0.0300317497130841 0.123575683023488 0.990156933784354 -0.0657137507987891 -0.015410060662143 0.038990565975031 0.0613253455112593 0.997355973443219 0.15805610489711 3.15781200721773e-05 1.56806555590015e-05 -6.66209042046495e-06 2.58425835174402e-06 5.0529168527591e-06 5.58681264206638e-06 1.56806555590015e-05 0.000104014476105623 5.49856763016205e-06 1.55882124524436e-06 2.71085252194283e-07 -2.80031634430868e-05 -6.66209042046495e-06 5.49856763016205e-06 1.69520639938187e-05 -3.02777299338233e-06 -3.73803261241226e-06 -3.02636146720887e-06 2.58425835174402e-06 1.55882124524436e-06 -3.02777299338233e-06 2.48600760686555e-05 -1.51383014976657e-06 6.66612759354362e-06 5.0529168527591e-06 2.71085252194283e-07 -3.73803261241226e-06 -1.51383014976657e-06 6.475461944977e-05 -4.29157951232009e-06 5.58681264206638e-06 -2.80031634430868e-05 -3.02636146720887e-06 6.66612759354362e-06 -4.29157951232009e-06 4.91948231205471e-05 0 0 0 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 710 0 0 0 0 0 2393 +1064 1113 0.991670821789106 -0.126044178525 -0.0264923813968784 0.0316145916551725 0.124209462696794 0.990305676086577 -0.0621826124192339 -0.0175667397742754 0.0340733119712999 0.0583740778999103 0.997713123317841 0.151799820242555 5.82006265201899e-05 3.39305833067939e-05 -4.05938544880557e-06 2.96749330579219e-06 -2.24601113711699e-06 2.83952075259381e-05 3.39305833067939e-05 7.59067092519408e-05 4.49374537140278e-06 -4.89275210558919e-06 1.32313347709175e-06 1.65054749408847e-05 -4.05938544880557e-06 4.49374537140278e-06 1.67856541036022e-05 -1.79356160147216e-06 -3.06957572041914e-06 1.26639892841415e-06 2.96749330579219e-06 -4.89275210558919e-06 -1.79356160147216e-06 2.41165213141788e-05 -2.24757034752995e-06 2.87561615799626e-06 -2.24601113711699e-06 1.32313347709175e-06 -3.06957572041914e-06 -2.24757034752995e-06 6.40526393009585e-05 3.04815677012153e-06 2.83952075259381e-05 1.65054749408847e-05 1.26639892841415e-06 2.87561615799626e-06 3.04815677012153e-06 7.48857266022143e-05 0 0 0 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 708 0 0 0 0 0 2462 +1064 1136 0.991835751828474 -0.125634783251922 -0.0218573244494316 0.0404439304685645 0.124076651137501 0.990330495067392 -0.0620523583925452 -0.0292262434925858 0.0294419095397722 0.0588337639184887 0.997833534306116 0.149707756242089 3.86396984658225e-05 1.19494502664077e-06 -8.18555993719533e-06 8.86163823825624e-06 -1.35775082374531e-05 2.61428282689019e-05 1.19494502664077e-06 7.43234494242793e-05 4.9395661933494e-06 -1.0896377111079e-05 2.21812916131677e-05 -2.61804383755448e-05 -8.18555993719533e-06 4.9395661933494e-06 1.71352620420186e-05 -2.97647632789174e-06 -1.92802662631476e-06 -2.52529326011916e-06 8.86163823825624e-06 -1.0896377111079e-05 -2.97647632789174e-06 3.57650642591285e-05 -3.81689576745174e-05 1.81598117011109e-05 -1.35775082374531e-05 2.21812916131677e-05 -1.92802662631476e-06 -3.81689576745174e-05 0.000151871023558247 -3.54694904570526e-05 2.61428282689019e-05 -2.61804383755448e-05 -2.52529326011916e-06 1.81598117011109e-05 -3.54694904570526e-05 8.03231656230984e-05 0 0 0 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 758 0 0 0 0 0 2459 +1064 1134 0.991805519617595 -0.125324614675681 -0.0248103247150116 0.0422969462662257 0.123357732527387 0.989944665166228 -0.0692273770601441 -0.035672881840961 0.0332367429477382 0.0655995492767874 0.997292343324117 0.157095200215926 4.92041113670298e-05 2.46807734588506e-05 -1.95082754490391e-06 7.06600621378436e-06 -1.2910817007286e-05 3.13912465791279e-05 2.46807734588506e-05 5.75346566509981e-05 4.26348229337569e-06 2.67732336675219e-06 -1.03617102440437e-05 -5.99728798942093e-06 -1.95082754490391e-06 4.26348229337569e-06 1.70911851478945e-05 -3.55607957843221e-06 1.40594201585499e-06 4.51324534350921e-07 7.06600621378436e-06 2.67732336675219e-06 -3.55607957843221e-06 4.29878755535185e-05 -5.42111756491667e-05 1.03315161042617e-05 -1.2910817007286e-05 -1.03617102440437e-05 1.40594201585499e-06 -5.42111756491667e-05 0.000173942412328416 -1.72653749605396e-05 3.13912465791279e-05 -5.99728798942093e-06 4.51324534350921e-07 1.03315161042617e-05 -1.72653749605396e-05 8.69634516452944e-05 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 708 0 0 0 0 0 2471 +1064 1133 0.991569384061922 -0.125101358621833 -0.0337610228226543 0.03981812487483 0.122508926623568 0.989978390022373 -0.070244929968304 -0.0412260350785031 0.0422104191948102 0.0655166952744269 0.996958295593008 0.162699679649551 5.27584778984397e-05 3.07627792865387e-05 -4.616483168079e-06 3.33219085722396e-08 8.38242841262335e-06 4.02405016840007e-05 3.07627792865387e-05 8.31212627643507e-05 4.26695101942875e-06 -1.77596926545516e-06 -1.12699114015428e-05 6.82584280009851e-06 -4.616483168079e-06 4.26695101942875e-06 1.88453438246969e-05 -4.14869073383599e-06 -7.90503867917792e-06 5.20419318602962e-06 3.33219085722396e-08 -1.77596926545516e-06 -4.14869073383599e-06 4.67316101150453e-05 -6.71945520932288e-05 5.99442966936038e-06 8.38242841262335e-06 -1.12699114015428e-05 -7.90503867917792e-06 -6.71945520932288e-05 0.000244024521168115 -2.84793393582966e-06 4.02405016840007e-05 6.82584280009851e-06 5.20419318602962e-06 5.99442966936038e-06 -2.84793393582966e-06 9.60206059624018e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 696 0 0 0 0 0 2442 +1064 1137 0.9916697405533 -0.124985444601965 -0.0311410389775411 0.0280967513713522 0.122587060001785 0.99000708233009 -0.0697021495822158 -0.0132893952870662 0.039541603294129 0.0653040241785454 0.99708166467698 0.163126716198494 3.50515543509249e-05 8.26696862229375e-06 -8.8355814681943e-06 5.25214069953032e-06 -3.75450536658699e-06 1.63667322867346e-05 8.26696862229375e-06 7.16306294312128e-05 4.95702446896616e-06 -4.74506309160356e-06 1.11942075065501e-05 -1.92009811109802e-05 -8.8355814681943e-06 4.95702446896616e-06 1.75051615865319e-05 -2.894142444314e-06 -3.05710410643358e-06 -2.18304814752682e-06 5.25214069953032e-06 -4.74506309160356e-06 -2.894142444314e-06 2.94540780955783e-05 -2.6293037109525e-05 9.07160478945952e-06 -3.75450536658699e-06 1.11942075065501e-05 -3.05710410643358e-06 -2.6293037109525e-05 0.000130505931370033 -1.51375446537087e-05 1.63667322867346e-05 -1.92009811109802e-05 -2.18304814752682e-06 9.07160478945952e-06 -1.51375446537087e-05 6.01849678550532e-05 0 0 0 0 0 0 0 0 0 3 0 0 0 0 0 0 0 0 819 0 0 0 0 0 2416 +1064 1115 0.991478626905423 -0.125066963587054 -0.0364470438973086 0.0286995449448953 0.12215826747234 0.989796281239471 -0.0733531139943653 -0.0221631216222404 0.0452491997486581 0.0682757370053867 0.996639821429225 0.166809843831212 2.86038492704943e-05 1.51138062170765e-05 -6.64705612208903e-06 2.7663593549807e-06 2.35492515754453e-06 2.56463559001548e-06 1.51138062170765e-05 5.54430793118534e-05 -1.11440269622308e-06 2.11142991787931e-06 -3.77493598453693e-06 -1.79072410812203e-05 -6.64705612208903e-06 -1.11440269622308e-06 1.61668188697535e-05 -2.25243861842566e-06 -2.15782146964966e-06 4.72602727234656e-07 2.7663593549807e-06 2.11142991787931e-06 -2.25243861842566e-06 2.50921920850025e-05 -4.27715464055853e-06 6.4102040970125e-06 2.35492515754453e-06 -3.77493598453693e-06 -2.15782146964966e-06 -4.27715464055853e-06 5.88036982064315e-05 2.29215656689117e-06 2.56463559001548e-06 -1.79072410812203e-05 4.72602727234656e-07 6.4102040970125e-06 2.29215656689117e-06 4.31178444558752e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 758 0 0 0 0 0 2428 +1064 1132 0.991546455248639 -0.125281941997013 -0.0337648055423908 0.0444400474632612 0.12262307677614 0.989852895220112 -0.0717971229668405 -0.0484253929815904 0.0424170735177638 0.0670498384324654 0.996847586665268 0.161530701539996 2.89829610081657e-05 9.04050807568863e-06 -7.66603756924571e-06 6.77189490232681e-06 -4.90180156626984e-06 6.06256242080831e-06 9.04050807568863e-06 6.70724350674098e-05 4.08633430648186e-06 -1.03051354317449e-06 -1.14172462282853e-05 -1.19954666528394e-05 -7.66603756924571e-06 4.08633430648186e-06 1.68372517201877e-05 -2.88023739116762e-06 -6.46440375446335e-06 -2.01388520648964e-06 6.77189490232681e-06 -1.03051354317449e-06 -2.88023739116762e-06 4.47050256083532e-05 -7.15801472734683e-05 1.12422918669377e-05 -4.90180156626984e-06 -1.14172462282853e-05 -6.46440375446335e-06 -7.15801472734683e-05 0.000245449934664272 -2.74107914682716e-05 6.06256242080831e-06 -1.19954666528394e-05 -2.01388520648964e-06 1.12422918669377e-05 -2.74107914682716e-05 4.77231434706382e-05 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 805 0 0 0 0 0 2411 +1064 1135 0.991707811454021 -0.125577100476137 -0.0273131568494315 0.0394626580193323 0.123519449819761 0.990066572517534 -0.0671649276006917 -0.0322007240276844 0.035476220448335 0.0632342772504672 0.997367968185921 0.158382798015757 2.81088392192493e-05 1.15730448868443e-05 -7.59056806491658e-06 4.54050860156967e-06 -6.52952884335822e-06 1.43622427709443e-06 1.15730448868443e-05 6.89666296072653e-05 3.00470883742042e-06 2.32076470988148e-06 7.5017379921835e-06 -2.24835022780196e-05 -7.59056806491658e-06 3.00470883742042e-06 1.64507563627571e-05 -6.09151737995016e-07 -1.09805719808995e-06 -3.96070283802936e-07 4.54050860156967e-06 2.32076470988148e-06 -6.09151737995016e-07 3.17853289155634e-05 -3.41871073063724e-05 5.31691173815787e-06 -6.52952884335822e-06 7.5017379921835e-06 -1.09805719808995e-06 -3.41871073063724e-05 0.000157110130866121 -4.87748011041728e-06 1.43622427709443e-06 -2.24835022780196e-05 -3.96070283802936e-07 5.31691173815787e-06 -4.87748011041728e-06 4.82020733985139e-05 0 0 0 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 803 0 0 0 0 0 2421 +1064 1116 0.991640141009686 -0.125906761482199 -0.028236822614348 0.034100867843707 0.123790290842594 0.990032982901937 -0.067161422404523 -0.0241172086358314 0.0364114629120473 0.0631045178997314 0.997342481392048 0.15227302656968 5.16123671923444e-05 1.62775151803935e-05 -8.93651065409163e-07 -7.30531596937024e-07 2.14485934980434e-06 2.74802050400367e-05 1.62775151803935e-05 8.92971176794253e-05 1.12448629081499e-05 -3.86227514203015e-06 1.16394975790953e-06 -1.67790724798783e-05 -8.93651065409163e-07 1.12448629081499e-05 1.80557526293457e-05 -6.27265230887304e-07 -1.77554675780996e-06 1.78768523493518e-06 -7.30531596937024e-07 -3.86227514203015e-06 -6.27265230887304e-07 2.10454255495103e-05 1.71741293354526e-07 -4.01921750816099e-06 2.14485934980434e-06 1.16394975790953e-06 -1.77554675780996e-06 1.71741293354526e-07 6.52914870021357e-05 -2.95654000704615e-06 2.74802050400367e-05 -1.67790724798783e-05 1.78768523493518e-06 -4.01921750816099e-06 -2.95654000704615e-06 8.69259662674331e-05 0 0 0 0 0 0 0 0 0 4 0 0 0 0 0 0 0 0 695 0 0 0 0 0 2473 +1064 1114 0.991425407376146 -0.126321947602532 -0.0334428940575831 0.0349550638848451 0.123687799284523 0.989728787127716 -0.0716816311118251 -0.0353170129371908 0.0421543582230244 0.0669305123587399 0.996866749670286 0.164876613872885 2.98258043404315e-05 1.43133664172321e-05 -6.37740403858363e-06 4.96095412591688e-07 3.56325408349265e-06 9.15174069850576e-06 1.43133664172321e-05 6.36992145635583e-05 2.90713200496542e-07 1.54518663899408e-06 7.65301302859617e-06 -1.17690739325009e-05 -6.37740403858363e-06 2.90713200496542e-07 1.55526970820895e-05 -1.11204066175253e-06 -3.39331102567143e-06 -4.61586405763377e-07 4.96095412591688e-07 1.54518663899408e-06 -1.11204066175253e-06 2.30125776084377e-05 3.7280883663504e-07 4.15908255249884e-06 3.56325408349265e-06 7.65301302859617e-06 -3.39331102567143e-06 3.7280883663504e-07 6.68398131310222e-05 1.36746155008131e-05 9.15174069850576e-06 -1.17690739325009e-05 -4.61586405763377e-07 4.15908255249884e-06 1.36746155008131e-05 4.48547925222476e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 778 0 0 0 0 0 2491 +1065 1148 0.993910383399264 -0.0644448089562706 -0.0893812976506771 -0.00353842723454722 0.0619212866855453 0.997607933698433 -0.0307272660213897 -0.00840420063684992 0.0911477044490736 0.025005543795977 0.995523389355133 -0.0380206280090953 5.05449623855502e-05 3.74067840474545e-05 -5.58256394682009e-06 1.15742136492988e-06 7.74080492663801e-06 1.60039018618799e-05 3.74067840474545e-05 7.41963943698909e-05 -5.7220545520782e-06 6.04606955817269e-06 1.08581470026007e-05 1.98796125177786e-06 -5.58256394682009e-06 -5.7220545520782e-06 1.42103947765578e-05 -7.56963790041933e-07 -7.43987025487167e-07 2.55720088395163e-06 1.15742136492988e-06 6.04606955817269e-06 -7.56963790041933e-07 2.39769756980262e-05 2.05260053333332e-06 1.69243534637667e-06 7.74080492663801e-06 1.08581470026007e-05 -7.43987025487167e-07 2.05260053333332e-06 6.42034476196814e-05 -1.84553726034597e-06 1.60039018618799e-05 1.98796125177786e-06 2.55720088395163e-06 1.69243534637667e-06 -1.84553726034597e-06 4.55880456755193e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1151 0 0 0 0 0 2919 +1064 1130 0.991897565184222 -0.125149280502544 -0.0218375312548877 0.0362838395778297 0.123599360395038 0.990403579924923 -0.0618380706509687 -0.016459548665668 0.0293669591811974 0.0586379268186749 0.997847270501281 0.146130946749062 4.17569133738942e-05 2.31611560991641e-05 -6.60786254226546e-06 5.86195832988087e-06 -1.16157047858427e-06 1.72989150318933e-05 2.31611560991641e-05 4.95279070222655e-05 -1.53161138998887e-06 2.93124678126961e-07 9.1422783536004e-06 -6.29724990511634e-06 -6.60786254226546e-06 -1.53161138998887e-06 1.5729000723143e-05 2.14753681242797e-06 -3.70065190522225e-06 -2.88930999107875e-07 5.86195832988087e-06 2.93124678126961e-07 2.14753681242797e-06 3.38130536513755e-05 -4.11705074455804e-05 1.00039396061099e-05 -1.16157047858427e-06 9.1422783536004e-06 -3.70065190522225e-06 -4.11705074455804e-05 0.000194359784014619 -1.52210269333732e-05 1.72989150318933e-05 -6.29724990511634e-06 -2.88930999107875e-07 1.00039396061099e-05 -1.52210269333732e-05 7.34829816336367e-05 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 758 0 0 0 0 0 2440 +1065 1103 0.997292580323223 -0.0668706049563267 -0.0305913619347517 0.00317774394601092 0.0642986319619865 0.994839551895256 -0.0784853611360966 -0.00319841947859538 0.0356818603784205 0.0763058856027593 0.996445792134381 0.123866935219869 4.18671300756686e-05 3.41946727689692e-05 2.7011181188125e-06 4.71831481106026e-07 -5.41291848603358e-06 2.13299913543599e-05 3.41946727689692e-05 4.43508621702777e-05 1.62257764842419e-06 1.72923049695996e-06 2.17195800967577e-06 1.36767889691276e-05 2.7011181188125e-06 1.62257764842419e-06 1.33849386269663e-05 -2.75150035942848e-06 -3.01960842514771e-06 4.82304990459279e-06 4.71831481106026e-07 1.72923049695996e-06 -2.75150035942848e-06 2.48184587090765e-05 6.26024979731846e-06 8.61434058721472e-06 -5.41291848603358e-06 2.17195800967577e-06 -3.01960842514771e-06 6.26024979731846e-06 4.90498497983039e-05 -8.93763691876477e-06 2.13299913543599e-05 1.36767889691276e-05 4.82304990459279e-06 8.61434058721472e-06 -8.93763691876477e-06 5.57896125695829e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 584 0 0 0 0 0 2431 +1064 1129 0.991777334556741 -0.125571175449248 -0.0246900497330471 0.0370955133896131 0.123732239381809 0.990146602318983 -0.0655746814993133 -0.0242603586183763 0.0326810586898421 0.061980527687878 0.997542160808476 0.153271406898836 2.52185276777547e-05 7.96236717282479e-06 -8.63886481921834e-06 4.28405979517893e-06 -3.95375106185989e-06 8.85609611521758e-06 7.96236717282479e-06 4.62146406032592e-05 -5.0467549176804e-07 -5.25349204142526e-06 1.01824168791747e-05 -1.72411293797488e-05 -8.63886481921834e-06 -5.0467549176804e-07 1.46464455080574e-05 -1.04332076263733e-06 3.13052010880279e-07 -2.31218706069326e-06 4.28405979517893e-06 -5.25349204142526e-06 -1.04332076263733e-06 3.98422900198349e-05 -5.22736415825743e-05 8.42070525846217e-06 -3.95375106185989e-06 1.01824168791747e-05 3.13052010880279e-07 -5.22736415825743e-05 0.000179999606812758 -2.21782403182181e-06 8.85609611521758e-06 -1.72411293797488e-05 -2.31218706069326e-06 8.42070525846217e-06 -2.21782403182181e-06 5.13257580289702e-05 0 0 0 0 0 0 0 0 0 6 0 0 0 0 0 0 0 0 809 0 0 0 0 0 2466 +1065 1102 0.997529489101433 -0.0656063217383535 -0.0251143170522036 0.00919422256492313 0.0636391164351915 0.995341747507624 -0.0724214645517311 -0.00101816678606072 0.0297486341263444 0.0706442935871903 0.997057873220599 0.114461928113529 2.635462793504e-05 2.08288885412691e-05 -4.75091886303538e-06 -4.10427181616428e-07 -1.4740321523604e-06 2.89903971287594e-06 2.08288885412691e-05 4.29274397213533e-05 -4.43579749637866e-06 4.92545766321348e-06 7.01237526010805e-07 -5.52533425087208e-06 -4.75091886303538e-06 -4.43579749637866e-06 1.17122669309846e-05 3.76246684502583e-07 1.14754096067114e-06 2.41114432028678e-06 -4.10427181616428e-07 4.92545766321348e-06 3.76246684502583e-07 2.33250891502879e-05 2.23564838614396e-06 2.08106887387552e-06 -1.4740321523604e-06 7.01237526010805e-07 1.14754096067114e-06 2.23564838614396e-06 4.87502608336856e-05 3.03213260348727e-06 2.89903971287594e-06 -5.52533425087208e-06 2.41114432028678e-06 2.08106887387552e-06 3.03213260348727e-06 4.38923087344997e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 628 0 0 0 0 0 2438 +1065 1109 0.997377462339135 -0.0656947526124942 -0.0303709910462396 0.0112265566313917 0.0633021342030596 0.995249363585319 -0.0739698863616453 -0.00490163166458624 0.035086142895528 0.071853348997803 0.996797902693678 0.117211894378556 2.96212401050867e-05 1.96876392649229e-05 -5.37628311097432e-06 3.61477798835136e-06 3.60123362155726e-06 1.44964371206374e-06 1.96876392649229e-05 3.97045047589721e-05 -2.95074950190275e-06 6.43230255165257e-07 4.95408442528123e-06 -4.90681320893183e-06 -5.37628311097432e-06 -2.95074950190275e-06 1.232879822408e-05 9.03692174827414e-07 -5.84441615559789e-08 -1.35226754100463e-06 3.61477798835136e-06 6.43230255165257e-07 9.03692174827414e-07 2.32838795604676e-05 1.82541280934834e-06 3.59009142826188e-06 3.60123362155726e-06 4.95408442528123e-06 -5.84441615559789e-08 1.82541280934834e-06 6.48311291409547e-05 -7.20208577372617e-06 1.44964371206374e-06 -4.90681320893183e-06 -1.35226754100463e-06 3.59009142826188e-06 -7.20208577372617e-06 4.14423785098046e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 761 0 0 0 0 0 2353 +1065 1108 0.997315080198501 -0.0646404141701915 -0.0344128996825889 0.0104339970286984 0.061931148628231 0.995281336535768 -0.0746966798001293 -0.00847036911163387 0.0390789411095769 0.0723648948004569 0.996612341064605 0.117235087844128 2.6372290794969e-05 2.41087301134715e-05 -1.59112189455495e-06 4.27161704958781e-06 -1.91523997451439e-06 -4.70071330797083e-06 2.41087301134715e-05 4.01550264950652e-05 -1.08336824177868e-06 4.22093809160074e-06 -3.04232175770996e-06 -2.01428029214416e-06 -1.59112189455495e-06 -1.08336824177868e-06 1.19964004925256e-05 1.4629277677991e-06 7.97159120468974e-09 -3.39684553978488e-07 4.27161704958781e-06 4.22093809160074e-06 1.4629277677991e-06 2.36703798472648e-05 2.8431206936098e-06 2.32040098259956e-06 -1.91523997451439e-06 -3.04232175770996e-06 7.97159120468974e-09 2.8431206936098e-06 6.87516763850612e-05 -8.46078947198123e-06 -4.70071330797083e-06 -2.01428029214416e-06 -3.39684553978488e-07 2.32040098259956e-06 -8.46078947198123e-06 3.85669010512594e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 642 0 0 0 0 0 2336 +1065 1106 0.997340222339247 -0.0662122553569435 -0.0304699547890789 0.00810801508622969 0.0637968912139792 0.9951871446725 -0.0743808022948737 -0.00742426378148216 0.0352482279800461 0.0722390775075672 0.99676430418887 0.120144212722651 2.76927606736723e-05 2.66947063004291e-05 -2.81832328126495e-06 9.12698646072254e-07 -1.77620481139371e-07 -6.3969747797859e-07 2.66947063004291e-05 3.68165124046868e-05 -2.1012122776972e-06 3.78501417974032e-07 -3.47700629132092e-08 4.49201486962217e-06 -2.81832328126495e-06 -2.1012122776972e-06 1.11253610547557e-05 2.69387572073226e-06 1.99733086782241e-06 3.32092596407809e-06 9.12698646072254e-07 3.78501417974032e-07 2.69387572073226e-06 2.03697212076025e-05 1.54469529061799e-06 1.16345941373825e-06 -1.77620481139371e-07 -3.47700629132092e-08 1.99733086782241e-06 1.54469529061799e-06 4.26760159586679e-05 3.96668389721751e-06 -6.3969747797859e-07 4.49201486962217e-06 3.32092596407809e-06 1.16345941373825e-06 3.96668389721751e-06 3.404079697681e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 743 0 0 0 0 0 2442 +1065 1104 0.99735009461499 -0.066787925766982 -0.0288472137859882 0.00605891291030051 0.0644330382890482 0.995021804909647 -0.0760262542230611 -0.0070684975397635 0.0337812425513399 0.0739660782121884 0.996688440248805 0.123188183961785 4.39564298642871e-05 3.61714697575159e-05 3.37635288701081e-06 -4.48673433287207e-06 -2.50870097670973e-06 2.86435867614269e-05 3.61714697575159e-05 5.27978921517703e-05 2.70336002428907e-06 2.92215016220769e-06 1.54025031832576e-08 2.56552305624119e-05 3.37635288701081e-06 2.70336002428907e-06 1.30125534781421e-05 -3.21533555671193e-06 -1.2908155842582e-06 6.91277398327722e-06 -4.48673433287207e-06 2.92215016220769e-06 -3.21533555671193e-06 2.44751649211235e-05 5.26495441301333e-06 1.03814706601619e-06 -2.50870097670973e-06 1.54025031832576e-08 -1.2908155842582e-06 5.26495441301333e-06 5.2696055120775e-05 2.58390386207984e-06 2.86435867614269e-05 2.56552305624119e-05 6.91277398327722e-06 1.03814706601619e-06 2.58390386207984e-06 6.76834806971009e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 675 0 0 0 0 0 2517 +1065 1110 0.997164246658888 -0.0650361757761638 -0.0378650369816704 0.0104464563340711 0.0619778626773309 0.99510293673283 -0.0769992846956901 -0.0101604089265381 0.0426873485140652 0.0744341396545291 0.996311873426554 0.125143461822246 2.70929859719131e-05 2.44995617148619e-05 -3.58091021802148e-06 1.66659214256838e-06 -5.00154292100815e-06 -9.43976686917737e-07 2.44995617148619e-05 3.87366288095343e-05 -3.19338520982487e-06 2.73850310460857e-07 1.79957660270168e-06 1.36626656190515e-06 -3.58091021802148e-06 -3.19338520982487e-06 1.18617173952629e-05 2.55088374514544e-06 6.22598899930176e-07 3.09780614614453e-06 1.66659214256838e-06 2.73850310460857e-07 2.55088374514544e-06 2.05236047301177e-05 -3.262655029188e-06 4.16134006699365e-06 -5.00154292100815e-06 1.79957660270168e-06 6.22598899930176e-07 -3.262655029188e-06 6.69814763806144e-05 -2.73404593818436e-06 -9.43976686917737e-07 1.36626656190515e-06 3.09780614614453e-06 4.16134006699365e-06 -2.73404593818436e-06 2.67051915103269e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 686 0 0 0 0 0 2408 +1065 1101 0.997442166338399 -0.0652723481457977 -0.0291315186301032 0.00722075232220058 0.0630076618242034 0.995350336593803 -0.0728542517225285 0.000983007900612358 0.0337514349562964 0.0708323937908108 0.996917054036219 0.116941042203372 2.37271917920379e-05 1.87074832133735e-05 -2.58483177478827e-06 -1.60205229436556e-06 -1.32627560548209e-06 2.75343125795137e-06 1.87074832133735e-05 4.92077944264966e-05 2.09400751859953e-07 -2.17190205709433e-07 -2.06705033863225e-06 -1.17003373598425e-05 -2.58483177478827e-06 2.09400751859953e-07 1.13472797087622e-05 1.62008926862313e-06 9.81638436514135e-07 3.74066079302631e-06 -1.60205229436556e-06 -2.17190205709433e-07 1.62008926862313e-06 2.26376017609062e-05 -5.55025281787994e-06 1.11824464882068e-06 -1.32627560548209e-06 -2.06705033863225e-06 9.81638436514135e-07 -5.55025281787994e-06 6.03207925192159e-05 1.81714028465192e-06 2.75343125795137e-06 -1.17003373598425e-05 3.74066079302631e-06 1.11824464882068e-06 1.81714028465192e-06 4.50348623575172e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 686 0 0 0 0 0 2459 +1065 1105 0.997453180611072 -0.0663447192969015 -0.0261826413921644 0.0109933346988688 0.0643308459961178 0.995368371144222 -0.0714377209821339 -0.0118499496688248 0.030800888660542 0.0695714305380649 0.997101359597212 0.116858094780362 3.61330969929418e-05 3.15470822425664e-05 2.12643010747346e-08 5.22905212516258e-07 -9.79151570632672e-06 1.64994775058718e-05 3.15470822425664e-05 5.63592740538605e-05 3.18005892447058e-06 1.44988265064958e-06 -6.78013589172993e-06 1.65758585647503e-05 2.12643010747346e-08 3.18005892447058e-06 1.26693889156494e-05 -3.27309932713495e-07 -1.65760627487959e-06 4.60538987274005e-06 5.22905212516258e-07 1.44988265064958e-06 -3.27309932713495e-07 2.2871495658896e-05 -4.62909828758608e-08 3.48929679075515e-06 -9.79151570632672e-06 -6.78013589172993e-06 -1.65760627487959e-06 -4.62909828758608e-08 5.38070003991744e-05 -6.38148960148741e-06 1.64994775058718e-05 1.65758585647503e-05 4.60538987274005e-06 3.48929679075515e-06 -6.38148960148741e-06 5.80815747909201e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 718 0 0 0 0 0 2465 +1065 1111 0.997324039818236 -0.0661311885872718 -0.0311676995729244 0.0152887478525801 0.0636197548388057 0.995102843951486 -0.0756495654575379 -0.0188418768245977 0.0360178621642602 0.0734642488268867 0.996647238369433 0.120266762107988 2.25066089116377e-05 1.57629307038884e-05 -2.7984970672701e-06 4.12230675622977e-07 3.28431636635377e-06 2.47586354210767e-06 1.57629307038884e-05 3.69238811345381e-05 -1.61333194974104e-06 3.12382913285636e-07 4.30924632257665e-06 -3.2180935393119e-06 -2.7984970672701e-06 -1.61333194974104e-06 1.16193895956198e-05 2.13164740502743e-06 5.47578093758354e-07 6.98455488429292e-07 4.12230675622977e-07 3.12382913285636e-07 2.13164740502743e-06 2.07656274853354e-05 4.64789907502911e-06 -2.46571326571439e-06 3.28431636635377e-06 4.30924632257665e-06 5.47578093758354e-07 4.64789907502911e-06 6.12200888423985e-05 2.97911764466413e-06 2.47586354210767e-06 -3.2180935393119e-06 6.98455488429292e-07 -2.46571326571439e-06 2.97911764466413e-06 3.19124362230396e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 669 0 0 0 0 0 2468 +1065 1112 0.99700178168033 -0.0659709294759509 -0.0404386422908316 0.012283985470004 0.0625020663471306 0.994690822545756 -0.0817536497386261 -0.0278497393881991 0.0456173106242094 0.0789810357448305 0.99583184171028 0.12974581549577 2.94783090667818e-05 2.27875343787409e-05 -4.28612017567772e-06 3.85348921702388e-06 -5.20513609930674e-06 7.83562340838833e-06 2.27875343787409e-05 4.71872803026631e-05 -1.36907049441538e-06 3.87116922146509e-06 -7.12488465945027e-06 5.45620516265413e-06 -4.28612017567772e-06 -1.36907049441538e-06 1.35235781461278e-05 2.37993205966633e-06 -2.67489579586379e-06 9.50255464844722e-07 3.85348921702388e-06 3.87116922146509e-06 2.37993205966633e-06 2.34451645230136e-05 -1.25570791892048e-05 7.00560124193546e-06 -5.20513609930674e-06 -7.12488465945027e-06 -2.67489579586379e-06 -1.25570791892048e-05 8.97839785957775e-05 -9.63223387451734e-06 7.83562340838833e-06 5.45620516265413e-06 9.50255464844722e-07 7.00560124193546e-06 -9.63223387451734e-06 4.25121777638239e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 698 0 0 0 0 0 2456 +1065 1107 0.997278023820865 -0.0659179985289374 -0.0330357484233144 0.00737777939325269 0.0632969756269445 0.995177705402745 -0.0749321529505802 -0.00617859364205565 0.0378158178601429 0.072637126452429 0.996641265340896 0.121115060781333 2.48087161809632e-05 2.1029780894857e-05 -3.36518164558717e-06 -1.25274328727625e-06 -2.26949667262299e-06 4.40794298023918e-06 2.1029780894857e-05 3.80246481088616e-05 -1.634150576419e-06 -2.33515794895077e-06 -1.97712532550986e-06 3.92199822073791e-06 -3.36518164558717e-06 -1.634150576419e-06 1.20611464603641e-05 5.31708779662781e-07 4.73413598612169e-08 2.18273365136513e-06 -1.25274328727625e-06 -2.33515794895077e-06 5.31708779662781e-07 2.06823442384586e-05 -6.52613633740304e-08 3.29898933364487e-06 -2.26949667262299e-06 -1.97712532550986e-06 4.73413598612169e-08 -6.52613633740304e-08 5.68998031689391e-05 -1.93270694073625e-07 4.40794298023918e-06 3.92199822073791e-06 2.18273365136513e-06 3.29898933364487e-06 -1.93270694073625e-07 3.3623418638409e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 658 0 0 0 0 0 2397 +1065 1135 0.997446640193026 -0.0654679301242121 -0.0285333154907545 0.0142051515823377 0.0632854205385845 0.995420446524091 -0.0716455873661006 -0.0170778347771475 0.0330931339540116 0.0696569075327804 0.997021945454598 0.112744461423091 3.59208252632295e-05 2.72864194377791e-05 -3.99399664231893e-06 1.76043789569077e-06 7.17288965900061e-06 1.89769995659456e-05 2.72864194377791e-05 4.62964260245684e-05 -1.35562361638539e-06 3.72967118891794e-06 -1.73007419754505e-06 6.88582539939015e-06 -3.99399664231893e-06 -1.35562361638539e-06 1.36783168905507e-05 6.24207466528953e-07 3.33919827207019e-06 1.06890359255051e-06 1.76043789569077e-06 3.72967118891794e-06 6.24207466528953e-07 3.44839061318789e-05 -4.21357185199609e-05 7.51877753971415e-06 7.17288965900061e-06 -1.73007419754505e-06 3.33919827207019e-06 -4.21357185199609e-05 0.000157839730951372 -3.19187393329476e-06 1.89769995659456e-05 6.88582539939015e-06 1.06890359255051e-06 7.51877753971415e-06 -3.19187393329476e-06 6.26399678912502e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 827 0 0 0 0 0 2422 +1065 1134 0.997412519574907 -0.0656195228774852 -0.0293656944846664 0.0174605376800151 0.063252688527644 0.995150135131025 -0.0753346264524324 -0.0202098545122215 0.0341666970785943 0.0732822404545185 0.996725814878247 0.116593993095618 3.67224540298362e-05 2.57071014705961e-05 -2.07140682975324e-06 3.10296006092419e-06 7.92279065720417e-07 6.91065196306682e-06 2.57071014705961e-05 5.24006766442877e-05 4.20345154299522e-07 5.65992412204412e-06 -9.15131210007686e-06 -4.51380346435416e-06 -2.07140682975324e-06 4.20345154299522e-07 1.25760182909325e-05 2.2913670365584e-06 -9.67049621039036e-07 1.52268086196332e-06 3.10296006092419e-06 5.65992412204412e-06 2.2913670365584e-06 3.59214903551771e-05 -4.34602763561095e-05 9.72158301148017e-07 7.92279065720417e-07 -9.15131210007686e-06 -9.67049621039036e-07 -4.34602763561095e-05 0.000170164464745927 2.52544900358493e-06 6.91065196306682e-06 -4.51380346435416e-06 1.52268086196332e-06 9.72158301148017e-07 2.52544900358493e-06 4.91055218834506e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 777 0 0 0 0 0 2511 +1065 1113 0.997109033893426 -0.0660768546148637 -0.0375156475663664 0.00957086990467248 0.062959007091659 0.994888011032978 -0.0789557403161829 -0.0199188898587583 0.0425410149637978 0.0763655340258304 0.996171956671537 0.126289613055077 4.05566101766303e-05 3.67775014645344e-05 -1.04605461120841e-06 -3.74474800458535e-07 2.29272157906106e-06 1.78390917521676e-05 3.67775014645344e-05 7.23630149410855e-05 3.14736297435563e-06 -4.5538523357894e-06 6.49576236349908e-06 1.62735408825132e-05 -1.04605461120841e-06 3.14736297435563e-06 1.27203016433065e-05 1.0517329699712e-06 -6.69267884546004e-07 5.98255575359662e-06 -3.74474800458535e-07 -4.5538523357894e-06 1.0517329699712e-06 2.24527635927299e-05 -4.2026421175694e-06 2.09122245510607e-06 2.29272157906106e-06 6.49576236349908e-06 -6.69267884546004e-07 -4.2026421175694e-06 6.15747956323951e-05 -5.26072340501921e-06 1.78390917521676e-05 1.62735408825132e-05 5.98255575359662e-06 2.09122245510607e-06 -5.26072340501921e-06 5.46949289073516e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 690 0 0 0 0 0 2476 +1065 1133 0.997339739368672 -0.0654450916913601 -0.0320995988999777 0.0161401913484838 0.0628738148044626 0.995164949036694 -0.0754559979108952 -0.0266597421135658 0.0368826204053363 0.0732370410537206 0.996632333475957 0.118512489592535 3.55198262746121e-05 3.4410534672664e-05 -1.64221067664297e-06 -8.86406000938486e-07 9.83190901307477e-07 6.66724983197382e-06 3.4410534672664e-05 5.34848069008342e-05 1.09224792065365e-06 -4.26873182960512e-06 3.73609318992029e-06 1.21320291701754e-05 -1.64221067664297e-06 1.09224792065365e-06 1.29268083013159e-05 2.42134715656406e-06 -1.92833764577977e-06 4.68128014277269e-06 -8.86406000938486e-07 -4.26873182960512e-06 2.42134715656406e-06 3.1894292341337e-05 -4.04055806916463e-05 -9.45291454038321e-07 9.83190901307477e-07 3.73609318992029e-06 -1.92833764577977e-06 -4.04055806916463e-05 0.000140098860951494 1.93365282561273e-06 6.66724983197382e-06 1.21320291701754e-05 4.68128014277269e-06 -9.45291454038321e-07 1.93365282561273e-06 4.04590485462307e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 762 0 0 0 0 0 2325 +1065 1136 0.997423323299225 -0.0650442261532248 -0.0302648770501085 0.0156337704564472 0.0626586325795214 0.995285843087732 -0.0740269296432556 -0.0179033507844181 0.0349372280239086 0.0719398303672668 0.99679689551319 0.121416911597852 5.10595187065131e-05 3.46809186368294e-05 -1.32379710182596e-06 5.57236893770073e-06 -1.46568079796156e-05 3.42186243946052e-05 3.46809186368294e-05 5.63832183934294e-05 -4.72004206045197e-07 4.51172692622627e-06 -2.14375239776094e-06 1.3217416988882e-05 -1.32379710182596e-06 -4.72004206045197e-07 1.09850718501494e-05 1.30988666086286e-06 -6.16202551902712e-07 5.02415715722341e-06 5.57236893770073e-06 4.51172692622627e-06 1.30988666086286e-06 2.55993864972559e-05 -1.64661489267059e-05 1.27876346629426e-05 -1.46568079796156e-05 -2.14375239776094e-06 -6.16202551902712e-07 -1.64661489267059e-05 9.43892672305634e-05 -2.46801988770235e-05 3.42186243946052e-05 1.3217416988882e-05 5.02415715722341e-06 1.27876346629426e-05 -2.46801988770235e-05 6.83365016148907e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 780 0 0 0 0 0 2487 +1065 1130 0.997280169207114 -0.0647763214989302 -0.0351609482138557 0.0120879237759151 0.0618702788763693 0.99501230763635 -0.0782468928708709 -0.0164178754016717 0.0400541221098467 0.0758586568906442 0.996313771598464 0.122250911526265 4.32666401237706e-05 3.72676552076868e-05 -9.66704757030857e-07 2.64200729121972e-06 -1.48244078688316e-06 1.10297496640299e-05 3.72676552076868e-05 4.86219860706627e-05 -2.57517885473602e-06 -1.8342586406069e-06 1.27090870453246e-05 9.01302290874981e-06 -9.66704757030857e-07 -2.57517885473602e-06 1.29267652946328e-05 5.40587584219344e-06 -5.66675366973064e-06 4.19274741441694e-06 2.64200729121972e-06 -1.8342586406069e-06 5.40587584219344e-06 3.65309330523562e-05 -5.63383806968211e-05 6.24950052520026e-06 -1.48244078688316e-06 1.27090870453246e-05 -5.66675366973064e-06 -5.63383806968211e-05 0.000212372004901209 -1.38713049306894e-05 1.10297496640299e-05 9.01302290874981e-06 4.19274741441694e-06 6.24950052520026e-06 -1.38713049306894e-05 5.12491667960585e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 784 0 0 0 0 0 2505 +1065 1114 0.997189558873718 -0.0662204498246 -0.0350404865586581 0.011531559065497 0.0633881812363923 0.995048387211472 -0.0765548534541784 -0.0243136351016959 0.0399364764692901 0.0741185478330227 0.996449456176449 0.122877835392204 2.62552461693011e-05 1.40253700439388e-05 -5.90896444461041e-06 3.04558857227815e-07 1.05696297671803e-06 7.34350027053464e-06 1.40253700439388e-05 4.15128693605751e-05 -7.09989656125281e-07 7.3941002478391e-07 1.03726440830364e-05 -5.54805494249439e-06 -5.90896444461041e-06 -7.09989656125281e-07 1.27576810814744e-05 8.98917261646067e-07 -5.57587594423439e-07 -1.79193220279837e-06 3.04558857227815e-07 7.3941002478391e-07 8.98917261646067e-07 2.00551802331503e-05 -4.72994733613867e-06 6.06718070564632e-06 1.05696297671803e-06 1.03726440830364e-05 -5.57587594423439e-07 -4.72994733613867e-06 6.25985182453058e-05 4.5263587402114e-06 7.34350027053464e-06 -5.54805494249439e-06 -1.79193220279837e-06 6.06718070564632e-06 4.5263587402114e-06 4.07107106962182e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 788 0 0 0 0 0 2473 +1065 1129 0.997452642462727 -0.0653127482189948 -0.0286787545790356 0.0157124862848903 0.0631833091089986 0.995561217900002 -0.069754790971676 -0.0142295513691215 0.0331073329363616 0.0677650819637051 0.997151843087247 0.111950813487841 4.00309926651338e-05 3.40067242482802e-05 -2.87759412375861e-06 7.94581047384317e-06 -6.18817318905968e-06 1.64600957578923e-05 3.40067242482802e-05 4.83645414518404e-05 -1.74594747563667e-06 4.57084892460295e-07 1.28416941669239e-05 9.277380512871e-06 -2.87759412375861e-06 -1.74594747563667e-06 1.19013322498325e-05 2.19981489736709e-06 2.01394072915904e-06 2.9097809449455e-06 7.94581047384317e-06 4.57084892460295e-07 2.19981489736709e-06 3.85116865033876e-05 -4.75882330834573e-05 5.17007778580237e-06 -6.18817318905968e-06 1.28416941669239e-05 2.01394072915904e-06 -4.75882330834573e-05 0.000180365333297858 -6.31141698319567e-06 1.64600957578923e-05 9.277380512871e-06 2.9097809449455e-06 5.17007778580237e-06 -6.31141698319567e-06 4.8353436473745e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 842 0 0 0 0 0 2450 +1065 1132 0.997319504007715 -0.0656951371166503 -0.0322173227477082 0.0141127065972813 0.0632082782881775 0.995332032567919 -0.0729305045921004 -0.0160744240839627 0.0368581128335376 0.0706986131648887 0.996816525552677 0.115095369783909 2.37457315829877e-05 2.10374947268976e-05 -2.99804915990003e-06 1.45392697703533e-06 2.32495869577399e-07 8.27107005182235e-07 2.10374947268976e-05 3.51461559747374e-05 -1.29721442685639e-06 1.18173267415533e-06 -8.49104829924838e-06 4.32554719100557e-06 -2.99804915990003e-06 -1.29721442685639e-06 1.14999819761094e-05 2.61759837837311e-06 1.27292928318042e-06 2.25707144373498e-06 1.45392697703533e-06 1.18173267415533e-06 2.61759837837311e-06 2.71020764595114e-05 -2.81145394000885e-05 1.63976018864244e-06 2.32495869577399e-07 -8.49104829924838e-06 1.27292928318042e-06 -2.81145394000885e-05 0.000121095329996101 -6.94695758706931e-06 8.27107005182235e-07 4.32554719100557e-06 2.25707144373498e-06 1.63976018864244e-06 -6.94695758706931e-06 3.82005458161683e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 855 0 0 0 0 0 2425 +1065 1116 0.997186465286755 -0.0659744836753029 -0.0355882136765168 0.0101946715320602 0.0629052901610802 0.994695874090006 -0.0813820774991039 -0.0182816384589035 0.0407685898536917 0.0789144192913883 0.996047406757954 0.129506049633549 4.56089846304376e-05 3.29682012671767e-05 -1.45069536020648e-06 1.44918529813008e-06 1.81518275631827e-06 1.61132034622611e-05 3.29682012671767e-05 5.26585703864424e-05 1.56008445193647e-06 -1.13974536731413e-06 2.86260456367861e-06 5.64856629057548e-06 -1.45069536020648e-06 1.56008445193647e-06 1.23956193356161e-05 1.97570181106361e-06 4.67055868334327e-07 4.69350135221614e-06 1.44918529813008e-06 -1.13974536731413e-06 1.97570181106361e-06 2.06315276812653e-05 -7.37851655773812e-06 2.31546448245075e-06 1.81518275631827e-06 2.86260456367861e-06 4.67055868334327e-07 -7.37851655773812e-06 7.00746437326395e-05 -1.70726472872184e-06 1.61132034622611e-05 5.64856629057548e-06 4.69350135221614e-06 2.31546448245075e-06 -1.70726472872184e-06 4.85313206522658e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 716 0 0 0 0 0 2441 +1065 1127 0.997221043142282 -0.0649747386307082 -0.0364482434980229 0.0113364897072504 0.0619087890898734 0.994891990599439 -0.0797322323437105 -0.0154148948314637 0.0414426464845766 0.0772541932904423 0.996149736069532 0.123168996429329 3.16693603385486e-05 2.41596537507303e-05 -4.60779238079208e-07 1.17121966118294e-06 -2.76767618382451e-06 1.58699611875105e-05 2.41596537507303e-05 4.63935724600504e-05 1.11293014229635e-06 3.62031426687016e-07 -1.59261538203613e-06 7.15860165972617e-06 -4.60779238079208e-07 1.11293014229635e-06 1.23286938426039e-05 2.08474837701457e-06 -1.10850632573056e-06 2.71016896484909e-06 1.17121966118294e-06 3.62031426687016e-07 2.08474837701457e-06 4.03832479301266e-05 -6.88714180671173e-05 1.5797998212949e-06 -2.76767618382451e-06 -1.59261538203613e-06 -1.10850632573056e-06 -6.88714180671173e-05 0.000239504577539605 4.52526874502528e-06 1.58699611875105e-05 7.15860165972617e-06 2.71016896484909e-06 1.5797998212949e-06 4.52526874502528e-06 5.09615721688594e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 781 0 0 0 0 0 2516 +1065 1115 0.997426957053879 -0.0654091695689507 -0.0293446056122736 0.0104613756394997 0.0630519019284856 0.995179530171954 -0.0751143154793368 -0.0135276291127876 0.0341163158245474 0.0730708099245448 0.996743063046606 0.118112409330691 2.36053160114454e-05 2.20414611125173e-05 -2.44699994948735e-06 -1.82067551376287e-06 2.45757593100003e-06 -5.19613891685997e-06 2.20414611125173e-05 3.26482766879908e-05 -3.04321040693323e-06 -1.07545378609906e-06 2.13272235482141e-06 -1.52087528601337e-06 -2.44699994948735e-06 -3.04321040693323e-06 1.17326901138723e-05 2.20852405070754e-06 2.76246495501551e-06 7.93612653729239e-07 -1.82067551376287e-06 -1.07545378609906e-06 2.20852405070754e-06 2.08797479469219e-05 -5.30938349784772e-06 2.76148613607117e-06 2.45757593100003e-06 2.13272235482141e-06 2.76246495501551e-06 -5.30938349784772e-06 4.98417526309478e-05 5.2661471196571e-06 -5.19613891685997e-06 -1.52087528601337e-06 7.93612653729239e-07 2.76148613607117e-06 5.2661471196571e-06 2.66365812345323e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 787 0 0 0 0 0 2388 +1065 1128 0.997303652413507 -0.0655620720289075 -0.0329702834982608 0.0183354582374746 0.0628557356276753 0.995022485951956 -0.0773266380278729 -0.0300873623165455 0.0378758680611168 0.0750457671109186 0.996460511740104 0.121569416408069 3.15383913105546e-05 2.28642675158157e-05 -3.12709015925457e-06 4.8410489428625e-07 -7.9960348137456e-07 1.5627158642851e-05 2.28642675158157e-05 4.52037052800478e-05 -3.33430765090479e-07 2.87073526367802e-06 -2.56537063156449e-06 -4.43715934028578e-07 -3.12709015925457e-06 -3.33430765090479e-07 1.27006016444676e-05 1.65838037702277e-06 9.75126420011858e-07 3.27121499796059e-06 4.8410489428625e-07 2.87073526367802e-06 1.65838037702277e-06 2.86352029043006e-05 -3.34697069556106e-05 -7.19460224965335e-07 -7.9960348137456e-07 -2.56537063156449e-06 9.75126420011858e-07 -3.34697069556106e-05 0.000126174702061528 5.56341599966359e-06 1.5627158642851e-05 -4.43715934028578e-07 3.27121499796059e-06 -7.19460224965335e-07 5.56341599966359e-06 5.83719400212772e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 776 0 0 0 0 0 2563 +1066 1104 0.998827663552727 -0.035195320511317 -0.0332353416697607 -0.00586419432279365 0.0315637381631128 0.994066044900072 -0.104098169099646 0.00167479579935696 0.0367018930706649 0.10292709939969 0.994011560925825 0.104568632613829 4.22588748968368e-05 3.17360135320715e-05 1.69736245514884e-06 -8.17175674793627e-07 -3.28513495311751e-06 1.46520196146176e-05 3.17360135320715e-05 6.05110351070531e-05 5.03187109419919e-06 5.07625138980828e-06 4.89176194831141e-06 3.54998252023493e-06 1.69736245514884e-06 5.03187109419919e-06 1.64017098416027e-05 -6.65125470709369e-07 -2.46203211744103e-06 4.98989414773746e-06 -8.17175674793627e-07 5.07625138980828e-06 -6.65125470709369e-07 2.5615863046865e-05 1.24566428775969e-05 3.92393216537863e-06 -3.28513495311751e-06 4.89176194831141e-06 -2.46203211744103e-06 1.24566428775969e-05 5.22852702035327e-05 -4.66638416929194e-07 1.46520196146176e-05 3.54998252023493e-06 4.98989414773746e-06 3.92393216537863e-06 -4.66638416929194e-07 4.03528343777459e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 675 0 0 0 0 0 2476 +1066 1148 0.996665669719928 -0.0312637470679145 -0.0753665769489425 0.00374706997456101 0.0271179241083929 0.998094904041694 -0.0554182345266647 -0.0416780983722663 0.0769555780549978 0.0531896667152035 0.995614733901094 -0.0643769035261549 2.89641385850003e-05 7.7440166263029e-06 -9.24995317511407e-06 -5.42700009790416e-07 -9.19813900057618e-07 5.60155138473653e-07 7.7440166263029e-06 6.18309915294073e-05 -1.78837445203606e-06 -2.29872393890377e-06 2.25756924802651e-05 -1.40901562052174e-05 -9.24995317511407e-06 -1.78837445203606e-06 1.64674099052961e-05 -2.81488225131298e-06 -2.1437474491117e-06 1.48520246968421e-06 -5.42700009790416e-07 -2.29872393890377e-06 -2.81488225131298e-06 2.90006954094108e-05 6.20332251932534e-07 4.15849698995916e-06 -9.19813900057618e-07 2.25756924802651e-05 -2.1437474491117e-06 6.20332251932534e-07 9.12519144647791e-05 -8.38171015039296e-06 5.60155138473653e-07 -1.40901562052174e-05 1.48520246968421e-06 4.15849698995916e-06 -8.38171015039296e-06 2.93898092396341e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1173 0 0 0 0 0 3053 +1066 1103 0.998929529740692 -0.0334018698258732 -0.0320017140818194 -0.00791865792209981 0.0301174318387084 0.994718013139947 -0.098127542689891 0.00633646211984856 0.0351103248558007 0.0970586906312415 0.99465917562825 0.0948481454209162 2.73092612432547e-05 2.33452498585516e-05 -3.23262860767374e-06 -1.32971826832271e-06 -1.1893307986126e-07 -2.48116694887684e-06 2.33452498585516e-05 4.12177855746658e-05 -4.33744096514002e-06 2.92004298501033e-06 -1.45180583871832e-06 -3.85435109606146e-06 -3.23262860767374e-06 -4.33744096514002e-06 1.21565288005975e-05 -1.95274495110358e-07 2.24038696423367e-08 5.09188834462932e-06 -1.32971826832271e-06 2.92004298501033e-06 -1.95274495110358e-07 2.57540441956802e-05 4.72982080476701e-06 2.38612008094214e-06 -1.1893307986126e-07 -1.45180583871832e-06 2.24038696423367e-08 4.72982080476701e-06 5.01558830931612e-05 -1.73985061421458e-06 -2.48116694887684e-06 -3.85435109606146e-06 5.09188834462932e-06 2.38612008094214e-06 -1.73985061421458e-06 3.04714935754993e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 595 0 0 0 0 0 2448 +1066 1109 0.998791548606696 -0.0318535139118753 -0.0374272104665054 0.000143628709354224 0.0279498092736217 0.994538762620168 -0.100555744776288 -0.00650950246165798 0.0404258654008334 0.0993881446522257 0.994227210505316 0.0998890672116872 2.76352206789062e-05 2.39498348382824e-05 -4.24982721071725e-06 1.50068444292218e-07 6.94984386635829e-06 -1.75885991776416e-06 2.39498348382824e-05 4.3085461297387e-05 -1.82516410220205e-06 5.79860300928331e-07 4.7663710586962e-06 -6.74154739637557e-06 -4.24982721071725e-06 -1.82516410220205e-06 1.28723816571472e-05 -1.27442136803748e-06 2.34662161212773e-06 8.86787326127974e-07 1.50068444292218e-07 5.79860300928331e-07 -1.27442136803748e-06 2.9142516341598e-05 -5.94339020998239e-06 1.85013441180779e-06 6.94984386635829e-06 4.7663710586962e-06 2.34662161212773e-06 -5.94339020998239e-06 6.42853287374786e-05 7.16770103819282e-06 -1.75885991776416e-06 -6.74154739637557e-06 8.86787326127974e-07 1.85013441180779e-06 7.16770103819282e-06 2.78435948187052e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 768 0 0 0 0 0 2356 +1066 1070 0.992778050906615 -0.0269310832905157 -0.11690362864711 0.00628450887607714 0.0255829016982169 0.999587939476647 -0.0130179258536373 0.0236358975993901 0.117206044122142 0.00993317701597701 0.993057941519833 0.0727038725959515 5.57865768752528e-05 2.14272252702788e-05 -2.19378034772741e-06 1.19170687222983e-05 1.16295192240296e-06 3.07030581716256e-05 2.14272252702788e-05 9.93877591860636e-05 9.27076742972626e-06 -3.32480549368012e-07 1.31020929035976e-05 -1.44062420653386e-05 -2.19378034772741e-06 9.27076742972626e-06 2.2882829767666e-05 -8.05994292099382e-06 -5.25723817157336e-07 -4.55687435678381e-06 1.19170687222983e-05 -3.32480549368012e-07 -8.05994292099382e-06 4.20520179897905e-05 -2.45172113063942e-05 4.54806600255068e-06 1.16295192240296e-06 1.31020929035976e-05 -5.25723817157336e-07 -2.45172113063942e-05 0.00012887857951481 -6.10347523840609e-06 3.07030581716256e-05 -1.44062420653386e-05 -4.55687435678381e-06 4.54806600255068e-06 -6.10347523840609e-06 6.53951322314659e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1095 0 0 0 0 0 2140 +1066 1107 0.998821130048096 -0.0320274533066457 -0.0364772861399355 -0.0037010327247158 0.0283205468847383 0.994787235824829 -0.0979607169438078 0.00485622147645923 0.0394245709373412 0.0968121773057817 0.994521546036948 0.097517552436645 3.81180384984367e-05 3.43961497960986e-05 2.10051437198749e-06 -3.72602667756212e-06 -2.40459742564348e-06 5.08275071403414e-06 3.43961497960986e-05 5.07409728208757e-05 3.14672571270951e-06 -7.92673139321682e-07 -5.58552025320927e-06 -6.69720730045944e-07 2.10051437198749e-06 3.14672571270951e-06 1.66693086930062e-05 -2.42881290171141e-07 1.16023596056299e-06 6.29364423065675e-06 -3.72602667756212e-06 -7.92673139321682e-07 -2.42881290171141e-07 2.38804490927401e-05 1.00036521602437e-06 -2.13869135706003e-08 -2.40459742564348e-06 -5.58552025320927e-06 1.16023596056299e-06 1.00036521602437e-06 5.88100731307732e-05 -6.83072670022846e-07 5.08275071403414e-06 -6.69720730045944e-07 6.29364423065675e-06 -2.13869135706003e-08 -6.83072670022846e-07 3.8697808109364e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 653 0 0 0 0 0 2357 +1066 1102 0.998969806311972 -0.032618989633334 -0.0315488128512357 -0.0037638593928553 0.0294092142333642 0.994816484002665 -0.0973409537386552 0.0106788377487665 0.0345604426360244 0.0963128479065766 0.994750929194302 0.0939369084202442 3.21755986889038e-05 1.33342992991645e-05 -6.40723575513082e-06 2.24885029877746e-06 -4.82452824283794e-06 9.41049308305344e-06 1.33342992991645e-05 5.20403682223297e-05 -8.75848918939879e-07 4.20303263476747e-06 2.62265610260207e-06 -1.40255025815798e-05 -6.40723575513082e-06 -8.75848918939879e-07 1.53893611955355e-05 2.98915091873594e-06 1.66982169518126e-06 8.39239544076442e-08 2.24885029877746e-06 4.20303263476747e-06 2.98915091873594e-06 2.55705754407182e-05 5.40242875161832e-06 6.98022410459014e-06 -4.82452824283794e-06 2.62265610260207e-06 1.66982169518126e-06 5.40242875161832e-06 5.27822693533451e-05 -1.44958544522924e-06 9.41049308305344e-06 -1.40255025815798e-05 8.39239544076442e-08 6.98022410459014e-06 -1.44958544522924e-06 4.56344931068727e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 634 0 0 0 0 0 2295 +1066 1110 0.998818934587116 -0.0328089565993588 -0.0358372470638976 -0.00271613302293437 0.0291143176698013 0.99464618459297 -0.0991530331420579 0.00379738936105953 0.0388984886194739 0.0979925499286019 0.994426652771139 0.0972939351963742 2.7242653820248e-05 1.96000185643744e-05 -6.07622594871342e-06 1.40908907393686e-06 -1.79147345257287e-06 7.01100334774942e-07 1.96000185643744e-05 4.69827272347749e-05 -1.51825197624204e-06 -6.60907020211976e-07 2.21621701311137e-06 -9.73974693275372e-06 -6.07622594871342e-06 -1.51825197624204e-06 1.33134262206303e-05 1.33940588989041e-06 2.26249051846567e-06 -5.59304419670831e-07 1.40908907393686e-06 -6.60907020211976e-07 1.33940588989041e-06 2.19578601633208e-05 -2.33883121440473e-06 7.88772685982118e-06 -1.79147345257287e-06 2.21621701311137e-06 2.26249051846567e-06 -2.33883121440473e-06 6.24005808454985e-05 -1.50307281086681e-06 7.01100334774942e-07 -9.73974693275372e-06 -5.59304419670831e-07 7.88772685982118e-06 -1.50307281086681e-06 2.98920247163778e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 706 0 0 0 0 0 2385 +1066 1100 0.99893109829261 -0.0318290604512774 -0.0335197221753062 -0.0025587275917342 0.0284097551243762 0.994784535801783 -0.0979623047064731 0.00241920947049973 0.0364629493828155 0.0969053055328749 0.994625464726239 0.0970494252114301 3.07045049427374e-05 1.30592469028709e-05 -6.80347120915224e-06 2.36695656587144e-06 -4.56780510795305e-06 8.32119153858835e-06 1.30592469028709e-05 4.14252721164038e-05 7.7301211024716e-08 -2.05573523743643e-06 2.27342565771508e-06 -1.1963398780957e-05 -6.80347120915224e-06 7.7301211024716e-08 1.76774284274086e-05 -9.42909860786664e-07 2.32190566379829e-07 -2.6518682344562e-06 2.36695656587144e-06 -2.05573523743643e-06 -9.42909860786664e-07 2.45648958064821e-05 3.59399679130736e-08 7.40223343032393e-06 -4.56780510795305e-06 2.27342565771508e-06 2.32190566379829e-07 3.59399679130736e-08 5.36998108119537e-05 -4.6850459149487e-06 8.32119153858835e-06 -1.1963398780957e-05 -2.6518682344562e-06 7.40223343032393e-06 -4.6850459149487e-06 3.70750181383587e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 695 0 0 0 0 0 2395 +1066 1106 0.998826420862034 -0.0345181855956223 -0.0339746354082754 -0.00373128458303928 0.0308994206994278 0.994323482550393 -0.101813740965051 -0.000317809247705516 0.0372962034043525 0.100644457930106 0.994223157193382 0.0994816100620894 3.10080199627958e-05 1.76013139458036e-05 -3.05108797217536e-06 -1.0055380544802e-06 9.18949866959536e-07 6.64721173032264e-06 1.76013139458036e-05 4.28024948593244e-05 1.25515828980234e-06 -1.24773473094192e-06 1.15843799961598e-05 -6.325269759073e-06 -3.05108797217536e-06 1.25515828980234e-06 1.55371408838774e-05 2.18507387495521e-06 1.02401934928358e-06 3.02582363928693e-07 -1.0055380544802e-06 -1.24773473094192e-06 2.18507387495521e-06 2.48169639124664e-05 2.22907921790961e-07 4.15923827335687e-06 9.18949866959536e-07 1.15843799961598e-05 1.02401934928358e-06 2.22907921790961e-07 6.26985641842904e-05 -1.48930702389766e-06 6.64721173032264e-06 -6.325269759073e-06 3.02582363928693e-07 4.15923827335687e-06 -1.48930702389766e-06 3.57406397982756e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 752 0 0 0 0 0 2461 +1066 1101 0.999029987128837 -0.0322018937769693 -0.0300353600699812 -0.000456769448890034 0.02911707445826 0.994757783897354 -0.098026258475049 0.00549277152912659 0.0330345393845409 0.0970566299270779 0.994730480982085 0.0959699427639082 4.32292398576609e-05 1.75961993610708e-05 -9.08340295731746e-06 8.14493692296517e-06 -1.64220402184311e-06 1.29820433709115e-05 1.75961993610708e-05 6.04315454938773e-05 -2.62426989074159e-06 1.33593648826443e-06 9.58404156661611e-06 -2.09326638548577e-05 -9.08340295731746e-06 -2.62426989074159e-06 1.67442305743433e-05 -9.96902997604242e-07 8.32823295006299e-08 -2.16105337308439e-06 8.14493692296517e-06 1.33593648826443e-06 -9.96902997604242e-07 2.71216164790905e-05 2.40599182914746e-06 1.02212873795827e-05 -1.64220402184311e-06 9.58404156661611e-06 8.32823295006299e-08 2.40599182914746e-06 6.43962462021395e-05 -4.57327991950885e-06 1.29820433709115e-05 -2.09326638548577e-05 -2.16105337308439e-06 1.02212873795827e-05 -4.57327991950885e-06 4.5786519962887e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 690 0 0 0 0 0 2460 +1066 1105 0.99875795259118 -0.0336819594645193 -0.0367161782121153 -0.00318504288799575 0.0298533286403576 0.994513948655524 -0.10025360192376 -0.00531313011413114 0.0398914891294388 0.0990329820626815 0.994284233787707 0.0975648207652295 4.12122289648978e-05 2.65103921758379e-05 -1.17868332271019e-06 -2.12103808945866e-06 -7.17123655682693e-06 1.43855614864039e-05 2.65103921758379e-05 4.94115065520059e-05 -1.29652627774683e-06 2.30202387019281e-06 5.13948217738045e-08 4.35875435672377e-06 -1.17868332271019e-06 -1.29652627774683e-06 1.45648101810997e-05 -3.47184377432435e-07 -8.11387765964394e-07 4.88443135659467e-06 -2.12103808945866e-06 2.30202387019281e-06 -3.47184377432435e-07 2.55280540777784e-05 4.53840010233262e-06 3.10138935239362e-06 -7.17123655682693e-06 5.13948217738045e-08 -8.11387765964394e-07 4.53840010233262e-06 6.88104350768925e-05 2.72095707591835e-06 1.43855614864039e-05 4.35875435672377e-06 4.88443135659467e-06 3.10138935239362e-06 2.72095707591835e-06 4.33661082807476e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 726 0 0 0 0 0 2416 +1066 1108 0.998839626564111 -0.0317402230289747 -0.0362209697183663 -0.00285268677329464 0.0280029382677254 0.99465417197452 -0.099392724190742 0.00399597818733133 0.0391820858766073 0.0982630979348499 0.994388821201548 0.0994351729059988 2.43801145168753e-05 1.34134715046465e-05 -5.32246752294498e-06 1.39007321030108e-06 3.84027491713792e-07 2.28488351705211e-06 1.34134715046465e-05 4.07204979690959e-05 -1.03114589858292e-07 -1.20284924944653e-06 -3.56500953457368e-06 -7.5847799121181e-06 -5.32246752294498e-06 -1.03114589858292e-07 1.45829911361532e-05 1.01220089720922e-06 -5.27296060819843e-07 -1.11091373038347e-06 1.39007321030108e-06 -1.20284924944653e-06 1.01220089720922e-06 2.03991163421245e-05 6.22109581285919e-06 6.15423389528238e-06 3.84027491713792e-07 -3.56500953457368e-06 -5.27296060819843e-07 6.22109581285919e-06 5.60727626353461e-05 3.82700977937794e-06 2.28488351705211e-06 -7.5847799121181e-06 -1.11091373038347e-06 6.15423389528238e-06 3.82700977937794e-06 2.8981924173915e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 653 0 0 0 0 0 2378 +1066 1112 0.998932352830608 -0.0329854534225095 -0.0323436907420324 0.00182017114550373 0.0297370981831672 0.994914997441299 -0.0962281292451699 -0.00788194670088855 0.0353533514670031 0.0951635840481636 0.994833670927537 0.0921518299330311 3.73762521689137e-05 2.69720024350753e-05 -6.85204343668714e-06 3.91693912146688e-06 -1.38534354909358e-06 1.29617929845372e-05 2.69720024350753e-05 6.33357437273335e-05 -3.74246502117004e-07 6.36750453384574e-06 1.09884980291319e-06 7.0858575444368e-06 -6.85204343668714e-06 -3.74246502117004e-07 1.55090755795936e-05 1.78348501752529e-06 2.91662291663358e-07 -1.21561760863566e-08 3.91693912146688e-06 6.36750453384574e-06 1.78348501752529e-06 2.7998883431358e-05 -1.03014870005818e-05 7.58119721885382e-06 -1.38534354909358e-06 1.09884980291319e-06 2.91662291663358e-07 -1.03014870005818e-05 0.00010052858869476 -2.24483013632941e-06 1.29617929845372e-05 7.0858575444368e-06 -1.21561760863566e-08 7.58119721885382e-06 -2.24483013632941e-06 4.15502338883833e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 718 0 0 0 0 0 2402 +1066 1111 0.998756596014766 -0.0326216134842774 -0.0376973772387349 -0.000668703346948888 0.0287115341893425 0.994575533733693 -0.0999757745798174 -0.00875474369380737 0.0407542601637092 0.0987691147678396 0.994275491122298 0.100161720700209 4.33200151749724e-05 2.0364040637534e-05 -8.15473890332368e-06 7.88277021505082e-06 -7.48573412714608e-06 1.96911931342221e-05 2.0364040637534e-05 5.18059065163322e-05 -4.33392562780052e-06 1.13269557073912e-06 3.04453735260487e-06 -1.13093463367458e-05 -8.15473890332368e-06 -4.33392562780052e-06 1.57644593932099e-05 -4.88861647306418e-08 4.32962282748971e-07 -1.17520291076797e-06 7.88277021505082e-06 1.13269557073912e-06 -4.88861647306418e-08 2.38812606663836e-05 -2.9044376219211e-06 1.26259820604525e-05 -7.48573412714608e-06 3.04453735260487e-06 4.32962282748971e-07 -2.9044376219211e-06 5.59670818116249e-05 -9.32397208181702e-06 1.96911931342221e-05 -1.13093463367458e-05 -1.17520291076797e-06 1.26259820604525e-05 -9.32397208181702e-06 5.56503747702971e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 663 0 0 0 0 0 2453 +1066 1135 0.999026506937833 -0.0320922909014394 -0.0302675288104257 0.000556182295323648 0.0290024295100359 0.994811256908008 -0.0975162663950237 0.0014955561629104 0.0332399987681703 0.0965435031154723 0.994773569455926 0.0961492538252207 2.59510685071676e-05 1.42455000270349e-05 -3.65317048965575e-06 8.42214581193327e-07 -2.89605735958717e-06 4.21578934263492e-06 1.42455000270349e-05 4.70446821911154e-05 9.97519686839137e-07 -3.32237345142578e-06 9.93267414020248e-06 -9.90023431690379e-06 -3.65317048965575e-06 9.97519686839137e-07 1.49649563612354e-05 2.33957923763608e-06 6.26388587458735e-06 4.49634854606985e-07 8.42214581193327e-07 -3.32237345142578e-06 2.33957923763608e-06 3.08410668094496e-05 -2.27277933435679e-05 7.09083181143597e-06 -2.89605735958717e-06 9.93267414020248e-06 6.26388587458735e-06 -2.27277933435679e-05 0.000100579501964323 -6.33907079097079e-06 4.21578934263492e-06 -9.90023431690379e-06 4.49634854606985e-07 7.09083181143597e-06 -6.33907079097079e-06 3.60207527263479e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 892 0 0 0 0 0 2409 +1066 1133 0.998758507821774 -0.0316229555805579 -0.0384893717014681 -0.00198210006280783 0.0276703692382435 0.994681173632266 -0.099215490160342 0.000245951031898348 0.0414221404546286 0.0980272997786214 0.994321303592692 0.0993670719995101 5.86084614692323e-05 4.02111003748999e-05 -3.07538084425745e-06 8.85471787946186e-06 -1.42150265460767e-05 3.56163749096331e-05 4.02111003748999e-05 6.19011099032097e-05 -1.78613231261185e-06 -4.68913259229259e-06 2.25193536001578e-05 1.16790388092397e-05 -3.07538084425745e-06 -1.78613231261185e-06 1.29151555702579e-05 9.90425567665207e-07 6.47153445864189e-07 4.04912287329523e-06 8.85471787946186e-06 -4.68913259229259e-06 9.90425567665207e-07 3.84026006812083e-05 -4.85514169496009e-05 1.49083132445849e-05 -1.42150265460767e-05 2.25193536001578e-05 6.47153445864189e-07 -4.85514169496009e-05 0.000167833572313605 -2.01184248718233e-05 3.56163749096331e-05 1.16790388092397e-05 4.04912287329523e-06 1.49083132445849e-05 -2.01184248718233e-05 6.68949284508026e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 798 0 0 0 0 0 2374 +1066 1115 0.998653108680991 -0.032109331601224 -0.0407548689841528 -0.00348759815844492 0.0277575195599783 0.994274622738111 -0.103186698207014 -0.00761823178451843 0.0438347878935241 0.10191646286597 0.993826718280012 0.104510618562066 2.68457136011265e-05 1.8788548646719e-05 -3.91750251053768e-06 -3.04467026136946e-07 -7.97070114745696e-07 3.14884179654772e-06 1.8788548646719e-05 3.35970213439862e-05 -2.01968816713287e-06 -4.23082814589815e-07 1.91066700568202e-06 -3.85208946556074e-06 -3.91750251053768e-06 -2.01968816713287e-06 1.23585264242871e-05 1.15419073320062e-06 -2.55375937707975e-07 1.71792173204908e-06 -3.04467026136946e-07 -4.23082814589815e-07 1.15419073320062e-06 2.0938711773026e-05 -9.97613857722349e-06 1.54073854976372e-06 -7.97070114745696e-07 1.91066700568202e-06 -2.55375937707975e-07 -9.97613857722349e-06 6.8426391581933e-05 2.93438198188513e-06 3.14884179654772e-06 -3.85208946556074e-06 1.71792173204908e-06 1.54073854976372e-06 2.93438198188513e-06 3.25931997568364e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 810 0 0 0 0 0 2413 +1066 1113 0.998925650575698 -0.0329886694393865 -0.0325467711230765 0.000226744962700292 0.0297551680706319 0.995006623344778 -0.0952704018733636 -0.00396097304417135 0.0355270966307056 0.0941996135270344 0.994919221955406 0.0922698860292352 4.25308152512625e-05 2.855004837062e-05 -4.38791626898669e-06 1.28330867310425e-07 1.23856562639799e-06 1.24525139426627e-05 2.855004837062e-05 6.36823290886911e-05 -6.52298182067776e-07 2.39155105271124e-06 3.34988509469073e-06 8.58438574270025e-06 -4.38791626898669e-06 -6.52298182067776e-07 1.48389373997205e-05 4.35757052784592e-06 -1.02885720267369e-06 1.17394841940202e-06 1.28330867310425e-07 2.39155105271124e-06 4.35757052784592e-06 2.64574565412085e-05 -1.62357777890287e-05 3.04051596092948e-06 1.23856562639799e-06 3.34988509469073e-06 -1.02885720267369e-06 -1.62357777890287e-05 0.000117232123661868 3.80715288180927e-06 1.24525139426627e-05 8.58438574270025e-06 1.17394841940202e-06 3.04051596092948e-06 3.80715288180927e-06 4.71099048230035e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 724 0 0 0 0 0 2393 +1066 1114 0.998629402564325 -0.0333079470721803 -0.0403719828080769 0.00347676497048128 0.0289399681883613 0.994121976537513 -0.104326286267672 -0.0223905508301955 0.0436095697671447 0.103014933029073 0.993723366434412 0.102237483113152 2.86104746414112e-05 1.72211568903848e-05 -4.52362457651306e-06 1.13319014744292e-06 -1.59280555254999e-05 6.33555769829264e-06 1.72211568903848e-05 3.87045430599672e-05 -2.56365593242935e-06 3.38904508500117e-06 4.27963624524969e-06 -3.357578638211e-06 -4.52362457651306e-06 -2.56365593242935e-06 1.32759180729011e-05 3.70232180375163e-06 7.04552716768652e-07 1.78292357964313e-06 1.13319014744292e-06 3.38904508500117e-06 3.70232180375163e-06 2.32804486641094e-05 -6.28823001500169e-06 3.86646862874886e-06 -1.59280555254999e-05 4.27963624524969e-06 7.04552716768652e-07 -6.28823001500169e-06 8.75230144201591e-05 -7.12308519178553e-06 6.33555769829264e-06 -3.357578638211e-06 1.78292357964313e-06 3.86646862874886e-06 -7.12308519178553e-06 3.55877655346005e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 814 0 0 0 0 0 2384 +1067 1103 0.999839157472131 -0.0124039598958852 -0.0129538011533301 -0.00837956536069053 0.0104856388338368 0.990252834532074 -0.138886194704294 0.00105395648570175 0.0145502770992542 0.138728027017233 0.990223623206516 0.0826749538960281 6.64407690154068e-05 5.35198907755852e-05 -1.99216481724111e-08 -1.15146509680031e-06 -1.57345432442009e-05 1.37588991689833e-05 5.35198907755852e-05 7.98320079525074e-05 4.69095767553883e-06 -1.03227220756041e-06 -2.37415777086032e-06 5.90769255537839e-06 -1.99216481724111e-08 4.69095767553883e-06 1.49661161888237e-05 -3.53843156844358e-06 -1.64516156518334e-06 2.95720099913966e-06 -1.15146509680031e-06 -1.03227220756041e-06 -3.53843156844358e-06 2.70760190419652e-05 -1.81419122328134e-07 8.49252076609866e-06 -1.57345432442009e-05 -2.37415777086032e-06 -1.64516156518334e-06 -1.81419122328134e-07 7.9110465034092e-05 -1.70933151599496e-05 1.37588991689833e-05 5.90769255537839e-06 2.95720099913966e-06 8.49252076609866e-06 -1.70933151599496e-05 3.97375158552705e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 608 0 0 0 0 0 2178 +1067 1104 0.999832890537108 -0.0122343628971943 -0.013583496041576 -0.00802369519929026 0.0101705246281224 0.989701261223003 -0.142786462812083 -0.00209320307535405 0.0151905045670152 0.142624450561947 0.989660302665971 0.0905074831492397 0.000201610894149201 5.07365521169336e-05 1.15908240751502e-05 2.54733423282155e-05 -9.04008796168206e-05 0.000187030695954007 5.07365521169336e-05 0.000104917019900469 8.31545813546865e-06 -1.36846829262082e-05 3.75867842731651e-05 6.94849516837772e-06 1.15908240751502e-05 8.31545813546865e-06 1.62501784477306e-05 -3.62117498614264e-06 -4.55529107875753e-06 1.29577706816442e-05 2.54733423282155e-05 -1.36846829262082e-05 -3.62117498614264e-06 3.85074012170333e-05 -3.5995029288813e-05 4.40170580551099e-05 -9.04008796168206e-05 3.75867842731651e-05 -4.55529107875753e-06 -3.5995029288813e-05 0.000163314263487231 -0.000119001198026418 0.000187030695954007 6.94849516837772e-06 1.29577706816442e-05 4.40170580551099e-05 -0.000119001198026418 0.000236049884112684 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 658 0 0 0 0 0 2232 +1067 1101 0.999884704491657 -0.0106957927956121 -0.0107785778331767 -0.00829810301548599 0.00922667291319964 0.991709104205504 -0.128171452136856 0.0110525971102859 0.0120601090619175 0.128057224131991 0.991693451181878 0.074263151845752 4.52128349157563e-05 1.7572081003047e-05 -6.71911001274494e-06 3.80991084443334e-06 -3.85251999835288e-06 1.22824563882082e-05 1.7572081003047e-05 8.5433386667301e-05 4.96439204476325e-06 3.48025217331951e-06 -1.4001556429984e-05 -2.2110473638169e-05 -6.71911001274494e-06 4.96439204476325e-06 1.51753339009789e-05 -2.5529251395221e-06 -3.59545109696863e-06 -1.63090172924959e-06 3.80991084443334e-06 3.48025217331951e-06 -2.5529251395221e-06 2.59649238230385e-05 -8.96302181475165e-06 5.97927026791811e-06 -3.85251999835288e-06 -1.4001556429984e-05 -3.59545109696863e-06 -8.96302181475165e-06 7.12978704035878e-05 1.16334746681243e-06 1.22824563882082e-05 -2.2110473638169e-05 -1.63090172924959e-06 5.97927026791811e-06 1.16334746681243e-06 4.15372841895662e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 694 0 0 0 0 0 2238 +1067 1109 0.999858664825584 -0.00960655338122698 -0.0137972644149053 -0.00254784659395646 0.00768171017018073 0.991039400428512 -0.133348783748325 0.00160501272981961 0.0149546548627014 0.133223950288339 0.990973126460808 0.0783932928664544 4.86757639304195e-05 1.24400752353331e-05 -1.02535152786731e-05 2.71388454587258e-06 2.25676440290499e-06 1.63107861698487e-05 1.24400752353331e-05 7.84270281836913e-05 3.42660418836065e-06 -6.11575113846627e-06 1.01732741844871e-05 -2.23256597305056e-05 -1.02535152786731e-05 3.42660418836065e-06 1.49461104936436e-05 -3.96993741515792e-06 -1.53360555328547e-06 -6.36692892724888e-07 2.71388454587258e-06 -6.11575113846627e-06 -3.96993741515792e-06 2.27253188472895e-05 -1.85783632649195e-06 4.01818929888524e-06 2.25676440290499e-06 1.01732741844871e-05 -1.53360555328547e-06 -1.85783632649195e-06 5.73469120755543e-05 -9.56895626822614e-06 1.63107861698487e-05 -2.23256597305056e-05 -6.36692892724888e-07 4.01818929888524e-06 -9.56895626822614e-06 4.52433095965701e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 766 0 0 0 0 0 2190 +1067 1108 0.999880934273823 -0.010619820851667 -0.0111953865849412 -0.00886127944782341 0.00911591383409502 0.991894024969661 -0.126740456620826 0.0144852324175689 0.0124505980048003 0.126623309996875 0.991872733759104 0.0729820160908679 5.3109667386449e-05 1.00841893655082e-05 -1.06870468699798e-05 7.74986067634423e-06 -8.8905658872272e-06 2.3159722182817e-05 1.00841893655082e-05 5.89704187240739e-05 1.68866099252198e-06 -4.01249687172231e-06 -1.21464558924825e-06 -1.1810377921164e-05 -1.06870468699798e-05 1.68866099252198e-06 1.63280026036273e-05 -3.79486242457912e-06 -4.20897773978651e-06 -1.90369071524149e-06 7.74986067634423e-06 -4.01249687172231e-06 -3.79486242457912e-06 2.33132233462098e-05 -5.23899066018001e-06 8.2588932780849e-06 -8.8905658872272e-06 -1.21464558924825e-06 -4.20897773978651e-06 -5.23899066018001e-06 7.45937777052275e-05 -1.09334785454654e-05 2.3159722182817e-05 -1.1810377921164e-05 -1.90369071524149e-06 8.2588932780849e-06 -1.09334785454654e-05 4.61142157723191e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 652 0 0 0 0 0 2184 +1067 1105 0.999910346687888 -0.0111577473407795 -0.00740292244911481 -0.00711619193387578 0.0101327550590739 0.991926135543681 -0.126411506202133 0.0106140655315235 0.0087536199038508 0.126325160992014 0.991950264801074 0.0705686355292052 9.81673260705707e-05 5.24811326515699e-05 5.56319742450975e-06 1.11621927400426e-05 -5.42961465043774e-05 6.68320762127524e-05 5.24811326515699e-05 8.58283969181197e-05 6.97204513802049e-06 -2.52880769099099e-06 -1.01601525362844e-05 2.0381750773004e-05 5.56319742450975e-06 6.97204513802049e-06 1.43963198818117e-05 4.61772929587313e-07 -1.13376809230657e-05 8.14885904558805e-06 1.11621927400426e-05 -2.52880769099099e-06 4.61772929587313e-07 3.17848314876471e-05 -2.86308335498078e-05 1.75553507976114e-05 -5.42961465043774e-05 -1.01601525362844e-05 -1.13376809230657e-05 -2.86308335498078e-05 0.000163889941284076 -5.73320465985298e-05 6.68320762127524e-05 2.0381750773004e-05 8.14885904558805e-06 1.75553507976114e-05 -5.73320465985298e-05 8.95890112553865e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 719 0 0 0 0 0 2274 +1067 1106 0.999847344983846 -0.0112255633320188 -0.0133893038143325 -0.0064070984908253 0.00931655418004658 0.990805264476291 -0.134974552061774 0.00305318972312036 0.0147813580892934 0.134829205344929 0.990758596651622 0.0787218965588988 0.00011269639902771 4.14802003495932e-05 -1.63866101000942e-06 1.63539679450014e-05 -4.19481786066894e-05 7.3783293391059e-05 4.14802003495932e-05 7.72289612554446e-05 1.77424826193253e-06 -1.91165246951935e-06 4.16188272635811e-06 6.39281106521947e-06 -1.63866101000942e-06 1.77424826193253e-06 1.5515538053272e-05 -3.05454343858171e-06 -8.97759764996053e-07 4.74625766874981e-06 1.63539679450014e-05 -1.91165246951935e-06 -3.05454343858171e-06 3.02985384104508e-05 -1.90772240121706e-05 1.53166865561872e-05 -4.19481786066894e-05 4.16188272635811e-06 -8.97759764996053e-07 -1.90772240121706e-05 0.000101534325516233 -4.08055735935603e-05 7.3783293391059e-05 6.39281106521947e-06 4.74625766874981e-06 1.53166865561872e-05 -4.08055735935603e-05 8.95637477740083e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 752 0 0 0 0 0 2242 +1067 1107 0.999902258168579 -0.0103285605609103 -0.00942310703091548 -0.00670992368140412 0.00904062899734017 0.991765679963624 -0.127746244851356 0.0124970633896232 0.010664948978262 0.127648567884758 0.991762119653832 0.0727164400577129 4.19320098757493e-05 1.29752359417025e-05 -1.11750716935161e-05 6.1379838996014e-06 7.74358332074934e-06 2.27916463671457e-05 1.29752359417025e-05 6.99864911726554e-05 6.70812999435468e-07 -1.06460455231419e-06 -4.34366959698197e-07 -1.77115377011298e-05 -1.11750716935161e-05 6.70812999435468e-07 1.61107012532075e-05 -4.7927785710098e-06 -4.35697683081839e-06 -3.43414539089636e-06 6.1379838996014e-06 -1.06460455231419e-06 -4.7927785710098e-06 2.62693652476838e-05 1.03879038116834e-07 8.47394507354531e-06 7.74358332074934e-06 -4.34366959698197e-07 -4.35697683081839e-06 1.03879038116834e-07 6.12643364211816e-05 -1.02166442670221e-06 2.27916463671457e-05 -1.77115377011298e-05 -3.43414539089636e-06 8.47394507354531e-06 -1.02166442670221e-06 5.2501262751819e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 671 0 0 0 0 0 2220 +1067 1110 0.99983909800465 -0.0105008092199259 -0.0145434214328712 -0.00422241419368091 0.00851885409454511 0.991451132174131 -0.130200159890644 0.00464347724466194 0.0157862986847212 0.130055317139901 0.991381060570292 0.0772784286240896 3.54642854166653e-05 9.92869191536406e-06 -8.66501077790969e-06 2.19836455909738e-06 -1.5179975025296e-06 1.33591795701552e-05 9.92869191536406e-06 6.01073899566259e-05 5.02782953919479e-06 -8.79711473749227e-06 3.44420121075637e-06 -1.12776288074194e-05 -8.66501077790969e-06 5.02782953919479e-06 1.46084064657951e-05 -3.1775656875756e-06 -3.40599635026179e-07 -3.73908072726557e-06 2.19836455909738e-06 -8.79711473749227e-06 -3.1775656875756e-06 2.1251912761252e-05 -2.96817804988602e-06 5.3979629880068e-06 -1.5179975025296e-06 3.44420121075637e-06 -3.40599635026179e-07 -2.96817804988602e-06 5.82926486934625e-05 -7.01984515445333e-06 1.33591795701552e-05 -1.12776288074194e-05 -3.73908072726557e-06 5.3979629880068e-06 -7.01984515445333e-06 3.86511032021701e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 732 0 0 0 0 0 2272 +1067 1145 0.99956323726018 -0.01097510243126 -0.0274386924719814 -0.0104751553213857 0.00700747465294351 0.990024463332549 -0.140721204166559 0.0222351217802443 0.0287094064190985 0.140467466445869 0.989668965287556 0.0854391681962556 7.52896532892999e-05 2.48597643385127e-05 -2.45624662221035e-06 2.18930659660157e-05 -7.20218986027807e-05 4.67591638352811e-05 2.48597643385127e-05 9.47188555861499e-05 7.41368296329229e-06 5.48787943003717e-06 -3.10839293262684e-05 -3.27475893990583e-06 -2.45624662221035e-06 7.41368296329229e-06 1.47395503797192e-05 -7.47827807638914e-07 -8.91969751466791e-06 -6.26176669378606e-07 2.18930659660157e-05 5.48787943003717e-06 -7.47827807638914e-07 7.62586901484995e-05 -0.000149910478407093 1.42941598608823e-05 -7.20218986027807e-05 -3.10839293262684e-05 -8.91969751466791e-06 -0.000149910478407093 0.000497460554281219 -5.06206071326313e-05 4.67591638352811e-05 -3.27475893990583e-06 -6.26176669378606e-07 1.42941598608823e-05 -5.06206071326313e-05 6.75342823812314e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 885 0 0 0 0 0 2206 +1067 1111 0.999868246431304 -0.0107539358596997 -0.0121590559631018 -0.00568877530940452 0.00913654153249237 0.991984426009038 -0.126029449591529 0.00308892753200957 0.0134169067677099 0.125901753041982 0.991951982302441 0.0729060000398979 3.5475097248294e-05 2.13881354336622e-05 -8.28467490169835e-06 5.51550830745904e-06 -4.09778043259595e-06 8.85590947015326e-06 2.13881354336622e-05 7.84251270517505e-05 4.91316785420418e-06 -1.78652323444428e-06 -1.32954488477112e-05 -1.54576047150318e-05 -8.28467490169835e-06 4.91316785420418e-06 1.56934503320421e-05 -2.16011893929783e-06 -3.46769308650244e-06 -9.93616589291037e-07 5.51550830745904e-06 -1.78652323444428e-06 -2.16011893929783e-06 2.28478852719817e-05 -6.72892753117917e-06 6.40107157860257e-06 -4.09778043259595e-06 -1.32954488477112e-05 -3.46769308650244e-06 -6.72892753117917e-06 6.57511930219988e-05 -2.00704919173166e-06 8.85590947015326e-06 -1.54576047150318e-05 -9.93616589291037e-07 6.40107157860257e-06 -2.00704919173166e-06 3.76881984408004e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 701 0 0 0 0 0 2337 +1067 1135 0.999873618891082 -0.0110677746684649 -0.0114127389148547 -0.00539528160953323 0.00941925345214353 0.990724997452275 -0.135555365395819 0.00178929769407936 0.0128071819716453 0.135430734277998 0.990704038703218 0.0793038039947754 5.45034086732185e-05 2.13404600662929e-05 -1.98104503825361e-06 4.48124849397885e-06 -9.21666968081439e-06 3.14951055579069e-05 2.13404600662929e-05 7.41978112880409e-05 5.29075240558865e-06 4.64105996876439e-06 -1.23830110436364e-05 -3.99046141091833e-06 -1.98104503825361e-06 5.29075240558865e-06 1.59757684939662e-05 -1.84250568585499e-07 -3.56239712965441e-06 1.62825606892754e-06 4.48124849397885e-06 4.64105996876439e-06 -1.84250568585499e-07 3.15668228737106e-05 -3.34709800395612e-05 6.77731127699529e-06 -9.21666968081439e-06 -1.23830110436364e-05 -3.56239712965441e-06 -3.34709800395612e-05 0.000135045690337298 -1.4423433903202e-05 3.14951055579069e-05 -3.99046141091833e-06 1.62825606892754e-06 6.77731127699529e-06 -1.4423433903202e-05 5.50328372624741e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 891 0 0 0 0 0 2197 +1067 1112 0.999731473841567 -0.0115161114379982 -0.0201086893634523 -0.00756711995243215 0.00864708386157849 0.990485834324116 -0.137342782642374 -0.00110247644555074 0.0214990267514379 0.13713202098929 0.990319443749407 0.0834430123990947 3.3121943057839e-05 1.16668932350988e-05 -7.06961037887221e-06 4.47181534765531e-06 -5.54592278712946e-06 6.50871020342048e-06 1.16668932350988e-05 7.50615610486028e-05 5.985807022388e-06 -8.2445675469787e-07 -9.89074261780518e-06 -7.26382827317737e-06 -7.06961037887221e-06 5.985807022388e-06 1.63104785660337e-05 -3.8123942324468e-06 -5.99797756669651e-07 -1.89919606304143e-06 4.47181534765531e-06 -8.2445675469787e-07 -3.8123942324468e-06 2.92520296811018e-05 -2.09635545998601e-05 4.77696486763613e-06 -5.54592278712946e-06 -9.89074261780518e-06 -5.99797756669651e-07 -2.09635545998601e-05 9.49393950362106e-05 -6.82286815074448e-06 6.50871020342048e-06 -7.26382827317737e-06 -1.89919606304143e-06 4.77696486763613e-06 -6.82286815074448e-06 3.34985517217483e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 755 0 0 0 0 0 2242 +1067 1115 0.999874089503913 -0.0112411379519119 -0.0112000873330227 -0.00408967257132001 0.00961092597890891 0.99062725316751 -0.136254450876376 -0.000198165877978782 0.0126267668288119 0.136129651800557 0.9906105605434 0.0778859531493069 0.000124643974355007 3.85472685694502e-05 -4.00448949021556e-06 3.63248165471664e-05 -0.000104098310540806 8.5705379778424e-05 3.85472685694502e-05 7.38107474130642e-05 5.84259410623082e-08 -2.72989957605045e-06 1.25537136585146e-06 6.79644740552818e-06 -4.00448949021556e-06 5.84259410623082e-08 1.47503728824083e-05 1.10619396879549e-06 -3.74316885636418e-06 1.63264329925801e-06 3.63248165471664e-05 -2.72989957605045e-06 1.10619396879549e-06 3.72922294703167e-05 -5.91053530119895e-05 3.57097682298942e-05 -0.000104098310540806 1.25537136585146e-06 -3.74316885636418e-06 -5.91053530119895e-05 0.000245251912130332 -0.000107975687301212 8.5705379778424e-05 6.79644740552818e-06 1.63264329925801e-06 3.57097682298942e-05 -0.000107975687301212 0.000101398545062879 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 824 0 0 0 0 0 2148 +1067 1113 0.999841954908597 -0.011447072191277 -0.0136025638319847 -0.00644615122832248 0.00953449899579485 0.991046060417661 -0.133179575984956 -0.00264766820884569 0.0150052835179717 0.1330288339755 0.99099857255077 0.0790702584497457 4.53698810743029e-05 -1.32831661383931e-06 -5.6121751935418e-06 1.97024998836103e-06 -9.77034045465671e-06 2.71742438954556e-05 -1.32831661383931e-06 0.000110323408438962 6.04014961862075e-06 -2.13586812651437e-06 3.37795217267072e-06 -3.6826168463267e-05 -5.6121751935418e-06 6.04014961862075e-06 1.82961091271105e-05 -5.00819417855629e-06 -5.54572569687704e-06 3.84493328456356e-06 1.97024998836103e-06 -2.13586812651437e-06 -5.00819417855629e-06 2.82334901423384e-05 -9.33899171478971e-06 -4.07803076200345e-07 -9.77034045465671e-06 3.37795217267072e-06 -5.54572569687704e-06 -9.33899171478971e-06 8.39086306039928e-05 -1.41367027232584e-05 2.71742438954556e-05 -3.6826168463267e-05 3.84493328456356e-06 -4.07803076200345e-07 -1.41367027232584e-05 6.4931054431976e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 756 0 0 0 0 0 2321 +1067 1116 0.999790630208506 -0.0113375397052473 -0.0170339643275111 -0.00536594913667419 0.0089128762415606 0.990638319607063 -0.136221438706234 0.000260661659650743 0.0184189137676901 0.13604109643606 0.990531959956918 0.0797827882901044 4.27769935812556e-05 2.75738796200606e-05 -8.98575213829023e-07 1.08388867840798e-06 -3.60385248605887e-06 8.60163837847746e-06 2.75738796200606e-05 5.95342445990584e-05 6.82573716901235e-06 -3.93041248409891e-06 -1.63254035488535e-05 -2.45964087291587e-06 -8.98575213829023e-07 6.82573716901235e-06 1.51465069787776e-05 -5.09223216080535e-08 -3.68545930186813e-06 4.92100056112692e-08 1.08388867840798e-06 -3.93041248409891e-06 -5.09223216080535e-08 2.68574575851262e-05 -1.83023076783483e-05 -1.00200153060642e-06 -3.60385248605887e-06 -1.63254035488535e-05 -3.68545930186813e-06 -1.83023076783483e-05 0.000108930396210284 -6.13971740356158e-06 8.60163837847746e-06 -2.45964087291587e-06 4.92100056112692e-08 -1.00200153060642e-06 -6.13971740356158e-06 3.60327599937025e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 777 0 0 0 0 0 2264 +1067 1114 0.999840910388155 -0.0107859633844431 -0.0142062277911533 -0.00421017418490504 0.00882363003300084 0.991263906857764 -0.13159791227114 -0.0036813383570947 0.0155015311251956 0.131451625912164 0.99120137841804 0.0787545364114209 8.22734621904995e-05 3.60906993322526e-05 -8.26844172376493e-06 1.35585510960391e-05 -1.90852296358991e-05 4.84207423010415e-05 3.60906993322526e-05 6.8059701326681e-05 2.41147305909003e-06 -4.7753388859038e-06 7.56870885767615e-06 2.20257050900417e-06 -8.26844172376493e-06 2.41147305909003e-06 1.49431159728696e-05 -1.44426065666307e-06 -6.20307489731739e-06 -1.88508644678177e-06 1.35585510960391e-05 -4.7753388859038e-06 -1.44426065666307e-06 2.56215100001743e-05 -1.75857708762034e-05 1.80115823632591e-05 -1.90852296358991e-05 7.56870885767615e-06 -6.20307489731739e-06 -1.75857708762034e-05 0.000102942566594443 -2.31912804022094e-05 4.84207423010415e-05 2.20257050900417e-06 -1.88508644678177e-06 1.80115823632591e-05 -2.31912804022094e-05 6.43742702288147e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 845 0 0 0 0 0 2222 +1068 1147 0.999615981821521 0.019297377622048 -0.0198871844138238 -0.00418399790689331 -0.0205859526138968 0.997556132331394 -0.0667681166651304 0.010169766534559 0.0185501332064153 0.067151873130555 0.997570307543825 -0.0215755786834304 7.2757144308557e-05 3.62722275374503e-05 -6.31080393222891e-06 1.62375979093789e-05 -2.01650469019388e-05 4.73183684683913e-05 3.62722275374503e-05 0.000119166181095772 5.13428181638655e-06 1.58121400631291e-05 -1.42978696009527e-05 4.41236375088271e-06 -6.31080393222891e-06 5.13428181638655e-06 1.94244090001496e-05 -1.26909903084109e-06 -4.58054944596874e-06 -2.97358800893036e-06 1.62375979093789e-05 1.58121400631291e-05 -1.26909903084109e-06 5.24522781189759e-05 -7.83627549348793e-05 1.50737198065857e-05 -2.01650469019388e-05 -1.42978696009527e-05 -4.58054944596874e-06 -7.83627549348793e-05 0.000268293049856654 -1.90715194859664e-05 4.73183684683913e-05 4.41236375088271e-06 -2.97358800893036e-06 1.50737198065857e-05 -1.90715194859664e-05 7.30673783042255e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1113 0 0 0 0 0 2315 +1068 1070 0.99897536374331 0.00315980636196648 -0.0451468521347487 0.00197962337970199 -0.00352248432348852 0.999962146376298 -0.00795599891260431 0.0321351888730134 0.0451200037468169 0.00810687598655977 0.998948679274179 0.0223859862197805 2.67717203952486e-05 1.78054056357938e-05 -1.58665095583367e-06 5.94401389145255e-06 -2.05928456261918e-06 -3.26785450192255e-07 1.78054056357938e-05 3.27280348774097e-05 -3.80145007314732e-06 5.63711744370005e-06 -1.27345324201653e-05 -6.43781508352701e-06 -1.58665095583367e-06 -3.80145007314732e-06 1.74350437835131e-05 -1.86004649535711e-06 6.5468647548083e-07 -2.67744397224364e-06 5.94401389145255e-06 5.63711744370005e-06 -1.86004649535711e-06 2.92171712707413e-05 -2.49318298502137e-05 -2.81121602164124e-06 -2.05928456261918e-06 -1.27345324201653e-05 6.5468647548083e-07 -2.49318298502137e-05 0.000105384536135964 9.65449155236451e-06 -3.26785450192255e-07 -6.43781508352701e-06 -2.67744397224364e-06 -2.81121602164124e-06 9.65449155236451e-06 3.50888931091128e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1171 0 0 0 0 0 2181 +1068 1104 0.999531610856191 0.00238263753476285 0.030510357874088 -0.00583133906019865 0.000700434274969442 0.994922384362825 -0.100642726938499 0.0126418365359566 -0.0305952331426553 0.100616957478194 0.994454704638063 0.0461723651626251 0.000215260694752912 1.59774207717762e-05 3.42042682103267e-06 2.89244440587087e-05 -0.00014818828018022 0.000233953153534388 1.59774207717762e-05 0.000107112136890563 1.11023796138577e-06 -1.0229632416368e-05 4.60103330539783e-05 -2.97211356929977e-05 3.42042682103267e-06 1.11023796138577e-06 1.60251867509667e-05 -3.46257014712458e-07 2.23108456992778e-06 5.02216960049337e-06 2.89244440587087e-05 -1.0229632416368e-05 -3.46257014712458e-07 3.16332607026445e-05 -3.11958863388327e-05 4.4655384924808e-05 -0.00014818828018022 4.60103330539783e-05 2.23108456992778e-06 -3.11958863388327e-05 0.000195830284936618 -0.000189726828085136 0.000233953153534388 -2.97211356929977e-05 5.02216960049337e-06 4.4655384924808e-05 -0.000189726828085136 0.000315695957327998 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 660 0 0 0 0 0 2178 +1068 1101 0.999375015589063 0.00372827787496405 0.0351522141613601 -0.0014881009060662 -0.000195460519189096 0.994990162176617 -0.0999726911057926 0.00965767734530902 -0.0353488332416292 0.0999033388623015 0.994369037567351 0.0438927220694611 4.27172223704717e-05 2.07950458564106e-05 -1.20938586938374e-05 4.26229481740194e-06 -6.85277628733088e-06 2.05570105608137e-05 2.07950458564106e-05 7.09523120032193e-05 -2.44287084340443e-06 4.36330788189537e-06 -1.57191797591041e-06 -1.24257610612055e-05 -1.20938586938374e-05 -2.44287084340443e-06 1.96124076629117e-05 -3.06904856048825e-06 -3.46292756899197e-06 -2.75832000254504e-06 4.26229481740194e-06 4.36330788189537e-06 -3.06904856048825e-06 2.59210500602118e-05 -4.67929877950442e-07 6.64598771112835e-06 -6.85277628733088e-06 -1.57191797591041e-06 -3.46292756899197e-06 -4.67929877950442e-07 6.36627071803534e-05 -6.83440015197335e-06 2.05570105608137e-05 -1.24257610612055e-05 -2.75832000254504e-06 6.64598771112835e-06 -6.83440015197335e-06 4.86903480496047e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 714 0 0 0 0 0 2223 +1068 1102 0.999392687302779 0.00348378477933367 0.0346715994632611 -0.00495646815924398 -8.12444790757611e-05 0.995220091272677 -0.0976573772253747 0.0209314744333101 -0.0348460896667638 0.0975952517841713 0.994615964512997 0.0423971927753294 4.12869106792445e-05 2.1888084708312e-05 -6.43854529466071e-06 -3.63427910088162e-06 8.38078584085585e-06 1.61625267962264e-05 2.1888084708312e-05 6.53792963268886e-05 -2.95813191095794e-06 3.84820418258036e-06 2.33117393710552e-07 -1.16593786335875e-05 -6.43854529466071e-06 -2.95813191095794e-06 1.23306545732168e-05 1.50785038312434e-06 1.00167103576658e-07 -3.97733844842008e-07 -3.63427910088162e-06 3.84820418258036e-06 1.50785038312434e-06 2.18783999474497e-05 2.85311344673091e-06 -7.15715985465808e-07 8.38078584085585e-06 2.33117393710552e-07 1.00167103576658e-07 2.85311344673091e-06 3.41013950551853e-05 7.02842911512001e-06 1.61625267962264e-05 -1.16593786335875e-05 -3.97733844842008e-07 -7.15715985465808e-07 7.02842911512001e-06 4.91924497144425e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 646 0 0 0 0 0 2081 +1068 1109 0.999480010637738 0.00430316542057398 0.0319560808446524 0.0012663281279453 -0.00103043365281784 0.994811359174703 -0.101731498875556 0.00480484390841953 -0.0322280396871098 0.101645670957219 0.994298501976938 0.047674084985057 3.90481806816103e-05 2.14774888448847e-05 -6.98673465000558e-06 6.93491318643506e-07 7.9532028208813e-06 8.30904411940375e-06 2.14774888448847e-05 5.72556296802146e-05 1.02837579082027e-06 -3.75590808175556e-07 2.12252814489322e-06 -6.58383692853185e-06 -6.98673465000558e-06 1.02837579082027e-06 1.44742484848001e-05 -7.33619696609402e-07 -2.03435292387638e-06 -1.26011600173056e-06 6.93491318643506e-07 -3.75590808175556e-07 -7.33619696609402e-07 1.97586635309464e-05 1.90398775049053e-06 3.37436797292278e-06 7.9532028208813e-06 2.12252814489322e-06 -2.03435292387638e-06 1.90398775049053e-06 4.22004622573829e-05 9.01162794468576e-07 8.30904411940375e-06 -6.58383692853185e-06 -1.26011600173056e-06 3.37436797292278e-06 9.01162794468576e-07 3.46798469525618e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 775 0 0 0 0 0 2183 +1068 1103 0.999724628644058 0.00262005806410766 0.0233195664247985 -0.00578938704450284 -1.50641439797235e-05 0.993818820059582 -0.111014200300916 0.00490782181976545 -0.0234662876393232 0.110983278880744 0.993545190292474 0.0564302407626473 4.47915044534115e-05 2.7980696935704e-05 -1.37452651948901e-06 1.04608700569697e-05 -1.48733812129794e-05 1.39423765853341e-05 2.7980696935704e-05 7.37194306537301e-05 -7.49254295802013e-06 1.25527539305862e-05 4.27113421215694e-06 -1.69603417796948e-06 -1.37452651948901e-06 -7.49254295802013e-06 1.33780509377024e-05 -2.47994270429622e-06 -1.25058062340711e-06 -1.48097363342909e-06 1.04608700569697e-05 1.25527539305862e-05 -2.47994270429622e-06 3.12547896448831e-05 -9.53381641878983e-06 1.29368974177645e-05 -1.48733812129794e-05 4.27113421215694e-06 -1.25058062340711e-06 -9.53381641878983e-06 7.46089875554383e-05 -2.41217947999478e-05 1.39423765853341e-05 -1.69603417796948e-06 -1.48097363342909e-06 1.29368974177645e-05 -2.41217947999478e-05 4.86277693239763e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 591 0 0 0 0 0 2242 +1068 1108 0.999518953044527 0.00391984198121 0.0307651969539554 -0.00404202533043804 -0.000875426788360357 0.995151267321353 -0.0983523704678402 0.0170689847953976 -0.0310015504888311 0.0982781256819004 0.994675984368649 0.0429987207699294 4.02952217236474e-05 2.55526602422321e-05 -8.6232275324354e-06 -3.41858197664747e-07 8.22667330762412e-09 1.03978938273223e-05 2.55526602422321e-05 4.75025271877866e-05 -5.30948895203585e-06 1.53926061759324e-06 -2.24414918920079e-06 4.53507123120806e-06 -8.6232275324354e-06 -5.30948895203585e-06 1.60790382015213e-05 -1.35111862665199e-06 -2.12156615132035e-06 -1.82330013273204e-06 -3.41858197664747e-07 1.53926061759324e-06 -1.35111862665199e-06 2.29749302422276e-05 -7.54129616398773e-07 -9.07049601544033e-07 8.22667330762412e-09 -2.24414918920079e-06 -2.12156615132035e-06 -7.54129616398773e-07 5.69052638572713e-05 1.20613713865639e-06 1.03978938273223e-05 4.53507123120806e-06 -1.82330013273204e-06 -9.07049601544033e-07 1.20613713865639e-06 3.53523574694506e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 675 0 0 0 0 0 2131 +1067 1117 0.999827057843353 -0.0114389355976336 -0.0146630541394778 -0.00462180142535935 0.00940652795336711 0.991222297081565 -0.131870675285324 -0.00213112173247576 0.0160428063681698 0.131709940857697 0.991158473627248 0.0811351813665779 3.57030557461829e-05 1.78462646935688e-05 -3.27296500271476e-06 2.65459717564416e-06 -7.77380639481567e-06 1.58356237130899e-05 1.78462646935688e-05 6.54877871565907e-05 8.83312461053599e-06 -3.59455501790996e-06 -1.5621530881294e-05 -7.70857594453947e-06 -3.27296500271476e-06 8.83312461053599e-06 1.51646890774773e-05 -2.01073115507818e-06 -6.51339387697522e-06 -1.36491135492906e-06 2.65459717564416e-06 -3.59455501790996e-06 -2.01073115507818e-06 2.64361338911272e-05 -2.14118537652753e-05 8.58055487205933e-06 -7.77380639481567e-06 -1.5621530881294e-05 -6.51339387697522e-06 -2.14118537652753e-05 0.000115957493334251 -8.23530484174962e-06 1.58356237130899e-05 -7.70857594453947e-06 -1.36491135492906e-06 8.58055487205933e-06 -8.23530484174962e-06 4.2060767574256e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 779 0 0 0 0 0 2337 +1068 1107 0.999582488512609 0.00436411177431699 0.0285622685961925 -0.0039146963637145 -0.00153519797218264 0.995153112893095 -0.0983256073785924 0.015619916354532 -0.0288529344456674 0.0982407065711773 0.994744324812296 0.0452070363472788 4.75420534164522e-05 3.15779195635824e-05 -1.21862227714405e-05 5.52651101084847e-06 -2.25925297946701e-06 2.51664029580239e-05 3.15779195635824e-05 6.23527412817451e-05 -8.31683357097342e-06 -3.45886631258517e-07 1.73503014771359e-05 3.76574674170101e-06 -1.21862227714405e-05 -8.31683357097342e-06 1.76683032040081e-05 -2.33657213430245e-06 -9.20550534981955e-07 -3.50075017280703e-06 5.52651101084847e-06 -3.45886631258517e-07 -2.33657213430245e-06 2.38716522948481e-05 -3.35911533823748e-06 8.02046804924182e-06 -2.25925297946701e-06 1.73503014771359e-05 -9.20550534981955e-07 -3.35911533823748e-06 7.1335788249306e-05 -9.43020837719918e-06 2.51664029580239e-05 3.76574674170101e-06 -3.50075017280703e-06 8.02046804924182e-06 -9.43020837719918e-06 5.30048385236606e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 665 0 0 0 0 0 2063 +1068 1110 0.99961937707591 0.0040718388094906 0.0272859140048133 -0.002809695775081 -0.00120718778600151 0.994556577117825 -0.104190967023663 0.00951162178258175 -0.0275616340592838 0.104118370331015 0.994182941559347 0.0506223887670368 2.73414994993395e-05 8.77585436471257e-06 -8.32775560644571e-06 5.39405336037407e-07 2.54778532684848e-06 7.15425151275284e-06 8.77585436471257e-06 4.64724096087266e-05 5.78874779719932e-07 -4.67587966805993e-06 8.60411965107939e-06 -1.22108574188164e-05 -8.32775560644571e-06 5.78874779719932e-07 1.46257808588465e-05 -7.88748010354254e-07 -1.1402683158861e-06 -1.01367514315133e-06 5.39405336037407e-07 -4.67587966805993e-06 -7.88748010354254e-07 2.09895697929144e-05 -6.25943431433459e-06 5.56055900517642e-06 2.54778532684848e-06 8.60411965107939e-06 -1.1402683158861e-06 -6.25943431433459e-06 6.44394214901856e-05 -6.66829917172775e-06 7.15425151275284e-06 -1.22108574188164e-05 -1.01367514315133e-06 5.56055900517642e-06 -6.66829917172775e-06 3.4822164547411e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 725 0 0 0 0 0 2146 +1068 1105 0.999529490772451 0.00331357972807562 0.03049290516745 -0.00473688992093242 -0.000179974603306703 0.994763973441537 -0.102198849073498 0.0107620789228402 -0.0306718875406711 0.102145275623453 0.994296524172996 0.0458579439679786 0.00010324998741621 4.44904021096582e-05 -5.58091741497235e-07 5.14712985507929e-06 -3.81463499440267e-05 7.56512514493596e-05 4.44904021096582e-05 7.79677251751493e-05 -8.17369548062236e-07 -8.44753119117491e-07 6.68997881877555e-06 1.11848375329692e-05 -5.58091741497235e-07 -8.17369548062236e-07 1.35597855594415e-05 -2.90977018577865e-06 1.31308692096386e-06 1.33906812868235e-06 5.14712985507929e-06 -8.44753119117491e-07 -2.90977018577865e-06 2.7612768126999e-05 -1.20843036978694e-05 1.10507314674613e-05 -3.81463499440267e-05 6.68997881877555e-06 1.31308692096386e-06 -1.20843036978694e-05 9.474567918764e-05 -3.63644393646971e-05 7.56512514493596e-05 1.11848375329692e-05 1.33906812868235e-06 1.10507314674613e-05 -3.63644393646971e-05 0.000104000413783534 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 715 0 0 0 0 0 2142 +1068 1100 0.999383973525164 0.0036859129915986 0.0349011103902634 -0.00406146919339012 -0.000225355492501535 0.995122946703228 -0.0986421317672415 0.0167466598145568 -0.0350944821297735 0.0985735004456177 0.99451075526308 0.0446791688034593 4.07158268385764e-05 2.74048437322909e-05 -8.2858608896041e-06 2.34545937457178e-06 2.61120332768382e-06 1.61370135565668e-05 2.74048437322909e-05 6.41605348530181e-05 -1.48263230247585e-06 4.67969653997349e-06 1.10788118355316e-05 6.68629708613331e-07 -8.2858608896041e-06 -1.48263230247585e-06 2.25713979826237e-05 -3.01628770695911e-06 -2.39615400230055e-06 -3.46200307075877e-07 2.34545937457178e-06 4.67969653997349e-06 -3.01628770695911e-06 2.62876299465341e-05 2.23196658563443e-06 2.20824310263739e-06 2.61120332768382e-06 1.10788118355316e-05 -2.39615400230055e-06 2.23196658563443e-06 6.57915465517628e-05 -8.7483263185848e-06 1.61370135565668e-05 6.68629708613331e-07 -3.46200307075877e-07 2.20824310263739e-06 -8.7483263185848e-06 4.01649554972738e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 697 0 0 0 0 0 2173 +1068 1106 0.99948787214991 0.00362763957269064 0.0317936103073669 -0.00303393802788643 -0.000553321400585202 0.995364183356819 -0.0961760694031552 0.0128015719928029 -0.0319951130748699 0.0961092228745167 0.994856436888149 0.0400434344638385 7.0426864528649e-05 4.47916357857426e-05 -5.28757915800353e-06 6.50958107059466e-06 -6.80439120167502e-06 3.89460746561552e-05 4.47916357857426e-05 6.90912985487971e-05 3.05599396782751e-07 -1.05746087523826e-09 8.25056602276565e-06 1.59078603111584e-05 -5.28757915800353e-06 3.05599396782751e-07 1.55321288644687e-05 1.42331858431244e-06 2.01937941629818e-06 -4.6478666973592e-07 6.50958107059466e-06 -1.05746087523826e-09 1.42331858431244e-06 2.188054115374e-05 -3.45655141150059e-06 8.94898559313691e-06 -6.80439120167502e-06 8.25056602276565e-06 2.01937941629818e-06 -3.45655141150059e-06 6.23209252632308e-05 -1.41772305502177e-05 3.89460746561552e-05 1.59078603111584e-05 -4.6478666973592e-07 8.94898559313691e-06 -1.41772305502177e-05 5.69040983057208e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 759 0 0 0 0 0 2237 +1068 1112 0.999569491349605 0.00420751895762337 0.0290366793437543 -0.00428546842635763 -0.00111779113236628 0.994406592497316 -0.105613821732108 0.0112228418523964 -0.0293186375207848 0.105535897125567 0.993983194984617 0.0521793184503086 2.38035105740213e-05 1.38188835531049e-05 -6.71329116693894e-06 2.79593216728728e-06 -7.98470626081238e-07 9.68237791014687e-06 1.38188835531049e-05 5.82220144872964e-05 -2.68484830610831e-06 9.98366181788975e-06 -1.05418025732102e-05 1.59868108126448e-07 -6.71329116693894e-06 -2.68484830610831e-06 1.31744975318839e-05 1.11501129278276e-06 9.49999845892843e-07 -2.98882782039505e-06 2.79593216728728e-06 9.98366181788975e-06 1.11501129278276e-06 3.04286999751392e-05 -2.73387768713591e-05 3.72561729532153e-06 -7.98470626081238e-07 -1.05418025732102e-05 9.49999845892843e-07 -2.73387768713591e-05 9.94514941367386e-05 5.87443739075881e-07 9.68237791014687e-06 1.59868108126448e-07 -2.98882782039505e-06 3.72561729532153e-06 5.87443739075881e-07 3.76133687237948e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 749 0 0 0 0 0 2215 +1068 1111 0.999538339032935 0.00344858132243945 0.0301863560262771 -0.00443921346582582 -0.00034049050311976 0.994746491286757 -0.102368462618639 0.012157935908841 -0.0303807977100655 0.102310924927639 0.994288429868794 0.0463003215940763 2.82730509351334e-05 1.57571328018899e-05 -6.93635428850735e-06 3.31002122098511e-06 4.52046421295492e-06 7.969035292809e-06 1.57571328018899e-05 4.56377238001533e-05 -4.62108097631479e-06 4.69138349948809e-06 -4.03611055246199e-06 -2.55554593084274e-06 -6.93635428850735e-06 -4.62108097631479e-06 1.51753606070499e-05 -2.1401114381587e-06 7.29854954612072e-07 -3.6433617281424e-06 3.31002122098511e-06 4.69138349948809e-06 -2.1401114381587e-06 2.63125754057445e-05 -1.51439738845744e-05 6.23171197582014e-07 4.52046421295492e-06 -4.03611055246199e-06 7.29854954612072e-07 -1.51439738845744e-05 7.62771900781074e-05 1.76693397755573e-06 7.969035292809e-06 -2.55554593084274e-06 -3.6433617281424e-06 6.23171197582014e-07 1.76693397755573e-06 3.83828662349203e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 707 0 0 0 0 0 2259 +1068 1113 0.999624789147241 0.00337097728902367 0.0271830357843107 -0.00416596687514093 -0.000428843562837258 0.994202701684015 -0.107521179575954 0.00535098862973663 -0.0273878990711746 0.107469179192561 0.993831111662411 0.0529604070635755 3.10861908702937e-05 1.83181455360389e-05 -7.88771479025989e-06 3.55834304812539e-08 3.17723816583275e-06 9.3589590759585e-06 1.83181455360389e-05 5.02237276852526e-05 -2.74619156820343e-06 -5.73659576934301e-07 1.59634945130218e-06 -2.24454213629521e-06 -7.88771479025989e-06 -2.74619156820343e-06 1.49855676254585e-05 -1.29298186750898e-06 2.43802934198131e-06 -1.95860551315486e-06 3.55834304812539e-08 -5.73659576934301e-07 -1.29298186750898e-06 2.368210066899e-05 -1.36283785215429e-05 -1.26314657074456e-07 3.17723816583275e-06 1.59634945130218e-06 2.43802934198131e-06 -1.36283785215429e-05 7.93536229979017e-05 -6.07159818613215e-07 9.3589590759585e-06 -2.24454213629521e-06 -1.95860551315486e-06 -1.26314657074456e-07 -6.07159818613215e-07 3.24039765996096e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 744 0 0 0 0 0 2194 +1068 1114 0.999486549392893 0.00352489357369902 0.0318467063914224 -0.0031457985232155 -0.00033224196449252 0.995017042891054 -0.0997044330590104 0.00951756360027392 -0.0320394631347718 0.0996426589450309 0.994507321903866 0.0454662445571952 9.30973711443716e-05 1.942393362013e-05 -1.0434778130455e-05 1.33155927771152e-05 -2.86460122485616e-05 7.39261853021831e-05 1.942393362013e-05 7.62650655713419e-05 2.09344596993122e-07 1.14548291305303e-06 1.83303543335929e-05 -1.2117851520172e-05 -1.0434778130455e-05 2.09344596993122e-07 1.49470090542298e-05 -1.64929201084025e-06 8.09216895487773e-07 -5.51602861881029e-06 1.33155927771152e-05 1.14548291305303e-06 -1.64929201084025e-06 2.40227977400513e-05 -9.00101858765892e-06 1.75322224954789e-05 -2.86460122485616e-05 1.83303543335929e-05 8.09216895487773e-07 -9.00101858765892e-06 8.17987836274219e-05 -3.76204065228708e-05 7.39261853021831e-05 -1.2117851520172e-05 -5.51602861881029e-06 1.75322224954789e-05 -3.76204065228708e-05 0.000101161245670779 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 825 0 0 0 0 0 2131 +1068 1115 0.999586504955133 0.00370192958041339 0.0285151684014617 -0.0027906205219722 -0.000619217082956402 0.994219336029912 -0.107366328215346 0.00777600039480251 -0.0287477943812431 0.107304275691245 0.993810523558989 0.0514403481641764 8.5463928944952e-05 3.94888543656385e-05 -9.59666806708698e-06 2.39754962349887e-05 -2.8840826052985e-05 6.16863329471981e-05 3.94888543656385e-05 7.84494024169473e-05 -6.69258449390094e-06 1.29463318789734e-05 -2.76277680262487e-07 1.39665779022033e-05 -9.59666806708698e-06 -6.69258449390094e-06 1.7190253142991e-05 -3.0629918116111e-06 -3.07992629951964e-06 -5.7121058064761e-06 2.39754962349887e-05 1.29463318789734e-05 -3.0629918116111e-06 3.98624669193411e-05 -4.83968945398302e-05 1.59790087904703e-05 -2.8840826052985e-05 -2.76277680262487e-07 -3.07992629951964e-06 -4.83968945398302e-05 0.000171799339010603 -3.36552943851603e-05 6.16863329471981e-05 1.39665779022033e-05 -5.7121058064761e-06 1.59790087904703e-05 -3.36552943851603e-05 8.83270495763069e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 809 0 0 0 0 0 2234 +1068 1117 0.999708989248528 0.00324764767543648 0.023903757032386 -0.00357545587289658 -0.000659370009280689 0.994204887602913 -0.107499798593623 0.00405285434141083 -0.0241143535446831 0.107452753575955 0.993917704692932 0.0560247704134194 4.12918544050731e-05 4.36978984451418e-05 -1.72700673634736e-06 1.70590163758509e-06 -2.89920467647511e-06 1.09793285557353e-05 4.36978984451418e-05 7.04384770974474e-05 4.55775074419193e-07 8.94947308892039e-06 -2.17114743257447e-05 1.03552032672171e-05 -1.72700673634736e-06 4.55775074419193e-07 1.18872166553698e-05 1.57078705433416e-06 1.11552992692381e-06 2.49568919298562e-07 1.70590163758509e-06 8.94947308892039e-06 1.57078705433416e-06 2.67924342910422e-05 -3.31175634451435e-05 2.06118460024616e-06 -2.89920467647511e-06 -2.17114743257447e-05 1.11552992692381e-06 -3.31175634451435e-05 0.000123405068282062 2.71425850173174e-06 1.09793285557353e-05 1.03552032672171e-05 2.49568919298562e-07 2.06118460024616e-06 2.71425850173174e-06 2.70609195186391e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 779 0 0 0 0 0 2143 +1069 1104 0.998727106685532 0.00199414750107508 0.0504002951111353 -0.0139867945260873 0.00257407801392597 0.995901150973364 -0.0904116785172494 0.0254998776418822 -0.05037400613336 0.0904263283876559 0.994628341965181 0.0291910866718563 0.000104187260805574 6.05060435593531e-05 6.18499047394307e-06 2.44886173006673e-06 -3.12340763246425e-05 4.45137670375396e-05 6.05060435593531e-05 0.000108911280350285 7.53996234548485e-06 -3.53102074730676e-06 1.85353551746997e-05 -5.75504381870576e-06 6.18499047394307e-06 7.53996234548485e-06 1.65054401828173e-05 -5.32385742797894e-06 3.03667119826492e-06 3.61278809707195e-06 2.44886173006673e-06 -3.53102074730676e-06 -5.32385742797894e-06 3.36497277507808e-05 -2.12734847246592e-05 1.29136449886379e-05 -3.12340763246425e-05 1.85353551746997e-05 3.03667119826492e-06 -2.12734847246592e-05 0.000116667017343748 -4.18223471374248e-05 4.45137670375396e-05 -5.75504381870576e-06 3.61278809707195e-06 1.29136449886379e-05 -4.18223471374248e-05 6.93921955101572e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 669 0 0 0 0 0 2332 +1069 1105 0.998559478406436 0.00222906786348714 0.0536096944696262 -0.0117064444281722 0.00269800679557188 0.995786823294032 -0.0916587328807847 0.0237340203091502 -0.0535881408895452 0.0916713358168188 0.994346356832247 0.0295747565828941 6.26839167614865e-05 4.20598807423821e-05 -4.01982441066198e-06 3.14091878997855e-06 -2.47070109115084e-05 2.50925399105166e-05 4.20598807423821e-05 7.75663048257547e-05 -1.94277825977385e-06 6.09883428869023e-06 -9.57196852030873e-06 5.32796688570838e-06 -4.01982441066198e-06 -1.94277825977385e-06 1.36731021527049e-05 -6.37260713580834e-07 2.69859736471445e-06 -1.6133786491837e-07 3.14091878997855e-06 6.09883428869023e-06 -6.37260713580834e-07 2.95629643971802e-05 -1.68412235096831e-05 6.59808174369865e-06 -2.47070109115084e-05 -9.57196852030873e-06 2.69859736471445e-06 -1.68412235096831e-05 9.82913961762213e-05 -1.26271262813584e-05 2.50925399105166e-05 5.32796688570838e-06 -1.6133786491837e-07 6.59808174369865e-06 -1.26271262813584e-05 4.65358598499698e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 727 0 0 0 0 0 2263 +1069 1101 0.998359487297754 0.00377338373402303 0.0571322649451444 -0.00704773326491702 0.00165643253636858 0.995504958005011 -0.094694956669794 0.0191313665633761 -0.0572327734241389 0.0946342441330701 0.993865569120665 0.0330306929734209 4.29790371431925e-05 2.39277638028857e-05 -1.187619741405e-05 6.52395644931084e-06 -1.15022493418586e-06 5.62857162684054e-06 2.39277638028857e-05 7.11306408378249e-05 -1.53630208549906e-07 2.11988214090377e-06 -3.69376456315841e-06 -1.91789151446855e-05 -1.187619741405e-05 -1.53630208549906e-07 1.90742865174305e-05 -6.22414260004573e-06 -4.14426733702189e-06 -4.50075158299748e-06 6.52395644931084e-06 2.11988214090377e-06 -6.22414260004573e-06 2.51109682088858e-05 -3.5478514972147e-07 4.81523302828532e-06 -1.15022493418586e-06 -3.69376456315841e-06 -4.14426733702189e-06 -3.5478514972147e-07 6.20211948559184e-05 7.80829498588701e-06 5.62857162684054e-06 -1.91789151446855e-05 -4.50075158299748e-06 4.81523302828532e-06 7.80829498588701e-06 3.96948650292674e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 715 0 0 0 0 0 2316 +1069 1108 0.998722037047293 0.00375484404457966 0.0504003359344647 -0.00934765864429286 0.000975531559904873 0.995618345065667 -0.0935048624771879 0.0203858732400411 -0.0505305952298371 0.093434533845378 0.994342318736769 0.0343183564898022 5.92815078892437e-05 3.0035271717676e-05 -1.21881787524054e-05 7.83777925332946e-06 -9.66178400952203e-06 1.91888773118931e-05 3.0035271717676e-05 7.14203077355507e-05 -6.93733569060566e-06 3.5356590054513e-06 9.73999955823711e-06 -7.14906588936057e-06 -1.21881787524054e-05 -6.93733569060566e-06 1.66258343557782e-05 -4.4595615269426e-06 -2.98920668922846e-06 -3.54698016935091e-06 7.83777925332946e-06 3.5356590054513e-06 -4.4595615269426e-06 2.23716345679071e-05 -2.8568711983153e-06 4.97930444111105e-06 -9.66178400952203e-06 9.73999955823711e-06 -2.98920668922846e-06 -2.8568711983153e-06 6.78185109082447e-05 -1.14245109845522e-05 1.91888773118931e-05 -7.14906588936057e-06 -3.54698016935091e-06 4.97930444111105e-06 -1.14245109845522e-05 4.49888578166338e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 688 0 0 0 0 0 2287 +1069 1109 0.998932490812426 0.0036544464438764 0.046049145708371 -0.00731520827266262 0.000743234410728785 0.995465285184017 -0.0951226239972065 0.01028941902555 -0.0461879465000627 0.0950553050318185 0.994399900735823 0.0344541144199914 4.38016936024602e-05 3.05237360020789e-05 -8.33292216308584e-06 2.83049292889685e-08 3.10672134788652e-06 6.13513853719755e-06 3.05237360020789e-05 6.95981938413139e-05 -1.37331696375153e-06 4.54498765734793e-06 -1.1989857710555e-05 -4.54913344642358e-06 -8.33292216308584e-06 -1.37331696375153e-06 1.43082854814051e-05 -1.01536611159363e-06 -2.03466381466851e-06 -1.02686171949666e-07 2.83049292889685e-08 4.54498765734793e-06 -1.01536611159363e-06 2.44579593743923e-05 -1.18731957145864e-05 -1.63540450461725e-06 3.10672134788652e-06 -1.1989857710555e-05 -2.03466381466851e-06 -1.18731957145864e-05 7.80959707282112e-05 7.93216631263552e-06 6.13513853719755e-06 -4.54913344642358e-06 -1.02686171949666e-07 -1.63540450461725e-06 7.93216631263552e-06 3.65817971405308e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 800 0 0 0 0 0 2275 +1069 1107 0.998638383627797 0.00409299263731194 0.0520060203873648 -0.00688809300984529 0.00104924311396962 0.995139693011717 -0.0984677128882026 0.0158864639823529 -0.0521562827869076 0.098388204596977 0.993780399968743 0.0368084169765647 4.4329507212813e-05 3.74855245801754e-05 -9.7681663220718e-06 9.17247397831598e-06 -1.11792137834529e-05 8.94637321380317e-06 3.74855245801754e-05 7.47868104288304e-05 -5.00209969055581e-06 1.10532614673636e-05 -1.94928165062096e-05 -4.1259092078561e-06 -9.7681663220718e-06 -5.00209969055581e-06 1.72023725052515e-05 -3.22645383871321e-06 -3.93494825967451e-06 -2.28150943970746e-06 9.17247397831598e-06 1.10532614673636e-05 -3.22645383871321e-06 2.44440901996288e-05 -1.05533805716362e-05 3.96904562551696e-06 -1.11792137834529e-05 -1.94928165062096e-05 -3.93494825967451e-06 -1.05533805716362e-05 9.02531597308734e-05 -6.84675006054165e-07 8.94637321380317e-06 -4.1259092078561e-06 -2.28150943970746e-06 3.96904562551696e-06 -6.84675006054165e-07 3.37030985588314e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 666 0 0 0 0 0 2199 +1069 1110 0.99859314431449 0.00376599388206504 0.0528918653308897 -0.00584557527762775 0.00142810193981887 0.995202841820024 -0.0978226157807972 0.0144909817004718 -0.0530065340590216 0.0977605284530942 0.993797356820605 0.035204429862385 4.55259654852263e-05 1.04590536097809e-05 -1.29545260430839e-05 8.5331797571357e-06 -2.65536339665554e-06 2.26649011941934e-05 1.04590536097809e-05 4.97685600109889e-05 -2.17609117426026e-06 1.30161776881316e-06 7.35653524971927e-06 -4.54146309619142e-06 -1.29545260430839e-05 -2.17609117426026e-06 1.60897605804505e-05 -4.57228404294391e-06 -1.34013995011154e-06 -3.15615233451814e-06 8.5331797571357e-06 1.30161776881316e-06 -4.57228404294391e-06 2.55915360163335e-05 -8.26695752150521e-06 1.01969801351151e-05 -2.65536339665554e-06 7.35653524971927e-06 -1.34013995011154e-06 -8.26695752150521e-06 7.256593511085e-05 -7.6343101856575e-06 2.26649011941934e-05 -4.54146309619142e-06 -3.15615233451814e-06 1.01969801351151e-05 -7.6343101856575e-06 4.01006506237536e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 723 0 0 0 0 0 2237 +1069 1071 0.998221821318325 -0.00846618260019322 -0.0590043998029408 0.0111885292048336 0.00740258732197931 0.999806579200256 -0.0182210287531168 0.0422251583415927 0.0591472496813298 0.0177518432863076 0.998091416111306 0.0220755542428872 2.67825040793928e-05 1.07079642255857e-05 -8.06702964024325e-06 3.82354010160398e-06 3.42065537896736e-06 1.17918884660184e-05 1.07079642255857e-05 6.5694236555292e-05 -3.46753667091384e-06 6.135734837432e-06 1.04200762633716e-05 -1.42995985145545e-05 -8.06702964024325e-06 -3.46753667091384e-06 1.98001872865682e-05 -1.02243700016215e-05 -3.60912254116526e-06 -1.31070446951052e-06 3.82354010160398e-06 6.135734837432e-06 -1.02243700016215e-05 3.20644755711406e-05 -9.71745880418209e-06 -5.55783812091508e-06 3.42065537896736e-06 1.04200762633716e-05 -3.60912254116526e-06 -9.71745880418209e-06 7.50670002230419e-05 3.19722079059975e-06 1.17918884660184e-05 -1.42995985145545e-05 -1.31070446951052e-06 -5.55783812091508e-06 3.19722079059975e-06 4.46096145324421e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1211 0 0 0 0 0 2214 +1069 1103 0.998625800253061 0.00254814760421955 0.052345181370588 -0.0142356166216637 0.00238651170760372 0.995569978342001 -0.0939932060628732 0.0230796217319799 -0.0523527996462664 0.0939889630110652 0.994195785145613 0.0313973809688772 6.31041588073541e-05 5.2452247117188e-05 -1.56729644416091e-07 5.08124362741512e-06 -2.13403540291748e-05 1.34404141053953e-05 5.2452247117188e-05 8.38567336635173e-05 -4.23539201001364e-06 1.25801312509226e-05 -1.30446008777017e-05 4.51285590131596e-06 -1.56729644416091e-07 -4.23539201001364e-06 1.31816098565061e-05 -1.74167554513009e-06 -2.60701435554676e-06 1.05990330265707e-06 5.08124362741512e-06 1.25801312509226e-05 -1.74167554513009e-06 2.42742304029796e-05 -2.68808225278123e-06 6.26194405922734e-06 -2.13403540291748e-05 -1.30446008777017e-05 -2.60701435554676e-06 -2.68808225278123e-06 7.08757430010222e-05 -1.60600407179916e-05 1.34404141053953e-05 4.51285590131596e-06 1.05990330265707e-06 6.26194405922734e-06 -1.60600407179916e-05 4.19580519889263e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 589 0 0 0 0 0 2313 +1069 1106 0.998588418282198 0.0025871127215388 0.0530516514391718 -0.00898057169119583 0.00235839163743174 0.995668305328416 -0.0929465639672842 0.0154256716901442 -0.0530623111213771 0.0929404788679616 0.994256736726612 0.0314775441115316 4.54974328970896e-05 3.07271684028904e-05 -6.22473740320004e-06 3.22298899086062e-06 -7.55517757966108e-06 1.19647464182513e-05 3.07271684028904e-05 6.25281083813196e-05 -1.94475898629792e-06 3.07669856037505e-06 -1.63169892733117e-06 1.63366328783081e-06 -6.22473740320004e-06 -1.94475898629792e-06 1.47705213415757e-05 -1.12879169548848e-06 -6.55010864792471e-08 -7.17889357223095e-07 3.22298899086062e-06 3.07669856037505e-06 -1.12879169548848e-06 2.31715762181611e-05 -5.6519298959985e-06 3.8308402626856e-06 -7.55517757966108e-06 -1.63169892733117e-06 -6.55010864792471e-08 -5.6519298959985e-06 6.69328506202586e-05 3.3100736091677e-06 1.19647464182513e-05 1.63366328783081e-06 -7.17889357223095e-07 3.8308402626856e-06 3.3100736091677e-06 3.46878003070349e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 765 0 0 0 0 0 2347 +1069 1111 0.998577638456166 0.00347085300904377 0.0532038828911675 -0.00624083658534135 0.0017689057506588 0.995172790077086 -0.0981223158238436 0.00890737270883817 -0.0532876247148693 0.0980768630696274 0.993751154959162 0.0358789467898383 4.82367310722436e-05 4.16798428310474e-05 -7.40591326465458e-06 2.86505932977643e-06 -3.03883026401772e-06 7.76361788409927e-07 4.16798428310474e-05 6.36034625565678e-05 -3.27921407987706e-06 3.05154172232689e-07 -2.85344359751967e-06 -8.03373544546459e-06 -7.40591326465458e-06 -3.27921407987706e-06 1.22003232320467e-05 -8.72331721565585e-07 -1.53100798353136e-06 -2.02095051490842e-06 2.86505932977643e-06 3.05154172232689e-07 -8.72331721565585e-07 2.08768734007198e-05 -1.1454446988868e-05 1.40897936340605e-06 -3.03883026401772e-06 -2.85344359751967e-06 -1.53100798353136e-06 -1.1454446988868e-05 7.78951174000221e-05 3.5793136460878e-06 7.76361788409927e-07 -8.03373544546459e-06 -2.02095051490842e-06 1.40897936340605e-06 3.5793136460878e-06 3.15449269847051e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 673 0 0 0 0 0 2315 +1069 1112 0.99875516331157 0.0041889368438841 0.0497048947951499 -0.00552778251532953 0.000986709429613988 0.994613465973266 -0.103648828788117 0.00481132595232795 -0.0498713360857766 0.103568847211721 0.993371201376532 0.0402576122615949 6.66292679878064e-05 2.51378499527162e-05 -1.45929011015681e-05 2.44820796781835e-05 -4.3305311145917e-05 4.42066610444854e-05 2.51378499527162e-05 6.4505618994019e-05 -4.28595347672717e-06 5.021349659388e-06 9.71999590427214e-06 3.6646805484997e-06 -1.45929011015681e-05 -4.28595347672717e-06 1.62506730555452e-05 -5.97063147254295e-06 2.56104858837802e-06 -9.04217310539417e-06 2.44820796781835e-05 5.021349659388e-06 -5.97063147254295e-06 3.54360904258276e-05 -3.57538816287966e-05 2.46300425831824e-05 -4.3305311145917e-05 9.71999590427214e-06 2.56104858837802e-06 -3.57538816287966e-05 0.000165071738949511 -4.33646707001785e-05 4.42066610444854e-05 3.6646805484997e-06 -9.04217310539417e-06 2.46300425831824e-05 -4.33646707001785e-05 6.49550461179618e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 715 0 0 0 0 0 2295 +1069 1113 0.99840010254362 0.0031910871097322 0.056453983065391 -0.00548240180766291 0.00246611561165138 0.994998791493323 -0.0998565130605737 0.00597532655065682 -0.0564902957566989 0.0998359749283025 0.993399025867972 0.0367763434452827 0.000117568634565413 2.29672889191412e-05 -1.84854843772155e-05 2.30236019603994e-05 -5.25292054570425e-05 8.18490249769091e-05 2.29672889191412e-05 8.00136919418681e-05 1.09045762094389e-07 1.94022671070674e-06 1.35529209968816e-05 -5.68426290701532e-06 -1.84854843772155e-05 1.09045762094389e-07 2.05438774399348e-05 -4.55730006759937e-06 4.42589446879709e-07 -8.99871832291333e-06 2.30236019603994e-05 1.94022671070674e-06 -4.55730006759937e-06 2.90123145919537e-05 -1.86145666105008e-05 2.08954223206071e-05 -5.25292054570425e-05 1.35529209968816e-05 4.42589446879709e-07 -1.86145666105008e-05 0.000120471466057018 -5.21505162898092e-05 8.18490249769091e-05 -5.68426290701532e-06 -8.99871832291333e-06 2.08954223206071e-05 -5.21505162898092e-05 9.69062796067705e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 693 0 0 0 0 0 2290 +1069 1116 0.998656979172258 0.0037037666616567 0.0516770748306909 -0.00354328455404401 0.00169843944883377 0.994564956845631 -0.104104091745169 -0.00329480608150985 -0.0517817849632424 0.104052048164195 0.993222944770637 0.0394363807543159 8.79391648183708e-05 4.82284743450901e-05 -1.11812967931756e-06 2.72161891966825e-06 -1.77728117720134e-05 4.66316949593354e-05 4.82284743450901e-05 8.33345207961348e-05 3.13905644924515e-06 2.35051222310536e-06 -6.50310744094472e-06 1.28702591281291e-05 -1.11812967931756e-06 3.13905644924515e-06 1.22548208233874e-05 -1.39738550440367e-07 -2.64906271074675e-06 -8.70544464596108e-07 2.72161891966825e-06 2.35051222310536e-06 -1.39738550440367e-07 2.42375768482106e-05 -1.79194836574594e-05 4.34758765645217e-06 -1.77728117720134e-05 -6.50310744094472e-06 -2.64906271074675e-06 -1.79194836574594e-05 0.000107612738095368 -1.68636900397402e-05 4.66316949593354e-05 1.28702591281291e-05 -8.70544464596108e-07 4.34758765645217e-06 -1.68636900397402e-05 6.1133592549149e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 723 0 0 0 0 0 2263 +1069 1114 0.998641049276604 0.00327517207057783 0.0520127671599101 -0.00928951976745546 0.00170870960808495 0.995429125440183 -0.0954878868593722 0.0126529642732502 -0.0520877625858335 0.0954469982414384 0.994070789992091 0.0354225026250248 3.64486543537597e-05 2.26594145502165e-05 -8.67008044903381e-06 -1.00318321036935e-07 3.50463231819656e-06 1.12135268281802e-05 2.26594145502165e-05 4.80713482412764e-05 -2.53768312992415e-06 -2.3974380059426e-06 8.65411671380271e-06 -2.14935780061819e-06 -8.67008044903381e-06 -2.53768312992415e-06 1.53945172357819e-05 -4.41739539787524e-07 -5.08599998318522e-07 -1.49865658125237e-06 -1.00318321036935e-07 -2.3974380059426e-06 -4.41739539787524e-07 2.37426510613978e-05 -9.57085668179942e-06 4.25886907192355e-06 3.50463231819656e-06 8.65411671380271e-06 -5.08599998318522e-07 -9.57085668179942e-06 7.54056549455276e-05 -4.32691751790855e-06 1.12135268281802e-05 -2.14935780061819e-06 -1.49865658125237e-06 4.25886907192355e-06 -4.32691751790855e-06 3.6884512959758e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 815 0 0 0 0 0 2283 +1069 1115 0.998817403927383 0.00410142927660847 0.0484455559329425 -0.00935905574625759 0.000578837272213358 0.995361665291818 -0.0962019761486739 0.0114155547930569 -0.0486154148308454 0.0961162501629496 0.994182180435476 0.0355659357300578 4.76158306372393e-05 2.87635636673168e-05 -8.26206998755597e-06 3.49306036004407e-06 3.38626451969476e-06 9.41406032911839e-06 2.87635636673168e-05 6.7590436150951e-05 -3.5228305536042e-06 3.34345101814145e-06 1.60542446071638e-06 -3.58157214587723e-06 -8.26206998755597e-06 -3.5228305536042e-06 1.33563081173911e-05 -2.69239295360318e-06 5.49281999440927e-07 -2.95305908121838e-06 3.49306036004407e-06 3.34345101814145e-06 -2.69239295360318e-06 3.00659104715244e-05 -2.68028912491829e-05 1.10803004962134e-06 3.38626451969476e-06 1.60542446071638e-06 5.49281999440927e-07 -2.68028912491829e-05 0.000103477018739834 3.11277147776243e-06 9.41406032911839e-06 -3.58157214587723e-06 -2.95305908121838e-06 1.10803004962134e-06 3.11277147776243e-06 4.02625451875475e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 786 0 0 0 0 0 2286 +1069 1119 0.998705874520696 0.0044371199379054 0.0506644664879447 -0.00510716423133832 0.000874844431334225 0.994540724488748 -0.104345493341197 0.00814948302810893 -0.0508508686756912 0.104254780705987 0.993249782207313 0.0385114996520848 4.88051480480709e-05 2.02830314438254e-05 -3.19080163357687e-06 1.46752512432237e-05 -3.14052847892379e-05 2.07910375268145e-05 2.02830314438254e-05 5.50955541551022e-05 -2.3690611542764e-06 -2.19403435509339e-07 1.41555382400054e-05 1.58194228420999e-06 -3.19080163357687e-06 -2.3690611542764e-06 1.57934454799757e-05 -2.01971452312654e-06 2.07952357739654e-06 -1.2612255700222e-06 1.46752512432237e-05 -2.19403435509339e-07 -2.01971452312654e-06 3.69598930359166e-05 -4.78333620184031e-05 7.90440077361264e-06 -3.14052847892379e-05 1.41555382400054e-05 2.07952357739654e-06 -4.78333620184031e-05 0.00019313685977805 -1.91050713743443e-05 2.07910375268145e-05 1.58194228420999e-06 -1.2612255700222e-06 7.90440077361264e-06 -1.91050713743443e-05 4.81137288379647e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 764 0 0 0 0 0 2275 +1070 1104 0.996993565041326 0.00368007923985542 0.0773969526724131 -0.0151248818798996 0.0036246150091097 0.995562969904872 -0.0940278422608263 0.0128177051760379 -0.0773995699744069 0.0940256878250804 0.992556535718141 0.0313183160705979 0.000339238238636851 0.000109847289932819 -1.16146534962552e-05 5.91085973956943e-05 -0.000194259827408656 0.000342580895478593 0.000109847289932819 0.000149945158391604 2.37001381226104e-06 7.68053997119442e-06 7.74848532502859e-06 6.70799141504958e-05 -1.16146534962552e-05 2.37001381226104e-06 1.71403018023617e-05 -6.52029870081685e-06 1.18530789518035e-05 -1.32719885158828e-05 5.91085973956943e-05 7.68053997119442e-06 -6.52029870081685e-06 4.56454569237302e-05 -5.70513114721804e-05 7.71743538871429e-05 -0.000194259827408656 7.74848532502859e-06 1.18530789518035e-05 -5.70513114721804e-05 0.000247017030085755 -0.000242548967779889 0.000342580895478593 6.70799141504958e-05 -1.32719885158828e-05 7.71743538871429e-05 -0.000242548967779889 0.000412639784876607 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 660 0 0 0 0 0 2258 +1069 1117 0.998469708883783 0.00342657346286364 0.0551950997447968 -0.00177731872109187 0.00226451523816789 0.994708014664384 -0.10271726988767 -0.0019864108096124 -0.0552549763575244 0.102685072706523 0.993178062298491 0.0379714308404581 8.42282268453074e-05 5.96638065713009e-05 -4.08842264623448e-06 1.20354741366799e-05 -2.69143784395544e-05 4.04796911202543e-05 5.96638065713009e-05 7.91821921360465e-05 -2.69320208975576e-06 1.11491623610536e-05 -1.18385589793058e-05 2.00095670234518e-05 -4.08842264623448e-06 -2.69320208975576e-06 1.31326925899999e-05 -1.12808069486072e-06 7.85240988985052e-07 -4.03327728771435e-07 1.20354741366799e-05 1.11491623610536e-05 -1.12808069486072e-06 2.82575960552167e-05 -2.20312960211995e-05 9.74044538210078e-06 -2.69143784395544e-05 -1.18385589793058e-05 7.85240988985052e-07 -2.20312960211995e-05 0.000106677161719346 -1.57412451515756e-05 4.04796911202543e-05 2.00095670234518e-05 -4.03327728771435e-07 9.74044538210078e-06 -1.57412451515756e-05 4.94682236676721e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 743 0 0 0 0 0 2241 +1070 1108 0.997571793004112 0.00540582060112869 0.0694355449765461 -0.0154601752922718 0.000845012940576101 0.995970249222187 -0.0896802576792925 0.0149935353098268 -0.0696405324196463 0.0895211693842437 0.993547259306967 0.0284000636722781 5.60167318543271e-05 2.32526762176097e-05 -1.27599102899792e-05 1.06085165219324e-05 -1.39813872691603e-05 2.3122229600374e-05 2.32526762176097e-05 7.36345182458981e-05 -4.3072605543012e-06 2.99322755564166e-06 6.30295810502907e-06 -2.07855128361987e-06 -1.27599102899792e-05 -4.3072605543012e-06 1.62990912596762e-05 -5.57732434209021e-06 -5.3149166673314e-07 -5.50431127018244e-06 1.06085165219324e-05 2.99322755564166e-06 -5.57732434209021e-06 2.6105933032625e-05 -1.1192279684881e-05 1.08610431210321e-05 -1.39813872691603e-05 6.30295810502907e-06 -5.3149166673314e-07 -1.1192279684881e-05 9.13156411904649e-05 -1.95126266030844e-05 2.3122229600374e-05 -2.07855128361987e-06 -5.50431127018244e-06 1.08610431210321e-05 -1.95126266030844e-05 5.50380532581347e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 701 0 0 0 0 0 2199 +1070 1106 0.996764072465725 0.00442454993403558 0.0802608696652573 -0.011407870165644 0.00308221813062488 0.995645882818551 -0.0931653152083122 0.007889379692339 -0.0803236190229091 0.0931112205072522 0.992410407463924 0.0310452754188115 0.000165130686873741 5.64464084883782e-05 -1.37399121672315e-05 1.16759154905548e-05 -4.93753120325016e-05 0.000114195396357416 5.64464084883782e-05 0.000109463154033388 -1.87476889654741e-06 6.91917873906244e-06 5.14582165638326e-06 5.70332605781828e-06 -1.37399121672315e-05 -1.87476889654741e-06 1.56118397184468e-05 -2.35860720179152e-06 2.42668097486239e-06 -7.69430389634475e-06 1.16759154905548e-05 6.91917873906244e-06 -2.35860720179152e-06 2.25873895638404e-05 -1.16095267256861e-06 8.44338106441887e-06 -4.93753120325016e-05 5.14582165638326e-06 2.42668097486239e-06 -1.16095267256861e-06 7.81289548300761e-05 -5.06777923102238e-05 0.000114195396357416 5.70332605781828e-06 -7.69430389634475e-06 8.44338106441887e-06 -5.06777923102238e-05 0.000128921511511278 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 762 0 0 0 0 0 2288 +1070 1105 0.996999378242089 0.00357024856613385 0.0773271822198584 -0.0123249398267452 0.00395744406836339 0.995278750368569 -0.096977047290716 0.00361020277756342 -0.0773083334533408 0.0969920738511968 0.992278166236016 0.0352022918365489 0.000154223772579278 4.26735073350006e-05 -7.02540755002809e-06 1.24493667708811e-05 -7.01636458394751e-05 0.000119197479219698 4.26735073350006e-05 0.00011045385119165 -9.1795443167398e-07 9.23693582087389e-06 1.13652031088152e-05 -1.20648942162442e-06 -7.02540755002809e-06 -9.1795443167398e-07 1.61381212825429e-05 -2.98026842378629e-06 6.12718293021727e-07 -4.05194006116642e-06 1.24493667708811e-05 9.23693582087389e-06 -2.98026842378629e-06 3.02437057376073e-05 -9.81331574555981e-06 1.3335163772886e-05 -7.01636458394751e-05 1.13652031088152e-05 6.12718293021727e-07 -9.81331574555981e-06 0.000110455434252073 -6.96593921338117e-05 0.000119197479219698 -1.20648942162442e-06 -4.05194006116642e-06 1.3335163772886e-05 -6.96593921338117e-05 0.000146486338833898 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 727 0 0 0 0 0 2181 +1070 1103 0.99685090924295 0.00430430936473953 0.0791816750416143 -0.0169026166337516 0.00290315228538612 0.995875422999332 -0.090684693155507 0.0186164587485402 -0.0792454190998511 0.0906289952873429 0.992726824844023 0.0239665031001275 4.47473695913632e-05 3.23084557882096e-05 -3.93272610624511e-06 3.41241045582458e-06 -1.05023258620251e-05 8.88666174713731e-06 3.23084557882096e-05 6.3880001219181e-05 -7.5054433426381e-06 1.05857118077962e-05 1.66876163889413e-06 -6.09434846699951e-07 -3.93272610624511e-06 -7.5054433426381e-06 1.32791640640409e-05 -1.5814680612257e-07 1.38626844627082e-06 5.62094059860299e-07 3.41241045582458e-06 1.05857118077962e-05 -1.5814680612257e-07 2.26637223950914e-05 1.60308686720805e-06 3.7885383495351e-06 -1.05023258620251e-05 1.66876163889413e-06 1.38626844627082e-06 1.60308686720805e-06 6.03361040848879e-05 -9.65569045619152e-06 8.88666174713731e-06 -6.09434846699951e-07 5.62094059860299e-07 3.7885383495351e-06 -9.65569045619152e-06 3.95646890297075e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 595 0 0 0 0 0 2320 +1070 1107 0.997001464825792 0.00457053280231233 0.0772475848498005 -0.0147522755284729 0.00224717385611569 0.996123128439132 -0.0879412485600338 0.0230217552741655 -0.0773500442461704 0.0878511423860854 0.993125947418843 0.0266942838187316 7.69147437661913e-05 4.94894588755876e-05 -1.57614028073698e-05 1.18240083297072e-05 -2.17938764637669e-05 2.68985295463696e-05 4.94894588755876e-05 7.47184409314016e-05 -8.15977598404754e-06 9.35209889869894e-06 -2.81222390862505e-06 9.87827180063287e-06 -1.57614028073698e-05 -8.15977598404754e-06 1.60862739811282e-05 -3.459161434052e-06 1.26715595089232e-06 -4.95532173718166e-06 1.18240083297072e-05 9.35209889869894e-06 -3.459161434052e-06 2.80307718763299e-05 -9.93753618596981e-06 1.11150104591103e-05 -2.17938764637669e-05 -2.81222390862505e-06 1.26715595089232e-06 -9.93753618596981e-06 8.66451478092503e-05 -8.26996311293897e-06 2.68985295463696e-05 9.87827180063287e-06 -4.95532173718166e-06 1.11150104591103e-05 -8.26996311293897e-06 4.90228091927296e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 681 0 0 0 0 0 2135 +1070 1109 0.997196282699261 0.00572063286913769 0.0746113136886864 -0.00803717932952004 0.0013015484337457 0.995596771618107 -0.0937303276174669 0.00270617043868838 -0.0748189798276456 0.0935646445147931 0.992797954044211 0.0275333127255498 7.58640222174764e-05 1.6866213009118e-05 -2.06908850009585e-05 9.8923883312544e-06 3.28950807980951e-06 3.64383628445219e-05 1.6866213009118e-05 9.15008052660483e-05 -8.2583344566603e-07 6.38024781544752e-06 2.50185309778824e-06 -2.89518388031465e-05 -2.06908850009585e-05 -8.2583344566603e-07 1.94805724620606e-05 -4.07181484612659e-06 -3.74156677545388e-06 -1.09225217506859e-05 9.8923883312544e-06 6.38024781544752e-06 -4.07181484612659e-06 2.61222666730144e-05 -4.58833003771925e-06 6.46165801701593e-06 3.28950807980951e-06 2.50185309778824e-06 -3.74156677545388e-06 -4.58833003771925e-06 6.08189926038148e-05 -9.45914847325776e-06 3.64383628445219e-05 -2.89518388031465e-05 -1.09225217506859e-05 6.46165801701593e-06 -9.45914847325776e-06 8.13739417915589e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 785 0 0 0 0 0 2205 +1070 1110 0.99682922423859 0.00539096187548202 0.0793878783816988 -0.00743678758131722 0.00180974171882017 0.995908188773279 -0.0903526666415408 0.00754899985660908 -0.0795501259508837 0.0902098501516511 0.992740630979117 0.0278601192721442 3.99279482881238e-05 2.82247292536586e-05 -4.2638792839178e-06 4.17330045525243e-06 -3.13345928618485e-06 1.88884946453703e-06 2.82247292536586e-05 7.4237944084511e-05 1.57738131998789e-06 9.25158545704965e-06 -1.29267141270099e-06 -1.60080066467773e-05 -4.2638792839178e-06 1.57738131998789e-06 1.49178047734574e-05 7.53981547611388e-07 9.64531590634832e-07 -1.8627802949949e-08 4.17330045525243e-06 9.25158545704965e-06 7.53981547611388e-07 2.39588189131951e-05 -4.09790970791421e-06 -6.95959861822456e-07 -3.13345928618485e-06 -1.29267141270099e-06 9.64531590634832e-07 -4.09790970791421e-06 6.38731708907324e-05 -6.24397022998984e-06 1.88884946453703e-06 -1.60080066467773e-05 -1.8627802949949e-08 -6.95959861822456e-07 -6.24397022998984e-06 3.56096361985313e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 736 0 0 0 0 0 2188 +1070 1101 0.996517004751403 0.00440569496759318 0.0832733396300741 -0.0135773795735459 0.00278878793485022 0.9962840870808 -0.0860827537398294 0.019184372877036 -0.0833431575064658 0.0860151596024224 0.992801747790274 0.0221165802488168 4.4069061996131e-05 1.59568055363705e-05 -1.38027016119946e-05 7.4268609123671e-06 -1.00040909829751e-05 1.58410064023699e-05 1.59568055363705e-05 6.48849228971199e-05 1.05767728254066e-06 3.80452479299529e-06 2.48152360407471e-06 -1.22146373789928e-05 -1.38027016119946e-05 1.05767728254066e-06 1.87679066135736e-05 -5.8508007709603e-06 1.22176302897793e-06 -3.2648151168345e-06 7.4268609123671e-06 3.80452479299529e-06 -5.8508007709603e-06 2.88845221858679e-05 -3.23409002547376e-06 3.87681828444252e-06 -1.00040909829751e-05 2.48152360407471e-06 1.22176302897793e-06 -3.23409002547376e-06 7.28337887996986e-05 -1.11800079727479e-05 1.58410064023699e-05 -1.22146373789928e-05 -3.2648151168345e-06 3.87681828444252e-06 -1.11800079727479e-05 4.71549630826698e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 728 0 0 0 0 0 2296 +1070 1111 0.996396775374265 0.00362889384292347 0.0847366340684076 -0.00972467362462529 0.00376185056500437 0.996210119117929 -0.0868979116398563 0.00701005135501864 -0.0847308356154535 0.0869035654994574 0.992606898927964 0.0224958336382202 3.1282246057276e-05 1.5796986830467e-05 -6.74376376861059e-06 4.22574503701073e-06 -4.32557460701916e-06 1.27904293124243e-05 1.5796986830467e-05 4.71416360672175e-05 -1.55905891308226e-06 3.51056020982133e-06 6.92086230232277e-06 -1.25427870352899e-06 -6.74376376861059e-06 -1.55905891308226e-06 1.44197936911985e-05 2.45316673339628e-06 3.43403710496161e-06 -1.10625009773146e-06 4.22574503701073e-06 3.51056020982133e-06 2.45316673339628e-06 2.00106251926699e-05 2.34857075505216e-06 5.62622132029075e-06 -4.32557460701916e-06 6.92086230232277e-06 3.43403710496161e-06 2.34857075505216e-06 5.34231913075674e-05 -5.11621985094646e-06 1.27904293124243e-05 -1.25427870352899e-06 -1.10625009773146e-06 5.62622132029075e-06 -5.11621985094646e-06 3.72497633082832e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 685 0 0 0 0 0 2313 +1070 1140 0.996724702886936 0.0040700515202563 0.0807669569537709 -0.0138414791365492 0.00304553864510757 0.996135054141297 -0.0877819947670182 0.0205270191371268 -0.080812074279225 0.0877404615416292 0.992860020375053 0.0249422100854343 0.000107681792766875 4.52922704406892e-05 -1.24912552381858e-05 1.28051337169444e-05 -2.61621997216065e-05 7.0582079426769e-05 4.52922704406892e-05 9.99391325368976e-05 4.37678232402411e-07 3.24174047118547e-06 1.67662157541477e-05 1.10344216497978e-05 -1.24912552381858e-05 4.37678232402411e-07 1.71699779443548e-05 -5.18159321629294e-06 1.80300316989908e-06 -5.2806180484809e-06 1.28051337169444e-05 3.24174047118547e-06 -5.18159321629294e-06 3.44056307459358e-05 -2.7380587065545e-05 7.35164545436833e-06 -2.61621997216065e-05 1.67662157541477e-05 1.80300316989908e-06 -2.7380587065545e-05 0.000140480978182484 -1.86258871119867e-05 7.0582079426769e-05 1.10344216497978e-05 -5.2806180484809e-06 7.35164545436833e-06 -1.86258871119867e-05 8.55752990340064e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 831 0 0 0 0 0 2250 +1070 1112 0.99711468229002 0.00499660875664446 0.0757452590107487 -0.00663512058879022 0.00220658314918353 0.995501811324656 -0.0947168128693937 -0.00878020510949895 -0.0758778054010402 0.0946106629839524 0.992618446885438 0.0307475717791925 3.75725846745882e-05 2.00726945891717e-05 -1.19063034772764e-05 6.42987118162941e-06 -2.21403697399535e-06 6.00170724768047e-06 2.00726945891717e-05 6.27145491752967e-05 -1.92834228947887e-06 5.98436423117318e-07 7.49378571237295e-06 -7.81297517514059e-06 -1.19063034772764e-05 -1.92834228947887e-06 1.68449279448583e-05 -4.75155978732378e-06 8.51267980345236e-07 -3.75481197606383e-06 6.42987118162941e-06 5.98436423117318e-07 -4.75155978732378e-06 2.6394695611374e-05 -2.01186791686457e-05 5.26744759625028e-06 -2.21403697399535e-06 7.49378571237295e-06 8.51267980345236e-07 -2.01186791686457e-05 0.000102114919898287 -1.30289661747818e-05 6.00170724768047e-06 -7.81297517514059e-06 -3.75481197606383e-06 5.26744759625028e-06 -1.30289661747818e-05 4.32142997734113e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 721 0 0 0 0 0 2275 +1070 1135 0.997462221553345 0.00606343518433939 0.0709390677104704 -0.00929474656968243 0.000808429937252575 0.995338220969401 -0.09644258560669 -0.00109820259567615 -0.0711931388190038 0.0962551849576556 0.992807371222568 0.0322209000109225 6.25620134509005e-05 3.96677208747059e-05 -9.87247465298074e-06 1.23260763493288e-05 -2.45630921856842e-05 2.82835098935938e-05 3.96677208747059e-05 7.52640245307157e-05 -2.10205342305632e-06 3.46321186805425e-06 -3.7592902847953e-06 5.0577707249807e-06 -9.87247465298074e-06 -2.10205342305632e-06 1.50342275737949e-05 -2.5430980629647e-06 3.36959543934558e-06 -3.70582854570161e-06 1.23260763493288e-05 3.46321186805425e-06 -2.5430980629647e-06 3.90282465939339e-05 -6.57064310018854e-05 7.78591114723636e-06 -2.45630921856842e-05 -3.7592902847953e-06 3.36959543934558e-06 -6.57064310018854e-05 0.000231586929445499 -2.30223972097236e-05 2.82835098935938e-05 5.0577707249807e-06 -3.70582854570161e-06 7.78591114723636e-06 -2.30223972097236e-05 5.8531716730138e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 876 0 0 0 0 0 2280 +1070 1137 0.996886313955236 0.00511613573582916 0.0786860991781661 -0.0112774546787583 0.00186726377944115 0.996081404365404 -0.0884214295486202 0.0160680288583309 -0.07883013620895 0.0882930406803174 0.992970366422232 0.0266426222985271 0.000130895198744722 7.73848715913035e-05 -1.47682477179221e-05 3.09134419700476e-05 -6.00717042372568e-05 9.11590965677353e-05 7.73848715913035e-05 0.000132878141319344 -2.97327106232705e-06 2.76557526068468e-05 -2.73014947085159e-05 1.96109787635888e-05 -1.47682477179221e-05 -2.97327106232705e-06 1.77350685073786e-05 -3.14348978347759e-06 9.12704045859181e-07 -9.90633382918329e-06 3.09134419700476e-05 2.76557526068468e-05 -3.14348978347759e-06 4.93601049102872e-05 -6.61645815491319e-05 2.29704045690658e-05 -6.00717042372568e-05 -2.73014947085159e-05 9.12704045859181e-07 -6.61645815491319e-05 0.000235842060574254 -4.99316271100605e-05 9.11590965677353e-05 1.96109787635888e-05 -9.90633382918329e-06 2.29704045690658e-05 -4.99316271100605e-05 0.000120186065738673 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 879 0 0 0 0 0 2281 +1070 1136 0.996190855148339 0.00627911652908262 0.0869732879362141 -0.00593723730554479 0.00183086656935238 0.995677994846593 -0.0928546095025584 0.00733117338500963 -0.0871804338508741 0.0926601493301278 0.991873816914073 0.0246441866060567 3.40740394556107e-05 2.30210989878777e-06 -9.60174652153829e-06 1.47612889237001e-06 8.48008590850345e-07 1.20189855780711e-05 2.30210989878777e-06 7.85596581320275e-05 9.5598226999146e-06 5.57744973548375e-06 -1.13566558805166e-06 -1.96403056031015e-05 -9.60174652153829e-06 9.5598226999146e-06 1.96326968814952e-05 -2.40748229802655e-06 -6.30501838287912e-06 -2.65036567908097e-06 1.47612889237001e-06 5.57744973548375e-06 -2.40748229802655e-06 2.73669015870447e-05 -1.30186874121295e-05 -2.32685160522286e-06 8.48008590850345e-07 -1.13566558805166e-06 -6.30501838287912e-06 -1.30186874121295e-05 9.73467998667916e-05 6.72961740519494e-06 1.20189855780711e-05 -1.96403056031015e-05 -2.65036567908097e-06 -2.32685160522286e-06 6.72961740519494e-06 5.08710278311377e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 810 0 0 0 0 0 2204 +1070 1138 0.997243337553003 0.00632782607579964 0.0739302666253958 -0.0125455588487227 0.000987884172106192 0.995136453352222 -0.0985010827068547 0.0180108235074754 -0.0741940010446275 0.098302583011407 0.992386946902404 0.0355761261918185 4.25013317474649e-05 1.90055601751007e-05 -5.24062224482932e-06 2.16895582202475e-06 4.13222909729655e-06 2.07695736152897e-05 1.90055601751007e-05 7.29788079169242e-05 3.98063344961718e-08 4.95282330423269e-06 -2.14043072551347e-06 -9.1391638482175e-06 -5.24062224482932e-06 3.98063344961718e-08 1.60692861283537e-05 -1.54827747120616e-06 -3.77955194282268e-06 -1.73995372797463e-06 2.16895582202475e-06 4.95282330423269e-06 -1.54827747120616e-06 2.58211060614002e-05 -1.41931525430603e-05 -4.85784917724232e-06 4.13222909729655e-06 -2.14043072551347e-06 -3.77955194282268e-06 -1.41931525430603e-05 0.000105656941284272 3.89964231149632e-06 2.07695736152897e-05 -9.1391638482175e-06 -1.73995372797463e-06 -4.85784917724232e-06 3.89964231149632e-06 5.44251695271765e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 882 0 0 0 0 0 2126 +1070 1115 0.99718849866939 0.00506525939330233 0.0747625659589578 -0.00890773345309389 0.00216193893400167 0.995352665802762 -0.0962725126886256 -0.002188332712012 -0.0749027645787163 0.0961634744932529 0.992543279676937 0.0317836853504902 0.000150153106638449 7.75713774908126e-05 -1.51235864739549e-05 3.81366386022698e-05 -6.15349014431307e-05 9.67903808832625e-05 7.75713774908126e-05 0.000101261769846989 -3.45424929265753e-06 2.17660353893588e-05 -3.06193548960421e-05 3.97157568135562e-05 -1.51235864739549e-05 -3.45424929265753e-06 1.57366502336043e-05 -3.8528638549102e-06 7.69214086866607e-06 -9.28908586043997e-06 3.81366386022698e-05 2.17660353893588e-05 -3.8528638549102e-06 4.13766733344581e-05 -5.1800109444907e-05 2.70915075861978e-05 -6.15349014431307e-05 -3.06193548960421e-05 7.69214086866607e-06 -5.1800109444907e-05 0.000170033580195919 -6.01759022704035e-05 9.67903808832625e-05 3.97157568135562e-05 -9.28908586043997e-06 2.70915075861978e-05 -6.01759022704035e-05 0.000123333861379936 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 789 0 0 0 0 0 2253 +1070 1113 0.997265740806877 0.00494780780098697 0.0737330415137909 -0.0112548513925097 0.00200464690386921 0.995577620327544 -0.0939211546656835 0.0038692614247877 -0.0738716698315445 0.0938121585984936 0.992845534459107 0.0304741948707801 3.92003639382382e-05 2.69122604466288e-05 -6.33606192481216e-06 -1.35012383704964e-06 4.36812744575068e-06 4.44526188702919e-06 2.69122604466288e-05 6.84002593548999e-05 8.07570304504436e-07 5.83087176402594e-06 -1.60323577589589e-05 -5.22178358941478e-06 -6.33606192481216e-06 8.07570304504436e-07 1.3919002483023e-05 9.11857009395136e-07 -2.35419780969682e-06 -6.8382904212568e-07 -1.35012383704964e-06 5.83087176402594e-06 9.11857009395136e-07 2.60750823126838e-05 -1.4361371664055e-05 -5.47250152470268e-06 4.36812744575068e-06 -1.60323577589589e-05 -2.35419780969682e-06 -1.4361371664055e-05 8.12708384989737e-05 7.39642174667462e-06 4.44526188702919e-06 -5.22178358941478e-06 -6.8382904212568e-07 -5.47250152470268e-06 7.39642174667462e-06 4.06424310947798e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 731 0 0 0 0 0 2293 +1070 1114 0.997320809762376 0.00491393419750583 0.0729866814262782 -0.0107344914325989 0.00228833445190274 0.995157240501593 -0.0982691721888969 -0.000643772363059983 -0.0731161127273235 0.0981729083197469 0.992479780213022 0.0338160832625892 0.000142159270232971 4.08246944747691e-05 -1.67609194225678e-05 3.24470749223856e-05 -7.75648335740981e-05 0.000108659118817537 4.08246944747691e-05 8.36438846939273e-05 -4.33109831477871e-06 7.80930036497496e-06 4.99739644415369e-06 2.87055827481116e-06 -1.67609194225678e-05 -4.33109831477871e-06 1.79442133971741e-05 -8.3285843252371e-06 3.61161546322788e-06 -8.4969334943838e-06 3.24470749223856e-05 7.80930036497496e-06 -8.3285843252371e-06 3.30956809929113e-05 -2.79514075840644e-05 2.90215436279108e-05 -7.75648335740981e-05 4.99739644415369e-06 3.61161546322788e-06 -2.79514075840644e-05 0.000136234586688114 -8.66215478234814e-05 0.000108659118817537 2.87055827481116e-06 -8.4969334943838e-06 2.90215436279108e-05 -8.66215478234814e-05 0.000150139257827082 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2191 +1070 1129 0.996463514484377 0.00558884969450587 0.0838404977354993 -0.00671211316730481 0.00265050831932123 0.99519839958014 -0.0978423235556935 0.00233588252873661 -0.0839847552064853 0.0977185255323678 0.991664081562243 0.0284086903822672 4.26236490477325e-05 2.6903298484587e-05 -6.72281980276961e-06 5.63319772196831e-06 -1.39373745235596e-05 1.5723933802441e-05 2.6903298484587e-05 6.84346981607681e-05 -2.78954217248574e-06 9.42325235552169e-06 -1.44936982289213e-05 -2.3666193231096e-06 -6.72281980276961e-06 -2.78954217248574e-06 1.48257149642061e-05 1.51580793303008e-06 9.46965151582802e-08 1.22659811446406e-08 5.63319772196831e-06 9.42325235552169e-06 1.51580793303008e-06 3.95690652043417e-05 -5.93126407363673e-05 2.83103166348135e-06 -1.39373745235596e-05 -1.44936982289213e-05 9.46965151582802e-08 -5.93126407363673e-05 0.00021240783337216 -8.12673874378302e-06 1.5723933802441e-05 -2.3666193231096e-06 1.22659811446406e-08 2.83103166348135e-06 -8.12673874378302e-06 4.5989620486613e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 883 0 0 0 0 0 2141 +1070 1132 0.997092516914618 0.00497896433567637 0.0760376395413247 -0.0127619795068879 0.00209547772755215 0.995694057264157 -0.0926766060121687 0.00950404235794608 -0.0761716593357772 0.0925664855278922 0.992788660325574 0.0259307661092221 0.000157973443575333 8.93083399096409e-05 -1.79042128558052e-05 6.22875539970918e-05 -0.000128752828977282 9.05881097494164e-05 8.93083399096409e-05 0.000146258187278872 -3.90434071719201e-06 1.95123088024543e-05 -2.09254551623142e-05 2.24775209515922e-05 -1.79042128558052e-05 -3.90434071719201e-06 1.76631328015316e-05 -7.54504023760672e-06 1.23660750479117e-05 -1.15599685046062e-05 6.22875539970918e-05 1.95123088024543e-05 -7.54504023760672e-06 6.66628182651984e-05 -0.000123594010941925 4.1331471005525e-05 -0.000128752828977282 -2.09254551623142e-05 1.23660750479117e-05 -0.000123594010941925 0.000369758332022862 -9.93272867574339e-05 9.05881097494164e-05 2.24775209515922e-05 -1.15599685046062e-05 4.1331471005525e-05 -9.93272867574339e-05 0.000108280794307131 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 866 0 0 0 0 0 2108 +1070 1116 0.997363817985827 0.00492532939533465 0.0723958265584594 -0.00949840662938193 0.00196779986785713 0.995490961213253 -0.0948360369606047 0.000678479716045817 -0.0725364896890878 0.0947284924036088 0.992856973783497 0.029017469600634 4.27703828989239e-05 2.69043164983371e-05 -7.45303825809118e-06 4.35877133905294e-06 -7.41785767718971e-06 5.54268730502567e-07 2.69043164983371e-05 5.07165257182104e-05 -4.66111289219535e-06 5.17818101467576e-06 -1.07356662353504e-05 -2.87636193716897e-06 -7.45303825809118e-06 -4.66111289219535e-06 1.38836774518923e-05 1.55257455057303e-06 2.61734563989319e-06 -2.59550365797436e-06 4.35877133905294e-06 5.17818101467576e-06 1.55257455057303e-06 1.9920382957185e-05 -9.9640464566052e-06 -1.26701788641751e-07 -7.41785767718971e-06 -1.07356662353504e-05 2.61734563989319e-06 -9.9640464566052e-06 6.78401628562802e-05 9.18804358595622e-07 5.54268730502567e-07 -2.87636193716897e-06 -2.59550365797436e-06 -1.26701788641751e-07 9.18804358595622e-07 4.30399766182112e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 751 0 0 0 0 0 2254 +1070 1126 0.996680274242782 0.00481873836137202 0.0812724473357193 -0.0095134128986543 0.0027014266535483 0.995739863798285 -0.092167380005121 0.00798564167807325 -0.0813703461303203 0.0920809611351745 0.992421263056699 0.0231636546382766 3.45112357250337e-05 2.38114631849552e-05 -4.10513137318429e-06 5.96647543013356e-07 -4.73419955744342e-06 7.29378930107736e-06 2.38114631849552e-05 8.90351709573711e-05 8.32714823264063e-06 1.27782266909374e-05 -3.50614800864617e-05 -1.07168004415479e-05 -4.10513137318429e-06 8.32714823264063e-06 1.66907470396624e-05 1.65552659613153e-06 -5.94759040660884e-06 -1.38903624522561e-06 5.96647543013356e-07 1.27782266909374e-05 1.65552659613153e-06 4.18794998854506e-05 -5.83975654551543e-05 -3.4600738513465e-06 -4.73419955744342e-06 -3.50614800864617e-05 -5.94759040660884e-06 -5.83975654551543e-05 0.000196257446350389 9.21331828220496e-06 7.29378930107736e-06 -1.07168004415479e-05 -1.38903624522561e-06 -3.4600738513465e-06 9.21331828220496e-06 4.78047994187094e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2335 +1070 1117 0.996672412219866 0.00487903619775997 0.0813652120111174 -0.00385780236983465 0.00271121945875085 0.995670283928334 -0.0929157413526797 -0.00740889463113032 -0.0814662630103998 0.0928271550132424 0.992343875520612 0.0263253508458543 5.57270392468641e-05 4.94822351432196e-05 -1.69239310112287e-06 7.56295526645656e-06 -1.7601819661564e-05 9.44406522191653e-06 4.94822351432196e-05 7.90390780900662e-05 -6.19957039486415e-07 1.50067873873098e-05 -3.43391652502381e-05 4.29673111766612e-06 -1.69239310112287e-06 -6.19957039486415e-07 1.21834776835403e-05 4.71237334377807e-06 -1.48333881514861e-06 1.94158036412497e-06 7.56295526645656e-06 1.50067873873098e-05 4.71237334377807e-06 2.71786390974804e-05 -3.09417430399528e-05 4.09465273257896e-06 -1.7601819661564e-05 -3.43391652502381e-05 -1.48333881514861e-06 -3.09417430399528e-05 0.000124733383923711 -1.14950646165021e-05 9.44406522191653e-06 4.29673111766612e-06 1.94158036412497e-06 4.09465273257896e-06 -1.14950646165021e-05 3.74430509733016e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 769 0 0 0 0 0 2228 +1070 1118 0.997075446082667 0.0056714557222634 0.0762127903244678 -0.00813024774044984 0.00156256660922574 0.995521215377988 -0.0945254892498656 -0.00143661479790596 -0.0764075467780678 0.094368131921349 0.992600897880428 0.0273271229803015 3.68551530754901e-05 1.92463004034951e-05 -7.77568376560526e-06 4.57204055681211e-06 -1.00091272848102e-05 8.91285430030926e-06 1.92463004034951e-05 8.05074469741094e-05 6.24953357347124e-06 -3.48645132291761e-06 1.14480352132906e-06 -1.13042533796626e-05 -7.77568376560526e-06 6.24953357347124e-06 1.71772995099996e-05 -2.74953213793939e-06 -1.0261288051317e-06 -3.788889628234e-06 4.57204055681211e-06 -3.48645132291761e-06 -2.74953213793939e-06 3.22626024527717e-05 -4.02926513864277e-05 5.33542875405169e-06 -1.00091272848102e-05 1.14480352132906e-06 -1.0261288051317e-06 -4.02926513864277e-05 0.000165489681724728 -1.94560789280344e-05 8.91285430030926e-06 -1.13042533796626e-05 -3.788889628234e-06 5.33542875405169e-06 -1.94560789280344e-05 4.58724744948266e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 781 0 0 0 0 0 2241 +1071 1104 0.993640074437222 0.0187477182355591 0.111031191713647 -0.0226150702531056 -0.00855075933307278 0.995758045604051 -0.0916122215079883 -0.00037016355233013 -0.112277722577635 0.0900801735997491 0.989585405782148 0.0336947937189245 0.00027895684368954 0.000121323433805667 -1.64584229145005e-05 8.11658696354696e-05 -0.000245198101194256 0.000273374866616797 0.000121323433805667 0.00011098296362277 -4.60536922014957e-06 3.13718141820464e-05 -7.88824776521318e-05 0.000101348781564153 -1.64584229145005e-05 -4.60536922014957e-06 1.45294276627457e-05 -1.0582645159993e-05 1.72903638622176e-05 -1.87971837260856e-05 8.11658696354696e-05 3.13718141820464e-05 -1.0582645159993e-05 5.84904121548677e-05 -9.30893741155615e-05 9.51037795975491e-05 -0.000245198101194256 -7.88824776521318e-05 1.72903638622176e-05 -9.30893741155615e-05 0.00033395297210369 -0.000271168982968812 0.000273374866616797 0.000101348781564153 -1.87971837260856e-05 9.51037795975491e-05 -0.000271168982968812 0.000325430356549513 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 659 0 0 0 0 0 2367 +1071 1102 0.993846398558587 0.017665000158803 0.10934936598589 -0.0277880145005411 -0.00932134453525071 0.997037604419587 -0.0763487256560695 0.0168080000593381 -0.110374130158212 0.0748596229127565 0.991066893932583 0.0190767729107256 5.89690953214244e-05 3.78595915622187e-05 -7.20441527647356e-06 5.61404141168957e-07 3.81180743846536e-06 1.71702463072605e-05 3.78595915622187e-05 8.49321502614878e-05 -4.12893352990972e-06 5.28781278328597e-06 4.31022917769116e-06 -5.46131392639279e-06 -7.20441527647356e-06 -4.12893352990972e-06 1.24016887889913e-05 2.63391365580158e-07 4.0297700166503e-07 -1.37627041159999e-06 5.61404141168957e-07 5.28781278328597e-06 2.63391365580158e-07 2.19378747159107e-05 -7.2660296416866e-06 1.13290655671764e-06 3.81180743846536e-06 4.31022917769116e-06 4.0297700166503e-07 -7.2660296416866e-06 5.87578637318834e-05 -6.04313607723766e-07 1.71702463072605e-05 -5.46131392639279e-06 -1.37627041159999e-06 1.13290655671764e-06 -6.04313607723766e-07 5.79301560196044e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 651 0 0 0 0 0 2261 +1071 1103 0.994145444859765 0.0173217752818813 0.106652663190679 -0.0297234430860163 -0.00844694356900101 0.996504706778168 -0.0831084743771614 0.0130482845751905 -0.10771946717712 0.0817210222038442 0.990816931083152 0.0200813754158878 8.95067001626803e-05 6.40854998425868e-05 -4.2142874026429e-06 2.11938596886917e-05 -5.64748892155514e-05 5.52720227023998e-05 6.40854998425868e-05 8.24069610457612e-05 -7.47773202944085e-06 2.12069851260742e-05 -2.36455627221781e-05 3.78127962983204e-05 -4.2142874026429e-06 -7.47773202944085e-06 1.14197006495944e-05 -3.34466531428651e-06 2.56005894886901e-06 -3.95295492619798e-06 2.11938596886917e-05 2.12069851260742e-05 -3.34466531428651e-06 2.94479242952835e-05 -1.86078520514677e-05 1.98720810008361e-05 -5.64748892155514e-05 -2.36455627221781e-05 2.56005894886901e-06 -1.86078520514677e-05 0.000119643674659377 -4.74130618359577e-05 5.52720227023998e-05 3.78127962983204e-05 -3.95295492619798e-06 1.98720810008361e-05 -4.74130618359577e-05 7.63037705784718e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 590 0 0 0 0 0 2394 +1071 1105 0.993907282502701 0.0181429917079853 0.108715894146075 -0.0234067180399651 -0.0085466682067944 0.99607551937506 -0.088093780508426 -0.00225248058050283 -0.109887525455165 0.0866278913144476 0.990161774759939 0.0244561018976238 6.24071146042313e-05 3.7331398207703e-05 -4.81242265585673e-06 7.98087003568114e-06 -2.12839766360971e-05 3.86810309373972e-05 3.7331398207703e-05 8.02453113587584e-05 -3.71702425434397e-06 1.0731684862425e-05 -3.53554579031794e-06 1.42879931045547e-05 -4.81242265585673e-06 -3.71702425434397e-06 1.31760258568636e-05 -4.69623512239706e-06 1.54269761320229e-06 -5.06074265128065e-06 7.98087003568114e-06 1.0731684862425e-05 -4.69623512239706e-06 2.99263430403687e-05 -1.5249584336253e-05 1.32965271913691e-05 -2.12839766360971e-05 -3.53554579031794e-06 1.54269761320229e-06 -1.5249584336253e-05 8.483538872346e-05 -2.38311506078527e-05 3.86810309373972e-05 1.42879931045547e-05 -5.06074265128065e-06 1.32965271913691e-05 -2.38311506078527e-05 6.7343865152889e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 726 0 0 0 0 0 2291 +1071 1109 0.994306571397237 0.0191992334648081 0.10481331742978 -0.0212635071368746 -0.0106135868645316 0.996586909566425 -0.0818650319410682 0.000401738400629974 -0.10602732595959 0.0802864939775481 0.991116685882471 0.0245654486540895 4.76989520792335e-05 2.17340974695382e-05 -1.28177553473351e-05 8.10497520997215e-06 -9.23878854670343e-07 1.69548401189337e-05 2.17340974695382e-05 6.58758529602217e-05 -5.29217986003699e-06 3.72997689611735e-06 9.51490948555428e-06 -8.13971292623313e-06 -1.28177553473351e-05 -5.29217986003699e-06 1.44098851561748e-05 -3.01164396462174e-06 1.01976775544222e-06 -6.17981196472452e-06 8.10497520997215e-06 3.72997689611735e-06 -3.01164396462174e-06 2.21147274954845e-05 -4.18754155545713e-06 8.93382864066875e-06 -9.23878854670343e-07 9.51490948555428e-06 1.01976775544222e-06 -4.18754155545713e-06 5.10623337419462e-05 -7.269954597004e-06 1.69548401189337e-05 -8.13971292623313e-06 -6.17981196472452e-06 8.93382864066875e-06 -7.269954597004e-06 5.23500208750194e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 797 0 0 0 0 0 2231 +1071 1107 0.9940728234135 0.0182640796560199 0.107171102191922 -0.0262882417067522 -0.010093513259371 0.997034476996155 -0.0762913669499207 0.0157233196542142 -0.108246675426064 0.0747574416049874 0.991309226318348 0.0188831814987853 8.32673226169754e-05 4.21742960078666e-05 -1.26740872448461e-05 1.46565442139298e-05 -2.90496881573238e-05 4.82633935938182e-05 4.21742960078666e-05 6.77502070516066e-05 -4.42724075487733e-06 -2.374517418436e-07 6.27901191625874e-06 9.92444948333782e-06 -1.26740872448461e-05 -4.42724075487733e-06 1.53350220066815e-05 -4.45337707793191e-06 1.27545836249071e-06 -3.68773546533914e-06 1.46565442139298e-05 -2.374517418436e-07 -4.45337707793191e-06 2.60218354893662e-05 -1.39695616799918e-05 1.27748583458005e-05 -2.90496881573238e-05 6.27901191625874e-06 1.27545836249071e-06 -1.39695616799918e-05 9.16636208548271e-05 -3.07429281702996e-05 4.82633935938182e-05 9.92444948333782e-06 -3.68773546533914e-06 1.27748583458005e-05 -3.07429281702996e-05 7.57305783376403e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 682 0 0 0 0 0 2225 +1071 1073 0.999995118832306 0.00156321783142664 -0.00270530249215053 0.00992250293044894 -0.00157233816590057 0.999993077162652 -0.00337244413773573 0.0238009453804478 0.0027000118989698 0.00337668132662907 0.999990653935807 0.0184511239227524 0.000106736467379782 2.45655215574227e-05 -8.67444824114256e-06 2.44815566153001e-05 -3.62553108790876e-05 1.24753865839669e-05 2.45655215574227e-05 5.72720358813638e-05 -4.36694885067606e-06 3.61517417354695e-06 2.55199038867955e-05 1.28116143636659e-05 -8.67444824114256e-06 -4.36694885067606e-06 1.98740915894583e-05 -5.35151533211098e-06 -3.44578515633587e-06 1.06164405222644e-07 2.44815566153001e-05 3.61517417354695e-06 -5.35151533211098e-06 2.87267380630946e-05 -2.39950763539304e-05 3.6166969618858e-06 -3.62553108790876e-05 2.55199038867955e-05 -3.44578515633587e-06 -2.39950763539304e-05 0.000122782495796449 8.7241656549795e-07 1.24753865839669e-05 1.28116143636659e-05 1.06164405222644e-07 3.6166969618858e-06 8.7241656549795e-07 5.4520609229757e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1065 0 0 0 0 0 2131 +1071 1106 0.993489328735528 0.0181685692538166 0.112467136443941 -0.0239796274803589 -0.00850161512902471 0.996272355206897 -0.0858435599838461 0.00430527163431087 -0.113607553572942 0.0843285084759094 0.989940415595504 0.0262358178487002 0.000104766597581925 5.09876097181641e-05 -1.64094618876343e-05 1.94240726081378e-05 -3.48226294523688e-05 7.04297638893484e-05 5.09876097181641e-05 8.27977498206053e-05 -5.07057993219104e-06 9.13576385232729e-06 -9.65750121941179e-06 1.79917996993097e-05 -1.64094618876343e-05 -5.07057993219104e-06 1.65043643052305e-05 -6.75332741713305e-06 2.47184277337036e-06 -8.58390989246503e-06 1.94240726081378e-05 9.13576385232729e-06 -6.75332741713305e-06 2.42524690094365e-05 -7.57482842091052e-06 1.8132126537771e-05 -3.48226294523688e-05 -9.65750121941179e-06 2.47184277337036e-06 -7.57482842091052e-06 6.87680344426176e-05 -3.82262623247822e-05 7.04297638893484e-05 1.79917996993097e-05 -8.58390989246503e-06 1.8132126537771e-05 -3.82262623247822e-05 9.34448900350092e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 771 0 0 0 0 0 2338 +1071 1101 0.993307318752115 0.0183031072008906 0.114041951843504 -0.0251323429515792 -0.00931485191934239 0.996842557520882 -0.0788552411000494 0.0127576472988488 -0.115125166871558 0.0772652042126267 0.990341498762309 0.0199730317231383 8.27425317558276e-05 5.28775902978575e-05 -1.80683013795347e-05 1.33710798781497e-05 2.88164606679575e-06 3.20493199323241e-05 5.28775902978575e-05 8.43753751477905e-05 -7.72159455559009e-06 4.01413016714653e-06 1.81958563104955e-05 2.35868439191065e-06 -1.80683013795347e-05 -7.72159455559009e-06 1.73864182289957e-05 -7.95666421660447e-06 -3.18705205435911e-06 -6.27281329965796e-06 1.33710798781497e-05 4.01413016714653e-06 -7.95666421660447e-06 2.59554488220327e-05 -4.85457132530149e-06 1.18256645174363e-05 2.88164606679575e-06 1.81958563104955e-05 -3.18705205435911e-06 -4.85457132530149e-06 6.99133612333006e-05 -7.73168384266572e-06 3.20493199323241e-05 2.35868439191065e-06 -6.27281329965796e-06 1.18256645174363e-05 -7.73168384266572e-06 6.05287310177147e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 729 0 0 0 0 0 2337 +1071 1108 0.993554525620475 0.0181104160015729 0.111899139636201 -0.0257519501482509 -0.0096990143303556 0.99711666047856 -0.0752615075394078 0.0148229329131383 -0.112939513634917 0.0736911000619121 0.990865423774376 0.0194622858817579 5.81254854010627e-05 4.12363687919193e-05 -9.67876609682034e-06 1.04633897783189e-05 -1.38292862299062e-05 1.01102900993631e-05 4.12363687919193e-05 6.64419268498499e-05 -4.3890657848314e-06 6.56652093700545e-06 -2.16308583484716e-05 6.32618175230292e-06 -9.67876609682034e-06 -4.3890657848314e-06 1.35481348182012e-05 -4.22158209611679e-06 -1.62499264821806e-06 -1.75662624239454e-06 1.04633897783189e-05 6.56652093700545e-06 -4.22158209611679e-06 2.47895377448235e-05 -1.36679041082104e-05 3.82143895788222e-06 -1.38292862299062e-05 -2.16308583484716e-05 -1.62499264821806e-06 -1.36679041082104e-05 7.69545457584481e-05 -6.61686500202929e-06 1.01102900993631e-05 6.32618175230292e-06 -1.75662624239454e-06 3.82143895788222e-06 -6.61686500202929e-06 3.93559588785698e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 701 0 0 0 0 0 2247 +1071 1110 0.993393362698545 0.0187525352628618 0.113216471273807 -0.0217247758577643 -0.00959571736756691 0.996676973981745 -0.0808883906552352 0.0080459388293236 -0.114357112392188 0.0792675971365809 0.990272234736243 0.0212125997720878 4.12068389762833e-05 1.73951245075335e-05 -8.17827725132311e-06 3.14038823213532e-06 -7.39228366140816e-06 8.14597287599758e-06 1.73951245075335e-05 5.78743851332417e-05 -1.32840378962596e-06 1.87558872489244e-06 -6.75387317372495e-06 -1.28637875006022e-05 -8.17827725132311e-06 -1.32840378962596e-06 1.35488521839189e-05 -1.73828760434854e-06 1.90706025008088e-07 -2.3553098052644e-06 3.14038823213532e-06 1.87558872489244e-06 -1.73828760434854e-06 2.02255172534608e-05 -2.40041476070303e-06 1.557623449246e-06 -7.39228366140816e-06 -6.75387317372495e-06 1.90706025008088e-07 -2.40041476070303e-06 5.05920406320798e-05 -7.26956807201053e-06 8.14597287599758e-06 -1.28637875006022e-05 -2.3553098052644e-06 1.557623449246e-06 -7.26956807201053e-06 3.79519636123994e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 745 0 0 0 0 0 2259 +1071 1100 0.993290820038473 0.0190012498926666 0.114071465887899 -0.0247670827135062 -0.00982250406962232 0.996706693370381 -0.0804940109851934 0.0116861009083125 -0.115225280390633 0.0788334947417569 0.990206248650099 0.0195835258818401 8.16640730659905e-05 2.56885114382971e-05 -1.70327563712961e-05 1.81725690597339e-05 -2.32339207841971e-05 5.3085888925849e-05 2.56885114382971e-05 7.9040310474647e-05 -6.98215606545631e-07 9.83593593351029e-07 7.82984124202407e-06 -7.45695187803614e-06 -1.70327563712961e-05 -6.98215606545631e-07 1.93752922117924e-05 -8.8964183446673e-06 4.47145505612688e-06 -1.0976659710242e-05 1.81725690597339e-05 9.83593593351029e-07 -8.8964183446673e-06 2.95988078127882e-05 -1.24789414997971e-05 1.73359894385974e-05 -2.32339207841971e-05 7.82984124202407e-06 4.47145505612688e-06 -1.24789414997971e-05 8.43463370842749e-05 -2.73270637408255e-05 5.3085888925849e-05 -7.45695187803614e-06 -1.0976659710242e-05 1.73359894385974e-05 -2.73270637408255e-05 8.24293333439699e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 714 0 0 0 0 0 2329 +1071 1111 0.993603767938467 0.0176168607879066 0.111540120828606 -0.0239890190026238 -0.00901178189417879 0.996975906223872 -0.077186982038299 0.00349335278860021 -0.112562605360627 0.075688100947695 0.990757776274988 0.016713679649045 9.26355323492609e-05 4.45536898515156e-05 -1.21808991498953e-05 1.92405119333839e-05 -3.02158319541924e-05 6.1969913362642e-05 4.45536898515156e-05 7.59508927008293e-05 -4.93960232463392e-06 6.21316662701405e-06 2.27095907028313e-06 1.41551501901631e-05 -1.21808991498953e-05 -4.93960232463392e-06 1.44759232279495e-05 -3.97031564234618e-06 1.4401171656252e-06 -5.59495829732978e-06 1.92405119333839e-05 6.21316662701405e-06 -3.97031564234618e-06 2.58826051129247e-05 -1.96521370706673e-05 2.06702607689667e-05 -3.02158319541924e-05 2.27095907028313e-06 1.4401171656252e-06 -1.96521370706673e-05 0.000119462144950065 -4.13862783525212e-05 6.1969913362642e-05 1.41551501901631e-05 -5.59495829732978e-06 2.06702607689667e-05 -4.13862783525212e-05 8.84429196507317e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 708 0 0 0 0 0 2378 +1071 1140 0.993537448907558 0.0182407881918075 0.11202951068537 -0.0254194171468732 -0.0093843833724687 0.996824221068623 -0.0790784777272089 0.0159620699929687 -0.113116183488396 0.0775161011472827 0.99055337215919 0.0206030457779536 0.000149054681124228 9.67990605269672e-05 -1.36662393825795e-05 2.67683450818721e-05 -5.15553336935178e-05 0.000101204596684405 9.67990605269672e-05 0.000114464361067177 -3.72474386791748e-06 1.92160164952801e-05 -3.75217504907749e-05 5.95772664596605e-05 -1.36662393825795e-05 -3.72474386791748e-06 1.58195221460715e-05 -5.15912593979459e-06 -6.92168203248218e-07 -7.03393536704246e-06 2.67683450818721e-05 1.92160164952801e-05 -5.15912593979459e-06 3.71977438709988e-05 -4.40042757982068e-05 1.64863066885726e-05 -5.15553336935178e-05 -3.75217504907749e-05 -6.92168203248218e-07 -4.40042757982068e-05 0.000151424032973636 -3.09564028521333e-05 0.000101204596684405 5.95772664596605e-05 -7.03393536704246e-06 1.64863066885726e-05 -3.09564028521333e-05 0.000109196060504274 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 834 0 0 0 0 0 2315 +1071 1112 0.993993391738415 0.018970135070647 0.10778344564804 -0.0235293865323597 -0.0102462871464697 0.996667674434301 -0.0809231755273708 0.00474001490315105 -0.108959399686648 0.0793327215789487 0.99087545559813 0.0210166629066956 3.4369593206212e-05 2.3549569185391e-05 -6.25166132847424e-06 1.32568559021267e-06 1.96854039637878e-07 9.78392633745879e-06 2.3549569185391e-05 6.42247528839687e-05 -1.66136564785808e-06 1.16264150300975e-06 -4.23076865307366e-06 -1.40996112400509e-06 -6.25166132847424e-06 -1.66136564785808e-06 1.26368029452619e-05 -5.11234582411902e-07 6.83889236906516e-07 -4.69329697252242e-07 1.32568559021267e-06 1.16264150300975e-06 -5.11234582411902e-07 2.27530776911733e-05 -1.54469460580294e-05 9.29316752749036e-07 1.96854039637878e-07 -4.23076865307366e-06 6.83889236906516e-07 -1.54469460580294e-05 7.25421674587236e-05 2.997246436603e-06 9.78392633745879e-06 -1.40996112400509e-06 -4.69329697252242e-07 9.29316752749036e-07 2.997246436603e-06 4.19303582920713e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 750 0 0 0 0 0 2381 +1071 1137 0.994039053804315 0.0192230754196793 0.107316507971659 -0.0225805813825792 -0.0102776865651389 0.996472005532268 -0.0832941255393677 0.00594803422938296 -0.108539065182498 0.081694648306413 0.990729658265766 0.0247423167284439 0.000116992827634151 5.40994337778552e-05 -1.60184385090468e-05 2.64914024154082e-05 -5.68489800390552e-05 9.19318837812338e-05 5.40994337778552e-05 9.49681757527931e-05 1.54296940154847e-06 1.10733050777777e-06 1.01586935571545e-05 2.51517741229268e-05 -1.60184385090468e-05 1.54296940154847e-06 1.84457133564814e-05 -9.17440158023912e-06 6.06646811054089e-06 -1.33240796153621e-05 2.64914024154082e-05 1.10733050777777e-06 -9.17440158023912e-06 4.42270097884235e-05 -6.60661952506531e-05 2.92406809276104e-05 -5.68489800390552e-05 1.01586935571545e-05 6.06646811054089e-06 -6.60661952506531e-05 0.000233313807930606 -6.39379543593195e-05 9.19318837812338e-05 2.51517741229268e-05 -1.33240796153621e-05 2.92406809276104e-05 -6.39379543593195e-05 0.000115812324003828 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 887 0 0 0 0 0 2304 +1071 1135 0.994391879294598 0.0193541074057055 0.103972154539022 -0.0227759582959817 -0.0106598347449233 0.996447833843767 -0.0835349169585694 0.00230253047253559 -0.105219571925421 0.0819581170756904 0.991065945701515 0.0231184756936983 6.59005001341994e-05 3.91651489647621e-05 -7.33892592615341e-06 1.23930846127651e-05 -1.04532661787718e-05 2.84190640062089e-05 3.91651489647621e-05 8.18135546844149e-05 2.38287757324365e-06 2.21573645043682e-06 4.52772125871342e-07 7.73622841375832e-06 -7.33892592615341e-06 2.38287757324365e-06 1.58275641251604e-05 -3.94507215662055e-06 -4.16545309390729e-06 -5.83248865990059e-06 1.23930846127651e-05 2.21573645043682e-06 -3.94507215662055e-06 2.97427942184097e-05 -3.10451454261884e-05 4.57197603960874e-06 -1.04532661787718e-05 4.52772125871342e-07 -4.16545309390729e-06 -3.10451454261884e-05 0.000138485611578993 5.39031108691243e-06 2.84190640062089e-05 7.73622841375832e-06 -5.83248865990059e-06 4.57197603960874e-06 5.39031108691243e-06 6.5400247362555e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 876 0 0 0 0 0 2370 +1071 1113 0.993756391062834 0.0181744778494387 0.110081440654965 -0.0228545226326819 -0.00941922375424422 0.99678731900041 -0.0795381600481293 0.00223347609424429 -0.111173348630145 0.0780046731604884 0.990734958260526 0.0207183694982139 3.63846947105907e-05 2.63292463727467e-05 -5.99321037814853e-06 1.62904477881621e-06 4.0611245187717e-06 4.85014159137627e-06 2.63292463727467e-05 6.25278987389123e-05 -2.77126928041566e-07 2.56034937566612e-06 -9.55782871024109e-06 -2.80574567089039e-06 -5.99321037814853e-06 -2.77126928041566e-07 1.22693356362318e-05 -5.40585500106048e-08 -5.35138929016016e-07 1.18019367251158e-06 1.62904477881621e-06 2.56034937566612e-06 -5.40585500106048e-08 2.06293775030513e-05 -7.98701882257649e-06 -1.98915190935655e-06 4.0611245187717e-06 -9.55782871024109e-06 -5.35138929016016e-07 -7.98701882257649e-06 5.96332292280975e-05 4.79941374529192e-06 4.85014159137627e-06 -2.80574567089039e-06 1.18019367251158e-06 -1.98915190935655e-06 4.79941374529192e-06 3.37879731217313e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 745 0 0 0 0 0 2391 +1071 1115 0.993802052298333 0.0190920856042029 0.109512433608718 -0.0190276623517488 -0.0093799660069404 0.996029894237687 -0.0885238161319917 -0.0110254834413507 -0.110767761940606 0.0869479272446665 0.990035636157874 0.0247036515074697 0.000135693299443887 6.02050772304469e-05 -1.55402246871844e-05 3.35455759600788e-05 -7.88067329522936e-05 8.55780835891178e-05 6.02050772304469e-05 9.30442192968962e-05 -2.88840819984199e-06 1.62060432553628e-05 -2.62318960874622e-05 2.09045523405789e-05 -1.55402246871844e-05 -2.88840819984199e-06 1.55899834990994e-05 -4.7751854713279e-06 3.27714736865957e-06 -8.4650358526497e-06 3.35455759600788e-05 1.62060432553628e-05 -4.7751854713279e-06 4.0582691913095e-05 -5.83899046249176e-05 2.38877532152771e-05 -7.88067329522936e-05 -2.62318960874622e-05 3.27714736865957e-06 -5.83899046249176e-05 0.000217009952672882 -6.59778880073679e-05 8.55780835891178e-05 2.09045523405789e-05 -8.4650358526497e-06 2.38877532152771e-05 -6.59778880073679e-05 0.000104292034325398 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 801 0 0 0 0 0 2324 +1071 1114 0.993592647277348 0.0186886113952849 0.111464734694467 -0.0183911755027512 -0.0091471104241527 0.996295683373509 -0.0855057989975037 -0.00833065402568256 -0.112649818673979 0.0839383529468453 0.990083012306186 0.0254427444401243 8.92581155981254e-05 4.80030676475805e-05 -1.26676845879243e-05 7.36553309700213e-06 1.2780631109444e-06 5.90621355465204e-05 4.80030676475805e-05 7.47858281261996e-05 -4.14902196369963e-06 3.81886617630871e-06 1.22552480990752e-05 1.41831570261812e-05 -1.26676845879243e-05 -4.14902196369963e-06 1.58199974091647e-05 -4.3457286944418e-06 -3.02166319474811e-06 -6.37776633801815e-06 7.36553309700213e-06 3.81886617630871e-06 -4.3457286944418e-06 2.83131539065761e-05 -2.35381700230902e-05 5.84801982224276e-06 1.2780631109444e-06 1.22552480990752e-05 -3.02166319474811e-06 -2.35381700230902e-05 0.000121930192243958 -1.81220547209631e-06 5.90621355465204e-05 1.41831570261812e-05 -6.37776633801815e-06 5.84801982224276e-06 -1.81220547209631e-06 8.11146715618717e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 828 0 0 0 0 0 2291 +1071 1116 0.993562363761601 0.0180820884347106 0.111834106578891 -0.0216940707457083 -0.00900565715634059 0.996662150736154 -0.0811384953592721 -0.00232651715184087 -0.11292797463712 0.079609015618983 0.990408843446248 0.0163109622160854 3.03867259633961e-05 2.89736965771309e-05 1.35052121065671e-06 1.93996793519214e-07 -4.41508264720572e-06 4.14069262011319e-06 2.89736965771309e-05 6.35715980166434e-05 1.16659252563013e-06 2.51077903231884e-06 -1.53591144104388e-05 6.29815174769662e-06 1.35052121065671e-06 1.16659252563013e-06 1.06297205652835e-05 1.58674746590336e-06 8.29922177051676e-07 2.98608931689944e-06 1.93996793519214e-07 2.51077903231884e-06 1.58674746590336e-06 1.89282504584959e-05 -9.25680942303499e-06 -1.33976837285466e-06 -4.41508264720572e-06 -1.53591144104388e-05 8.29922177051676e-07 -9.25680942303499e-06 6.43862578099184e-05 -3.01870793326226e-06 4.14069262011319e-06 6.29815174769662e-06 2.98608931689944e-06 -1.33976837285466e-06 -3.01870793326226e-06 4.0053806927979e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 759 0 0 0 0 0 2360 +1071 1129 0.993769614250228 0.0187911871966254 0.109858295438691 -0.0224072947580301 -0.00976585618156089 0.996574418546309 -0.0821222037705256 0.00555978303722985 -0.111025140603354 0.0805376904488082 0.990548887522053 0.0190737139157172 5.46374403991556e-05 3.04877977449593e-05 -8.47360151401172e-06 1.19060694956941e-05 -2.66026038353438e-05 2.57216390497963e-05 3.04877977449593e-05 5.71256598821967e-05 -4.14993241947396e-06 9.21049298026036e-06 -9.3468305344325e-06 6.65680299017409e-06 -8.47360151401172e-06 -4.14993241947396e-06 1.19767034841614e-05 -4.66758422517748e-07 2.07396387064746e-07 -4.06090157226415e-06 1.19060694956941e-05 9.21049298026036e-06 -4.66758422517748e-07 3.95877385610955e-05 -6.50878653231984e-05 5.21174648634419e-06 -2.66026038353438e-05 -9.3468305344325e-06 2.07396387064746e-07 -6.50878653231984e-05 0.000224160046340859 -1.24311362593307e-05 2.57216390497963e-05 6.65680299017409e-06 -4.06090157226415e-06 5.21174648634419e-06 -1.24311362593307e-05 5.28956980752769e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 885 0 0 0 0 0 2258 +1071 1117 0.993878437014331 0.0183251312901458 0.108948804496188 -0.0211432070170832 -0.00964218714170259 0.996772548949933 -0.0796963856581796 -0.000821024075755066 -0.110057624293249 0.0781580144518259 0.990847437354447 0.0178262844469748 3.78679169262498e-05 3.365260714121e-05 -2.2288427920105e-06 4.07864631778098e-06 -1.09280341761867e-05 1.25732036813264e-05 3.365260714121e-05 6.0542825128596e-05 -5.09248055818497e-07 6.89687420418406e-06 -2.05698631753226e-05 8.25325071195366e-06 -2.2288427920105e-06 -5.09248055818497e-07 1.11596900155758e-05 1.00141654029309e-06 -4.18771790088664e-07 1.12001535508606e-06 4.07864631778098e-06 6.89687420418406e-06 1.00141654029309e-06 2.56172460426357e-05 -2.81505043329469e-05 2.99171006158977e-06 -1.09280341761867e-05 -2.05698631753226e-05 -4.18771790088664e-07 -2.81505043329469e-05 0.000108082198152924 -4.53383858568978e-06 1.25732036813264e-05 8.25325071195366e-06 1.12001535508606e-06 2.99171006158977e-06 -4.53383858568978e-06 3.99026189415487e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 778 0 0 0 0 0 2316 +1072 1106 0.988011989162189 0.0265163389904362 0.152082849257631 -0.0347393725474188 -0.0139884095772648 0.996462882591248 -0.0828616196766554 0.00850355696068643 -0.153742101160592 0.0797408764968399 0.984888196165556 0.00867090588695815 4.97536742262209e-05 1.86551217346179e-05 -8.30942746395258e-06 1.61840294644758e-06 3.75756709342874e-06 1.05731466873611e-05 1.86551217346179e-05 0.000110252032437863 7.55505808039961e-06 5.57578782050384e-06 -4.98847960924534e-08 -2.57999453556163e-05 -8.30942746395258e-06 7.55505808039961e-06 1.55650754191463e-05 -8.0941550641355e-07 -6.80327502058585e-07 -4.6582699870845e-06 1.61840294644758e-06 5.57578782050384e-06 -8.0941550641355e-07 2.12095090868577e-05 -3.97503014695585e-06 -6.64132573547323e-08 3.75756709342874e-06 -4.98847960924534e-08 -6.80327502058585e-07 -3.97503014695585e-06 5.67981055609247e-05 -2.14990305998535e-06 1.05731466873611e-05 -2.57999453556163e-05 -4.6582699870845e-06 -6.64132573547323e-08 -2.14990305998535e-06 4.40547453319215e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 792 0 0 0 0 0 2324 +1072 1105 0.987502400827227 0.026126187993339 0.15542339161593 -0.0334817745635165 -0.0134328704479807 0.996528141462135 -0.0821658156750812 0.00620330304016158 -0.157030463133717 0.0790511579609076 0.984424881884367 0.00462076281904455 5.83161126211593e-05 4.9215768632022e-05 1.90103728509666e-06 6.4144694024286e-07 -6.73884908458048e-06 1.73634324297562e-05 4.9215768632022e-05 7.70447185587527e-05 1.68724863731754e-06 2.37996607665204e-06 -1.08528368398924e-05 1.07974791251337e-05 1.90103728509666e-06 1.68724863731754e-06 1.25707001336111e-05 -1.90743116016002e-06 1.30643389213096e-06 8.49225309476045e-08 6.4144694024286e-07 2.37996607665204e-06 -1.90743116016002e-06 2.41357464560003e-05 -6.8281001947296e-06 3.5865111484607e-06 -6.73884908458048e-06 -1.08528368398924e-05 1.30643389213096e-06 -6.8281001947296e-06 6.08438932856995e-05 -3.67318807656596e-06 1.73634324297562e-05 1.07974791251337e-05 8.49225309476045e-08 3.5865111484607e-06 -3.67318807656596e-06 4.34499529486642e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 747 0 0 0 0 0 2255 +1072 1107 0.988549586861243 0.0272629629776417 0.148413089605149 -0.0359489308273742 -0.0148511443747435 0.996346235417094 -0.0841048314958496 0.0102808118813012 -0.150163770022022 0.0809376922074288 0.985342545591587 0.00898876728516157 0.000113774221625913 6.91843325726096e-05 -2.13855835453899e-05 2.5241171334969e-05 -3.55365967135321e-05 5.49012403549175e-05 6.91843325726096e-05 0.000100446221992928 -9.84195275202378e-06 1.21085985065752e-05 -1.76208149221929e-05 2.57090761423185e-05 -2.13855835453899e-05 -9.84195275202378e-06 1.80917741412002e-05 -7.33857343790374e-06 2.42130701970364e-06 -1.06351666899042e-05 2.5241171334969e-05 1.21085985065752e-05 -7.33857343790374e-06 3.03405689637617e-05 -1.71584869438378e-05 1.99048653584459e-05 -3.55365967135321e-05 -1.76208149221929e-05 2.42130701970364e-06 -1.71584869438378e-05 0.000102947093867687 -3.20782716936696e-05 5.49012403549175e-05 2.57090761423185e-05 -1.06351666899042e-05 1.99048653584459e-05 -3.20782716936696e-05 7.16866924367726e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 685 0 0 0 0 0 2176 +1072 1108 0.988327407259574 0.0281284988579519 0.149725494193765 -0.0335588313380676 -0.0149228225214718 0.9959552503792 -0.0886027573504175 0.00214238363317117 -0.151612154616844 0.0853342064713941 0.984749626950087 0.0131242663506825 6.86384363674128e-05 1.28715766209739e-05 -2.09603461760467e-05 1.3003066686485e-05 -4.3428975106263e-06 3.11934090571802e-05 1.28715766209739e-05 9.53132820383662e-05 1.19164496417757e-07 1.05962432523752e-05 6.02097145504494e-06 -1.72371111302174e-05 -2.09603461760467e-05 1.19164496417757e-07 1.9519394259926e-05 -6.6040232870439e-06 -2.32233892132891e-06 -1.19164302177032e-05 1.3003066686485e-05 1.05962432523752e-05 -6.6040232870439e-06 2.80660609812843e-05 -9.24251524131214e-06 7.87747765002185e-06 -4.3428975106263e-06 6.02097145504494e-06 -2.32233892132891e-06 -9.24251524131214e-06 9.81432488591828e-05 -7.15152275804511e-06 3.11934090571802e-05 -1.72371111302174e-05 -1.19164302177032e-05 7.87747765002185e-06 -7.15152275804511e-06 5.78526926710086e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 701 0 0 0 0 0 2247 +1072 1104 0.987947081937353 0.0265352649501874 0.152500632803581 -0.0361712192773365 -0.013614261992654 0.996274671643284 -0.0851553316737278 0.00721312085264191 -0.154192137159664 0.0820527778694333 0.984627912707153 0.00870716945956801 8.12112247042892e-05 8.21770536782697e-05 6.27654369909454e-06 3.14448227481311e-06 -2.72872308694039e-05 4.65676836612631e-05 8.21770536782697e-05 0.000136096178925916 6.05745378797113e-06 2.02198920845947e-05 -4.65700745503865e-05 4.35912942482956e-05 6.27654369909454e-06 6.05745378797113e-06 1.38574903610942e-05 -2.8010069089715e-06 9.24080182609893e-07 2.36867189932474e-06 3.14448227481311e-06 2.02198920845947e-05 -2.8010069089715e-06 3.21983196527202e-05 -1.42631766538502e-05 6.27044497026121e-06 -2.72872308694039e-05 -4.65700745503865e-05 9.24080182609893e-07 -1.42631766538502e-05 8.11606202489536e-05 -1.91529862676466e-05 4.65676836612631e-05 4.35912942482956e-05 2.36867189932474e-06 6.27044497026121e-06 -1.91529862676466e-05 6.9991975854212e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 688 0 0 0 0 0 2308 +1072 1109 0.98763353477307 0.0270894170057903 0.154422033654324 -0.0312242127734923 -0.0141678697058761 0.996350578314856 -0.0841712335637849 0.00354339036022416 -0.156138632181943 0.0809425016782797 0.98441304286484 0.00905451609049701 5.17034987631774e-05 2.80322011019607e-05 -1.00357673142165e-05 7.41508179506901e-06 -3.38179989266583e-06 2.95930967197629e-06 2.80322011019607e-05 0.000144081395636948 5.13724446304618e-06 1.82432746271846e-05 -2.89219425632962e-05 -3.51134093708123e-05 -1.00357673142165e-05 5.13724446304618e-06 1.59887928646687e-05 -2.56394970320353e-06 -3.65068984785055e-06 -2.93105463243932e-06 7.41508179506901e-06 1.82432746271846e-05 -2.56394970320353e-06 2.68184866084338e-05 -1.20177753076505e-05 -1.40064991577736e-06 -3.38179989266583e-06 -2.89219425632962e-05 -3.65068984785055e-06 -1.20177753076505e-05 7.58130245268854e-05 -1.21814358191561e-06 2.95930967197629e-06 -3.51134093708123e-05 -2.93105463243932e-06 -1.40064991577736e-06 -1.21814358191561e-06 4.59903582673329e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 825 0 0 0 0 0 2221 +1072 1111 0.987698735136621 0.0274579084952651 0.153939182375976 -0.0301658739193022 -0.0136102057116827 0.995821787860294 -0.0902980017675497 -0.0100648794282866 -0.155775386085236 0.087092078191948 0.983945628074135 0.0112934341606774 4.76381446065961e-05 1.89075577375452e-05 -1.50553860061943e-05 1.16743615067268e-05 -5.40872756510602e-06 1.7193070184872e-05 1.89075577375452e-05 0.000104471266830115 -2.43157768956911e-07 5.70951711126816e-06 5.45067610360126e-06 -2.15847855693519e-05 -1.50553860061943e-05 -2.43157768956911e-07 1.83782394075261e-05 -6.47924880407847e-06 -3.0842851463674e-06 -8.93275881700129e-06 1.16743615067268e-05 5.70951711126816e-06 -6.47924880407847e-06 2.79507784525403e-05 -1.0944140726019e-05 5.09539013306706e-06 -5.40872756510602e-06 5.45067610360126e-06 -3.0842851463674e-06 -1.0944140726019e-05 8.55869738622538e-05 -1.49566602531421e-07 1.7193070184872e-05 -2.15847855693519e-05 -8.93275881700129e-06 5.09539013306706e-06 -1.49566602531421e-07 4.75404163685129e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 707 0 0 0 0 0 2366 +1072 1103 0.988131450926725 0.0259991386491555 0.151394453263479 -0.0393851664393549 -0.0137319670047928 0.996577379243364 -0.081516625682174 0.0153461135160349 -0.152995649518622 0.0784701979730545 0.985106471026581 0.00390284621549308 0.000144405961278368 8.10060256462682e-05 -9.69743174801048e-06 3.33466373616108e-05 -8.94972037159793e-05 7.47731673413398e-05 8.10060256462682e-05 0.000110214277973157 -8.37272319207963e-06 1.76385303350831e-05 -1.89110743534645e-05 3.26021759766563e-05 -9.69743174801048e-06 -8.37272319207963e-06 1.19806423347738e-05 -1.5356091892469e-06 1.26614820930056e-05 -7.38026694308817e-06 3.33466373616108e-05 1.76385303350831e-05 -1.5356091892469e-06 3.3913715127031e-05 -4.12756091181483e-05 2.87507028229174e-05 -8.94972037159793e-05 -1.89110743534645e-05 1.26614820930056e-05 -4.12756091181483e-05 0.000178458179091134 -7.85522545889044e-05 7.47731673413398e-05 3.26021759766563e-05 -7.38026694308817e-06 2.87507028229174e-05 -7.85522545889044e-05 9.54889632098834e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 599 0 0 0 0 0 2395 +1072 1102 0.988454709394459 0.0273113020812697 0.149034828998265 -0.0371938507941664 -0.0142965615854383 0.996043515923685 -0.0877093080192649 0.00790609378167144 -0.15084063047717 0.0845659929582226 0.984934361788764 0.01023990234569 5.47101486785339e-05 2.01159003767071e-05 -7.36364722923899e-06 2.67978949507606e-06 -2.46684557596811e-06 1.75779405196615e-05 2.01159003767071e-05 0.000117753568830975 6.95214290562018e-06 3.8400072345102e-06 -2.22628184102751e-06 -1.25119681364906e-05 -7.36364722923899e-06 6.95214290562018e-06 1.45236058864607e-05 -2.90183626332127e-06 -1.60974354527671e-06 -3.7794938157454e-06 2.67978949507606e-06 3.8400072345102e-06 -2.90183626332127e-06 2.3937932939066e-05 -2.40954046154412e-06 3.10481275748935e-06 -2.46684557596811e-06 -2.22628184102751e-06 -1.60974354527671e-06 -2.40954046154412e-06 5.75553832291239e-05 -4.81942139650999e-06 1.75779405196615e-05 -1.25119681364906e-05 -3.7794938157454e-06 3.10481275748935e-06 -4.81942139650999e-06 4.78389799986007e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 651 0 0 0 0 0 2220 +1072 1137 0.987115300003029 0.0264683373093108 0.157806247088039 -0.0314967923343886 -0.0135178142398825 0.996492639104308 -0.0825814077689894 0.00410934083774314 -0.159438556184214 0.0793841755705293 0.984010924467244 0.00511124952671131 6.47192038335406e-05 2.72948222982226e-05 -9.11401199344231e-06 8.37302057188066e-06 -2.77720787520311e-05 3.91025674363483e-05 2.72948222982226e-05 0.000118688752789993 7.68117227255377e-06 7.27411048691415e-06 -1.35264831985204e-05 -1.07055155177819e-05 -9.11401199344231e-06 7.68117227255377e-06 1.80335617868684e-05 -4.01168962506632e-06 -1.36746916764285e-06 -7.25833706733644e-06 8.37302057188066e-06 7.27411048691415e-06 -4.01168962506632e-06 3.06619829033206e-05 -2.72090086884798e-05 8.54383307833109e-06 -2.77720787520311e-05 -1.35264831985204e-05 -1.36746916764285e-06 -2.72090086884798e-05 0.000136207326873774 -2.40089534765994e-05 3.91025674363483e-05 -1.07055155177819e-05 -7.25833706733644e-06 8.54383307833109e-06 -2.40089534765994e-05 6.46869518116166e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 916 0 0 0 0 0 2229 +1072 1110 0.987844980751429 0.0268185696869745 0.153111261258452 -0.0319064056081265 -0.0137356316368415 0.996211310884458 -0.0858740734413282 0.00147373763437214 -0.154834190112346 0.0827271925415973 0.98447071321926 0.0098183086077217 8.31829176751387e-05 1.93415258257141e-05 -1.93121047851432e-05 1.57547513691619e-05 -1.1438427453331e-05 4.3907118105343e-05 1.93415258257141e-05 0.000104920239200695 -5.0177293341295e-07 1.14425520359701e-05 1.49498908590653e-05 -1.16854457731198e-05 -1.93121047851432e-05 -5.0177293341295e-07 1.72509560275051e-05 -5.58471608625614e-06 -1.98395204630749e-06 -9.79347395018508e-06 1.57547513691619e-05 1.14425520359701e-05 -5.58471608625614e-06 2.3506401366072e-05 -1.10610331703936e-07 7.70549038818735e-06 -1.1438427453331e-05 1.49498908590653e-05 -1.98395204630749e-06 -1.10610331703936e-07 8.12451602789289e-05 -1.5800030453125e-05 4.3907118105343e-05 -1.16854457731198e-05 -9.79347395018508e-06 7.70549038818735e-06 -1.5800030453125e-05 7.22178468144528e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 740 0 0 0 0 0 2205 +1072 1140 0.987571980043124 0.0264918105765444 0.154918585734833 -0.03617652740634 -0.0138916667324547 0.99654718750504 -0.0818579542328652 0.0174658178139952 -0.156552246324027 0.0786885445803386 0.984530094574427 0.00638846644650771 6.25059803708165e-05 3.96056938829691e-05 -9.48481675941623e-06 4.51659209554449e-06 2.86599423459855e-06 2.1770414181056e-05 3.96056938829691e-05 0.000131874006439535 5.75768666307486e-06 7.35065652555697e-06 -1.8713611449905e-05 -6.65881007876546e-06 -9.48481675941623e-06 5.75768666307486e-06 1.84354690429605e-05 -4.65731611821149e-06 -7.0297467010871e-07 -1.89781716103474e-06 4.51659209554449e-06 7.35065652555697e-06 -4.65731611821149e-06 3.43065032394348e-05 -2.97292722608492e-05 -1.86978642688475e-06 2.86599423459855e-06 -1.8713611449905e-05 -7.0297467010871e-07 -2.97292722608492e-05 0.000121518474443327 8.00205054998616e-06 2.1770414181056e-05 -6.65881007876546e-06 -1.89781716103474e-06 -1.86978642688475e-06 8.00205054998616e-06 4.39745259616549e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 862 0 0 0 0 0 2292 +1072 1135 0.98852936373403 0.0269126946329689 0.148611587378597 -0.0356913508863443 -0.0152093497625647 0.996732106519727 -0.0793333694768327 0.00916641316268068 -0.150261015288044 0.0761630796405992 0.985708279656951 0.00281184138464354 8.52579245566806e-05 5.45535374068807e-05 -1.18893032796779e-05 1.9108805866361e-05 -3.1706020551785e-05 3.7372523686144e-05 5.45535374068807e-05 0.000102406415763505 1.65113283432779e-07 9.97809045596649e-06 -1.6295432630908e-05 2.14078686242924e-05 -1.18893032796779e-05 1.65113283432779e-07 1.68372479809121e-05 -4.42986385479761e-06 1.76662099474287e-06 -6.29740527927589e-06 1.9108805866361e-05 9.97809045596649e-06 -4.42986385479761e-06 3.83094128082483e-05 -5.28483326323128e-05 9.35940108240842e-06 -3.1706020551785e-05 -1.6295432630908e-05 1.76662099474287e-06 -5.28483326323128e-05 0.000193364188875088 -2.07758233892355e-05 3.7372523686144e-05 2.14078686242924e-05 -6.29740527927589e-06 9.35940108240842e-06 -2.07758233892355e-05 5.86371612148721e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 901 0 0 0 0 0 2374 +1072 1112 0.988030571771519 0.027675500518595 0.151755250043912 -0.0324622929521619 -0.0138904091966008 0.99573971832165 -0.0911562937436155 -0.00614622347086536 -0.153631525987331 0.0879572625072346 0.984205707255875 0.0152327587903617 0.000133686026098056 2.32037906487499e-05 -2.46440305075368e-05 2.45937693250302e-05 -6.41028599878947e-05 9.58005721824233e-05 2.32037906487499e-05 0.000149165055242998 2.61213706984009e-06 2.06349690203023e-05 -9.71665022764119e-07 -2.11048447160453e-05 -2.46440305075368e-05 2.61213706984009e-06 2.03707891409951e-05 -5.93266631795095e-06 1.27061856269648e-06 -1.76512628202999e-05 2.45937693250302e-05 2.06349690203023e-05 -5.93266631795095e-06 3.48451042317164e-05 -2.73115635720663e-05 1.96339024655631e-05 -6.41028599878947e-05 -9.71665022764119e-07 1.27061856269648e-06 -2.73115635720663e-05 0.000163543730852047 -7.17701745744484e-05 9.58005721824233e-05 -2.11048447160453e-05 -1.76512628202999e-05 1.96339024655631e-05 -7.17701745744484e-05 0.00013265130836009 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 752 0 0 0 0 0 2366 +1072 1101 0.98800182759947 0.027227530227303 0.152023189868614 -0.0347756834088781 -0.0140634614785914 0.996108561267322 -0.0870054781102114 0.00545146937926713 -0.153800545224481 0.0838235991094847 0.984539992342101 0.011268891999276 7.4733017612425e-05 2.88064799010901e-05 -1.71076661236803e-05 1.49342350396566e-05 -1.69250244651464e-05 3.67739340168381e-05 2.88064799010901e-05 8.88713921061359e-05 5.39549340652306e-06 6.84044096862903e-06 -1.68166494115634e-05 -7.23368928618729e-06 -1.71076661236803e-05 5.39549340652306e-06 2.01745002722105e-05 -7.03947301851125e-06 -1.36529698747903e-06 -1.20202808812194e-05 1.49342350396566e-05 6.84044096862903e-06 -7.03947301851125e-06 2.9148683181147e-05 -1.38440001432258e-05 1.18653012093123e-05 -1.69250244651464e-05 -1.68166494115634e-05 -1.36529698747903e-06 -1.38440001432258e-05 8.18685809917882e-05 -9.08826589817564e-06 3.67739340168381e-05 -7.23368928618729e-06 -1.20202808812194e-05 1.18653012093123e-05 -9.08826589817564e-06 6.26750595100704e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 738 0 0 0 0 0 2297 +1072 1133 0.986908731392386 0.026361453252776 0.159110746600829 -0.0281632506057742 -0.0129485917056442 0.996317749480956 -0.0847542095830224 -0.0119277827072485 -0.160759105105472 0.0815844093660307 0.983616029898905 0.00265269246693742 0.000100957651701287 4.1500315969208e-05 -1.63109985727653e-05 2.07686823059409e-05 -4.71526093863672e-05 5.21387862184721e-05 4.1500315969208e-05 9.06265278377384e-05 -1.79517176937155e-06 1.19811424814496e-05 -1.90198544410529e-05 1.31238311687122e-05 -1.63109985727653e-05 -1.79517176937155e-06 1.72867469051605e-05 -5.1113250576825e-06 1.42654030267291e-06 -6.07810891918142e-06 2.07686823059409e-05 1.19811424814496e-05 -5.1113250576825e-06 4.16082350215152e-05 -5.3429745462682e-05 1.16628809339107e-05 -4.71526093863672e-05 -1.90198544410529e-05 1.42654030267291e-06 -5.3429745462682e-05 0.000210350049341514 -3.43339741128099e-05 5.21387862184721e-05 1.31238311687122e-05 -6.07810891918142e-06 1.16628809339107e-05 -3.43339741128099e-05 7.38870434539006e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2258 +1072 1100 0.988200794447233 0.0274536319304108 0.150683403026634 -0.0362155396294125 -0.0145463899281577 0.996180203955705 -0.086101125351699 0.00903786098720396 -0.152471611764012 0.0828933009392226 0.984825420196638 0.0107713627922058 6.66794353321441e-05 1.48321622496566e-05 -1.47527218563788e-05 9.69828181264559e-06 -4.50465344157975e-06 4.47688711722644e-05 1.48321622496566e-05 0.000115599478300398 3.19965724026936e-06 1.43484204662846e-05 2.4199909497278e-06 -1.85587416789256e-05 -1.47527218563788e-05 3.19965724026936e-06 1.79816451106694e-05 -4.55806184419446e-06 -6.00394143065534e-07 -9.75762595822653e-06 9.69828181264559e-06 1.43484204662846e-05 -4.55806184419446e-06 2.60541200129545e-05 -2.94452367254113e-06 6.74024110419391e-06 -4.50465344157975e-06 2.4199909497278e-06 -6.00394143065534e-07 -2.94452367254113e-06 6.11596394678432e-05 -1.40577128830015e-05 4.47688711722644e-05 -1.85587416789256e-05 -9.75762595822653e-06 6.74024110419391e-06 -1.40577128830015e-05 7.36563138109261e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 730 0 0 0 0 0 2334 +1072 1113 0.988896579004809 0.0271785124153725 0.146098886017223 -0.0351503434551899 -0.0148357822032614 0.99627756792857 -0.0849170607637322 0.00210721122161752 -0.147862962228556 0.0818066996353076 0.985618693154597 0.0123199715145825 0.000109781429672724 3.86465143974965e-05 -2.2308904763007e-05 2.08163470230628e-05 -4.39370574019549e-05 6.16002314900866e-05 3.86465143974965e-05 0.000108389062465739 -5.35607073706878e-06 8.09676129048576e-06 2.18283115368914e-06 -1.17801136919864e-06 -2.2308904763007e-05 -5.35607073706878e-06 1.85956459266247e-05 -7.23673887837935e-06 5.38979894896528e-06 -1.38735414973331e-05 2.08163470230628e-05 8.09676129048576e-06 -7.23673887837935e-06 2.71079481835021e-05 -2.02991579668973e-05 1.56819321368909e-05 -4.39370574019549e-05 2.18283115368914e-06 5.38979894896528e-06 -2.02991579668973e-05 0.000123897514676167 -3.67003056722556e-05 6.16002314900866e-05 -1.17801136919864e-06 -1.38735414973331e-05 1.56819321368909e-05 -3.67003056722556e-05 8.3473047310386e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 736 0 0 0 0 0 2393 +1072 1132 0.988973953700113 0.0273160972447267 0.145548444629555 -0.0324228169599143 -0.0153431193272274 0.996451598022209 -0.0827574859955006 -0.0030438567126794 -0.14729259177595 0.0796118309694084 0.985883790706401 0.00245531954955043 4.98619881691825e-05 2.45643759342159e-05 -8.772495406176e-06 3.63869785966921e-06 -6.05735358535187e-06 1.70969125669839e-05 2.45643759342159e-05 8.65279794085616e-05 2.8237008741785e-06 1.57770429835952e-06 -4.21410341643462e-06 1.32871611808924e-06 -8.772495406176e-06 2.8237008741785e-06 1.72362575720435e-05 -3.37771520749754e-06 -5.60345604510311e-06 -1.99636253671437e-06 3.63869785966921e-06 1.57770429835952e-06 -3.37771520749754e-06 2.80494556801698e-05 -2.06231794332411e-05 -1.5804683250924e-06 -6.05735358535187e-06 -4.21410341643462e-06 -5.60345604510311e-06 -2.06231794332411e-05 0.000105099642561291 -1.18546794526224e-06 1.70969125669839e-05 1.32871611808924e-06 -1.99636253671437e-06 -1.5804683250924e-06 -1.18546794526224e-06 4.5792280342366e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 902 0 0 0 0 0 2182 +1072 1099 0.988142846136111 0.0273924312664816 0.151074055811506 -0.0361989495698226 -0.0145590508228296 0.996239643461074 -0.0854084705148802 0.00846017278513819 -0.152845509156027 0.0821962742821351 0.984825884522219 0.0110792813531464 5.07023524611971e-05 3.25445350494304e-05 -6.60967861690063e-06 7.68430640450032e-06 -8.35692046005674e-07 1.92364443996772e-05 3.25445350494304e-05 8.36561987088819e-05 2.80822930851835e-06 1.80726518262757e-06 -6.00414145669713e-06 -7.40840608337563e-07 -6.60967861690063e-06 2.80822930851835e-06 1.73267630033529e-05 -6.71557215078909e-06 -1.43419957336115e-06 -5.21625496693697e-06 7.68430640450032e-06 1.80726518262757e-06 -6.71557215078909e-06 2.55737453758246e-05 -1.50330203707904e-06 5.03015958720282e-06 -8.35692046005674e-07 -6.00414145669713e-06 -1.43419957336115e-06 -1.50330203707904e-06 5.70216200717534e-05 4.99234002348076e-06 1.92364443996772e-05 -7.40840608337563e-07 -5.21625496693697e-06 5.03015958720282e-06 4.99234002348076e-06 4.86399077537537e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 735 0 0 0 0 0 2295 +1072 1114 0.987797646118161 0.0266792511837128 0.153440633079041 -0.0306442111796405 -0.0138581260342899 0.996367028680959 -0.0840279507086422 -0.00356358146092936 -0.155124990463298 0.0808762122861391 0.984578730026202 0.00839863157724138 4.64349157151232e-05 1.23103701866092e-05 -1.00589593612162e-05 1.14591890201881e-07 4.0614296956827e-06 1.99915825246657e-05 1.23103701866092e-05 9.83917450953086e-05 7.43927649570593e-06 1.25679809626142e-06 1.35486401305168e-05 -1.19280035387217e-05 -1.00589593612162e-05 7.43927649570593e-06 2.03517539534137e-05 -3.6259797532046e-06 -4.71893696526594e-07 -3.76608917215844e-06 1.14591890201881e-07 1.25679809626142e-06 -3.6259797532046e-06 2.44527297712073e-05 -1.16469378993045e-05 -6.51311391055983e-07 4.0614296956827e-06 1.35486401305168e-05 -4.71893696526594e-07 -1.16469378993045e-05 7.69393927266061e-05 8.41864445662972e-07 1.99915825246657e-05 -1.19280035387217e-05 -3.76608917215844e-06 -6.51311391055983e-07 8.41864445662972e-07 4.04868524006096e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 851 0 0 0 0 0 2250 +1072 1134 0.987960343283671 0.0273689546125534 0.152267200743389 -0.029245719642719 -0.0140429853602702 0.996029109829393 -0.0879136333832139 -0.0129245715135801 -0.154068668654541 0.084716897345706 0.984421603096526 0.00441382554550512 6.12811913038686e-05 2.67946900700811e-05 -1.4654824963918e-05 1.06078091656023e-05 -9.19682486468973e-06 2.97017403395896e-05 2.67946900700811e-05 9.38229644601748e-05 2.56617675751758e-06 8.92037730426816e-06 -8.65637910260439e-06 -2.0551703046318e-06 -1.4654824963918e-05 2.56617675751758e-06 2.00964522352903e-05 -5.5776238971979e-06 -1.50513439933485e-06 -8.11653165795398e-06 1.06078091656023e-05 8.92037730426816e-06 -5.5776238971979e-06 3.35582245217534e-05 -3.16404089510149e-05 7.83126700630722e-06 -9.19682486468973e-06 -8.65637910260439e-06 -1.50513439933485e-06 -3.16404089510149e-05 0.000137474758742514 -1.29872614041253e-05 2.97017403395896e-05 -2.0551703046318e-06 -8.11653165795398e-06 7.83126700630722e-06 -1.29872614041253e-05 6.29691940849164e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 803 0 0 0 0 0 2362 +1072 1115 0.987472324521551 0.0269357047326673 0.155476287949514 -0.0295049134235567 -0.0136101429567742 0.996189682777254 -0.0861445293495194 -0.00775834982963738 -0.157204237578704 0.0829492841362034 0.984076340508494 0.00700901347038312 5.89275286095165e-05 8.21444756452541e-06 -1.05877281051614e-05 7.07591911121239e-06 -6.74475061382536e-06 1.25587936673777e-05 8.21444756452541e-06 8.69337734829717e-05 4.72996418128563e-06 4.71923865555773e-06 -6.54946044826899e-06 -7.52155895782859e-06 -1.05877281051614e-05 4.72996418128563e-06 1.80428880994114e-05 -2.82466270352311e-06 2.05518608872855e-07 -2.8201955349691e-06 7.07591911121239e-06 4.71923865555773e-06 -2.82466270352311e-06 2.63841159964878e-05 -1.71666754617687e-05 8.35304088086043e-07 -6.74475061382536e-06 -6.54946044826899e-06 2.05518608872855e-07 -1.71666754617687e-05 9.38140227463847e-05 -9.65767394608873e-06 1.25587936673777e-05 -7.52155895782859e-06 -2.8201955349691e-06 8.35304088086043e-07 -9.65767394608873e-06 4.00704503309806e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 825 0 0 0 0 0 2332 +1072 1128 0.98771209672399 0.0273962601926251 0.153864417304836 -0.0299204667672799 -0.0146008460467007 0.996385470769535 -0.0836827875616816 -0.0035116755377359 -0.155600865292643 0.0804079508931236 0.984541991056425 0.00377349369937238 0.000181832901777339 7.24933611696995e-05 -2.18602505011154e-05 5.01340465034465e-05 -0.000150840072992208 0.000118606121580625 7.24933611696995e-05 8.08276071210027e-05 -4.93993333685021e-06 1.14444650760132e-05 -3.42239151369431e-05 4.05686512930059e-05 -2.18602505011154e-05 -4.93993333685021e-06 1.72931360011451e-05 -5.94606724316203e-06 9.53283758020157e-06 -1.35088552063489e-05 5.01340465034465e-05 1.14444650760132e-05 -5.94606724316203e-06 5.27223259216659e-05 -0.000102270549611305 4.24985673063548e-05 -0.000150840072992208 -3.42239151369431e-05 9.53283758020157e-06 -0.000102270549611305 0.000377208897930095 -0.000128582592698974 0.000118606121580625 4.05686512930059e-05 -1.35088552063489e-05 4.24985673063548e-05 -0.000128582592698974 0.000121715203627814 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 815 0 0 0 0 0 2418 +1072 1125 0.987851197539375 0.0273119519881536 0.152983884114042 -0.0288283880159486 -0.0143994601330978 0.996286716336964 -0.0848848302017803 -0.00983011529934343 -0.154734181963447 0.0816506958274486 0.984576303189852 0.00341026346560246 4.36104503343959e-05 2.25643790644233e-05 -1.24418071394097e-05 8.09341069285715e-06 1.44290680669155e-07 8.72666716879475e-06 2.25643790644233e-05 9.82249199340308e-05 3.14555500441963e-06 1.68586662878013e-06 6.48440748518091e-06 -1.19915351626152e-05 -1.24418071394097e-05 3.14555500441963e-06 2.10520300373444e-05 -7.40276635923815e-06 -2.92999913842044e-06 -4.50141070420405e-06 8.09341069285715e-06 1.68586662878013e-06 -7.40276635923815e-06 3.25507450545198e-05 -2.83664609245693e-05 5.19452212194392e-06 1.44290680669155e-07 6.48440748518091e-06 -2.92999913842044e-06 -2.83664609245693e-05 0.000122117685166335 -7.63901236415744e-06 8.72666716879475e-06 -1.19915351626152e-05 -4.50141070420405e-06 5.19452212194392e-06 -7.63901236415744e-06 4.24847603772245e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 909 0 0 0 0 0 2253 +1072 1123 0.987960664323922 0.0268871243620855 0.152350937943198 -0.0300220176360105 -0.0137145129740671 0.996125916990052 -0.0868623602869029 -0.0102848032422166 -0.154096196846381 0.0837271762587592 0.984501966515667 0.00724803145233189 0.000103256382432374 7.18489403981877e-05 -1.2203378595541e-05 5.41073560186224e-06 -2.10616658240011e-06 4.24503616636945e-05 7.18489403981877e-05 0.00014426468845985 1.85156657886824e-06 1.10912858648331e-05 -1.5071542819561e-05 1.24531815938874e-05 -1.2203378595541e-05 1.85156657886824e-06 1.71187634620419e-05 -1.43718193779544e-06 -7.73376312106209e-07 -4.67560455110573e-06 5.41073560186224e-06 1.10912858648331e-05 -1.43718193779544e-06 3.52238227951814e-05 -3.31150236622792e-05 1.82860499480499e-06 -2.10616658240011e-06 -1.5071542819561e-05 -7.73376312106209e-07 -3.31150236622792e-05 0.00013111826416619 1.22332979144004e-05 4.24503616636945e-05 1.24531815938874e-05 -4.67560455110573e-06 1.82860499480499e-06 1.22332979144004e-05 6.86810412746896e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 801 0 0 0 0 0 2315 +1072 1124 0.987583242743029 0.026850010188651 0.154785062606288 -0.029088335063168 -0.01408924398555 0.996453535682186 -0.0829568829596822 -0.0040074095602502 -0.15646351605751 0.0797460229687982 0.984459110356332 0.00383189555195651 6.59167899236536e-05 3.53318754227143e-05 -1.04387386450165e-05 4.21755440244912e-06 1.5687125921454e-06 2.01207015206145e-05 3.53318754227143e-05 9.36665480774868e-05 -8.23555108658123e-09 6.54580775591843e-06 -1.67497127378251e-06 -6.21803066924829e-06 -1.04387386450165e-05 -8.23555108658123e-09 1.67615396465498e-05 -2.76869575254568e-06 -1.29204913749715e-06 -5.11676608937484e-07 4.21755440244912e-06 6.54580775591843e-06 -2.76869575254568e-06 2.81339924976052e-05 -2.3297202119026e-05 -2.58265253198281e-06 1.5687125921454e-06 -1.67497127378251e-06 -1.29204913749715e-06 -2.3297202119026e-05 0.000101659718910438 2.0089454719024e-06 2.01207015206145e-05 -6.21803066924829e-06 -5.11676608937484e-07 -2.58265253198281e-06 2.0089454719024e-06 4.94946695428331e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 920 0 0 0 0 0 2327 +1073 1075 0.999246657466851 -0.0123823932298679 0.0367803463717531 -0.0192418994616522 0.0132168642463861 0.999658750503273 -0.022532133536973 0.0130950710553432 -0.0364887933593016 0.0230012799673475 0.999069321458249 0.0134796261310429 3.43365633471086e-05 9.17719170436328e-06 -1.12612909084342e-05 5.25940811560458e-06 -2.41670608690452e-07 1.364158320341e-05 9.17719170436328e-06 5.63053183854999e-05 6.06158010132309e-07 5.771743701371e-07 1.69199441840843e-05 -2.9623324632905e-06 -1.12612909084342e-05 6.06158010132309e-07 2.11810284417157e-05 -1.02988430315826e-05 -6.97624580226468e-06 -3.76409456270846e-06 5.25940811560458e-06 5.771743701371e-07 -1.02988430315826e-05 2.47319490798172e-05 -1.06074908051133e-05 2.81156397111139e-06 -2.41670608690452e-07 1.69199441840843e-05 -6.97624580226468e-06 -1.06074908051133e-05 9.44022621295138e-05 -9.46853520613638e-06 1.364158320341e-05 -2.9623324632905e-06 -3.76409456270846e-06 2.81156397111139e-06 -9.46853520613638e-06 4.39111084194653e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1096 0 0 0 0 0 2220 +1072 1116 0.987604937251169 0.0270031242375197 0.154619918505111 -0.0293395742584361 -0.0136554582001872 0.996136895696572 -0.0867456828513108 -0.0093599417810901 -0.156365010083641 0.0835590588351158 0.984158456402287 0.00806503548410405 0.000146052905927446 9.76590661220207e-05 -1.0052661092924e-05 1.81231311741047e-05 -5.86894336594185e-05 0.000100519454077868 9.76590661220207e-05 0.000130783984982942 -1.4280515359958e-06 8.80704571915628e-06 -1.61495335372871e-05 6.45309760520988e-05 -1.0052661092924e-05 -1.4280515359958e-06 1.52887174650883e-05 -2.62734161367269e-06 7.65072085832963e-06 -7.74404944850536e-06 1.81231311741047e-05 8.80704571915628e-06 -2.62734161367269e-06 2.63775953595221e-05 -2.30526616144697e-05 1.37536812539886e-05 -5.86894336594185e-05 -1.61495335372871e-05 7.65072085832963e-06 -2.30526616144697e-05 0.000130806078977589 -4.74457988962133e-05 0.000100519454077868 6.45309760520988e-05 -7.74404944850536e-06 1.37536812539886e-05 -4.74457988962133e-05 0.000116033968014734 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 765 0 0 0 0 0 2356 +1072 1126 0.988412860451338 0.0264427023190082 0.149468393944916 -0.0334185432913545 -0.0143858138945238 0.996595786782957 -0.0811781135839613 -0.00059002956014418 -0.151106140355038 0.0780872669551619 0.985428492122324 0.00172952524820327 0.000206363907602359 9.15944753420114e-05 -2.76841557599259e-05 5.83591908220961e-05 -0.000172220296165259 0.000152957015013721 9.15944753420114e-05 0.000130558512985297 -6.59855253871305e-06 1.62639361794198e-05 -2.24086372264012e-05 5.17789011706022e-05 -2.76841557599259e-05 -6.59855253871305e-06 1.86946478605509e-05 -9.39976373664227e-06 1.93462090736629e-05 -2.00924158300742e-05 5.83591908220961e-05 1.62639361794198e-05 -9.39976373664227e-06 5.16466378303786e-05 -0.000107958724005735 5.79628226342606e-05 -0.000172220296165259 -2.24086372264012e-05 1.93462090736629e-05 -0.000107958724005735 0.000426567838984879 -0.000175800684869588 0.000152957015013721 5.17789011706022e-05 -2.00924158300742e-05 5.79628226342606e-05 -0.000175800684869588 0.000169958794604949 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2358 +1072 1117 0.987915739587627 0.0271474106453487 0.152595902862049 -0.0269789794534992 -0.013545869356543 0.995896759600629 -0.0894771123826784 -0.0197654287301805 -0.154398837101859 0.0863288034911859 0.984229819091747 0.00918002586174454 0.000128455033588901 9.46814290335989e-05 -1.41517480053505e-05 2.96831699511469e-05 -7.57726396476525e-05 8.43671185680022e-05 9.46814290335989e-05 0.000145891495997491 -7.29670081007905e-06 1.66480055580965e-05 -2.35860953916186e-05 4.52868404034623e-05 -1.41517480053505e-05 -7.29670081007905e-06 1.45732950325088e-05 -3.07691041801924e-06 9.01797540258258e-06 -1.01489772020672e-05 2.96831699511469e-05 1.66480055580965e-05 -3.07691041801924e-06 3.27692203258472e-05 -4.03596125485862e-05 2.71332789874498e-05 -7.57726396476525e-05 -2.35860953916186e-05 9.01797540258258e-06 -4.03596125485862e-05 0.000187365113447027 -6.67640029293234e-05 8.43671185680022e-05 4.52868404034623e-05 -1.01489772020672e-05 2.71332789874498e-05 -6.67640029293234e-05 0.000104904612364146 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 769 0 0 0 0 0 2287 +1072 1122 0.98814680925479 0.0268679682599935 0.151142302619607 -0.0305965454153299 -0.0145755414746618 0.996537440473885 -0.0818577016808967 -0.00271824755991588 -0.15281831353047 0.0786844458285006 0.985116907292918 0.0020272201347997 5.81130138783059e-05 1.69261454650405e-05 -1.12183911822263e-05 4.96674900045154e-06 -1.14068426019327e-05 2.47061486699251e-05 1.69261454650405e-05 0.000143201040876846 8.98530301754092e-06 1.13003804483214e-05 -5.60837384637476e-06 -3.22210909465745e-05 -1.12183911822263e-05 8.98530301754092e-06 1.70409956356469e-05 -3.46228004608394e-06 2.68176074007768e-07 -5.39297665875588e-06 4.96674900045154e-06 1.13003804483214e-05 -3.46228004608394e-06 3.99723942992126e-05 -4.87728102170435e-05 -3.23260244879747e-06 -1.14068426019327e-05 -5.60837384637476e-06 2.68176074007768e-07 -4.87728102170435e-05 0.000178636329563649 -6.04769591007122e-06 2.47061486699251e-05 -3.22210909465745e-05 -5.39297665875588e-06 -3.23260244879747e-06 -6.04769591007122e-06 6.34110883334933e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 920 0 0 0 0 0 2245 +1073 1105 0.992954770056247 0.0167052305316284 0.117310527641089 -0.0382501240813307 -0.00657522970481352 0.996254977825632 -0.0862136039843965 -0.00405177913541309 -0.118311415243308 0.0848348656540137 0.989345973152259 0.00661270051280264 6.65267690521987e-05 4.75406639061543e-05 -2.19096751956818e-06 1.47491397021439e-06 -8.63651101321213e-06 3.50138416504888e-05 4.75406639061543e-05 8.37503076877115e-05 2.76082167390818e-06 2.62844551626796e-06 -1.32016814628713e-06 1.52908479940735e-05 -2.19096751956818e-06 2.76082167390818e-06 1.63344741502549e-05 -7.05176533764134e-06 -2.86899267235682e-06 -1.25523965472509e-06 1.47491397021439e-06 2.62844551626796e-06 -7.05176533764134e-06 2.48805569746509e-05 1.57588112907555e-06 3.58327478192679e-06 -8.63651101321213e-06 -1.32016814628713e-06 -2.86899267235682e-06 1.57588112907555e-06 5.23123626146826e-05 -9.90984575914271e-06 3.50138416504888e-05 1.52908479940735e-05 -1.25523965472509e-06 3.58327478192679e-06 -9.90984575914271e-06 6.28052852188712e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 751 0 0 0 0 0 2290 +1073 1107 0.992393393176012 0.0167655769740123 0.121960110730228 -0.0374330161577023 -0.00699327756467621 0.99676086171814 -0.0801179044646914 0.00479830929007719 -0.122908287961001 0.0786555781597116 0.989296140078822 0.00321055720606059 0.00013579071903854 5.1834463434984e-05 -1.93911824613641e-05 2.89335882167356e-05 -8.28260430957087e-05 9.74609469979249e-05 5.1834463434984e-05 9.17311808690443e-05 -4.91894586438163e-06 1.44398032636703e-05 -2.18881643255476e-05 1.88975568397427e-05 -1.93911824613641e-05 -4.91894586438163e-06 1.7321374242024e-05 -7.10196399172557e-06 4.88908754945559e-06 -1.17458797677795e-05 2.89335882167356e-05 1.44398032636703e-05 -7.10196399172557e-06 3.06933933273875e-05 -2.76058611551961e-05 2.24864736813452e-05 -8.28260430957087e-05 -2.18881643255476e-05 4.88908754945559e-06 -2.76058611551961e-05 0.000150533832396288 -7.98046558671081e-05 9.74609469979249e-05 1.88975568397427e-05 -1.17458797677795e-05 2.24864736813452e-05 -7.98046558671081e-05 0.000120875350403642 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 686 0 0 0 0 0 2239 +1073 1108 0.992797449904033 0.0171596811541154 0.118569679120501 -0.0399111109954295 -0.00770101670694181 0.996783124371478 -0.0797752926031312 0.00724306745224863 -0.119557173794502 0.078287599981893 0.989735890974631 0.00406710374370425 9.20612648800081e-05 2.02138114662537e-05 -2.04262063793785e-05 1.5460387795882e-05 -2.68839459653164e-05 4.58317633705122e-05 2.02138114662537e-05 0.000128615515049124 5.12510948968495e-06 1.44752652397906e-05 -2.52119347314893e-05 -1.62472677449444e-05 -2.04262063793785e-05 5.12510948968495e-06 1.76644386409756e-05 -4.17999064405753e-06 -2.28727967679191e-06 -1.0002681629245e-05 1.5460387795882e-05 1.44752652397906e-05 -4.17999064405753e-06 2.59163420444894e-05 -9.26405665428983e-06 6.06914690369124e-06 -2.68839459653164e-05 -2.52119347314893e-05 -2.28727967679191e-06 -9.26405665428983e-06 8.5545963695694e-05 -2.3414766391197e-05 4.58317633705122e-05 -1.62472677449444e-05 -1.0002681629245e-05 6.06914690369124e-06 -2.3414766391197e-05 8.02286461530925e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 696 0 0 0 0 0 2287 +1073 1140 0.991617533863548 0.0173950428282096 0.128031554779983 -0.034902564795461 -0.00642779706365652 0.996310562077285 -0.0855800637891378 0.00194214114797601 -0.129047859181327 0.0840397309505998 0.988070834334496 0.00428622576647281 9.30154100454718e-05 3.59984600208037e-05 -1.80226034798108e-05 7.62666535525874e-06 1.63253304603434e-07 5.59547739176774e-05 3.59984600208037e-05 0.000102253199680842 3.35342945555594e-06 -3.54161949352971e-06 1.79098278391152e-05 -1.56323422414419e-06 -1.80226034798108e-05 3.35342945555594e-06 2.03012520676527e-05 -7.87718370732631e-06 -8.93695722503238e-07 -1.0090504812141e-05 7.62666535525874e-06 -3.54161949352971e-06 -7.87718370732631e-06 3.03980300612588e-05 -1.97334984026856e-05 1.86923097341426e-06 1.63253304603434e-07 1.79098278391152e-05 -8.93695722503238e-07 -1.97334984026856e-05 9.46416135643606e-05 -2.11428077734344e-06 5.59547739176774e-05 -1.56323422414419e-06 -1.0090504812141e-05 1.86923097341426e-06 -2.11428077734344e-06 7.5496265572922e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 856 0 0 0 0 0 2331 +1073 1106 0.992260554623811 0.0175780716869918 0.122922752708417 -0.0348602714598888 -0.0064011115635801 0.995854328008722 -0.0907368897254421 -0.00545734184426529 -0.124008134847672 0.0892477942700177 0.988259487032398 0.0133942895832132 7.29009786554589e-05 1.2691440726891e-05 -1.01644696315553e-05 1.66543710450964e-06 -1.44232793298073e-05 5.1707631352839e-05 1.2691440726891e-05 0.000132343984174279 7.93329640757366e-06 1.99366145568714e-05 -1.61789652134164e-05 -3.3730006797326e-05 -1.01644696315553e-05 7.93329640757366e-06 1.62240479204072e-05 -1.82458210848613e-06 -1.35612886328264e-06 -8.33804589184808e-06 1.66543710450964e-06 1.99366145568714e-05 -1.82458210848613e-06 2.79274376836706e-05 -1.08053772949373e-05 -2.26819023474399e-06 -1.44232793298073e-05 -1.61789652134164e-05 -1.35612886328264e-06 -1.08053772949373e-05 7.68585870707239e-05 -1.92266262172296e-05 5.1707631352839e-05 -3.3730006797326e-05 -8.33804589184808e-06 -2.26819023474399e-06 -1.92266262172296e-05 9.11274687692167e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 775 0 0 0 0 0 2349 +1073 1110 0.991106698650065 0.0161813778866347 0.132082076379267 -0.0343548290132261 -0.00584915166794425 0.996917239476281 -0.0782419648255073 0.00299831734600509 -0.132940961767749 0.0767735673567438 0.988146001378129 -0.000176816675020032 4.7602645743396e-05 2.2378970155997e-06 -1.3627755394093e-05 7.11211836267208e-06 -4.85407716872146e-06 1.30361093128902e-05 2.2378970155997e-06 0.00010976919199861 1.06985764833188e-05 3.25902326682038e-06 -4.16240990544069e-06 -3.69209279563948e-05 -1.3627755394093e-05 1.06985764833188e-05 1.94569793633252e-05 -6.36151758827622e-06 -4.40822716421976e-06 -5.52749220611092e-06 7.11211836267208e-06 3.25902326682038e-06 -6.36151758827622e-06 2.46522993235217e-05 -1.83757710682179e-06 -2.50670096108302e-06 -4.85407716872146e-06 -4.16240990544069e-06 -4.40822716421976e-06 -1.83757710682179e-06 5.98937327919254e-05 -4.85938229175241e-06 1.30361093128902e-05 -3.69209279563948e-05 -5.52749220611092e-06 -2.50670096108302e-06 -4.85938229175241e-06 5.19665694471588e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 751 0 0 0 0 0 2280 +1073 1111 0.992065022041132 0.0164025118045062 0.124651312263574 -0.0358422698145937 -0.00668544541104319 0.996932823382255 -0.0779759609286206 -0.00250888075980629 -0.125547986292828 0.0765238738537774 0.989131841499518 3.69623721304677e-05 9.25003658919703e-05 2.42420026869661e-06 -1.87215705969749e-05 6.35335846155086e-06 -1.68230665471509e-05 6.54398241876909e-05 2.42420026869661e-06 9.65762391502585e-05 1.14628857558583e-05 1.59130980283196e-06 1.54070837279749e-05 -2.19976396243263e-05 -1.87215705969749e-05 1.14628857558583e-05 2.15348178682714e-05 -6.62071412321368e-06 4.98102883489634e-07 -1.08540150200664e-05 6.35335846155086e-06 1.59130980283196e-06 -6.62071412321368e-06 2.32956825550542e-05 -8.8522357840121e-07 3.5231304279219e-06 -1.68230665471509e-05 1.54070837279749e-05 4.98102883489634e-07 -8.8522357840121e-07 7.37202262056435e-05 -2.64473029144304e-05 6.54398241876909e-05 -2.19976396243263e-05 -1.08540150200664e-05 3.5231304279219e-06 -2.64473029144304e-05 9.54881838730195e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 708 0 0 0 0 0 2331 +1073 1136 0.992212541930177 0.0174144902886696 0.123332911927199 -0.0350927223014018 -0.0080728097360512 0.997087163804674 -0.0758420563995837 0.00489049881747677 -0.124294414111906 0.0742557964332614 0.989462973191337 -0.00194064430629513 4.53476423237692e-05 8.47650830417928e-06 -1.33024117090606e-05 5.52243339315096e-06 2.77265168123237e-06 1.9909893904282e-05 8.47650830417928e-06 9.45694501697768e-05 1.29769894682549e-05 2.23925342968496e-06 -2.6103637308399e-06 -1.74803423012541e-05 -1.33024117090606e-05 1.29769894682549e-05 2.41812991928684e-05 -1.0377565784764e-05 -4.13754711567686e-06 -5.23014307346234e-06 5.52243339315096e-06 2.23925342968496e-06 -1.0377565784764e-05 3.84408481056866e-05 -3.88358983516871e-05 -4.03561686306847e-06 2.77265168123237e-06 -2.6103637308399e-06 -4.13754711567686e-06 -3.88358983516871e-05 0.000166163213188939 1.25117675410241e-05 1.9909893904282e-05 -1.74803423012541e-05 -5.23014307346234e-06 -4.03561686306847e-06 1.25117675410241e-05 5.97279249265711e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 813 0 0 0 0 0 2350 +1073 1103 0.992772332277123 0.0162348053995844 0.118909744590925 -0.0412279360376592 -0.00593371236241695 0.996236236450132 -0.0864763102894494 0.00210880212304146 -0.119866122497732 0.0851457120312859 0.989132104625082 0.00238170704338827 7.42975233097713e-05 3.87858745080906e-05 -1.59789314149029e-07 8.37814378127664e-06 -2.98460304552974e-05 3.51583871230752e-05 3.87858745080906e-05 9.87051808213615e-05 3.76503333098521e-07 8.98035222502525e-06 -4.57626748161659e-06 2.23321235366283e-06 -1.59789314149029e-07 3.76503333098521e-07 1.60026665148914e-05 -3.42170029446944e-06 5.22503726224151e-07 -2.3939555024774e-06 8.37814378127664e-06 8.98035222502525e-06 -3.42170029446944e-06 2.59953155247791e-05 -5.81697147413571e-06 1.09711660014481e-05 -2.98460304552974e-05 -4.57626748161659e-06 5.22503726224151e-07 -5.81697147413571e-06 8.89731909086541e-05 -3.37238647508401e-05 3.51583871230752e-05 2.23321235366283e-06 -2.3939555024774e-06 1.09711660014481e-05 -3.37238647508401e-05 6.8717986262241e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 606 0 0 0 0 0 2367 +1073 1109 0.992448315563726 0.0180522131125969 0.121327896777537 -0.03368670386819 -0.00773895361087917 0.996355785553108 -0.0849426700301861 -0.00319717178290592 -0.122419155085027 0.0833622588260767 0.988971326314207 0.00722565128837407 7.32797609189894e-05 1.27482286752663e-05 -2.01368737330113e-05 1.33188254529833e-05 -9.27132860851736e-06 3.55917410342634e-05 1.27482286752663e-05 8.31911447496241e-05 3.20500710652238e-06 9.55780229125408e-06 -7.08836677129259e-06 -1.16312273020812e-05 -2.01368737330113e-05 3.20500710652238e-06 1.93011989709839e-05 -5.43802353279253e-06 -8.52238659311886e-08 -1.01066815093319e-05 1.33188254529833e-05 9.55780229125408e-06 -5.43802353279253e-06 2.83156601071024e-05 -1.4234629725263e-05 9.26144790462246e-06 -9.27132860851736e-06 -7.08836677129259e-06 -8.52238659311886e-08 -1.4234629725263e-05 8.50435325565495e-05 -2.21294378731627e-05 3.55917410342634e-05 -1.16312273020812e-05 -1.01066815093319e-05 9.26144790462246e-06 -2.21294378731627e-05 7.08229676290083e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 819 0 0 0 0 0 2254 +1073 1134 0.991941504819886 0.0165531326590139 0.125610687502431 -0.0387888258387917 -0.00722239921418464 0.997203977725991 -0.0743778445308296 0.0100542333107146 -0.126490663549731 0.0728712604984599 0.989287567610204 -0.00989405371125182 0.000106083690082716 6.19335353089628e-05 -1.21195983336812e-05 3.73980024644071e-05 -8.89910614905852e-05 4.70497325516663e-05 6.19335353089628e-05 0.000106591062810748 -6.83306857009382e-07 2.88339289053324e-05 -5.12236252393102e-05 1.84024408257407e-05 -1.21195983336812e-05 -6.83306857009382e-07 1.58656047899214e-05 -6.21781093785449e-06 6.43029735599924e-06 -5.60152513150767e-06 3.73980024644071e-05 2.88339289053324e-05 -6.21781093785449e-06 6.78162880956612e-05 -0.000132638497776495 1.02107465887259e-05 -8.89910614905852e-05 -5.12236252393102e-05 6.43029735599924e-06 -0.000132638497776495 0.000427881393926433 -2.53765875396854e-05 4.70497325516663e-05 1.84024408257407e-05 -5.60152513150767e-06 1.02107465887259e-05 -2.53765875396854e-05 6.90732361890011e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 795 0 0 0 0 0 2338 +1073 1135 0.992184523359877 0.0176706268244037 0.123521741214922 -0.0305076079313241 -0.00701646919299654 0.996256457740147 -0.0861617059436353 -0.0194273902042186 -0.124581863708957 0.0846216246516599 0.988594224075842 -0.0021211099181294 4.49450596333558e-05 1.27215367313196e-05 -6.32651757011188e-06 6.68908612590494e-06 -1.14646700869285e-05 9.98249158204541e-06 1.27215367313196e-05 0.00010883035709318 4.32913391217475e-06 1.61919432646648e-05 -7.24911528299759e-06 -1.88698884129074e-05 -6.32651757011188e-06 4.32913391217475e-06 1.7169387664789e-05 -3.91735784161218e-06 -1.95162054432041e-06 -1.49827136414624e-06 6.68908612590494e-06 1.61919432646648e-05 -3.91735784161218e-06 3.28457554996147e-05 -3.09858657113285e-05 -7.00834889941811e-08 -1.14646700869285e-05 -7.24911528299759e-06 -1.95162054432041e-06 -3.09858657113285e-05 0.000133078469648012 -1.9980210434888e-05 9.98249158204541e-06 -1.88698884129074e-05 -1.49827136414624e-06 -7.00834889941811e-08 -1.9980210434888e-05 5.55286869318418e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 886 0 0 0 0 0 2327 +1073 1104 0.992413325686558 0.0176808222908018 0.121668317662681 -0.0358097700496991 -0.00593084722684725 0.995337958423961 -0.0962661600542678 -0.00871506229830824 -0.122803159775788 0.0948142238461255 0.987891515757443 0.0203701709117977 8.9010665316264e-05 9.02692084917652e-05 6.64860679386306e-06 7.76075709315618e-06 -3.31275985156504e-05 4.56315170843409e-05 9.02692084917652e-05 0.000133393209098689 5.41783401483471e-06 2.10886101679627e-05 -5.1858456580233e-05 4.56494576325342e-05 6.64860679386306e-06 5.41783401483471e-06 1.55627099925362e-05 -6.0857014627142e-06 -2.57138766370572e-06 2.66820459306314e-06 7.76075709315618e-06 2.10886101679627e-05 -6.0857014627142e-06 3.52850272373364e-05 -1.61778956746771e-05 1.05136726017151e-05 -3.31275985156504e-05 -5.1858456580233e-05 -2.57138766370572e-06 -1.61778956746771e-05 9.38921691080956e-05 -2.58166587168916e-05 4.56315170843409e-05 4.56494576325342e-05 2.66820459306314e-06 1.05136726017151e-05 -2.58166587168916e-05 6.08082605503973e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 672 0 0 0 0 0 2314 +1073 1102 0.992376823689468 0.0163959912181806 0.122145041962318 -0.0425770737987902 -0.00688272208261584 0.996937150601595 -0.0779034395075458 0.0155996703766538 -0.123048234204057 0.0764688774753868 0.989450171982863 0.00142996731526366 8.6380834557877e-05 -4.08700334976192e-06 -1.66347520524924e-05 7.78425141928129e-06 -2.23421862568324e-05 5.25343394767462e-05 -4.08700334976192e-06 0.000178291599291015 1.87183487609379e-05 1.38553464589805e-05 -7.72915171606093e-06 -4.79637622218135e-05 -1.66347520524924e-05 1.87183487609379e-05 1.95690430350109e-05 -2.78385715837023e-06 -4.1546170271654e-06 -1.11658974849315e-05 7.78425141928129e-06 1.38553464589805e-05 -2.78385715837023e-06 2.55131114594759e-05 -5.65088853403283e-06 1.01021885169503e-06 -2.23421862568324e-05 -7.72915171606093e-06 -4.1546170271654e-06 -5.65088853403283e-06 7.62957551726077e-05 -2.05611320745903e-05 5.25343394767462e-05 -4.79637622218135e-05 -1.11658974849315e-05 1.01021885169503e-06 -2.05611320745903e-05 9.46012993451773e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 656 0 0 0 0 0 2232 +1073 1112 0.992111948136769 0.016600999588203 0.124250912177483 -0.035343715073333 -0.00660565867591266 0.996738499881961 -0.0804284037297491 -0.00587835816074446 -0.125180859709947 0.0789732211938367 0.988985835437772 -7.13951021143735e-05 3.96822729973157e-05 -1.21919692608665e-05 -1.2739255744743e-05 5.76812595960175e-06 -8.19600554621047e-06 1.78448809502582e-05 -1.21919692608665e-05 0.000152390138637124 1.16022356356879e-05 1.28013281299509e-05 8.88780355747898e-06 -3.72299416703095e-05 -1.2739255744743e-05 1.16022356356879e-05 2.07383675327852e-05 -5.25495657673884e-06 -1.46114442327258e-06 -7.62535575938881e-06 5.76812595960175e-06 1.28013281299509e-05 -5.25495657673884e-06 2.4598916442833e-05 -3.20353378980756e-06 1.48795108021063e-06 -8.19600554621047e-06 8.88780355747898e-06 -1.46114442327258e-06 -3.20353378980756e-06 6.48779530085113e-05 -2.0127725074734e-05 1.78448809502582e-05 -3.72299416703095e-05 -7.62535575938881e-06 1.48795108021063e-06 -2.0127725074734e-05 6.02204436442248e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 765 0 0 0 0 0 2344 +1073 1137 0.99148780302569 0.0175768566434979 0.129007715125197 -0.0298567240503763 -0.00648609107450342 0.996283394467762 -0.0858913763445856 -0.011452665546113 -0.130037944746383 0.0843234962411303 0.987916839064812 0.00568095872100179 5.98038080872544e-05 2.10586181934477e-05 -1.07276140670991e-05 5.81450356285548e-06 8.84464316595534e-08 3.44725486114004e-05 2.10586181934477e-05 0.000101631241319758 8.50243055649844e-06 1.21212119186782e-05 -1.85070132660396e-05 -1.57215275761711e-05 -1.07276140670991e-05 8.50243055649844e-06 1.85679428788444e-05 -6.66317653931001e-06 -2.55139484890953e-06 -7.72805880639911e-06 5.81450356285548e-06 1.21212119186782e-05 -6.66317653931001e-06 3.39701273066702e-05 -2.31113132471037e-05 3.81183356587022e-06 8.84464316595534e-08 -1.85070132660396e-05 -2.55139484890953e-06 -2.31113132471037e-05 9.97715006047994e-05 -7.13445592143266e-07 3.44725486114004e-05 -1.57215275761711e-05 -7.72805880639911e-06 3.81183356587022e-06 -7.13445592143266e-07 6.67448767124183e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 894 0 0 0 0 0 2338 +1073 1132 0.992013568100161 0.017084008899222 0.124968865503047 -0.0341536712539663 -0.00654813971109852 0.99642418184633 -0.0842375907668045 -0.00693699211214885 -0.125961115315447 0.0827465193938875 0.988578176451759 -0.000202580167549341 5.67508180010183e-05 1.90637433316345e-05 -1.24181278432402e-05 8.58470364323931e-06 -1.96196594751647e-06 3.6775779760824e-05 1.90637433316345e-05 9.89443707746124e-05 8.14172297698457e-06 4.40529955890491e-06 8.76213147080906e-06 -6.455027707232e-06 -1.24181278432402e-05 8.14172297698457e-06 2.12873620647401e-05 -6.36810340486172e-06 -8.45772281083e-06 -8.44918184229348e-06 8.58470364323931e-06 4.40529955890491e-06 -6.36810340486172e-06 3.74847450374706e-05 -4.66762017275321e-05 3.62292448997795e-07 -1.96196594751647e-06 8.76213147080906e-06 -8.45772281083e-06 -4.66762017275321e-05 0.000197796904776018 2.40640265189351e-07 3.6775779760824e-05 -6.455027707232e-06 -8.44918184229348e-06 3.62292448997795e-07 2.40640265189351e-07 7.38614342400589e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 902 0 0 0 0 0 2184 +1073 1133 0.992445978542175 0.0166428206528088 0.121548328644138 -0.038836833654034 -0.00785283602467448 0.997341794579668 -0.0724408569177414 0.00706423197117484 -0.122430848407721 0.0709391380362459 0.989938546604202 -0.00790619123229369 5.68279808663319e-05 4.02882581164227e-05 -9.99611024145346e-06 2.77855020259586e-06 9.21068046785986e-06 3.1684833459322e-05 4.02882581164227e-05 0.000121246306905215 9.12724524502839e-07 1.06489442009372e-05 -7.20007463255923e-06 2.01679841629593e-05 -9.99611024145346e-06 9.12724524502839e-07 1.66484994551597e-05 -3.80899438152819e-06 -3.6832038572703e-06 -2.8782369188605e-06 2.77855020259586e-06 1.06489442009372e-05 -3.80899438152819e-06 3.27797664941201e-05 -2.74609851723576e-05 -2.17327748728101e-06 9.21068046785986e-06 -7.20007463255923e-06 -3.6832038572703e-06 -2.74609851723576e-05 0.000113956277986316 7.49525349019475e-06 3.1684833459322e-05 2.01679841629593e-05 -2.8782369188605e-06 -2.17327748728101e-06 7.49525349019475e-06 6.81968784710439e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 790 0 0 0 0 0 2267 +1073 1113 0.992907176657812 0.017208473326358 0.117640158904981 -0.0367929125151132 -0.00769481669780485 0.996696454073405 -0.0808515196733405 -0.00514554396962119 -0.11864286045692 0.0793728346682756 0.989759478246772 0.00148811397404676 5.59082696946138e-05 5.66988387818197e-06 -1.54083524688722e-05 2.76638650804469e-06 1.43212400166132e-06 1.67313358247948e-05 5.66988387818197e-06 0.000144161408050658 1.39767317240707e-05 1.30968445492784e-05 -1.11994293344018e-05 -3.15268499606462e-05 -1.54083524688722e-05 1.39767317240707e-05 2.37736409116205e-05 -7.85434434214203e-06 -2.71052135315611e-06 -4.56964932710641e-06 2.76638650804469e-06 1.30968445492784e-05 -7.85434434214203e-06 3.19489124939026e-05 -1.20076772046855e-05 -1.06864397609331e-05 1.43212400166132e-06 -1.11994293344018e-05 -2.71052135315611e-06 -1.20076772046855e-05 7.42199158050321e-05 6.93943405660342e-06 1.67313358247948e-05 -3.15268499606462e-05 -4.56964932710641e-06 -1.06864397609331e-05 6.93943405660342e-06 6.04330006505153e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 744 0 0 0 0 0 2336 +1073 1114 0.992164405483963 0.0183710250941739 0.123581139044933 -0.0305667028313704 -0.00727763752245518 0.995948969761422 -0.0896252510359371 -0.0171251265523364 -0.124727015849597 0.0880236051758403 0.988278815137258 0.0100595439974711 6.32524903913122e-05 3.12136109010652e-05 -9.72381768981208e-06 7.6165173477138e-06 -9.43152784028407e-06 3.74675228611405e-05 3.12136109010652e-05 0.000103809166877277 1.13457939232886e-06 5.14956144020662e-06 1.62098908525041e-05 3.96821001592852e-06 -9.72381768981208e-06 1.13457939232886e-06 1.65271054288177e-05 -6.39842836857321e-06 -2.13338540680131e-06 -4.5942267597603e-06 7.6165173477138e-06 5.14956144020662e-06 -6.39842836857321e-06 2.29029650524763e-05 -3.51951041902924e-06 5.26048273151629e-06 -9.43152784028407e-06 1.62098908525041e-05 -2.13338540680131e-06 -3.51951041902924e-06 6.83715427711036e-05 -1.60859385347742e-05 3.74675228611405e-05 3.96821001592852e-06 -4.5942267597603e-06 5.26048273151629e-06 -1.60859385347742e-05 6.3795786929616e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 828 0 0 0 0 0 2307 +1073 1101 0.992339733357493 0.0164316891592742 0.122441223414959 -0.0418408367576035 -0.00701570657925048 0.997011051553683 -0.0769398657460039 0.0128882644457864 -0.123339504868362 0.0754914741622671 0.989488960962999 0.000844957490873095 8.17361727266688e-05 1.97345900666151e-05 -1.5831577802457e-05 1.0525918259304e-05 -1.52423696159821e-05 5.94516721674409e-05 1.97345900666151e-05 8.34996792403036e-05 1.57699713330887e-06 6.74520473910708e-06 2.16223283437965e-06 -1.72935269647001e-06 -1.5831577802457e-05 1.57699713330887e-06 1.76393776203343e-05 -6.82131336946054e-06 -4.2327312349561e-06 -8.43936401402224e-06 1.0525918259304e-05 6.74520473910708e-06 -6.82131336946054e-06 2.54410576738841e-05 -9.62786499511326e-06 5.94407792636298e-06 -1.52423696159821e-05 2.16223283437965e-06 -4.2327312349561e-06 -9.62786499511326e-06 9.50957368250918e-05 -2.38296961937724e-05 5.94516721674409e-05 -1.72935269647001e-06 -8.43936401402224e-06 5.94407792636298e-06 -2.38296961937724e-05 8.24958332129913e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 724 0 0 0 0 0 2374 +1073 1115 0.992054286597979 0.0178138139626951 0.124543006526571 -0.0301843250412733 -0.00633084736937829 0.995739316292653 -0.0919952953178857 -0.0188372611198728 -0.125651155244035 0.0904758643017123 0.987940233599532 0.00918607287478229 7.293585018597e-05 1.8507268102341e-05 -1.09978191540069e-05 6.54586458644524e-06 -1.81402112097046e-06 2.69709708427922e-05 1.8507268102341e-05 7.7203588635379e-05 3.78506433145473e-06 -1.21664916141599e-06 8.708777922502e-06 -4.39417025626212e-06 -1.09978191540069e-05 3.78506433145473e-06 1.85053729636701e-05 -3.77603637630936e-06 -1.37373244997526e-06 -3.91921888486316e-06 6.54586458644524e-06 -1.21664916141599e-06 -3.77603637630936e-06 2.06923915897551e-05 -3.93177522757416e-06 1.8497700033998e-06 -1.81402112097046e-06 8.708777922502e-06 -1.37373244997526e-06 -3.93177522757416e-06 6.24723251342218e-05 -1.46702486105556e-05 2.69709708427922e-05 -4.39417025626212e-06 -3.91921888486316e-06 1.8497700033998e-06 -1.46702486105556e-05 6.00800988160172e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 802 0 0 0 0 0 2304 +1073 1128 0.992557729372779 0.0175268186757186 0.120507113854168 -0.0346070414857331 -0.00807874419564275 0.996885427999368 -0.0784485648991699 -0.000263380852452782 -0.121506739543838 0.0768911833022902 0.989607931544508 -0.00369861693116889 4.89854792790145e-05 9.26795897596725e-06 -1.03311837674327e-05 2.91684101383796e-06 5.11370898704806e-06 2.49082891547104e-05 9.26795897596725e-06 0.000121544205767491 1.23352049950779e-05 8.61617645633721e-06 -1.02181064570807e-05 -1.76877432410777e-05 -1.03311837674327e-05 1.23352049950779e-05 2.03935158623936e-05 -6.49042141217257e-06 -5.64072788372272e-06 -4.53264582476718e-06 2.91684101383796e-06 8.61617645633721e-06 -6.49042141217257e-06 3.35459377476274e-05 -1.5967474386293e-05 -7.05066761556571e-06 5.11370898704806e-06 -1.02181064570807e-05 -5.64072788372272e-06 -1.5967474386293e-05 8.30601477390965e-05 3.23966792151999e-06 2.49082891547104e-05 -1.76877432410777e-05 -4.53264582476718e-06 -7.05066761556571e-06 3.23966792151999e-06 5.6725205113113e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 815 0 0 0 0 0 2386 +1073 1129 0.991327358348837 0.0171707597571126 0.130289038673561 -0.0294067192588673 -0.00656813226545109 0.996661911520666 -0.081375019278134 -0.0144991554211423 -0.131251393240837 0.0798135272578318 0.988130999735866 -0.00357579252496345 5.94077920215789e-05 1.88287757759803e-05 -1.02875463230599e-05 3.75465900523782e-06 -1.65900934926629e-06 2.8147999687445e-05 1.88287757759803e-05 8.76229911742466e-05 4.17833892667321e-06 3.11414469345335e-06 1.54363444087329e-05 -1.41797747353674e-05 -1.02875463230599e-05 4.17833892667321e-06 1.7367373115525e-05 -3.73418053314393e-06 -2.52485659880509e-06 -3.61270167609231e-06 3.75465900523782e-06 3.11414469345335e-06 -3.73418053314393e-06 2.56352897803784e-05 -1.36325652209422e-05 -2.61889884180292e-06 -1.65900934926629e-06 1.54363444087329e-05 -2.52485659880509e-06 -1.36325652209422e-05 9.16365696626416e-05 -1.14149741798597e-05 2.8147999687445e-05 -1.41797747353674e-05 -3.61270167609231e-06 -2.61889884180292e-06 -1.14149741798597e-05 6.52342082610859e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 903 0 0 0 0 0 2289 +1073 1099 0.991467326057158 0.017961396177859 0.129112081574155 -0.03633737676603 -0.00703035869124231 0.996388042678383 -0.084625306287265 0.00288965630691122 -0.130165722898702 0.0829955218965634 0.988012463447388 0.00325822916020362 8.94033805718696e-05 2.93386659844422e-05 -1.60154470410864e-05 1.35500244500639e-05 -1.10215945520652e-05 4.60293955960027e-05 2.93386659844422e-05 0.000154503967216872 5.15332753946964e-06 2.13919711263255e-05 -7.70529917230833e-06 -2.96507394845592e-05 -1.60154470410864e-05 5.15332753946964e-06 2.0880985123521e-05 -9.48769885697553e-06 -7.51556646946543e-07 -7.82403850086945e-06 1.35500244500639e-05 2.13919711263255e-05 -9.48769885697553e-06 3.6203752938034e-05 -1.07768955364189e-05 6.41597813289655e-06 -1.10215945520652e-05 -7.70529917230833e-06 -7.51556646946543e-07 -1.07768955364189e-05 7.97044983579616e-05 -2.48827395266733e-05 4.60293955960027e-05 -2.96507394845592e-05 -7.82403850086945e-06 6.41597813289655e-06 -2.48827395266733e-05 9.51788709691834e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 716 0 0 0 0 0 2276 +1073 1125 0.99145788578718 0.0181005298357689 0.129165132795503 -0.0263312400323325 -0.00682752616409083 0.996168262265803 -0.0871904704701715 -0.025269464480642 -0.130248399594368 0.0855638011894963 0.987782461035379 0.00154887091683365 7.11294806101653e-05 5.30828968217033e-05 -1.56581525102439e-05 1.90464443424759e-05 -1.52630701854023e-05 3.15622148836309e-05 5.30828968217033e-05 0.000128774541516623 -2.75975646098676e-06 1.97729805457429e-05 -1.36167901001737e-05 1.10141177540364e-05 -1.56581525102439e-05 -2.75975646098676e-06 1.93328922943973e-05 -8.06753996970546e-06 -3.46904615250905e-06 -5.19762584101908e-06 1.90464443424759e-05 1.97729805457429e-05 -8.06753996970546e-06 3.87095021040222e-05 -3.42770265209568e-05 5.83781349109508e-06 -1.52630701854023e-05 -1.36167901001737e-05 -3.46904615250905e-06 -3.42770265209568e-05 0.000147186571464985 -1.04565900651571e-05 3.15622148836309e-05 1.10141177540364e-05 -5.19762584101908e-06 5.83781349109508e-06 -1.04565900651571e-05 6.17194824432704e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 890 0 0 0 0 0 2277 +1073 1100 0.991343070428095 0.0171668770796512 0.130169946783154 -0.036865875485403 -0.00629558855738504 0.996490241574996 -0.0834719354664891 0.00380767627061929 -0.131146034171504 0.0819298283724417 0.9879717713295 0.00474260595034696 0.000117441897389984 5.10987151406807e-05 -2.3476742243988e-05 2.06079312700661e-05 -1.78396841454558e-05 6.47468917163387e-05 5.10987151406807e-05 0.000121493859376664 -1.76906064525535e-06 1.1719604215559e-05 -9.04339383783378e-06 1.37944287623455e-05 -2.3476742243988e-05 -1.76906064525535e-06 2.14624390272641e-05 -8.25778035374622e-06 -3.70365480617717e-06 -1.10435521484536e-05 2.06079312700661e-05 1.1719604215559e-05 -8.25778035374622e-06 2.90073792052053e-05 -6.65242866556489e-06 1.14405821269759e-05 -1.78396841454558e-05 -9.04339383783378e-06 -3.70365480617717e-06 -6.65242866556489e-06 7.53876463321556e-05 -1.71170837070091e-05 6.47468917163387e-05 1.37944287623455e-05 -1.10435521484536e-05 1.14405821269759e-05 -1.71170837070091e-05 8.45514595992566e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 710 0 0 0 0 0 2286 +1073 1116 0.991969265671572 0.0170850906629112 0.12531989323345 -0.0327538257088479 -0.0068725568821515 0.996651638332412 -0.0814756391274115 -0.00945936697740218 -0.126292295588071 0.0799600618206283 0.988765212064389 -0.000234471404855087 4.3690637581217e-05 1.70794683951661e-05 -2.6454506145797e-07 -4.03121314799317e-06 -7.88974674917881e-06 9.34904966631077e-06 1.70794683951661e-05 8.1918809328895e-05 1.13547859148796e-05 -3.76217446791515e-06 1.86599357000269e-06 -1.48185501105396e-05 -2.6454506145797e-07 1.13547859148796e-05 1.77278704104489e-05 -3.32934713132449e-06 -5.3446450762779e-07 -1.50594896824566e-06 -4.03121314799317e-06 -3.76217446791515e-06 -3.32934713132449e-06 2.02333866023854e-05 -5.96048610717251e-06 1.38971479440575e-06 -7.88974674917881e-06 1.86599357000269e-06 -5.3446450762779e-07 -5.96048610717251e-06 7.23163221378172e-05 -1.8624463460948e-05 9.34904966631077e-06 -1.48185501105396e-05 -1.50594896824566e-06 1.38971479440575e-06 -1.8624463460948e-05 5.69051329746717e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 768 0 0 0 0 0 2313 +1073 1117 0.991795871633545 0.0167307026270932 0.126732129313209 -0.0312532860348769 -0.00670967057115108 0.996844869109752 -0.0790903739426513 -0.0110126155969575 -0.127655510384326 0.0775911755238027 0.988778883345185 -0.00155951978949935 4.6202026399302e-05 3.4969744740821e-05 8.37945146440708e-07 5.38423154439311e-07 -6.48766231458945e-06 1.8188275528288e-05 3.4969744740821e-05 9.1500861773575e-05 8.62954570573955e-06 1.05839122615014e-05 -2.72381167994913e-05 -5.46325560381359e-07 8.37945146440708e-07 8.62954570573955e-06 1.65270532680084e-05 -5.32882700212407e-07 -4.99093583542534e-06 2.06117922635329e-07 5.38423154439311e-07 1.05839122615014e-05 -5.32882700212407e-07 2.50568840579148e-05 -2.02825339631244e-05 -4.64941917118624e-07 -6.48766231458945e-06 -2.72381167994913e-05 -4.99093583542534e-06 -2.02825339631244e-05 9.9959683379254e-05 -7.85261006360999e-06 1.8188275528288e-05 -5.46325560381359e-07 2.06117922635329e-07 -4.64941917118624e-07 -7.85261006360999e-06 5.00045683798708e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 774 0 0 0 0 0 2301 +1073 1122 0.991776140463336 0.0172387964678466 0.126818417842166 -0.0299700717341246 -0.00643817383448279 0.996352661016898 -0.0850877476621888 -0.0166856081508026 -0.127822678446851 0.0835715189576419 0.98826978305207 0.00137575065350223 0.000114781487907777 5.22206666216665e-05 -1.87053827092365e-05 1.90056828667371e-05 -2.92247549677678e-05 6.04924672834066e-05 5.22206666216665e-05 0.000142395481332816 -8.74154649122391e-07 1.33278210674887e-05 1.04759820511329e-05 1.97667658470291e-05 -1.87053827092365e-05 -8.74154649122391e-07 2.1211706433189e-05 -8.34968925281699e-06 1.22245737682078e-06 -9.75778979644116e-06 1.90056828667371e-05 1.33278210674887e-05 -8.34968925281699e-06 3.67628089439347e-05 -3.34310545240839e-05 1.0537738944306e-05 -2.92247549677678e-05 1.04759820511329e-05 1.22245737682078e-06 -3.34310545240839e-05 0.000140302263990562 -1.85952968466914e-05 6.04924672834066e-05 1.97667658470291e-05 -9.75778979644116e-06 1.0537738944306e-05 -1.85952968466914e-05 7.58776390943023e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 907 0 0 0 0 0 2262 +1073 1124 0.991892333144781 0.0173154405772772 0.125895889393645 -0.0304593066493574 -0.00666164017091966 0.996396352644759 -0.0845572645397975 -0.0138784377710215 -0.126906351294312 0.0830330292945819 0.988433252196287 0.000681773082921455 0.000112659930571949 4.9534965026244e-05 -2.1034217317648e-05 2.38077526018147e-05 -3.1988259616729e-05 7.37818054090858e-05 4.9534965026244e-05 8.29654212961198e-05 -3.17152980198647e-06 1.53640325090344e-05 -1.402315727726e-05 1.75449023385058e-05 -2.1034217317648e-05 -3.17152980198647e-06 1.92350625735265e-05 -5.75901000133829e-06 2.8124341953453e-07 -1.35393494453897e-05 2.38077526018147e-05 1.53640325090344e-05 -5.75901000133829e-06 3.28801135019305e-05 -3.13611683491358e-05 1.93068199915991e-05 -3.1988259616729e-05 -1.402315727726e-05 2.8124341953453e-07 -3.13611683491358e-05 0.000133518090253992 -4.11704181808463e-05 7.37818054090858e-05 1.75449023385058e-05 -1.35393494453897e-05 1.93068199915991e-05 -4.11704181808463e-05 9.65604024343973e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 900 0 0 0 0 0 2422 +1074 1139 0.995029834209583 0.0202810267106144 0.0974900455862748 -0.038522956724467 -0.013608494079282 0.997549553921987 -0.0686272275335277 0.0213001952979898 -0.0986429821211055 0.0669594461267996 0.992867561486751 -0.00370742853991617 9.35432509509469e-05 4.77137402432023e-05 -2.00951224563938e-05 1.61733927236414e-05 -3.30348876766074e-07 4.73948585665688e-05 4.77137402432023e-05 9.77223568066285e-05 -4.55308790840961e-06 1.26099494553144e-05 9.2786956180394e-07 7.66062527139304e-06 -2.00951224563938e-05 -4.55308790840961e-06 1.78578764354262e-05 -5.85787173316253e-06 -5.18395672253436e-06 -9.11926049437675e-06 1.61733927236414e-05 1.26099494553144e-05 -5.85787173316253e-06 3.67999432208148e-05 -3.04501546053159e-05 3.9616998700727e-06 -3.30348876766074e-07 9.2786956180394e-07 -5.18395672253436e-06 -3.04501546053159e-05 0.000130809649962452 5.95930849407025e-06 4.73948585665688e-05 7.66062527139304e-06 -9.11926049437675e-06 3.9616998700727e-06 5.95930849407025e-06 7.09389864409582e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 882 0 0 0 0 0 2386 +1074 1106 0.994341232913821 0.0196039236736657 0.104408805682369 -0.0338156095671841 -0.0120119628504605 0.997270401343272 -0.072852311927001 0.00459675217553391 -0.105552002709095 0.0711859029669989 0.991862562023022 0.00363313981502236 6.17297320265212e-05 2.29582166936668e-05 -1.1226423202567e-05 5.03826161725577e-06 -2.15753565314416e-06 1.54892304904762e-05 2.29582166936668e-05 0.000113357322824107 7.56108798398934e-06 7.98869646898947e-06 4.1260154566134e-07 -2.32585652649403e-05 -1.1226423202567e-05 7.56108798398934e-06 1.70477338916275e-05 -3.39996458121046e-06 -1.95575968631436e-06 -5.65572538617043e-06 5.03826161725577e-06 7.98869646898947e-06 -3.39996458121046e-06 2.23058367208425e-05 1.45353960888767e-07 5.01121729796496e-06 -2.15753565314416e-06 4.1260154566134e-07 -1.95575968631436e-06 1.45353960888767e-07 5.10648088001491e-05 -8.45714192055894e-06 1.54892304904762e-05 -2.32585652649403e-05 -5.65572538617043e-06 5.01121729796496e-06 -8.45714192055894e-06 4.96832538125481e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 776 0 0 0 0 0 2360 +1074 1105 0.994214413979616 0.0200273981785628 0.105530101664717 -0.0318518855969994 -0.0120743595411594 0.997074996045379 -0.0754696104586392 -0.000226477388075886 -0.106732885639053 0.073758766145491 0.991548150893266 -0.000149835327886926 6.39261208557721e-05 3.85729147062338e-05 -2.83843144790201e-06 1.47501872212176e-07 -1.59445215377341e-05 2.93683425835413e-05 3.85729147062338e-05 8.3909195199813e-05 2.58825493618365e-06 -3.12357341476048e-07 2.30284607524579e-06 1.14725888963043e-05 -2.83843144790201e-06 2.58825493618365e-06 1.44725994946129e-05 -3.90315741948206e-06 2.0612768298201e-06 9.8432717183198e-07 1.47501872212176e-07 -3.12357341476048e-07 -3.90315741948206e-06 2.56518493482406e-05 -6.24405150193725e-06 3.68394186103888e-06 -1.59445215377341e-05 2.30284607524579e-06 2.0612768298201e-06 -6.24405150193725e-06 7.57622192206181e-05 -1.35649478749026e-05 2.93683425835413e-05 1.14725888963043e-05 9.8432717183198e-07 3.68394186103888e-06 -1.35649478749026e-05 5.27370016379354e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 753 0 0 0 0 0 2357 +1074 1107 0.994306665773135 0.0200645708592006 0.104650214502161 -0.0315678970043935 -0.012542040628829 0.997322053935339 -0.0720514951341195 0.00564750236609476 -0.105815649201699 0.0703287546486738 0.991895616813377 4.46995316764243e-05 5.98318882778443e-05 -4.3763541660019e-06 -1.80429850648537e-05 1.00580411987912e-05 -1.57104542205882e-05 2.98232918683766e-05 -4.3763541660019e-06 9.8295266747844e-05 4.17936391534702e-06 5.18085649818881e-06 1.29998805475006e-05 -3.19893510420532e-05 -1.80429850648537e-05 4.17936391534702e-06 1.89305028550261e-05 -6.39573285635052e-06 -5.44213712760981e-07 -7.82569747028911e-06 1.00580411987912e-05 5.18085649818881e-06 -6.39573285635052e-06 2.26004518008311e-05 -4.7456833567546e-06 5.28096469029259e-06 -1.57104542205882e-05 1.29998805475006e-05 -5.44213712760981e-07 -4.7456833567546e-06 6.71546247947444e-05 -1.64201934137341e-05 2.98232918683766e-05 -3.19893510420532e-05 -7.82569747028911e-06 5.28096469029259e-06 -1.64201934137341e-05 5.58809190096067e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 685 0 0 0 0 0 2281 +1074 1108 0.994047167285617 0.0201188756256682 0.107076888519414 -0.0316069272878623 -0.0126492285691393 0.997467696585229 -0.0699870794187301 0.00401003515236744 -0.108213798695203 0.0682160180054278 0.991784426505799 -0.00153454540979254 5.59912267970798e-05 3.81626854728906e-06 -1.56485466208064e-05 7.09706777228271e-06 -1.50286729744197e-05 1.24597960843983e-05 3.81626854728906e-06 0.000121816313409368 8.64900931629543e-06 6.93057216563595e-06 -2.51800730510965e-06 -3.24672558649437e-05 -1.56485466208064e-05 8.64900931629543e-06 1.67801830892203e-05 -4.47171268279643e-06 1.09665466254736e-07 -5.31039341031708e-06 7.09706777228271e-06 6.93057216563595e-06 -4.47171268279643e-06 2.23164100666754e-05 -7.46446256614324e-06 6.63432745869138e-07 -1.50286729744197e-05 -2.51800730510965e-06 1.09665466254736e-07 -7.46446256614324e-06 7.82837470006372e-05 -7.49219606083824e-06 1.24597960843983e-05 -3.24672558649437e-05 -5.31039341031708e-06 6.63432745869138e-07 -7.49219606083824e-06 5.03312201683755e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 699 0 0 0 0 0 2291 +1074 1140 0.994179287589102 0.0189132272350596 0.106065234475675 -0.0364371239150984 -0.0116726071989985 0.997584505491781 -0.0684755769884097 0.0170106843505702 -0.10710412863192 0.0668389425280856 0.991998619652127 -0.00287181968232468 6.34620026662452e-05 4.13679890621285e-05 -1.08725614952033e-05 1.2064401648468e-06 3.11698121015902e-06 2.42070492944435e-05 4.13679890621285e-05 0.000123638250224547 3.47416220361297e-06 6.0937881267432e-06 3.81907421378235e-07 -1.14642977560818e-06 -1.08725614952033e-05 3.47416220361297e-06 1.64514424696277e-05 -2.72790433376151e-06 3.80230002287321e-07 -2.02232149428735e-06 1.2064401648468e-06 6.0937881267432e-06 -2.72790433376151e-06 2.88158649079962e-05 -2.12031065937935e-05 -4.9730469274692e-06 3.11698121015902e-06 3.81907421378235e-07 3.80230002287321e-07 -2.12031065937935e-05 9.62363465601259e-05 1.59637407320152e-05 2.42070492944435e-05 -1.14642977560818e-06 -2.02232149428735e-06 -4.9730469274692e-06 1.59637407320152e-05 6.00210452722288e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 845 0 0 0 0 0 2391 +1074 1110 0.994183200938097 0.0199985394721394 0.105829208593186 -0.0297001592580218 -0.0122929551536408 0.997258438331707 -0.0729691059955907 0.000948787953144038 -0.10699834683802 0.0712437056531063 0.991703427532014 0.00197008881183699 4.07423369193419e-05 1.38911199674042e-05 -1.19475843938623e-05 8.91463186869895e-06 -2.81114426667886e-06 6.40567437478008e-06 1.38911199674042e-05 8.87448946433995e-05 2.46888516385795e-06 7.71731984374161e-06 -3.08227320446482e-06 -2.11297686541875e-05 -1.19475843938623e-05 2.46888516385795e-06 1.57543550087241e-05 -5.84231406443815e-06 1.27731329167259e-06 -1.06891829763253e-06 8.91463186869895e-06 7.71731984374161e-06 -5.84231406443815e-06 2.89732970114872e-05 -1.55633160057734e-05 -2.26259513789231e-06 -2.81114426667886e-06 -3.08227320446482e-06 1.27731329167259e-06 -1.55633160057734e-05 8.47793082926383e-05 -3.76400558513745e-06 6.40567437478008e-06 -2.11297686541875e-05 -1.06891829763253e-06 -2.26259513789231e-06 -3.76400558513745e-06 4.52442403715684e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 752 0 0 0 0 0 2331 +1074 1136 0.994864644588259 0.0201564257822131 0.0991869822505141 -0.0318613398936743 -0.01319456594354 0.997435020330652 -0.0703511453179895 0.00384452184779975 -0.100350597296873 0.0686811380051134 0.992578792290306 -0.00449123007384608 6.3215911529332e-05 3.98029317954683e-05 -7.3844078021086e-06 8.05762123875821e-06 -1.27601683506699e-05 3.08410721464915e-05 3.98029317954683e-05 9.80813169848162e-05 3.37983530027071e-06 1.72745176445155e-05 -2.93490551697679e-05 6.97828248513833e-06 -7.3844078021086e-06 3.37983530027071e-06 1.57714705488472e-05 -4.82478759540203e-06 -4.49863765861257e-07 -3.14724570396568e-06 8.05762123875821e-06 1.72745176445155e-05 -4.82478759540203e-06 3.59522072872033e-05 -3.09354110817122e-05 2.69651075225267e-06 -1.27601683506699e-05 -2.93490551697679e-05 -4.49863765861257e-07 -3.09354110817122e-05 0.000110139347333032 -1.75456843687633e-06 3.08410721464915e-05 6.97828248513833e-06 -3.14724570396568e-06 2.69651075225267e-06 -1.75456843687633e-06 6.27118943214011e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2369 +1074 1135 0.994625355859659 0.0197291159085025 0.101642331075763 -0.0329158334108408 -0.0126765652948445 0.997496502954684 -0.0695703333720776 0.00306896415090075 -0.102760430971127 0.0679079419408757 0.992385411646092 -0.00666175753933035 0.000103065569170316 4.24557104890458e-05 -1.61841340071537e-05 2.75382519542956e-05 -5.60193045463368e-05 6.48419281100234e-05 4.24557104890458e-05 8.57697346104881e-05 8.06658868476829e-07 6.89391283157254e-06 -8.85395780909204e-06 2.11770657035667e-05 -1.61841340071537e-05 8.06658868476829e-07 1.77705107838799e-05 -7.65936797200919e-06 4.47898366675278e-06 -8.26127065422069e-06 2.75382519542956e-05 6.89391283157254e-06 -7.65936797200919e-06 4.28710288345127e-05 -5.64437384434541e-05 2.27471151653398e-05 -5.60193045463368e-05 -8.85395780909204e-06 4.47898366675278e-06 -5.64437384434541e-05 0.000205311629508344 -5.90903202078964e-05 6.48419281100234e-05 2.11770657035667e-05 -8.26127065422069e-06 2.27471151653398e-05 -5.90903202078964e-05 9.35638992968563e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 873 0 0 0 0 0 2392 +1074 1104 0.994479004112094 0.0195323756729953 0.103101875253497 -0.0359267266231458 -0.011032563051988 0.996540232971861 -0.0823762503449485 -0.000567680553996473 -0.104354170653226 0.0807839734660205 0.991253830609657 0.00804913181089958 0.000232142734969534 0.000136193146958921 -1.03550907758905e-05 6.52547639241925e-05 -0.000184014865139765 0.000196316654575326 0.000136193146958921 0.000137962427261302 -2.27141809005883e-06 3.73202523640948e-05 -8.28648841700116e-05 0.000101101195412693 -1.03550907758905e-05 -2.27141809005883e-06 1.67861488572085e-05 -1.31235115430007e-05 1.35845089978431e-05 -1.33126713946951e-05 6.52547639241925e-05 3.73202523640948e-05 -1.31235115430007e-05 6.23787868326732e-05 -8.51350491476206e-05 7.01118892507763e-05 -0.000184014865139765 -8.28648841700116e-05 1.35845089978431e-05 -8.51350491476206e-05 0.000284375974130463 -0.000174730337762723 0.000196316654575326 0.000101101195412693 -1.33126713946951e-05 7.01118892507763e-05 -0.000174730337762723 0.000215005176746399 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 675 0 0 0 0 0 2384 +1074 1137 0.994770014169655 0.0196773098542062 0.100226854613953 -0.0337865831394673 -0.0127363660593106 0.997505710909978 -0.0694272401985244 0.00792701954039591 -0.101343001181671 0.0677876108067096 0.992539387597595 -0.00277850584753936 9.55238998648152e-05 5.23050123507615e-05 -1.55837087722861e-05 2.50789666720926e-05 -4.51717551454672e-05 5.76680527308787e-05 5.23050123507615e-05 0.000124141782192646 7.02966799480213e-06 2.14367028833617e-05 -4.83771814142596e-05 1.91557683650508e-05 -1.55837087722861e-05 7.02966799480213e-06 1.98577846280417e-05 -8.75491049355636e-06 -2.88849449180565e-06 -8.48605612542453e-06 2.50789666720926e-05 2.14367028833617e-05 -8.75491049355636e-06 3.85165517873206e-05 -4.1439993703785e-05 1.51172476092994e-05 -4.51717551454672e-05 -4.83771814142596e-05 -2.88849449180565e-06 -4.1439993703785e-05 0.000162924192500173 -3.38383507274487e-05 5.76680527308787e-05 1.91557683650508e-05 -8.48605612542453e-06 1.51172476092994e-05 -3.38383507274487e-05 8.05448549861312e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 891 0 0 0 0 0 2339 +1074 1134 0.994500094452515 0.0197943951850118 0.102848160183832 -0.0350245630053349 -0.0127082214694819 0.99752856360186 -0.0691032988032623 0.0135124016854062 -0.103961835502372 0.0674162199894798 0.992293802278996 -0.0072857128886116 5.53379687451579e-05 1.76901868866982e-05 -1.16379125771481e-05 1.09399994893414e-05 -1.24501754847466e-05 1.88967663386324e-05 1.76901868866982e-05 7.0067215099643e-05 9.7152229451671e-07 3.83407227076278e-06 -1.53849280968025e-06 5.49408607269724e-06 -1.16379125771481e-05 9.7152229451671e-07 1.60125405915197e-05 -3.46367588351811e-06 -2.23221618779669e-06 -3.93864527086099e-06 1.09399994893414e-05 3.83407227076278e-06 -3.46367588351811e-06 3.16699081766266e-05 -2.94801490500305e-05 7.36494639725835e-06 -1.24501754847466e-05 -1.53849280968025e-06 -2.23221618779669e-06 -2.94801490500305e-05 0.00012743456522319 -1.29113090537671e-05 1.88967663386324e-05 5.49408607269724e-06 -3.93864527086099e-06 7.36494639725835e-06 -1.29113090537671e-05 5.35029967821641e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 792 0 0 0 0 0 2413 +1074 1133 0.994800598275943 0.0203533193316888 0.0997873341762768 -0.0338824250386385 -0.0135789472001501 0.997585867686416 -0.0681032215484355 0.00425211853015762 -0.100932560964048 0.0663941185988794 0.992675394654626 -0.00493622042560334 6.61749412837012e-05 3.81318029490264e-05 -1.11852194017195e-05 1.56153598596225e-05 -2.60547365393994e-05 2.35198360975729e-05 3.81318029490264e-05 8.16696654604326e-05 -2.58170532557464e-06 1.63631163516543e-05 -2.34651016415723e-05 1.00410002475201e-05 -1.11852194017195e-05 -2.58170532557464e-06 1.53383582115036e-05 -5.59387931274965e-06 8.39676425898157e-07 -5.08076750252461e-07 1.56153598596225e-05 1.63631163516543e-05 -5.59387931274965e-06 4.26816380838302e-05 -5.35999606631219e-05 1.12755822410377e-06 -2.60547365393994e-05 -2.34651016415723e-05 8.39676425898157e-07 -5.35999606631219e-05 0.000167306108475277 -3.72532215246896e-06 2.35198360975729e-05 1.00410002475201e-05 -5.08076750252461e-07 1.12755822410377e-06 -3.72532215246896e-06 4.35321240411518e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 788 0 0 0 0 0 2304 +1074 1132 0.995106970800214 0.0193977184826789 0.0968805717493943 -0.0389942798160104 -0.0130464775245832 0.997749792393834 -0.0657658057219885 0.0149992380415051 -0.0979382769351358 0.0641800615123461 0.993120845423782 -0.00752546085071385 5.73878423560633e-05 2.6256031089399e-05 -9.81336842358034e-06 8.24051807867421e-06 -1.29484510180904e-05 2.99031394985287e-05 2.6256031089399e-05 8.83686109872839e-05 5.7503919055353e-06 9.78242124917581e-06 -1.58259836683271e-05 5.1564801669948e-06 -9.81336842358034e-06 5.7503919055353e-06 1.64774147634077e-05 -4.45539885266153e-06 -1.80514600120893e-06 -3.7384380782497e-06 8.24051807867421e-06 9.78242124917581e-06 -4.45539885266153e-06 3.34622161851721e-05 -3.46536879561232e-05 1.90084024240564e-06 -1.29484510180904e-05 -1.58259836683271e-05 -1.80514600120893e-06 -3.46536879561232e-05 0.000130616354441578 -5.33374710875607e-06 2.99031394985287e-05 5.1564801669948e-06 -3.7384380782497e-06 1.90084024240564e-06 -5.33374710875607e-06 6.4759958439197e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 886 0 0 0 0 0 2254 +1074 1112 0.993887621190133 0.0203186801692049 0.108510587876023 -0.0263702834683247 -0.0117492343900824 0.99680248503358 -0.0790364556526078 -0.0151087288456676 -0.109769540111387 0.0772784385651088 0.990948379582243 0.00140735125240535 3.91232384717855e-05 1.05898261292843e-05 -8.58475013410278e-06 6.63507624007463e-06 -5.54220433954776e-07 1.2916240660979e-05 1.05898261292843e-05 9.42326760756934e-05 5.40362517652866e-06 2.62233578202125e-06 8.18020829159295e-06 -1.5999225368637e-05 -8.58475013410278e-06 5.40362517652866e-06 1.44185915861648e-05 -3.11452822394743e-06 4.65515731556222e-07 -5.36147966257857e-06 6.63507624007463e-06 2.62233578202125e-06 -3.11452822394743e-06 2.21485537955754e-05 -4.65196297049814e-06 3.56001266060218e-06 -5.54220433954776e-07 8.18020829159295e-06 4.65515731556222e-07 -4.65196297049814e-06 6.5238050166594e-05 -8.33457396824763e-06 1.2916240660979e-05 -1.5999225368637e-05 -5.36147966257857e-06 3.56001266060218e-06 -8.33457396824763e-06 4.6419362005654e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 756 0 0 0 0 0 2404 +1074 1103 0.994303409975744 0.0186108076003523 0.104949353266567 -0.0387219023775378 -0.0115918284103215 0.99767909701162 -0.0670973091873584 0.0154768655066326 -0.105954511110729 0.065498528430347 0.992211461508456 -0.00942679163287183 5.41259050082522e-05 5.16593749870602e-05 -2.10817238827884e-06 1.14945756133038e-05 -2.32777259109361e-05 1.97393506034248e-05 5.16593749870602e-05 8.2608351508291e-05 -3.40216185230248e-06 1.86431407434332e-05 -2.65834808030954e-05 2.00279843238429e-05 -2.10817238827884e-06 -3.40216185230248e-06 1.29041413501996e-05 -1.89444686152686e-06 4.62910848118613e-06 1.50361363291432e-06 1.14945756133038e-05 1.86431407434332e-05 -1.89444686152686e-06 3.12063524942787e-05 -2.11658309485746e-05 1.06334135506957e-05 -2.32777259109361e-05 -2.65834808030954e-05 4.62910848118613e-06 -2.11658309485746e-05 9.1574120918835e-05 -1.13445376641274e-05 1.97393506034248e-05 2.00279843238429e-05 1.50361363291432e-06 1.06334135506957e-05 -1.13445376641274e-05 5.01427803825036e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 604 0 0 0 0 0 2409 +1074 1109 0.995063615768783 0.0208479476835767 0.0970245517925129 -0.0323829675446117 -0.0136706293061776 0.997160114904502 -0.0740595647976291 0.000305355473828419 -0.0982930031463494 0.0723675916486379 0.992522754001866 0.0033474203958866 5.67347830334739e-05 1.34732994898561e-05 -1.40565632398602e-05 6.33204615322523e-06 -1.58073274551343e-06 1.76534787322376e-05 1.34732994898561e-05 0.000116849655314941 5.72535966703502e-06 9.15384081585921e-06 4.26711321516761e-06 -3.06215641020898e-05 -1.40565632398602e-05 5.72535966703502e-06 1.78062923603315e-05 -5.48495677867763e-06 6.13593000801153e-07 -5.01737899685139e-06 6.33204615322523e-06 9.15384081585921e-06 -5.48495677867763e-06 2.62619259857581e-05 -9.46067090310554e-06 1.64671453245675e-06 -1.58073274551343e-06 4.26711321516761e-06 6.13593000801153e-07 -9.46067090310554e-06 6.98901159151261e-05 -1.26617256472014e-05 1.76534787322376e-05 -3.06215641020898e-05 -5.01737899685139e-06 1.64671453245675e-06 -1.26617256472014e-05 6.25424254215304e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 806 0 0 0 0 0 2270 +1074 1114 0.99533816127171 0.0203695063171919 0.0942710344095411 -0.0342171180570163 -0.013646441208883 0.997353030537249 -0.0714192349475855 -0.000867831972905211 -0.0954762764176709 0.0697998258633917 0.992981502824124 0.00308330220369913 8.34145097529505e-05 3.54263152972468e-05 -1.39849276420947e-05 1.41126769933509e-05 -2.2101584330905e-05 4.65595240664261e-05 3.54263152972468e-05 0.000114208324332775 4.36189302599766e-06 1.73293720948262e-05 -2.63113001025239e-05 4.50424689371218e-07 -1.39849276420947e-05 4.36189302599766e-06 1.80280610434501e-05 -6.66890439805208e-06 -4.89911905830506e-06 -6.39937747981869e-06 1.41126769933509e-05 1.73293720948262e-05 -6.66890439805208e-06 3.23771750583248e-05 -2.3309479806072e-05 1.19510303090683e-05 -2.2101584330905e-05 -2.63113001025239e-05 -4.89911905830506e-06 -2.3309479806072e-05 0.000100775086870058 -2.62174841842657e-05 4.65595240664261e-05 4.50424689371218e-07 -6.39937747981869e-06 1.19510303090683e-05 -2.62174841842657e-05 7.97248655150863e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 822 0 0 0 0 0 2351 +1074 1113 0.995111127440896 0.0206908496671303 0.0965698337130179 -0.0305237641620524 -0.0130480628981579 0.996780234143687 -0.0791132913931744 -0.00914352536712483 -0.097895822678567 0.0774664673294698 0.992177078117399 0.00417886643904379 4.88427953834456e-05 1.27712380323018e-05 -1.20165337848647e-05 4.52272071683086e-06 4.33757520813277e-06 1.94505888355601e-05 1.27712380323018e-05 0.000159967917107263 1.06372096328188e-05 1.31751768706316e-05 -7.73859508000555e-07 -1.41110599831488e-05 -1.20165337848647e-05 1.06372096328188e-05 1.81819725145483e-05 -3.16698512160108e-06 -3.33844172095585e-06 -5.63009512671241e-06 4.52272071683086e-06 1.31751768706316e-05 -3.16698512160108e-06 2.47991801731466e-05 -8.24207521895619e-06 -3.73929716560764e-07 4.33757520813277e-06 -7.73859508000555e-07 -3.33844172095585e-06 -8.24207521895619e-06 7.52947231011642e-05 -2.89361125010693e-06 1.94505888355601e-05 -1.41110599831488e-05 -5.63009512671241e-06 -3.73929716560764e-07 -2.89361125010693e-06 5.69701548113201e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 729 0 0 0 0 0 2405 +1074 1127 0.994649010143505 0.0206982938235021 0.101217228046131 -0.032749872301888 -0.0132779249821418 0.997211025673187 -0.0734429505398475 0.00628946996063966 -0.102455079565218 0.0717060032955808 0.992149789982671 -0.00570230561475911 6.07365319782942e-05 7.57095130263955e-06 -1.2649546530092e-05 1.61142737332114e-06 -4.78554819950315e-06 3.42768434956096e-05 7.57095130263955e-06 0.000131200059577758 1.28418766611044e-05 -5.01518198863284e-07 2.98295342522301e-05 -1.56579707177431e-05 -1.2649546530092e-05 1.28418766611044e-05 1.94093860145328e-05 -5.49877769072199e-06 -9.49739889268201e-07 -5.44648070821922e-06 1.61142737332114e-06 -5.01518198863284e-07 -5.49877769072199e-06 3.68491561328552e-05 -4.8520062796354e-05 1.23647187937545e-06 -4.78554819950315e-06 2.98295342522301e-05 -9.49739889268201e-07 -4.8520062796354e-05 0.000195955995505655 -1.25417947845296e-05 3.42768434956096e-05 -1.56579707177431e-05 -5.44648070821922e-06 1.23647187937545e-06 -1.25417947845296e-05 6.41712791378857e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 814 0 0 0 0 0 2449 +1074 1102 0.994481361727371 0.0200795623744874 0.102973940158289 -0.0351317312437119 -0.0127719960872699 0.997384590231432 -0.0711396885347803 0.0101690366106532 -0.104133074922527 0.0694319115661369 0.992136841551331 -0.000318449183648081 7.14584702855583e-05 1.23429655871977e-05 -1.26049678142886e-05 4.49342274461052e-06 -9.50427476783362e-06 2.30093030683577e-05 1.23429655871977e-05 0.000100500769837581 9.38225811402657e-06 2.31218265998143e-06 -7.81736498020439e-06 -1.57162039967296e-05 -1.26049678142886e-05 9.38225811402657e-06 1.59613289566354e-05 -3.27575046196459e-06 -2.21778552489712e-06 -2.87380610919956e-06 4.49342274461052e-06 2.31218265998143e-06 -3.27575046196459e-06 2.0109506634874e-05 -5.15750914951041e-06 -2.64374818485927e-06 -9.50427476783362e-06 -7.81736498020439e-06 -2.21778552489712e-06 -5.15750914951041e-06 6.29610384424413e-05 -6.05864715786991e-06 2.30093030683577e-05 -1.57162039967296e-05 -2.87380610919956e-06 -2.64374818485927e-06 -6.05864715786991e-06 5.08537038119065e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 652 0 0 0 0 0 2296 +1074 1126 0.994292159316444 0.0204778644033276 0.1047079700468 -0.028396917875017 -0.0127557244152898 0.997184519350207 -0.0738940177750434 -0.0055583429026506 -0.105926358459468 0.0721366164841142 0.99175395897659 -0.00621456068904746 5.30394288189181e-05 2.31803439072892e-05 -8.27918814641215e-06 6.91000093029155e-07 6.57233407122038e-06 3.23551564237786e-05 2.31803439072892e-05 0.00010018971229589 7.37103844531352e-06 1.34767422065796e-05 -1.60734736676164e-05 3.01928074137225e-06 -8.27918814641215e-06 7.37103844531352e-06 1.95011697086713e-05 -4.00045497433628e-06 -7.95713848330725e-06 -4.90637800298693e-06 6.91000093029155e-07 1.34767422065796e-05 -4.00045497433628e-06 3.05917297586269e-05 -2.17280655682416e-05 2.14122867169215e-07 6.57233407122038e-06 -1.60734736676164e-05 -7.95713848330725e-06 -2.17280655682416e-05 9.62870168943142e-05 6.4889898168774e-06 3.23551564237786e-05 3.01928074137225e-06 -4.90637800298693e-06 2.14122867169215e-07 6.4889898168774e-06 5.66582303683113e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 820 0 0 0 0 0 2390 +1074 1101 0.99427797621911 0.0198026938997413 0.104972183553285 -0.0357846944283099 -0.0124073750009796 0.997424653448224 -0.070640765421071 0.0138046130045865 -0.106100721256815 0.0689341280354141 0.991963065310791 -0.00108606986633805 4.55383499766153e-05 7.66724527524647e-06 -1.20777204473614e-05 4.85497446616198e-06 -2.91274970110441e-06 1.88438258107995e-05 7.66724527524647e-06 8.8894907611594e-05 7.88124507410655e-06 -3.41122462504279e-06 8.34250508455538e-06 -2.75068711043437e-05 -1.20777204473614e-05 7.88124507410655e-06 1.7810106946183e-05 -6.80701865848253e-06 -1.9034501598187e-06 -3.68548626682369e-06 4.85497446616198e-06 -3.41122462504279e-06 -6.80701865848253e-06 2.34358723124719e-05 2.8166144140714e-06 3.67548989974541e-06 -2.91274970110441e-06 8.34250508455538e-06 -1.9034501598187e-06 2.8166144140714e-06 5.57024907821362e-05 -6.53121776909294e-06 1.88438258107995e-05 -2.75068711043437e-05 -3.68548626682369e-06 3.67548989974541e-06 -6.53121776909294e-06 5.22737186183147e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 713 0 0 0 0 0 2376 +1074 1128 0.994442042432456 0.0203626196060422 0.10329756998858 -0.0302556767236976 -0.0127676147058793 0.997201619840283 -0.0736608267849151 -0.00116913092845703 -0.104508431513865 0.0719325594615865 0.991919197632457 -0.0042615100261988 8.24576545571353e-05 2.29099712295739e-05 -1.30055054138895e-05 -2.20169298854115e-06 6.75604725908032e-06 4.36636572684033e-05 2.29099712295739e-05 0.000111726307376147 1.0005375174904e-05 8.02848553265894e-06 -7.21907107647984e-06 -4.97348063058524e-06 -1.30055054138895e-05 1.0005375174904e-05 1.74989945167525e-05 -2.71194491600437e-06 -3.47241942971394e-06 -5.04359628052982e-06 -2.20169298854115e-06 8.02848553265894e-06 -2.71194491600437e-06 3.18458481523088e-05 -2.80164391862785e-05 -6.79095561681888e-06 6.75604725908032e-06 -7.21907107647984e-06 -3.47241942971394e-06 -2.80164391862785e-05 0.000114890815764456 3.14141286103448e-06 4.36636572684033e-05 -4.97348063058524e-06 -5.04359628052982e-06 -6.79095561681888e-06 3.14141286103448e-06 6.57432718448389e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 817 0 0 0 0 0 2435 +1074 1129 0.994613606684593 0.0201612382503695 0.101672503018652 -0.0340538737978249 -0.013033137149763 0.997441344850012 -0.0702915423065588 0.008618967231577 -0.10282952267662 0.0685878127367473 0.992331497640827 -0.004658308816341 0.000105828990650221 6.07604989193305e-05 -1.33807788504151e-05 2.2435803223146e-05 -4.74143988989286e-05 5.91063199853415e-05 6.07604989193305e-05 9.86542212844575e-05 -1.94931368754651e-06 2.00090730182371e-05 -4.34201847125079e-05 2.36909075223805e-05 -1.33807788504151e-05 -1.94931368754651e-06 1.60138689231667e-05 -4.76676245953183e-06 1.29318403891402e-06 -3.51211265032268e-06 2.2435803223146e-05 2.00090730182371e-05 -4.76676245953183e-06 5.12056166705591e-05 -7.5701239265362e-05 1.08381448138021e-05 -4.74143988989286e-05 -4.34201847125079e-05 1.29318403891402e-06 -7.5701239265362e-05 0.000233702610420573 -2.85115915060229e-05 5.91063199853415e-05 2.36909075223805e-05 -3.51211265032268e-06 1.08381448138021e-05 -2.85115915060229e-05 7.76829434726369e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 888 0 0 0 0 0 2327 +1074 1125 0.99421355869823 0.0203856972470921 0.10546953611518 -0.0281920583746332 -0.0126503638989897 0.99721515428114 -0.073497648705688 -0.0087990728764424 -0.106674120543947 0.0717381308635198 0.991702713814167 -0.00357400051612106 0.000104845380887428 4.88101392420807e-05 -2.16425234286196e-05 2.56400103027146e-05 -3.18410012702178e-05 5.40104175941621e-05 4.88101392420807e-05 0.0001071812096968 6.18639851343029e-07 7.38290237553981e-06 -5.17875261200283e-06 1.15343850527904e-05 -2.16425234286196e-05 6.18639851343029e-07 1.8902955479648e-05 -7.43236816058755e-06 7.42114834033503e-07 -1.05149866360504e-05 2.56400103027146e-05 7.38290237553981e-06 -7.43236816058755e-06 3.61002423425751e-05 -4.27236463648219e-05 1.58477083526339e-05 -3.18410012702178e-05 -5.17875261200283e-06 7.42114834033503e-07 -4.27236463648219e-05 0.000177444448700901 -2.99045927855578e-05 5.40104175941621e-05 1.15343850527904e-05 -1.05149866360504e-05 1.58477083526339e-05 -2.99045927855578e-05 8.42216854378874e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 897 0 0 0 0 0 2315 +1074 1124 0.99429729629061 0.0194848525245749 0.104848591365252 -0.0339004872663785 -0.0123752046346124 0.997606051034246 -0.0680369109389085 0.00759997280865068 -0.105923278364264 0.0663513938207259 0.99215812834377 -0.0133933142325753 0.000146660267043545 0.00013484738605436 -2.39700978452655e-05 3.91556008513378e-05 -2.7052431568405e-05 -0.00017088825393835 0.00013484738605436 0.000438167181885593 -5.95519066301836e-06 0.000108127135997898 -3.47370460091008e-05 -0.000464426366002401 -2.39700978452655e-05 -5.95519066301836e-06 1.90062799895059e-05 -6.72094116585896e-06 8.78649562908321e-07 1.9384825503819e-05 3.91556008513378e-05 0.000108127135997898 -6.72094116585896e-06 6.27521942328636e-05 -4.16700689964512e-05 -0.000132945506235727 -2.7052431568405e-05 -3.47370460091008e-05 8.78649562908321e-07 -4.16700689964512e-05 0.000132267820614745 4.93011058528179e-05 -0.00017088825393835 -0.000464426366002401 1.9384825503819e-05 -0.000132945506235727 4.93011058528179e-05 0.000684389960761633 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 890 0 0 0 0 0 2393 +1074 1115 0.995083268518176 0.0200233666932742 0.0969966674760033 -0.0335094364781902 -0.0130171804910606 0.997295605228352 -0.0723327643898517 -0.00364672493359569 -0.0981826956609301 0.0707145004824422 0.992652818307726 0.0029268233187282 6.26290448463294e-05 3.41709534447988e-05 -1.01428096757558e-05 1.06444560474084e-05 -1.36028426872371e-05 2.75339916915758e-05 3.41709534447988e-05 9.55117269999801e-05 3.13404041492545e-06 7.48940693697874e-06 -7.40962622802037e-06 6.62147075359215e-06 -1.01428096757558e-05 3.13404041492545e-06 1.65611127097974e-05 -4.28926947633517e-06 6.42522929885882e-07 -3.09558276676561e-06 1.06444560474084e-05 7.48940693697874e-06 -4.28926947633517e-06 2.84010907862397e-05 -2.23440052713975e-05 1.13970142875082e-05 -1.36028426872371e-05 -7.40962622802037e-06 6.42522929885882e-07 -2.23440052713975e-05 9.91347167825566e-05 -2.73199079410473e-05 2.75339916915758e-05 6.62147075359215e-06 -3.09558276676561e-06 1.13970142875082e-05 -2.73199079410473e-05 6.45195314307948e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2366 +1074 1117 0.99437597118296 0.0196745130444696 0.10406412191725 -0.0279198905596986 -0.011998617193417 0.997195003557354 -0.0738793480324181 -0.00878057243935752 -0.105225762622045 0.0722152228876455 0.991822817071626 -0.000152204348692262 6.64523396462029e-05 3.50363998972432e-05 -5.51012177023464e-06 5.01563078842265e-06 -1.11842031646827e-05 3.3272501170491e-05 3.50363998972432e-05 8.56586699478708e-05 5.29096616251641e-06 5.08620771018135e-06 -1.01005353757804e-05 1.00299545988638e-05 -5.51012177023464e-06 5.29096616251641e-06 1.41439770424469e-05 -6.46790504969004e-07 -1.54259662325133e-07 -1.2805918554336e-06 5.01563078842265e-06 5.08620771018135e-06 -6.46790504969004e-07 2.1115451418632e-05 -1.25915221616392e-05 4.16632774277986e-06 -1.11842031646827e-05 -1.01005353757804e-05 -1.54259662325133e-07 -1.25915221616392e-05 7.89027999128722e-05 -2.00663620217756e-05 3.3272501170491e-05 1.00299545988638e-05 -1.2805918554336e-06 4.16632774277986e-06 -2.00663620217756e-05 6.31970088961081e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 777 0 0 0 0 0 2355 +1074 1100 0.994661486928704 0.0209087625700774 0.101051224973115 -0.036419749291033 -0.0135660794117597 0.997253460499891 -0.072811379676437 0.0124307884802293 -0.102296079642247 0.0710518062316544 0.992213259799045 0.000467074103045142 5.76143324566744e-05 -5.58624898379691e-06 -1.74731691478708e-05 8.91442395383878e-06 -1.01924509985158e-05 2.48739530290723e-05 -5.58624898379691e-06 0.000134313990861963 1.08877024515793e-05 1.09439462925634e-05 -6.51488752384231e-07 -3.98316871738024e-05 -1.74731691478708e-05 1.08877024515793e-05 2.00659994084703e-05 -6.47851927854706e-06 -1.36193845549351e-06 -7.69134376185006e-06 8.91442395383878e-06 1.09439462925634e-05 -6.47851927854706e-06 2.53236879599032e-05 -2.88954563927002e-06 2.68552542823725e-06 -1.01924509985158e-05 -6.51488752384231e-07 -1.36193845549351e-06 -2.88954563927002e-06 6.31814189139618e-05 -1.3492077063069e-05 2.48739530290723e-05 -3.98316871738024e-05 -7.69134376185006e-06 2.68552542823725e-06 -1.3492077063069e-05 5.94953417279981e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 723 0 0 0 0 0 2350 +1075 1077 0.998674173748354 0.0118220126127971 0.0501012445536561 -0.0222086194891162 -0.0113226582904509 0.999883472951683 -0.0102390393747959 0.0200693209480519 -0.050216452456143 0.00965818491559379 0.998691657803777 -0.00016701343298756 5.47921134980584e-05 2.57181577424636e-05 -1.31303813059525e-05 1.13034030617467e-05 -9.12950383262094e-06 2.35845712599382e-05 2.57181577424636e-05 7.92484215972531e-05 7.03092381018705e-07 5.3318869752655e-06 6.56128214637073e-06 -1.256210008624e-06 -1.31303813059525e-05 7.03092381018705e-07 1.97668412013893e-05 -8.22562785853838e-06 -5.5432675011702e-06 -6.80674613109642e-06 1.13034030617467e-05 5.3318869752655e-06 -8.22562785853838e-06 3.15385347486184e-05 -1.97696116437774e-05 6.72896309664192e-06 -9.12950383262094e-06 6.56128214637073e-06 -5.5432675011702e-06 -1.97696116437774e-05 0.000104884674690662 -2.00465383128556e-06 2.35845712599382e-05 -1.256210008624e-06 -6.80674613109642e-06 6.72896309664192e-06 -2.00465383128556e-06 3.89887390785022e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 952 0 0 0 0 0 2263 +1075 1079 0.998235407318306 0.00427995999077145 0.0592262907713598 -0.0188494365481417 -0.00266471648272089 0.999623062796302 -0.0273245605967693 0.00729696687493534 -0.0593209142050507 0.0271185226038809 0.997870540135172 -0.00128848484907962 3.44483655228416e-05 1.81061620488765e-05 -5.83647998000984e-06 1.8747665602039e-06 6.0356136677309e-06 2.30172627541375e-06 1.81061620488765e-05 4.54595404397282e-05 -6.55738801711425e-07 -2.44252329422489e-06 6.69409997004981e-06 -7.62241404004462e-06 -5.83647998000984e-06 -6.55738801711425e-07 1.62803919073757e-05 -3.73797545180539e-06 -2.08812327407865e-06 -1.36952053157505e-06 1.8747665602039e-06 -2.44252329422489e-06 -3.73797545180539e-06 2.16540130406299e-05 -5.50100489409282e-06 -4.13740783765003e-06 6.0356136677309e-06 6.69409997004981e-06 -2.08812327407865e-06 -5.50100489409282e-06 5.83874523517554e-05 5.8147801208801e-06 2.30172627541375e-06 -7.62241404004462e-06 -1.36952053157505e-06 -4.13740783765003e-06 5.8147801208801e-06 4.43257518358828e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 945 0 0 0 0 0 2118 +1074 1122 0.994774428654564 0.0199826244741153 0.100122578942572 -0.0319245462432154 -0.0129945301386962 0.997464625769055 -0.0699675819638942 -0.000105520405492466 -0.101266866651731 0.0683009155028411 0.992511968018529 -0.00731726867276044 7.61148304548923e-05 3.05349959261834e-05 -1.63852569693534e-05 1.50760407871582e-05 -1.22514973090508e-05 3.4223526478735e-05 3.05349959261834e-05 9.75942642118549e-05 3.50065126948667e-06 9.22399384745644e-06 -5.02145589834268e-06 1.12836326801752e-05 -1.63852569693534e-05 3.50065126948667e-06 1.90958020314419e-05 -5.97727984235288e-06 -3.03071447502841e-06 -4.07952207985264e-06 1.50760407871582e-05 9.22399384745644e-06 -5.97727984235288e-06 3.99107953783549e-05 -4.79463375540671e-05 5.77750470575748e-06 -1.22514973090508e-05 -5.02145589834268e-06 -3.03071447502841e-06 -4.79463375540671e-05 0.000188204468771316 -2.5183854946822e-06 3.4223526478735e-05 1.12836326801752e-05 -4.07952207985264e-06 5.77750470575748e-06 -2.5183854946822e-06 6.48903809570568e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 892 0 0 0 0 0 2313 +1074 1116 0.994670264329797 0.0203100758411821 0.101086923374969 -0.0289328154636163 -0.0124527461801535 0.996894254148509 -0.0777610130995056 -0.0117732318235391 -0.102352305155595 0.076087757655317 0.991833987502103 0.00368797598296672 4.29631388119501e-05 2.64774609397358e-05 1.77368019982226e-06 -2.74581163460343e-06 1.59606364342411e-06 1.03468115029765e-05 2.64774609397358e-05 0.000101523899146292 1.08412982811526e-05 2.84253315437308e-06 -5.57084986545544e-06 -3.424249648526e-06 1.77368019982226e-06 1.08412982811526e-05 1.50246492450825e-05 -2.12942794967197e-07 3.22908506341839e-07 1.73778132016602e-06 -2.74581163460343e-06 2.84253315437308e-06 -2.12942794967197e-07 2.24512614361918e-05 -1.52012672726869e-05 -1.73391460876624e-06 1.59606364342411e-06 -5.57084986545544e-06 3.22908506341839e-07 -1.52012672726869e-05 8.10259479358573e-05 -1.32162296956629e-05 1.03468115029765e-05 -3.424249648526e-06 1.73778132016602e-06 -1.73391460876624e-06 -1.32162296956629e-05 5.45375141754394e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 765 0 0 0 0 0 2372 +1075 1140 0.996668544588053 0.0274648648088927 0.0767951393628602 -0.0218631974567991 -0.0223925608966248 0.997558523775491 -0.0661480525741557 0.00128036147986705 -0.0784243931772687 0.0642080434516702 0.994850210690477 -0.000654236418146198 7.59601730284505e-05 2.6264660252782e-05 -1.31557063814604e-05 7.54072043236859e-06 -1.07097015412306e-05 3.21681727877061e-05 2.6264660252782e-05 9.48831817793131e-05 6.14805396419091e-06 8.37403268349276e-06 -2.04200701039371e-05 -1.48203261554976e-05 -1.31557063814604e-05 6.14805396419091e-06 1.68313017053426e-05 -4.10349667708981e-06 -1.27069447270852e-06 -6.16909892270156e-06 7.54072043236859e-06 8.37403268349276e-06 -4.10349667708981e-06 3.20145519887952e-05 -2.11176506895874e-05 4.50657745444536e-06 -1.07097015412306e-05 -2.04200701039371e-05 -1.27069447270852e-06 -2.11176506895874e-05 0.000105823319714688 7.53500248114577e-06 3.21681727877061e-05 -1.48203261554976e-05 -6.16909892270156e-06 4.50657745444536e-06 7.53500248114577e-06 6.06132134218376e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 869 0 0 0 0 0 2376 +1075 1135 0.9972081185395 0.0283041923826271 0.0691002244025073 -0.0235677535472942 -0.0239306133953789 0.99770628226032 -0.0633206133957356 0.00123097955054919 -0.0707339668153183 0.0614902189934183 0.99559814127323 -0.00502098719139417 5.09204963117073e-05 1.24367269840877e-05 -1.15635717607481e-05 4.5103550316848e-06 -4.29195238685256e-08 9.9226932655626e-06 1.24367269840877e-05 0.000170793313619388 1.84593497111821e-05 2.38385689771097e-05 -4.11645766563302e-05 -3.47329082449656e-05 -1.15635717607481e-05 1.84593497111821e-05 2.26163616577765e-05 -6.75444601144038e-06 -5.42474090910456e-06 -2.83616723553834e-06 4.5103550316848e-06 2.38385689771097e-05 -6.75444601144038e-06 4.4535798143442e-05 -4.27263491371154e-05 -6.33139293649693e-06 -4.29195238685256e-08 -4.11645766563302e-05 -5.42474090910456e-06 -4.27263491371154e-05 0.000143232316169855 1.25948901765144e-05 9.9226932655626e-06 -3.47329082449656e-05 -2.83616723553834e-06 -6.33139293649693e-06 1.25948901765144e-05 5.66628324647208e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 881 0 0 0 0 0 2368 +1075 1107 0.997188413114143 0.0274269355935706 0.0697354426016181 -0.0256550197115663 -0.0230940099391115 0.997796593550048 -0.0621982685036522 0.00354173277560567 -0.0712876949818807 0.0604129216630542 0.995624599656067 -0.00183635306025682 0.000109183080386288 3.18424551250271e-05 -1.73840842546318e-05 1.54096331456392e-05 -1.46013245113313e-05 5.40193701347533e-05 3.18424551250271e-05 0.000106683988266572 1.55582903220238e-06 2.23289197629967e-06 8.43520022928793e-06 -1.93647235261092e-05 -1.73840842546318e-05 1.55582903220238e-06 1.84915151287655e-05 -6.05338026831096e-06 -6.87178357808659e-06 -7.78318652361397e-06 1.54096331456392e-05 2.23289197629967e-06 -6.05338026831096e-06 2.74152728031621e-05 1.32558671281681e-06 1.17691757339391e-05 -1.46013245113313e-05 8.43520022928793e-06 -6.87178357808659e-06 1.32558671281681e-06 8.28798653214858e-05 -2.02335515940584e-05 5.40193701347533e-05 -1.93647235261092e-05 -7.78318652361397e-06 1.17691757339391e-05 -2.02335515940584e-05 8.07728535672078e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 693 0 0 0 0 0 2259 +1075 1106 0.996781859699404 0.0274110040658669 0.0753296822660205 -0.0217073472119861 -0.0222911461877611 0.997437236476357 -0.0679857638924734 -0.0068075932022028 -0.0770001881545392 0.0660877912061548 0.994838366207123 0.00019210359252113 7.44575289998633e-05 5.60558932470539e-06 -1.36577760283902e-05 4.55465713746878e-06 -1.02596665848374e-05 1.94212919483413e-05 5.60558932470539e-06 0.000110068963405507 8.54368899643191e-06 6.93138376502668e-06 -3.92544396936844e-06 -3.95619023157524e-05 -1.36577760283902e-05 8.54368899643191e-06 1.81353046988033e-05 -2.83347165303743e-06 -7.39070745846641e-07 -4.06019780795414e-06 4.55465713746878e-06 6.93138376502668e-06 -2.83347165303743e-06 2.31665369256296e-05 -1.92755032290517e-06 -5.04992803710023e-07 -1.02596665848374e-05 -3.92544396936844e-06 -7.39070745846641e-07 -1.92755032290517e-06 5.61478160444036e-05 -8.70538998956756e-06 1.94212919483413e-05 -3.95619023157524e-05 -4.06019780795414e-06 -5.04992803710023e-07 -8.70538998956756e-06 5.72114869992384e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2409 +1075 1108 0.997182144890439 0.0271581719108869 0.0699299907776511 -0.0265016576242989 -0.0230902790756648 0.998029919296838 -0.058336259740872 0.00707868112891151 -0.0713765292229285 0.0565571736104738 0.99584470535786 -0.00430614007357373 6.99954138082446e-05 -1.87151309702887e-05 -2.16561063554038e-05 6.37083349916089e-06 -7.66225306690754e-06 3.08586384082198e-05 -1.87151309702887e-05 0.000144493348339937 1.21336861674957e-05 1.61019925929557e-05 -4.62936373532677e-06 -6.19817129841162e-05 -2.16561063554038e-05 1.21336861674957e-05 2.06863592460318e-05 -4.89115403921951e-06 -6.54993290924444e-06 -1.28795814958857e-05 6.37083349916089e-06 1.61019925929557e-05 -4.89115403921951e-06 2.90057256594798e-05 -5.39578815370255e-06 -1.97955909873661e-06 -7.66225306690754e-06 -4.62936373532677e-06 -6.54993290924444e-06 -5.39578815370255e-06 7.59008395112944e-05 -3.86615989052908e-06 3.08586384082198e-05 -6.19817129841162e-05 -1.28795814958857e-05 -1.97955909873661e-06 -3.86615989052908e-06 8.48383120990463e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 731 0 0 0 0 0 2338 +1075 1105 0.997364212297998 0.0267987099689923 0.0674274215078121 -0.0255656097814435 -0.0221984308448691 0.997433334804928 -0.0680732861550381 -0.00397978977036306 -0.0690786341441396 0.0663970764711668 0.995399201597461 0.00337554618875611 5.68629970186651e-05 2.79029599644374e-05 -3.60119594265193e-06 -2.60750499152383e-06 4.89027110373133e-06 1.87744175564458e-05 2.79029599644374e-05 9.57333943278334e-05 9.46695693530868e-06 1.05926245687556e-06 4.31762840359817e-06 -9.64830336639726e-06 -3.60119594265193e-06 9.46695693530868e-06 1.83328991602695e-05 -6.11703574170185e-06 -3.43007933861371e-06 2.27283229973178e-06 -2.60750499152383e-06 1.05926245687556e-06 -6.11703574170185e-06 2.58530120030126e-05 -1.44478923404081e-06 -1.830406032581e-06 4.89027110373133e-06 4.31762840359817e-06 -3.43007933861371e-06 -1.44478923404081e-06 6.98715396036142e-05 6.22495895744671e-06 1.87744175564458e-05 -9.64830336639726e-06 2.27283229973178e-06 -1.830406032581e-06 6.22495895744671e-06 5.39257935410218e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 770 0 0 0 0 0 2343 +1075 1137 0.996825763252723 0.0278837613244533 0.0745713991422156 -0.0227971130985052 -0.0232443479963626 0.997782102052075 -0.0623744908657906 0.00347746922788128 -0.0761452428051201 0.0604431359125544 0.995263045289639 -0.00147788721436828 8.93841914691152e-05 4.77969363720289e-05 -1.27972644171012e-05 1.36779235277628e-05 -3.95588854558566e-06 4.9348794960599e-05 4.77969363720289e-05 0.000153405540377119 1.04791904288216e-05 2.21804042286958e-05 -3.02223269171053e-05 -3.53975395029447e-06 -1.27972644171012e-05 1.04791904288216e-05 1.94579010560274e-05 -6.25022282870105e-06 -7.51589667845789e-06 -7.03647703851447e-06 1.36779235277628e-05 2.21804042286958e-05 -6.25022282870105e-06 4.05991194812678e-05 -4.2722598441877e-05 5.00849160891556e-06 -3.95588854558566e-06 -3.02223269171053e-05 -7.51589667845789e-06 -4.2722598441877e-05 0.000157992583803833 3.27243202441867e-06 4.9348794960599e-05 -3.53975395029447e-06 -7.03647703851447e-06 5.00849160891556e-06 3.27243202441867e-06 7.19764162261001e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 887 0 0 0 0 0 2360 +1075 1109 0.996986829103729 0.027812730474716 0.0724134974796301 -0.0206947526875214 -0.0231971483026562 0.997691913628925 -0.0638180052185812 -0.00346299962697052 -0.0740213138515939 0.0619459240224495 0.995330873424857 0.000495270028379672 6.03792709458094e-05 -8.01254010587707e-06 -1.84227198338279e-05 6.31028978506582e-06 2.02490731097723e-06 1.206901296137e-05 -8.01254010587707e-06 0.000154024113981166 1.54797942900449e-05 1.6254459409983e-05 -2.54729791789378e-05 -5.6456998575498e-05 -1.84227198338279e-05 1.54797942900449e-05 1.94360448742249e-05 -4.02080227140571e-06 -6.49715912540901e-06 -8.0736817208673e-06 6.31028978506582e-06 1.6254459409983e-05 -4.02080227140571e-06 2.9108842817104e-05 -1.00225490069519e-05 -2.73263607030241e-06 2.02490731097723e-06 -2.54729791789378e-05 -6.49715912540901e-06 -1.00225490069519e-05 8.86306688170422e-05 7.24438582573591e-06 1.206901296137e-05 -5.6456998575498e-05 -8.0736817208673e-06 -2.73263607030241e-06 7.24438582573591e-06 5.27628364943611e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 834 0 0 0 0 0 2310 +1075 1136 0.997344434030601 0.0276303951529506 0.067384279857192 -0.0280582839091719 -0.0239088705571169 0.998176667986492 -0.055422968127559 0.0209905765176999 -0.068792774452435 0.0536647067547862 0.996186555536692 -0.00683774536869296 0.000119342966222065 -0.000191707696144295 -1.77725392602129e-05 -2.68686985489978e-05 -2.04235630571285e-05 0.000148753609453362 -0.000191707696144295 0.000759435681460178 3.33700319306127e-05 0.000128876338334595 6.49731100667394e-06 -0.000430529033245078 -1.77725392602129e-05 3.33700319306127e-05 2.04023130873881e-05 -2.07067784000752e-06 -4.61985984244232e-06 -1.527838513167e-05 -2.68686985489978e-05 0.000128876338334595 -2.07067784000752e-06 5.84376632269326e-05 -3.37654011032769e-05 -7.54352356335197e-05 -2.04235630571285e-05 6.49731100667394e-06 -4.61985984244232e-06 -3.37654011032769e-05 0.00015330535416751 -1.77232810445047e-05 0.000148753609453362 -0.000430529033245078 -1.527838513167e-05 -7.54352356335197e-05 -1.77232810445047e-05 0.000315560593628126 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 800 0 0 0 0 0 2346 +1075 1133 0.997405237405829 0.0277968830017005 0.0664087772121401 -0.0291099176986354 -0.024279658085254 0.998288893863798 -0.0531957008738312 0.0168928699665296 -0.0677738194193381 0.0514452882544625 0.996373469998941 -0.00950073393428452 0.000115381714067512 9.35184722221153e-05 -1.14020382554489e-05 2.01968797213865e-05 -3.88088285972786e-05 2.5263855849288e-05 9.35184722221153e-05 0.000159825379172339 1.32259296263573e-06 2.44757175260849e-05 -4.74477318334529e-05 1.03209189000169e-05 -1.14020382554489e-05 1.32259296263573e-06 1.68813167434052e-05 -2.44269168796795e-06 -2.26216344047474e-06 1.13900724057287e-06 2.01968797213865e-05 2.44757175260849e-05 -2.44269168796795e-06 5.41072048047852e-05 -9.01153638140496e-05 -1.71312994744001e-06 -3.88088285972786e-05 -4.74477318334529e-05 -2.26216344047474e-06 -9.01153638140496e-05 0.000301712392285931 2.29547939090605e-06 2.5263855849288e-05 1.03209189000169e-05 1.13900724057287e-06 -1.71312994744001e-06 2.29547939090605e-06 5.44659566385283e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 770 0 0 0 0 0 2304 +1075 1104 0.997511482542638 0.0275833854311528 0.0648845054211279 -0.0265651960928905 -0.0234324303425517 0.997681949307091 -0.0638877862744052 0.001647337140015 -0.0664963412815275 0.0622083987493576 0.995845546117073 0.00277134779898666 0.000181931087404542 0.000106800836376183 6.01062502652598e-06 1.60018316144747e-05 -7.90836999635267e-05 0.00010650656673431 0.000106800836376183 0.000144267981794297 1.16539849578213e-05 9.50521759812805e-06 -3.44538133812504e-05 4.20174489939197e-05 6.01062502652598e-06 1.16539849578213e-05 1.95908223926341e-05 -8.40268083920422e-06 1.34610411803765e-06 2.53196700379854e-06 1.60018316144747e-05 9.50521759812805e-06 -8.40268083920422e-06 4.25950912586115e-05 -3.29482660450744e-05 1.54013541218753e-05 -7.90836999635267e-05 -3.44538133812504e-05 1.34610411803765e-06 -3.29482660450744e-05 0.000145139670439606 -5.31094507567253e-05 0.00010650656673431 4.20174489939197e-05 2.53196700379854e-06 1.54013541218753e-05 -5.31094507567253e-05 0.00010938037022647 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 693 0 0 0 0 0 2414 +1075 1112 0.996810046910763 0.0277862553121376 0.0748174738513041 -0.0243806916955605 -0.0233125081148667 0.997924981641094 -0.060018813567221 0.00526045803799674 -0.0763299242968061 0.0580831734011776 0.995389415065527 -0.00346067299986592 4.41318820212165e-05 -1.68636788682061e-06 -1.767274986099e-05 4.5283762427161e-06 5.49221371464387e-06 9.81845652284839e-06 -1.68636788682061e-06 0.0001539641821833 1.47477001797312e-05 1.16844163304234e-05 -4.13483366236164e-06 -3.99969069749409e-05 -1.767274986099e-05 1.47477001797312e-05 2.20661142618845e-05 -6.30071370597722e-06 -5.01029982443298e-06 -6.04886525009115e-06 4.5283762427161e-06 1.16844163304234e-05 -6.30071370597722e-06 2.67214161166577e-05 -8.00524692989046e-06 2.21796666277544e-07 5.49221371464387e-06 -4.13483366236164e-06 -5.01029982443298e-06 -8.00524692989046e-06 6.46153021451115e-05 -3.43828118401886e-06 9.81845652284839e-06 -3.99969069749409e-05 -6.04886525009115e-06 2.21796666277544e-07 -3.43828118401886e-06 4.28584574618441e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 756 0 0 0 0 0 2382 +1075 1111 0.996762895469174 0.0272131866716655 0.075651653564753 -0.0219373480602153 -0.0224161735546653 0.997726827512235 -0.0635507106611528 -0.00721468126631172 -0.0772091016595546 0.0616491697717294 0.995107096993776 -0.0014289416692058 0.000134624873506359 5.91531842361055e-05 -2.08970868817547e-05 3.1060453084365e-05 -5.25056108833994e-05 6.418802976023e-05 5.91531842361055e-05 0.00015172904699309 -2.29034412316729e-06 2.18817856874021e-05 -1.76879317748226e-05 -1.47527611168017e-05 -2.08970868817547e-05 -2.29034412316729e-06 1.86950026364727e-05 -6.0215265190977e-06 -8.49001365313686e-07 -9.65665055691536e-06 3.1060453084365e-05 2.18817856874021e-05 -6.0215265190977e-06 3.40101510797468e-05 -1.58214546008032e-05 1.3713669004622e-05 -5.25056108833994e-05 -1.76879317748226e-05 -8.49001365313686e-07 -1.58214546008032e-05 0.000104946860486297 -3.45298585571325e-05 6.418802976023e-05 -1.47527611168017e-05 -9.65665055691536e-06 1.3713669004622e-05 -3.45298585571325e-05 9.13556792875354e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 699 0 0 0 0 0 2369 +1075 1110 0.996307907661482 0.0272755125663239 0.0814039283170302 -0.020691504159163 -0.0225255959137922 0.998020994868846 -0.0587085285944627 0.00318673327134715 -0.0828441347346234 0.0566580992907687 0.994950606374421 -0.00725838962587621 4.56496481754701e-05 -8.68958439806803e-06 -1.65088372358426e-05 5.27055002847046e-06 5.92856805647119e-06 1.5305453221132e-05 -8.68958439806803e-06 0.000134046753287487 1.47743304992204e-05 5.62608936475573e-06 -6.49242670034731e-06 -4.24883731764482e-05 -1.65088372358426e-05 1.47743304992204e-05 2.04616053738709e-05 -6.52856060520566e-06 -6.71356829704931e-06 -7.19560495551851e-06 5.27055002847046e-06 5.62608936475573e-06 -6.52856060520566e-06 2.5491074647756e-05 -2.15570735310562e-06 -2.83256004618848e-07 5.92856805647119e-06 -6.49242670034731e-06 -6.71356829704931e-06 -2.15570735310562e-06 6.21342823329506e-05 1.96950736689196e-06 1.5305453221132e-05 -4.24883731764482e-05 -7.19560495551851e-06 -2.83256004618848e-07 1.96950736689196e-06 5.27996580183055e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 758 0 0 0 0 0 2310 +1075 1132 0.997229026202707 0.0279012811940787 0.0689622201392205 -0.0255024941545158 -0.0234397966881238 0.997630864250058 -0.0646779299831271 0.00231930526348294 -0.0706034363896035 0.0628822487146557 0.995520455624377 -0.00601422699677404 8.20157241763493e-05 3.65329291734825e-05 -1.52804334449632e-05 1.44403003673526e-05 -1.19552936955985e-05 3.70044080051834e-05 3.65329291734825e-05 9.72986327777658e-05 3.142021297808e-06 1.38211166349731e-05 -3.29395466844001e-05 3.75956238504849e-06 -1.52804334449632e-05 3.142021297808e-06 1.93265174816115e-05 -8.50126103055561e-06 -3.09518838450964e-06 -4.92028608114109e-06 1.44403003673526e-05 1.38211166349731e-05 -8.50126103055561e-06 5.18046315465007e-05 -6.18112698919803e-05 -1.42171567098261e-07 -1.19552936955985e-05 -3.29395466844001e-05 -3.09518838450964e-06 -6.18112698919803e-05 0.000199129247879894 4.82368833229231e-06 3.70044080051834e-05 3.75956238504849e-06 -4.92028608114109e-06 -1.42171567098261e-07 4.82368833229231e-06 6.67255309295244e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 886 0 0 0 0 0 2210 +1075 1129 0.996977257680677 0.0276246193115744 0.0726169957751493 -0.0241678535015229 -0.0232952497436846 0.997938245544175 -0.0598045936328767 0.00728240394930305 -0.0741193564927329 0.0579321887045945 0.995565257783235 -0.00777262134860165 6.44800074997029e-05 1.98480068793733e-05 -1.2695425756258e-05 1.99528338901023e-05 -4.07009193068102e-05 1.93825278257413e-05 1.98480068793733e-05 0.000140374135659 1.37716982155948e-05 1.19323366999913e-05 -4.0243994947714e-05 -2.39385672067278e-05 -1.2695425756258e-05 1.37716982155948e-05 2.1043888149719e-05 -7.65044489526796e-06 -1.10855126662354e-06 -2.53707974608145e-07 1.99528338901023e-05 1.19323366999913e-05 -7.65044489526796e-06 6.15641206592774e-05 -9.73008433981021e-05 4.85691270034036e-06 -4.07009193068102e-05 -4.0243994947714e-05 -1.10855126662354e-06 -9.73008433981021e-05 0.000284955050600259 -1.64902441915377e-05 1.93825278257413e-05 -2.39385672067278e-05 -2.53707974608145e-07 4.85691270034036e-06 -1.64902441915377e-05 5.78793592009861e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 885 0 0 0 0 0 2300 +1075 1115 0.996906258030685 0.0277129953246325 0.0735520400083844 -0.0191508869491301 -0.0224858379386119 0.997225132739436 -0.0709677513030633 -0.014477299324986 -0.0753146718206789 0.0690943161407062 0.994763125415087 0.00281893788434278 8.39279833816319e-05 -4.53834882150798e-06 -1.70811061052608e-05 8.21371391972304e-06 -1.14346053315147e-05 4.001303946912e-05 -4.53834882150798e-06 0.000116478292619737 1.1779385254132e-05 -7.73026301687809e-07 9.26726004287803e-06 -2.58338326824019e-05 -1.70811061052608e-05 1.1779385254132e-05 1.99554641727694e-05 -5.62905568813323e-06 -2.37733451202194e-06 -6.7708158400762e-06 8.21371391972304e-06 -7.73026301687809e-07 -5.62905568813323e-06 2.83889201955801e-05 -1.20184107844793e-05 1.13386441837122e-06 -1.14346053315147e-05 9.26726004287803e-06 -2.37733451202194e-06 -1.20184107844793e-05 9.59505209153939e-05 -1.73706846374998e-05 4.001303946912e-05 -2.58338326824019e-05 -6.7708158400762e-06 1.13386441837122e-06 -1.73706846374998e-05 7.35439867300577e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 797 0 0 0 0 0 2360 +1075 1124 0.997056831694455 0.0270235813614918 0.0717453860663776 -0.0270251890485302 -0.0228878926271366 0.998062700286429 -0.057853182004549 0.0109326236920411 -0.0731697939214223 0.0560408096601185 0.995743746608602 -0.00566500433157295 0.000154388613967155 6.68741718691787e-05 -1.65208050277174e-05 4.05627186214847e-05 -8.84759152232718e-05 8.64360966201094e-05 6.68741718691787e-05 0.000129969653646771 5.59880363420352e-06 2.3419348828045e-05 -4.30042182834096e-05 1.80955957842756e-05 -1.65208050277174e-05 5.59880363420352e-06 1.92870459271732e-05 -5.88589419832661e-06 -7.26201664802426e-06 -7.32998443601366e-06 4.05627186214847e-05 2.3419348828045e-05 -5.88589419832661e-06 5.88968328847999e-05 -0.000103764160307696 2.70799897826419e-05 -8.84759152232718e-05 -4.30042182834096e-05 -7.26201664802426e-06 -0.000103764160307696 0.000379825066186485 -6.36558130004985e-05 8.64360966201094e-05 1.80955957842756e-05 -7.32998443601366e-06 2.70799897826419e-05 -6.36558130004985e-05 9.58062296867907e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 882 0 0 0 0 0 2465 +1075 1114 0.996842758496537 0.027156255232272 0.0746126841413388 -0.0201762144322309 -0.022207908692181 0.997548058594431 -0.0663677601400124 -0.00946807007424768 -0.0762320380452683 0.0645012294165171 0.995001642098757 0.00276623509023555 0.000104839247817602 4.4099891643965e-05 -1.10830401670684e-05 1.34563331274328e-05 -2.58053859533032e-05 4.55422079662075e-05 4.4099891643965e-05 9.47170810175324e-05 2.78950113618909e-06 4.03597071041175e-06 -3.10289129188019e-06 4.89311701483451e-07 -1.10830401670684e-05 2.78950113618909e-06 1.64116770282378e-05 -5.51876812130327e-06 -2.16753392821083e-06 -3.89950222938323e-06 1.34563331274328e-05 4.03597071041175e-06 -5.51876812130327e-06 2.91376969958743e-05 -1.32835595417469e-05 8.15932064774052e-06 -2.58053859533032e-05 -3.10289129188019e-06 -2.16753392821083e-06 -1.32835595417469e-05 9.59401784206649e-05 -1.5914120346175e-05 4.55422079662075e-05 4.89311701483451e-07 -3.89950222938323e-06 8.15932064774052e-06 -1.5914120346175e-05 6.42962900818547e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 828 0 0 0 0 0 2357 +1075 1116 0.996652777471782 0.0269778205082819 0.0771714866929808 -0.0204901666241986 -0.0225972152467348 0.998113542864673 -0.0570852118610703 -0.00236545241558758 -0.0785659405905302 0.055150274258189 0.995382258345191 -0.00762469591404726 6.04814510578e-05 4.66143906193067e-05 1.762871906766e-06 2.37093834321532e-07 -2.10512942501709e-05 1.52907984384971e-05 4.66143906193067e-05 0.00013536018327559 1.47690953435928e-05 7.87128794212891e-06 -2.9438248939999e-05 -4.69732566415024e-07 1.762871906766e-06 1.47690953435928e-05 1.67797925487388e-05 -2.75602697418293e-06 2.45364523150972e-06 2.97855132695275e-06 2.37093834321532e-07 7.87128794212891e-06 -2.75602697418293e-06 3.14645976636438e-05 -2.2454929917333e-05 -8.95473234252319e-07 -2.10512942501709e-05 -2.9438248939999e-05 2.45364523150972e-06 -2.2454929917333e-05 0.000101285204517933 -2.28370143629129e-05 1.52907984384971e-05 -4.69732566415024e-07 2.97855132695275e-06 -8.95473234252319e-07 -2.28370143629129e-05 5.20289834916429e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 754 0 0 0 0 0 2358 +1075 1125 0.996312670120464 0.0270866220335897 0.0814087112306846 -0.0185905766158826 -0.0218491779629863 0.997675169716623 -0.0645512908720602 -0.0101005982379308 -0.0829679262111166 0.0625345555490485 0.994588232678484 -0.00721748199790138 6.86336181928792e-05 -1.47481021667173e-06 -1.53338881336535e-05 5.93196345434808e-06 -6.49908219576371e-06 3.69432619455887e-05 -1.47481021667173e-06 0.000130509222678416 1.39978028018768e-05 1.46838785967244e-05 -3.08171253965095e-05 -2.81778292775546e-05 -1.53338881336535e-05 1.39978028018768e-05 2.00416667760311e-05 -3.87905236473861e-06 -5.94761236680345e-06 -8.18811224834506e-06 5.93196345434808e-06 1.46838785967244e-05 -3.87905236473861e-06 3.78525850358882e-05 -3.95548588876348e-05 2.73586881343536e-06 -6.49908219576371e-06 -3.08171253965095e-05 -5.94761236680345e-06 -3.95548588876348e-05 0.000156643166350728 -3.98601479400447e-06 3.69432619455887e-05 -2.81778292775546e-05 -8.18811224834506e-06 2.73586881343536e-06 -3.98601479400447e-06 7.52395118812377e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 880 0 0 0 0 0 2346 +1075 1117 0.9964399919173 0.0269223168519129 0.0798907464176884 -0.0212648476381962 -0.0224058639946161 0.998128398988987 -0.0569005833918727 0.00100291323893677 -0.0812731183510572 0.0549079956564242 0.995178271590819 -0.00995041797281137 4.97882515224843e-05 1.79524792233463e-05 -4.80985988956981e-06 -5.20986781269562e-06 3.7168517899918e-06 1.45231075177877e-05 1.79524792233463e-05 0.000112885383244705 1.49239617159423e-05 4.38843820086544e-06 -2.11404151822448e-05 -1.08387496832687e-05 -4.80985988956981e-06 1.49239617159423e-05 1.92432276344688e-05 -2.57975112716984e-06 -7.64133040039871e-06 -6.8885814266256e-07 -5.20986781269562e-06 4.38843820086544e-06 -2.57975112716984e-06 2.99018621218754e-05 -2.28885311337959e-05 -8.28031387806457e-07 3.7168517899918e-06 -2.11404151822448e-05 -7.64133040039871e-06 -2.28885311337959e-05 0.000117997931814364 2.02011250191012e-07 1.45231075177877e-05 -1.08387496832687e-05 -6.8885814266256e-07 -8.28031387806457e-07 2.02011250191012e-07 4.6161678737377e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 769 0 0 0 0 0 2254 +1075 1113 0.996725128540711 0.0277253040434051 0.0759626595848495 -0.0224338072995166 -0.0231503442865429 0.997902196601589 -0.0604588089292054 -0.00182013850267996 -0.0774795437190844 0.0585022523790698 0.995276045512831 -0.00102527979076527 6.63964792423673e-05 -1.51495623202275e-05 -1.82834981566459e-05 3.26689810968571e-06 -8.65995705907175e-06 2.50341041101247e-05 -1.51495623202275e-05 0.000199943745125593 2.46169398653496e-05 1.46180636849732e-05 7.1302713586964e-06 -6.30410807281738e-05 -1.82834981566459e-05 2.46169398653496e-05 2.08163589672704e-05 -4.77866062890964e-06 -1.76452003054122e-06 -8.92783172503501e-06 3.26689810968571e-06 1.46180636849732e-05 -4.77866062890964e-06 2.64282238997987e-05 -5.57544768450547e-06 -3.85691544461445e-06 -8.65995705907175e-06 7.1302713586964e-06 -1.76452003054122e-06 -5.57544768450547e-06 6.87143939317912e-05 -1.2094794993349e-05 2.50341041101247e-05 -6.30410807281738e-05 -8.92783172503501e-06 -3.85691544461445e-06 -1.2094794993349e-05 6.14140687107841e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 738 0 0 0 0 0 2348 +1075 1122 0.996983314409207 0.0276554473898329 0.0725220450573518 -0.0204198988928746 -0.0228816081909602 0.997567138733533 -0.0658501004219945 -0.0096874395000748 -0.0741667229708025 0.0639920303526897 0.995190593431787 -0.00449419594909885 0.000107523130987602 3.10453276435272e-05 -1.50844554202466e-05 2.47942956987581e-05 -5.16571715246022e-05 5.45947624899022e-05 3.10453276435272e-05 0.000125254962903105 1.36665749121244e-05 1.40404733572581e-05 -2.98669282371105e-05 -7.29420440935961e-06 -1.50844554202466e-05 1.36665749121244e-05 2.21947148606464e-05 -6.03596355225542e-06 -3.45983425551757e-06 -6.23606959902895e-06 2.47942956987581e-05 1.40404733572581e-05 -6.03596355225542e-06 4.7483152665273e-05 -6.58389188415629e-05 1.21479027018638e-05 -5.16571715246022e-05 -2.98669282371105e-05 -3.45983425551757e-06 -6.58389188415629e-05 0.000237903431248527 -3.10307432303814e-05 5.45947624899022e-05 -7.29420440935961e-06 -6.23606959902895e-06 1.21479027018638e-05 -3.10307432303814e-05 7.92825233786943e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 895 0 0 0 0 0 2246 +1075 1103 0.996994584381964 0.0269241292263914 0.0726422052145693 -0.0300464076974076 -0.0224775423371593 0.997863177454424 -0.0613501358681568 0.0106345992642922 -0.0741387806988774 0.059532934968475 0.995469372130817 -0.0108750513975896 9.69122225847919e-05 7.73294033066026e-05 3.86414062502733e-06 1.42353737719523e-05 -4.47012336989465e-05 3.33934721805188e-05 7.73294033066026e-05 9.20471660803887e-05 4.41006079810369e-06 1.593098589264e-05 -4.15218779787889e-05 2.571661290717e-05 3.86414062502733e-06 4.41006079810369e-06 1.4050142232321e-05 -2.76234091160713e-06 -7.05610992617766e-07 3.03301112930688e-06 1.42353737719523e-05 1.593098589264e-05 -2.76234091160713e-06 3.50309133305078e-05 -2.83114610101695e-05 1.60340307031295e-05 -4.47012336989465e-05 -4.15218779787889e-05 -7.05610992617766e-07 -2.83114610101695e-05 0.000120065216447891 -3.33001410953811e-05 3.33934721805188e-05 2.571661290717e-05 3.03301112930688e-06 1.60340307031295e-05 -3.33001410953811e-05 5.34109461477239e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 623 0 0 0 0 0 2418 +1076 1139 0.998765253501572 0.0183630627897444 0.0461602244678345 -0.0207173155302324 -0.0160125003534752 0.998581198692854 -0.0507857209220474 0.0271394033179142 -0.0470273136631354 0.049983872820361 0.997642242603784 -0.00789878571342378 3.59680643119821e-05 5.36055960535146e-06 -1.21863121125238e-05 3.15922113550872e-06 3.06777210772121e-06 8.54917586814561e-06 5.36055960535146e-06 8.54425010382347e-05 6.95915986900992e-06 1.33074027667545e-06 -1.18892334110133e-05 -2.05225524626435e-05 -1.21863121125238e-05 6.95915986900992e-06 1.73072610229522e-05 -3.17885973367128e-06 -6.64903315395117e-06 -4.66657335157459e-06 3.15922113550872e-06 1.33074027667545e-06 -3.17885973367128e-06 2.51641122559657e-05 -1.29076773250052e-05 1.80785802078902e-06 3.06777210772121e-06 -1.18892334110133e-05 -6.64903315395117e-06 -1.29076773250052e-05 8.88339094070058e-05 2.22241232218369e-06 8.54917586814561e-06 -2.05225524626435e-05 -4.66657335157459e-06 1.80785802078902e-06 2.22241232218369e-06 4.59671364100456e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 903 0 0 0 0 0 2446 +1076 1140 0.998650790561586 0.017711830158816 0.0488148500268598 -0.0162198258521442 -0.0151048181587903 0.998466056908548 -0.0532670411219368 0.0150885226894005 -0.0496834276103153 0.0524578332941943 0.997386451054439 -0.00489297587186685 3.76952394001471e-05 8.52094176627643e-06 -9.0870899262579e-06 3.50779865250014e-06 -6.17345520430361e-06 3.44413071452587e-06 8.52094176627643e-06 7.71641479885181e-05 6.03880027337381e-06 1.73775504014497e-06 -1.44303338976048e-05 -1.9971742717772e-05 -9.0870899262579e-06 6.03880027337381e-06 1.4321478738845e-05 -2.6270410955249e-06 3.40414591435556e-07 -1.78477060486598e-06 3.50779865250014e-06 1.73775504014497e-06 -2.6270410955249e-06 2.797456233457e-05 -1.77882674857559e-05 -1.26896580070602e-06 -6.17345520430361e-06 -1.44303338976048e-05 3.40414591435556e-07 -1.77882674857559e-05 8.66007138909648e-05 7.33946671894776e-06 3.44413071452587e-06 -1.9971742717772e-05 -1.78477060486598e-06 -1.26896580070602e-06 7.33946671894776e-06 4.06641356482369e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 862 0 0 0 0 0 2448 +1076 1079 0.999463902910402 -0.00531939192498441 0.0323049663156424 -0.0129362295448648 0.00582360571120484 0.99986238149743 -0.01553395258165 0.0144253256004348 -0.0322178893726266 0.0157137562612171 0.999357336225905 -0.00330696029918552 0.000102017782927625 6.95175135156598e-05 -7.11760497731335e-06 2.17401661725985e-06 2.35168311602406e-05 4.48904536091137e-05 6.95175135156598e-05 9.23832370975251e-05 -1.62900027133903e-07 -5.09512930490482e-06 3.28602591729007e-05 1.89202509808278e-05 -7.11760497731335e-06 -1.62900027133903e-07 1.56539648519873e-05 -5.96408075611698e-06 -4.15461364018045e-06 -3.70146643956636e-06 2.17401661725985e-06 -5.09512930490482e-06 -5.96408075611698e-06 2.36189286891873e-05 -2.07733878551965e-06 2.701997583801e-06 2.35168311602406e-05 3.28602591729007e-05 -4.15461364018045e-06 -2.07733878551965e-06 7.70944856783237e-05 1.01237731496754e-05 4.48904536091137e-05 1.89202509808278e-05 -3.70146643956636e-06 2.701997583801e-06 1.01237731496754e-05 6.18502834270592e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 887 0 0 0 0 0 2218 +1076 1136 0.998672193602303 0.0179482215785393 0.0482877941899493 -0.0164424535869149 -0.0156206004976523 0.998717676307009 -0.0481559951825347 0.0148525943849722 -0.0490901880792485 0.0473377690020898 0.997671934585838 -0.0139594460788124 6.60008268142269e-05 2.22801110140899e-05 -1.04598750387496e-05 1.25633102746625e-05 -2.38018688621676e-05 3.31528850847463e-05 2.22801110140899e-05 8.53486559597865e-05 6.73472011632045e-06 9.04980759216747e-07 -2.05266252889488e-06 -4.8652432797497e-06 -1.04598750387496e-05 6.73472011632045e-06 1.55476974139606e-05 -5.47011522663118e-06 1.8672731836291e-06 -4.99539004133578e-06 1.25633102746625e-05 9.04980759216747e-07 -5.47011522663118e-06 3.14001805775752e-05 -2.69220368640818e-05 1.04396830589096e-05 -2.38018688621676e-05 -2.05266252889488e-06 1.8672731836291e-06 -2.69220368640818e-05 0.000122247937349079 -1.48265038898877e-05 3.31528850847463e-05 -4.8652432797497e-06 -4.99539004133578e-06 1.04396830589096e-05 -1.48265038898877e-05 6.83791448251613e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 799 0 0 0 0 0 2399 +1076 1133 0.998912949286219 0.0180737822085948 0.0429681061368021 -0.0144049783771598 -0.0156929420897046 0.99835667007021 -0.0551152510190306 -5.99021946219268e-06 -0.0438936364052512 0.054381041944761 0.997555036556944 -0.00380084431830645 3.86243220135704e-05 1.26398476048741e-05 -1.04170863685947e-05 6.79102892177317e-07 9.64652500711912e-06 1.52318563973302e-05 1.26398476048741e-05 5.43515475729084e-05 -1.28507503716114e-06 4.77982724449226e-06 -1.15147682544381e-05 -4.64867949897137e-06 -1.04170863685947e-05 -1.28507503716114e-06 1.43179652086729e-05 -3.21155179528596e-06 -2.11340339551068e-06 -8.91775175189096e-07 6.79102892177317e-07 4.77982724449226e-06 -3.21155179528596e-06 3.11092359738863e-05 -2.20251937158224e-05 -2.66816978760479e-06 9.64652500711912e-06 -1.15147682544381e-05 -2.11340339551068e-06 -2.20251937158224e-05 9.94425291568916e-05 1.61849541100794e-05 1.52318563973302e-05 -4.64867949897137e-06 -8.91775175189096e-07 -2.66816978760479e-06 1.61849541100794e-05 5.28763048609317e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 786 0 0 0 0 0 2381 +1076 1137 0.998822708840801 0.0184573726491791 0.0448611379571893 -0.0130960431216766 -0.0160277693529999 0.998416223978562 -0.0539273057546664 0.00448026043099684 -0.0457854443408784 0.0531447936422711 0.997536627896554 -0.00514843016285809 3.64024165743406e-05 1.14194382692326e-05 -6.07949426481233e-06 -8.81218585663672e-08 7.83405139588625e-07 4.62828522133887e-06 1.14194382692326e-05 7.85956065916189e-05 5.35352006594322e-06 -1.75322435662357e-06 5.91930872653281e-06 -2.06730055948061e-05 -6.07949426481233e-06 5.35352006594322e-06 1.47314935568646e-05 -3.41267475865631e-06 -1.41745978678409e-06 -5.42936161503128e-07 -8.81218585663672e-08 -1.75322435662357e-06 -3.41267475865631e-06 2.6552971616432e-05 -1.42272052606831e-05 1.07153759615223e-06 7.83405139588625e-07 5.91930872653281e-06 -1.41745978678409e-06 -1.42272052606831e-05 8.34751777183441e-05 -9.35306224024997e-07 4.62828522133887e-06 -2.06730055948061e-05 -5.42936161503128e-07 1.07153759615223e-06 -9.35306224024997e-07 4.54439507665139e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 891 0 0 0 0 0 2364 +1076 1134 0.998927336020314 0.0177837136706673 0.042754144587851 -0.0155682289673078 -0.0154605833267798 0.998417631170017 -0.0540666637776725 0.00481462104293462 -0.0436479978298529 0.0533476643999707 0.997621611127442 -0.00826764703705932 9.57667621332853e-05 5.02825708922014e-05 -1.20965484541988e-05 2.85318090902598e-05 -3.04120058020881e-05 2.95150625353189e-05 5.02825708922014e-05 0.000105991690601344 -5.68365873559194e-07 2.49320028114492e-05 -2.3840527940913e-05 -2.76788899920487e-06 -1.20965484541988e-05 -5.68365873559194e-07 1.61163829145e-05 -4.48502896588127e-06 1.93106094428621e-06 -2.4604959165977e-06 2.85318090902598e-05 2.49320028114492e-05 -4.48502896588127e-06 5.17025849869602e-05 -6.270726803985e-05 6.83468386647083e-06 -3.04120058020881e-05 -2.3840527940913e-05 1.93106094428621e-06 -6.270726803985e-05 0.000197645358581483 -3.16276194445279e-06 2.95150625353189e-05 -2.76788899920487e-06 -2.4604959165977e-06 6.83468386647083e-06 -3.16276194445279e-06 6.38973100192015e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 784 0 0 0 0 0 2439 +1076 1132 0.998844414952473 0.0182407169719541 0.0444647159284862 -0.0164762687803669 -0.0158961589307905 0.99849316281513 -0.0525234799179028 0.00890218856926004 -0.0453557807726751 0.0517559663786539 0.99762927638212 -0.00873200478921921 4.27145656831955e-05 1.57789724852104e-05 -1.16718227308018e-05 7.06484779873332e-06 -5.21748032297106e-06 4.2584927654248e-06 1.57789724852104e-05 5.52884252142242e-05 3.1161367067127e-06 -2.08348193149313e-06 4.06612901801037e-06 -8.69806109200626e-06 -1.16718227308018e-05 3.1161367067127e-06 1.73985156521771e-05 -5.10741029392397e-06 -5.01486394382248e-06 -1.33195558242528e-06 7.06484779873332e-06 -2.08348193149313e-06 -5.10741029392397e-06 3.02923262678739e-05 -2.89046603327982e-05 2.79967531743089e-06 -5.21748032297106e-06 4.06612901801037e-06 -5.01486394382248e-06 -2.89046603327982e-05 0.000137987512069447 -2.72523473361515e-06 4.2584927654248e-06 -8.69806109200626e-06 -1.33195558242528e-06 2.79967531743089e-06 -2.72523473361515e-06 4.33581225142832e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 886 0 0 0 0 0 2280 +1076 1128 0.998761154681622 0.0176658484580166 0.0465196055152207 -0.0199069362626335 -0.0154687257639328 0.998766919300519 -0.0471737155012243 0.0223951248639903 -0.0472956067967587 0.0463956755442639 0.997802869743577 -0.0154665967661403 5.34056867101149e-05 2.60312136071816e-05 -7.51790431754742e-06 5.80344014366196e-06 -7.5676919849112e-06 1.52190808205941e-05 2.60312136071816e-05 7.38063059537184e-05 2.38278992246762e-06 -1.71742936471804e-07 2.94035174133626e-06 -5.5994629563197e-06 -7.51790431754742e-06 2.38278992246762e-06 1.56690581459071e-05 -4.22298595471023e-06 -1.65925122583675e-06 -5.86546589911139e-07 5.80344014366196e-06 -1.71742936471804e-07 -4.22298595471023e-06 2.923627292757e-05 -2.4786570127345e-05 5.58684640351017e-07 -7.5676919849112e-06 2.94035174133626e-06 -1.65925122583675e-06 -2.4786570127345e-05 0.000118666838298275 -5.32886425799497e-06 1.52190808205941e-05 -5.5994629563197e-06 -5.86546589911139e-07 5.58684640351017e-07 -5.32886425799497e-06 5.61947039014694e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 802 0 0 0 0 0 2441 +1076 1125 0.998778619429688 0.0183641512293526 0.0458696775631951 -0.0160494882942585 -0.0159432543500286 0.998488535583006 -0.0525971192180124 0.0109509595285776 -0.0467662486292872 0.0518015661822013 0.997561785419938 -0.00818903395359582 3.46290697010023e-05 7.62791245381172e-06 -1.12075955020377e-05 5.29183251172361e-06 -1.91657791091434e-06 5.95641754181694e-06 7.62791245381172e-06 6.67500213208041e-05 5.42149535717767e-06 4.69706332618203e-06 -1.414325969113e-05 -1.82762577867873e-05 -1.12075955020377e-05 5.42149535717767e-06 1.74021265067614e-05 -3.76698797270835e-06 -4.76447123055187e-06 -4.86497838152744e-06 5.29183251172361e-06 4.69706332618203e-06 -3.76698797270835e-06 3.07823203311993e-05 -2.52707008858496e-05 -4.3983381609863e-07 -1.91657791091434e-06 -1.414325969113e-05 -4.76447123055187e-06 -2.52707008858496e-05 0.000106179617567989 1.17948679248745e-05 5.95641754181694e-06 -1.82762577867873e-05 -4.86497838152744e-06 -4.3983381609863e-07 1.17948679248745e-05 4.51698475110404e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 885 0 0 0 0 0 2394 +1076 1135 0.999053102409918 0.0184416226253616 0.0394056483268721 -0.0201571379545465 -0.0164138594355869 0.998554719486153 -0.0511767272337656 0.0184641012602103 -0.040292478002056 0.0504814693414743 0.997911888630244 -0.00911515198921984 4.40837172905471e-05 2.47762068815078e-05 -7.01968019285778e-06 2.5474899036562e-06 3.08723733871854e-06 5.72712546546799e-06 2.47762068815078e-05 7.02523060413077e-05 2.84497030868922e-06 4.36419549357884e-06 -1.7110858005536e-05 -2.58539779405273e-06 -7.01968019285778e-06 2.84497030868922e-06 1.5930633544268e-05 -1.99830483095999e-06 -3.1589924595781e-06 -1.09136444541792e-06 2.5474899036562e-06 4.36419549357884e-06 -1.99830483095999e-06 2.91474166001399e-05 -2.67136495612221e-05 1.19422277191552e-06 3.08723733871854e-06 -1.7110858005536e-05 -3.1589924595781e-06 -2.67136495612221e-05 0.000110710086439025 3.89860621224967e-06 5.72712546546799e-06 -2.58539779405273e-06 -1.09136444541792e-06 1.19422277191552e-06 3.89860621224967e-06 3.87058049216496e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 882 0 0 0 0 0 2390 +1076 1117 0.998724964792725 0.0172669626082244 0.0474372923137059 -0.011308682748936 -0.0147527781558571 0.998493568341039 -0.0528483634397842 -0.00993914363833108 -0.0482783619901697 0.0520811480659329 0.997475189555951 -0.00708231571214232 7.51460707657229e-05 3.25572517245033e-05 -6.78918326079657e-06 3.76266482102777e-06 -1.00696065175833e-05 4.11279798441185e-05 3.25572517245033e-05 6.69302670090816e-05 -9.30549378629625e-07 1.7623374595367e-06 5.92932343313237e-06 -9.6367890535525e-07 -6.78918326079657e-06 -9.30549378629625e-07 1.21757626872533e-05 -6.87363245827008e-07 2.89990406056074e-07 -1.26857605339933e-06 3.76266482102777e-06 1.7623374595367e-06 -6.87363245827008e-07 2.66072460039209e-05 -1.91836282386023e-05 9.71263693703415e-06 -1.00696065175833e-05 5.92932343313237e-06 2.89990406056074e-07 -1.91836282386023e-05 0.000109729754749454 -1.66583106531201e-05 4.11279798441185e-05 -9.6367890535525e-07 -1.26857605339933e-06 9.71263693703415e-06 -1.66583106531201e-05 8.14238700431078e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 754 0 0 0 0 0 2359 +1076 1118 0.998711196345883 0.0177567244284877 0.0475462409759788 -0.0145105908946442 -0.0153462668545185 0.998601551915276 -0.0505908351980054 0.00282526557249042 -0.0483780775455682 0.0497959762427908 0.997587050017703 -0.00888366107002504 8.39723787111456e-05 4.02885421929899e-05 -8.71690489972555e-06 1.78701899367735e-05 -3.52181701327363e-05 5.05242621553185e-05 4.02885421929899e-05 9.03624620978452e-05 3.96949702743074e-06 2.30452639616832e-06 -1.57439654692198e-06 1.2660615897049e-05 -8.71690489972555e-06 3.96949702743074e-06 1.80210315923117e-05 -5.07460696890628e-06 -5.96625909295022e-06 -3.50987031995711e-06 1.78701899367735e-05 2.30452639616832e-06 -5.07460696890628e-06 3.31963014705641e-05 -2.9930913886203e-05 1.59584972460831e-05 -3.52181701327363e-05 -1.57439654692198e-06 -5.96625909295022e-06 -2.9930913886203e-05 0.000154955079036834 -3.03369014964618e-05 5.05242621553185e-05 1.2660615897049e-05 -3.50987031995711e-06 1.59584972460831e-05 -3.03369014964618e-05 9.10648998190781e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 791 0 0 0 0 0 2405 +1076 1126 0.998647394806445 0.0178804256964256 0.0488228555413854 -0.0187643931469223 -0.0155940075159002 0.998781766646656 -0.0468167656270499 0.0207921930961363 -0.0496004816095008 0.0459920970504572 0.997709636734559 -0.0173318673674233 6.35574033533294e-05 3.663184186418e-05 -8.09590760881551e-06 8.98634809004404e-06 -5.55110774103855e-06 3.06469143918431e-05 3.663184186418e-05 9.03992984890282e-05 3.76974228186827e-06 5.80483654189356e-06 -1.39735942331536e-06 -2.5807187058011e-06 -8.09590760881551e-06 3.76974228186827e-06 1.7294894619212e-05 -5.94660436639337e-06 -5.29111475436486e-06 -3.80295376135259e-06 8.98634809004404e-06 5.80483654189356e-06 -5.94660436639337e-06 3.72579272348497e-05 -3.22638381809051e-05 5.86110409432152e-06 -5.55110774103855e-06 -1.39735942331536e-06 -5.29111475436486e-06 -3.22638381809051e-05 0.000157097874399143 1.2350892532494e-06 3.06469143918431e-05 -2.5807187058011e-06 -3.80295376135259e-06 5.86110409432152e-06 1.2350892532494e-06 6.01997837275914e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2463 +1076 1111 0.99899227201855 0.0181539884737062 0.0410472063569681 -0.012183612320714 -0.0157616721734215 0.998199537142136 -0.0578727374462595 -0.00741593806799274 -0.0420239233950445 0.0571674448591385 0.99747976075245 0.00327231998189033 3.71081481464515e-05 1.94238926923131e-05 -1.20611933361136e-05 1.02747605008485e-05 -3.58038123066448e-06 -3.05402152990789e-08 1.94238926923131e-05 6.29987891097559e-05 -4.10314901165618e-06 8.88773560491464e-06 -8.08529233323771e-06 -1.6409208019292e-05 -1.20611933361136e-05 -4.10314901165618e-06 1.50103100323466e-05 -6.03218784315612e-06 -1.56893034610582e-06 -3.50530629931466e-06 1.02747605008485e-05 8.88773560491464e-06 -6.03218784315612e-06 2.8045565203375e-05 -5.63768923186682e-06 5.51349607982455e-06 -3.58038123066448e-06 -8.08529233323771e-06 -1.56893034610582e-06 -5.63768923186682e-06 5.93244273373309e-05 5.21382747240287e-06 -3.05402152990789e-08 -1.6409208019292e-05 -3.50530629931466e-06 5.51349607982455e-06 5.21382747240287e-06 4.13930960725329e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 699 0 0 0 0 0 2389 +1076 1116 0.998682896643469 0.0172907255276918 0.0483063428809887 -0.0142403008828878 -0.0148469420711694 0.998613803185495 -0.0504979246953438 -0.00111067583991967 -0.0491125265379919 0.0497142122348056 0.99755523999372 -0.00575635847849143 0.00014054201107627 4.78375759774736e-05 -2.71115083859389e-06 1.207767488588e-05 -5.04140641723645e-05 7.33393316801385e-05 4.78375759774736e-05 9.96812645985466e-05 5.86718728301624e-06 5.88610787401281e-06 -1.13635437876268e-06 -4.45689290207033e-06 -2.71115083859389e-06 5.86718728301624e-06 1.30173065026335e-05 1.18669263262477e-06 -1.98065773762106e-06 -7.38300454935259e-07 1.207767488588e-05 5.88610787401281e-06 1.18669263262477e-06 2.76675083748434e-05 -3.22945024613283e-05 1.15851455766937e-05 -5.04140641723645e-05 -1.13635437876268e-06 -1.98065773762106e-06 -3.22945024613283e-05 0.000164216503559244 -4.06236123949837e-05 7.33393316801385e-05 -4.45689290207033e-06 -7.38300454935259e-07 1.15851455766937e-05 -4.06236123949837e-05 0.00011613089131169 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 740 0 0 0 0 0 2450 +1076 1115 0.998802376628371 0.0176107103382973 0.0456472926130104 -0.0128732449477889 -0.0150834014659448 0.998365193078894 -0.0551310461424356 -0.00634274285145053 -0.0465435649873786 0.0543765034727576 0.997435157004375 -0.000744674675376118 3.69160933090288e-05 1.82640970931762e-05 -8.8477955739116e-06 5.03448737496339e-06 -6.39629742859035e-06 6.34491246078201e-07 1.82640970931762e-05 7.69046033008059e-05 9.39959980958895e-09 1.31898079322027e-05 -1.9408897517284e-05 -2.51901651221403e-05 -8.8477955739116e-06 9.39959980958895e-09 1.37008558821293e-05 -6.41766002213052e-07 1.43295023075213e-07 -5.52660050137767e-07 5.03448737496339e-06 1.31898079322027e-05 -6.41766002213052e-07 2.7285818765086e-05 -1.6907368134256e-05 1.04188541951047e-06 -6.39629742859035e-06 -1.9408897517284e-05 1.43295023075213e-07 -1.6907368134256e-05 7.44962715301344e-05 1.96215866902977e-06 6.34491246078201e-07 -2.51901651221403e-05 -5.52660050137767e-07 1.04188541951047e-06 1.96215866902977e-06 4.61041207602082e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 809 0 0 0 0 0 2425 +1076 1124 0.998821087467072 0.018462866968314 0.0448949637977935 -0.0148879847441178 -0.016062048312251 0.998451424260271 -0.0532612804638763 0.00871905037380775 -0.0458087964817868 0.0524773849953207 0.997570888823919 -0.00819167134151628 2.8915728527699e-05 1.06579204939791e-05 -6.29946494062879e-06 7.91232189235803e-07 1.18137868025602e-06 6.67962067647598e-06 1.06579204939791e-05 7.67924964663762e-05 5.85528586651575e-06 -1.36243400406636e-07 -5.94513935597196e-07 -1.93980341658445e-05 -6.29946494062879e-06 5.85528586651575e-06 1.45195405366676e-05 -1.45338732153541e-06 -2.94038600443965e-06 -2.13255061249796e-06 7.91232189235803e-07 -1.36243400406636e-07 -1.45338732153541e-06 3.04946754358873e-05 -3.0526041453699e-05 -2.34459574685451e-06 1.18137868025602e-06 -5.94513935597196e-07 -2.94038600443965e-06 -3.0526041453699e-05 0.00012695490333821 1.28460946184627e-07 6.67962067647598e-06 -1.93980341658445e-05 -2.13255061249796e-06 -2.34459574685451e-06 1.28460946184627e-07 4.68442769027092e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 881 0 0 0 0 0 2484 +1076 1112 0.998869918615648 0.0175437262531798 0.0441712955879919 -0.0134593046862228 -0.0149566354460063 0.998190934818398 -0.058233638925517 -0.00603635391078411 -0.0451130218551532 0.0575071762089368 0.997325292942865 -0.00147229772174059 7.72924293373995e-05 4.50006122734351e-05 -1.29868837541953e-05 1.99311351118808e-05 -1.70636604837982e-05 2.55931574290522e-05 4.50006122734351e-05 8.86220347881963e-05 -5.09223466519548e-06 1.15070095059752e-05 -8.42484388452468e-07 -1.23311064044819e-05 -1.29868837541953e-05 -5.09223466519548e-06 1.53003919560647e-05 -4.3458782903236e-06 -5.44904253086703e-08 -2.53998755752412e-06 1.99311351118808e-05 1.15070095059752e-05 -4.3458782903236e-06 3.01760470214624e-05 -1.30817199280332e-05 1.48123551165546e-05 -1.70636604837982e-05 -8.42484388452468e-07 -5.44904253086703e-08 -1.30817199280332e-05 9.13737173677199e-05 -2.90188324118449e-05 2.55931574290522e-05 -1.23311064044819e-05 -2.53998755752412e-06 1.48123551165546e-05 -2.90188324118449e-05 7.84138277233166e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 752 0 0 0 0 0 2400 +1076 1123 0.998775602655781 0.0177858388179879 0.0461623166351211 -0.0155412330085346 -0.0152051181844044 0.998333627774154 -0.0556666150964397 0.00639708957419625 -0.0470754704764479 0.0548965535606511 0.9973817065129 -0.00645275601362466 5.73568260103095e-05 2.46754082632835e-05 -4.06770803258275e-06 6.57235434511976e-06 -1.47839427249071e-05 2.5964677215261e-05 2.46754082632835e-05 7.64945053413911e-05 1.6101968477309e-06 1.04653307803764e-05 -1.45909042728397e-05 -6.1828688098525e-06 -4.06770803258275e-06 1.6101968477309e-06 1.16430587710387e-05 -5.90382461675086e-07 2.3013144831861e-08 -9.6858704762678e-07 6.57235434511976e-06 1.04653307803764e-05 -5.90382461675086e-07 3.4538557807903e-05 -3.29686048013659e-05 4.34025537290197e-06 -1.47839427249071e-05 -1.45909042728397e-05 2.3013144831861e-08 -3.29686048013659e-05 0.000127009576457286 -9.67554044095875e-07 2.5964677215261e-05 -6.1828688098525e-06 -9.6858704762678e-07 4.34025537290197e-06 -9.67554044095875e-07 5.95252343304696e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 772 0 0 0 0 0 2491 +1076 1106 0.998654503945607 0.0171741747876155 0.0489308641811809 -0.0153412435844141 -0.0144957694507703 0.998404332884422 -0.0545771082565084 0.00235895706498604 -0.0497901036068701 0.0537943844464917 0.997309936672066 -0.0045587788952727 5.14794987059187e-05 1.69015169165311e-05 -1.70224297487431e-05 1.24104886656275e-05 -5.38074624844021e-06 9.0532958696052e-06 1.69015169165311e-05 8.02936560817979e-05 8.24177527888697e-07 2.63517816675667e-06 5.49523110729603e-06 -2.99547688382354e-05 -1.70224297487431e-05 8.24177527888697e-07 1.9495781911813e-05 -8.27185706060908e-06 -2.68217707231297e-06 -6.85877950970949e-06 1.24104886656275e-05 2.63517816675667e-06 -8.27185706060908e-06 2.4995431388775e-05 -2.05282883430622e-06 9.63862765996113e-06 -5.38074624844021e-06 5.49523110729603e-06 -2.68217707231297e-06 -2.05282883430622e-06 5.73474820186792e-05 -6.29771259807401e-06 9.0532958696052e-06 -2.99547688382354e-05 -6.85877950970949e-06 9.63862765996113e-06 -6.29771259807401e-06 4.80761694075659e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 793 0 0 0 0 0 2505 +1076 1121 0.998878139314446 0.0178965304651684 0.043842639028906 -0.0144053873051532 -0.015511521739848 0.998412424332058 -0.0541481637056829 -0.000146062208852124 -0.044742099783357 0.0534073509611974 0.99756994710661 -0.00904393268434306 4.2787746787399e-05 1.59023024854517e-05 -9.03907911341126e-06 1.31878305033894e-06 4.17863063231826e-06 4.06303492805037e-06 1.59023024854517e-05 7.37480018911048e-05 1.52739627603411e-06 1.55597186843005e-05 -3.80990645666283e-05 -7.91992111906316e-06 -9.03907911341126e-06 1.52739627603411e-06 1.51779149969364e-05 -8.13692184802809e-07 -2.77251573899458e-06 1.49221492688211e-06 1.31878305033894e-06 1.55597186843005e-05 -8.13692184802809e-07 3.58446767645558e-05 -4.06962585249645e-05 -4.01328145426739e-06 4.17863063231826e-06 -3.80990645666283e-05 -2.77251573899458e-06 -4.06962585249645e-05 0.000142620117597812 9.58560752575755e-06 4.06303492805037e-06 -7.91992111906316e-06 1.49221492688211e-06 -4.01328145426739e-06 9.58560752575755e-06 4.0764602767415e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 898 0 0 0 0 0 2366 +1076 1110 0.99860548626765 0.0168301586758057 0.0500382709043441 -0.0132772043145356 -0.0141774469921792 0.998498962183346 -0.0529038988692205 -0.00084049555118667 -0.0508535425799745 0.0521207087224259 0.997345150351341 -0.00602232126250294 4.34572421089705e-05 1.29026030807558e-05 -1.3306598623651e-05 9.25175352977672e-06 -2.58379947102741e-06 7.53147153683484e-06 1.29026030807558e-05 6.71843739486408e-05 -3.8256085805902e-06 3.4014487260108e-06 7.34437551608816e-06 -2.41954403373281e-05 -1.3306598623651e-05 -3.8256085805902e-06 1.56757196761084e-05 -4.734195949118e-06 -1.71132831193362e-06 -3.88626388468112e-07 9.25175352977672e-06 3.4014487260108e-06 -4.734195949118e-06 2.71859000043952e-05 -8.53226758797001e-06 2.94189896373006e-06 -2.58379947102741e-06 7.34437551608816e-06 -1.71132831193362e-06 -8.53226758797001e-06 7.99167814017477e-05 -2.89371357750959e-06 7.53147153683484e-06 -2.41954403373281e-05 -3.88626388468112e-07 2.94189896373006e-06 -2.89371357750959e-06 4.70348362377684e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 751 0 0 0 0 0 2363 +1076 1122 0.998905799429983 0.0176013458079133 0.0433289336459647 -0.015163852516525 -0.0153222430054998 0.998509592173878 -0.0523815158814344 0.00675541866197959 -0.0441863410391331 0.051660303546406 0.997686714506646 -0.00778504554597026 2.86686072365824e-05 1.13713023180746e-05 -8.73385746699286e-06 3.92890347310589e-06 -2.50319921543095e-06 6.75239587963077e-06 1.13713023180746e-05 5.75461295128254e-05 2.8867114082299e-06 -1.52670286865248e-06 -5.47644175133994e-06 -1.5797327694589e-05 -8.73385746699286e-06 2.8867114082299e-06 1.40507487886637e-05 -1.35849155041287e-06 -1.21940798284566e-06 -1.60289733818869e-06 3.92890347310589e-06 -1.52670286865248e-06 -1.35849155041287e-06 2.75531128462324e-05 -3.24105409710883e-05 5.16406173038135e-06 -2.50319921543095e-06 -5.47644175133994e-06 -1.21940798284566e-06 -3.24105409710883e-05 0.000122368273238583 -9.53941946090315e-06 6.75239587963077e-06 -1.5797327694589e-05 -1.60289733818869e-06 5.16406173038135e-06 -9.53941946090315e-06 4.97139568944625e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 898 0 0 0 0 0 2342 +1076 1107 0.998731323644188 0.0177266051654839 0.0471329040187005 -0.0135294038197949 -0.0150535441583457 0.998290491961603 -0.05647552095672 0.00138918405463067 -0.0480534492019223 0.0556943545466434 0.997290832651855 -0.000733589529356652 4.1665019453985e-05 1.57614025973675e-05 -1.00934134818967e-05 5.16296406867783e-06 2.76264133585131e-06 5.01621578485961e-06 1.57614025973675e-05 6.11594860497188e-05 -2.92419901221635e-06 5.01125281815328e-06 -3.19739777460941e-06 -1.69912150492406e-05 -1.00934134818967e-05 -2.92419901221635e-06 1.39376474787543e-05 -3.34801787263937e-06 -3.51079774573694e-06 -3.19588460796735e-06 5.16296406867783e-06 5.01125281815328e-06 -3.34801787263937e-06 2.56732488056837e-05 -1.59272251599353e-06 6.01221715976904e-06 2.76264133585131e-06 -3.19739777460941e-06 -3.51079774573694e-06 -1.59272251599353e-06 5.96284382566989e-05 1.19866013084284e-06 5.01621578485961e-06 -1.69912150492406e-05 -3.19588460796735e-06 6.01221715976904e-06 1.19866013084284e-06 4.61203083405041e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 676 0 0 0 0 0 2350 +1076 1119 0.998864059175234 0.0184906606951141 0.0439168163125686 -0.0182861029487693 -0.0164592874500523 0.998797777771021 -0.0461745706672801 0.0199983623078881 -0.0447178168587229 0.0453992795838134 0.997967545699088 -0.0139818361157904 7.38020374604624e-05 5.59936634652016e-05 -6.34128224231552e-06 7.30249566505606e-06 -9.56409291496821e-06 1.73585817831639e-05 5.59936634652016e-05 8.97178932002097e-05 7.43890005306063e-07 6.2813976902681e-06 -1.36030526746524e-05 8.92168021029227e-06 -6.34128224231552e-06 7.43890005306063e-07 1.47225092410128e-05 -1.06935616415119e-06 -3.14280474082992e-06 4.13910049429313e-07 7.30249566505606e-06 6.2813976902681e-06 -1.06935616415119e-06 3.2596060554001e-05 -3.53422410258594e-05 5.61002729940156e-06 -9.56409291496821e-06 -1.36030526746524e-05 -3.14280474082992e-06 -3.53422410258594e-05 0.000144123137433755 -1.31095579789048e-05 1.73585817831639e-05 8.92168021029227e-06 4.13910049429313e-07 5.61002729940156e-06 -1.31095579789048e-05 4.86019241831226e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 793 0 0 0 0 0 2398 +1076 1114 0.998703178975542 0.0179150938195907 0.0476551121872686 -0.0114026459636927 -0.015286512770332 0.998371414724409 -0.0549621759804431 -0.006716437569932 -0.0485621543124723 0.0541624193940594 0.997350564994031 -0.000585071705993137 3.12390830591757e-05 8.33575430733061e-06 -7.30188301721773e-06 1.20169113938824e-06 -6.41318307498625e-06 -1.78552610523074e-06 8.33575430733061e-06 7.8884591476171e-05 5.781067232785e-06 -2.96064418845124e-07 -1.2564297072987e-05 -3.16012969545737e-05 -7.30188301721773e-06 5.781067232785e-06 1.60340423552912e-05 -3.42069903362671e-06 -7.77891273490931e-07 -3.13943410108144e-06 1.20169113938824e-06 -2.96064418845124e-07 -3.42069903362671e-06 2.4272263463239e-05 -6.85079461793631e-06 4.66896077114225e-06 -6.41318307498625e-06 -1.2564297072987e-05 -7.77891273490931e-07 -6.85079461793631e-06 6.87152794486327e-05 -3.20477086669489e-06 -1.78552610523074e-06 -3.16012969545737e-05 -3.13943410108144e-06 4.66896077114225e-06 -3.20477086669489e-06 4.09946802767082e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 833 0 0 0 0 0 2420 +1076 1113 0.998730848354978 0.0167241907669606 0.0475078308001486 -0.0181665551105972 -0.0142289059353085 0.998525601713165 -0.0523847397554382 0.00601967989817137 -0.0483138777167532 0.0516422711211577 0.997496288240422 -0.00230254845037487 7.93648382507981e-05 1.06006410712316e-05 -1.29200105458395e-05 1.8905377955954e-05 -1.76718648971467e-05 3.50631353931531e-05 1.06006410712316e-05 9.47020282026922e-05 2.02121890729805e-06 8.06873824234399e-06 5.24322764792233e-06 -2.93678067105754e-05 -1.29200105458395e-05 2.02121890729805e-06 1.66913764269739e-05 -5.99519575218939e-06 -1.09189488800848e-06 -3.89271500767039e-06 1.8905377955954e-05 8.06873824234399e-06 -5.99519575218939e-06 3.15965941042053e-05 -1.24212845267287e-05 4.77119276595275e-06 -1.76718648971467e-05 5.24322764792233e-06 -1.09189488800848e-06 -1.24212845267287e-05 8.28120692057779e-05 -5.58702006998102e-06 3.50631353931531e-05 -2.93678067105754e-05 -3.89271500767039e-06 4.77119276595275e-06 -5.58702006998102e-06 7.12912764690134e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 720 0 0 0 0 0 2429 +1076 1108 0.998827403816753 0.0181122629427844 0.0448972528756097 -0.0144304260255457 -0.0155630206358026 0.998281704592764 -0.0564927487741189 0.00132550867070864 -0.0458433176523535 0.0557277687195313 0.997393004798093 -0.00038965573391516 3.98936531772036e-05 6.16566434502012e-06 -1.14759743911165e-05 8.44698094854008e-06 -3.03267918555403e-06 8.42093010933746e-06 6.16566434502012e-06 6.91629515112304e-05 1.5908052402917e-06 2.42222763283938e-06 2.98726310967091e-06 -2.72231527202843e-05 -1.14759743911165e-05 1.5908052402917e-06 1.56103673645311e-05 -5.65835926323653e-06 -3.53996703738637e-06 -4.92385850080594e-06 8.44698094854008e-06 2.42222763283938e-06 -5.65835926323653e-06 2.59654451835096e-05 -1.53098601714147e-06 6.12638368249213e-06 -3.03267918555403e-06 2.98726310967091e-06 -3.53996703738637e-06 -1.53098601714147e-06 6.73587893314277e-05 -2.1050166103278e-06 8.42093010933746e-06 -2.72231527202843e-05 -4.92385850080594e-06 6.12638368249213e-06 -2.1050166103278e-06 4.65990323202038e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 699 0 0 0 0 0 2424 +1076 1109 0.998679587166625 0.0177584328481207 0.048204981479919 -0.0119431404362135 -0.015179539810861 0.998460645233707 -0.0533471788440642 7.93943192473323e-05 -0.0490781392050578 0.0525450091090379 0.997411829822516 -0.00444681294061416 3.35008988509683e-05 1.10540486995321e-05 -1.18151928987622e-05 5.86606052976856e-06 -6.26379054186636e-07 2.02589383178346e-06 1.10540486995321e-05 6.3459245369368e-05 2.5652928304696e-06 -1.9033358546227e-06 -1.50629327005636e-06 -2.25906592368285e-05 -1.18151928987622e-05 2.5652928304696e-06 1.65320241020781e-05 -4.38685717581804e-06 -3.34714959898769e-06 -2.98057716513428e-06 5.86606052976856e-06 -1.9033358546227e-06 -4.38685717581804e-06 2.16741503248118e-05 -1.3853362219805e-06 3.37408132981427e-06 -6.26379054186636e-07 -1.50629327005636e-06 -3.34714959898769e-06 -1.3853362219805e-06 5.83426604954245e-05 -3.89376497029144e-06 2.02589383178346e-06 -2.25906592368285e-05 -2.98057716513428e-06 3.37408132981427e-06 -3.89376497029144e-06 3.54857158509989e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 829 0 0 0 0 0 2375 +1076 1105 0.998760135446131 0.0175302168020445 0.0465927391607218 -0.0146853106776886 -0.0150600016879197 0.998488927264866 -0.0528493943070022 0.00443454342933782 -0.0474487954829793 0.0520821814859022 0.997514941331148 -0.00578961895690963 3.91279470523455e-05 2.12672230211769e-05 -3.01322407132922e-06 2.22991333178573e-07 -7.35765148901437e-06 5.19920536737384e-06 2.12672230211769e-05 6.65480897902156e-05 7.9878016500709e-06 -2.8767463740638e-06 -6.15455612926674e-06 -1.23500006862015e-05 -3.01322407132922e-06 7.9878016500709e-06 1.42587260178887e-05 -2.01178379072405e-06 1.87215306412269e-07 -3.73885124262508e-07 2.22991333178573e-07 -2.8767463740638e-06 -2.01178379072405e-06 2.12683065113571e-05 -3.44255135485187e-06 4.57724068865273e-06 -7.35765148901437e-06 -6.15455612926674e-06 1.87215306412269e-07 -3.44255135485187e-06 5.41242122768328e-05 -2.43876013478655e-06 5.19920536737384e-06 -1.23500006862015e-05 -3.73885124262508e-07 4.57724068865273e-06 -2.43876013478655e-06 3.71031721799734e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 745 0 0 0 0 0 2429 +1077 1079 0.999940080574223 -0.00855135151075066 0.00683444573881203 -0.00655157015050469 0.00867148746286733 0.999804922155068 -0.0177460682879485 0.0119322290960008 -0.00668135962200196 0.0178042697642666 0.999819167355659 0.00411870276018828 2.9248215363551e-05 9.73977968798879e-06 -7.97028650070806e-06 8.25144082972478e-06 -2.93819591204748e-06 9.56496004535959e-06 9.73977968798879e-06 6.19586240520449e-05 3.408600479471e-06 -3.15551539190865e-06 1.98236358652248e-05 -1.73068728237346e-05 -7.97028650070806e-06 3.408600479471e-06 1.94743222155183e-05 -8.66496368486626e-06 -5.94610631160264e-06 -7.03433329851624e-06 8.25144082972478e-06 -3.15551539190865e-06 -8.66496368486626e-06 2.7847601137087e-05 -8.3279235452987e-06 1.22759570926079e-06 -2.93819591204748e-06 1.98236358652248e-05 -5.94610631160264e-06 -8.3279235452987e-06 8.19462236143895e-05 6.20086317686339e-06 9.56496004535959e-06 -1.73068728237346e-05 -7.03433329851624e-06 1.22759570926079e-06 6.20086317686339e-06 4.46777234702297e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 980 0 0 0 0 0 2253 +1077 1080 0.99986547706603 -0.00899444570520916 0.0137159658054604 -0.0101167281838006 0.00930396464454649 0.999699662676052 -0.0226720243313448 0.0194754392159295 -0.0135079240971196 0.0227965872850325 0.999648864149178 -0.00238262717625281 5.02185284379051e-05 3.46376295062776e-05 -5.16925365193776e-06 5.63603245355585e-06 3.21420061656446e-06 1.7989985255398e-06 3.46376295062776e-05 6.34302538135638e-05 8.15995669908097e-07 -2.65959163529903e-06 2.01351834733251e-05 -1.22315812362822e-05 -5.16925365193776e-06 8.15995669908097e-07 1.42129656741229e-05 -3.33418480375126e-06 -3.7243951065036e-07 -1.61494946015801e-06 5.63603245355585e-06 -2.65959163529903e-06 -3.33418480375126e-06 2.64003646027344e-05 -2.33260201156701e-05 2.04997399934684e-06 3.21420061656446e-06 2.01351834733251e-05 -3.7243951065036e-07 -2.33260201156701e-05 0.000112217246390584 2.39049326503872e-06 1.7989985255398e-06 -1.22315812362822e-05 -1.61494946015801e-06 2.04997399934684e-06 2.39049326503872e-06 3.44369244101848e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 832 0 0 0 0 0 2334 +1077 1137 0.999623498454625 0.0127926141321944 0.0242736556991366 -0.0105904315087074 -0.0117699569606757 0.99905602459926 -0.0418154017685726 0.0150038471123372 -0.0247856702648786 0.0415139583223292 0.998830446979833 -0.00905304330095802 6.78047955929976e-05 3.39031168108055e-05 -9.58578098746258e-06 1.75654989272644e-05 -3.24690595602408e-05 3.44506674132446e-06 3.39031168108055e-05 0.000105243981189707 9.54175760965883e-06 4.50786159722611e-07 -6.30087904857792e-06 -3.13709064684704e-05 -9.58578098746258e-06 9.54175760965883e-06 1.90363631217824e-05 -7.55965184238714e-06 -6.50804446448898e-06 -2.13144456760772e-06 1.75654989272644e-05 4.50786159722611e-07 -7.55965184238714e-06 3.25798909125503e-05 -2.53005907298991e-05 6.56727920342322e-06 -3.24690595602408e-05 -6.30087904857792e-06 -6.50804446448898e-06 -2.53005907298991e-05 0.000129044731152025 -1.09350832098718e-05 3.44506674132446e-06 -3.13709064684704e-05 -2.13144456760772e-06 6.56727920342322e-06 -1.09350832098718e-05 5.15925123960395e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 881 0 0 0 0 0 2434 +1077 1140 0.999513415224755 0.0124262841988931 0.0286097928471337 -0.0146919686273407 -0.0112687104059506 0.99912519047438 -0.0402724462296463 0.0272743628416839 -0.0290852015900592 0.0399304548000805 0.998779059566191 -0.0100252109929514 4.90077971374073e-05 1.76299898582073e-05 -4.51453530334831e-06 1.25694035623632e-06 -6.54723622210476e-06 1.65541427321692e-06 1.76299898582073e-05 0.000108314793162088 1.32051270873145e-05 4.65728587373338e-06 -1.23228109481839e-05 -5.41305876096501e-05 -4.51453530334831e-06 1.32051270873145e-05 1.6867839509e-05 -4.69408505953859e-06 -4.45512811402725e-06 -5.82563555915926e-06 1.25694035623632e-06 4.65728587373338e-06 -4.69408505953859e-06 3.35315305643173e-05 -2.71985165528208e-05 -1.03185414582541e-05 -6.54723622210476e-06 -1.23228109481839e-05 -4.45512811402725e-06 -2.71985165528208e-05 0.000128908326887299 1.79797413270116e-05 1.65541427321692e-06 -5.41305876096501e-05 -5.82563555915926e-06 -1.03185414582541e-05 1.79797413270116e-05 6.86703176304461e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 863 0 0 0 0 0 2416 +1077 1136 0.999635610471344 0.0128130730266941 0.023758607644302 -0.00701457725165364 -0.011652053351954 0.99876113609213 -0.048377915257289 0.000528243608849124 -0.0243490437238611 0.0480834502877115 0.998546496603019 -0.00689505660556238 3.58274353475132e-05 -2.37748361090267e-06 -1.15184828104511e-05 5.1031247770207e-06 3.35733777560905e-09 1.5426107644189e-05 -2.37748361090267e-06 8.78523029638162e-05 1.34407025957428e-05 -2.93326397938304e-06 -1.2975675167721e-05 -3.13687329257078e-05 -1.15184828104511e-05 1.34407025957428e-05 2.17536972884796e-05 -9.27596011193938e-06 -7.37523972115595e-06 -3.41145903797693e-06 5.1031247770207e-06 -2.93326397938304e-06 -9.27596011193938e-06 3.23903874281838e-05 -2.15870736821264e-05 -1.61481479347211e-06 3.35733777560905e-09 -1.2975675167721e-05 -7.37523972115595e-06 -2.15870736821264e-05 0.000110135296336051 9.56818460785285e-06 1.5426107644189e-05 -3.13687329257078e-05 -3.41145903797693e-06 -1.61481479347211e-06 9.56818460785285e-06 6.20873718348077e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 798 0 0 0 0 0 2422 +1076 1120 0.998787136076404 0.0176630119028219 0.0459594910634911 -0.0178755002359028 -0.0152159300999137 0.998475397212365 -0.0530599343460175 0.0125517331459708 -0.0468266193472141 0.0522962634624112 0.997533141578956 -0.00734847484640229 7.24848156623774e-05 5.09644817463378e-05 -1.20927925513633e-05 2.25477363110172e-05 -2.84647718859303e-05 2.75216708705348e-05 5.09644817463378e-05 8.96849774778163e-05 -1.11083989692283e-06 1.8056912175077e-05 -3.7696285896276e-05 1.16144373961664e-05 -1.20927925513633e-05 -1.11083989692283e-06 1.71667453388157e-05 -7.90048373128328e-06 -4.77286972445715e-06 -3.70388066653281e-06 2.25477363110172e-05 1.8056912175077e-05 -7.90048373128328e-06 4.26238978053413e-05 -4.82946374454384e-05 1.33450647772343e-05 -2.84647718859303e-05 -3.7696285896276e-05 -4.77286972445715e-06 -4.82946374454384e-05 0.00017447490145577 -1.19644298700968e-05 2.75216708705348e-05 1.16144373961664e-05 -3.70388066653281e-06 1.33450647772343e-05 -1.19644298700968e-05 6.25980023926859e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 778 0 0 0 0 0 2462 +1077 1125 0.999514093299256 0.0123425907826797 0.0286223295511963 -0.0144014574205531 -0.0111775466530393 0.999116497522716 -0.0405127983328647 0.0220362964051932 -0.0290970745434159 0.0401731854688117 0.998768980006039 -0.0167020938036079 3.46474998707758e-05 2.03630203951e-05 -9.79746011508063e-06 8.64739429919273e-06 -2.77616968732643e-06 -2.58188140764358e-06 2.03630203951e-05 6.56375045635442e-05 4.84480013134961e-06 -3.79970113543299e-06 -3.92537765469145e-06 -1.39455612759289e-05 -9.79746011508063e-06 4.84480013134961e-06 1.62530364773011e-05 -5.06350124906131e-06 -7.84430518482705e-06 -1.84849248259598e-06 8.64739429919273e-06 -3.79970113543299e-06 -5.06350124906131e-06 4.06830945068216e-05 -5.12099440967028e-05 1.78634969002663e-06 -2.77616968732643e-06 -3.92537765469145e-06 -7.84430518482705e-06 -5.12099440967028e-05 0.000187982916203005 8.02479401582846e-06 -2.58188140764358e-06 -1.39455612759289e-05 -1.84849248259598e-06 1.78634969002663e-06 8.02479401582846e-06 3.71294103825387e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 888 0 0 0 0 0 2405 +1077 1132 0.999571570179717 0.0126128785915372 0.0264119552871562 -0.0128271840605548 -0.0115188839163559 0.99908572735804 -0.0411706777060752 0.0172005805656921 -0.0269070883184545 0.0408488027130679 0.998802975523768 -0.0155818055229168 5.30539521206117e-05 1.77408615868913e-05 -1.09982515935524e-05 1.10324684577236e-05 -1.61084253556622e-05 1.21295186422056e-05 1.77408615868913e-05 0.000126081655439412 2.0016615952536e-05 -2.22897667364964e-07 -1.40374516787779e-05 -3.97252333997229e-05 -1.09982515935524e-05 2.0016615952536e-05 2.1320489380073e-05 -6.26424316525373e-06 -9.84714978548356e-06 -7.34792839604022e-06 1.10324684577236e-05 -2.22897667364964e-07 -6.26424316525373e-06 4.99865263194919e-05 -7.05536367669445e-05 -4.33337644951895e-06 -1.61084253556622e-05 -1.40374516787779e-05 -9.84714978548356e-06 -7.05536367669445e-05 0.000253862389688545 6.77795052320272e-06 1.21295186422056e-05 -3.97252333997229e-05 -7.34792839604022e-06 -4.33337644951895e-06 6.77795052320272e-06 6.34831826167195e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 877 0 0 0 0 0 2276 +1077 1139 0.999546333672111 0.0123289343391898 0.027479523662179 -0.0170096618372966 -0.0111286757845304 0.998995303346479 -0.0434112481617218 0.0293459238986745 -0.0279871295048834 0.0430857432306295 0.998679297528662 -0.00992436068697611 6.38490078659003e-05 1.17102893594209e-05 -1.41155686390291e-05 8.38914132524892e-06 1.24355676835008e-05 2.56657916908992e-05 1.17102893594209e-05 7.78393664065978e-05 5.18933513634621e-06 4.07209129402055e-06 -9.43922415616012e-06 -2.16811142371881e-05 -1.41155686390291e-05 5.18933513634621e-06 1.87316077073946e-05 -6.38905327060972e-06 -8.62672105500252e-06 -4.9707463586158e-06 8.38914132524892e-06 4.07209129402055e-06 -6.38905327060972e-06 3.13747470663663e-05 -1.01471002735158e-05 2.00162260650612e-06 1.24355676835008e-05 -9.43922415616012e-06 -8.62672105500252e-06 -1.01471002735158e-05 8.26328932954777e-05 1.36726704087159e-05 2.56657916908992e-05 -2.16811142371881e-05 -4.9707463586158e-06 2.00162260650612e-06 1.36726704087159e-05 5.51609150482132e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 870 0 0 0 0 0 2470 +1077 1133 0.999667577725834 0.0130222603489639 0.0222520735925231 -0.0100588785589811 -0.0120839541831577 0.999053189675313 -0.0417935670992893 0.0106086077833875 -0.0227752518111788 0.0415107809488963 0.998878442539406 -0.0105099075023296 4.30958255737036e-05 2.19857161128635e-06 -1.02919926679556e-05 6.77145267524029e-07 9.83166679274827e-06 4.37359229971002e-06 2.19857161128635e-06 0.000109300572163018 1.19445763037246e-05 7.36124011848752e-07 -1.22959255165985e-05 -4.32067648565411e-05 -1.02919926679556e-05 1.19445763037246e-05 1.75290735225622e-05 -4.39363922962928e-06 -1.00496547948746e-05 -4.2218436176042e-06 6.77145267524029e-07 7.36124011848752e-07 -4.39363922962928e-06 3.84099414197121e-05 -4.57704784209029e-05 -3.08462677289785e-06 9.83166679274827e-06 -1.22959255165985e-05 -1.00496547948746e-05 -4.57704784209029e-05 0.000175100237265491 1.37539833254584e-06 4.37359229971002e-06 -4.32067648565411e-05 -4.2218436176042e-06 -3.08462677289785e-06 1.37539833254584e-06 6.1866378885316e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 794 0 0 0 0 0 2323 +1077 1118 0.999569761581888 0.0124447062384495 0.0265597631345931 -0.00415266136950587 -0.0111477802439141 0.998764268063672 -0.0484320537957113 -0.0114988454422499 -0.0271296650690788 0.0481151340627455 0.99847329215526 -0.00568327389656575 4.08098629843575e-05 8.3960680620073e-06 -1.05096566031505e-05 2.95045433676618e-06 1.45339787064044e-06 8.64468583095353e-06 8.3960680620073e-06 7.46966336460488e-05 8.17204189917819e-06 -1.59023641032321e-06 -6.70419011049295e-06 -2.54505375834949e-05 -1.05096566031505e-05 8.17204189917819e-06 1.72947975996962e-05 -3.62315127198581e-06 -9.27207898865491e-06 -5.14512409666094e-06 2.95045433676618e-06 -1.59023641032321e-06 -3.62315127198581e-06 3.01879220327647e-05 -3.23959691159526e-05 5.66284212649734e-07 1.45339787064044e-06 -6.70419011049295e-06 -9.27207898865491e-06 -3.23959691159526e-05 0.000155121679440476 -1.80461329294853e-06 8.64468583095353e-06 -2.54505375834949e-05 -5.14512409666094e-06 5.66284212649734e-07 -1.80461329294853e-06 5.17664981016149e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 795 0 0 0 0 0 2449 +1077 1130 0.999662452870196 0.0130913980713019 0.0224409362122485 -0.013761690061567 -0.011947701858675 0.998659539397312 -0.0503624541801216 0.0154122497268402 -0.0230701699568882 0.0500773368629697 0.998478856857206 -0.00917295430042609 4.25690341444037e-05 -8.3893571731173e-06 -1.29043486707272e-05 -7.35718329100965e-08 1.31845510534746e-05 2.11125668208957e-05 -8.3893571731173e-06 7.74894382069014e-05 1.19924396296424e-05 5.64957999481976e-06 -2.33928792807891e-05 -2.45386197314367e-05 -1.29043486707272e-05 1.19924396296424e-05 2.01869207939696e-05 -7.61462084570701e-06 -7.29463946098767e-06 -3.76464012321055e-06 -7.35718329100965e-08 5.64957999481976e-06 -7.61462084570701e-06 5.12405525608325e-05 -7.49740357562557e-05 -1.85871692966005e-06 1.31845510534746e-05 -2.33928792807891e-05 -7.29463946098767e-06 -7.49740357562557e-05 0.000242148850885431 4.63599940131178e-06 2.11125668208957e-05 -2.45386197314367e-05 -3.76464012321055e-06 -1.85871692966005e-06 4.63599940131178e-06 6.385054128261e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 801 0 0 0 0 0 2460 +1077 1134 0.9994452315504 0.0127253310267913 0.0307781591624064 -0.00763113505007079 -0.0113726114180818 0.998978510067039 -0.0437332840496985 0.00740897367913897 -0.0313032400990881 0.0433589941591924 0.99856902855276 -0.0183593629759499 4.17719320537038e-05 8.48044822165913e-06 -1.02678297558296e-05 7.66285441620516e-06 -3.21704463304742e-06 6.0209238783652e-06 8.48044822165913e-06 0.000134639216892857 1.7033585271061e-05 1.42297260722321e-05 -3.38363448617081e-05 -4.79671268349802e-05 -1.02678297558296e-05 1.7033585271061e-05 1.98835123037341e-05 -3.57782871187764e-06 -9.38700961699611e-06 -6.65230878704336e-06 7.66285441620516e-06 1.42297260722321e-05 -3.57782871187764e-06 3.59240441570001e-05 -3.99631871720603e-05 -9.65877922855729e-06 -3.21704463304742e-06 -3.38363448617081e-05 -9.38700961699611e-06 -3.99631871720603e-05 0.000150940286260514 1.62786637075764e-05 6.0209238783652e-06 -4.79671268349802e-05 -6.65230878704336e-06 -9.65877922855729e-06 1.62786637075764e-05 6.07178067832925e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 784 0 0 0 0 0 2476 +1077 1117 0.99955455759498 0.0117709634612843 0.0274250033782439 -0.00140385620281103 -0.0103269004257459 0.998582505508729 -0.0522143162313369 -0.0203764141275848 -0.0280007413955471 0.0519078424816754 0.998259252083444 -0.00395246081558936 4.80394253040575e-05 3.20752972795204e-05 -2.8153363117675e-06 5.48001124351342e-06 -1.26758449391184e-05 5.48094220838216e-06 3.20752972795204e-05 7.0649453057368e-05 6.39420204080811e-06 3.6597527428082e-06 -2.02551035438216e-05 -1.04910742949509e-05 -2.8153363117675e-06 6.39420204080811e-06 1.44495193468177e-05 -2.66089081112058e-06 -3.13458308521527e-06 5.00714328854068e-07 5.48001124351342e-06 3.6597527428082e-06 -2.66089081112058e-06 3.08737391532698e-05 -3.29866504619984e-05 4.63063445941474e-06 -1.26758449391184e-05 -2.02551035438216e-05 -3.13458308521527e-06 -3.29866504619984e-05 0.000134556095143372 -8.12443912796838e-06 5.48094220838216e-06 -1.04910742949509e-05 5.00714328854068e-07 4.63063445941474e-06 -8.12443912796838e-06 4.25626761532419e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 755 0 0 0 0 0 2368 +1077 1122 0.999712591445512 0.0127307322296015 0.0203141074673722 -0.0141186867122021 -0.0119023535192987 0.999113055269899 -0.0403910481412642 0.0205990863224995 -0.0208102975951666 0.040137653719998 0.99897742730647 -0.0116968058547362 6.98643652533907e-05 3.33222513605642e-05 -8.91719159864161e-06 1.70479760968101e-05 -3.23444740833303e-05 7.90275218205516e-06 3.33222513605642e-05 8.17865353038266e-05 8.05434725796742e-06 5.64099872971888e-06 -2.76717196728055e-05 -1.94151671454687e-05 -8.91719159864161e-06 8.05434725796742e-06 1.85743919430928e-05 -2.59790609979341e-06 -1.04020848654941e-05 -4.43839766503765e-06 1.70479760968101e-05 5.64099872971888e-06 -2.59790609979341e-06 3.468324788077e-05 -4.37576389274931e-05 2.41719939073023e-06 -3.23444740833303e-05 -2.76717196728055e-05 -1.04020848654941e-05 -4.37576389274931e-05 0.000175623623164439 3.76006030498968e-06 7.90275218205516e-06 -1.94151671454687e-05 -4.43839766503765e-06 2.41719939073023e-06 3.76006030498968e-06 6.00484384048544e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 895 0 0 0 0 0 2324 +1077 1129 0.999622688945901 0.0123123263965197 0.0245537443839462 -0.0134919514739692 -0.0112453833824723 0.99900626999432 -0.0431278780444433 0.0164914996167715 -0.0250603491026725 0.0428354891502446 0.998767790716196 -0.0124686377712577 6.22457257156291e-05 1.84284602697788e-05 -1.08319628815101e-05 1.67258409947045e-05 -2.76260911500143e-05 2.90684279966441e-05 1.84284602697788e-05 6.95205778280207e-05 3.30895647170689e-06 -4.14115647314273e-06 1.95054766882785e-07 -1.32777805477629e-05 -1.08319628815101e-05 3.30895647170689e-06 1.61440416679627e-05 -4.47121999884342e-06 -6.01438378220753e-06 -2.49730333437982e-06 1.67258409947045e-05 -4.14115647314273e-06 -4.47121999884342e-06 4.20270493457161e-05 -5.8304590056353e-05 9.64401034483778e-06 -2.76260911500143e-05 1.95054766882785e-07 -6.01438378220753e-06 -5.8304590056353e-05 0.000225538469842767 -1.19400450414125e-05 2.90684279966441e-05 -1.32777805477629e-05 -2.49730333437982e-06 9.64401034483778e-06 -1.19400450414125e-05 6.63166586275461e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 869 0 0 0 0 0 2365 +1077 1135 0.999666999825658 0.0131221383707624 0.0222193371671029 -0.010727339836849 -0.0121220855793497 0.998933168331689 -0.0445598501795096 0.00557371825153488 -0.0227803533944002 0.0442756670349751 0.998759591096794 -0.00887171713869104 8.49774356089198e-05 3.84891702675962e-05 -9.50451698040692e-06 1.28672894459048e-05 -1.04664130487797e-05 2.44364437038343e-05 3.84891702675962e-05 0.000105646340280152 7.37363297634789e-06 1.08073127075109e-05 -2.03139644269616e-05 -2.30607876651487e-05 -9.50451698040692e-06 7.37363297634789e-06 1.83047548710693e-05 -4.81831573580952e-06 -9.79745556262101e-06 -3.40865230151885e-06 1.28672894459048e-05 1.08073127075109e-05 -4.81831573580952e-06 3.97838797108276e-05 -4.23142868732998e-05 6.3796631669879e-06 -1.04664130487797e-05 -2.03139644269616e-05 -9.79745556262101e-06 -4.23142868732998e-05 0.000171744374060786 -1.55415736759906e-05 2.44364437038343e-05 -2.30607876651487e-05 -3.40865230151885e-06 6.3796631669879e-06 -1.55415736759906e-05 7.41483019228119e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 872 0 0 0 0 0 2398 +1077 1128 0.999521365890773 0.012405209422155 0.028339899559366 -0.00844428664290562 -0.0110537020928397 0.998816818740684 -0.0473579800116258 0.00381186527753753 -0.0288938539811709 0.047022052059978 0.998475874431718 -0.0127399656912624 5.11189822349489e-05 6.92755472038166e-06 -1.45541681723938e-05 1.08095511678347e-05 3.51605715780096e-07 2.12173795075273e-05 6.92755472038166e-06 7.11777341672029e-05 8.32318162128269e-06 -2.76052585330497e-06 -1.06003791441448e-06 -1.99626816142855e-05 -1.45541681723938e-05 8.32318162128269e-06 2.04245955631645e-05 -8.13166875707017e-06 -9.98241205886365e-06 -3.58525122745944e-06 1.08095511678347e-05 -2.76052585330497e-06 -8.13166875707017e-06 3.97149794966971e-05 -4.06096501747448e-05 3.75410599875438e-06 3.51605715780096e-07 -1.06003791441448e-06 -9.98241205886365e-06 -4.06096501747448e-05 0.000162759817520263 -9.0572953642851e-06 2.12173795075273e-05 -1.99626816142855e-05 -3.58525122745944e-06 3.75410599875438e-06 -9.0572953642851e-06 6.82135301293081e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 800 0 0 0 0 0 2505 +1077 1119 0.999558466291259 0.0128275851256517 0.0268015955739601 -0.00488521078271464 -0.0114844107259064 0.99869905676803 -0.0496820120458698 -0.00447759425490819 -0.0274040284583242 0.0493522752311524 0.998405414725784 -0.00692305553162735 6.279493366295e-05 2.8482049341688e-05 -7.58696159323204e-06 1.7384438114491e-05 -2.39239068951775e-05 5.73441101382724e-06 2.8482049341688e-05 0.000110135025247348 8.30063428569973e-06 9.56488384010255e-06 -2.03067723681145e-05 -2.5599950423934e-05 -7.58696159323204e-06 8.30063428569973e-06 1.69999283879483e-05 -4.09558090254855e-06 -6.53034638633773e-06 -2.77948805114795e-06 1.7384438114491e-05 9.56488384010255e-06 -4.09558090254855e-06 3.52747072611523e-05 -2.93163099853296e-05 -1.34732460320594e-06 -2.39239068951775e-05 -2.03067723681145e-05 -6.53034638633773e-06 -2.93163099853296e-05 0.000119672472905238 -6.87658751889709e-08 5.73441101382724e-06 -2.5599950423934e-05 -2.77948805114795e-06 -1.34732460320594e-06 -6.87658751889709e-08 5.79391089940867e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 789 0 0 0 0 0 2465 +1077 1124 0.999619434812201 0.0128386369284307 0.0244162844748403 -0.0124298908561276 -0.0118304134540761 0.999089165985504 -0.0409985332407874 0.0172555569899532 -0.0249204105753097 0.0406940758859354 0.998860833812472 -0.0151094127426821 3.93633261572931e-05 6.2911009055368e-06 -1.05185944747795e-05 7.54163296822743e-06 -9.71597607546898e-06 9.61871495954586e-06 6.2911009055368e-06 8.90154290188359e-05 1.04483708880739e-05 6.91272435234289e-06 -3.14807394029136e-05 -3.05389269978645e-05 -1.05185944747795e-05 1.04483708880739e-05 1.79314643458374e-05 -6.9111004168462e-06 -9.06648798327936e-06 -4.10436873305153e-06 7.54163296822743e-06 6.91272435234289e-06 -6.9111004168462e-06 4.80627447296187e-05 -6.46306799560423e-05 -4.92455549694148e-06 -9.71597607546898e-06 -3.14807394029136e-05 -9.06648798327936e-06 -6.46306799560423e-05 0.000233218269137444 2.35859821152215e-05 9.61871495954586e-06 -3.05389269978645e-05 -4.10436873305153e-06 -4.92455549694148e-06 2.35859821152215e-05 5.06338437638234e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 881 0 0 0 0 0 2494 +1077 1126 0.999516250209651 0.0123429343694017 0.0285467605516085 -0.00554571634281842 -0.0109304092838562 0.998733143844151 -0.0491185661442368 -0.00387341228592358 -0.0291168631505116 0.0487827772716049 0.998384920219623 -0.0101450036873034 4.04165317195558e-05 1.46841760474671e-05 -8.48646596799439e-06 7.44329960842514e-06 -1.76612138326443e-06 1.22308054755381e-05 1.46841760474671e-05 0.000114681863842549 1.26137032144657e-05 7.25551825249582e-07 -8.67438452036357e-07 -1.90667113637061e-05 -8.48646596799439e-06 1.26137032144657e-05 1.9360147605414e-05 -8.36611851394064e-06 -5.2353301901473e-06 -2.14667549255484e-06 7.44329960842514e-06 7.25551825249582e-07 -8.36611851394064e-06 3.56302648177049e-05 -2.99585992459011e-05 3.0269153782967e-06 -1.76612138326443e-06 -8.67438452036357e-07 -5.2353301901473e-06 -2.99585992459011e-05 0.000128153009226978 -6.19808896640674e-06 1.22308054755381e-05 -1.90667113637061e-05 -2.14667549255484e-06 3.0269153782967e-06 -6.19808896640674e-06 4.96262767275387e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 799 0 0 0 0 0 2541 +1077 1121 0.999545871290489 0.0126855664603096 0.0273336347695899 -0.0101617827003887 -0.0115240416528744 0.999040998686035 -0.0422407316271062 0.00807040350315798 -0.0278432693863182 0.0419065549525544 0.998733494482832 -0.0151758475264305 3.84886964272989e-05 -2.19897755763788e-07 -1.13324682565648e-05 1.17136470442593e-06 9.24979474665125e-06 9.47210518323794e-06 -2.19897755763788e-07 9.18797078655427e-05 1.14197530918049e-05 7.51331874910609e-06 -1.21443094040868e-05 -3.01217223505735e-05 -1.13324682565648e-05 1.14197530918049e-05 1.76709279559771e-05 -3.2164574282732e-06 -9.32998603422868e-06 -4.75897930513261e-06 1.17136470442593e-06 7.51331874910609e-06 -3.2164574282732e-06 3.14665503373533e-05 -2.82745503764959e-05 -5.79938594417752e-06 9.24979474665125e-06 -1.21443094040868e-05 -9.32998603422868e-06 -2.82745503764959e-05 0.00011557822458454 1.03198616570159e-05 9.47210518323794e-06 -3.01217223505735e-05 -4.75897930513261e-06 -5.79938594417752e-06 1.03198616570159e-05 5.21622922031039e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 889 0 0 0 0 0 2394 +1077 1116 0.999622169684806 0.0124253496975726 0.0245179232304553 -0.00286614250758156 -0.0111100624891605 0.998528902504907 -0.0530716249405698 -0.0169762276053466 -0.0251412884739111 0.0527791772125959 0.998289674426533 -0.00155946561373002 4.37340057557921e-05 1.54879345266589e-05 -2.84501105951412e-06 -1.23564458439356e-06 -1.17835638731488e-06 1.0413238831596e-05 1.54879345266589e-05 0.000106341467645871 2.17267343421808e-05 -1.19594200294119e-06 -3.19820202824497e-05 -3.20269329924813e-05 -2.84501105951412e-06 2.17267343421808e-05 2.08655980601434e-05 -6.00168292897863e-06 -7.8815124569525e-06 -3.93109174458548e-06 -1.23564458439356e-06 -1.19594200294119e-06 -6.00168292897863e-06 2.90475042215804e-05 -1.87994986276139e-05 -3.47499432111952e-06 -1.17835638731488e-06 -3.19820202824497e-05 -7.8815124569525e-06 -1.87994986276139e-05 9.2907892692814e-05 1.20087965577618e-05 1.0413238831596e-05 -3.20269329924813e-05 -3.93109174458548e-06 -3.47499432111952e-06 1.20087965577618e-05 4.9329710741685e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 756 0 0 0 0 0 2436 +1077 1127 0.999514245504045 0.0123014279494092 0.0286347324919559 -0.0110739414920264 -0.0109625857387307 0.998860355169821 -0.0464522613436564 0.0134144671538522 -0.029173528213114 0.0461157862388127 0.99851000972007 -0.0136517755990584 5.37468333479638e-05 1.61113451180649e-05 -1.21424292047636e-05 5.24894278058946e-06 9.8323992153686e-06 1.42683298286744e-05 1.61113451180649e-05 0.000105391718102009 1.05853913763566e-05 9.54201052348671e-06 -2.61892927723579e-05 -3.20496982598351e-05 -1.21424292047636e-05 1.05853913763566e-05 1.88013931506959e-05 -8.21561512252292e-06 -3.79772809153292e-06 -4.19764686475043e-06 5.24894278058946e-06 9.54201052348671e-06 -8.21561512252292e-06 4.3777755709626e-05 -4.55634767620117e-05 -5.17957612994042e-06 9.8323992153686e-06 -2.61892927723579e-05 -3.79772809153292e-06 -4.55634767620117e-05 0.000145845523015001 1.67213474648471e-05 1.42683298286744e-05 -3.20496982598351e-05 -4.19764686475043e-06 -5.17957612994042e-06 1.67213474648471e-05 6.51397955942293e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 799 0 0 0 0 0 2495 +1077 1120 0.999586958628505 0.0127324647148667 0.0257642481376676 -0.00795605344142297 -0.01159028289267 0.998964036791661 -0.0440058920984011 0.00642598008998387 -0.0262978607928956 0.0436891009199424 0.998698996183797 -0.0114000054559138 3.94787920738404e-05 -2.80611885961669e-06 -1.30511165085937e-05 3.22102284396774e-06 7.78409868244827e-06 1.22744162196363e-05 -2.80611885961669e-06 0.000103758771119197 9.98706571044598e-06 8.77271016037462e-06 -3.29547389128818e-05 -4.37550735271391e-05 -1.30511165085937e-05 9.98706571044598e-06 1.66346421112485e-05 -3.17520824920529e-06 -9.97931135621956e-06 -6.17150909078364e-06 3.22102284396774e-06 8.77271016037462e-06 -3.17520824920529e-06 3.9763025040129e-05 -4.91546410952762e-05 -5.02993233553619e-06 7.78409868244827e-06 -3.29547389128818e-05 -9.97931135621956e-06 -4.91546410952762e-05 0.000190976672943719 1.48573768433154e-05 1.22744162196363e-05 -4.37550735271391e-05 -6.17150909078364e-06 -5.02993233553619e-06 1.48573768433154e-05 6.32875950059183e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 791 0 0 0 0 0 2469 +1077 1115 0.999470542153903 0.01177169885044 0.0303325315916545 -0.00700218404353126 -0.0104718522539279 0.999034707294168 -0.0426613868976097 -0.00514675252231517 -0.0308054488192605 0.042321161702276 0.998629032021007 -0.0100984895605018 5.02725098534068e-05 1.05175562748777e-05 -9.92967243535807e-06 3.37796348510724e-06 4.20363622518057e-06 1.31741881753329e-05 1.05175562748777e-05 0.000100248551992164 1.15600979446515e-05 2.84779911390596e-06 -6.06438797558699e-06 -3.3056270791588e-05 -9.92967243535807e-06 1.15600979446515e-05 1.93564853032765e-05 -5.18992573332021e-06 -5.19365211779192e-06 -3.9522604094548e-06 3.37796348510724e-06 2.84779911390596e-06 -5.18992573332021e-06 2.68084881554367e-05 -9.90854293871667e-06 8.64886605233337e-07 4.20363622518057e-06 -6.06438797558699e-06 -5.19365211779192e-06 -9.90854293871667e-06 6.97173353916346e-05 -3.83529059390008e-06 1.31741881753329e-05 -3.3056270791588e-05 -3.9522604094548e-06 8.64886605233337e-07 -3.83529059390008e-06 5.28235938368883e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 807 0 0 0 0 0 2394 +1077 1113 0.999554169852734 0.0122721267267046 0.0272186780651561 -0.00632525157898134 -0.0108682621632987 0.99863242371435 -0.0511386662316493 -0.00793980104018258 -0.0278090346391369 0.0508200473436017 0.998320579964389 -0.00181260544665241 4.33443852782155e-05 -6.88753104081772e-06 -1.25962144630673e-05 3.81587156497694e-06 5.42686104970644e-06 2.13418256753787e-05 -6.88753104081772e-06 0.000126523044843217 1.02616470087399e-05 2.81130341525301e-06 -2.04161460644413e-06 -6.46825657835235e-05 -1.25962144630673e-05 1.02616470087399e-05 1.78257032659612e-05 -6.22714383562303e-06 -6.17075991969656e-06 -7.65326379890799e-06 3.81587156497694e-06 2.81130341525301e-06 -6.22714383562303e-06 2.37045784392978e-05 -2.30637448710647e-06 6.45530431331385e-07 5.42686104970644e-06 -2.04161460644413e-06 -6.17075991969656e-06 -2.30637448710647e-06 6.6137457259101e-05 -3.26101988850341e-06 2.13418256753787e-05 -6.46825657835235e-05 -7.65326379890799e-06 6.45530431331385e-07 -3.26101988850341e-06 8.22940828683646e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 735 0 0 0 0 0 2482 +1077 1111 0.999679919685022 0.0126573052391128 0.0219054970870622 -0.00594818667382214 -0.0116720150163211 0.998939550324281 -0.0445369381904828 -0.00527671876739674 -0.0224459850308722 0.0442670015023385 0.998767545695186 -0.00271734458142932 3.33530421531641e-05 7.84597315648306e-06 -9.2125943707328e-06 1.82223213951525e-06 2.95809380932295e-06 -3.97590472361834e-06 7.84597315648306e-06 8.86376219418021e-05 1.00776943455951e-05 3.01059870167811e-07 -1.30848013357912e-05 -3.50762078415171e-05 -9.2125943707328e-06 1.00776943455951e-05 1.88565913723017e-05 -5.24906688399543e-06 -3.89426930008796e-06 -1.99069916015724e-06 1.82223213951525e-06 3.01059870167811e-07 -5.24906688399543e-06 2.62781392995899e-05 -1.18647969318596e-05 -4.96427677073687e-06 2.95809380932295e-06 -1.30848013357912e-05 -3.89426930008796e-06 -1.18647969318596e-05 7.34191045841363e-05 1.05213763271354e-05 -3.97590472361834e-06 -3.50762078415171e-05 -1.99069916015724e-06 -4.96427677073687e-06 1.05213763271354e-05 4.36972692748418e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 726 0 0 0 0 0 2483 +1077 1123 0.999508631517794 0.0124146857248949 0.0287814367219205 -0.00705053757884483 -0.0111497511193257 0.998982430738465 -0.0437010998241959 0.00350654474735685 -0.0292946850367591 0.0433587206247985 0.998629982913781 -0.0134681401306296 3.67781593345668e-05 -2.10678491732259e-06 -9.03810968614253e-06 4.18421915992408e-06 -2.17420464117701e-06 9.12857081619366e-06 -2.10678491732259e-06 0.00014022125810323 1.51594569887255e-05 7.69200164486106e-06 -2.04005458104356e-05 -5.0665715458551e-05 -9.03810968614253e-06 1.51594569887255e-05 1.74500211075382e-05 -5.58605600360844e-06 -6.69799901584561e-06 -4.0715218231006e-06 4.18421915992408e-06 7.69200164486106e-06 -5.58605600360844e-06 3.23115823187492e-05 -2.52480192762884e-05 -1.11963211522586e-06 -2.17420464117701e-06 -2.04005458104356e-05 -6.69799901584561e-06 -2.52480192762884e-05 0.000106529351717075 3.48576132202387e-07 9.12857081619366e-06 -5.0665715458551e-05 -4.0715218231006e-06 -1.11963211522586e-06 3.48576132202387e-07 5.77994148763794e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 793 0 0 0 0 0 2559 +1077 1112 0.999563453939972 0.0122154270294485 0.0269013919729205 -0.00485545752846191 -0.0108104361883366 0.998600653675949 -0.0517674506556587 -0.0139843151755893 -0.0274961091249361 0.0514540359977366 0.998296772589461 -0.00219988656643062 4.11621455623717e-05 6.04538000690709e-06 -1.13109154383825e-05 6.37422023696525e-06 -2.77751035922295e-06 1.13729105963694e-05 6.04538000690709e-06 9.93486263952296e-05 7.89001379666887e-06 6.6842602691886e-06 -1.6889644036245e-05 -3.99289143407743e-05 -1.13109154383825e-05 7.89001379666887e-06 1.80650452646995e-05 -6.7329870994861e-06 -4.75616224472187e-06 -5.24209120373717e-06 6.37422023696525e-06 6.6842602691886e-06 -6.7329870994861e-06 2.91897903630419e-05 -1.14044575641042e-05 2.28881704469056e-06 -2.77751035922295e-06 -1.6889644036245e-05 -4.75616224472187e-06 -1.14044575641042e-05 8.09707445215499e-05 -6.78240528241113e-07 1.13729105963694e-05 -3.99289143407743e-05 -5.24209120373717e-06 2.28881704469056e-06 -6.78240528241113e-07 5.78288269847626e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 765 0 0 0 0 0 2453 +1077 1106 0.999574255982972 0.0114341170035708 0.0268433929382279 -0.0132727565222867 -0.0103078967907805 0.999075954959151 -0.0417250942025478 0.011267728451905 -0.0272956780432007 0.0414306310694095 0.998768466046737 -0.0102243838557112 5.21076451514514e-05 1.56878905934945e-05 -9.55897190206052e-06 7.92014008593044e-06 -9.05973265214033e-06 7.54199980428696e-06 1.56878905934945e-05 0.000106392250856737 1.29295932669775e-05 2.2785232346579e-06 -7.88023067160838e-06 -4.2729251226488e-05 -9.55897190206052e-06 1.29295932669775e-05 1.91669405836008e-05 -6.06535674758878e-06 -5.62791392445508e-06 -3.44264738077906e-06 7.92014008593044e-06 2.2785232346579e-06 -6.06535674758878e-06 2.56311321620078e-05 -3.26589211731178e-06 -5.68621711863855e-07 -9.05973265214033e-06 -7.88023067160838e-06 -5.62791392445508e-06 -3.26589211731178e-06 7.03831901941622e-05 8.68463362900671e-07 7.54199980428696e-06 -4.2729251226488e-05 -3.44264738077906e-06 -5.68621711863855e-07 8.68463362900671e-07 5.47031108054628e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 807 0 0 0 0 0 2439 +1077 1110 0.999605851911659 0.0125227115811089 0.0251261321858802 -0.0048009055233433 -0.0113229842514934 0.99881488424343 -0.0473351565057497 -0.00516477397910183 -0.0256891193232932 0.04703199664526 0.998562997732218 -0.00599715076563778 4.14163237310339e-05 -3.75710302165377e-06 -1.30235639229082e-05 5.27708508630003e-06 1.44265060278538e-06 1.02012998860617e-05 -3.75710302165377e-06 0.000101954188193388 8.50154110867486e-06 5.06259113247154e-06 -1.30173359255391e-05 -4.89904596142912e-05 -1.30235639229082e-05 8.50154110867486e-06 1.68668810717585e-05 -3.61329347207749e-06 -7.87038049670486e-06 -6.32804499531723e-06 5.27708508630003e-06 5.06259113247154e-06 -3.61329347207749e-06 2.41554940716115e-05 -2.44801911163523e-06 1.15977842880652e-06 1.44265060278538e-06 -1.30173359255391e-05 -7.87038049670486e-06 -2.44801911163523e-06 6.64549598141877e-05 8.26111627948892e-06 1.02012998860617e-05 -4.89904596142912e-05 -6.32804499531723e-06 1.15977842880652e-06 8.26111627948892e-06 5.56844373991082e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 768 0 0 0 0 0 2357 +1077 1107 0.999631071261962 0.012194864992075 0.0242694589038823 -0.00868372020100502 -0.0110946988492662 0.998927138565967 -0.0449608662489128 0.00519166496407733 -0.0247917128312317 0.0446750165554933 0.998693903991939 -0.00532630586306237 3.32189089535551e-05 5.47689375368945e-06 -1.02693902941199e-05 6.10210407162812e-06 -4.36625536262203e-06 2.54510360869354e-06 5.47689375368945e-06 7.70509095240979e-05 5.22266115356566e-06 -2.56940740996375e-06 6.02620948691603e-06 -3.34973151026835e-05 -1.02693902941199e-05 5.22266115356566e-06 1.50061866755026e-05 -4.79068954173315e-06 -2.12079828691392e-06 -3.60374099771962e-06 6.10210407162812e-06 -2.56940740996375e-06 -4.79068954173315e-06 2.38746717369083e-05 -6.49993223254194e-06 6.18142018331718e-06 -4.36625536262203e-06 6.02620948691603e-06 -2.12079828691392e-06 -6.49993223254194e-06 6.22523427610005e-05 -6.92946257480269e-06 2.54510360869354e-06 -3.34973151026835e-05 -3.60374099771962e-06 6.18142018331718e-06 -6.92946257480269e-06 4.42813609252751e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 712 0 0 0 0 0 2335 +1077 1114 0.999706125433822 0.0125267383388056 0.0207543633168044 -0.00786022082662233 -0.011590261364228 0.998935737164714 -0.0446436877587279 -0.00286037560738454 -0.0212915150142892 0.0443900196190653 0.998787363529703 -0.00386854710299516 8.53570742256488e-05 2.14842990549701e-05 -1.19108659221286e-05 1.7310910030545e-05 -3.81990217559766e-05 2.80731826254558e-05 2.14842990549701e-05 9.13972118332078e-05 8.34405545598156e-06 -1.06917445649092e-06 -3.97612555486434e-06 -2.12874679234415e-05 -1.19108659221286e-05 8.34405545598156e-06 1.70485228881118e-05 -4.30472410392579e-06 -6.91412501441337e-06 -4.00523038787907e-06 1.7310910030545e-05 -1.06917445649092e-06 -4.30472410392579e-06 2.63538494312788e-05 -1.78450440121231e-05 8.99286030815206e-06 -3.81990217559766e-05 -3.97612555486434e-06 -6.91412501441337e-06 -1.78450440121231e-05 0.00011587888007024 -1.67532796581388e-05 2.80731826254558e-05 -2.12874679234415e-05 -4.00523038787907e-06 8.99286030815206e-06 -1.67532796581388e-05 5.58324378841014e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 846 0 0 0 0 0 2415 +1078 1118 0.999654337697084 0.0166397215546303 0.0203549696631471 -0.00381463240492611 -0.0158579134378512 0.999152467722835 -0.0379851658514979 -0.00667319841960855 -0.0209697807523323 0.0376492484646448 0.999070969643922 -0.00773886323442513 0.00010523800531347 4.68392108406976e-05 -9.22626034562823e-06 2.3393617486019e-05 -4.69404866635085e-05 2.54422467419698e-05 4.68392108406976e-05 9.64587349910592e-05 5.60186328440365e-06 6.4216388057509e-06 -1.64369191967952e-05 -1.70725491834327e-05 -9.22626034562823e-06 5.60186328440365e-06 1.71263973234975e-05 -6.17178709946784e-06 -3.195776323481e-06 -3.2248744752361e-06 2.3393617486019e-05 6.4216388057509e-06 -6.17178709946784e-06 3.71585417595065e-05 -4.33233243529717e-05 1.1139597720942e-05 -4.69404866635085e-05 -1.64369191967952e-05 -3.195776323481e-06 -4.33233243529717e-05 0.000176794224094701 -2.22746422613643e-05 2.54422467419698e-05 -1.70725491834327e-05 -3.2248744752361e-06 1.1139597720942e-05 -2.22746422613643e-05 7.17321927985637e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 769 0 0 0 0 0 2422 +1078 1124 0.99959565866754 0.0167237158517049 0.0229964454017888 -0.00289245875618625 -0.0157470656017646 0.998992915041472 -0.0420141121752625 -0.000937831625996599 -0.0236759181013058 0.0416349975988141 0.998852330365709 -0.0105783858619193 4.07735960788016e-05 1.75529910051442e-05 -9.21632937607396e-06 1.18874933147207e-05 -9.34676263232525e-06 7.7162967298374e-07 1.75529910051442e-05 4.94602934733014e-05 2.57395549137827e-06 -1.71721589923708e-07 -6.43195929312051e-06 -1.36896878863443e-05 -9.21632937607396e-06 2.57395549137827e-06 1.43420685573113e-05 -2.89535313028088e-06 -4.54252837735038e-06 -2.02116424412694e-06 1.18874933147207e-05 -1.71721589923708e-07 -2.89535313028088e-06 2.78512924335894e-05 -2.77784258519374e-05 2.18860630900475e-06 -9.34676263232525e-06 -6.43195929312051e-06 -4.54252837735038e-06 -2.77784258519374e-05 0.000129460164957765 2.17882459896793e-06 7.7162967298374e-07 -1.36896878863443e-05 -2.02116424412694e-06 2.18860630900475e-06 2.17882459896793e-06 4.71446192920446e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 881 0 0 0 0 0 2505 +1078 1122 0.99961478635836 0.0163043195867725 0.0224599211161397 -0.00548727018303495 -0.0153630351328375 0.99902192030847 -0.0414629942802404 0.00256282425878424 -0.0231139794331923 0.0411019696120324 0.998887567271099 -0.00931697224895625 3.14029940834857e-05 2.27884504069625e-05 -5.54408993945167e-06 1.86404813820346e-06 2.14811870844741e-06 -2.95281225561612e-07 2.27884504069625e-05 4.49129981639256e-05 2.65180730971408e-06 -8.01094177476303e-07 -6.86062983538387e-06 -2.83972407299996e-06 -5.54408993945167e-06 2.65180730971408e-06 1.38874536528157e-05 -1.63068905263267e-06 -1.8542895940879e-06 8.43388901544183e-08 1.86404813820346e-06 -8.01094177476303e-07 -1.63068905263267e-06 3.32722855713008e-05 -4.01157293337136e-05 5.74207368369451e-07 2.14811870844741e-06 -6.86062983538387e-06 -1.8542895940879e-06 -4.01157293337136e-05 0.000138061286868852 3.62250599520117e-06 -2.95281225561612e-07 -2.83972407299996e-06 8.43388901544183e-08 5.74207368369451e-07 3.62250599520117e-06 4.11658176735721e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 887 0 0 0 0 0 2372 +1078 1121 0.999677451210859 0.0168821275930544 0.0189733315074929 -0.00358035023185895 -0.01604395539467 0.998924919329051 -0.0434924940506237 -0.00880519533854549 -0.0196871794794284 0.0431740583149365 0.998873573407948 -0.00634625795610117 3.0949796656083e-05 1.24430619292132e-05 -4.15402420348283e-06 3.72305620220292e-06 -2.98103363762337e-06 -2.24697298798084e-06 1.24430619292132e-05 6.00326446367157e-05 4.81161022421369e-06 -3.1682127597436e-08 -5.08643439663279e-06 -1.72068042480386e-05 -4.15402420348283e-06 4.81161022421369e-06 1.38898215021893e-05 -7.13173101877319e-07 -3.46483358389817e-06 -2.49732880183388e-06 3.72305620220292e-06 -3.1682127597436e-08 -7.13173101877319e-07 3.05122996788925e-05 -3.61458451990237e-05 -4.46475000609439e-07 -2.98103363762337e-06 -5.08643439663279e-06 -3.46483358389817e-06 -3.61458451990237e-05 0.000129129330534513 2.86206912895705e-07 -2.24697298798084e-06 -1.72068042480386e-05 -2.49732880183388e-06 -4.46475000609439e-07 2.86206912895705e-07 4.13372823124374e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 892 0 0 0 0 0 2375 +1078 1119 0.999595770335249 0.0161171828153379 0.0234207674079344 -0.00631599608363977 -0.0152788400584935 0.999251333426089 -0.0355433494855307 0.00470543170107122 -0.0239760917237685 0.035171139650011 0.999093658253005 -0.0124535676556809 6.04895842812996e-05 5.00265021387142e-05 -2.18964050207374e-06 9.86919853170713e-06 -9.33203183992913e-06 6.48720394148709e-06 5.00265021387142e-05 9.71690312542021e-05 6.01107149722397e-06 1.25374457364445e-05 -1.91783303769638e-05 -1.60459998277136e-05 -2.18964050207374e-06 6.01107149722397e-06 1.53159618951071e-05 1.12985404513493e-07 -6.09142128926752e-06 -3.33889845495782e-06 9.86919853170713e-06 1.25374457364445e-05 1.12985404513493e-07 3.16766265374898e-05 -3.1593686353286e-05 3.39632408948416e-06 -9.33203183992913e-06 -1.91783303769638e-05 -6.09142128926752e-06 -3.1593686353286e-05 0.000133527679338174 -3.5355471055093e-06 6.48720394148709e-06 -1.60459998277136e-05 -3.33889845495782e-06 3.39632408948416e-06 -3.5355471055093e-06 7.23499668577901e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 758 0 0 0 0 0 2452 +1078 1080 0.999942417505132 -0.00558800108220203 0.00916165475762309 -0.0116451263356803 0.00579301318376312 0.999729935201037 -0.0225055029089002 0.0240640075864214 -0.00903341974256237 0.0225572805726905 0.999704739621114 0.00527987814467788 4.28016153311109e-05 2.43807397671305e-05 -6.04578398146865e-06 -4.09143684644083e-07 1.61612367774484e-05 -3.94278000801578e-06 2.43807397671305e-05 5.36276401504609e-05 -1.1388786569239e-06 -1.7544040851843e-06 1.32785327101984e-05 -1.79400524230581e-05 -6.04578398146865e-06 -1.1388786569239e-06 1.36237692059105e-05 -3.68620315747609e-06 -3.12746824726698e-07 -3.43403406714025e-07 -4.09143684644083e-07 -1.7544040851843e-06 -3.68620315747609e-06 2.76810415983269e-05 -2.06395518084921e-05 2.95744341185176e-07 1.61612367774484e-05 1.32785327101984e-05 -3.12746824726698e-07 -2.06395518084921e-05 9.97550662584191e-05 8.95884260271066e-06 -3.94278000801578e-06 -1.79400524230581e-05 -3.43403406714025e-07 2.95744341185176e-07 8.95884260271066e-06 3.96929858505916e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 838 0 0 0 0 0 2382 +1078 1081 0.999906639623725 -0.000762972186530257 0.0136429435912103 -0.00602641954458365 0.00116238119399364 0.999570222970304 -0.0292919480584287 0.00852394458086559 -0.0136147312257795 0.0293050716521973 0.999477789582695 -0.00222352398080663 4.67620671730356e-05 1.3588333441055e-05 -6.75181474371787e-06 5.09560852422747e-07 -8.95860048501851e-06 -5.633680591237e-06 1.3588333441055e-05 7.97250003381868e-05 1.20477711905543e-05 2.96914758395079e-06 -1.96006829734458e-05 -4.37105996731922e-05 -6.75181474371787e-06 1.20477711905543e-05 1.85159780030439e-05 -6.01113373415687e-06 -7.20348548842633e-06 -4.34456518594647e-06 5.09560852422747e-07 2.96914758395079e-06 -6.01113373415687e-06 2.5472264326566e-05 -6.33374316851036e-06 -7.88699012558032e-06 -8.95860048501851e-06 -1.96006829734458e-05 -7.20348548842633e-06 -6.33374316851036e-06 7.67679559921996e-05 1.61870851717632e-05 -5.633680591237e-06 -4.37105996731922e-05 -4.34456518594647e-06 -7.88699012558032e-06 1.61870851717632e-05 6.45356478619025e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 943 0 0 0 0 0 2302 +1078 1123 0.999658679826832 0.0165611047817996 0.0202052878049957 -0.00132156187603725 -0.0156358599987048 0.998859145640569 -0.0451212483459159 -0.0116048842649294 -0.0209294942360621 0.0447899205022644 0.9987771619798 -0.00712626890015315 5.56251147858018e-05 3.00108700933783e-05 -4.0075637607316e-06 4.31150543390345e-07 9.55849475839467e-06 1.39898579654326e-05 3.00108700933783e-05 5.31109837102518e-05 1.50510351832132e-06 3.95559676580525e-06 -1.37583708522404e-05 -6.59914234994484e-06 -4.0075637607316e-06 1.50510351832132e-06 1.2362581543685e-05 -1.01064931402148e-06 -2.81617356366481e-06 -1.54171825111218e-06 4.31150543390345e-07 3.95559676580525e-06 -1.01064931402148e-06 3.26087262526259e-05 -3.39446724633682e-05 -1.71054341397305e-06 9.55849475839467e-06 -1.37583708522404e-05 -2.81617356366481e-06 -3.39446724633682e-05 0.000130059628929446 1.47384920376859e-05 1.39898579654326e-05 -6.59914234994484e-06 -1.54171825111218e-06 -1.71054341397305e-06 1.47384920376859e-05 4.77621080844319e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 759 0 0 0 0 0 2539 +1078 1125 0.999587643052555 0.0166354940378127 0.0234052172550557 -0.00367249461575462 -0.0156641218334754 0.99903262363976 -0.0410907798738806 -0.00210826550059452 -0.0240661410247779 0.0407072136307016 0.998881246002046 -0.00771114305579841 4.51265498909255e-05 7.45105895897062e-06 -1.3907664697353e-05 9.66606266742813e-06 -3.52591913350968e-06 1.56574193124221e-07 7.45105895897062e-06 7.38197154493926e-05 5.18176359914477e-06 -2.60889138008711e-06 1.04038240154485e-05 -2.77410620573304e-05 -1.3907664697353e-05 5.18176359914477e-06 1.78205570492725e-05 -5.42174439084956e-06 -3.9257225899632e-06 -4.94056907104986e-06 9.66606266742813e-06 -2.60889138008711e-06 -5.42174439084956e-06 3.96940149753667e-05 -4.54604106111236e-05 9.0704235755943e-07 -3.52591913350968e-06 1.04038240154485e-05 -3.9257225899632e-06 -4.54604106111236e-05 0.000161476582193372 1.38547919451776e-06 1.56574193124221e-07 -2.77410620573304e-05 -4.94056907104986e-06 9.0704235755943e-07 1.38547919451776e-06 4.95284968457818e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 885 0 0 0 0 0 2387 +1078 1128 0.999571257897217 0.016167755166344 0.0244111466067649 -0.00925513350937716 -0.0153503431190854 0.99932720568996 -0.0333092019421353 0.0147957582036195 -0.0249332579480131 0.0329202014085085 0.999146932631693 -0.0156542886214054 6.65148084414629e-05 3.65901287598144e-05 -7.92549605604422e-06 6.12233736687563e-06 -6.36612756639334e-06 -8.58442913745837e-06 3.65901287598144e-05 7.02488759141304e-05 2.78801002186467e-06 6.12478988297258e-06 -1.80501564233639e-05 -2.46651558256577e-05 -7.92549605604422e-06 2.78801002186467e-06 1.52010086630789e-05 -1.95060853578644e-06 -8.63031540388286e-06 -3.38963515485862e-06 6.12233736687563e-06 6.12478988297258e-06 -1.95060853578644e-06 3.1109833288407e-05 -3.78316910939975e-05 -4.95779545867785e-06 -6.36612756639334e-06 -1.80501564233639e-05 -8.63031540388286e-06 -3.78316910939975e-05 0.000160681031993137 1.72403377738176e-05 -8.58442913745837e-06 -2.46651558256577e-05 -3.38963515485862e-06 -4.95779545867785e-06 1.72403377738176e-05 6.83598173023322e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 761 0 0 0 0 0 2479 +1078 1120 0.999658424634668 0.0166560352508939 0.0201397752384527 -0.00551949281441456 -0.0157515507989389 0.998895674694499 -0.0442642036418926 0.00281734556707581 -0.0208548005112218 0.0439318513876148 0.998816834924849 -0.00488051935985331 4.6771307985761e-05 2.01147277156966e-05 -6.79176622410824e-06 6.55191232766515e-06 -7.68722707826546e-06 1.32114028066728e-05 2.01147277156966e-05 5.41433188405514e-05 1.47459687802474e-07 -1.0476966581221e-06 4.80536352900612e-06 -5.0794890351716e-06 -6.79176622410824e-06 1.47459687802474e-07 1.48638425404215e-05 -5.54953573545662e-06 -6.13014565528597e-07 -2.4983771406945e-07 6.55191232766515e-06 -1.0476966581221e-06 -5.54953573545662e-06 3.21115380499803e-05 -1.98646565917016e-05 6.21793185352051e-06 -7.68722707826546e-06 4.80536352900612e-06 -6.13014565528597e-07 -1.98646565917016e-05 9.4272995067349e-05 -1.63303942891579e-05 1.32114028066728e-05 -5.0794890351716e-06 -2.4983771406945e-07 6.21793185352051e-06 -1.63303942891579e-05 5.78113773397767e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 767 0 0 0 0 0 2521 +1078 1130 0.999582339269831 0.0167256430124801 0.023566923551264 -0.0164442035877121 -0.0159167105294106 0.999291530567309 -0.0341041824761847 0.0342293128025742 -0.0241206414876345 0.0337148305981957 0.999140382955248 -0.0154959026316463 8.45581576401302e-05 4.14036893743898e-05 -5.24365036525925e-06 1.556412599855e-05 -3.86507542789789e-05 3.96019736910989e-07 4.14036893743898e-05 6.54294938237007e-05 3.9798416851208e-07 -2.82623847893767e-06 1.32944577553918e-05 -1.48974651483354e-05 -5.24365036525925e-06 3.9798416851208e-07 1.47629306171484e-05 -2.60578312875227e-06 -4.39751823447046e-06 -1.7819184188376e-06 1.556412599855e-05 -2.82623847893767e-06 -2.60578312875227e-06 3.96635140956331e-05 -6.50152451418743e-05 5.08159044870348e-06 -3.86507542789789e-05 1.32944577553918e-05 -4.39751823447046e-06 -6.50152451418743e-05 0.000258661152772844 -1.43595135990115e-05 3.96019736910989e-07 -1.48974651483354e-05 -1.7819184188376e-06 5.08159044870348e-06 -1.43595135990115e-05 4.64613256761924e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 759 0 0 0 0 0 2416 +1078 1129 0.999666171914828 0.0171656839583838 0.0193102051619098 -0.00828567034275726 -0.0164044265515362 0.999107933246114 -0.038913140636481 0.0119345105198238 -0.0199609498438681 0.0385833774949807 0.99905599615958 -0.00788635910711777 4.78603618642685e-05 3.50882562508117e-05 -3.52850437947595e-06 1.12824851365759e-05 -1.79348265051542e-05 -1.62289415657568e-06 3.50882562508117e-05 6.38127079034644e-05 2.89036252196763e-06 5.56840180704109e-06 -1.2180248269828e-05 -1.24375454717564e-05 -3.52850437947595e-06 2.89036252196763e-06 1.23904727834539e-05 -1.07319000110958e-07 -2.20409104477538e-07 -3.96003506459145e-07 1.12824851365759e-05 5.56840180704109e-06 -1.07319000110958e-07 4.11147788623071e-05 -6.37029720081192e-05 2.82265190212178e-06 -1.79348265051542e-05 -1.2180248269828e-05 -2.20409104477538e-07 -6.37029720081192e-05 0.000209690599810903 -8.55202147009616e-06 -1.62289415657568e-06 -1.24375454717564e-05 -3.96003506459145e-07 2.82265190212178e-06 -8.55202147009616e-06 4.09706024118471e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 860 0 0 0 0 0 2424 +1078 1127 0.999599313561858 0.016280846083112 0.0231548348618584 -0.00751338201945418 -0.015340093661209 0.999072206534097 -0.040241864489068 0.00852355558144449 -0.0237885235592134 0.039870542784231 0.998921641554013 -0.0149178614601492 6.8788128696653e-05 3.64617579300976e-05 -6.50908078383933e-06 6.82078963877993e-06 -1.88201679313919e-06 1.37186791853119e-05 3.64617579300976e-05 7.15589204618458e-05 4.36352212714277e-06 3.46459789164108e-06 -1.22893441056047e-05 -8.87620071218461e-06 -6.50908078383933e-06 4.36352212714277e-06 1.61243759088025e-05 -2.42253531890712e-06 -1.09766146030626e-05 -4.22312301644081e-06 6.82078963877993e-06 3.46459789164108e-06 -2.42253531890712e-06 4.65990980169851e-05 -8.09372434262413e-05 -5.55045377412575e-06 -1.88201679313919e-06 -1.22893441056047e-05 -1.09766146030626e-05 -8.09372434262413e-05 0.00032131335640153 2.78778663063594e-05 1.37186791853119e-05 -8.87620071218461e-06 -4.22312301644081e-06 -5.55045377412575e-06 2.78778663063594e-05 6.28633939196922e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 776 0 0 0 0 0 2466 +1078 1131 0.999596443379203 0.0167216431977392 0.0229638200745383 -0.00995157841374192 -0.0157743137527718 0.999041484695034 -0.0408323754387584 0.0168360717402565 -0.0236245933145394 0.0404536587604893 0.998902087335697 -0.00807919559479718 4.76129254684506e-05 2.97322003719857e-05 -6.0920241622247e-06 6.00838036515809e-06 -3.4191318734904e-06 -2.78338460027206e-06 2.97322003719857e-05 4.80554436603897e-05 -9.22090211231581e-08 2.21910752778599e-06 -1.06999427838711e-05 -8.17373925104814e-06 -6.0920241622247e-06 -9.22090211231581e-08 1.25347946943133e-05 3.84146899774124e-07 -2.20136864052153e-06 -2.10119702732438e-06 6.00838036515809e-06 2.21910752778599e-06 3.84146899774124e-07 3.82804787088517e-05 -5.57939277477554e-05 -2.19824315643628e-06 -3.4191318734904e-06 -1.06999427838711e-05 -2.20136864052153e-06 -5.57939277477554e-05 0.000191857838966294 9.18076009448243e-06 -2.78338460027206e-06 -8.17373925104814e-06 -2.10119702732438e-06 -2.19824315643628e-06 9.18076009448243e-06 3.90346462577241e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 863 0 0 0 0 0 2437 +1078 1137 0.999652415701561 0.017370422880638 0.0198322008607692 -0.00251737664160375 -0.0164852553439782 0.998897442209502 -0.0439560724309874 -0.000892975413872278 -0.0205738702795057 0.0436138550951665 0.998836596999459 -0.00513792411912091 3.67812064253764e-05 1.95334795232163e-05 -5.38716447269561e-06 4.10540555659512e-07 6.46907580342052e-06 -5.73428201066092e-06 1.95334795232163e-05 4.58709896832552e-05 2.74250348289222e-06 -1.01787301178836e-07 -9.59859039987715e-06 -1.37307032669797e-05 -5.38716447269561e-06 2.74250348289222e-06 1.26253585896343e-05 -1.78212663245127e-06 -2.55154751659902e-06 -3.34931568021597e-07 4.10540555659512e-07 -1.01787301178836e-07 -1.78212663245127e-06 2.83634091699806e-05 -2.16575442560896e-05 -5.86906786346211e-07 6.46907580342052e-06 -9.59859039987715e-06 -2.55154751659902e-06 -2.16575442560896e-05 9.81517094773595e-05 2.02276929512672e-06 -5.73428201066092e-06 -1.37307032669797e-05 -3.34931568021597e-07 -5.86906786346211e-07 2.02276929512672e-06 4.34250045683281e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 866 0 0 0 0 0 2435 +1078 1133 0.999659027328481 0.0168616785568345 0.0199377249685603 -0.00266831650901448 -0.0159987001745692 0.998960758007921 -0.0426783967946793 -0.00857784876560537 -0.0206366342556194 0.0423448669437731 0.998889904629191 -0.00555140295981124 5.49717568841128e-05 2.00444796309068e-05 -6.51266813912259e-06 7.13681545901726e-06 -7.38482045977547e-06 1.70506856547352e-05 2.00444796309068e-05 6.36456979946043e-05 2.50618426354292e-06 -3.9471820469317e-06 6.03372031766434e-06 -1.20551991234002e-05 -6.51266813912259e-06 2.50618426354292e-06 1.50750629191286e-05 -2.0111858624847e-06 -3.15685339163374e-06 -2.53840597588264e-06 7.13681545901726e-06 -3.9471820469317e-06 -2.0111858624847e-06 2.93084751470408e-05 -2.24301058656223e-05 -6.7468764531249e-07 -7.38482045977547e-06 6.03372031766434e-06 -3.15685339163374e-06 -2.24301058656223e-05 0.000114087842948017 6.52970481145177e-06 1.70506856547352e-05 -1.20551991234002e-05 -2.53840597588264e-06 -6.7468764531249e-07 6.52970481145177e-06 6.41123829652505e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 770 0 0 0 0 0 2370 +1078 1116 0.999625775275765 0.0160377765115099 0.0221607565054435 -0.00252691274366705 -0.0150044330763266 0.998827179566704 -0.0460340346578688 -0.0151210586274668 -0.0228730494771626 0.0456842979960368 0.998694031485232 0.000486368944602488 0.00012518837786811 5.54192257663944e-05 -1.76150867695365e-07 1.65485410347815e-05 -4.06282162175829e-05 4.87845011652635e-05 5.54192257663944e-05 0.000100293562064279 6.76101695816318e-06 7.53117589889949e-06 -1.03345679775718e-05 -2.47549710641296e-05 -1.76150867695365e-07 6.76101695816318e-06 1.35896675923557e-05 -5.41898115180585e-07 6.51926179791623e-07 -2.03660025496966e-06 1.65485410347815e-05 7.53117589889949e-06 -5.41898115180585e-07 3.09178102051444e-05 -3.31049067984789e-05 6.7372981381185e-06 -4.06282162175829e-05 -1.03345679775718e-05 6.51926179791623e-07 -3.31049067984789e-05 0.000140201149367401 -3.00794611249364e-05 4.87845011652635e-05 -2.47549710641296e-05 -2.03660025496966e-06 6.7372981381185e-06 -3.00794611249364e-05 0.000101198066920516 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 728 0 0 0 0 0 2407 +1078 1126 0.999540205439349 0.0162644616800892 0.0255899393614334 -0.00743603550820464 -0.0153768388617222 0.999286088199895 -0.0345089373463198 0.00842408412944717 -0.0261329396908492 0.0340995779505921 0.999076717898433 -0.0185438932422222 5.1464153686668e-05 2.71096213951915e-05 -3.83723908740055e-06 8.32475357976285e-06 -1.24316145415076e-05 9.64957391892429e-06 2.71096213951915e-05 6.19120988992304e-05 4.47787773650495e-06 3.44679918953977e-06 -9.69923972138949e-06 -5.92457818717148e-06 -3.83723908740055e-06 4.47787773650495e-06 1.56046263161141e-05 -2.59089145865818e-06 -1.00778971688161e-05 -7.33204621687179e-07 8.32475357976285e-06 3.44679918953977e-06 -2.59089145865818e-06 3.11865786691886e-05 -2.90850075638387e-05 5.93466776224944e-06 -1.24316145415076e-05 -9.69923972138949e-06 -1.00778971688161e-05 -2.90850075638387e-05 0.000148894755417345 -3.43538820329575e-06 9.64957391892429e-06 -5.92457818717148e-06 -7.33204621687179e-07 5.93466776224944e-06 -3.43538820329575e-06 4.9132882830048e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 766 0 0 0 0 0 2512 +1078 1138 0.999557210099337 0.0165015226820649 0.0247605227651425 -0.0120269017228102 -0.0155612920963731 0.999168052517832 -0.0376968037904294 0.0254356521199129 -0.02536197797336 0.0372948062992165 0.998982416009603 -0.0069457421292981 4.40589024052632e-05 1.2993624251567e-05 -1.01144705890473e-05 5.51172980010224e-06 -5.14313163271589e-06 1.15129783392013e-06 1.2993624251567e-05 8.52237560146235e-05 5.42233639655439e-06 -2.60702470879441e-06 6.17134233055511e-06 -3.43791028696078e-05 -1.01144705890473e-05 5.42233639655439e-06 1.7060094311992e-05 -4.01631574630127e-06 -8.92517549442066e-07 -3.65541521529231e-06 5.51172980010224e-06 -2.60702470879441e-06 -4.01631574630127e-06 2.37343044981902e-05 -6.97663628653469e-06 1.99144705410583e-06 -5.14313163271589e-06 6.17134233055511e-06 -8.92517549442066e-07 -6.97663628653469e-06 7.45880260848315e-05 -7.06239101404592e-06 1.15129783392013e-06 -3.43791028696078e-05 -3.65541521529231e-06 1.99144705410583e-06 -7.06239101404592e-06 5.12734357761758e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 845 0 0 0 0 0 2390 +1078 1115 0.999567712374313 0.0161944003185089 0.0245383328102482 -0.000982947718420843 -0.0151482520789667 0.998992843465386 -0.0422354017844641 -0.0142372184494153 -0.0251975958721205 0.0418454310918995 0.998806308079298 -0.0027850036874542 3.60909569388919e-05 1.59370239981153e-05 -7.90275924697804e-06 3.86592092123074e-06 -4.00122261880029e-06 -3.25062795577914e-06 1.59370239981153e-05 6.03180004781362e-05 4.2720649831712e-06 2.69025242366207e-06 -5.85025313836817e-06 -2.19290211732794e-05 -7.90275924697804e-06 4.2720649831712e-06 1.6770427366395e-05 -3.74545086856824e-06 1.14523771556572e-06 -4.10829702513042e-06 3.86592092123074e-06 2.69025242366207e-06 -3.74545086856824e-06 2.57333949370185e-05 -1.59797283381424e-05 2.65832577554684e-07 -4.00122261880029e-06 -5.85025313836817e-06 1.14523771556572e-06 -1.59797283381424e-05 8.08858004748398e-05 -1.33029515205242e-06 -3.25062795577914e-06 -2.19290211732794e-05 -4.10829702513042e-06 2.65832577554684e-07 -1.33029515205242e-06 4.31948745634054e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 789 0 0 0 0 0 2429 +1078 1136 0.999607287335089 0.0167420391636711 0.0224716539495138 -0.00666995722268583 -0.0159131811620888 0.999204388395527 -0.0365699449879767 0.00763317442071903 -0.0230660306920619 0.0361979880071145 0.999078407279604 -0.0126425095092297 7.04769582258528e-05 2.33621222747782e-05 -1.09087794293866e-05 1.77483139272421e-05 -3.4308383496684e-05 2.28585171996557e-05 2.33621222747782e-05 7.48640495332697e-05 1.7603399802291e-06 -7.12983250199241e-07 1.12440582936405e-05 -1.73118680713958e-05 -1.09087794293866e-05 1.7603399802291e-06 1.69717724733689e-05 -7.63320312491974e-06 5.08095749010065e-08 -2.65061483463849e-06 1.77483139272421e-05 -7.12983250199241e-07 -7.63320312491974e-06 3.67255791548517e-05 -3.17079450374102e-05 1.30332325624375e-05 -3.4308383496684e-05 1.12440582936405e-05 5.08095749010065e-08 -3.17079450374102e-05 0.000154431905851555 -2.87191487999535e-05 2.28585171996557e-05 -1.73118680713958e-05 -2.65061483463849e-06 1.30332325624375e-05 -2.87191487999535e-05 5.93421858122635e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 771 0 0 0 0 0 2450 +1078 1135 0.999684216318578 0.0166349007978729 0.0188347476477722 -0.00850353949583344 -0.0158862577349618 0.999104184923894 -0.0392231370843879 0.0073231686390445 -0.0194703481912548 0.038911537402257 0.999052950447725 -0.01146058863155 3.32908450510423e-05 2.02924165466715e-05 -5.69356085563818e-06 4.30348363637979e-06 -4.57931492864621e-06 -5.53510751412754e-06 2.02924165466715e-05 6.78887774891291e-05 5.81689095187855e-06 4.06650490222998e-06 -1.97013123438664e-05 -2.1558775229024e-05 -5.69356085563818e-06 5.81689095187855e-06 1.48782438327957e-05 -2.47827352829104e-06 -1.27810734088513e-06 -2.69432153712949e-06 4.30348363637979e-06 4.06650490222998e-06 -2.47827352829104e-06 3.57396508838856e-05 -4.58928144272703e-05 -5.41760639347991e-06 -4.57931492864621e-06 -1.97013123438664e-05 -1.27810734088513e-06 -4.58928144272703e-05 0.000167904819611406 1.71135632848382e-05 -5.53510751412754e-06 -2.1558775229024e-05 -2.69432153712949e-06 -5.41760639347991e-06 1.71135632848382e-05 4.96317045954131e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 847 0 0 0 0 0 2421 +1078 1132 0.999685687256761 0.0164789071153423 0.0188937109711749 -0.0067068323155814 -0.0156946357601274 0.999038651887923 -0.0409322665182176 0.00468142035882837 -0.0195500665557768 0.0406228710733916 0.998983271753546 -0.00768490241643695 3.97901163507084e-05 1.56958864963673e-05 -7.02959164280402e-06 5.36262088410103e-06 -4.79613890040584e-06 5.47385944066316e-08 1.56958864963673e-05 5.87205401752096e-05 7.57977013921256e-06 -5.12347876889675e-06 -5.65039668805228e-06 -1.05552896175388e-05 -7.02959164280402e-06 7.57977013921256e-06 1.77241844330474e-05 -6.86488441629826e-06 -2.79582997725612e-06 -3.95811627910508e-06 5.36262088410103e-06 -5.12347876889675e-06 -6.86488441629826e-06 2.97726018976148e-05 -1.51440325803724e-05 -1.37724716884496e-06 -4.79613890040584e-06 -5.65039668805228e-06 -2.79582997725612e-06 -1.51440325803724e-05 8.7948531121976e-05 5.31263057714455e-06 5.47385944066316e-08 -1.05552896175388e-05 -3.95811627910508e-06 -1.37724716884496e-06 5.31263057714455e-06 4.88795386149065e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 865 0 0 0 0 0 2309 +1078 1140 0.99959244664674 0.0164533507892146 0.0233286916605129 -0.00588522329819559 -0.0154879317604088 0.999040049267047 -0.0409768706745871 0.00751630716557311 -0.0239805040933078 0.04059885722904 0.99888771551918 -0.00414487473983578 3.62649838092091e-05 1.98497325475999e-05 -6.3336056805758e-06 3.99997030571951e-06 -1.83543643313017e-06 -2.78789152167961e-06 1.98497325475999e-05 6.81650322240398e-05 6.07756819848683e-06 5.0977805779392e-07 -1.28679390077228e-05 -2.4985720055733e-05 -6.3336056805758e-06 6.07756819848683e-06 1.76569771498586e-05 -5.80496459100041e-06 -5.12504095625502e-06 -4.39744215123927e-06 3.99997030571951e-06 5.0977805779392e-07 -5.80496459100041e-06 2.68173853592518e-05 -8.32115983244867e-06 3.12742162655299e-06 -1.83543643313017e-06 -1.28679390077228e-05 -5.12504095625502e-06 -8.32115983244867e-06 7.7199153595196e-05 2.87532936350923e-06 -2.78789152167961e-06 -2.4985720055733e-05 -4.39744215123927e-06 3.12742162655299e-06 2.87532936350923e-06 4.29621268552463e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 838 0 0 0 0 0 2473 +1079 1081 0.999965266792271 0.00369599918124017 0.0074702609803102 -0.00436326049104006 -0.0034671707162901 0.999531308321883 -0.0304161537931674 -0.00370588723127884 -0.00757917781067139 0.0303891966724654 0.999509406053448 0.00106209080247166 8.95799937685401e-05 4.82822362511615e-05 -8.08828948528135e-07 9.73194067016561e-06 -2.24356663948591e-05 9.78356496964919e-06 4.82822362511615e-05 6.80214022283536e-05 2.4729158507666e-06 3.70816570663906e-06 -5.47399001964159e-06 -1.89039297998709e-05 -8.08828948528135e-07 2.4729158507666e-06 1.31296172033639e-05 -2.35304019907539e-06 -2.83879856885108e-06 -7.3472198742598e-08 9.73194067016561e-06 3.70816570663906e-06 -2.35304019907539e-06 2.14674070897537e-05 -7.0234107030901e-06 2.69206184503884e-06 -2.24356663948591e-05 -5.47399001964159e-06 -2.83879856885108e-06 -7.0234107030901e-06 6.99867324745241e-05 -8.92677846994659e-06 9.78356496964919e-06 -1.89039297998709e-05 -7.3472198742598e-08 2.69206184503884e-06 -8.92677846994659e-06 5.7228890941148e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 820 0 0 0 0 0 2362 +1079 1082 0.999809667593323 0.0147119394739649 0.0128135640570369 -0.0135102569505503 -0.0143320569501513 0.999469358366229 -0.0292505355605022 0.0086105021835457 -0.0132370967552184 0.0290613235058725 0.999489979312239 0.00024825333906787 4.14680469622048e-05 1.28523245401873e-05 -8.56857543912532e-06 6.18900317828179e-06 -3.17416323486634e-06 1.76891169650893e-05 1.28523245401873e-05 5.48262036785049e-05 1.86456483290437e-06 -2.32443004185961e-06 1.40180530002286e-05 -2.47615462622221e-05 -8.56857543912532e-06 1.86456483290437e-06 1.5317308584423e-05 -5.74912458001159e-06 -2.56269048278624e-06 -3.30810945139452e-06 6.18900317828179e-06 -2.32443004185961e-06 -5.74912458001159e-06 2.77511307961543e-05 -1.9737050218182e-05 2.08496980096524e-06 -3.17416323486634e-06 1.40180530002286e-05 -2.56269048278624e-06 -1.9737050218182e-05 9.78102644320128e-05 -5.31511699099858e-06 1.76891169650893e-05 -2.47615462622221e-05 -3.30810945139452e-06 2.08496980096524e-06 -5.31511699099858e-06 6.87609167373404e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 872 0 0 0 0 0 2459 +1078 1134 0.999681873308183 0.0169059605168779 0.0187173897230152 -0.00458694944814585 -0.0160936838749429 0.998957092466994 -0.0427284536254611 -0.00147784350252455 -0.0194202347662141 0.0424136288106965 0.998911376736061 -0.00830067575694345 9.64848011349628e-05 4.38630252102241e-05 -6.04479522404822e-06 1.83545652820752e-05 -1.79589383589988e-05 1.49393616126447e-05 4.38630252102241e-05 6.74554275450365e-05 7.7790355719049e-07 4.39564218788501e-06 -8.40742001633003e-06 -1.12415894419119e-05 -6.04479522404822e-06 7.7790355719049e-07 1.57962772317349e-05 -1.42889840139002e-06 -6.45150280488701e-06 -1.96732080941662e-06 1.83545652820752e-05 4.39564218788501e-06 -1.42889840139002e-06 3.38946641984067e-05 -3.51743869314776e-05 5.81054078723267e-06 -1.79589383589988e-05 -8.40742001633003e-06 -6.45150280488701e-06 -3.51743869314776e-05 0.000150807545744533 -3.82790011742493e-07 1.49393616126447e-05 -1.12415894419119e-05 -1.96732080941662e-06 5.81054078723267e-06 -3.82790011742493e-07 6.09880655923654e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 766 0 0 0 0 0 2428 +1078 1114 0.999610688615142 0.0165889376807001 0.0224338662068656 -0.00278552357339836 -0.0155920581554958 0.998914075790343 -0.0439039509657154 -0.00811344558912834 -0.0231378246349421 0.0435370685112141 0.998783842849199 -0.00299810148324013 3.48488018828968e-05 2.21686811669298e-05 -4.40533679473726e-06 2.76563914081679e-06 -2.8636050121384e-06 3.22477186897901e-07 2.21686811669298e-05 5.35162094271291e-05 3.05962212567088e-06 -1.13693768151441e-06 -1.14265271160285e-05 -1.09137656478859e-05 -4.40533679473726e-06 3.05962212567088e-06 1.30512060655837e-05 -1.28637322422425e-06 -2.10105386695303e-06 3.38284020671031e-07 2.76563914081679e-06 -1.13693768151441e-06 -1.28637322422425e-06 2.24259557281696e-05 -1.06232957472752e-05 2.63710730210429e-06 -2.8636050121384e-06 -1.14265271160285e-05 -2.10105386695303e-06 -1.06232957472752e-05 8.04520506409907e-05 6.28071904487663e-08 3.22477186897901e-07 -1.09137656478859e-05 3.38284020671031e-07 2.63710730210429e-06 6.28071904487663e-08 3.69330556662858e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 823 0 0 0 0 0 2472 +1078 1113 0.99969150521638 0.0159809971019973 0.0190132093512526 -0.00920998517241201 -0.0151287533140915 0.99891021175482 -0.0441532521463854 -0.000904573222109836 -0.0196981019737936 0.0438519849444341 0.998843825728058 0.000924665896121862 0.000117459926554716 4.0411703913795e-05 -8.72255087367769e-06 2.53024973026495e-05 -4.85745118566759e-05 2.04518721487179e-05 4.0411703913795e-05 9.9246438369945e-05 1.97233311525504e-06 5.63765901785594e-06 -1.05497772510583e-06 -3.71295171830331e-05 -8.72255087367769e-06 1.97233311525504e-06 1.5617545702429e-05 -5.07147940827828e-06 -4.03464934806877e-06 -2.57671791641277e-06 2.53024973026495e-05 5.63765901785594e-06 -5.07147940827828e-06 2.85584214732073e-05 -1.75607468330893e-05 3.66396862119678e-06 -4.85745118566759e-05 -1.05497772510583e-06 -4.03464934806877e-06 -1.75607468330893e-05 0.000111143996451928 -1.48203415011462e-05 2.04518721487179e-05 -3.71295171830331e-05 -2.57671791641277e-06 3.66396862119678e-06 -1.48203415011462e-05 8.08214786283281e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 694 0 0 0 0 0 2399 +1078 1139 0.99959209975679 0.0163037730312534 0.0234482640883305 -0.0105504147050564 -0.0154041382464806 0.999157148449168 -0.0380487217631664 0.0199547569941185 -0.0240488384063353 0.0376720013786487 0.999000737579024 -0.0079171493093533 3.53196686246321e-05 1.64606128154334e-05 -5.89340099928328e-06 6.18509080735662e-06 -6.88910280897935e-06 -5.24326182185359e-06 1.64606128154334e-05 6.03593266095338e-05 4.32908986407963e-06 1.329645000382e-06 -4.99937148850312e-06 -2.14867668094578e-05 -5.89340099928328e-06 4.32908986407963e-06 1.48059176758877e-05 -2.52613989210335e-06 -1.60882657731031e-06 -5.29287034727465e-06 6.18509080735662e-06 1.329645000382e-06 -2.52613989210335e-06 3.05097075666656e-05 -2.49832354694474e-05 2.92667623045733e-06 -6.88910280897935e-06 -4.99937148850312e-06 -1.60882657731031e-06 -2.49832354694474e-05 0.0001059130390289 5.33747904759797e-06 -5.24326182185359e-06 -2.14867668094578e-05 -5.29287034727465e-06 2.92667623045733e-06 5.33747904759797e-06 4.10925214655015e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 859 0 0 0 0 0 2451 +1079 1083 0.999798479439679 0.0151043338215436 0.0132234492441655 -0.0135060785616081 -0.0146983529351823 0.999433427229414 -0.0302784239593237 -0.000183377314710668 -0.0136732926209624 0.0300779593103506 0.999454029674515 -0.00516861469478225 3.48360039618814e-05 1.05298616842788e-05 -6.67978890896564e-06 2.4458495562068e-06 -3.46415684141326e-06 2.79785188001019e-07 1.05298616842788e-05 4.51636444613411e-05 4.36776633611482e-06 -3.94558049681062e-06 2.44401442119754e-06 -1.79187235035674e-05 -6.67978890896564e-06 4.36776633611482e-06 1.47789764699904e-05 -3.58057523777043e-06 -6.74347969078395e-07 -1.43331985541101e-07 2.4458495562068e-06 -3.94558049681062e-06 -3.58057523777043e-06 2.10139672575425e-05 -3.61514821397961e-06 -9.33379395767836e-07 -3.46415684141326e-06 2.44401442119754e-06 -6.74347969078395e-07 -3.61514821397961e-06 5.8882131165369e-05 4.67602007754488e-06 2.79785188001019e-07 -1.79187235035674e-05 -1.43331985541101e-07 -9.33379395767836e-07 4.67602007754488e-06 4.82094976773409e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 813 0 0 0 0 0 2401 +1079 1124 0.999515292673781 0.020827350876824 0.0231387373618178 -0.00811551941316854 -0.0202134785372866 0.99944563341545 -0.026454510621313 0.014558949817526 -0.0236768873940005 0.0259739735551603 0.999382188004713 -0.0186506340868012 8.34257410807174e-05 3.06663214995431e-05 -1.13414274173588e-05 1.9483422361733e-05 -3.3668692567781e-05 2.47273606575085e-05 3.06663214995431e-05 0.000105587385681795 4.75942615044652e-06 9.9423237886103e-06 -3.37079354942375e-06 -4.462395619696e-05 -1.13414274173588e-05 4.75942615044652e-06 1.66528301049405e-05 -4.17956270525848e-06 1.76518142964429e-06 -4.06650295504547e-06 1.9483422361733e-05 9.9423237886103e-06 -4.17956270525848e-06 4.77109793978493e-05 -5.62108449855425e-05 3.18524762834925e-06 -3.3668692567781e-05 -3.37079354942375e-06 1.76518142964429e-06 -5.62108449855425e-05 0.000190270153410395 -1.62155417964643e-05 2.47273606575085e-05 -4.462395619696e-05 -4.06650295504547e-06 3.18524762834925e-06 -1.62155417964643e-05 9.79490586929588e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 847 0 0 0 0 0 2444 +1079 1118 0.999551865944359 0.021384205821152 0.0209471484586557 -0.00225217815456392 -0.0207539957115712 0.999338765829028 -0.0298546943263446 -0.00272969944527434 -0.0215717164165126 0.0294065783918156 0.999334735810845 -0.0114108537084472 3.06742742172082e-05 2.71947349492896e-06 -1.00216049962465e-05 2.94582494193653e-06 -5.17152880075261e-07 -5.87545624128839e-07 2.71947349492896e-06 7.57527501127264e-05 8.76883936955466e-06 -2.81820963241469e-06 -1.17336802584409e-05 -3.51751902223244e-05 -1.00216049962465e-05 8.76883936955466e-06 1.79443124989991e-05 -4.26967533394497e-06 -4.19069819722313e-06 -2.98060522999909e-06 2.94582494193653e-06 -2.81820963241469e-06 -4.26967533394497e-06 2.92703903690227e-05 -2.19564926277292e-05 -1.12625739751606e-06 -5.17152880075261e-07 -1.17336802584409e-05 -4.19069819722313e-06 -2.19564926277292e-05 0.000104646875731605 -4.8443236440713e-06 -5.87545624128839e-07 -3.51751902223244e-05 -2.98060522999909e-06 -1.12625739751606e-06 -4.8443236440713e-06 5.59587335158828e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 781 0 0 0 0 0 2483 +1079 1121 0.999646920124307 0.0212216154694791 0.0159899381754263 -0.00727706466381257 -0.0206673024276746 0.999205779455296 -0.0340686500099202 0.00235540046466276 -0.0167002304280936 0.0337261521671383 0.999291573547805 -0.0117054643031607 0.000120554410849965 6.85797640154367e-06 -9.17306111661315e-06 2.42572329802594e-05 -5.60554811640163e-05 4.36249776030725e-05 6.85797640154367e-06 0.000118820765687506 1.1984194573665e-05 1.82042398365118e-08 1.23349688697834e-05 -5.85061552688648e-05 -9.17306111661315e-06 1.1984194573665e-05 1.88017493600434e-05 -4.22414097556317e-06 -6.51755489647245e-06 -6.989154604819e-06 2.42572329802594e-05 1.82042398365118e-08 -4.22414097556317e-06 3.8755673796313e-05 -4.52125394972811e-05 9.55188279956762e-06 -5.60554811640163e-05 1.23349688697834e-05 -6.51755489647245e-06 -4.52125394972811e-05 0.000202216844985379 -4.46493950821823e-05 4.36249776030725e-05 -5.85061552688648e-05 -6.989154604819e-06 9.55188279956762e-06 -4.46493950821823e-05 0.000105351894194657 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 853 0 0 0 0 0 2436 +1079 1120 0.999643732070793 0.0217891449121667 0.01541564450726 -0.0102910755032429 -0.0213657930431199 0.999403993623157 -0.0271138418104852 0.0187725994461628 -0.0159972441131648 0.0267748145480421 0.999513480392687 -0.0148439164757578 4.60419371372549e-05 1.55662143520712e-05 -1.01926485497232e-05 7.4216023603953e-06 -6.23955782291314e-06 5.28511326017644e-06 1.55662143520712e-05 7.25250283428369e-05 6.32939216210717e-06 3.44029920189018e-06 -1.3377779708858e-05 -2.74857492959331e-05 -1.01926485497232e-05 6.32939216210717e-06 1.8305628311685e-05 -3.21661548368468e-06 -7.95919258779681e-06 -6.43186458302168e-06 7.4216023603953e-06 3.44029920189018e-06 -3.21661548368468e-06 3.38109142961459e-05 -3.07312350099989e-05 -4.26726003317267e-06 -6.23955782291314e-06 -1.3377779708858e-05 -7.95919258779681e-06 -3.07312350099989e-05 0.000139755081661939 1.47545488750103e-05 5.28511326017644e-06 -2.74857492959331e-05 -6.43186458302168e-06 -4.26726003317267e-06 1.47545488750103e-05 5.54763870747743e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 757 0 0 0 0 0 2410 +1079 1123 0.999602277206914 0.0213462467458777 0.0184289216346528 -0.00910221113703919 -0.0208645924551119 0.999445636443602 -0.0259439506537788 0.0166744720472263 -0.0189725112843333 0.0255491202139669 0.999493514872337 -0.0171233546248298 4.29858673029889e-05 2.08098073160021e-05 -4.01594735902164e-06 8.62621029470802e-06 -1.5315051405841e-05 -7.66010299857679e-07 2.08098073160021e-05 7.27149178486168e-05 7.50498790259053e-06 1.0894572275619e-06 -1.37882085432636e-05 -2.25514530408412e-05 -4.01594735902164e-06 7.50498790259053e-06 1.41987665386954e-05 -1.9385258168199e-06 -5.23918087644471e-06 -1.62729848120169e-06 8.62621029470802e-06 1.0894572275619e-06 -1.9385258168199e-06 3.50921024137928e-05 -3.57724053564207e-05 -4.66094885092433e-06 -1.5315051405841e-05 -1.37882085432636e-05 -5.23918087644471e-06 -3.57724053564207e-05 0.000134482380949363 7.56655092630142e-06 -7.66010299857679e-07 -2.25514530408412e-05 -1.62729848120169e-06 -4.66094885092433e-06 7.56655092630142e-06 5.58141068087959e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 748 0 0 0 0 0 2517 +1079 1117 0.999476924292084 0.020787288197142 0.0247743104252168 0.000593074227432725 -0.0200112103417733 0.999313676281009 -0.0311725497576411 -0.0110239671639974 -0.0254053000040021 0.0306604802171177 0.999206938368906 -0.0118880457784859 3.3001672521627e-05 1.65536247504413e-05 -5.97536051476716e-06 1.48448464573136e-06 4.22021006373602e-07 -8.94662759617599e-06 1.65536247504413e-05 5.79621560777356e-05 4.4434922699983e-06 1.63783815531095e-06 -1.14210908805439e-05 -2.39216159774889e-05 -5.97536051476716e-06 4.4434922699983e-06 1.40306650414285e-05 1.43150575644144e-06 -2.66443533484518e-06 1.52549245124456e-06 1.48448464573136e-06 1.63783815531095e-06 1.43150575644144e-06 2.07670873827977e-05 -9.25854155065708e-06 -2.96697190158505e-06 4.22021006373602e-07 -1.14210908805439e-05 -2.66443533484518e-06 -9.25854155065708e-06 6.74694255129742e-05 6.79508627925921e-07 -8.94662759617599e-06 -2.39216159774889e-05 1.52549245124456e-06 -2.96697190158505e-06 6.79508627925921e-07 4.4933810755496e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 748 0 0 0 0 0 2426 +1079 1128 0.999510563940259 0.0213444369941674 0.0228702335192867 -0.00597467649633264 -0.0206730311068828 0.99935972797258 -0.0292020528632082 0.0130455766465645 -0.0234788917259428 0.0287149632765526 0.999311859494997 -0.0169010243165111 2.70142589019241e-05 2.62288012490553e-06 -8.24736499908407e-06 2.83281739625631e-07 3.25348203254987e-06 -9.05547618393931e-07 2.62288012490553e-06 6.53868256387893e-05 6.8835235747705e-06 -3.54065288105273e-07 -1.0998793555636e-05 -3.02506896649229e-05 -8.24736499908407e-06 6.8835235747705e-06 1.59051788668845e-05 -2.79824999544674e-06 -5.56459819773618e-06 -1.28577621803127e-06 2.83281739625631e-07 -3.54065288105273e-07 -2.79824999544674e-06 3.37276603575657e-05 -3.21814960802386e-05 -5.90011750074576e-06 3.25348203254987e-06 -1.0998793555636e-05 -5.56459819773618e-06 -3.21814960802386e-05 0.00012378278083334 1.01498285373715e-06 -9.05547618393931e-07 -3.02506896649229e-05 -1.28577621803127e-06 -5.90011750074576e-06 1.01498285373715e-06 5.218942808511e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 777 0 0 0 0 0 2528 +1079 1130 0.999547813533779 0.0220196478053255 0.0204769033394164 -0.0100531210146466 -0.0214156012220958 0.999342262864658 -0.0292645464144046 0.0253147236326908 -0.021107829924901 0.0288127881863956 0.999361937814718 -0.0140049009347825 3.55866304978869e-05 1.80302672100853e-05 -6.04245948575439e-06 -1.48722043186786e-06 5.45273562639934e-06 -8.75273219352025e-06 1.80302672100853e-05 6.19840435704196e-05 5.60654265419482e-06 -5.21287515450833e-06 1.66266302416493e-06 -1.80488834944293e-05 -6.04245948575439e-06 5.60654265419482e-06 1.4917250785612e-05 -8.98490399904256e-07 -2.01057989137314e-06 3.55862688757134e-07 -1.48722043186786e-06 -5.21287515450833e-06 -8.98490399904256e-07 3.87963854354972e-05 -5.74095577065867e-05 -3.1842967485215e-06 5.45273562639934e-06 1.66266302416493e-06 -2.01057989137314e-06 -5.74095577065867e-05 0.000219100102357044 4.99212540559719e-06 -8.75273219352025e-06 -1.80488834944293e-05 3.55862688757134e-07 -3.1842967485215e-06 4.99212540559719e-06 5.03238020860143e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 783 0 0 0 0 0 2484 +1079 1125 0.999587008033095 0.0210790694364096 0.0195316717958407 -0.00601820002320065 -0.020470094686545 0.999313741543777 -0.0308710412085822 0.00532644262951843 -0.0201690008421166 0.0304584765455056 0.999332523543369 -0.0137201134326036 8.42630491267706e-05 1.91105396888972e-05 -9.38563980474501e-06 1.06943798599739e-05 -2.11544756230429e-05 4.10803648724255e-05 1.91105396888972e-05 8.21542264480681e-05 7.5618701576234e-06 -1.4018454267278e-05 3.23874236575284e-05 -3.36641914960395e-05 -9.38563980474501e-06 7.5618701576234e-06 1.7310893556009e-05 -6.70765664693089e-06 -1.84984633825457e-06 -3.23071941997594e-06 1.06943798599739e-05 -1.4018454267278e-05 -6.70765664693089e-06 5.01773346871834e-05 -7.39512986603844e-05 7.88982632087914e-06 -2.11544756230429e-05 3.23874236575284e-05 -1.84984633825457e-06 -7.39512986603844e-05 0.000270824832991474 -3.24099354668609e-05 4.10803648724255e-05 -3.36641914960395e-05 -3.23071941997594e-06 7.88982632087914e-06 -3.24099354668609e-05 9.36105632695866e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 853 0 0 0 0 0 2402 +1079 1126 0.999595173873352 0.0218975783925378 0.0181654735596552 -0.00669341366639802 -0.0213519577120484 0.999330627002786 -0.0297050809809038 0.0150732474189976 -0.0188037834216088 0.0293051871647634 0.999393628023649 -0.0139151832899643 3.43488758953214e-05 1.07622247034909e-05 -7.52824499077973e-06 5.19537263526279e-06 -9.04307070885845e-08 -6.72287466965261e-06 1.07622247034909e-05 6.25133546366583e-05 6.66401284426322e-06 -1.47909285579949e-06 -5.98692704302813e-06 -2.66182181301937e-05 -7.52824499077973e-06 6.66401284426322e-06 1.66344852292424e-05 -2.45511598732391e-06 -6.82984910103093e-06 -2.62924187595236e-06 5.19537263526279e-06 -1.47909285579949e-06 -2.45511598732391e-06 3.76069006418384e-05 -4.67445634233092e-05 8.10555218354887e-07 -9.04307070885845e-08 -5.98692704302813e-06 -6.82984910103093e-06 -4.67445634233092e-05 0.000181246365498762 -5.39340248902238e-07 -6.72287466965261e-06 -2.66182181301937e-05 -2.62924187595236e-06 8.10555218354887e-07 -5.39340248902238e-07 5.45341268517725e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 790 0 0 0 0 0 2537 +1079 1127 0.999533796761599 0.0211356413797827 0.0220334698767241 -0.0106527527168922 -0.0204989900690839 0.999376971301279 -0.0287308308064652 0.028762125021605 -0.0226269869291272 0.0282657725199108 0.999344317823623 -0.0178467589170952 4.40728851756783e-05 9.61498051532445e-07 -8.3240867051513e-06 8.66213686741592e-06 -1.053462086667e-05 -1.68293291125785e-06 9.61498051532445e-07 8.44028289783027e-05 6.56624374851912e-06 3.85860448841981e-06 -1.11389210488723e-05 -3.59575499326844e-05 -8.3240867051513e-06 6.56624374851912e-06 1.54047862338069e-05 -2.42682901851825e-06 -5.0644481895299e-06 -5.07292926583055e-06 8.66213686741592e-06 3.85860448841981e-06 -2.42682901851825e-06 3.59152303120223e-05 -3.72209734346701e-05 -6.84792347639799e-06 -1.053462086667e-05 -1.11389210488723e-05 -5.0644481895299e-06 -3.72209734346701e-05 0.000158406231274884 9.82310820596444e-06 -1.68293291125785e-06 -3.59575499326844e-05 -5.07292926583055e-06 -6.84792347639799e-06 9.82310820596444e-06 5.55961756897355e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 781 0 0 0 0 0 2516 +1079 1131 0.999580192669111 0.0215583244727899 0.0193565769057643 -0.0153433325868383 -0.0209279758602189 0.999262399201025 -0.0321974745811886 0.032859545568528 -0.0200364230833988 0.031778863871103 0.999294073614512 -0.014250159560825 0.000105216658973328 3.66387604534659e-05 -8.18779415272923e-06 2.40593467899134e-05 -3.94381884301745e-05 2.58595698698468e-05 3.66387604534659e-05 8.52078278804849e-05 3.17677705577539e-06 1.26133715730663e-05 -2.96961410026267e-05 -2.80702268239143e-05 -8.18779415272923e-06 3.17677705577539e-06 1.44427328893066e-05 4.93614029807715e-07 -8.12450094934835e-06 -7.95622471589734e-07 2.40593467899134e-05 1.26133715730663e-05 4.93614029807715e-07 6.31430205302833e-05 -0.000109040644134399 5.65453295712537e-06 -3.94381884301745e-05 -2.96961410026267e-05 -8.12450094934835e-06 -0.000109040644134399 0.000332810399980468 -8.57332158397608e-06 2.58595698698468e-05 -2.80702268239143e-05 -7.95622471589734e-07 5.65453295712537e-06 -8.57332158397608e-06 8.49533156983054e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 855 0 0 0 0 0 2355 +1079 1122 0.999604910820021 0.0216881297204501 0.0178786826619561 -0.00572464558241667 -0.0211674730372227 0.999360646236087 -0.0288138307034827 0.00480724624728487 -0.0184921699569426 0.02842400013755 0.999424892558948 -0.0140260335797597 8.12593347936802e-05 2.86235070767278e-05 -9.53567327491857e-06 8.5068452060432e-06 -7.87335904883815e-06 2.72841237745498e-05 2.86235070767278e-05 0.00010288003110086 9.4989037039971e-06 9.11935225954229e-06 -1.11952925738058e-05 -3.25118939778975e-05 -9.53567327491857e-06 9.4989037039971e-06 1.84775873890299e-05 -3.08800130975361e-06 -8.09188669348425e-06 -4.96003774228996e-06 8.5068452060432e-06 9.11935225954229e-06 -3.08800130975361e-06 3.42809364332882e-05 -2.45718210767914e-05 4.98588723314068e-06 -7.87335904883815e-06 -1.11952925738058e-05 -8.09188669348425e-06 -2.45718210767914e-05 0.00012939663519331 -8.71374640593496e-06 2.72841237745498e-05 -3.25118939778975e-05 -4.96003774228996e-06 4.98588723314068e-06 -8.71374640593496e-06 8.01152611119633e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 862 0 0 0 0 0 2426 +1079 1116 0.99958540998621 0.0212797708984536 0.0193953472051638 -0.00237029760926292 -0.0206747749703094 0.999309343246347 -0.030877017026931 -0.006789171520502 -0.0200390075259879 0.0304632212850783 0.999334994046696 -0.00678973244012704 3.93915424983535e-05 2.55049011893746e-05 -5.94222147121398e-07 3.16621276728962e-07 -7.30495354338861e-06 -9.38899061522599e-06 2.55049011893746e-05 7.51614969549149e-05 1.1682005506922e-05 -2.54274873126603e-06 -7.45374177419424e-06 -2.30423553407382e-05 -5.94222147121398e-07 1.1682005506922e-05 1.5225764063487e-05 -2.07560460586519e-06 -7.12571792355942e-07 4.25068081290903e-07 3.16621276728962e-07 -2.54274873126603e-06 -2.07560460586519e-06 2.49583394589842e-05 -1.85242310767537e-05 -3.0957331147693e-06 -7.30495354338861e-06 -7.45374177419424e-06 -7.12571792355942e-07 -1.85242310767537e-05 8.65678367103611e-05 -4.07774238613881e-07 -9.38899061522599e-06 -2.30423553407382e-05 4.25068081290903e-07 -3.0957331147693e-06 -4.07774238613881e-07 4.40029366781617e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 742 0 0 0 0 0 2496 +1079 1119 0.999532633824077 0.0217793610980214 0.021451651471747 -0.0017402287961899 -0.0211286700656247 0.999323366971134 -0.0301062705550535 0.000978563111889859 -0.0220928319135707 0.0296389550362035 0.999316485965483 -0.0143152844742148 3.3670656888676e-05 1.12690889303852e-05 -7.13432533584195e-06 -2.6774641314339e-07 4.19396722883868e-06 8.65808986134749e-07 1.12690889303852e-05 7.6002831602776e-05 6.62380578045689e-06 -9.1055653190216e-07 -1.68126314152981e-06 -3.23879820379169e-05 -7.13432533584195e-06 6.62380578045689e-06 1.51625694738451e-05 -1.52102155384102e-06 -4.50925956105153e-06 -2.82391748588193e-06 -2.6774641314339e-07 -9.1055653190216e-07 -1.52102155384102e-06 2.68932149234141e-05 -1.41797954320469e-05 -1.91636542914169e-07 4.19396722883868e-06 -1.68126314152981e-06 -4.50925956105153e-06 -1.41797954320469e-05 7.73202562722311e-05 -4.39342257815207e-06 8.65808986134749e-07 -3.23879820379169e-05 -2.82391748588193e-06 -1.91636542914169e-07 -4.39342257815207e-06 5.82996146779675e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 778 0 0 0 0 0 2526 +1079 1133 0.999615939026677 0.0218103325680254 0.0170963106279462 -0.0103342184245293 -0.0213582125508884 0.999428625657488 -0.0261963541932013 0.0168866149311054 -0.0176578934317253 0.0258211465596846 0.999510613845545 -0.0181096503410719 5.14686222561176e-05 3.07487765890044e-05 -7.54459650430207e-06 1.1494914175469e-05 -1.72395705860758e-05 -9.18956843771218e-06 3.07487765890044e-05 6.36892188521952e-05 2.38497609436288e-06 1.56223436093121e-06 -8.20799357398153e-06 -1.41812745704448e-05 -7.54459650430207e-06 2.38497609436288e-06 1.42715261072053e-05 -4.72841870917003e-06 9.11761339972566e-07 2.73371393735287e-07 1.1494914175469e-05 1.56223436093121e-06 -4.72841870917003e-06 4.03376180021041e-05 -5.53500166544153e-05 -3.11939235423225e-06 -1.72395705860758e-05 -8.20799357398153e-06 9.11761339972566e-07 -5.53500166544153e-05 0.000188663513333757 2.11642689644013e-06 -9.18956843771218e-06 -1.41812745704448e-05 2.73371393735287e-07 -3.11939235423225e-06 2.11642689644013e-06 4.3817829284763e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 757 0 0 0 0 0 2316 +1079 1115 0.999687022727835 0.0212662934094359 0.0131757866627117 -0.00383486790260371 -0.0206944264966572 0.998898369582285 -0.0421163621153016 -0.0121967846360642 -0.0140569307294288 0.0418305153025461 0.999025830841221 0.00227957334798249 0.000123761720301131 2.83161987056326e-05 -1.55315287930701e-05 2.32531518386495e-05 -3.56494330558902e-05 3.82968400205255e-05 2.83161987056326e-05 9.72247204682632e-05 2.18380331263797e-06 -5.87267044477681e-06 2.17867476519316e-05 -4.17325946450501e-05 -1.55315287930701e-05 2.18380331263797e-06 1.70469671664507e-05 -4.91405680316451e-06 -5.65645090300869e-07 -6.29043000703522e-06 2.32531518386495e-05 -5.87267044477681e-06 -4.91405680316451e-06 3.20188497485387e-05 -2.41947366135305e-05 1.62160626639101e-05 -3.56494330558902e-05 2.17867476519316e-05 -5.65645090300869e-07 -2.41947366135305e-05 0.000131781708521837 -4.07961341481917e-05 3.82968400205255e-05 -4.17325946450501e-05 -6.29043000703522e-06 1.62160626639101e-05 -4.07961341481917e-05 8.75357799763416e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 778 0 0 0 0 0 2355 +1079 1136 0.999523152829662 0.0213026433923898 0.0223531729727285 -0.00577584547289222 -0.0206731951901991 0.999393502391756 -0.028022247907104 0.0137787831183293 -0.022936563781002 0.0275467740694975 0.999357338133004 -0.0147279471820171 3.08730856760987e-05 1.22175476985169e-05 -8.35843907783043e-06 2.97707664902904e-06 6.86405910647309e-07 -2.85583199734519e-06 1.22175476985169e-05 8.7509750583003e-05 9.60204462838422e-06 7.86286638848105e-06 -2.30889152150951e-05 -3.85212821599384e-05 -8.35843907783043e-06 9.60204462838422e-06 1.70906156198659e-05 -3.45673984284463e-06 -3.8650556875491e-06 -2.89488659497506e-06 2.97707664902904e-06 7.86286638848105e-06 -3.45673984284463e-06 3.09501995261055e-05 -2.12048621810347e-05 -1.01763435664203e-05 6.86405910647309e-07 -2.30889152150951e-05 -3.8650556875491e-06 -2.12048621810347e-05 8.78166264373903e-05 2.120282415922e-05 -2.85583199734519e-06 -3.85212821599384e-05 -2.89488659497506e-06 -1.01763435664203e-05 2.120282415922e-05 5.64403050154603e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 777 0 0 0 0 0 2458 +1079 1129 0.999534862445797 0.0211803188833373 0.0219420338041241 -0.00457823752988386 -0.02047639187434 0.999283722898894 -0.0318238672247033 0.0052731410663611 -0.0226003568836787 0.0313597710662439 0.999252615021549 -0.0121604339609378 4.83232101753743e-05 1.47420260158556e-05 -9.82641231507085e-06 5.44783200720893e-06 -5.86320455390537e-06 7.08132851022314e-06 1.47420260158556e-05 5.475240620249e-05 6.70236626366192e-07 5.47274330391702e-06 -1.57413929816521e-05 -1.51017641955055e-05 -9.82641231507085e-06 6.70236626366192e-07 1.59058970845336e-05 -1.7513937639222e-06 -5.08896859254051e-06 -5.83175123267217e-07 5.44783200720893e-06 5.47274330391702e-06 -1.7513937639222e-06 3.68151557817262e-05 -3.59282461676384e-05 -5.45235642204138e-06 -5.86320455390537e-06 -1.57413929816521e-05 -5.08896859254051e-06 -3.59282461676384e-05 0.000140664576641936 4.54451646954536e-06 7.08132851022314e-06 -1.51017641955055e-05 -5.83175123267217e-07 -5.45235642204138e-06 4.54451646954536e-06 4.06920029143422e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 863 0 0 0 0 0 2440 +1079 1135 0.999579375999415 0.0214817092743755 0.0194835120877007 -0.00224435876900564 -0.0207393423377762 0.99908005028593 -0.0375357536231831 -0.00337306052549263 -0.0202719203830544 0.0371158899572001 0.999105329760916 -0.0129976369359333 3.66016052082417e-05 1.79111111249335e-05 -7.43224214027883e-06 4.98876187755062e-06 8.87331886205072e-06 -3.37905582682319e-06 1.79111111249335e-05 7.10123479557408e-05 5.38777373942869e-06 -1.46987851611508e-06 -1.85777660755743e-06 -2.11029930344892e-05 -7.43224214027883e-06 5.38777373942869e-06 1.77086278950637e-05 -3.90201537623687e-06 -5.99027436524292e-06 -2.660833420536e-06 4.98876187755062e-06 -1.46987851611508e-06 -3.90201537623687e-06 3.71520893334281e-05 -3.07934047691953e-05 1.99394925858577e-06 8.87331886205072e-06 -1.85777660755743e-06 -5.99027436524292e-06 -3.07934047691953e-05 0.000142461144063439 -3.85987386311227e-06 -3.37905582682319e-06 -2.11029930344892e-05 -2.660833420536e-06 1.99394925858577e-06 -3.85987386311227e-06 4.70121823692584e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 857 0 0 0 0 0 2400 +1079 1114 0.999713855373879 0.0210054048922419 0.01144466420689 -0.00646750531815156 -0.0205825550278667 0.999143752097028 -0.0358904036477443 -0.00538123891422516 -0.0121887571975295 0.0356445733707974 0.99929019738372 0.000381275447718014 5.6692319617209e-05 1.17105207826111e-05 -9.49874209518773e-06 7.79374204909612e-06 -7.24024811958038e-06 2.1216829160752e-05 1.17105207826111e-05 8.11204537847182e-05 6.56739756068259e-06 -3.69397042560583e-06 1.9372565742234e-05 -3.94058368972346e-05 -9.49874209518773e-06 6.56739756068259e-06 1.70784718068845e-05 -3.93048443903074e-06 -2.76270272386266e-06 -3.54424847453923e-06 7.79374204909612e-06 -3.69397042560583e-06 -3.93048443903074e-06 2.52531725935173e-05 -3.48979947640765e-06 8.03537856863791e-06 -7.24024811958038e-06 1.9372565742234e-05 -2.76270272386266e-06 -3.48979947640765e-06 6.98867283871874e-05 -2.45203574601902e-05 2.1216829160752e-05 -3.94058368972346e-05 -3.54424847453923e-06 8.03537856863791e-06 -2.45203574601902e-05 7.4886128133219e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 821 0 0 0 0 0 2471 +1079 1132 0.999616912246352 0.0214116498499397 0.0175376737845424 -0.0113847425611861 -0.0209309599511413 0.999412250986674 -0.027148618625495 0.0171722774600392 -0.0181086627499982 0.0267711379745506 0.999477554777972 -0.0168506839832543 6.53266529058277e-05 2.68585987233044e-05 -8.73501787495167e-06 8.57544219930416e-06 -5.19878672384376e-06 2.2980958658904e-05 2.68585987233044e-05 7.03361188435212e-05 2.99248316600042e-06 1.59035040419067e-06 -3.19594160695698e-06 -1.17073054974816e-05 -8.73501787495167e-06 2.99248316600042e-06 1.58609570949106e-05 -3.62389947401133e-06 -7.87463220943812e-06 -2.02488430824314e-06 8.57544219930416e-06 1.59035040419067e-06 -3.62389947401133e-06 4.22162795455736e-05 -6.29202005126693e-05 5.04444061457916e-06 -5.19878672384376e-06 -3.19594160695698e-06 -7.87463220943812e-06 -6.29202005126693e-05 0.000248462379862753 -8.98871101861215e-06 2.2980958658904e-05 -1.17073054974816e-05 -2.02488430824314e-06 5.04444061457916e-06 -8.98871101861215e-06 6.2213703150095e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 846 0 0 0 0 0 2349 +1079 1134 0.999499724789362 0.0211841051207622 0.0234847575295597 -0.00805234189632537 -0.0206034316574817 0.999482625959654 -0.0246977531109429 0.016089939947506 -0.023995806923819 0.0242015308405503 0.999419074840504 -0.0196242217596349 4.4750699182904e-05 2.01654776280044e-05 -7.59478810697469e-06 4.78550964911766e-06 -1.01703114211882e-05 2.72147977591596e-06 2.01654776280044e-05 9.16678924663517e-05 7.24804028017657e-06 6.39493986519548e-06 -1.03824263491603e-05 -3.8200661208188e-05 -7.59478810697469e-06 7.24804028017657e-06 1.66318367013089e-05 -2.45399401711682e-06 -3.64025569073659e-06 -5.74820858236059e-06 4.78550964911766e-06 6.39493986519548e-06 -2.45399401711682e-06 3.54558176896038e-05 -2.97354092817754e-05 -7.61377666204802e-06 -1.01703114211882e-05 -1.03824263491603e-05 -3.64025569073659e-06 -2.97354092817754e-05 0.000135077121225714 1.18399058960221e-05 2.72147977591596e-06 -3.8200661208188e-05 -5.74820858236059e-06 -7.61377666204802e-06 1.18399058960221e-05 7.1439822775484e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 755 0 0 0 0 0 2449 +1079 1137 0.999511626350543 0.02170541131762 0.0224807453085068 -0.00112545631390195 -0.0208658641455618 0.999100008643118 -0.0369295063977442 -0.00218933585119643 -0.0232620829581526 0.0364423908224338 0.999064976689501 -0.00867934297252506 7.58507999895684e-05 2.86448912485841e-05 -9.34293300789086e-06 1.88710319414664e-05 -2.36876475466838e-05 2.68509875327162e-05 2.86448912485841e-05 8.51648231360308e-05 6.53430638760614e-06 3.48479592478744e-06 -1.8321505553497e-06 -3.1110932039205e-05 -9.34293300789086e-06 6.53430638760614e-06 1.62565889187117e-05 -3.82561433869308e-06 -3.98088516585596e-06 -5.02993336016975e-06 1.88710319414664e-05 3.48479592478744e-06 -3.82561433869308e-06 3.53387526757615e-05 -3.2263274553167e-05 7.41558679271671e-06 -2.36876475466838e-05 -1.8321505553497e-06 -3.98088516585596e-06 -3.2263274553167e-05 0.000141995067967519 -1.8897840366399e-05 2.68509875327162e-05 -3.1110932039205e-05 -5.02993336016975e-06 7.41558679271671e-06 -1.8897840366399e-05 8.02123699455245e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 850 0 0 0 0 0 2426 +1079 1139 0.999466345294974 0.0211913024686657 0.0248586669471501 -0.00829116199860403 -0.0203640081866389 0.999245429807071 -0.0330738292348692 0.0190852698012258 -0.0255407868571489 0.0325499571330641 0.999143717638936 -0.0120947851393428 4.66030181604905e-05 1.72225860972089e-05 -1.07898787222388e-05 5.67210320705762e-06 1.79336322248397e-09 -1.17581799760231e-05 1.72225860972089e-05 8.99423154524835e-05 9.54685597157767e-06 8.15074487570618e-06 -3.14451358397974e-05 -4.66393813252377e-05 -1.07898787222388e-05 9.54685597157767e-06 1.77827182191589e-05 -4.74834864846777e-06 -7.18179775987575e-06 -4.42637428765427e-06 5.67210320705762e-06 8.15074487570618e-06 -4.74834864846777e-06 3.2652516219959e-05 -1.70830111621286e-05 -7.69934085959649e-06 1.79336322248397e-09 -3.14451358397974e-05 -7.18179775987575e-06 -1.70830111621286e-05 9.33408612087289e-05 2.22058641590492e-05 -1.17581799760231e-05 -4.66393813252377e-05 -4.42637428765427e-06 -7.69934085959649e-06 2.22058641590492e-05 6.71286203485097e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 864 0 0 0 0 0 2449 +1079 1140 0.999583278884233 0.0208810277263932 0.0199311629398536 -0.00865898302493058 -0.020187850561002 0.999205326330773 -0.0343681032636409 0.014522493657372 -0.0206329654866199 0.0339514140103654 0.999210479439605 -0.00607518861567108 7.72178804187383e-05 4.05453312909428e-05 -5.98633842465978e-06 6.64901142203636e-06 -3.67514872740691e-06 1.83997793466157e-05 4.05453312909428e-05 7.66010929319495e-05 3.02841078293011e-06 1.50252153096818e-06 1.03006669341087e-06 -1.77946094616435e-05 -5.98633842465978e-06 3.02841078293011e-06 1.59972115480498e-05 -3.56932387206786e-06 -3.52065049796765e-07 -7.96153929485175e-07 6.64901142203636e-06 1.50252153096818e-06 -3.56932387206786e-06 3.39482085375077e-05 -2.74869297597424e-05 -1.3024499785552e-06 -3.67514872740691e-06 1.03006669341087e-06 -3.52065049796765e-07 -2.74869297597424e-05 0.000117305080839788 3.34704264142085e-06 1.83997793466157e-05 -1.77946094616435e-05 -7.96153929485175e-07 -1.3024499785552e-06 3.34704264142085e-06 6.11571505663018e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 833 0 0 0 0 0 2465 +1079 1138 0.999610511729484 0.0215665367608644 0.0177118415773471 -0.0111415882438324 -0.0209443195088625 0.999181943664409 -0.0345944928467636 0.0229813841151169 -0.018443435694833 0.0342100562284891 0.99924447045386 -0.00291125269447671 5.09946952913061e-05 2.29563166117477e-05 -1.08134228574508e-05 6.8153855318971e-06 1.37770791030757e-06 -6.04898513075343e-06 2.29563166117477e-05 8.10283814094852e-05 4.97288393545995e-06 -2.21847576880545e-06 7.8235708056694e-07 -4.02290882265039e-05 -1.08134228574508e-05 4.97288393545995e-06 1.74405110328047e-05 -5.98183116996394e-06 -5.66972114235617e-06 -2.27824930550574e-06 6.8153855318971e-06 -2.21847576880545e-06 -5.98183116996394e-06 2.71936271717224e-05 -1.40147537963637e-05 -1.77910551444046e-06 1.37770791030757e-06 7.8235708056694e-07 -5.66972114235617e-06 -1.40147537963637e-05 9.07150076302894e-05 5.35297691842205e-06 -6.04898513075343e-06 -4.02290882265039e-05 -2.27824930550574e-06 -1.77910551444046e-06 5.35297691842205e-06 5.62385414359921e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 870 0 0 0 0 0 2366 +1079 1111 0.99952842502203 0.0202665390135173 0.0230693512997822 -0.00389260975846991 -0.0195989344105692 0.999392855612158 -0.028806282671425 -0.00441747447965583 -0.0236391485242042 0.02834056364629 0.999318769517145 -0.012827068629486 4.49041666005181e-05 1.79414462238117e-05 -6.46762022947397e-06 5.9085959898969e-06 -5.92254340017775e-06 3.99167253699935e-07 1.79414462238117e-05 9.11808439697273e-05 3.78850079852933e-06 8.43283521249771e-06 -7.74437895796639e-07 -4.23423375145748e-05 -6.46762022947397e-06 3.78850079852933e-06 1.51240903959704e-05 -2.13154978046346e-06 -4.4788451502625e-06 -4.4184540284022e-06 5.9085959898969e-06 8.43283521249771e-06 -2.13154978046346e-06 2.57793731292082e-05 -1.20549801019279e-06 -1.14264922866572e-06 -5.92254340017775e-06 -7.74437895796639e-07 -4.4788451502625e-06 -1.20549801019279e-06 7.10261186189332e-05 -2.70226278487258e-06 3.99167253699935e-07 -4.23423375145748e-05 -4.4184540284022e-06 -1.14264922866572e-06 -2.70226278487258e-06 6.11362557091024e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 701 0 0 0 0 0 2458 +1080 1082 0.999871777457007 0.0147293540876665 0.00628289528211388 -0.011974207656338 -0.0146264575405871 0.999763073132949 -0.0161203082965526 0.00844879428120789 -0.00651884842432095 0.0160263448085531 0.999850319241484 -0.00199163464089855 3.54656618262522e-05 1.70161895337616e-05 -8.3731036366322e-06 1.74411311658171e-06 5.55529243720519e-06 6.98875347813124e-06 1.70161895337616e-05 5.76142405890948e-05 2.78145367864616e-06 -5.69564324604195e-06 1.33049067840405e-05 -1.34006688052952e-05 -8.3731036366322e-06 2.78145367864616e-06 1.63224219881871e-05 -7.25071643806866e-06 -3.3720673370601e-08 -1.42184055369693e-06 1.74411311658171e-06 -5.69564324604195e-06 -7.25071643806866e-06 2.7704598830744e-05 -2.02996112158714e-05 1.61417169345469e-07 5.55529243720519e-06 1.33049067840405e-05 -3.3720673370601e-08 -2.02996112158714e-05 9.02864120641843e-05 1.14591045908264e-05 6.98875347813124e-06 -1.34006688052952e-05 -1.42184055369693e-06 1.61417169345469e-07 1.14591045908264e-05 4.29717928708637e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 911 0 0 0 0 0 2504 +1080 1083 0.999866439287169 0.0149288085889487 0.00665088425035362 -0.0128187878436857 -0.0148072114443619 0.999728847830628 -0.0179715693384525 0.00108953547426554 -0.00691737496735767 0.017870687993454 0.999816377358464 -0.00111870930849517 7.26803880603775e-05 5.49787139405055e-05 -7.76259943107615e-07 1.18352257679726e-05 -1.65708358701354e-05 2.55471361742342e-05 5.49787139405055e-05 8.00712944150493e-05 3.79079504101382e-06 8.28803545672955e-06 -9.90568932062382e-06 6.97672143701437e-06 -7.76259943107615e-07 3.79079504101382e-06 1.25472495831262e-05 1.44934711464732e-08 -9.89197813894628e-07 1.93966551376358e-06 1.18352257679726e-05 8.28803545672955e-06 1.44934711464732e-08 2.34520374797892e-05 -1.06632925153648e-05 6.89478416131192e-06 -1.65708358701354e-05 -9.90568932062382e-06 -9.89197813894628e-07 -1.06632925153648e-05 7.57388210180525e-05 -1.64291188008599e-05 2.55471361742342e-05 6.97672143701437e-06 1.93966551376358e-06 6.89478416131192e-06 -1.64291188008599e-05 6.4680226923139e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 731 0 0 0 0 0 2380 +1079 1112 0.999585051237652 0.0211331245399382 0.0195733591751796 -0.000942479081787615 -0.0204251860610516 0.999154220813054 -0.0356883006856648 -0.00962943586509146 -0.0203110097383795 0.0352737023664721 0.999171271006512 -0.0099899510297177 4.63073721702653e-05 8.79656916480014e-06 -8.61068824679892e-06 6.57307785005146e-06 -5.53664988390164e-06 -6.42292022859017e-06 8.79656916480014e-06 9.42953065443887e-05 5.97159447598243e-06 6.53592187760695e-06 -1.10016944744292e-05 -3.46745719991938e-05 -8.61068824679892e-06 5.97159447598243e-06 1.50228851618196e-05 -1.42319053723491e-06 -2.60976859869944e-06 -3.06344111334418e-06 6.57307785005146e-06 6.53592187760695e-06 -1.42319053723491e-06 2.65834132525606e-05 -8.48252401824139e-06 -2.7527576040632e-06 -5.53664988390164e-06 -1.10016944744292e-05 -2.60976859869944e-06 -8.48252401824139e-06 7.80598021433462e-05 -8.9881638740754e-06 -6.42292022859017e-06 -3.46745719991938e-05 -3.06344111334418e-06 -2.7527576040632e-06 -8.9881638740754e-06 5.14446756566323e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 760 0 0 0 0 0 2510 +1080 1084 0.999867224903793 0.0153188938409502 0.00555554269882755 -0.0118169143843076 -0.0151888023276676 0.999625847968025 -0.0227478429319569 -0.000281734100544063 -0.00590193587222332 0.0226604405450477 0.999725798200319 0.00306936985213769 7.16178705379908e-05 3.03163140357622e-05 -8.80591300401869e-06 1.94654507388912e-05 -1.57609073040839e-05 3.66912917477979e-05 3.03163140357622e-05 6.49846633753435e-05 -2.26151580758198e-06 6.87926689812611e-06 5.42100087643194e-06 -1.18257500992437e-05 -8.80591300401869e-06 -2.26151580758198e-06 1.29011291762243e-05 -2.56385726316266e-06 -7.32758221200497e-07 -6.81117120962618e-07 1.94654507388912e-05 6.87926689812611e-06 -2.56385726316266e-06 2.58241286132086e-05 -6.68025176511906e-06 1.52015035254041e-05 -1.57609073040839e-05 5.42100087643194e-06 -7.32758221200497e-07 -6.68025176511906e-06 6.35107573442446e-05 -2.26613531975588e-05 3.66912917477979e-05 -1.18257500992437e-05 -6.81117120962618e-07 1.52015035254041e-05 -2.26613531975588e-05 7.42107119435134e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 738 0 0 0 0 0 2576 +1079 1113 0.999555921109144 0.0210096875671147 0.0211318149713421 -0.00329470608477079 -0.0203451108871895 0.999306478922974 -0.0311871391050211 -0.00415747296020744 -0.0217723916609723 0.0307433604360389 0.999290152433447 -0.005785268539816 4.29480277153274e-05 7.44517114682945e-06 -1.08039351089283e-05 3.77176358085429e-06 4.91564242998808e-06 -7.1494409204726e-07 7.44517114682945e-06 7.99120127343391e-05 8.21079453669233e-06 8.8487876262945e-06 -2.82716359107859e-05 -3.30822713487668e-05 -1.08039351089283e-05 8.21079453669233e-06 1.67548321353336e-05 -1.18785807936915e-06 -8.86460985576002e-06 -3.38315374498436e-06 3.77176358085429e-06 8.8487876262945e-06 -1.18785807936915e-06 2.48195872893897e-05 -7.8342263533563e-06 -6.95110728071356e-06 4.91564242998808e-06 -2.82716359107859e-05 -8.86460985576002e-06 -7.8342263533563e-06 7.48876356786761e-05 8.69928351910726e-06 -7.1494409204726e-07 -3.30822713487668e-05 -3.38315374498436e-06 -6.95110728071356e-06 8.69928351910726e-06 5.05810436021807e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 715 0 0 0 0 0 2501 +1080 1125 0.999686444499392 0.0218563866909362 0.0122192898721863 -0.00290504798310999 -0.021632451251645 0.999600907274249 -0.0181676423716342 0.00193457346047547 -0.0126114922594216 0.0178976126149457 0.999760284130989 -0.0113258193729702 3.38070031509619e-05 1.57332383710429e-05 -1.08719807153763e-05 5.60900263612043e-06 1.73127668048475e-06 -4.54353927950516e-06 1.57332383710429e-05 5.98083689286394e-05 8.43739450733916e-07 -1.47869262948522e-06 3.80060148500299e-06 -2.97584269596049e-05 -1.08719807153763e-05 8.43739450733916e-07 1.56937167130205e-05 -3.12039352355358e-06 -3.77250535878414e-07 -2.62200973305653e-06 5.60900263612043e-06 -1.47869262948522e-06 -3.12039352355358e-06 2.97467457653442e-05 -2.55965357751953e-05 2.26565244565783e-06 1.73127668048475e-06 3.80060148500299e-06 -3.77250535878414e-07 -2.55965357751953e-05 0.000116718428694427 6.79936314803441e-07 -4.54353927950516e-06 -2.97584269596049e-05 -2.62200973305653e-06 2.26565244565783e-06 6.79936314803441e-07 4.62278246156181e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 813 0 0 0 0 0 2487 +1080 1118 0.999706474602423 0.0216129826957352 0.0109473109478434 -0.000170621634781005 -0.0213433081445903 0.999479782348666 -0.0241790792568508 -0.0113035886815735 -0.0114641979850308 0.0239383302520844 0.99964770219778 -0.00259990935719167 5.03152361622817e-05 6.55549403399281e-06 -6.30541122866145e-06 1.37378869522675e-05 -3.32319113712606e-05 3.06881598039749e-05 6.55549403399281e-06 7.03709863845529e-05 4.99047834744604e-06 -1.01439306666915e-05 2.85516917698686e-05 -3.81845936534171e-05 -6.30541122866145e-06 4.99047834744604e-06 1.55554971666832e-05 -5.14126889526327e-06 2.94768059966339e-07 -5.88376396979671e-06 1.37378869522675e-05 -1.01439306666915e-05 -5.14126889526327e-06 3.53253777769086e-05 -4.51485949707613e-05 2.64104632513949e-05 -3.32319113712606e-05 2.85516917698686e-05 2.94768059966339e-07 -4.51485949707613e-05 0.000201818055383933 -7.37837375107332e-05 3.06881598039749e-05 -3.81845936534171e-05 -5.88376396979671e-06 2.64104632513949e-05 -7.37837375107332e-05 9.98617774409575e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 716 0 0 0 0 0 2509 +1080 1121 0.999721359895786 0.0207845991667279 0.0111894148908113 -0.0041999665164365 -0.0205629559102396 0.999596974902597 -0.0195717298625027 0.000473553564152079 -0.0115916958359767 0.019336188948593 0.999745839893615 -0.0116817743347607 3.75981302460407e-05 2.21092516878414e-05 -5.6917808755263e-06 4.37749142793932e-06 5.77346667673297e-06 -6.08934136443321e-06 2.21092516878414e-05 5.33903125778586e-05 5.61065367879732e-07 3.76221709209845e-06 -1.27860147817694e-05 -7.18182102025264e-06 -5.6917808755263e-06 5.61065367879732e-07 1.30375678014006e-05 -1.83382508836675e-06 -2.14372946575443e-07 5.01448686322553e-07 4.37749142793932e-06 3.76221709209845e-06 -1.83382508836675e-06 2.88192788135674e-05 -3.19929922242296e-05 -2.32696757475576e-06 5.77346667673297e-06 -1.27860147817694e-05 -2.14372946575443e-07 -3.19929922242296e-05 0.000136074795474397 4.49115920406381e-06 -6.08934136443321e-06 -7.18182102025264e-06 5.01448686322553e-07 -2.32696757475576e-06 4.49115920406381e-06 4.02534268873053e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 839 0 0 0 0 0 2444 +1080 1122 0.999691628888304 0.0215304757816296 0.0123727823575296 -0.000702896406863105 -0.0212794315047975 0.999571986639967 -0.0200755901398295 -0.0033134450452925 -0.0127997236486873 0.0198061136330793 0.999721903799887 -0.0129195305035121 3.51917942567637e-05 1.98924192611925e-05 -7.3771541857762e-06 1.87103423064428e-06 5.98653602310474e-06 -1.35199209858975e-06 1.98924192611925e-05 4.85213088892189e-05 -6.76747115206978e-07 -2.66535838745076e-06 5.08130526955319e-06 -1.02831336257637e-05 -7.3771541857762e-06 -6.76747115206978e-07 1.36722119921308e-05 -8.7523109240258e-07 -4.12652782957925e-06 -1.48124984552742e-06 1.87103423064428e-06 -2.66535838745076e-06 -8.7523109240258e-07 2.76312696805863e-05 -2.6693376113645e-05 6.11237374108924e-06 5.98653602310474e-06 5.08130526955319e-06 -4.12652782957925e-06 -2.6693376113645e-05 0.000126383746610089 -9.14759014071264e-06 -1.35199209858975e-06 -1.02831336257637e-05 -1.48124984552742e-06 6.11237374108924e-06 -9.14759014071264e-06 4.09145309916164e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 822 0 0 0 0 0 2398 +1080 1119 0.999717883850187 0.0218077707672818 0.00941136782122567 -0.00152181983890745 -0.021577461958312 0.999481090439152 -0.0239157477408004 -0.00499869082571826 -0.00992803331694209 0.0237059272909897 0.999669677026233 -0.00312376978565908 8.32362000106073e-05 4.83653727337325e-05 -4.43538153639952e-06 2.18025691949713e-05 -4.32703913783434e-05 2.71135076334777e-05 4.83653727337325e-05 7.48622653327452e-05 -6.82698200850412e-08 5.20070163312666e-06 -2.37806462156978e-07 -4.22595621365163e-06 -4.43538153639952e-06 -6.82698200850412e-08 1.39957690596018e-05 -2.51604455615899e-07 -2.84981675273367e-06 2.67473319883001e-06 2.18025691949713e-05 5.20070163312666e-06 -2.51604455615899e-07 3.3999817147573e-05 -4.07110359611133e-05 1.8958100703661e-05 -4.32703913783434e-05 -2.37806462156978e-07 -2.84981675273367e-06 -4.07110359611133e-05 0.000174665506498852 -5.19791219086083e-05 2.71135076334777e-05 -4.22595621365163e-06 2.67473319883001e-06 1.8958100703661e-05 -5.19791219086083e-05 7.43926222722967e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 721 0 0 0 0 0 2478 +1080 1124 0.999672676022635 0.0219430013071461 0.0131546762551931 -0.00375539429984692 -0.0216974083096877 0.999592841353109 -0.0185303531607344 0.0104922173613204 -0.0135559317786366 0.0182388653499452 0.999741756907432 -0.0115920296571319 2.89825924467609e-05 1.70805341829804e-05 -6.18873611385603e-06 4.08864523568671e-06 -2.54998482973747e-06 -4.95702037846725e-06 1.70805341829804e-05 4.89953418579931e-05 1.93983697410415e-07 6.42278900113663e-07 -5.33032162629951e-06 -2.37641107010449e-05 -6.18873611385603e-06 1.93983697410415e-07 1.34538572591212e-05 3.91427598302245e-07 -3.36202063128958e-06 1.55748632168442e-07 4.08864523568671e-06 6.42278900113663e-07 3.91427598302245e-07 2.91970565876146e-05 -3.45765744026448e-05 2.93222113660876e-06 -2.54998482973747e-06 -5.33032162629951e-06 -3.36202063128958e-06 -3.45765744026448e-05 0.000144298607104245 -1.25626611689279e-05 -4.95702037846725e-06 -2.37641107010449e-05 1.55748632168442e-07 2.93222113660876e-06 -1.25626611689279e-05 4.78304836254745e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 812 0 0 0 0 0 2518 +1080 1131 0.999646874613229 0.0212368259170215 0.0159725796593181 -0.00761032673532161 -0.0209665895747929 0.999637328611207 -0.0169000996639299 0.0185984440584262 -0.0163256913362136 0.016559241287532 0.999729595105785 -0.0147932558656175 2.96322499006184e-05 1.30231675850171e-05 -8.60477332603008e-06 7.99498967492096e-06 -5.11520979149136e-06 -7.20560050118816e-06 1.30231675850171e-05 5.31263233462032e-05 2.87583682592698e-06 -2.81659054299602e-06 -2.50287590948919e-06 -2.37917578903629e-05 -8.60477332603008e-06 2.87583682592698e-06 1.49688642019099e-05 -4.38605331330183e-06 2.50253990324246e-08 -1.05664787197832e-06 7.99498967492096e-06 -2.81659054299602e-06 -4.38605331330183e-06 3.02790109395881e-05 -3.14874081637792e-05 -2.55872088223683e-07 -5.11520979149136e-06 -2.50287590948919e-06 2.50253990324246e-08 -3.14874081637792e-05 0.00012791449141972 -5.86054543783875e-06 -7.20560050118816e-06 -2.37917578903629e-05 -1.05664787197832e-06 -2.55872088223683e-07 -5.86054543783875e-06 4.55640882897216e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 818 0 0 0 0 0 2430 +1080 1129 0.999599792446618 0.021254480834528 0.0186682078714956 -0.00586558546686139 -0.0209983859925028 0.999684142808469 -0.0138087799246114 0.0140090412272038 -0.0189558098320423 0.0134112513119087 0.999730371456154 -0.0189022509120692 5.10189868210069e-05 2.7161126006735e-05 -6.17261229343042e-06 4.95105788154699e-06 -1.64615856540187e-06 5.01035834223089e-06 2.7161126006735e-05 6.0212089756699e-05 1.12140395272395e-07 -7.76841546293585e-06 2.41807981143101e-05 -1.79968844185156e-05 -6.17261229343042e-06 1.12140395272395e-07 1.28434354217067e-05 7.15808866630311e-08 -6.34567334252738e-07 6.47848195956586e-07 4.95105788154699e-06 -7.76841546293585e-06 7.15808866630311e-08 3.00929444617722e-05 -4.12026403526388e-05 2.56622418683848e-06 -1.64615856540187e-06 2.41807981143101e-05 -6.34567334252738e-07 -4.12026403526388e-05 0.000188163397481403 -8.11069408157121e-06 5.01035834223089e-06 -1.79968844185156e-05 6.47848195956586e-07 2.56622418683848e-06 -8.11069408157121e-06 4.91576046716348e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 810 0 0 0 0 0 2436 +1080 1123 0.999661396541959 0.0216183156803003 0.0144824269694789 0.000131036564808959 -0.0212894980969816 0.99952044237059 -0.0224864971500398 -0.00834744555746579 -0.014961602005067 0.0221705595429392 0.999642244382957 -0.010898525616074 4.93391548124788e-05 2.54373172870252e-05 -3.97398014367646e-06 9.6623614961814e-06 -2.1846752227313e-05 -1.34995858301819e-06 2.54373172870252e-05 6.18624900464548e-05 3.3179194182776e-06 -1.56214413285563e-07 -3.48041336730322e-06 -2.12090227312979e-05 -3.97398014367646e-06 3.3179194182776e-06 1.34650187642419e-05 -8.92895374593162e-07 -3.3979220631841e-06 -8.04346221587328e-07 9.6623614961814e-06 -1.56214413285563e-07 -8.92895374593162e-07 3.49209739761212e-05 -4.60359242307671e-05 6.34354719191135e-06 -2.1846752227313e-05 -3.48041336730322e-06 -3.3979220631841e-06 -4.60359242307671e-05 0.000186970247029111 -1.72238405244372e-05 -1.34995858301819e-06 -2.12090227312979e-05 -8.04346221587328e-07 6.34354719191135e-06 -1.72238405244372e-05 4.73708310738458e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 696 0 0 0 0 0 2602 +1080 1128 0.999753751616105 0.0215173343748628 0.00542590553943273 -0.00435669652752789 -0.021391243715511 0.999522127555067 -0.0223143725006111 -0.000729002638460134 -0.00590345846314752 0.0221928107546738 0.999736279390211 -0.00623872807799375 6.78205222148199e-05 2.62914823317118e-05 -6.11949040188263e-06 1.55152400727358e-05 -2.51644478789741e-05 3.08775282574143e-05 2.62914823317118e-05 7.80516409587431e-05 2.36032257134087e-06 -6.78261640564503e-06 2.85814830419068e-05 -1.82326646640292e-05 -6.11949040188263e-06 2.36032257134087e-06 1.34023166656335e-05 -3.67589819602268e-06 2.68560541750107e-07 -2.14169496666903e-06 1.55152400727358e-05 -6.78261640564503e-06 -3.67589819602268e-06 3.1500736143285e-05 -3.17140365465508e-05 1.86352457716591e-05 -2.51644478789741e-05 2.85814830419068e-05 2.68560541750107e-07 -3.17140365465508e-05 0.000155662592755958 -4.22302680496642e-05 3.08775282574143e-05 -1.82326646640292e-05 -2.14169496666903e-06 1.86352457716591e-05 -4.22302680496642e-05 7.94582409355176e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 721 0 0 0 0 0 2567 +1080 1132 0.999688387098652 0.0220005790514918 0.0117942028766347 -0.00414778103136132 -0.0217863922763055 0.999600754898582 -0.0179912177955762 0.0068345910560404 -0.0121853113082552 0.0177286583695435 0.99976857965268 -0.0125506109197624 3.85296241842489e-05 2.09696925196376e-05 -8.3407439414426e-06 5.8989919972353e-06 -1.13132861469926e-06 5.98576896170909e-07 2.09696925196376e-05 5.57212399136959e-05 2.43677021829701e-06 1.29679170596955e-06 -8.5824906554326e-06 -1.51092296683775e-05 -8.3407439414426e-06 2.43677021829701e-06 1.47909772480152e-05 -2.11183273442154e-06 -4.1696419089943e-06 -2.37118346490931e-06 5.8989919972353e-06 1.29679170596955e-06 -2.11183273442154e-06 3.20819309588795e-05 -3.23542128223855e-05 8.94674673852167e-07 -1.13132861469926e-06 -8.5824906554326e-06 -4.1696419089943e-06 -3.23542128223855e-05 0.000129237143795132 -1.9495867641988e-06 5.98576896170909e-07 -1.51092296683775e-05 -2.37118346490931e-06 8.94674673852167e-07 -1.9495867641988e-06 4.51583031846929e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 813 0 0 0 0 0 2362 +1080 1133 0.999690702498159 0.0216358629010067 0.0122633101268501 3.6544116574342e-05 -0.0213818930989375 0.999561684171791 -0.0204756973790544 -0.00874906076396269 -0.012700944305211 0.0202071515108352 0.999715137947593 -0.0101014067239411 2.80929459734517e-05 1.24095301996999e-05 -7.75996311176315e-06 5.28233852506958e-06 -2.95300569850616e-06 1.70899240025298e-06 1.24095301996999e-05 4.63179152481419e-05 -3.33088203268165e-07 -1.96641475635919e-06 2.89062947582752e-06 -1.576090194729e-05 -7.75996311176315e-06 -3.33088203268165e-07 1.26656968640369e-05 -1.6101281949764e-06 -1.69017547943521e-06 -1.68192634717295e-06 5.28233852506958e-06 -1.96641475635919e-06 -1.6101281949764e-06 3.14607437757789e-05 -4.07586060635019e-05 1.37341990700589e-06 -2.95300569850616e-06 2.89062947582752e-06 -1.69017547943521e-06 -4.07586060635019e-05 0.000164491083817245 -2.33353801576226e-06 1.70899240025298e-06 -1.576090194729e-05 -1.68192634717295e-06 1.37341990700589e-06 -2.33353801576226e-06 4.69168325531442e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 716 0 0 0 0 0 2450 +1080 1120 0.99967606497046 0.0215467020599068 0.0135463927123528 -0.00124608888831669 -0.0212624443397034 0.999557764127634 -0.0207890507928169 -0.0021680356007236 -0.0139883374950954 0.020494287069984 0.999692107907038 -0.0110947107217542 2.78534977655452e-05 1.33299867717333e-05 -6.71006567676022e-06 6.99871151173327e-06 -1.33622025570393e-05 -6.61883351667909e-08 1.33299867717333e-05 5.24391676933301e-05 -1.716570864929e-06 5.99416317478164e-06 -1.3971174813417e-05 -2.08113253137221e-05 -6.71006567676022e-06 -1.716570864929e-06 1.37289536218414e-05 -1.44827059115441e-06 -2.92198434895426e-06 -2.86840200853273e-07 6.99871151173327e-06 5.99416317478164e-06 -1.44827059115441e-06 3.68628286297348e-05 -5.00254354234724e-05 1.53108615340535e-06 -1.33622025570393e-05 -1.3971174813417e-05 -2.92198434895426e-06 -5.00254354234724e-05 0.000166490555284691 -5.59889149553014e-06 -6.61883351667909e-08 -2.08113253137221e-05 -2.86840200853273e-07 1.53108615340535e-06 -5.59889149553014e-06 5.62163095539374e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 717 0 0 0 0 0 2511 +1080 1115 0.999723872175078 0.021644884874975 0.00914758777038365 -0.00120972529897817 -0.0214318917738596 0.999510896600004 -0.0227737039774029 -0.00908952287115858 -0.00963604785487104 0.0225713654129715 0.999698794660238 -0.00233254336633912 3.04607265704968e-05 1.60386610337989e-05 -5.50760503817765e-06 2.50505891152084e-06 -6.33946434029152e-06 -6.4663566583655e-06 1.60386610337989e-05 4.33664985816179e-05 -3.24759992392495e-07 1.23221391814364e-06 -1.01526875578302e-05 -1.81958062864309e-05 -5.50760503817765e-06 -3.24759992392495e-07 1.27352744371353e-05 3.04845501714441e-07 -1.69326049599251e-07 8.33380699320986e-07 2.50505891152084e-06 1.23221391814364e-06 3.04845501714441e-07 2.30689599772378e-05 -1.3402498111982e-05 -9.66495620033304e-08 -6.33946434029152e-06 -1.01526875578302e-05 -1.69326049599251e-07 -1.3402498111982e-05 8.09812245170437e-05 1.4912536204219e-06 -6.4663566583655e-06 -1.81958062864309e-05 8.33380699320986e-07 -9.66495620033304e-08 1.4912536204219e-06 3.95217467997658e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 749 0 0 0 0 0 2404 +1080 1137 0.999683920382783 0.0218066521075643 0.0125111650923942 -0.00244409069974426 -0.0215603885718743 0.999577519927759 -0.0194918264844398 0.00524233583174518 -0.0129309308535493 0.0192159199345068 0.999731733740773 -0.00746091218734576 3.05668451494786e-05 1.35659573663115e-05 -7.83761338754753e-06 3.5376963059808e-06 -2.13549062020467e-06 -8.10152418004879e-06 1.35659573663115e-05 5.97357543844636e-05 4.31496955296064e-06 4.32826546684076e-06 -2.33475747536496e-05 -2.34402462484273e-05 -7.83761338754753e-06 4.31496955296064e-06 1.60292723410773e-05 -2.67631545247316e-06 -5.15589529031517e-06 -1.37561636970902e-06 3.5376963059808e-06 4.32826546684076e-06 -2.67631545247316e-06 2.77577175058437e-05 -2.17127662396911e-05 2.4586957490255e-06 -2.13549062020467e-06 -2.33475747536496e-05 -5.15589529031517e-06 -2.17127662396911e-05 0.000101950142907904 6.80132327702115e-06 -8.10152418004879e-06 -2.34402462484273e-05 -1.37561636970902e-06 2.4586957490255e-06 6.80132327702115e-06 3.99273752690479e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 819 0 0 0 0 0 2455 +1080 1126 0.999707430692684 0.021790795822325 0.0104982967790833 -0.00593584016118835 -0.0215976792875999 0.999601615981402 -0.018170018622995 0.00840014722659226 -0.0108900535913255 0.0179379637863319 0.999779793848615 -0.0105686259140559 0.00014642741089704 5.10969537021766e-05 -7.32960983147402e-06 5.42998428115838e-05 -0.000120797920708284 4.76947166104756e-05 5.10969537021766e-05 9.87257525035133e-05 5.31558849093349e-07 6.04794905429439e-06 4.35977419007009e-06 -2.91303191964675e-05 -7.32960983147402e-06 5.31558849093349e-07 1.34107829553964e-05 -1.39419029859406e-06 -7.2544386113162e-06 -3.17168011204175e-06 5.42998428115838e-05 6.04794905429439e-06 -1.39419029859406e-06 6.5614003613855e-05 -0.000132555329283386 3.7375941260896e-05 -0.000120797920708284 4.35977419007009e-06 -7.2544386113162e-06 -0.000132555329283386 0.000444023942724915 -9.87839781482879e-05 4.76947166104756e-05 -2.91303191964675e-05 -3.17168011204175e-06 3.7375941260896e-05 -9.87839781482879e-05 9.67472071077806e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 725 0 0 0 0 0 2578 +1080 1114 0.999711121997136 0.0213362791145721 0.0110650688553428 -0.00266312097335602 -0.0211014610995864 0.999558422848888 -0.0209209859066666 -0.00393925350641673 -0.0115065587684175 0.0206814531740247 0.999719899071695 -0.00287005680888647 2.83377894600873e-05 1.214092799385e-05 -8.73354881480087e-06 4.15408434561746e-06 -1.17693908827466e-06 -5.05754653634585e-06 1.214092799385e-05 4.898427437635e-05 2.20697183742916e-06 -8.10675768563641e-06 4.0527216319325e-06 -2.15251071045032e-05 -8.73354881480087e-06 2.20697183742916e-06 1.53827741659583e-05 -3.99777585712774e-06 -1.53903166117104e-06 -8.10186813550355e-07 4.15408434561746e-06 -8.10675768563641e-06 -3.99777585712774e-06 2.33122442845105e-05 -5.85174169177576e-06 6.25842460936573e-06 -1.17693908827466e-06 4.0527216319325e-06 -1.53903166117104e-06 -5.85174169177576e-06 6.57379168119967e-05 -9.78855578448576e-06 -5.05754653634585e-06 -2.15251071045032e-05 -8.10186813550355e-07 6.25842460936573e-06 -9.78855578448576e-06 3.62883064520988e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 782 0 0 0 0 0 2488 +1080 1138 0.999642966092509 0.0214185529174194 0.0159745401403395 -0.0102039177065541 -0.0211501948122473 0.999635433373276 -0.01678301534369 0.0254920458654432 -0.0163281842583798 0.0164391586021381 0.999731536195232 -0.0099528809726097 4.53698685875754e-05 1.97026698462379e-05 -5.30347598934684e-06 3.39780476756327e-06 -7.4668912219573e-06 7.82868172455877e-06 1.97026698462379e-05 5.27335758138788e-05 2.11844297265432e-06 2.82282471165983e-06 -9.52561242531313e-06 -2.01885129623155e-05 -5.30347598934684e-06 2.11844297265432e-06 1.33574592619643e-05 -7.54146539559834e-07 -3.45914572316017e-06 -6.9185359996091e-07 3.39780476756327e-06 2.82282471165983e-06 -7.54146539559834e-07 2.36841048483199e-05 -1.47982311946194e-05 -1.94648910053832e-08 -7.4668912219573e-06 -9.52561242531313e-06 -3.45914572316017e-06 -1.47982311946194e-05 9.73670882139795e-05 -1.59603175157302e-06 7.82868172455877e-06 -2.01885129623155e-05 -6.9185359996091e-07 -1.94648910053832e-08 -1.59603175157302e-06 5.32061867484515e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 794 0 0 0 0 0 2402 +1080 1127 0.999737813670133 0.0212707641528436 0.00847693992059418 -0.00382451229984089 -0.0210551599673516 0.999471678404993 -0.0247597315222782 0.000443820637679378 -0.00899911977987267 0.0245747565330802 0.999657489935692 -0.00706821662371239 5.16007541824303e-05 1.33418945585464e-05 -9.2957820902816e-06 7.32058612167587e-06 -2.77748148011137e-06 9.09911104878474e-06 1.33418945585464e-05 5.70492822477964e-05 1.71658134002607e-06 -1.10194780455603e-06 2.05430050727122e-06 -2.30097697287227e-05 -9.2957820902816e-06 1.71658134002607e-06 1.57574756913386e-05 -3.73506088651857e-06 -7.53953744435112e-06 -2.68961508854423e-06 7.32058612167587e-06 -1.10194780455603e-06 -3.73506088651857e-06 3.35580725552726e-05 -3.47899130249462e-05 3.77171452814399e-06 -2.77748148011137e-06 2.05430050727122e-06 -7.53953744435112e-06 -3.47899130249462e-05 0.0001677213314879 -7.42358472795191e-07 9.09911104878474e-06 -2.30097697287227e-05 -2.68961508854423e-06 3.77171452814399e-06 -7.42358472795191e-07 6.95895010781912e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 719 0 0 0 0 0 2522 +1080 1134 0.99968524089787 0.0214381908227311 0.0130316194394597 0.00240742198751501 -0.0211799267753955 0.999582688349717 -0.019643315742029 -0.0142743849838963 -0.0134472983441144 0.0193611240841106 0.999722119912051 -0.0116608566194728 5.32576792881579e-05 2.11936608889525e-05 -4.60034376937907e-06 1.42325235012352e-05 -3.26818770443913e-05 6.2880040610645e-06 2.11936608889525e-05 7.10182008586893e-05 3.85352186199812e-06 5.81410485472431e-06 -1.58130877327551e-05 -1.90616864908533e-05 -4.60034376937907e-06 3.85352186199812e-06 1.48874021255605e-05 -7.60578181940213e-07 -1.57176572409467e-06 -2.09110151367371e-06 1.42325235012352e-05 5.81410485472431e-06 -7.60578181940213e-07 3.69190815749198e-05 -4.6207695288489e-05 6.55655274779839e-06 -3.26818770443913e-05 -1.58130877327551e-05 -1.57176572409467e-06 -4.6207695288489e-05 0.000157392161610775 -1.30860447353125e-05 6.2880040610645e-06 -1.90616864908533e-05 -2.09110151367371e-06 6.55655274779839e-06 -1.30860447353125e-05 6.09096967869061e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 702 0 0 0 0 0 2525 +1080 1130 0.999693696380281 0.0217042326625496 0.0118928424718614 -0.00680359383248693 -0.0214796201541845 0.999594397725508 -0.0186993570427444 0.00793131636767522 -0.0122938739038004 0.0184381756231467 0.999754417016563 -0.0116323557221094 7.79635975292744e-05 2.23933411563901e-05 -9.23142688420128e-06 1.82843762846619e-05 -3.21673433929211e-05 2.83338067898099e-05 2.23933411563901e-05 7.08146011508748e-05 2.66324255676632e-06 -6.11922452804862e-06 1.71568403002379e-05 -2.22006076499187e-05 -9.23142688420128e-06 2.66324255676632e-06 1.62494103726693e-05 -4.15315186349191e-06 -1.3606065960012e-06 -2.84473792585233e-06 1.82843762846619e-05 -6.11922452804862e-06 -4.15315186349191e-06 3.44473544535227e-05 -3.457913963997e-05 1.08781625416184e-05 -3.21673433929211e-05 1.71568403002379e-05 -1.3606065960012e-06 -3.457913963997e-05 0.000155439258849102 -3.09531801072981e-05 2.83338067898099e-05 -2.22006076499187e-05 -2.84473792585233e-06 1.08781625416184e-05 -3.09531801072981e-05 7.91290876002091e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 716 0 0 0 0 0 2510 +1080 1135 0.999661293953694 0.0217261317116007 0.0143273365171646 -0.00340882991433077 -0.0215022152932701 0.999647058041628 -0.0156017334357625 0.00162846329601381 -0.0146612451145106 0.0152883795599438 0.99977563150045 -0.0176351780376915 5.09119056172508e-05 2.05304379108272e-05 -8.29720842682814e-06 8.58124970058968e-06 -6.7336903306703e-06 1.31720101364026e-05 2.05304379108272e-05 6.63551046304354e-05 2.21077515117858e-07 4.46245873674678e-06 3.36364062110798e-06 -2.07991497577526e-05 -8.29720842682814e-06 2.21077515117858e-07 1.4856533324258e-05 -1.76912028691945e-06 -2.57230513006484e-06 -2.31076484831775e-06 8.58124970058968e-06 4.46245873674678e-06 -1.76912028691945e-06 2.76434927778702e-05 -2.06734228323819e-05 3.84569189528665e-06 -6.7336903306703e-06 3.36364062110798e-06 -2.57230513006484e-06 -2.06734228323819e-05 0.000109920018913438 -1.19309294772074e-05 1.31720101364026e-05 -2.07991497577526e-05 -2.31076484831775e-06 3.84569189528665e-06 -1.19309294772074e-05 6.20833480811041e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 810 0 0 0 0 0 2503 +1080 1136 0.999695440306625 0.0219764370339 0.0112277711696501 0.00146799190836585 -0.0216992225484388 0.999470583898789 -0.0242424351459685 -0.0114707795800214 -0.0117545893563459 0.0239914179720206 0.99964305704224 -0.00378751332569689 4.25669768572563e-05 1.82020887709781e-05 -6.57331585986748e-06 1.08047242493439e-05 -1.5439316714612e-05 1.6337089226386e-05 1.82020887709781e-05 5.37804833985228e-05 1.34567824739739e-06 4.92260553265851e-06 -8.21251307426578e-06 -1.16336585175632e-05 -6.57331585986748e-06 1.34567824739739e-06 1.45789532459724e-05 -5.52841067121497e-06 5.30638007969487e-07 -1.40362432032646e-06 1.08047242493439e-05 4.92260553265851e-06 -5.52841067121497e-06 4.2908076910383e-05 -4.66191101371626e-05 1.08564068185023e-05 -1.5439316714612e-05 -8.21251307426578e-06 5.30638007969487e-07 -4.66191101371626e-05 0.000156280152727819 -1.81593881956509e-05 1.6337089226386e-05 -1.16336585175632e-05 -1.40362432032646e-06 1.08564068185023e-05 -1.81593881956509e-05 6.60873443051808e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 729 0 0 0 0 0 2501 +1080 1139 0.999601497336632 0.0209295700023152 0.0189420068071476 -0.00872399190632273 -0.020634299307923 0.999664569969588 -0.0156516209892224 0.0201938195922464 -0.0192632347863719 0.0152545287386208 0.999698067987794 -0.0138369097654991 3.62315064363958e-05 1.07643544348338e-05 -8.796674125588e-06 5.39307691333113e-07 1.65566183014725e-05 5.4998517548952e-06 1.07643544348338e-05 6.22329944456254e-05 2.54534806201858e-06 -2.36571313831033e-06 -6.058786182475e-07 -3.04985325594816e-05 -8.796674125588e-06 2.54534806201858e-06 1.4394542346619e-05 -4.24337523955215e-06 -1.80677311968221e-06 -3.16290514114475e-06 5.39307691333113e-07 -2.36571313831033e-06 -4.24337523955215e-06 2.75994772507077e-05 -1.65989569782205e-05 -4.05159543782444e-07 1.65566183014725e-05 -6.058786182475e-07 -1.80677311968221e-06 -1.65989569782205e-05 0.00010172569263074 8.94338096290091e-06 5.4998517548952e-06 -3.04985325594816e-05 -3.16290514114475e-06 -4.05159543782444e-07 8.94338096290091e-06 5.23791380698457e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 815 0 0 0 0 0 2541 +1081 1083 0.999918169508158 0.0111328801214118 0.00630184636884178 -0.00693908453626608 -0.0110474178827889 0.999848681386904 -0.013437592306408 -0.00408171172482743 -0.00645049188645695 0.0133668735713507 0.999889852856478 0.00236942831128004 3.20032001435783e-05 1.9835940349714e-05 -5.72673060882335e-06 1.12062922939702e-06 3.34476105302578e-06 1.20472977715713e-05 1.9835940349714e-05 3.9814976016142e-05 1.29198551836795e-07 -4.73245229419254e-06 2.6149325246638e-06 3.0998279442453e-06 -5.72673060882335e-06 1.29198551836795e-07 1.31704488902013e-05 -1.97406025651946e-06 -3.57318121155875e-07 3.88778265241903e-07 1.12062922939702e-06 -4.73245229419254e-06 -1.97406025651946e-06 2.09603246297891e-05 -2.98030771414933e-06 -1.05706509172551e-06 3.34476105302578e-06 2.6149325246638e-06 -3.57318121155875e-07 -2.98030771414933e-06 5.71110428827991e-05 1.02197894190211e-05 1.20472977715713e-05 3.0998279442453e-06 3.88778265241903e-07 -1.05706509172551e-06 1.02197894190211e-05 5.24708658006225e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 763 0 0 0 0 0 2491 +1081 1085 0.999904064348993 0.0135010385260691 0.00309581283056088 -0.00737528236468228 -0.0134660782049266 0.999848286810825 -0.0110484432947396 0.00269612004517699 -0.00324450861349864 0.0110056948974554 0.999934171755162 -0.00375815438073275 2.48876076090704e-05 1.05617274558687e-05 -6.99357141000633e-06 1.93935741468274e-06 1.26623864042584e-06 -7.51483428158565e-07 1.05617274558687e-05 4.36914210527091e-05 4.70345592410045e-06 -3.69264961586976e-06 6.60693643584464e-07 -1.96330500254641e-05 -6.99357141000633e-06 4.70345592410045e-06 1.52438786716577e-05 -4.22814859204787e-06 -2.31441364798017e-06 -2.49594424499674e-06 1.93935741468274e-06 -3.69264961586976e-06 -4.22814859204787e-06 2.05039296175808e-05 2.65461850784772e-07 5.22683116185851e-06 1.26623864042584e-06 6.60693643584464e-07 -2.31441364798017e-06 2.65461850784772e-07 4.61741527529473e-05 -3.49570829819788e-06 -7.51483428158565e-07 -1.96330500254641e-05 -2.49594424499674e-06 5.22683116185851e-06 -3.49570829819788e-06 3.48385380329928e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 883 0 0 0 0 0 2689 +1081 1120 0.999833678219629 0.0181994482183696 0.0011815169719148 0.00316113447072331 -0.0181791069246789 0.999716103772581 -0.0154023351862828 -0.012311938091447 -0.00146149554536856 0.015378294519107 0.999880678925468 0.000482698144754902 2.81204696207449e-05 9.80072596940109e-06 -8.03946413864934e-06 3.73682399452061e-06 9.67431019354592e-07 1.24171039985037e-05 9.80072596940109e-06 6.33842795832961e-05 4.8781267277627e-06 -5.22333705833084e-06 6.14509965362656e-06 -2.12118223559355e-05 -8.03946413864934e-06 4.8781267277627e-06 1.64763563768639e-05 -4.79951237890058e-06 -2.25344541576851e-06 -4.33593846857642e-06 3.73682399452061e-06 -5.22333705833084e-06 -4.79951237890058e-06 3.70076464287333e-05 -4.12587967514764e-05 8.47630241512226e-06 9.67431019354592e-07 6.14509965362656e-06 -2.25344541576851e-06 -4.12587967514764e-05 0.000153820692471263 -5.53535430096486e-06 1.24171039985037e-05 -2.12118223559355e-05 -4.33593846857642e-06 8.47630241512226e-06 -5.53535430096486e-06 6.56815855246303e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 759 0 0 0 0 0 2625 +1081 1084 0.99989749278258 0.0112263256928982 0.00888670571961463 -0.00607497321756402 -0.0111388799223204 0.999889650490237 -0.00982915034920417 -0.00369260831949181 -0.00899607031909969 0.00972915484243649 0.999912203278301 -0.00672564517477156 4.17425682222899e-05 1.06070527282545e-05 -6.61121646758774e-06 7.41117139642945e-06 -7.30930394742081e-06 2.85637268760131e-05 1.06070527282545e-05 5.39815183271473e-05 1.82481537406731e-06 2.46953686996935e-09 7.60807493424011e-06 -2.10671384454908e-05 -6.61121646758774e-06 1.82481537406731e-06 1.4915837635817e-05 -2.81442983286489e-06 -2.88163035447581e-07 -2.66402874543081e-06 7.41117139642945e-06 2.46953686996935e-09 -2.81442983286489e-06 2.42088344540793e-05 -7.66501804087915e-06 8.59467036062407e-06 -7.30930394742081e-06 7.60807493424011e-06 -2.88163035447581e-07 -7.66501804087915e-06 7.75628086096719e-05 -1.13476642254938e-05 2.85637268760131e-05 -2.10671384454908e-05 -2.66402874543081e-06 8.59467036062407e-06 -1.13476642254938e-05 7.90716722831082e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 789 0 0 0 0 0 2489 +1081 1118 0.999806874324571 0.0171341995908855 0.00962461727604401 0.00437422279042701 -0.0170129863387254 0.999776655292072 -0.0125378558309018 -0.0186795510357255 -0.00983729379295799 0.0123716909667932 0.999875076653805 -0.00567183922968063 3.71139131104936e-05 -6.09877566708438e-06 -1.15401251183334e-05 4.81937314378001e-06 3.3129153683239e-06 2.08959992098605e-05 -6.09877566708438e-06 9.58216995808977e-05 1.30120055408697e-05 -3.6693171446134e-06 1.35166619302251e-06 -4.3496062604347e-05 -1.15401251183334e-05 1.30120055408697e-05 2.00129387797582e-05 -6.974383657471e-06 -3.09086876836487e-06 -6.80110345963264e-06 4.81937314378001e-06 -3.6693171446134e-06 -6.974383657471e-06 3.34647753913825e-05 -1.45039374152114e-05 5.82925312989898e-06 3.3129153683239e-06 1.35166619302251e-06 -3.09086876836487e-06 -1.45039374152114e-05 0.000102086519350475 -4.62970850031275e-07 2.08959992098605e-05 -4.3496062604347e-05 -6.80110345963264e-06 5.82925312989898e-06 -4.62970850031275e-07 7.55201407579143e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 778 0 0 0 0 0 2598 +1080 1140 0.99963837900645 0.0215416100924863 0.0160956594142504 -0.00494583797730868 -0.0212550640876807 0.999616211746863 -0.0177665827743962 0.0137454778413298 -0.0164722028880426 0.0174180437326979 0.99971259784227 -0.00854996934462532 2.72210643480385e-05 1.27469161816046e-05 -7.3236899087118e-06 2.13310369152843e-06 -2.55070630547625e-06 -4.18344868171869e-06 1.27469161816046e-05 4.44993613727253e-05 3.01832788452399e-07 5.31868456097056e-07 -1.17253420940538e-05 -1.88382607723665e-05 -7.3236899087118e-06 3.01832788452399e-07 1.39374267126399e-05 -4.92715997518421e-07 -2.85743224832763e-06 -1.42528388399859e-07 2.13310369152843e-06 5.31868456097056e-07 -4.92715997518421e-07 2.36662182880634e-05 -1.27868831708922e-05 -3.56297637012943e-07 -2.55070630547625e-06 -1.17253420940538e-05 -2.85743224832763e-06 -1.27868831708922e-05 7.96871090482221e-05 5.29307245093811e-06 -4.18344868171869e-06 -1.88382607723665e-05 -1.42528388399859e-07 -3.56297637012943e-07 5.29307245093811e-06 3.27146085054634e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 802 0 0 0 0 0 2482 +1081 1123 0.999848785116674 0.0172456469311195 0.0022348518158743 0.00208921765384329 -0.0172108995457901 0.999743344287776 -0.0147319546944248 -0.0115438146203743 -0.00248834031765508 0.0146912631935118 0.999888981311547 -0.00109608502977798 2.75744957589827e-05 1.54175951374991e-05 -5.04046139601128e-06 1.08014284363144e-06 -1.01860506071225e-06 7.62466659069431e-06 1.54175951374991e-05 5.04631299885281e-05 2.78451369413078e-06 1.32123103532309e-06 -8.86738696051892e-06 -9.29170266963989e-06 -5.04046139601128e-06 2.78451369413078e-06 1.32756095435761e-05 -4.32437337870486e-07 -9.76765871483479e-07 7.40208952635567e-07 1.08014284363144e-06 1.32123103532309e-06 -4.32437337870486e-07 2.84880549644478e-05 -2.49186937584413e-05 9.44502273814692e-07 -1.01860506071225e-06 -8.86738696051892e-06 -9.76765871483479e-07 -2.49186937584413e-05 0.000103981798694098 8.47464366246833e-06 7.62466659069431e-06 -9.29170266963989e-06 7.40208952635567e-07 9.44502273814692e-07 8.47464366246833e-06 4.98400969510769e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 758 0 0 0 0 0 2661 +1081 1126 0.999823472595097 0.0179668945511765 0.00549675795971748 -0.000924860096283103 -0.0179204585878413 0.999804266929906 -0.00838361453997931 0.000565236056861969 -0.00564630958080398 0.00828363017887636 0.999949749067011 -0.0129231164451427 2.9728085371297e-05 7.53702078007912e-06 -7.52758018100322e-06 1.87321564817323e-06 3.96825332944347e-06 1.41379282144634e-05 7.53702078007912e-06 4.06589813107385e-05 4.87414296952619e-08 -1.48003642883573e-06 -8.88885619088402e-07 -1.31028059769668e-05 -7.52758018100322e-06 4.87414296952619e-08 1.57382086738264e-05 -4.92392398275297e-06 -1.98883932691257e-07 -3.89652281024193e-07 1.87321564817323e-06 -1.48003642883573e-06 -4.92392398275297e-06 3.1077449311371e-05 -1.29937906782353e-05 5.57151790628951e-06 3.96825332944347e-06 -8.88885619088402e-07 -1.98883932691257e-07 -1.29937906782353e-05 8.63296936761044e-05 -1.41411408872885e-07 1.41379282144634e-05 -1.31028059769668e-05 -3.89652281024193e-07 5.57151790628951e-06 -1.41411408872885e-07 5.97668667741238e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 772 0 0 0 0 0 2652 +1081 1117 0.999840372391468 0.0173549123048636 0.00424697009427987 0.00236458150070832 -0.0172988916268946 0.999767272128595 -0.0128899157882598 -0.0147062387319579 -0.00446968506409224 0.0128143903264247 0.999907902417013 -0.00158340527215042 5.18668522507811e-05 2.00761584458826e-05 -2.94097124437136e-06 7.86217847908384e-06 -2.96475022766082e-05 3.48893896354905e-05 2.00761584458826e-05 5.21174966608773e-05 -1.21235480875096e-06 -2.4914545641447e-06 1.5732171613181e-05 -1.56831207190375e-05 -2.94097124437136e-06 -1.21235480875096e-06 1.16379863089689e-05 2.1094413162467e-06 9.08105484226219e-07 2.02926173009554e-06 7.86217847908384e-06 -2.4914545641447e-06 2.1094413162467e-06 2.89864028363106e-05 -3.32153086548631e-05 1.80829544511526e-05 -2.96475022766082e-05 1.5732171613181e-05 9.08105484226219e-07 -3.32153086548631e-05 0.000160301646990971 -5.0698381431185e-05 3.48893896354905e-05 -1.56831207190375e-05 2.02926173009554e-06 1.80829544511526e-05 -5.0698381431185e-05 9.87461505068503e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 725 0 0 0 0 0 2510 +1081 1124 0.999828267198397 0.0174409181006959 0.00626502089826673 0.00305934674329704 -0.0173668024778626 0.999780776836992 -0.0116958299797778 -0.00805420608881078 -0.00646763347336607 0.0115850180416684 0.999911974662884 -0.00784810724316004 2.43601455059116e-05 1.50052120146133e-05 -6.617009764483e-06 2.89461833648336e-06 -4.52973914376416e-06 -6.62339592743688e-06 1.50052120146133e-05 5.2231300087238e-05 3.2858235452737e-06 -2.57965748873589e-06 -9.55558535593545e-06 -1.8241705832884e-05 -6.617009764483e-06 3.2858235452737e-06 1.43941803263232e-05 -1.77518439747852e-06 -7.87809027149851e-07 1.68066116555495e-07 2.89461833648336e-06 -2.57965748873589e-06 -1.77518439747852e-06 3.19901757770434e-05 -3.89590261829859e-05 3.41134008874042e-07 -4.52973914376416e-06 -9.55558535593545e-06 -7.87809027149851e-07 -3.89590261829859e-05 0.000143394751483268 -1.40321701293601e-06 -6.62339592743688e-06 -1.8241705832884e-05 1.68066116555495e-07 3.41134008874042e-07 -1.40321701293601e-06 4.01467264224713e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 878 0 0 0 0 0 2635 +1081 1119 0.999829249509013 0.0179679070642615 0.00431580142903081 0.00296218829687265 -0.0179094778038576 0.999752268018029 -0.013215642156213 -0.0142396510117021 -0.00455218969704637 0.013136091828927 0.999903355660148 -0.00550871609562264 4.59647217755863e-05 2.70101480605653e-07 -4.5617930705976e-06 8.902585456939e-06 -1.38212566679752e-05 3.77785734501758e-05 2.70101480605653e-07 6.2184730262795e-05 3.47772551306208e-06 -5.90567332579444e-06 9.57416668603134e-06 -2.9487357549812e-05 -4.5617930705976e-06 3.47772551306208e-06 1.45880075399543e-05 -9.36944764094501e-07 -6.08211414929594e-06 6.27681096806227e-07 8.902585456939e-06 -5.90567332579444e-06 -9.36944764094501e-07 3.02508276303492e-05 -3.22287820809874e-05 1.40543648800483e-05 -1.38212566679752e-05 9.57416668603134e-06 -6.08211414929594e-06 -3.22287820809874e-05 0.000165261819606829 -3.78693050059879e-05 3.77785734501758e-05 -2.9487357549812e-05 6.27681096806227e-07 1.40543648800483e-05 -3.78693050059879e-05 9.92768842451014e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 762 0 0 0 0 0 2639 +1081 1125 0.999829674004613 0.0172086850542762 0.00666964305889648 0.00126942947384719 -0.0171323032293814 0.999788866200236 -0.0113449199249517 -0.00168213554540532 -0.00686346602576886 0.0112287212428561 0.999913400576952 -0.00932346155765026 2.13498695657094e-05 2.83340540487155e-06 -8.06891566299314e-06 2.59842235491233e-06 -2.24314178042929e-06 4.98903000649494e-08 2.83340540487155e-06 6.54333367210841e-05 8.07367956225066e-06 -9.07152713157274e-06 8.23288842505682e-06 -2.16874338983528e-05 -8.06891566299314e-06 8.07367956225066e-06 1.70943216818831e-05 -4.31462563202641e-06 3.34377196753586e-06 -3.62695707867605e-06 2.59842235491233e-06 -9.07152713157274e-06 -4.31462563202641e-06 3.54938718432525e-05 -2.7130155648294e-05 4.06661397987898e-06 -2.24314178042929e-06 8.23288842505682e-06 3.34377196753586e-06 -2.7130155648294e-05 0.000102834801953228 -1.53888381168709e-06 4.98903000649494e-08 -2.16874338983528e-05 -3.62695707867605e-06 4.06661397987898e-06 -1.53888381168709e-06 4.12868316134118e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 884 0 0 0 0 0 2454 +1081 1127 0.999769172310808 0.0173844844179818 0.0126246504301145 0.000395090881791028 -0.0172708515909021 0.999809846058372 -0.00905480038757222 0.000276926184059279 -0.0127796628393192 0.00883467182495714 0.999879307112343 -0.0157181985433994 3.34475629693204e-05 7.04313320809152e-06 -6.16468816701056e-06 -5.44683816697186e-07 7.17306988060692e-06 2.07996104464843e-05 7.04313320809152e-06 6.11501511541784e-05 4.59488390681431e-06 -1.42671547735783e-06 -5.51425985413519e-06 -1.50520636093022e-05 -6.16468816701056e-06 4.59488390681431e-06 1.7239271841602e-05 -6.26015440151817e-06 -5.68385540316661e-06 3.07352883454443e-07 -5.44683816697186e-07 -1.42671547735783e-06 -6.26015440151817e-06 3.79854221796411e-05 -2.79003491482899e-05 -3.75436345127747e-06 7.17306988060692e-06 -5.51425985413519e-06 -5.68385540316661e-06 -2.79003491482899e-05 0.00013860138681986 1.09251716674649e-05 2.07996104464843e-05 -1.50520636093022e-05 3.07352883454443e-07 -3.75436345127747e-06 1.09251716674649e-05 7.01363495201104e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 779 0 0 0 0 0 2736 +1081 1128 0.999780072306291 0.0173472552790543 0.0117847254321157 -0.000850477066331395 -0.0172512058042923 0.999817531089986 -0.00820368352768592 0.00381551346887831 -0.0119248864784946 0.00799857858671126 0.999896904597203 -0.016937545841502 3.58465776568204e-05 5.83834355859459e-06 -6.88111302519556e-06 4.68490028904746e-06 -5.59696408674002e-06 2.09703502608702e-05 5.83834355859459e-06 6.65876398295617e-05 7.9208318078991e-06 4.80206620614277e-06 -1.03925625894546e-05 -2.67957158541726e-05 -6.88111302519556e-06 7.9208318078991e-06 1.62000434716034e-05 -8.94555007015824e-07 -3.0629134366004e-06 -5.298837403302e-06 4.68490028904746e-06 4.80206620614277e-06 -8.94555007015824e-07 3.15588683030372e-05 -2.43425851053297e-05 7.5620896299239e-07 -5.59696408674002e-06 -1.03925625894546e-05 -3.0629134366004e-06 -2.43425851053297e-05 0.000132239136015252 -4.98646858566802e-06 2.09703502608702e-05 -2.67957158541726e-05 -5.298837403302e-06 7.5620896299239e-07 -4.98646858566802e-06 7.15416714327135e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 773 0 0 0 0 0 2630 +1081 1121 0.999822077589818 0.018728562748229 0.00224813286207779 0.00261422027235102 -0.018697879792113 0.999741041835892 -0.0129706807903129 -0.0108068922505082 -0.00249047289878778 0.0129263376975132 0.999913349915116 -0.00480235227350571 2.01751467579871e-05 6.14499077737775e-06 -7.2469833674743e-06 2.98852847918894e-06 -6.79853892799209e-06 -1.41298252452196e-06 6.14499077737775e-06 3.72648254312582e-05 -7.33299637890142e-07 -3.48004341356722e-06 -1.70738580621699e-06 -7.37807020861842e-06 -7.2469833674743e-06 -7.33299637890142e-07 1.35457861445659e-05 -9.03659070744564e-07 1.68219166637561e-06 -2.63525924284793e-07 2.98852847918894e-06 -3.48004341356722e-06 -9.03659070744564e-07 3.01133943600872e-05 -3.50459836188943e-05 -4.74715454280181e-07 -6.79853892799209e-06 -1.70738580621699e-06 1.68219166637561e-06 -3.50459836188943e-05 0.000127264358887703 2.83603421005108e-06 -1.41298252452196e-06 -7.37807020861842e-06 -2.63525924284793e-07 -4.74715454280181e-07 2.83603421005108e-06 3.65538145954837e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 876 0 0 0 0 0 2595 +1081 1130 0.999816460310835 0.0179908245923044 0.00658603993310168 -0.00295589370259191 -0.0179341462004016 0.999802475039838 -0.00856605535102509 0.00819469056100497 -0.00673884942509453 0.00844636813684667 0.999941621682848 -0.0137360382762422 2.55789003899961e-05 1.1172632270366e-05 -6.0031638542541e-06 4.17057122575306e-06 -1.4125062336534e-05 1.2606995944438e-05 1.1172632270366e-05 4.78326243078086e-05 1.22591923050379e-06 -3.0792317468192e-06 -4.21384651303148e-07 -1.55547348459527e-05 -6.0031638542541e-06 1.22591923050379e-06 1.44067160502979e-05 -1.23181427903243e-06 -6.2377703841578e-06 -1.92875884048286e-06 4.17057122575306e-06 -3.0792317468192e-06 -1.23181427903243e-06 4.19858398321442e-05 -6.10841596047323e-05 8.49439554400099e-06 -1.4125062336534e-05 -4.21384651303148e-07 -6.2377703841578e-06 -6.10841596047323e-05 0.000257836912044487 -1.81227784645457e-05 1.2606995944438e-05 -1.55547348459527e-05 -1.92875884048286e-06 8.49439554400099e-06 -1.81227784645457e-05 5.98440870980857e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 769 0 0 0 0 0 2668 +1081 1122 0.999830034726818 0.017779236061791 0.00487856774359661 0.00181571172487667 -0.0177189184823835 0.999769299355455 -0.0121403457165469 -0.00583544434409617 -0.00509328832723995 0.0120518393352111 0.999914402127829 -0.00900386945672649 2.00282491152353e-05 1.40820887744573e-05 -6.07383962272432e-06 2.30727860244334e-06 -1.96848344203715e-06 -6.46549206205022e-06 1.40820887744573e-05 3.16060453654937e-05 -1.91568741952294e-06 -9.81163894319593e-07 -5.76655052379046e-06 -1.09325427888236e-05 -6.07383962272432e-06 -1.91568741952294e-06 1.2822290704805e-05 -9.28786037861616e-07 1.77476570173658e-06 1.57358557024057e-06 2.30727860244334e-06 -9.81163894319593e-07 -9.28786037861616e-07 2.58535026257936e-05 -2.51991681101361e-05 -3.48075309659309e-06 -1.96848344203715e-06 -5.76655052379046e-06 1.77476570173658e-06 -2.51991681101361e-05 9.44903955960103e-05 1.0182770050015e-05 -6.46549206205022e-06 -1.09325427888236e-05 1.57358557024057e-06 -3.48075309659309e-06 1.0182770050015e-05 3.32892742692901e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 893 0 0 0 0 0 2475 +1081 1129 0.999826605833929 0.0178438134761661 0.00532509034977712 -0.0050711270401155 -0.0177983619655624 0.999805770203584 -0.00846405215965804 0.0147513686190879 -0.00547508702655206 0.00836780665684757 0.999950000366921 -0.0123368684769085 2.67490493177564e-05 1.71399343140174e-05 -5.79508169355519e-06 4.3347711926648e-06 -8.01218566859625e-06 -3.91607610535626e-06 1.71399343140174e-05 3.55617569623007e-05 -3.10574928971766e-06 -1.37888965991263e-06 -5.93437784909945e-06 -8.23257202607387e-06 -5.79508169355519e-06 -3.10574928971766e-06 1.32187065197954e-05 -7.09461547035582e-07 -4.15172726050628e-08 2.11924186664914e-06 4.3347711926648e-06 -1.37888965991263e-06 -7.09461547035582e-07 3.38276895144372e-05 -4.5136275144932e-05 2.3050889063517e-06 -8.01218566859625e-06 -5.93437784909945e-06 -4.15172726050628e-08 -4.5136275144932e-05 0.00016475382781661 -1.9175040680257e-06 -3.91607610535626e-06 -8.23257202607387e-06 2.11924186664914e-06 2.3050889063517e-06 -1.9175040680257e-06 3.6417233176979e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 854 0 0 0 0 0 2376 +1081 1132 0.999826662884352 0.0175837661876301 0.0061200777935388 0.000170626376647252 -0.0175164713223647 0.999787366540161 -0.0108809438516565 -0.0030135823204152 -0.00631010443281133 0.0107718556130726 0.999922071817948 -0.00871493021223405 2.02701593201561e-05 3.29172284930513e-06 -9.04960898336158e-06 2.64965636587022e-06 -1.36091736119688e-06 -6.50346466837705e-07 3.29172284930513e-06 5.68229395660697e-05 6.77292726162069e-06 -5.31013273840609e-06 -5.5510778664899e-06 -2.44902133067949e-05 -9.04960898336158e-06 6.77292726162069e-06 1.75884043930091e-05 -5.3615767867814e-06 -4.43029287105306e-07 5.87645643761812e-07 2.64965636587022e-06 -5.31013273840609e-06 -5.3615767867814e-06 3.17686113822068e-05 -2.60369731859651e-05 -5.18059404949941e-06 -1.36091736119688e-06 -5.5510778664899e-06 -4.43029287105306e-07 -2.60369731859651e-05 0.00010139423112478 1.25542582459846e-05 -6.50346466837705e-07 -2.44902133067949e-05 5.87645643761812e-07 -5.18059404949941e-06 1.25542582459846e-05 5.19208991485849e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 870 0 0 0 0 0 2380 +1081 1131 0.999830131243629 0.0183148602243338 0.00206749904747323 -0.00330230844484444 -0.018289451934938 0.999764233693941 -0.0117035453724754 0.0103668115097868 -0.00228136039848607 0.0116637438813236 0.999929373742667 -0.00569302276221023 2.10464750852005e-05 7.5745740299841e-06 -7.06351991493369e-06 2.10634158018308e-06 5.27878913499797e-08 2.38842878818362e-07 7.5745740299841e-06 4.80823590463682e-05 1.38017012679922e-06 6.88171161785307e-06 -3.19126270941021e-05 -1.87389137220113e-05 -7.06351991493369e-06 1.38017012679922e-06 1.44844063715865e-05 -1.22671398499495e-06 -5.94765771757075e-06 -2.5907925319123e-07 2.10634158018308e-06 6.88171161785307e-06 -1.22671398499495e-06 4.96750223848856e-05 -7.80303889789627e-05 -3.13243762874226e-06 5.27878913499797e-08 -3.19126270941021e-05 -5.94765771757075e-06 -7.80303889789627e-05 0.000242402053439263 1.23754540444527e-05 2.38842878818362e-07 -1.87389137220113e-05 -2.5907925319123e-07 -3.13243762874226e-06 1.23754540444527e-05 3.86863177759572e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 876 0 0 0 0 0 2545 +1081 1114 0.999832092217736 0.0179285465794766 0.00378874504990744 0.00148517163253567 -0.0178778854640479 0.999755568204594 -0.0130071155620145 -0.00837947699483534 -0.00402101763737077 0.0129371968160321 0.999908225966615 0.000224383828899238 2.73670909880006e-05 1.23580770356048e-05 -6.25157568245536e-06 6.29577195309553e-07 7.62578130515442e-07 -7.52984517489375e-06 1.23580770356048e-05 3.74062290021453e-05 7.84799095781141e-07 -7.71191932832518e-06 2.31800145252732e-06 -1.86632355688029e-05 -6.25157568245536e-06 7.84799095781141e-07 1.39582432594541e-05 -2.82425688329984e-06 -1.52240463261208e-07 1.51266436359809e-06 6.29577195309553e-07 -7.71191932832518e-06 -2.82425688329984e-06 2.1729655155415e-05 -3.27537005880911e-06 3.66288660135352e-06 7.62578130515442e-07 2.31800145252732e-06 -1.52240463261208e-07 -3.27537005880911e-06 5.23279352038364e-05 -9.92490744414984e-06 -7.52984517489375e-06 -1.86632355688029e-05 1.51266436359809e-06 3.66288660135352e-06 -9.92490744414984e-06 3.10335373368676e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 820 0 0 0 0 0 2474 +1081 1136 0.999809110632877 0.0174915645619685 0.00870559961572142 0.00155140909568319 -0.0174311804629737 0.999823809695484 -0.00696444640130339 -0.00439524537315622 -0.0088258848373409 0.00681136808459745 0.999937852579676 -0.0133849517062518 2.9238632859126e-05 1.28850667976774e-05 -5.82162484431905e-06 -2.58352216018093e-08 -4.42468107029117e-07 4.72710911815137e-06 1.28850667976774e-05 4.83903896603968e-05 2.29213599274051e-06 2.84722874566465e-06 -1.96775854753682e-05 -7.04728341594619e-06 -5.82162484431905e-06 2.29213599274051e-06 1.54327636240449e-05 -1.45398916712312e-06 -4.92508533630875e-06 8.2068950206598e-07 -2.58352216018093e-08 2.84722874566465e-06 -1.45398916712312e-06 3.33981274372617e-05 -3.16372193178931e-05 2.7108282366184e-06 -4.42468107029117e-07 -1.96775854753682e-05 -4.92508533630875e-06 -3.16372193178931e-05 0.000135080347706787 5.18120494054144e-06 4.72710911815137e-06 -7.04728341594619e-06 8.2068950206598e-07 2.7108282366184e-06 5.18120494054144e-06 4.68454592827635e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 778 0 0 0 0 0 2448 +1081 1137 0.999791594944348 0.0178709895042891 0.00986886076372979 0.0033994780669251 -0.0177609192509531 0.999780306474114 -0.0111305226241926 -0.00287427137673971 -0.0100656060919063 0.0109529229278822 0.999889352405224 -0.00492082368926654 2.22377216123658e-05 1.13309976271847e-05 -5.99528360623828e-06 5.18112327424577e-07 2.1659255375234e-06 -7.97990350510261e-06 1.13309976271847e-05 4.44775667249983e-05 1.85439584270166e-06 1.33064867471346e-06 -1.42457065310793e-05 -1.97853183794405e-05 -5.99528360623828e-06 1.85439584270166e-06 1.39342763561552e-05 -1.0065830476988e-06 -3.11532039457629e-07 -2.62789093328619e-07 5.18112327424577e-07 1.33064867471346e-06 -1.0065830476988e-06 2.47042540325322e-05 -1.32644148905258e-05 1.10642292369541e-06 2.1659255375234e-06 -1.42457065310793e-05 -3.11532039457629e-07 -1.32644148905258e-05 6.85598175292194e-05 5.97134498555431e-06 -7.97990350510261e-06 -1.97853183794405e-05 -2.62789093328619e-07 1.10642292369541e-06 5.97134498555431e-06 3.22005830615342e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 879 0 0 0 0 0 2547 +1081 1138 0.999792229375185 0.0173011754390932 0.0107780985996186 -0.00774910732354527 -0.0172183604923014 0.99982187463135 -0.00772962292805313 0.0277747133004058 -0.0109099103091885 0.00754243575235798 0.999912038891405 -0.010267806473149 2.2882429714783e-05 2.94510643877161e-06 -7.47708213062846e-06 2.19845879686475e-07 1.68262045736325e-06 3.0065503000218e-06 2.94510643877161e-06 6.41820587905424e-05 3.91660604393366e-06 -2.38961412527479e-06 3.24136626016348e-06 -3.0866590826975e-05 -7.47708213062846e-06 3.91660604393366e-06 1.53754647555984e-05 -3.21297540737103e-06 -1.80120373311567e-06 -2.40734124426205e-06 2.19845879686475e-07 -2.38961412527479e-06 -3.21297540737103e-06 2.38214862292541e-05 -6.82851007719535e-06 1.63767229324557e-06 1.68262045736325e-06 3.24136626016348e-06 -1.80120373311567e-06 -6.82851007719535e-06 6.56206495328351e-05 -1.24125405290152e-07 3.0065503000218e-06 -3.0866590826975e-05 -2.40734124426205e-06 1.63767229324557e-06 -1.24125405290152e-07 4.48367850257594e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 855 0 0 0 0 0 2398 +1082 1084 0.999996259566223 0.000797767881728509 -0.00261618423844131 -0.0042600226626868 -0.000798923205893966 0.999999583800445 -0.000440591247287666 0.00177861508819355 0.00261583166004054 0.000442679729584267 0.999996480723499 0.000388866877075495 6.44494290100387e-05 3.56285705552875e-05 -6.4473704076496e-06 1.02463165056118e-05 -8.46696756898303e-06 9.00634180567353e-06 3.56285705552875e-05 5.84429500786135e-05 7.42722880839195e-07 -3.6987224054346e-06 1.38619558599513e-05 -1.63168092782358e-05 -6.4473704076496e-06 7.42722880839195e-07 1.1829674738318e-05 -1.40703635913559e-06 5.23475389672908e-08 -2.34349953368259e-06 1.02463165056118e-05 -3.6987224054346e-06 -1.40703635913559e-06 2.10873851765456e-05 -6.19085756156751e-06 8.27872391270449e-06 -8.46696756898303e-06 1.38619558599513e-05 5.23475389672908e-08 -6.19085756156751e-06 6.69969302945896e-05 -1.09448433973413e-05 9.00634180567353e-06 -1.63168092782358e-05 -2.34349953368259e-06 8.27872391270449e-06 -1.09448433973413e-05 4.70063998863828e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 775 0 0 0 0 0 2494 +1081 1135 0.999798250295125 0.0180986475883418 0.00871192643905159 -0.000192371273054044 -0.0180254851610589 0.999802203731766 -0.008404480817594 0.000894404607510857 -0.00886231298899342 0.00824574851531806 0.999926730835768 -0.0132412583386473 2.36003791588829e-05 1.21105315288949e-05 -5.34554762349467e-06 9.83332459759256e-07 2.43784578423016e-06 -9.95957557976612e-07 1.21105315288949e-05 5.5394407047233e-05 7.39418625180636e-06 2.97647586124304e-06 -2.67742373975254e-05 -1.25977256447013e-05 -5.34554762349467e-06 7.39418625180636e-06 1.70069768183409e-05 -1.9202418943995e-07 -1.07148385313296e-05 -8.90551238189248e-07 9.83332459759256e-07 2.97647586124304e-06 -1.9202418943995e-07 2.64575718009338e-05 -2.51306948482815e-05 -8.73445202811269e-07 2.43784578423016e-06 -2.67742373975254e-05 -1.07148385313296e-05 -2.51306948482815e-05 0.000132607329244648 7.24253303478349e-06 -9.95957557976612e-07 -1.25977256447013e-05 -8.90551238189248e-07 -8.73445202811269e-07 7.24253303478349e-06 3.94127371515634e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 863 0 0 0 0 0 2608 +1082 1120 0.999973125205277 0.00733079005952321 9.15657936267989e-05 0.00380839645863845 -0.00733036032973771 0.999964970851975 -0.00404015921035539 0.00483398126749332 -0.000121180145133224 0.0040393794216448 0.999991834331291 -0.00495937536527442 5.99701096953436e-05 4.67883329943463e-05 -6.27860416241594e-06 1.0331431858159e-05 -2.29578085004704e-06 -1.67206063020077e-05 4.67883329943463e-05 8.21850800892676e-05 6.82267108341847e-07 4.60733087584203e-06 -2.70432581023392e-06 -3.09052479510392e-05 -6.27860416241594e-06 6.82267108341847e-07 1.39162646879524e-05 -1.54313741596638e-06 -3.65250093699754e-06 -2.35531361686406e-06 1.0331431858159e-05 4.60733087584203e-06 -1.54313741596638e-06 4.06846788698534e-05 -5.39699263266132e-05 -1.12261971867484e-06 -2.29578085004704e-06 -2.70432581023392e-06 -3.65250093699754e-06 -5.39699263266132e-05 0.000191489741964161 2.64016385693563e-06 -1.67206063020077e-05 -3.09052479510392e-05 -2.35531361686406e-06 -1.12261971867484e-06 2.64016385693563e-06 5.88655095190942e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 705 0 0 0 0 0 2516 +1082 1121 0.999974686671396 0.00707333407846397 0.000770688950599029 0.00286953763835066 -0.00707259770385749 0.999974533752715 -0.000954048090237101 0.00465513779662404 -0.000777417624912801 0.000948573167201894 0.999999247915109 -0.00731955099903672 5.30196622518563e-05 1.63819187779969e-05 -8.85352646388686e-06 1.72623904068735e-05 -3.47860969175725e-05 -6.57216578703586e-09 1.63819187779969e-05 5.89967116301861e-05 5.45553972221072e-06 1.40606995112845e-06 -9.86625997118352e-06 -1.91568500342249e-05 -8.85352646388686e-06 5.45553972221072e-06 1.57686747328764e-05 -1.6285027054139e-06 -7.49936719442915e-07 -3.60486249093075e-06 1.72623904068735e-05 1.40606995112845e-06 -1.6285027054139e-06 4.76865447915542e-05 -8.58730485139497e-05 2.94745847160054e-06 -3.47860969175725e-05 -9.86625997118352e-06 -7.49936719442915e-07 -8.58730485139497e-05 0.000278497974879715 -1.43260476840832e-05 -6.57216578703586e-09 -1.91568500342249e-05 -3.60486249093075e-06 2.94745847160054e-06 -1.43260476840832e-05 4.51588435619866e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 821 0 0 0 0 0 2475 +1081 1134 0.999835305441467 0.0174626420858959 0.00494146983688229 0.00156254193327401 -0.017391300045348 0.999748915037077 -0.0141297404406678 -0.00479112938283399 -0.0051869717081935 0.0140414747647054 0.999887959878971 -0.00521371419855278 3.0711332479539e-05 -3.9059455932543e-07 -8.02401249615465e-06 2.37868941909058e-06 5.66887001124954e-06 1.16757258537973e-05 -3.9059455932543e-07 6.8020912514992e-05 6.40534872034168e-06 3.49761647397812e-06 -1.13749736659449e-05 -2.13704478028402e-05 -8.02401249615465e-06 6.40534872034168e-06 1.6652461023361e-05 -5.2469709358786e-06 -3.90825206650286e-06 -1.64757336986144e-06 2.37868941909058e-06 3.49761647397812e-06 -5.2469709358786e-06 3.94610036273723e-05 -3.44642117686565e-05 -7.78808023349382e-07 5.66887001124954e-06 -1.13749736659449e-05 -3.90825206650286e-06 -3.44642117686565e-05 0.000139458516805739 1.19339765657877e-05 1.16757258537973e-05 -2.13704478028402e-05 -1.64757336986144e-06 -7.78808023349382e-07 1.19339765657877e-05 5.56396849022798e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 764 0 0 0 0 0 2647 +1082 1085 0.999996269888645 0.00193223129935362 -0.00193046393446063 -0.00715554297146472 -0.0019302325898221 0.999997599746386 0.00103667912833747 0.0145012476090614 0.00193246240471676 -0.00103294901700911 0.99999759929981 -0.000436224002030582 7.33784344464282e-05 5.98365224152614e-05 1.9926831835023e-06 7.81121228124991e-06 -1.75196824853844e-05 -1.62895445922428e-05 5.98365224152614e-05 7.79801128775484e-05 7.62999726239317e-06 2.3994901662178e-06 -1.41085669573654e-05 -2.96674055720861e-05 1.9926831835023e-06 7.62999726239317e-06 1.32056804157983e-05 8.46987532887432e-08 -3.3589536981969e-06 -9.25128591240248e-07 7.81121228124991e-06 2.3994901662178e-06 8.46987532887432e-08 2.99289295361903e-05 -3.46518771914416e-05 2.02838071846396e-06 -1.75196824853844e-05 -1.41085669573654e-05 -3.3589536981969e-06 -3.46518771914416e-05 0.000135370671952472 -2.88973046260371e-06 -1.62895445922428e-05 -2.96674055720861e-05 -9.25128591240248e-07 2.02838071846396e-06 -2.88973046260371e-06 4.20715455318702e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 838 0 0 0 0 0 2591 +1082 1123 0.999974078002024 0.00704262975277424 0.00149822901042426 0.0066873079413269 -0.00703644768572614 0.999966870348204 -0.00409226220870004 -0.00562343496404654 -0.00152699966220597 0.00408161391903426 0.99999050430484 -0.00411690324316746 5.30941742705758e-05 3.32695359677773e-05 -4.36809780973126e-06 1.22868119390969e-05 -2.6196374483003e-05 -4.58532492101152e-06 3.32695359677773e-05 6.09911249497312e-05 4.09545401236178e-06 4.16648783582399e-06 -2.03597255426463e-05 -2.24377149039204e-05 -4.36809780973126e-06 4.09545401236178e-06 1.44634259884577e-05 -8.11496480082279e-07 -7.4928931436858e-06 -2.1100908750904e-06 1.22868119390969e-05 4.16648783582399e-06 -8.11496480082279e-07 5.15313469083123e-05 -9.17511350063173e-05 2.67094309111105e-06 -2.6196374483003e-05 -2.03597255426463e-05 -7.4928931436858e-06 -9.17511350063173e-05 0.00031375129450729 1.75242395095048e-06 -4.58532492101152e-06 -2.24377149039204e-05 -2.1100908750904e-06 2.67094309111105e-06 1.75242395095048e-06 5.02011357778098e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 701 0 0 0 0 0 2623 +1082 1119 0.99996857358007 0.0067629048472359 0.00413702432516314 0.000615726553997469 -0.00677265293864393 0.99997431140073 0.00234685125398359 0.0138331665091278 -0.00412104651908177 -0.00237479613080363 0.999988688595488 -0.0124769201005695 0.00025205278426653 8.78516281297398e-05 -8.54113156592394e-06 9.8367955719719e-05 -0.000268270089055453 0.000120619839717412 8.78516281297398e-05 0.000110495251161127 2.1412460455892e-06 -8.8695591276957e-06 4.39102775465153e-05 -6.28344967673376e-06 -8.54113156592394e-06 2.1412460455892e-06 1.46762450655552e-05 -4.73313264450655e-06 6.91016734154863e-06 -2.17778741202639e-06 9.8367955719719e-05 -8.8695591276957e-06 -4.73313264450655e-06 0.000106933540765961 -0.000266540146088231 8.07505113023217e-05 -0.000268270089055453 4.39102775465153e-05 6.91016734154863e-06 -0.000266540146088231 0.000879035418930687 -0.0002412653059703 0.000120619839717412 -6.28344967673376e-06 -2.17778741202639e-06 8.07505113023217e-05 -0.0002412653059703 0.00013923380496145 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 714 0 0 0 0 0 2521 +1082 1086 0.999986866978363 0.00343019337494191 -0.0038078398350072 -0.003563498554056 -0.00344031784541916 0.999990556247001 -0.00265549052629499 0.0069805563322207 0.00379869502869782 0.00266855583101732 0.99998922430487 0.000423927901374822 4.43802987632189e-05 2.16578282451791e-05 -6.80559895013745e-06 7.19298162454075e-06 -6.21889810523171e-06 -1.00926004592358e-05 2.16578282451791e-05 4.34225961348455e-05 -2.42140823440341e-07 -5.91940013355662e-07 1.14937114853523e-06 -1.8675655068043e-05 -6.80559895013745e-06 -2.42140823440341e-07 1.29487157115465e-05 -7.79131924560363e-08 -1.99763495832941e-06 1.15861399664115e-07 7.19298162454075e-06 -5.91940013355662e-07 -7.79131924560363e-08 2.25695588641222e-05 -1.36780331917161e-05 2.1294740914582e-06 -6.21889810523171e-06 1.14937114853523e-06 -1.99763495832941e-06 -1.36780331917161e-05 7.79198346205705e-05 -2.80255788199922e-06 -1.00926004592358e-05 -1.8675655068043e-05 1.15861399664115e-07 2.1294740914582e-06 -2.80255788199922e-06 3.1178513312305e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 845 0 0 0 0 0 2529 +1082 1124 0.99997149248624 0.00718938796502151 0.00230801116323149 -0.00422150998428476 -0.00719157439780202 0.999973698082472 0.000940425938276893 0.0320618859023979 -0.00230118937118958 -0.000956997363062855 0.99999689433694 -0.0108644722983034 6.1563031197314e-05 4.41724622251304e-05 -6.38769061190048e-06 1.54337411186649e-05 -3.2033026514825e-05 -2.30215405750192e-05 4.41724622251304e-05 8.22420739979283e-05 3.37192934138748e-06 1.33996561306335e-05 -4.08691245630302e-05 -3.36293922279258e-05 -6.38769061190048e-06 3.37192934138748e-06 1.35520283678706e-05 4.95216521797163e-07 -3.69473597617937e-06 -1.43506693624316e-06 1.54337411186649e-05 1.33996561306335e-05 4.95216521797163e-07 5.92644286606098e-05 -0.000116942235432827 4.32972938532227e-07 -3.2033026514825e-05 -4.08691245630302e-05 -3.69473597617937e-06 -0.000116942235432827 0.000365441667366189 -4.27148565878006e-06 -2.30215405750192e-05 -3.36293922279258e-05 -1.43506693624316e-06 4.32972938532227e-07 -4.27148565878006e-06 5.79201389149616e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 806 0 0 0 0 0 2529 +1082 1126 0.999975899803714 0.00664740445676476 0.00200295425333604 -0.0125293696329696 -0.00667439558771784 0.999882711629671 0.0137846083598722 0.0512083322858226 -0.00191108746304965 -0.0137976446571358 0.999902981667034 -0.0196280025583801 0.000177508933010403 6.7033233930772e-05 -2.32194596554006e-06 2.95727430226187e-05 -6.7163770862111e-05 4.95219016456968e-05 6.7033233930772e-05 8.68120516022162e-05 3.22447427130475e-06 -3.35772504510071e-06 2.88116078813709e-05 -5.69869506845247e-06 -2.32194596554006e-06 3.22447427130475e-06 1.6248071353469e-05 -4.40275561336048e-06 -4.67428232573954e-06 4.42250093288938e-07 2.95727430226187e-05 -3.35772504510071e-06 -4.40275561336048e-06 5.4842075945576e-05 -0.000100671360518415 1.18139859038688e-05 -6.7163770862111e-05 2.88116078813709e-05 -4.67428232573954e-06 -0.000100671360518415 0.000383879614984008 -4.26773679175705e-05 4.95219016456968e-05 -5.69869506845247e-06 4.42250093288938e-07 1.18139859038688e-05 -4.26773679175705e-05 7.35447316675553e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 740 0 0 0 0 0 2524 +1082 1125 0.999966732985353 0.00696961257477021 0.0042376199873351 0.00224422302629282 -0.00696685730660144 0.999975510298675 -0.000664606781859091 0.0116381754831302 -0.00424214826107141 0.000635061778604179 0.999990800395018 -0.0101231854531764 3.25704495396572e-05 1.53123718440393e-05 -9.38629429392484e-06 6.58903812703707e-06 -1.70429317765118e-06 -1.80031545648113e-06 1.53123718440393e-05 4.77321723152862e-05 1.58224768017458e-07 1.94943902045707e-06 -9.73312816792982e-06 -1.39513654737478e-05 -9.38629429392484e-06 1.58224768017458e-07 1.49662846049006e-05 -2.88621871339887e-06 -4.8508305884305e-07 -2.99262017255746e-06 6.58903812703707e-06 1.94943902045707e-06 -2.88621871339887e-06 5.35796322477449e-05 -9.14171501425766e-05 -3.299598102147e-06 -1.70429317765118e-06 -9.73312816792982e-06 -4.8508305884305e-07 -9.14171501425766e-05 0.000284238568397731 1.77281065005207e-05 -1.80031545648113e-06 -1.39513654737478e-05 -2.99262017255746e-06 -3.299598102147e-06 1.77281065005207e-05 4.26783245463477e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 822 0 0 0 0 0 2425 +1082 1128 0.999968997601898 0.00661053886209039 0.00427838883324473 -0.00565078924679334 -0.00663232672112404 0.999965007929004 0.0050985448718384 0.0323800220827804 -0.00424453499454353 -0.00512676247730263 0.999977849869277 -0.0163161812966124 0.000219033932439427 2.64186054944713e-05 -3.46279027634414e-06 8.36944310606602e-05 -0.00025240493453688 0.00011511720212925 2.64186054944713e-05 0.000104322587372489 7.39807616282042e-06 -1.89217196941654e-05 7.20796641996808e-05 -4.18349427627593e-05 -3.46279027634414e-06 7.39807616282042e-06 1.43606174625784e-05 -2.0915662441444e-06 -5.34362046372311e-06 -3.30017653790998e-06 8.36944310606602e-05 -1.89217196941654e-05 -2.0915662441444e-06 9.63745617703002e-05 -0.000240589062625927 6.1937826995628e-05 -0.00025240493453688 7.20796641996808e-05 -5.34362046372311e-06 -0.000240589062625927 0.000829927880766913 -0.000191886259195901 0.00011511720212925 -4.18349427627593e-05 -3.30017653790998e-06 6.1937826995628e-05 -0.000191886259195901 0.000146115367678135 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 712 0 0 0 0 0 2544 +1082 1118 0.999976473597326 0.00680265660238496 -0.000880973896994892 -0.00387438390900034 -0.00679017867889245 0.99988626210914 0.0134668600245787 0.0234489820020725 0.00097248412114154 -0.013460561227635 0.99990892963613 -0.0126689919015167 0.000136652706473805 3.99670660686985e-05 -4.60770737454975e-06 1.84056919409925e-05 -3.90344189452022e-05 4.737497204471e-05 3.99670660686985e-05 7.19757341174592e-05 1.36595581727976e-06 -1.98432464611381e-06 1.69450406045353e-05 -1.37826460441074e-05 -4.60770737454975e-06 1.36595581727976e-06 1.43575370155693e-05 -1.88642624624223e-06 -5.02888958089175e-06 1.55327210629191e-06 1.84056919409925e-05 -1.98432464611381e-06 -1.88642624624223e-06 5.46493644632254e-05 -9.63286316720156e-05 1.18951045537901e-05 -3.90344189452022e-05 1.69450406045353e-05 -5.02888958089175e-06 -9.63286316720156e-05 0.000337007362580246 -4.78836236369811e-05 4.737497204471e-05 -1.37826460441074e-05 1.55327210629191e-06 1.18951045537901e-05 -4.78836236369811e-05 7.75973302235993e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 731 0 0 0 0 0 2462 +1082 1132 0.999971394227374 0.0066756724468033 0.00355613896583485 -0.00272691060977734 -0.00667577699503684 0.999977716598831 1.75300128947717e-05 0.0229124023144575 -0.00355594269833958 -4.1269502134483e-05 0.999993676764185 -0.0146203991376336 3.09447890656108e-05 1.04315962633249e-05 -9.04247747990783e-06 2.69657841167072e-06 -6.71908427046684e-07 -3.2554425917518e-06 1.04315962633249e-05 5.65544260294378e-05 7.0948259777363e-06 -4.07542609734861e-06 -5.12838762494358e-06 -1.52552987644324e-05 -9.04247747990783e-06 7.0948259777363e-06 1.66963455328053e-05 -2.85808306468652e-06 1.53704503236792e-08 -1.67445170020926e-06 2.69657841167072e-06 -4.07542609734861e-06 -2.85808306468652e-06 3.87829625783728e-05 -4.74999502221208e-05 -9.81360211919866e-07 -6.71908427046684e-07 -5.12838762494358e-06 1.53704503236792e-08 -4.74999502221208e-05 0.000151920653955711 1.86748352716508e-06 -3.2554425917518e-06 -1.52552987644324e-05 -1.67445170020926e-06 -9.81360211919866e-07 1.86748352716508e-06 4.24765773266449e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 823 0 0 0 0 0 2357 +1082 1129 0.999972726700144 0.00734715432202988 0.000751784043264179 -0.01088037082565 -0.00735207158155918 0.99995011255149 0.00676161605845966 0.0486378776359437 -0.000702067902028612 -0.00676695881697734 0.999976857416726 -0.0140505855939112 6.7382739161773e-05 4.91260165287689e-05 -3.47711899532917e-06 9.52116976323505e-06 -8.7744329763097e-06 -1.26730607641295e-05 4.91260165287689e-05 6.5217496611806e-05 5.33684997492594e-07 8.78776559661396e-06 -1.43701119186787e-05 -2.28384571364849e-05 -3.47711899532917e-06 5.33684997492594e-07 1.37445965933005e-05 3.18496214521269e-07 2.70922300382877e-07 6.92034399057048e-07 9.52116976323505e-06 8.78776559661396e-06 3.18496214521269e-07 4.38338157440136e-05 -7.12046934067528e-05 -7.05843673399525e-06 -8.7744329763097e-06 -1.43701119186787e-05 2.70922300382877e-07 -7.12046934067528e-05 0.000227195820490227 1.05132281128166e-05 -1.26730607641295e-05 -2.28384571364849e-05 6.92034399057048e-07 -7.05843673399525e-06 1.05132281128166e-05 5.17527797780492e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 825 0 0 0 0 0 2307 +1082 1122 0.999972856751947 0.00698074417163181 0.00235689841948051 0.00139750481253119 -0.00697632240836468 0.999973899554041 -0.00187913180480935 0.0133770998802228 -0.00236995464177483 0.00186263831581059 0.999995456936431 -0.0110131146149505 4.96506297856141e-05 2.85491178331014e-05 -6.95137302354425e-06 2.77674789932601e-06 1.06069418771512e-05 -1.38963604775751e-05 2.85491178331014e-05 5.09666775340039e-05 -1.84206747055347e-06 5.57675998231291e-06 -8.46307951459082e-06 -1.9918873630409e-05 -6.95137302354425e-06 -1.84206747055347e-06 1.2387329488529e-05 5.92336554873112e-07 -3.7061608166702e-06 1.87703373636145e-07 2.77674789932601e-06 5.57675998231291e-06 5.92336554873112e-07 3.67429304583519e-05 -4.7726721351506e-05 1.02719350307556e-06 1.06069418771512e-05 -8.46307951459082e-06 -3.7061608166702e-06 -4.7726721351506e-05 0.000157577652418333 -3.07822505602951e-06 -1.38963604775751e-05 -1.9918873630409e-05 1.87703373636145e-07 1.02719350307556e-06 -3.07822505602951e-06 4.31793154288347e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 828 0 0 0 0 0 2406 +1082 1115 0.999975054602248 0.0065569918523958 0.0026260295272781 0.00499122912206522 -0.00654337342039755 0.999965271589929 -0.0051613833767563 -0.000872083490942045 -0.0026597814781963 0.00514407153218504 0.999983231904696 -0.000837125618114962 3.42735315826222e-05 2.0686797393055e-05 -6.25187801631666e-06 7.21515747385494e-06 -7.51670423804727e-06 -9.39301101440342e-06 2.0686797393055e-05 5.42982264037571e-05 9.17756955329076e-07 4.66657409261854e-06 -1.89506717011404e-05 -2.18586575247879e-05 -6.25187801631666e-06 9.17756955329076e-07 1.432291406703e-05 -7.17315871444521e-07 7.064840100858e-07 -2.87211953738657e-06 7.21515747385494e-06 4.66657409261854e-06 -7.17315871444521e-07 3.27116981214617e-05 -4.03230038002317e-05 -3.40525139052038e-06 -7.51670423804727e-06 -1.89506717011404e-05 7.064840100858e-07 -4.03230038002317e-05 0.000144096182925702 8.76954671271805e-06 -9.39301101440342e-06 -2.18586575247879e-05 -2.87211953738657e-06 -3.40525139052038e-06 8.76954671271805e-06 3.97606414057224e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 761 0 0 0 0 0 2463 +1082 1133 0.999974177665158 0.00709400691445541 0.00114850719999734 -0.000867780992852737 -0.00709485331243533 0.999974561411402 0.000734565552092723 0.0184447000225723 -0.00114326697048951 -0.00074269507400733 0.999999070671899 -0.0118984561825556 0.000201314607982077 7.60090589898205e-05 2.14725331053305e-06 6.81356619807322e-05 -0.000175727683021537 3.63145297506812e-05 7.60090589898205e-05 6.25740839443225e-05 1.18955653010915e-06 2.02484021952832e-05 -5.70906240428387e-05 -2.00193547416636e-06 2.14725331053305e-06 1.18955653010915e-06 1.3270549619764e-05 1.72014647901159e-06 -5.06187274758538e-06 3.42751656094952e-06 6.81356619807322e-05 2.02484021952832e-05 1.72014647901159e-06 8.33393509958289e-05 -0.000176935526541972 2.1227835871404e-05 -0.000175727683021537 -5.70906240428387e-05 -5.06187274758538e-06 -0.000176935526541972 0.000521122644589282 -6.73635950135148e-05 3.63145297506812e-05 -2.00193547416636e-06 3.42751656094952e-06 2.1227835871404e-05 -6.73635950135148e-05 7.29216228370999e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 697 0 0 0 0 0 2384 +1082 1114 0.999976741942348 0.00674915773423852 -0.000982061222613993 0.00396349143180892 -0.00675094509283662 0.999975540878302 -0.00182821921582737 0.000414972481310889 0.000969698262398649 0.00183480653639112 0.999997846582808 0.000526496368269178 8.21263987856408e-05 7.33534393470277e-05 -4.16115886891407e-06 2.16066488432481e-05 -3.58860776964837e-05 -4.19092005995256e-05 7.33534393470277e-05 0.000106163155522068 3.57520412253265e-06 1.68105741396093e-05 -3.64271471725727e-05 -5.97939448718097e-05 -4.16115886891407e-06 3.57520412253265e-06 1.36170211413666e-05 -8.3768898082938e-07 9.50946932781146e-07 -1.96981592865264e-06 2.16066488432481e-05 1.68105741396093e-05 -8.3768898082938e-07 3.19188326758963e-05 -2.84652422584828e-05 -1.00113155315581e-05 -3.58860776964837e-05 -3.64271471725727e-05 9.50946932781146e-07 -2.84652422584828e-05 0.000101954245191943 1.57093581015097e-05 -4.19092005995256e-05 -5.97939448718097e-05 -1.96981592865264e-06 -1.00113155315581e-05 1.57093581015097e-05 6.62926349877392e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 782 0 0 0 0 0 2418 +1082 1134 0.999974136885019 0.00709534226818617 0.00117544849259241 0.00477064133518475 -0.00708965566373943 0.999963475357673 -0.00477333564436678 0.00108776552450841 -0.00120927400991436 0.00476487866597523 0.999987916720831 -0.0082763831297835 3.68219727380417e-05 2.08600224716833e-05 -6.06160591061485e-06 3.14518780174895e-06 -1.99443344515773e-06 3.01575242334862e-06 2.08600224716833e-05 5.23852115256912e-05 9.4314442252647e-07 3.33680790563014e-06 -2.12211556301613e-05 -6.02712607027815e-06 -6.06160591061485e-06 9.4314442252647e-07 1.28576501776203e-05 -1.63056452911626e-06 -1.08311598656517e-06 5.3598061881461e-07 3.14518780174895e-06 3.33680790563014e-06 -1.63056452911626e-06 4.28271532709709e-05 -6.47622356991101e-05 -2.97116805464181e-06 -1.99443344515773e-06 -2.12211556301613e-05 -1.08311598656517e-06 -6.47622356991101e-05 0.000210565257779502 1.10902974730979e-05 3.01575242334862e-06 -6.02712607027815e-06 5.3598061881461e-07 -2.97116805464181e-06 1.10902974730979e-05 4.20544978132136e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 705 0 0 0 0 0 2545 +1082 1137 0.99995003647155 0.00715846091497575 0.0069771769272669 0.0061167071151921 -0.00713750045199638 0.999969953998936 -0.0030244316264265 0.00650004516853755 -0.00699861756658931 0.00297448091167886 0.999971085489707 -0.00744060820748692 3.0560294209953e-05 1.59494576575221e-05 -7.07213947916541e-06 3.37545130203168e-06 -8.40652217964996e-06 -3.61265703842904e-06 1.59494576575221e-05 6.03391665692833e-05 3.79711127774923e-06 1.10125821265759e-06 -1.11853997541208e-05 -2.13007848261296e-05 -7.07213947916541e-06 3.79711127774923e-06 1.53251818633756e-05 -3.05813570249078e-06 2.46031167266329e-08 -2.37160871804414e-06 3.37545130203168e-06 1.10125821265759e-06 -3.05813570249078e-06 3.96229347893155e-05 -4.72153145584127e-05 4.11489284492361e-06 -8.40652217964996e-06 -1.11853997541208e-05 2.46031167266329e-08 -4.72153145584127e-05 0.000164113129458342 2.84340511782441e-06 -3.61265703842904e-06 -2.13007848261296e-05 -2.37160871804414e-06 4.11489284492361e-06 2.84340511782441e-06 3.29494208229602e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 822 0 0 0 0 0 2444 +1082 1135 0.999973177072213 0.0065048937702633 0.00336622832586804 -0.00465251358351833 -0.00652456052790776 0.99996151668187 0.00586474766825081 0.0270426754312548 -0.00332794922166111 -0.0058865535190105 0.99997713635945 -0.016358860730239 6.27073147376576e-05 4.98661011756662e-05 -1.75247916230623e-06 -1.22416830092841e-06 2.69841544213616e-05 -1.82293679740966e-05 4.98661011756662e-05 0.000100401079946968 9.25677326320505e-06 6.19267312708479e-07 7.77945100803004e-06 -3.68605406029506e-05 -1.75247916230623e-06 9.25677326320505e-06 1.52158218560526e-05 -1.19239223082125e-06 -4.05562446914597e-07 -2.65808599258038e-06 -1.22416830092841e-06 6.19267312708479e-07 -1.19239223082125e-06 4.6104640967957e-05 -7.16704197515547e-05 -4.60761763593908e-06 2.69841544213616e-05 7.77945100803004e-06 -4.05562446914597e-07 -7.16704197515547e-05 0.000238612169299877 -3.1672894472028e-07 -1.82293679740966e-05 -3.68605406029506e-05 -2.65808599258038e-06 -4.60761763593908e-06 -3.1672894472028e-07 6.36374407019717e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 819 0 0 0 0 0 2463 +1082 1131 0.999971250320478 0.00723633230416248 0.00226583920093683 -0.0050059078735876 -0.00723613999969943 0.999973814466237 -9.30577708509009e-05 0.0313744061671936 -0.0022664532656813 7.66591657950259e-05 0.999997428653178 -0.0110879183360349 2.92431940107639e-05 8.72627972897537e-06 -6.24916243432569e-06 4.02370374086008e-07 8.67831774546761e-06 9.85038365643239e-07 8.72627972897537e-06 5.37835652766798e-05 3.01531068716237e-06 6.23440262128309e-06 -2.74309388252525e-05 -1.64274558018092e-05 -6.24916243432569e-06 3.01531068716237e-06 1.33351115022055e-05 4.87676165532844e-07 -3.37948140192961e-06 -1.30320769607634e-06 4.02370374086008e-07 6.23440262128309e-06 4.87676165532844e-07 6.45708665531822e-05 -0.000126879865462623 -1.47821580511256e-06 8.67831774546761e-06 -2.74309388252525e-05 -3.37948140192961e-06 -0.000126879865462623 0.000374219324051206 6.34330941039066e-06 9.85038365643239e-07 -1.64274558018092e-05 -1.30320769607634e-06 -1.47821580511256e-06 6.34330941039066e-06 4.33649670970278e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2437 +1082 1136 0.999966940538478 0.00699511741309947 0.00414561967525798 0.00168080937067219 -0.00702060595811132 0.999956344920639 0.00616598288494306 0.0130316848085015 -0.00410230692365472 -0.00619488380306132 0.999972396865319 -0.0138098863026873 0.000275149362520888 6.61784328657226e-05 -5.11124102771122e-06 9.02809697571002e-05 -0.000249204791921175 0.000111073747466911 6.61784328657226e-05 9.61295309099973e-05 6.96792195346455e-06 -9.15331927853741e-06 3.81477258053319e-05 -1.2649777396706e-05 -5.11124102771122e-06 6.96792195346455e-06 1.49632172383637e-05 -3.45252148142862e-06 5.92829334137074e-06 -6.40141040642807e-06 9.02809697571002e-05 -9.15331927853741e-06 -3.45252148142862e-06 9.02120163626252e-05 -0.000212371427890958 6.11839056706979e-05 -0.000249204791921175 3.81477258053319e-05 5.92829334137074e-06 -0.000212371427890958 0.000710006313226376 -0.000172262241488901 0.000111073747466911 -1.2649777396706e-05 -6.40141040642807e-06 6.11839056706979e-05 -0.000172262241488901 0.000120363815060112 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 727 0 0 0 0 0 2358 +1082 1138 0.99996892566923 0.00705996658157836 0.00350778673719858 -0.0084761288085472 -0.00708131758613603 0.99995624779911 0.00611207237929044 0.0470353243872887 -0.0034644822370666 -0.00613672220264217 0.999975168693422 -0.0108918345729519 6.01218016206589e-05 3.10942810083446e-05 -7.6953537523535e-06 9.25880182002785e-06 -3.41212576620441e-06 -5.85602105683726e-06 3.10942810083446e-05 7.08880242141883e-05 4.58052099617164e-06 4.30963434721814e-06 -1.02142617962197e-05 -2.86684238542852e-05 -7.6953537523535e-06 4.58052099617164e-06 1.57796532754043e-05 -2.2912409507087e-06 -4.93015935411229e-06 -2.92105486972652e-06 9.25880182002785e-06 4.30963434721814e-06 -2.2912409507087e-06 4.46097725955256e-05 -5.71209692763413e-05 9.51584358270317e-07 -3.41212576620441e-06 -1.02142617962197e-05 -4.93015935411229e-06 -5.71209692763413e-05 0.000197867306398304 -3.65025559236183e-06 -5.85602105683726e-06 -2.86684238542852e-05 -2.92105486972652e-06 9.51584358270317e-07 -3.65025559236183e-06 4.9577795910183e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 815 0 0 0 0 0 2301 +1083 1086 0.999985406470171 0.00268309201984494 0.00468912186866433 6.25942911952241e-05 -0.00269345447537745 0.999993941672437 0.0022049765103608 0.0176796195283315 -0.00468317730554918 -0.00221757426825307 0.99998657501723 -0.0062047712209463 2.48114605345895e-05 -1.08679078666366e-05 -1.19565699513486e-05 5.00088439388675e-06 3.34883782563422e-06 1.41731267647446e-05 -1.08679078666366e-05 7.99732261345408e-05 1.3646103734819e-05 -9.17131175240511e-07 7.02070976041005e-06 -4.36113544295044e-05 -1.19565699513486e-05 1.3646103734819e-05 1.86026817467254e-05 -6.95842554074416e-06 -6.26166417351668e-06 -8.68308060089056e-06 5.00088439388675e-06 -9.17131175240511e-07 -6.95842554074416e-06 2.71049183587261e-05 -4.85363668629111e-06 3.23567532615442e-06 3.34883782563422e-06 7.02070976041005e-06 -6.26166417351668e-06 -4.85363668629111e-06 8.79256843683075e-05 -5.52101571264762e-07 1.41731267647446e-05 -4.36113544295044e-05 -8.68308060089056e-06 3.23567532615442e-06 -5.52101571264762e-07 5.81235144265415e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 967 0 0 0 0 0 2681 +1083 1087 0.999989568120906 0.00369482929690163 0.00268549545342021 0.00301149211014824 -0.00369704771902498 0.999992828395456 0.000821581291565419 0.00755736528053973 -0.00268244059148295 -0.000831501125769238 0.9999960565514 -0.00570318207311084 3.52930885290525e-05 -1.89022840976941e-05 -1.52783269120402e-05 7.72554828288054e-06 -4.40590139164771e-06 2.38009456679288e-05 -1.89022840976941e-05 0.000115536500947361 1.9714974981586e-05 -1.23192658483938e-05 6.68057082248941e-06 -6.43521931307625e-05 -1.52783269120402e-05 1.9714974981586e-05 2.2528131507159e-05 -1.12594334234627e-05 -6.591697813141e-06 -1.13041118997892e-05 7.72554828288054e-06 -1.23192658483938e-05 -1.12594334234627e-05 2.77498074514303e-05 8.14831400154661e-06 8.26677605642529e-06 -4.40590139164771e-06 6.68057082248941e-06 -6.591697813141e-06 8.14831400154661e-06 5.23956839590299e-05 -9.17864334353207e-06 2.38009456679288e-05 -6.43521931307625e-05 -1.13041118997892e-05 8.26677605642529e-06 -9.17864334353207e-06 7.57213872058161e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 878 0 0 0 0 0 2573 +1083 1124 0.999976998356676 0.00581266248908202 0.00349509833332467 0.0101152426204325 -0.00582728989365247 0.999974244627749 0.00418960304302099 -0.000158741149757197 -0.00347065556731372 -0.00420987362646124 0.999985115646219 -0.0113020935789257 2.37691955856162e-05 -1.46869272973881e-05 -1.31509974624817e-05 5.46421169772968e-06 1.08929426137438e-06 6.70809973763163e-06 -1.46869272973881e-05 0.000111641983462768 2.34950649151786e-05 -9.39409634364403e-06 -5.76142463184592e-06 -4.19657228939183e-05 -1.31509974624817e-05 2.34950649151786e-05 2.48994314752765e-05 -1.23823125567928e-05 -1.21171987937823e-05 -5.90650007999976e-06 5.46421169772968e-06 -9.39409634364403e-06 -1.23823125567928e-05 3.54908554522202e-05 -6.35684428368964e-06 -1.25605916146494e-06 1.08929426137438e-06 -5.76142463184592e-06 -1.21171987937823e-05 -6.35684428368964e-06 9.3513655719802e-05 3.65130224396899e-06 6.70809973763163e-06 -4.19657228939183e-05 -5.90650007999976e-06 -1.25605916146494e-06 3.65130224396899e-06 5.31102743702351e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 917 0 0 0 0 0 2695 +1083 1123 0.999973984745092 0.00590519265569057 0.00414228592937388 0.0124772453510485 -0.00591182566629896 0.99998125953377 0.00159087980226653 -0.00263332056673952 -0.00413281384927987 -0.00161532688739737 0.999990155235907 -0.00748569603431122 2.37697119290177e-05 -2.06412305550414e-05 -1.28152746654719e-05 3.9423307428412e-06 1.97408654741966e-06 8.91805060068376e-06 -2.06412305550414e-05 0.000109292334853815 2.71180140810406e-05 -1.62397107043069e-05 -1.05219989921145e-06 -4.58360203309242e-05 -1.28152746654719e-05 2.71180140810406e-05 2.41164453758925e-05 -1.16598899483759e-05 -6.11342900474062e-06 -8.99660214608961e-06 3.9423307428412e-06 -1.62397107043069e-05 -1.16598899483759e-05 3.43706049867365e-05 -2.05157556265742e-05 3.56239543237012e-06 1.97408654741966e-06 -1.05219989921145e-06 -6.11342900474062e-06 -2.05157556265742e-05 0.000123230934583305 3.56082156639566e-06 8.91805060068376e-06 -4.58360203309242e-05 -8.99660214608961e-06 3.56239543237012e-06 3.56082156639566e-06 5.80533467416659e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 828 0 0 0 0 0 2778 +1083 1120 0.999975172867535 0.00649656376501926 0.00272915880652604 0.014301864227265 -0.00650052245911328 0.99997782855853 0.00144416035288078 -0.00696421649571725 -0.0027197162173219 -0.0014618654566367 0.99999523303518 -0.00587573861630055 2.35597539970805e-05 -1.68327559943057e-05 -1.37227850110788e-05 4.13488100399379e-06 2.5665015992877e-06 1.09700521477044e-05 -1.68327559943057e-05 9.72354904590164e-05 1.39894503612264e-05 -1.02009634831936e-05 9.55040005981504e-06 -4.27307954978826e-05 -1.37227850110788e-05 1.39894503612264e-05 1.96351552027556e-05 -7.77212422535653e-06 -9.55174264035885e-06 -7.60922888274187e-06 4.13488100399379e-06 -1.02009634831936e-05 -7.77212422535653e-06 2.70030647079479e-05 -5.88869543784927e-06 8.23827854027433e-06 2.5665015992877e-06 9.55040005981504e-06 -9.55174264035885e-06 -5.88869543784927e-06 0.000101474672249544 -1.00918383283599e-05 1.09700521477044e-05 -4.27307954978826e-05 -7.60922888274187e-06 8.23827854027433e-06 -1.00918383283599e-05 5.45606815893102e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 828 0 0 0 0 0 2642 +1083 1122 0.999973897967808 0.00646396236886428 0.00322809131865703 0.0124091250753479 -0.00647315819702661 0.999974997767224 0.00284641237296439 -0.00448459832297448 -0.00320961150670135 -0.00286723402159711 0.999990738638634 -0.008626821082698 2.79593673165089e-05 -1.66116556223842e-05 -1.436641464216e-05 7.84958045808942e-06 -8.28036592987586e-07 9.75342385146849e-06 -1.66116556223842e-05 0.000106156767542862 2.04259926217858e-05 -7.70433091104944e-06 1.10559212244226e-06 -5.06612458700443e-05 -1.436641464216e-05 2.04259926217858e-05 2.31221671017587e-05 -9.13023751598756e-06 -1.18542687084277e-05 -8.5076381423605e-06 7.84958045808942e-06 -7.70433091104944e-06 -9.13023751598756e-06 3.39324978557006e-05 -1.64852698848934e-05 3.87885391925102e-06 -8.28036592987586e-07 1.10559212244226e-06 -1.18542687084277e-05 -1.64852698848934e-05 0.000128302091516101 -3.1710196872945e-06 9.75342385146849e-06 -5.06612458700443e-05 -8.5076381423605e-06 3.87885391925102e-06 -3.1710196872945e-06 6.09397460893766e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 925 0 0 0 0 0 2508 +1083 1085 0.99999106136968 0.00117684183720898 0.0040610619338297 -0.000579602254782037 -0.00118287833667359 0.999998198747171 0.00148435213260691 0.0118268250308176 -0.0040593077711396 -0.00148914260671735 0.999990652193667 -0.00408175925400233 3.06191082304831e-05 -2.46215692487169e-05 -1.36864283483771e-05 6.3873891149589e-06 -1.97106971384091e-06 1.84286002980413e-05 -2.46215692487169e-05 0.000101412520404626 2.30039707493857e-05 -1.32133497428691e-05 4.90550363786887e-06 -6.33029784929128e-05 -1.36864283483771e-05 2.30039707493857e-05 2.70327324871089e-05 -1.45295404750294e-05 -1.02689355780717e-05 -1.04247701676307e-05 6.3873891149589e-06 -1.32133497428691e-05 -1.45295404750294e-05 2.96987163357887e-05 1.14036470637287e-05 4.89595196736255e-06 -1.97106971384091e-06 4.90550363786887e-06 -1.02689355780717e-05 1.14036470637287e-05 5.58681288188081e-05 -1.03006438006457e-05 1.84286002980413e-05 -6.33029784929128e-05 -1.04247701676307e-05 4.89595196736255e-06 -1.03006438006457e-05 7.09790579769355e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 919 0 0 0 0 0 2742 +1083 1119 0.999978130176209 0.00642109671189083 0.00158388330039453 0.0124653542742098 -0.0064189798783438 0.999978503041555 -0.00133796565451911 -0.00781091156829064 -0.00159244045858589 0.00132776947841113 0.999997850578489 -0.000677826899939389 3.07434673117981e-05 -2.43281564488684e-05 -1.34340980217236e-05 3.61691830876385e-06 7.71476403327833e-06 1.89485723876479e-05 -2.43281564488684e-05 0.000131410923394989 2.44984040260868e-05 -2.55483671708946e-06 -2.92467719236106e-05 -5.39435616233013e-05 -1.34340980217236e-05 2.44984040260868e-05 2.6751020319996e-05 -1.24061374454019e-05 -1.60198544574166e-05 -9.44665404568378e-06 3.61691830876385e-06 -2.55483671708946e-06 -1.24061374454019e-05 3.88303037833244e-05 -1.26507698655072e-05 4.84422088800211e-06 7.71476403327833e-06 -2.92467719236106e-05 -1.60198544574166e-05 -1.26507698655072e-05 0.000113769018234439 -2.94650502667501e-07 1.89485723876479e-05 -5.39435616233013e-05 -9.44665404568378e-06 4.84422088800211e-06 -2.94650502667501e-07 6.79168787901013e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 821 0 0 0 0 0 2727 +1083 1128 0.999975910649909 0.00565818179311574 0.0040203356427859 0.0113258975418867 -0.00565953623302704 0.999983931687916 0.000325600374897985 -0.00400282326009717 -0.00401842873666503 -0.000348345766635841 0.999991865409772 -0.00682633042015548 2.46650104914838e-05 -1.03298522724569e-05 -1.00390230626018e-05 2.23503225049417e-06 5.99486846834936e-06 1.30427767905335e-05 -1.03298522724569e-05 8.41161420293115e-05 1.69039501662699e-05 -7.99292527454642e-06 -3.71088594035281e-06 -3.16123824253137e-05 -1.00390230626018e-05 1.69039501662699e-05 2.3166570327211e-05 -1.28706445807997e-05 -3.42692412197956e-06 -5.7375284424032e-06 2.23503225049417e-06 -7.99292527454642e-06 -1.28706445807997e-05 4.44604303341294e-05 -3.87666142175659e-05 4.07490970996552e-07 5.99486846834936e-06 -3.71088594035281e-06 -3.42692412197956e-06 -3.87666142175659e-05 0.000159864965618208 3.61808071284675e-06 1.30427767905335e-05 -3.16123824253137e-05 -5.7375284424032e-06 4.07490970996552e-07 3.61808071284675e-06 5.99283210795419e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 845 0 0 0 0 0 2620 +1083 1121 0.999983344342874 0.00576507344332363 0.000273797433070974 0.00906431430978114 -0.00576528239440152 0.999983085241659 0.000768602294215585 -0.00628911635047166 -0.000269361753178699 -0.000770168012159822 0.999999667142684 -0.0089230715360658 3.11157051023775e-05 -3.38413935005701e-05 -1.53273371891231e-05 1.07056297574957e-05 -1.54877266372896e-05 2.13850160598185e-05 -3.38413935005701e-05 0.000134015834418991 2.45432763675078e-05 -2.19485431232537e-05 3.78029207382386e-05 -6.42737754316589e-05 -1.53273371891231e-05 2.45432763675078e-05 2.49582702289531e-05 -1.57076383299389e-05 -5.6042281493325e-06 -1.27728422822129e-05 1.07056297574957e-05 -2.19485431232537e-05 -1.57076383299389e-05 3.95601150074289e-05 -3.03936469592358e-05 8.83126727073113e-06 -1.54877266372896e-05 3.78029207382386e-05 -5.6042281493325e-06 -3.03936469592358e-05 0.000171308318906523 -2.70737681565037e-05 2.13850160598185e-05 -6.42737754316589e-05 -1.27728422822129e-05 8.83126727073113e-06 -2.70737681565037e-05 7.6283360123868e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 918 0 0 0 0 0 2642 +1083 1127 0.999949062603867 0.00495874215552866 0.00879107922175818 0.0107845592830323 -0.00496555714164412 0.999987387616167 0.000753558801667001 0.00368974480077735 -0.00878723164149623 -0.000797173023556171 0.999961073779999 -0.0108312192985802 3.31786955088255e-05 -2.3810500559003e-05 -1.48615737991643e-05 5.54713294912218e-06 1.1424093751928e-05 1.89628043482154e-05 -2.3810500559003e-05 0.000154728596398698 2.48685809619409e-05 -1.73551877122073e-06 -1.75303310864024e-05 -7.16452187685329e-05 -1.48615737991643e-05 2.48685809619409e-05 2.57029398100881e-05 -1.38761623668489e-05 -1.00540125163133e-05 -9.06580780885147e-06 5.54713294912218e-06 -1.73551877122073e-06 -1.38761623668489e-05 3.95912382434245e-05 -1.05373586500126e-05 -1.71078466266625e-06 1.1424093751928e-05 -1.75303310864024e-05 -1.00540125163133e-05 -1.05373586500126e-05 0.000104128890935348 1.27558072280758e-05 1.89628043482154e-05 -7.16452187685329e-05 -9.06580780885147e-06 -1.71078466266625e-06 1.27558072280758e-05 9.61536554481388e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 839 0 0 0 0 0 2737 +1083 1130 0.999980362714759 0.00607434214902977 0.00154160705603193 0.0102266614639163 -0.00607408367168447 0.999981537740721 -0.000172294086347954 -0.00249080089369157 -0.00154262516771349 0.000162926852712638 0.999998796880493 -0.00459394948023146 2.56797568825065e-05 -1.71778164491374e-05 -1.19171061340198e-05 1.99980212434402e-06 9.81149677081677e-06 1.96269144129296e-05 -1.71778164491374e-05 0.000117655221275407 1.88817027357979e-05 6.45778173989639e-06 -2.07272718300391e-05 -5.25902533171581e-05 -1.19171061340198e-05 1.88817027357979e-05 2.24845479178986e-05 -9.31841982917926e-06 -1.51867173294803e-05 -8.3567417180227e-06 1.99980212434402e-06 6.45778173989639e-06 -9.31841982917926e-06 3.54813337119927e-05 -8.0709717698457e-06 -5.11536716094635e-06 9.81149677081677e-06 -2.07272718300391e-05 -1.51867173294803e-05 -8.0709717698457e-06 0.000103586918266345 1.84409566850178e-05 1.96269144129296e-05 -5.25902533171581e-05 -8.3567417180227e-06 -5.11536716094635e-06 1.84409566850178e-05 7.67262873443038e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 839 0 0 0 0 0 2687 +1083 1126 0.999977502129481 0.00638398997198749 0.00205910342642412 0.0125224890355431 -0.00638363618635191 0.999979608483679 -0.000178341998520444 -0.00401149085124758 -0.00206019997171314 0.000165193419060891 0.999997864141325 -0.00416609441230827 2.87020389134017e-05 -3.32596587976485e-05 -1.2584933312938e-05 1.17207793896722e-06 5.11266657870196e-06 2.7472748610886e-05 -3.32596587976485e-05 0.000144356381232433 2.63283799073625e-05 -2.10751030552627e-06 -2.28315018963346e-05 -8.19242912223187e-05 -1.2584933312938e-05 2.63283799073625e-05 2.25809936497803e-05 -1.21588693532481e-05 -1.09103499097548e-05 -1.34856939697393e-05 1.17207793896722e-06 -2.10751030552627e-06 -1.21588693532481e-05 3.69343232180476e-05 -5.26974240179433e-06 -4.7538815491858e-07 5.11266657870196e-06 -2.28315018963346e-05 -1.09103499097548e-05 -5.26974240179433e-06 7.88171166792606e-05 7.29645985942328e-06 2.7472748610886e-05 -8.19242912223187e-05 -1.34856939697393e-05 -4.7538815491858e-07 7.29645985942328e-06 9.28881516868792e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 842 0 0 0 0 0 2784 +1083 1125 0.999943941092467 0.00617715583104114 0.00859984990011253 0.0112828604654543 -0.00620438927458684 0.99997581116829 0.00314366538461825 0.00152351499903743 -0.00858022296882912 -0.00319684597065445 0.999958079096142 -0.0113051829720487 2.24198198106257e-05 -1.31941042180781e-05 -1.29029007179921e-05 4.68377634873943e-06 2.89320603251211e-06 9.24215187468137e-06 -1.31941042180781e-05 9.32453550799737e-05 1.66911934151355e-05 -1.23389316719619e-05 6.8703406726446e-06 -3.79473930864681e-05 -1.29029007179921e-05 1.66911934151355e-05 2.41551706646553e-05 -1.26748107742671e-05 -8.65616140821735e-06 -9.38259787113665e-06 4.68377634873943e-06 -1.23389316719619e-05 -1.26748107742671e-05 3.77041694580904e-05 -2.20319659330556e-05 2.61232488315395e-06 2.89320603251211e-06 6.8703406726446e-06 -8.65616140821735e-06 -2.20319659330556e-05 0.000128393986769553 1.25729042404846e-05 9.24215187468137e-06 -3.79473930864681e-05 -9.38259787113665e-06 2.61232488315395e-06 1.25729042404846e-05 5.71731751238362e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 917 0 0 0 0 0 2553 +1083 1131 0.999978808080716 0.00650806157182712 0.000168890636094642 0.00272352489303736 -0.00650843463799597 0.999976148679427 0.00231135259610696 0.0170990846695741 -0.000153844182820272 -0.0023124028277753 0.999997314558959 -0.0102130864782434 2.99543673368917e-05 -2.09352780841181e-05 -1.559108851256e-05 7.32266139154948e-06 4.4469028852326e-06 1.64964167130019e-05 -2.09352780841181e-05 0.000107412980937688 2.00718434176656e-05 -5.83170473015514e-06 -1.34025638650152e-05 -5.17921364334072e-05 -1.559108851256e-05 2.00718434176656e-05 2.32589479889776e-05 -1.26337718347611e-05 -1.06942981958632e-05 -1.00346441076497e-05 7.32266139154948e-06 -5.83170473015514e-06 -1.26337718347611e-05 4.56524230609732e-05 -4.56298691414143e-05 -1.4657853623931e-06 4.4469028852326e-06 -1.34025638650152e-05 -1.06942981958632e-05 -4.56298691414143e-05 0.000191562027546075 1.50951337409e-05 1.64964167130019e-05 -5.17921364334072e-05 -1.00346441076497e-05 -1.4657853623931e-06 1.50951337409e-05 6.26527672538109e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 915 0 0 0 0 0 2590 +1083 1132 0.999976706475097 0.00655434818052932 -0.00190447555674204 0.00689193156972718 -0.0065527410419674 0.999978170244837 0.000848892587151165 0.00328132663720503 0.00190999792009098 -0.000836393278306459 0.999997826174752 -0.00867363273822145 2.58512500839167e-05 -2.0645772594878e-05 -1.33317880963993e-05 3.58493483044139e-06 4.34745059486127e-06 1.57673734241468e-05 -2.0645772594878e-05 0.000110723168986954 2.421256331242e-05 -9.4866578810793e-06 -1.82218197669209e-05 -5.40698993008831e-05 -1.33317880963993e-05 2.421256331242e-05 2.24726421816164e-05 -9.35631597305532e-06 -1.4653317500617e-05 -1.10730645607446e-05 3.58493483044139e-06 -9.4866578810793e-06 -9.35631597305532e-06 3.05931688153365e-05 -1.55755806278375e-05 2.36642659689417e-06 4.34745059486127e-06 -1.82218197669209e-05 -1.4653317500617e-05 -1.55755806278375e-05 0.00012202174075691 8.92380507544826e-06 1.57673734241468e-05 -5.40698993008831e-05 -1.10730645607446e-05 2.36642659689417e-06 8.92380507544826e-06 6.89569915668637e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 903 0 0 0 0 0 2447 +1083 1129 0.999970457804994 0.00685978913426086 -0.00346796919007088 0.0100226885000317 -0.00686464983785073 0.999975469653418 -0.00139164436191619 -0.00168589066418179 0.00345833773271209 0.00141540964382537 0.999993018233461 -0.000907361309014593 3.83418728472758e-05 -3.73379386990602e-05 -1.81768496177456e-05 7.83258336461443e-06 9.04837295119425e-06 4.20231934395777e-05 -3.73379386990602e-05 0.00015690035320243 2.52061748506869e-05 -8.4212132886899e-06 -1.07964840663089e-05 -0.000101120034294607 -1.81768496177456e-05 2.52061748506869e-05 2.56220062693873e-05 -1.25205492991949e-05 -1.294818536797e-05 -1.74228770212465e-05 7.83258336461443e-06 -8.4212132886899e-06 -1.25205492991949e-05 3.7857438265269e-05 -7.02179336494378e-06 8.44763237476165e-06 9.04837295119425e-06 -1.07964840663089e-05 -1.294818536797e-05 -7.02179336494378e-06 0.000120027973148481 7.72088715998282e-06 4.20231934395777e-05 -0.000101120034294607 -1.74228770212465e-05 8.44763237476165e-06 7.72088715998282e-06 0.000122572153071049 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 904 0 0 0 0 0 2595 +1083 1137 0.99994125684008 0.00531550873447724 0.00944606986924807 0.00919474589831021 -0.00534601974086936 0.99998056513988 0.00320771187252244 0.00842135077829464 -0.00942883566572539 -0.00325802231738557 0.999950239936252 -0.00798730545461116 3.22035205464314e-05 -2.20628094192923e-05 -1.53056590322091e-05 5.20142444502338e-06 6.92601655358835e-06 1.3644193274462e-05 -2.20628094192923e-05 0.00014000924373701 3.08844285140859e-05 -1.39775309998257e-05 -2.4351303773646e-05 -7.86574321736931e-05 -1.53056590322091e-05 3.08844285140859e-05 2.72024897635147e-05 -1.27100880844772e-05 -1.64725024873335e-05 -1.81304437036796e-05 5.20142444502338e-06 -1.39775309998257e-05 -1.27100880844772e-05 3.10366728786773e-05 7.20106708625428e-06 7.98344202177609e-06 6.92601655358835e-06 -2.4351303773646e-05 -1.64725024873335e-05 7.20106708625428e-06 7.3731048078086e-05 1.11306411817401e-05 1.3644193274462e-05 -7.86574321736931e-05 -1.81304437036796e-05 7.98344202177609e-06 1.11306411817401e-05 7.4762822963868e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 910 0 0 0 0 0 2629 +1083 1138 0.999985555744004 0.00536637603890618 0.000300518825773933 -0.00147797208237381 -0.00536624971511889 0.999985513548027 -0.000419592758733151 0.0265745086206258 -0.000302766164848961 0.000417974038964732 0.999999866815167 0.00126465233226956 3.10339432804153e-05 -3.85008180164488e-06 -1.0487736989073e-05 5.04415540798155e-06 8.74620895666003e-06 1.80359058383672e-05 -3.85008180164488e-06 0.000103239763532473 1.65929934518133e-05 -1.0063861304207e-05 1.41306901606018e-05 -5.51676381537351e-05 -1.0487736989073e-05 1.65929934518133e-05 2.32852992797418e-05 -1.44385671869084e-05 -7.37784477259714e-06 -7.52431344677408e-06 5.04415540798155e-06 -1.0063861304207e-05 -1.44385671869084e-05 3.37689749439965e-05 -5.79687453276704e-07 3.72767973739573e-06 8.74620895666003e-06 1.41306901606018e-05 -7.37784477259714e-06 -5.79687453276704e-07 7.58849132841824e-05 4.13818494907528e-06 1.80359058383672e-05 -5.51676381537351e-05 -7.52431344677408e-06 3.72767973739573e-06 4.13818494907528e-06 7.82718361840707e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 911 0 0 0 0 0 2569 +1084 1088 0.999992217603914 0.00347082612402916 0.00187565925052664 0.000195855459745356 -0.00347415327125425 0.999992392418352 0.0017735175408138 0.00530094594106208 -0.00186948941028366 -0.00178002006631881 0.999996668263404 -0.00601185051267867 2.48074575850647e-05 -1.88981284821308e-05 -1.179732746942e-05 5.39595295127315e-06 -3.22671669752866e-06 1.50999760221294e-05 -1.88981284821308e-05 0.000103796637253232 2.36088231131867e-05 -1.6627497506638e-05 1.06505853549448e-05 -5.04922993708326e-05 -1.179732746942e-05 2.36088231131867e-05 2.48664259892549e-05 -1.45162936710667e-05 -9.24944147802949e-06 -1.06293911237574e-05 5.39595295127315e-06 -1.6627497506638e-05 -1.45162936710667e-05 2.65634324101346e-05 6.77497271989974e-06 9.00746664337267e-06 -3.22671669752866e-06 1.06505853549448e-05 -9.24944147802949e-06 6.77497271989974e-06 5.32307581709734e-05 -8.43586352589478e-06 1.50999760221294e-05 -5.04922993708326e-05 -1.06293911237574e-05 9.00746664337267e-06 -8.43586352589478e-06 5.88468585029969e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 820 0 0 0 0 0 2695 +1083 1135 0.999949211398824 0.00536787037368552 0.00852998185936674 0.0111967662637255 -0.00538646682470767 0.99998316295747 0.00215865159764746 -0.00283832335946717 -0.00851825087774128 -0.00220448842705323 0.999961289067111 -0.0142643913447153 4.04432522738862e-05 -2.36257414243485e-05 -1.57348500735822e-05 9.02133470520735e-06 -4.55179801419515e-06 2.45452653593372e-05 -2.36257414243485e-05 0.00014900422499775 2.96606170000588e-05 -1.17975874356153e-05 7.76772003568801e-06 -6.59642140537358e-05 -1.57348500735822e-05 2.96606170000588e-05 2.55363456509667e-05 -1.12206871563269e-05 -7.73173153572165e-06 -1.1024585374275e-05 9.02133470520735e-06 -1.17975874356153e-05 -1.12206871563269e-05 3.60083192335573e-05 -1.48194888048432e-05 2.85811131993217e-06 -4.55179801419515e-06 7.76772003568801e-06 -7.73173153572165e-06 -1.48194888048432e-05 0.000132156959975439 -1.90937550400346e-05 2.45452653593372e-05 -6.59642140537358e-05 -1.1024585374275e-05 2.85811131993217e-06 -1.90937550400346e-05 8.84395552879023e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 900 0 0 0 0 0 2640 +1084 1120 0.999979411749677 0.00634758665264155 -0.000940329972354119 0.00794371166172982 -0.00634610566967056 0.999978631326295 0.00156966035167138 -0.00114376219286757 0.000950273433847214 -0.00156366060174222 0.999998325971561 -0.00741555245677585 2.81513247245989e-05 -2.02149535191771e-05 -1.76076563342618e-05 7.35850113196227e-06 8.84809641899665e-06 1.9276161562007e-05 -2.02149535191771e-05 0.000111244108222131 1.92456745436419e-05 -3.85792397408331e-06 -1.23233513673267e-05 -5.13144411134432e-05 -1.76076563342618e-05 1.92456745436419e-05 2.52777366550388e-05 -1.2089246295788e-05 -1.66790728922091e-05 -9.6830189875319e-06 7.35850113196227e-06 -3.85792397408331e-06 -1.2089246295788e-05 3.20673670969863e-05 -8.99337843697767e-06 2.33303833623231e-06 8.84809641899665e-06 -1.23233513673267e-05 -1.66790728922091e-05 -8.99337843697767e-06 0.000111112246822829 7.49996060541072e-07 1.9276161562007e-05 -5.13144411134432e-05 -9.6830189875319e-06 2.33303833623231e-06 7.49996060541072e-07 7.18052823507975e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 813 0 0 0 0 0 2644 +1084 1121 0.99998350633389 0.00570161852033729 -0.000691813867713722 0.00761009636520549 -0.00570152374270928 0.999983736535526 0.000138893698400154 -0.00961326898640817 0.000692594535306618 -0.000134947014341562 0.999999751051025 -0.00336712298216681 2.70419910921293e-05 -8.07302700926399e-06 -1.18769965343171e-05 9.05304171909425e-06 -5.21617820660178e-07 1.40728710131614e-05 -8.07302700926399e-06 7.54923927906953e-05 1.49513537719496e-05 -1.31341463842054e-05 1.18247397629476e-05 -3.38051141142411e-05 -1.18769965343171e-05 1.49513537719496e-05 2.21367945015667e-05 -1.37324569134934e-05 -7.18232374033568e-06 -5.77927964974322e-06 9.05304171909425e-06 -1.31341463842054e-05 -1.37324569134934e-05 3.81455502153228e-05 -2.41666293128238e-05 5.69867421464329e-06 -5.21617820660178e-07 1.18247397629476e-05 -7.18232374033568e-06 -2.41666293128238e-05 0.000130498243602835 -8.37517863779477e-06 1.40728710131614e-05 -3.38051141142411e-05 -5.77927964974322e-06 5.69867421464329e-06 -8.37517863779477e-06 7.12748269425867e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 929 0 0 0 0 0 2532 +1084 1087 0.999993774322581 0.00268187945617703 -0.00229321579036225 -0.00321389345593453 -0.00268412955585861 0.999995918804396 -0.000978684361453566 0.0130615325923371 0.00229058171781699 0.00098483355676131 0.999996891664299 0.00026384237361141 3.83059820796959e-05 6.03119485790028e-06 -1.06516839728167e-05 8.62230892008745e-06 -9.07034763078088e-06 1.75635684785864e-05 6.03119485790028e-06 0.000107925502127043 1.27636382391219e-05 -7.9527171582541e-06 1.33733131153046e-05 -5.10761595855814e-05 -1.06516839728167e-05 1.27636382391219e-05 1.97984834317134e-05 -8.84459494618573e-06 -4.19230400176748e-06 -7.77273020601534e-06 8.62230892008745e-06 -7.9527171582541e-06 -8.84459494618573e-06 2.69496006711421e-05 -6.40105962263756e-06 1.05044470832347e-05 -9.07034763078088e-06 1.33733131153046e-05 -4.19230400176748e-06 -6.40105962263756e-06 8.34846226602529e-05 -1.42213270878734e-05 1.75635684785864e-05 -5.10761595855814e-05 -7.77273020601534e-06 1.05044470832347e-05 -1.42213270878734e-05 7.17416079354673e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 891 0 0 0 0 0 2588 +1084 1119 0.999984267440588 0.00546859580747582 0.00124873183870875 0.00835322986424204 -0.00547036936509092 0.999984027332098 0.00142131618156323 -0.00178100209867591 -0.00124093928941819 -0.00142812484501765 0.999998210262952 -0.00463824134405309 2.1189088271155e-05 -8.20225049152264e-06 -8.30430472889935e-06 3.45838846477844e-06 2.02662479678163e-06 5.19745988565845e-06 -8.20225049152264e-06 8.71339247357442e-05 1.82850172306601e-05 -8.28357398901802e-06 -1.83809196154906e-05 -4.00230371387862e-05 -8.30430472889935e-06 1.82850172306601e-05 2.35994513773992e-05 -1.27304871868756e-05 -1.08773158533853e-05 -5.6486528153498e-06 3.45838846477844e-06 -8.28357398901802e-06 -1.27304871868756e-05 3.10729818321673e-05 -6.10406204136203e-06 2.08643121989427e-06 2.02662479678163e-06 -1.83809196154906e-05 -1.08773158533853e-05 -6.10406204136203e-06 7.98929326625418e-05 -5.56904782861503e-06 5.19745988565845e-06 -4.00230371387862e-05 -5.6486528153498e-06 2.08643121989427e-06 -5.56904782861503e-06 5.27456141958941e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 843 0 0 0 0 0 2640 +1084 1122 0.999952968006912 0.00586224767782426 -0.00772630741883999 0.00753253855798025 -0.00588140309599678 0.999979681343337 -0.0024588611390586 -0.00804053408215481 0.00771173597764973 0.00250418702229229 0.999967128547518 0.000374210301457294 3.22752026527386e-05 -1.83537880992255e-05 -1.13364116556974e-05 2.58769826969003e-06 5.11411018758284e-06 2.56945289531601e-05 -1.83537880992255e-05 0.00010902211465204 1.70536217909751e-05 -5.33216128898208e-06 -5.0684533412406e-06 -5.15633572083905e-05 -1.13364116556974e-05 1.70536217909751e-05 2.31804069741793e-05 -1.49418816201264e-05 -9.44977921085639e-06 -4.26449023576007e-06 2.58769826969003e-06 -5.33216128898208e-06 -1.49418816201264e-05 3.58384451764846e-05 -1.24125591855189e-05 -2.77964722657612e-06 5.11411018758284e-06 -5.0684533412406e-06 -9.44977921085639e-06 -1.24125591855189e-05 9.24110723702638e-05 7.55186034880973e-06 2.56945289531601e-05 -5.15633572083905e-05 -4.26449023576007e-06 -2.77964722657612e-06 7.55186034880973e-06 8.43706419004714e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 924 0 0 0 0 0 2573 +1084 1086 0.999997163720068 0.0023799224605518 9.23087311998391e-05 -0.00262562661204776 -0.00237987340745657 0.999997028746509 -0.00052792112801632 0.0107945862796746 -9.35648682771652e-05 0.00052769994758956 0.99999985638918 -0.00181153760945184 2.98333772509229e-05 -1.97308343670849e-05 -1.48327926751839e-05 8.75296984403189e-06 8.13863696792518e-07 2.18616242012865e-05 -1.97308343670849e-05 8.40187344402032e-05 1.58768213399948e-05 -8.43718271579865e-06 2.09133974958853e-06 -6.07770428008121e-05 -1.48327926751839e-05 1.58768213399948e-05 2.39636270932095e-05 -1.34512233093248e-05 -8.19416043832153e-06 -1.4736928971195e-05 8.75296984403189e-06 -8.43718271579865e-06 -1.34512233093248e-05 2.75746813645653e-05 -2.68979795121791e-07 8.17933179750996e-06 8.13863696792518e-07 2.09133974958853e-06 -8.19416043832153e-06 -2.68979795121791e-07 6.01823057558599e-05 -9.94172785744326e-07 2.18616242012865e-05 -6.07770428008121e-05 -1.4736928971195e-05 8.17933179750996e-06 -9.94172785744326e-07 7.24861780811208e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 950 0 0 0 0 0 2573 +1084 1125 0.999981276966781 0.0055385999201055 -0.00260185065118902 0.00559058191879602 -0.00554144198046271 0.999984055965485 -0.00108638648491548 -0.00215780380622821 0.00259579210709387 0.00110078414889062 0.999996025060897 -0.00165279447206253 3.56947868630297e-05 -2.34273108432192e-05 -1.4292913922238e-05 1.08303416291071e-05 -7.7168102868235e-06 3.79445781032789e-05 -2.34273108432192e-05 0.000123988913102744 1.89537931986534e-05 -1.64858312647919e-05 1.51311894916211e-05 -7.55588555942549e-05 -1.4292913922238e-05 1.89537931986534e-05 2.24592652839165e-05 -1.50721367488347e-05 -8.89281561480299e-06 -1.16483743533507e-05 1.08303416291071e-05 -1.64858312647919e-05 -1.50721367488347e-05 3.75490802897985e-05 -1.2688914212806e-05 1.3105201622674e-05 -7.7168102868235e-06 1.51311894916211e-05 -8.89281561480299e-06 -1.2688914212806e-05 0.000118519463728327 -1.82247000301058e-05 3.79445781032789e-05 -7.55588555942549e-05 -1.16483743533507e-05 1.3105201622674e-05 -1.82247000301058e-05 0.000111957496292202 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 916 0 0 0 0 0 2628 +1084 1126 0.999970359444517 0.00526692114989098 0.00561602831229342 0.00799453292259205 -0.00527810981317117 0.999984111804736 0.00197931677459031 -0.000178376149044226 -0.00560551417835656 -0.0020089001206878 0.999982271108394 -0.00924041205237494 2.30167813782979e-05 -1.78157390266913e-05 -1.23127149989218e-05 3.34536511742456e-06 2.80056192735656e-06 1.21613858286954e-05 -1.78157390266913e-05 0.000114729447463956 2.81892228271056e-05 -1.55986911824999e-05 -4.50787054605123e-06 -6.03230362728043e-05 -1.23127149989218e-05 2.81892228271056e-05 2.68534962924475e-05 -1.46258293057443e-05 -8.82797934205855e-06 -1.07187262704001e-05 3.34536511742456e-06 -1.55986911824999e-05 -1.46258293057443e-05 3.40910448895454e-05 -1.23570267749145e-05 6.0615331016266e-06 2.80056192735656e-06 -4.50787054605123e-06 -8.82797934205855e-06 -1.23570267749145e-05 0.000103802230139196 -6.57796632412887e-06 1.21613858286954e-05 -6.03230362728043e-05 -1.07187262704001e-05 6.0615331016266e-06 -6.57796632412887e-06 6.75772491543295e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 857 0 0 0 0 0 2704 +1084 1123 0.999963528231636 0.00450631785844652 0.00725501935878269 0.00584742401525808 -0.00453829853638252 0.999980031997766 0.00439766439622931 0.00281105708614924 -0.00723505721693574 -0.00443042944936949 0.999964011973412 -0.0129186823409515 2.55948318961949e-05 -1.69961830464831e-05 -1.33030825240434e-05 5.1001296986257e-06 6.23355346553343e-07 1.5957151529674e-05 -1.69961830464831e-05 0.00010608001519891 2.44548845208168e-05 -8.70190596158496e-06 -9.35337679452646e-06 -4.85499029642336e-05 -1.33030825240434e-05 2.44548845208168e-05 2.4770681366683e-05 -1.27196517582395e-05 -8.48432224307926e-06 -9.81058799539164e-06 5.1001296986257e-06 -8.70190596158496e-06 -1.27196517582395e-05 3.49762398880965e-05 -1.8044181658867e-05 2.20149557219542e-06 6.23355346553343e-07 -9.35337679452646e-06 -8.48432224307926e-06 -1.8044181658867e-05 0.000107438509774702 -1.47639813610118e-07 1.5957151529674e-05 -4.85499029642336e-05 -9.81058799539164e-06 2.20149557219542e-06 -1.47639813610118e-07 6.75776551847343e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 825 0 0 0 0 0 2718 +1084 1128 0.999985197047422 0.00538405993716303 0.000785865524249038 0.00661534106308757 -0.00538474248518781 0.999985124570883 0.000869013995414282 0.00181715913615952 -0.000781175010724592 -0.000873232814917387 0.999999313614791 -0.00687903500551365 2.00054929973823e-05 -9.3356144517625e-06 -1.00342804044207e-05 4.13368333950354e-06 2.21582916699797e-06 4.02901805427083e-06 -9.3356144517625e-06 7.80320992272851e-05 1.61274825830479e-05 -9.92968168333176e-06 -8.42944201383407e-06 -3.24073830267808e-05 -1.00342804044207e-05 1.61274825830479e-05 2.01930807138283e-05 -1.1207142248717e-05 -4.79273999342043e-06 -6.29361324901135e-06 4.13368333950354e-06 -9.92968168333176e-06 -1.1207142248717e-05 3.60804172206935e-05 -3.0311644299944e-05 -1.77157335492069e-06 2.21582916699797e-06 -8.42944201383407e-06 -4.79273999342043e-06 -3.0311644299944e-05 0.000129940630106153 5.10125991959222e-06 4.02901805427083e-06 -3.24073830267808e-05 -6.29361324901135e-06 -1.77157335492069e-06 5.10125991959222e-06 4.73409233513663e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 842 0 0 0 0 0 2717 +1084 1124 0.999981436865165 0.005963353032563 0.00125073805776063 0.00843529044887207 -0.00596309515585177 0.99998219858003 -0.000209807559030201 -0.00314260006694753 -0.00125196694939059 0.000202345394290722 0.999999195817226 -0.00400635334057783 4.562497667035e-05 -3.26822616326868e-05 -2.04062849083398e-05 1.65419176491759e-05 4.21677895961635e-07 4.68309492976416e-05 -3.26822616326868e-05 0.000150800962549785 2.34659973159783e-05 -1.28814637249151e-05 1.52152295958868e-06 -8.33144056840328e-05 -2.04062849083398e-05 2.34659973159783e-05 2.81923165338464e-05 -1.79216284866749e-05 -9.62386350349516e-06 -1.54957618480189e-05 1.65419176491759e-05 -1.28814637249151e-05 -1.79216284866749e-05 4.66142780998563e-05 -2.59882417058636e-05 1.63203144217497e-05 4.21677895961635e-07 1.52152295958868e-06 -9.62386350349516e-06 -2.59882417058636e-05 0.000148394151395904 -3.93484613040435e-06 4.68309492976416e-05 -8.33144056840328e-05 -1.54957618480189e-05 1.63203144217497e-05 -3.93484613040435e-06 0.000119643044363794 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 902 0 0 0 0 0 2679 +1084 1127 0.999983260816835 0.00578463240520092 0.00012694119342572 0.00739001369015825 -0.00578474390136036 0.999982866562918 0.000896280427107351 0.000485584989115153 -0.000121754365683977 -0.000896999746399616 0.999999590283581 -0.00518727258662949 2.12405888330771e-05 -2.47447506993512e-06 -1.07262064416874e-05 3.69936373424396e-06 6.63214601825162e-06 2.28619346929226e-06 -2.47447506993512e-06 7.77984137608552e-05 1.72699221550069e-05 -9.07678900439758e-07 -2.30825213959059e-05 -3.59697656463558e-05 -1.07262064416874e-05 1.72699221550069e-05 2.1661335322935e-05 -9.24324817346038e-06 -1.15511843115687e-05 -7.82667624836844e-06 3.69936373424396e-06 -9.07678900439758e-07 -9.24324817346038e-06 3.77646813987984e-05 -4.29439191443703e-05 -3.80407550062621e-06 6.63214601825162e-06 -2.30825213959059e-05 -1.15511843115687e-05 -4.29439191443703e-05 0.000167221120445121 1.67090369735788e-05 2.28619346929226e-06 -3.59697656463558e-05 -7.82667624836844e-06 -3.80407550062621e-06 1.67090369735788e-05 4.92513123431114e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 861 0 0 0 0 0 2641 +1084 1130 0.999980202232664 0.00605575940856807 -0.0017096551425571 0.00834641531155205 -0.00605457050587396 0.999981426107061 0.000699726287255701 -0.000523379694507068 0.00171386076165299 -0.000689361206636124 0.999998293729753 -0.00625262785148741 2.72461412099876e-05 -1.48565504779933e-05 -1.35545232546588e-05 3.22117187086104e-06 3.53630279512702e-06 8.88956846436993e-06 -1.48565504779933e-05 0.000106155716674087 1.98042935889624e-05 -9.03593395047714e-06 -1.11502104259821e-05 -4.9235042036137e-05 -1.35545232546588e-05 1.98042935889624e-05 2.72341588231226e-05 -9.02862603197475e-06 -1.71786070075592e-05 -7.79935092794034e-06 3.22117187086104e-06 -9.03593395047714e-06 -9.02862603197475e-06 3.60533260882298e-05 -2.09396782843621e-05 1.37538429529281e-06 3.53630279512702e-06 -1.11502104259821e-05 -1.71786070075592e-05 -2.09396782843621e-05 0.000130629307993752 -3.39613128623134e-06 8.88956846436993e-06 -4.9235042036137e-05 -7.79935092794034e-06 1.37538429529281e-06 -3.39613128623134e-06 5.95337975208214e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 831 0 0 0 0 0 2585 +1084 1129 0.999984939580943 0.00531826177672797 0.00135525015075943 0.00557217383544336 -0.00531763754778036 0.99998575371413 -0.0004637884153827 0.00250569248609722 -0.00135769739168038 0.000456574701446498 0.999998974098141 -0.00345893617996193 2.64598093447667e-05 -8.40508534120133e-06 -1.23095670085952e-05 7.73347216483956e-06 -1.49644759930678e-06 1.6768448191533e-05 -8.40508534120133e-06 0.000105643347363785 1.79201115266892e-05 -1.41829366499874e-05 3.5733139179378e-07 -4.06466774149572e-05 -1.23095670085952e-05 1.79201115266892e-05 2.06809468989587e-05 -1.12419603003611e-05 -6.61149900532208e-06 -7.33714448945196e-06 7.73347216483956e-06 -1.41829366499874e-05 -1.12419603003611e-05 4.32382637488147e-05 -4.31252515006063e-05 8.1034661980374e-06 -1.49644759930678e-06 3.5733139179378e-07 -6.61149900532208e-06 -4.31252515006063e-05 0.00018075106184224 -5.99520554154588e-06 1.6768448191533e-05 -4.06466774149572e-05 -7.33714448945196e-06 8.1034661980374e-06 -5.99520554154588e-06 6.25732050582049e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 926 0 0 0 0 0 2578 +1084 1132 0.99997542333451 0.00590434964650262 -0.00378039445276961 0.0057219875072393 -0.00590836428534065 0.999981992441352 -0.0010516769923383 -0.000550103688802569 0.00377411690841684 0.0010739870931939 0.999992301267007 -0.00560256313540805 3.80404236980788e-05 -2.05067602395953e-05 -1.28579028565901e-05 3.00685877993718e-06 1.47353367793208e-05 3.0317954817121e-05 -2.05067602395953e-05 0.000125965270499967 2.20304515518049e-05 -2.78264937733114e-06 -2.54103992641751e-05 -6.01201054826735e-05 -1.28579028565901e-05 2.20304515518049e-05 2.50753761515389e-05 -1.49810619146037e-05 -1.23718655733602e-05 -8.20607618378114e-06 3.00685877993718e-06 -2.78264937733114e-06 -1.49810619146037e-05 4.65725354043822e-05 -3.1589604048595e-05 -5.04006076717729e-06 1.47353367793208e-05 -2.54103992641751e-05 -1.23718655733602e-05 -3.1589604048595e-05 0.000149157204645503 1.43720381380083e-05 3.0317954817121e-05 -6.01201054826735e-05 -8.20607618378114e-06 -5.04006076717729e-06 1.43720381380083e-05 8.91365827370596e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 905 0 0 0 0 0 2533 +1084 1134 0.999981195302783 0.00540333981074251 0.00290051024937643 0.00662181254978054 -0.00541195950484554 0.999980938153532 0.0029722085894809 0.000171170077185625 -0.002884395107298 -0.00298785014201132 0.999991376471014 -0.0131661169101375 2.33916619497674e-05 -1.04638886159436e-05 -1.27809744760786e-05 5.67984611288884e-06 2.84466326767945e-06 9.01046763366864e-06 -1.04638886159436e-05 0.000106406467874464 1.83688338002964e-05 -8.12027642825264e-06 8.80582361657685e-06 -4.20088306085831e-05 -1.27809744760786e-05 1.83688338002964e-05 2.50296624402874e-05 -1.59294640764762e-05 -4.98909548888015e-06 -4.54045271215412e-06 5.67984611288884e-06 -8.12027642825264e-06 -1.59294640764762e-05 3.88651978407823e-05 -1.97667358984484e-05 -3.53293172110924e-09 2.84466326767945e-06 8.80582361657685e-06 -4.98909548888015e-06 -1.97667358984484e-05 0.000106610893033104 -1.27470746447045e-05 9.01046763366864e-06 -4.20088306085831e-05 -4.54045271215412e-06 -3.53293172110924e-09 -1.27470746447045e-05 6.19543904205503e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 814 0 0 0 0 0 2604 +1084 1131 0.999969810586381 0.00545046976504923 0.00553807684824034 0.00416746797228087 -0.00546178220791118 0.999983024686304 0.00202959955266787 0.0076012928819194 -0.0055269205666516 -0.00205978604984326 0.999982605063947 -0.00896115579763552 4.17847469706363e-05 -2.20488920033652e-05 -1.3356186856476e-05 5.6279608028947e-06 4.22348940080638e-06 2.90920970585735e-05 -2.20488920033652e-05 0.000126602554671081 2.00159879893921e-05 -9.10934440904858e-06 2.17706931011446e-06 -6.82271681612496e-05 -1.3356186856476e-05 2.00159879893921e-05 2.50461369887699e-05 -1.39649889280604e-05 -1.08737192848934e-05 -7.95468130681137e-06 5.6279608028947e-06 -9.10934440904858e-06 -1.39649889280604e-05 4.19400300551344e-05 -2.12285102752688e-05 -6.5369823898361e-07 4.22348940080638e-06 2.17706931011446e-06 -1.08737192848934e-05 -2.12285102752688e-05 0.000138691703977643 -2.81756360925077e-06 2.90920970585735e-05 -6.82271681612496e-05 -7.95468130681137e-06 -6.5369823898361e-07 -2.81756360925077e-06 9.4219460594338e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 912 0 0 0 0 0 2589 +1084 1133 0.999970635056334 0.00641860650445507 -0.00418694585263285 0.00759273939011254 -0.00641591646998348 0.999979202887971 0.000655596971007747 -0.00295119839707109 0.00419106679523331 -0.00062871462458479 0.999991019798197 -0.00825448587673513 2.17276529470592e-05 -1.15906091458284e-05 -1.27409262688232e-05 6.30295943246134e-06 -1.4768667918758e-06 1.07890494515173e-05 -1.15906091458284e-05 9.03267825213063e-05 1.22804410530842e-05 -8.0041790965741e-06 6.97344418442599e-06 -3.73986719072812e-05 -1.27409262688232e-05 1.22804410530842e-05 1.97874250593999e-05 -1.09031326348982e-05 -4.19193732765994e-06 -5.94124045701541e-06 6.30295943246134e-06 -8.0041790965741e-06 -1.09031326348982e-05 3.76487274759598e-05 -2.02939502892297e-05 -1.17876695590958e-06 -1.4768667918758e-06 6.97344418442599e-06 -4.19193732765994e-06 -2.02939502892297e-05 0.000106089684242571 -1.71545124901224e-06 1.07890494515173e-05 -3.73986719072812e-05 -5.94124045701541e-06 -1.17876695590958e-06 -1.71545124901224e-06 6.04585147932215e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 825 0 0 0 0 0 2562 +1084 1138 0.999974012041256 0.00604192611229624 -0.00393323924606302 0.000892900710921305 -0.00605276698194348 0.99997790002995 -0.00275017518590703 0.0192795754827757 0.00391653596632436 0.00277391069510841 0.99998848301642 0.00502588958584428 2.87448731278655e-05 -7.48230135212304e-06 -1.01327557258501e-05 4.91910851615997e-06 3.64805488130092e-06 7.80267397523471e-06 -7.48230135212304e-06 9.40982407428548e-05 1.8591300283637e-05 -7.94816773909449e-06 1.25123062456251e-05 -4.90362089408741e-05 -1.01327557258501e-05 1.8591300283637e-05 2.21759985963381e-05 -1.07935613039811e-05 -3.9473049577767e-06 -8.8356939349727e-06 4.91910851615997e-06 -7.94816773909449e-06 -1.07935613039811e-05 2.90095948156651e-05 1.81660353760533e-07 3.49668829699039e-06 3.64805488130092e-06 1.25123062456251e-05 -3.9473049577767e-06 1.81660353760533e-07 6.17885381340938e-05 -1.81295356080712e-05 7.80267397523471e-06 -4.90362089408741e-05 -8.8356939349727e-06 3.49668829699039e-06 -1.81295356080712e-05 6.30899833282215e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 938 0 0 0 0 0 2547 +1084 1136 0.999974296709555 0.0070946631615618 -0.00103521729836943 0.0084815850947564 -0.00709494061969061 0.999974795586344 -0.000264593370760801 0.000664297146794246 0.00103331400548409 0.00027193137510095 0.999999429157584 -0.00378946784788393 2.68328804286186e-05 -3.54148703361384e-05 -1.74235270322422e-05 6.60016800029458e-06 4.13440606933994e-06 2.11549699443916e-05 -3.54148703361384e-05 0.000144076366958842 3.10128518322638e-05 -1.42354699264289e-05 -4.28834524192422e-06 -7.09429928213468e-05 -1.74235270322422e-05 3.10128518322638e-05 2.68478787775107e-05 -1.56221320601969e-05 -1.14773225658782e-05 -1.15649927687158e-05 6.60016800029458e-06 -1.42354699264289e-05 -1.56221320601969e-05 3.37202667671226e-05 -1.15214633505229e-05 4.34608106302866e-06 4.13440606933994e-06 -4.28834524192422e-06 -1.14773225658782e-05 -1.15214633505229e-05 9.99476299414872e-05 5.00869452483369e-07 2.11549699443916e-05 -7.09429928213468e-05 -1.15649927687158e-05 4.34608106302866e-06 5.00869452483369e-07 7.23184622736175e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 840 0 0 0 0 0 2607 +1085 1087 0.999996203580182 0.00229288667614486 -0.00152823293813226 -0.00412095224890088 -0.00229211389698343 0.999997244462918 0.000507228207460731 0.0176770369497066 0.00152939174382838 -0.000503723397854192 0.999998703610976 0.00105604871426142 2.78402941317646e-05 -2.75834578763608e-07 -1.21010805370476e-05 5.61585940053423e-06 1.20947340727835e-06 4.91228719540569e-06 -2.75834578763608e-07 7.65956102926421e-05 7.14695414157784e-06 -3.74816023181689e-06 7.34437180925587e-06 -4.9427108376473e-05 -1.21010805370476e-05 7.14695414157784e-06 2.04179105149593e-05 -9.32879046459912e-06 -6.18236367186287e-06 -6.3731833552366e-06 5.61585940053423e-06 -3.74816023181689e-06 -9.32879046459912e-06 2.77352930185185e-05 -9.35191158752276e-06 4.60199387535151e-06 1.20947340727835e-06 7.34437180925587e-06 -6.18236367186287e-06 -9.35191158752276e-06 7.98597004209125e-05 -1.34605585018496e-05 4.91228719540569e-06 -4.9427108376473e-05 -6.3731833552366e-06 4.60199387535151e-06 -1.34605585018496e-05 5.92790143256772e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 986 0 0 0 0 0 2554 +1085 1088 0.999997008469307 0.00233359082933513 0.000733079994879269 -0.000675039030855814 -0.00233185737752214 0.999994504337894 -0.00235663641250965 0.00881904757076057 -0.00073857539123963 0.00235491992456511 0.999996954424632 0.00250639317394485 2.99013386406413e-05 -2.55798879471075e-05 -1.26227379115453e-05 5.48905804012673e-06 -2.30488330510851e-07 2.52306485846009e-05 -2.55798879471075e-05 0.000119052318142894 2.61997296136098e-05 -1.23608877017998e-05 8.80600856206944e-06 -5.83211499083752e-05 -1.26227379115453e-05 2.61997296136098e-05 2.56783826650819e-05 -1.32924118878006e-05 -9.7568647536269e-06 -1.00875899585825e-05 5.48905804012673e-06 -1.23608877017998e-05 -1.32924118878006e-05 2.7271525038323e-05 7.11989348332664e-06 5.76808221945456e-06 -2.30488330510851e-07 8.80600856206944e-06 -9.7568647536269e-06 7.11989348332664e-06 5.51023218911315e-05 -1.15706948390321e-05 2.52306485846009e-05 -5.83211499083752e-05 -1.00875899585825e-05 5.76808221945456e-06 -1.15706948390321e-05 7.13606826215722e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 838 0 0 0 0 0 2677 +1085 1120 0.999990369774192 0.00423131560499355 -0.00116461458247468 0.00857716221715372 -0.004232216992247 0.999990745666936 -0.000772605860852601 -0.00640824456200778 0.00116133466550791 0.000777527322109069 0.999999023376052 0.00195507796154469 2.83922125295709e-05 -4.59169285660629e-06 -1.19774133563255e-05 5.02234853468699e-06 2.74631737374553e-06 1.9181897263525e-05 -4.59169285660629e-06 6.93360650158112e-05 8.25640655718384e-06 -3.95183998094751e-06 -3.04004029583354e-06 -2.23805057588948e-05 -1.19774133563255e-05 8.25640655718384e-06 1.89776044495704e-05 -1.03308655068909e-05 -6.60577743944564e-06 -3.81715791651702e-06 5.02234853468699e-06 -3.95183998094751e-06 -1.03308655068909e-05 3.3351663452085e-05 -1.46361130673917e-05 4.46319318532076e-06 2.74631737374553e-06 -3.04004029583354e-06 -6.60577743944564e-06 -1.46361130673917e-05 9.21340378525049e-05 -5.96455830913495e-06 1.9181897263525e-05 -2.23805057588948e-05 -3.81715791651702e-06 4.46319318532076e-06 -5.96455830913495e-06 6.05063856033315e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 827 0 0 0 0 0 2665 +1085 1124 0.999971253706369 0.00577308991663233 -0.00491560715759316 0.0072087014297538 -0.00577120002995604 0.999983267058281 0.000398564500179679 0.00149818000179244 0.0049178258537222 -0.000370184090752372 0.99998783890236 -0.00162438557718586 2.41855442338798e-05 -1.71764593601161e-05 -1.36524166895696e-05 8.70724633145791e-06 -3.71904201254482e-06 1.07954876513352e-05 -1.71764593601161e-05 9.90644633317904e-05 2.00475973302373e-05 -2.02981296968254e-05 1.01777609903229e-05 -4.6783690504193e-05 -1.36524166895696e-05 2.00475973302373e-05 2.48630683940533e-05 -1.56809553626785e-05 -9.92337913714055e-06 -1.03331071609442e-05 8.70724633145791e-06 -2.02981296968254e-05 -1.56809553626785e-05 3.48836993573298e-05 -1.12636582015262e-05 1.03612648648668e-05 -3.71904201254482e-06 1.01777609903229e-05 -9.92337913714055e-06 -1.12636582015262e-05 0.000105534105059368 -9.76814120576829e-06 1.07954876513352e-05 -4.6783690504193e-05 -1.03331071609442e-05 1.03612648648668e-05 -9.76814120576829e-06 5.50260236507214e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 949 0 0 0 0 0 2690 +1085 1123 0.999970730877055 0.00499022266208254 -0.00579957472501351 0.00676932019336703 -0.0050059550928344 0.999983821446678 -0.00270134383347994 -0.0028470991470771 0.00578600058906867 0.00273029717814611 0.999979533627815 0.00468922401695298 2.39581379220055e-05 -1.03331501042774e-05 -1.13532950413702e-05 5.63600056099847e-06 -1.48434718268582e-06 1.67542966048329e-05 -1.03331501042774e-05 9.32881764184552e-05 1.98324440920023e-05 -1.02570752380353e-05 -2.18086751578036e-07 -3.73067601796454e-05 -1.13532950413702e-05 1.98324440920023e-05 2.16551956847328e-05 -1.06638582248506e-05 -9.4080912728214e-06 -5.26147123870091e-06 5.63600056099847e-06 -1.02570752380353e-05 -1.06638582248506e-05 3.96978804923632e-05 -4.01621470469925e-05 2.80635807676529e-06 -1.48434718268582e-06 -2.18086751578036e-07 -9.4080912728214e-06 -4.01621470469925e-05 0.000176034367182145 -9.1761006342124e-06 1.67542966048329e-05 -3.73067601796454e-05 -5.26147123870091e-06 2.80635807676529e-06 -9.1761006342124e-06 6.71505296528968e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 835 0 0 0 0 0 2747 +1085 1119 0.99998607555468 0.00523968101687148 -0.000628044258733412 0.00762893308371677 -0.00523946283420054 0.999986213178285 0.000348543488159044 -0.00461379434986652 0.000629861856697648 -0.000345248020332435 0.99999974203889 -0.001080952678775 4.5057672019791e-05 -2.7159327380337e-06 -3.64566261376177e-06 3.50355039913385e-06 -6.93528494382035e-06 4.26878092966851e-05 -2.7159327380337e-06 9.48604111357556e-05 1.37980941579914e-05 -7.62196201158059e-06 1.40410473222015e-05 -4.42155045159527e-05 -3.64566261376177e-06 1.37980941579914e-05 2.01875345438972e-05 -7.74228312630767e-06 -1.01318065909213e-05 6.35680124580361e-07 3.50355039913385e-06 -7.62196201158059e-06 -7.74228312630767e-06 3.58257483969377e-05 -2.83826002581166e-05 8.01570024621693e-06 -6.93528494382035e-06 1.40410473222015e-05 -1.01318065909213e-05 -2.83826002581166e-05 0.000169703621028919 -3.49407716295608e-05 4.26878092966851e-05 -4.42155045159527e-05 6.35680124580361e-07 8.01570024621693e-06 -3.49407716295608e-05 0.000121132288173328 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 834 0 0 0 0 0 2706 +1085 1122 0.999971122023408 0.00544961952932236 -0.00529686381090128 0.0087422210840124 -0.0054453798325398 0.999984842091864 0.000814509048319702 -0.00670157151812485 0.00530122228594276 -0.000785642091574879 0.999985639801282 -0.00240702172414599 2.38700757048281e-05 -1.0439079812292e-05 -1.10306873618726e-05 4.63667132369887e-06 -9.29835675086565e-07 6.02080009281579e-06 -1.0439079812292e-05 0.000109701932865254 1.77769682775322e-05 -1.52269509264624e-05 2.87546019116732e-05 -4.46741174633853e-05 -1.10306873618726e-05 1.77769682775322e-05 2.22106402819663e-05 -1.26508773272582e-05 -5.28407648726678e-06 -8.57907646442908e-06 4.63667132369887e-06 -1.52269509264624e-05 -1.26508773272582e-05 3.76304431661001e-05 -3.11883450448215e-05 7.90436400851679e-06 -9.29835675086565e-07 2.87546019116732e-05 -5.28407648726678e-06 -3.11883450448215e-05 0.000169198833470214 -1.74031567403227e-05 6.02080009281579e-06 -4.46741174633853e-05 -8.57907646442908e-06 7.90436400851679e-06 -1.74031567403227e-05 5.1674924478388e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 959 0 0 0 0 0 2525 +1085 1125 0.999986763616353 0.00503523128962208 -0.00105784590193846 0.00681268148012301 -0.0050353620716442 0.99998731516302 -0.000121003565611483 0.00146392958721344 0.00105722320239592 0.000126328601094132 0.999999433159932 -0.00494598810379196 2.7927668584836e-05 -3.39388603833444e-05 -1.74013063011076e-05 3.82975450668876e-06 9.94862806003098e-06 1.87441139724918e-05 -3.39388603833444e-05 0.000134875837703052 2.98811577818795e-05 -5.04321951747925e-06 -2.24031376391542e-05 -6.17346704780907e-05 -1.74013063011076e-05 2.98811577818795e-05 2.4948792303938e-05 -1.08668228420822e-05 -9.65014325095424e-06 -1.50653322182619e-05 3.82975450668876e-06 -5.04321951747925e-06 -1.08668228420822e-05 3.58112896551533e-05 -1.63672472413678e-05 -1.3018139378629e-06 9.94862806003098e-06 -2.24031376391542e-05 -9.65014325095424e-06 -1.63672472413678e-05 9.29609559678664e-05 1.81070672522804e-05 1.87441139724918e-05 -6.17346704780907e-05 -1.50653322182619e-05 -1.3018139378629e-06 1.81070672522804e-05 5.94523104759403e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 950 0 0 0 0 0 2536 +1085 1126 0.999988751869208 0.00469899436666059 -0.000644660380611687 0.00347560345584405 -0.0046981287312479 0.999988068888994 0.00133778402033713 0.00589867385334321 0.000650938928672498 -0.00133474027531145 0.999998897372846 -0.00750248963276799 4.43091015551376e-05 -1.66724442741611e-05 -9.93051521032159e-06 3.63773633916087e-06 -6.07669832239623e-07 5.2679462279575e-05 -1.66724442741611e-05 0.000118891001787073 1.88916964007421e-05 1.25443676406977e-06 -1.39923730793514e-05 -5.18968904566371e-05 -9.93051521032159e-06 1.88916964007421e-05 2.16534484186945e-05 -1.06885903127759e-05 -1.07437399441897e-05 -3.5601882890768e-06 3.63773633916087e-06 1.25443676406977e-06 -1.06885903127759e-05 3.3766255780474e-05 -9.70531585871723e-06 6.23955425748848e-07 -6.07669832239623e-07 -1.39923730793514e-05 -1.07437399441897e-05 -9.70531585871723e-06 0.000106722921289416 -1.07333602169331e-05 5.2679462279575e-05 -5.18968904566371e-05 -3.5601882890768e-06 6.23955425748848e-07 -1.07333602169331e-05 0.000138373222904422 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 861 0 0 0 0 0 2735 +1085 1089 0.999964794936261 0.00382443134306472 -0.00746877586920733 0.000214282838790249 -0.00384408725393319 0.999989181426097 -0.00261916474230355 0.00585839174710944 0.00745867825197051 0.00264778316056315 0.999968678191006 0.00561897467615133 2.41631315669879e-05 -1.59655860063126e-05 -1.4245569589961e-05 7.59026191173043e-06 1.68499738782923e-06 1.34098554262456e-05 -1.59655860063126e-05 0.000104491611509784 1.74893728224063e-05 -8.94170629362152e-06 8.08000634098768e-06 -4.88196151517154e-05 -1.4245569589961e-05 1.74893728224063e-05 2.09499812428766e-05 -1.31621686536998e-05 -8.09098802501697e-06 -1.12918318164054e-05 7.59026191173043e-06 -8.94170629362152e-06 -1.31621686536998e-05 2.96158752538848e-05 -2.49262144147835e-06 1.03155289588851e-05 1.68499738782923e-06 8.08000634098768e-06 -8.09098802501697e-06 -2.49262144147835e-06 6.77027088472046e-05 -4.89928236729788e-06 1.34098554262456e-05 -4.88196151517154e-05 -1.12918318164054e-05 1.03155289588851e-05 -4.89928236729788e-06 5.0367498036901e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 836 0 0 0 0 0 2555 +1085 1121 0.999981154136352 0.00612295961441161 -0.000448037598095223 0.00857328739555312 -0.00612289178150269 0.99998124327648 0.000152615388185254 -0.00587812013328539 0.000448963652236265 -0.000149869226289276 0.999999887985421 -0.0037875277829996 2.18356917075654e-05 -2.5973699800747e-05 -1.3574389569358e-05 4.88025259868057e-06 -2.66256726190412e-06 1.43991230222325e-05 -2.5973699800747e-05 0.000127475558417902 2.58913747915153e-05 -1.13065460903971e-05 3.31907048470912e-06 -5.20768699461407e-05 -1.3574389569358e-05 2.58913747915153e-05 2.31842595506538e-05 -1.35095213404597e-05 -8.30784035484927e-06 -9.2290774456541e-06 4.88025259868057e-06 -1.13065460903971e-05 -1.35095213404597e-05 3.85732104262716e-05 -2.86896594486538e-05 1.54408374581667e-06 -2.66256726190412e-06 3.31907048470912e-06 -8.30784035484927e-06 -2.86896594486538e-05 0.000139631414490982 -9.362190197717e-07 1.43991230222325e-05 -5.20768699461407e-05 -9.2290774456541e-06 1.54408374581667e-06 -9.362190197717e-07 5.58883806659016e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 964 0 0 0 0 0 2676 +1085 1127 0.999981184735421 0.00541957526448673 -0.00287373956657973 0.0051736143262482 -0.00541245172515076 0.999982275219047 0.002480849463774 0.00277915801844018 0.00288713378056418 -0.00246524880926019 0.999992793477454 -0.00617882333493216 5.51639005643493e-05 -4.26819175268074e-06 -1.3137509413486e-05 8.89083942463928e-06 4.73938966764607e-06 3.95960905209769e-05 -4.26819175268074e-06 0.000123813494929807 1.98722350711982e-05 -1.30646931647269e-05 2.69532542353248e-05 -7.12023290910817e-05 -1.3137509413486e-05 1.98722350711982e-05 2.32850252222621e-05 -1.3423033909008e-05 -8.04879494350777e-06 -1.22887165182547e-05 8.89083942463928e-06 -1.30646931647269e-05 -1.3423033909008e-05 3.63313219840324e-05 -2.26213040905077e-05 1.06444341663393e-05 4.73938966764607e-06 2.69532542353248e-05 -8.04879494350777e-06 -2.26213040905077e-05 0.000151140705985485 -1.65033141472427e-05 3.95960905209769e-05 -7.12023290910817e-05 -1.22887165182547e-05 1.06444341663393e-05 -1.65033141472427e-05 0.000121034347918862 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 856 0 0 0 0 0 2791 +1085 1130 0.999985582042257 0.0053422826731013 -0.000543804606597959 0.00768489563415804 -0.00534143032304453 0.999984522393923 0.00155695044950796 -0.001741342640157 0.000552113859213758 -0.00155402330704668 0.999998640089999 -0.00870721297628472 3.84979949416534e-05 4.70708592448765e-07 -1.008326141335e-05 6.38077935940447e-06 -8.2559976901704e-06 2.88102070815975e-05 4.70708592448765e-07 0.000112222927550451 1.91051436597242e-05 -9.84619583860117e-06 1.00996736658708e-05 -4.03549013840488e-05 -1.008326141335e-05 1.91051436597242e-05 2.45838290264321e-05 -1.13195223031661e-05 -1.03516436437582e-05 -6.59284937570475e-06 6.38077935940447e-06 -9.84619583860117e-06 -1.13195223031661e-05 3.6272199658186e-05 -2.35703562804834e-05 7.41936441677889e-06 -8.2559976901704e-06 1.00996736658708e-05 -1.03516436437582e-05 -2.35703562804834e-05 0.000165458475674156 -2.40875398095856e-05 2.88102070815975e-05 -4.03549013840488e-05 -6.59284937570475e-06 7.41936441677889e-06 -2.40875398095856e-05 9.65818588019802e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 841 0 0 0 0 0 2738 +1085 1131 0.999981720320653 0.00564446970726443 -0.0021677145271233 0.0048839626664608 -0.00564298957299267 0.999983841312267 0.000688318996636965 0.00681226743456536 0.00217156469542662 -0.000676074023912636 0.999997413611999 -0.00478629235929941 2.25635799647914e-05 -1.59155640836158e-05 -1.40365181994541e-05 8.08477528530001e-06 2.14407968014006e-06 7.0457895140356e-06 -1.59155640836158e-05 9.06766216750242e-05 2.08046769924463e-05 -1.54104143734188e-05 5.73976490981943e-06 -3.32420126208231e-05 -1.40365181994541e-05 2.08046769924463e-05 2.27815061941847e-05 -1.46426601111341e-05 -4.43644819530394e-06 -6.7656465945574e-06 8.08477528530001e-06 -1.54104143734188e-05 -1.46426601111341e-05 3.67642320088411e-05 -2.67602046382023e-05 5.46006159645886e-06 2.14407968014006e-06 5.73976490981943e-06 -4.43644819530394e-06 -2.67602046382023e-05 0.00011946468272247 -6.25911046595073e-06 7.0457895140356e-06 -3.32420126208231e-05 -6.7656465945574e-06 5.46006159645886e-06 -6.25911046595073e-06 4.77766127806613e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 963 0 0 0 0 0 2597 +1085 1132 0.999983664817695 0.00559376088291742 -0.00117470717939942 0.00643640066569113 -0.00559359126363165 0.999984344848735 0.000147628659371035 0.00116177828479895 0.00117551458860082 -0.000141055416013957 0.999999299134165 -0.00697127275290035 2.25069025953243e-05 -1.68621252610307e-05 -1.34751322520345e-05 8.62732165163103e-06 -6.80926005245569e-06 5.80680349364021e-06 -1.68621252610307e-05 9.73965396259034e-05 2.42343169474641e-05 -1.74030032941994e-05 1.40949819241071e-05 -3.36872967802758e-05 -1.34751322520345e-05 2.42343169474641e-05 2.43596664082248e-05 -1.33989071026378e-05 -8.86637699712313e-06 -7.76049899832499e-06 8.62732165163103e-06 -1.74030032941994e-05 -1.33989071026378e-05 3.57150530380324e-05 -3.12225764932749e-05 1.40646544228671e-06 -6.80926005245569e-06 1.40949819241071e-05 -8.86637699712313e-06 -3.12225764932749e-05 0.000156893895129647 -2.51965752003305e-06 5.80680349364021e-06 -3.36872967802758e-05 -7.76049899832499e-06 1.40646544228671e-06 -2.51965752003305e-06 4.17191187232743e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 942 0 0 0 0 0 2447 +1085 1113 0.999985218488504 0.00407062603395461 0.00360455381306333 0.0033848330033345 -0.00407245815287543 0.999991581963684 0.00050108518426103 0.00143393413667354 -0.00360248373940215 -0.000515757172028106 0.999993378030798 -0.000227657221042198 4.12297524639222e-05 -1.50336081298937e-05 -1.70077958356201e-05 9.9962004628471e-06 5.19881152589145e-06 3.84393302890272e-05 -1.50336081298937e-05 0.000124873031055914 2.17717726218932e-05 -8.76347814255403e-06 1.43410825753057e-05 -6.12370907396252e-05 -1.70077958356201e-05 2.17717726218932e-05 2.56957458950327e-05 -1.52604567098808e-05 -1.05570223763697e-05 -1.26737879727914e-05 9.9962004628471e-06 -8.76347814255403e-06 -1.52604567098808e-05 3.08248713281615e-05 6.50384194307755e-06 9.83787570316928e-06 5.19881152589145e-06 1.43410825753057e-05 -1.05570223763697e-05 6.50384194307755e-06 6.98438286835395e-05 -1.47034439903906e-05 3.84393302890272e-05 -6.12370907396252e-05 -1.26737879727914e-05 9.83787570316928e-06 -1.47034439903906e-05 0.000109239153929814 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 763 0 0 0 0 0 2724 +1085 1129 0.999979507223673 0.00608028884495557 -0.00200380145248363 0.0058583488579547 -0.00607616035492284 0.999979418092459 0.00206001621560749 0.0047644515829656 0.00201628570404359 -0.00204779858121124 0.999995870547939 -0.00707212402004522 2.27990464422326e-05 -7.59430201207835e-06 -1.06917610144691e-05 8.6485976692816e-06 -3.93305237583653e-06 1.07533588637199e-05 -7.59430201207835e-06 7.73176331194071e-05 1.33282964842839e-05 -1.42471925179574e-05 2.34355496932047e-05 -2.47692467318513e-05 -1.06917610144691e-05 1.33282964842839e-05 2.38738582317825e-05 -1.51364972850492e-05 -3.88914785159815e-06 -4.65570476351444e-06 8.6485976692816e-06 -1.42471925179574e-05 -1.51364972850492e-05 3.87190354525776e-05 -2.3382068789085e-05 8.36684076989086e-06 -3.93305237583653e-06 2.34355496932047e-05 -3.88914785159815e-06 -2.3382068789085e-05 0.000118425769204224 -1.40342240448091e-05 1.07533588637199e-05 -2.47692467318513e-05 -4.65570476351444e-06 8.36684076989086e-06 -1.40342240448091e-05 5.22453221300793e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 946 0 0 0 0 0 2475 +1085 1135 0.999983424104727 0.00559737771151405 -0.00134939932541111 0.00548077331117742 -0.00559165775932865 0.999975521016891 0.00420603500941389 0.00306838268282625 0.00137290906010336 -0.0041984199114097 0.999990244147892 -0.00710924354084599 2.43886579197001e-05 1.25440778743399e-06 -9.6046232172721e-06 4.0193756838976e-06 7.26841766756069e-06 4.38047979702199e-06 1.25440778743399e-06 7.59425122313139e-05 1.41408991095367e-05 -1.07892562655041e-05 2.92730014443324e-06 -2.65831717507705e-05 -9.6046232172721e-06 1.41408991095367e-05 2.30474161074045e-05 -1.4356542644147e-05 -4.24342908564876e-06 -2.80385017037728e-06 4.0193756838976e-06 -1.07892562655041e-05 -1.4356542644147e-05 3.92493606151871e-05 -1.80542654935624e-05 3.37268080085773e-06 7.26841766756069e-06 2.92730014443324e-06 -4.24342908564876e-06 -1.80542654935624e-05 9.68000079629754e-05 -4.71798804828764e-06 4.38047979702199e-06 -2.65831717507705e-05 -2.80385017037728e-06 3.37268080085773e-06 -4.71798804828764e-06 4.97956039942974e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 950 0 0 0 0 0 2672 +1085 1138 0.999985135863395 0.00543600956596029 -0.000421725345772625 -0.00153753873330602 -0.00543432185151639 0.999977609861135 0.00390485882273474 0.0300231745553811 0.000442942753197681 -0.00390250898911791 0.999992287082909 -0.00554745699962913 3.30646325100836e-05 -2.3288613865767e-05 -1.36124892673412e-05 2.85494679156543e-06 1.00496268923462e-05 1.74503347492091e-05 -2.3288613865767e-05 0.000142420072813536 2.62583746171353e-05 -6.56089920417906e-06 3.82331428182636e-06 -7.43898453109338e-05 -1.36124892673412e-05 2.62583746171353e-05 2.77762752383228e-05 -1.46049367608735e-05 -1.46093434764556e-05 -1.35687899468503e-05 2.85494679156543e-06 -6.56089920417906e-06 -1.46049367608735e-05 3.00777700256505e-05 1.0529937007789e-05 3.05582356889261e-06 1.00496268923462e-05 3.82331428182636e-06 -1.46093434764556e-05 1.0529937007789e-05 6.46235776437375e-05 -8.51336492142852e-06 1.74503347492091e-05 -7.43898453109338e-05 -1.35687899468503e-05 3.05582356889261e-06 -8.51336492142852e-06 7.55895259937846e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 953 0 0 0 0 0 2486 +1085 1128 0.999968022458133 0.00452710544638663 0.00659237267204861 0.00644076221876715 -0.00455140630196458 0.999982886146886 0.00367588275352956 0.00350574920666917 -0.00657561874231725 -0.00370576977435938 0.999971513848537 -0.0131122650994224 4.45910398888369e-05 -2.2085421465386e-06 -7.55968045851969e-06 7.6563947214647e-06 -9.84825925646378e-06 3.56206029294696e-05 -2.2085421465386e-06 0.000120141158510044 2.37611799277251e-05 6.69372719831663e-06 -3.75661652713462e-05 -3.63904384627221e-05 -7.55968045851969e-06 2.37611799277251e-05 2.30806448175844e-05 -6.7665895943415e-06 -1.35871099844858e-05 -5.58606245352099e-06 7.6563947214647e-06 6.69372719831663e-06 -6.7665895943415e-06 5.52674917572825e-05 -7.13463889445424e-05 4.70042809013661e-06 -9.84825925646378e-06 -3.75661652713462e-05 -1.35871099844858e-05 -7.13463889445424e-05 0.000270414095087101 -9.06992489173124e-06 3.56206029294696e-05 -3.63904384627221e-05 -5.58606245352099e-06 4.70042809013661e-06 -9.06992489173124e-06 9.45622634950946e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 843 0 0 0 0 0 2707 +1086 1089 0.9999711524261 0.00275615096567202 -0.00707799035546605 0.00227339681156642 -0.00276944012392303 0.999994419591562 -0.00186841835129981 -0.00103152382889451 0.00707280121434573 0.00188796652245051 0.999973205173715 0.00572277936443953 2.36394364935505e-05 -1.01292625000186e-05 -1.30818046652803e-05 7.23182796498822e-06 9.2187438760627e-07 1.13518528163727e-05 -1.01292625000186e-05 8.67685948548094e-05 1.5933878193149e-05 -1.05022254669348e-05 4.94887159922009e-06 -4.66317887476681e-05 -1.30818046652803e-05 1.5933878193149e-05 2.27406479909966e-05 -1.2727551249519e-05 -9.07184998026308e-06 -9.57463442307183e-06 7.23182796498822e-06 -1.05022254669348e-05 -1.2727551249519e-05 2.62182792967187e-05 6.30924629822822e-06 5.69680123316125e-06 9.2187438760627e-07 4.94887159922009e-06 -9.07184998026308e-06 6.30924629822822e-06 5.07873177425563e-05 -3.56685279772141e-06 1.13518528163727e-05 -4.66317887476681e-05 -9.57463442307183e-06 5.69680123316125e-06 -3.56685279772141e-06 5.00778950790286e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 794 0 0 0 0 0 2537 +1086 1090 0.999997755439231 0.000295642382648566 -0.00209802575787312 0.000480876529028812 -0.000293260918489674 0.999999312529224 0.00113531454340231 0.00149836960541743 0.00209835996263839 -0.00113469672615906 0.999997154670355 0.0013175994283538 2.78465181276668e-05 -9.28895499435156e-06 -1.17164423581661e-05 4.25934496877633e-06 6.0257809873555e-06 5.9854766008634e-07 -9.28895499435156e-06 0.000101310903937092 1.7300330694531e-05 -7.30589854444109e-06 4.14339137620595e-06 -6.28586693526397e-05 -1.17164423581661e-05 1.7300330694531e-05 2.32404450432761e-05 -1.11520752751131e-05 -1.05305740975337e-05 -8.32152438215996e-06 4.25934496877633e-06 -7.30589854444109e-06 -1.11520752751131e-05 2.386877443364e-05 8.1708823745428e-06 2.66288609945191e-06 6.0257809873555e-06 4.14339137620595e-06 -1.05305740975337e-05 8.1708823745428e-06 4.9525148311588e-05 -4.14702885215541e-06 5.9854766008634e-07 -6.28586693526397e-05 -8.32152438215996e-06 2.66288609945191e-06 -4.14702885215541e-06 5.90619006971549e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 896 0 0 0 0 0 2580 +1086 1088 0.999999337201567 0.00108656962072428 -0.000380739920368852 -0.00160886089536125 -0.00108675174864046 0.99999929501704 -0.000478472632220459 0.00850491908543531 0.000380219758127178 0.000478886084863786 0.999999813050509 0.00183603446673836 2.96952423736533e-05 -3.25109622834988e-05 -1.49305512449585e-05 6.74089871712023e-06 -4.37598945378439e-06 2.25298760110908e-05 -3.25109622834988e-05 0.000144007615548142 3.02063138169556e-05 -1.84212477776524e-05 1.93729413057958e-05 -7.10106194614315e-05 -1.49305512449585e-05 3.02063138169556e-05 2.66682544929286e-05 -1.46936893711823e-05 -4.79055077663995e-06 -1.33012656019536e-05 6.74089871712023e-06 -1.84212477776524e-05 -1.46936893711823e-05 2.84112054997597e-05 5.38390461762141e-06 6.56227472038366e-06 -4.37598945378439e-06 1.93729413057958e-05 -4.79055077663995e-06 5.38390461762141e-06 5.80235114392701e-05 -1.08109666795244e-05 2.25298760110908e-05 -7.10106194614315e-05 -1.33012656019536e-05 6.56227472038366e-06 -1.08109666795244e-05 6.75763948881711e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 814 0 0 0 0 0 2654 +1086 1124 0.999994037766242 0.00343850885284632 0.000317944708490398 0.00754676437055363 -0.00343901193185107 0.999992813742246 0.00159551270731683 -0.0023515819364764 -0.000312456239088833 -0.00159659661014327 0.999998676624306 -0.00445393903415344 2.09836962489773e-05 -1.51331118232635e-05 -1.31943969495866e-05 6.36270214255201e-06 -1.49746803611471e-06 1.1421255994423e-05 -1.51331118232635e-05 9.24878943681343e-05 1.86764432308486e-05 -1.11807669141642e-05 1.1529558630659e-07 -4.28967176768171e-05 -1.31943969495866e-05 1.86764432308486e-05 2.23881634724294e-05 -1.23424515563945e-05 -1.01902174889392e-05 -1.00151207344245e-05 6.36270214255201e-06 -1.11807669141642e-05 -1.23424515563945e-05 3.56076324578596e-05 -2.10247315865296e-05 6.93153691870792e-06 -1.49746803611471e-06 1.1529558630659e-07 -1.01902174889392e-05 -2.10247315865296e-05 0.000121270312607554 -2.78549149736803e-06 1.1421255994423e-05 -4.28967176768171e-05 -1.00151207344245e-05 6.93153691870792e-06 -2.78549149736803e-06 5.48153170932794e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 939 0 0 0 0 0 2688 +1086 1125 0.999993751308432 0.00327386181912152 0.00133385639344702 0.00684038320732991 -0.00327543986898143 0.999993936443485 0.00118261148676075 -0.000475023021603851 -0.00132997659894003 -0.00118697306339692 0.999998411127334 -0.00673271278965184 2.45549345213348e-05 -2.66135525541054e-05 -1.70197728773786e-05 7.66430554442997e-06 -2.12009666349335e-07 1.82796903232713e-05 -2.66135525541054e-05 0.000126734112564795 2.34597969939702e-05 -1.37479194383372e-05 1.03359935339052e-05 -6.39456234355574e-05 -1.70197728773786e-05 2.34597969939702e-05 2.54582988545541e-05 -1.24046207429514e-05 -8.34784517432155e-06 -1.376321876798e-05 7.66430554442997e-06 -1.37479194383372e-05 -1.24046207429514e-05 3.26434385545182e-05 -1.6358565420808e-05 6.19824733252826e-06 -2.12009666349335e-07 1.03359935339052e-05 -8.34784517432155e-06 -1.6358565420808e-05 0.000117552855264361 -3.28379684431721e-06 1.82796903232713e-05 -6.39456234355574e-05 -1.376321876798e-05 6.19824733252826e-06 -3.28379684431721e-06 6.72976103996914e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 921 0 0 0 0 0 2530 +1086 1128 0.999961054371045 0.00229997994670164 0.00852055358483546 0.0046914494162614 -0.00233339326370923 0.999989619323717 0.0039136326712349 0.00390115268550053 -0.00851146385906434 -0.00393336205468695 0.999956040856758 -0.0129969553428734 3.8453696115684e-05 -3.49065526730637e-05 -1.70686222082523e-05 4.54835719664588e-06 9.73992356241906e-06 4.14370308979454e-05 -3.49065526730637e-05 0.000145381062810484 2.87790022613013e-05 -8.02987225605479e-06 -1.70033892880431e-05 -8.1812022534672e-05 -1.70686222082523e-05 2.87790022613013e-05 2.67728196847597e-05 -1.31317060866328e-05 -1.40301602352588e-05 -1.37733463311689e-05 4.54835719664588e-06 -8.02987225605479e-06 -1.31317060866328e-05 3.75716101995758e-05 -1.32926921721048e-05 -2.68238527359795e-06 9.73992356241906e-06 -1.70033892880431e-05 -1.40301602352588e-05 -1.32926921721048e-05 0.000117055915232835 9.22947100202135e-06 4.14370308979454e-05 -8.1812022534672e-05 -1.37733463311689e-05 -2.68238527359795e-06 9.22947100202135e-06 0.000115647801187955 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 836 0 0 0 0 0 2695 +1086 1126 0.999995524009997 0.00291071013567365 -0.000692622897065825 0.00475912875801299 -0.00291003866540604 0.999995296829279 0.000968501052650072 -0.0038462132244894 0.000695438665372454 -0.000966481158238036 0.999999291139365 -0.00669270929375031 3.28863721100775e-05 -2.55343979645925e-05 -1.38251126995715e-05 3.76891761890783e-06 8.39732386289464e-06 3.59108085347025e-05 -2.55343979645925e-05 0.000125291176427648 2.65378177901129e-05 -5.69794253736731e-06 -1.9894638597936e-05 -6.98716422959188e-05 -1.38251126995715e-05 2.65378177901129e-05 2.57276315646603e-05 -1.60212817510126e-05 -1.14658638606379e-05 -1.47489119373243e-05 3.76891761890783e-06 -5.69794253736731e-06 -1.60212817510126e-05 4.36149154856138e-05 -1.81270854034313e-05 -7.29225926371512e-07 8.39732386289464e-06 -1.9894638597936e-05 -1.14658638606379e-05 -1.81270854034313e-05 0.000122872123725451 1.97484626903989e-05 3.59108085347025e-05 -6.98716422959188e-05 -1.47489119373243e-05 -7.29225926371512e-07 1.97484626903989e-05 0.000113196424872655 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 829 0 0 0 0 0 2701 +1086 1130 0.999988999662191 0.00292291621201054 0.00366839412123917 0.00565199871651408 -0.00292884229987957 0.999994413082247 0.00161111361306483 -0.00278273455689935 -0.00366366447612392 -0.00162184003814575 0.999991973566537 -0.00834582754403934 2.78774441052603e-05 -3.84479947781038e-06 -9.58729076853621e-06 3.6618425589836e-06 1.41015212033141e-06 1.96216484290617e-05 -3.84479947781038e-06 7.88598612124363e-05 1.63844492333886e-05 -1.53711029753259e-05 4.27664873890324e-06 -2.45302956013097e-05 -9.58729076853621e-06 1.63844492333886e-05 2.29207009113473e-05 -1.30142209360413e-05 -5.35043825717057e-06 -2.47976278561219e-06 3.6618425589836e-06 -1.53711029753259e-05 -1.30142209360413e-05 4.21014208058549e-05 -2.94729586564746e-05 2.13723553290568e-06 1.41015212033141e-06 4.27664873890324e-06 -5.35043825717057e-06 -2.94729586564746e-05 0.000135063221697288 4.16595779673494e-06 1.96216484290617e-05 -2.45302956013097e-05 -2.47976278561219e-06 2.13723553290568e-06 4.16595779673494e-06 7.70801914135583e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 837 0 0 0 0 0 2721 +1086 1127 0.999989610598385 0.00316310805157048 0.00328229230028885 0.00365186492376808 -0.00317108185920793 0.999992026954554 0.00242698726070341 0.00565036538945851 -0.00327458930747778 -0.00243737046332811 0.999991668110336 -0.0100756920032166 3.5104001412073e-05 -1.1624138852612e-05 -1.2669670618148e-05 8.55517817544522e-06 3.94866904754116e-07 1.94667150327537e-05 -1.1624138852612e-05 0.000120131620012053 2.14260931829227e-05 -1.09898745551947e-05 2.09355942201523e-05 -6.53359930529666e-05 -1.2669670618148e-05 2.14260931829227e-05 2.3611073231454e-05 -1.42206019231732e-05 -6.14010894845229e-06 -1.18925693326047e-05 8.55517817544522e-06 -1.09898745551947e-05 -1.42206019231732e-05 3.94304603969532e-05 -2.28252147429626e-05 4.44134253587602e-06 3.94866904754116e-07 2.09355942201523e-05 -6.14010894845229e-06 -2.28252147429626e-05 0.000132388994795696 -1.09056536196953e-05 1.94667150327537e-05 -6.53359930529666e-05 -1.18925693326047e-05 4.44134253587602e-06 -1.09056536196953e-05 9.29489114452998e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 832 0 0 0 0 0 2761 +1086 1132 0.999978236827758 0.00299047568282703 0.00588072495853456 0.00620654582267549 -0.00300762182154607 0.999991246009272 0.00290897160542762 0.000463976007159464 -0.00587197426987474 -0.00292659529368932 0.999978477247466 -0.0100954122919966 2.69988226147096e-05 -2.55352945077818e-05 -1.76763907152727e-05 9.48642962446619e-06 -4.44095746626182e-06 1.48835746278426e-05 -2.55352945077818e-05 0.000112786735128732 2.90042654833807e-05 -1.61119743256549e-05 1.14157570004868e-06 -5.26096554692668e-05 -1.76763907152727e-05 2.90042654833807e-05 2.89668076899246e-05 -1.75890368606302e-05 -5.93935475501252e-06 -1.12490992580896e-05 9.48642962446619e-06 -1.61119743256549e-05 -1.75890368606302e-05 4.02778415489775e-05 -3.21106340646053e-05 4.02342904949253e-06 -4.44095746626182e-06 1.14157570004868e-06 -5.93935475501252e-06 -3.21106340646053e-05 0.000154933626060922 -5.92569681206763e-06 1.48835746278426e-05 -5.26096554692668e-05 -1.12490992580896e-05 4.02342904949253e-06 -5.92569681206763e-06 6.23374797073801e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 918 0 0 0 0 0 2432 +1086 1129 0.999975275153354 0.00228893401780117 0.00664904978450183 0.000986619229533607 -0.00231853887666145 0.999987418849569 0.00444820413801768 0.0141895913902354 -0.00663878448603664 -0.00446351023727075 0.999968001296496 -0.0104049390309715 2.72794738080476e-05 -2.79819016537024e-05 -1.58369053803628e-05 5.52603592632342e-06 3.0963614339968e-06 2.1996862629144e-05 -2.79819016537024e-05 0.000143157135658324 2.50218125977735e-05 1.02692271987276e-06 -1.53641910328985e-05 -6.00278074232628e-05 -1.58369053803628e-05 2.50218125977735e-05 2.50287979369919e-05 -1.30296480868379e-05 -6.22776037159525e-06 -1.51617561435439e-05 5.52603592632342e-06 1.02692271987276e-06 -1.30296480868379e-05 4.03193209387321e-05 -3.16216492639565e-05 1.85018904126626e-06 3.0963614339968e-06 -1.53641910328985e-05 -6.22776037159525e-06 -3.16216492639565e-05 0.000131896632392591 8.92066217415825e-06 2.1996862629144e-05 -6.00278074232628e-05 -1.51617561435439e-05 1.85018904126626e-06 8.92066217415825e-06 6.56656103149851e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 923 0 0 0 0 0 2467 +1086 1113 0.999989376788225 0.00179753989318164 0.00424442705559153 0.00102062650691371 -0.00179927546264276 0.999998299240371 0.000405122419963549 0.00251812995732727 -0.00424369161312984 -0.00041275500971639 0.999990910316086 0.00221658756159161 3.86224927546894e-05 -3.96152126564415e-05 -1.95387240483222e-05 9.32780541434527e-06 1.33174081653661e-06 3.82452412025149e-05 -3.96152126564415e-05 0.000147052518215541 2.4463530778668e-05 -1.1154452962341e-05 1.99477468849019e-06 -9.69429601489328e-05 -1.95387240483222e-05 2.4463530778668e-05 2.70560536383436e-05 -1.62922102638456e-05 -1.02495284982492e-05 -2.18660265892636e-05 9.32780541434527e-06 -1.1154452962341e-05 -1.62922102638456e-05 3.47946072324905e-05 3.21916999940731e-06 1.33116712144545e-05 1.33174081653661e-06 1.99477468849019e-06 -1.02495284982492e-05 3.21916999940731e-06 8.36363454607017e-05 5.38102558380344e-07 3.82452412025149e-05 -9.69429601489328e-05 -2.18660265892636e-05 1.33116712144545e-05 5.38102558380344e-07 0.000104572837795101 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 748 0 0 0 0 0 2709 +1086 1131 0.99997380312364 0.00273318391285144 0.00670244523606025 0.00450678095417069 -0.00275566351906565 0.999990601901152 0.00334700282959523 0.00691527474702682 -0.00669323427152728 -0.00336538483240147 0.999971937006192 -0.0102293142938043 2.29177009016955e-05 -1.5141050848568e-05 -1.42458526550795e-05 7.15822956206427e-06 1.88063986852325e-06 1.17756946083616e-05 -1.5141050848568e-05 8.56048329381904e-05 1.97165308662539e-05 -1.02935233316958e-05 -1.23708974270452e-05 -3.33594897354941e-05 -1.42458526550795e-05 1.97165308662539e-05 2.26533160238715e-05 -1.20899482759313e-05 -8.6554612832867e-06 -6.32191456772795e-06 7.15822956206427e-06 -1.02935233316958e-05 -1.20899482759313e-05 4.02208851320927e-05 -4.01229706249631e-05 3.40360005430353e-06 1.88063986852325e-06 -1.23708974270452e-05 -8.6554612832867e-06 -4.01229706249631e-05 0.000169335210140889 -5.4998202327645e-06 1.17756946083616e-05 -3.33594897354941e-05 -6.32191456772795e-06 3.40360005430353e-06 -5.4998202327645e-06 4.9627919793105e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 935 0 0 0 0 0 2608 +1086 1138 0.999970766274101 0.00262995444442935 0.0071798284663999 -0.0038894379791478 -0.00265003235271554 0.999992601180558 0.00278835303914659 0.0307262776209278 -0.00717244210267751 -0.00280729830292104 0.999970337135318 -0.00555144541249024 3.39813622604522e-05 -3.08210274719676e-05 -1.53582737202428e-05 2.59339352468333e-06 1.46897369199067e-07 1.71341019577837e-05 -3.08210274719676e-05 0.000161894773656931 2.7106638970794e-05 -1.40903351077204e-05 4.37717407836856e-05 -7.99793768270096e-05 -1.53582737202428e-05 2.7106638970794e-05 2.77997891921363e-05 -1.49513535396197e-05 -5.15619815664552e-06 -1.54066917601717e-05 2.59339352468333e-06 -1.40903351077204e-05 -1.49513535396197e-05 3.88344740518925e-05 -2.15689537619367e-05 8.52596554120218e-06 1.46897369199067e-07 4.37717407836856e-05 -5.15619815664552e-06 -2.15689537619367e-05 0.000155272315055852 -1.08324238557609e-05 1.71341019577837e-05 -7.99793768270096e-05 -1.54066917601717e-05 8.52596554120218e-06 -1.08324238557609e-05 6.40567964348001e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 920 0 0 0 0 0 2459 +1087 1089 0.999990096648132 0.000251032079341908 0.00444337580624914 -0.00195692062857438 -0.000250368432002387 0.999999957420993 -0.000149912176360574 0.0122718756354891 -0.00444341324981996 0.000148798210694134 0.999990116920054 -0.001533265787876 2.70518128200533e-05 -1.7673471003145e-05 -1.42174988211964e-05 6.07679754373333e-06 5.17508284174625e-06 1.8056393937537e-05 -1.7673471003145e-05 0.000112625352031913 2.2695220882051e-05 -7.33531939160982e-06 -5.38085645792853e-06 -6.19925326738545e-05 -1.42174988211964e-05 2.2695220882051e-05 2.3859133284097e-05 -1.38473528867461e-05 -9.72087819543738e-06 -1.07694968682695e-05 6.07679754373333e-06 -7.33531939160982e-06 -1.38473528867461e-05 3.03848836673458e-05 -3.96605632255574e-06 2.85112888720069e-06 5.17508284174625e-06 -5.38085645792853e-06 -9.72087819543738e-06 -3.96605632255574e-06 7.51430593326834e-05 3.12610795162734e-06 1.8056393937537e-05 -6.19925326738545e-05 -1.07694968682695e-05 2.85112888720069e-06 3.12610795162734e-06 7.18034832284397e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 838 0 0 0 0 0 2598 +1087 1090 0.999994506250825 -0.000385639978769087 0.00329222568708011 -0.00256903240910783 0.000384389320293673 0.999999853729755 0.000380506661857205 0.011242916106248 -0.00329237194410645 -0.000379239075054935 0.999994508217273 -0.00257526116010513 2.33842773272487e-05 -1.59844901094068e-05 -1.06162685821109e-05 4.45429889379112e-06 -6.0148566728736e-06 7.42227588923138e-06 -1.59844901094068e-05 9.18710383584962e-05 1.52645591504995e-05 -4.09737954633338e-06 1.41937470215019e-05 -4.48977653205761e-05 -1.06162685821109e-05 1.52645591504995e-05 1.90660530965417e-05 -1.02436848900491e-05 -1.69594868500625e-06 -7.43084776342876e-06 4.45429889379112e-06 -4.09737954633338e-06 -1.02436848900491e-05 2.59416887645619e-05 -1.08322611353557e-05 2.52062305106894e-06 -6.0148566728736e-06 1.41937470215019e-05 -1.69594868500625e-06 -1.08322611353557e-05 7.75765911522839e-05 -5.71442222514369e-06 7.42227588923138e-06 -4.48977653205761e-05 -7.43084776342876e-06 2.52062305106894e-06 -5.71442222514369e-06 3.94485893415849e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 937 0 0 0 0 0 2472 +1087 1091 0.999971767993304 -0.00078706757150098 0.0074728669855129 0.00147500095159908 0.000769332235814315 0.999996881667039 0.0023758754404657 0.00450869537253623 -0.00747471365713858 -0.00237005924726845 0.999969255264835 -0.00448097596698649 2.99471662942968e-05 -3.19083428462353e-05 -1.77974491075243e-05 7.66693695536569e-06 4.79137819312732e-07 2.03294022383428e-05 -3.19083428462353e-05 0.000147949417696905 2.5068881697963e-05 -5.46366044923988e-06 1.97483342079742e-05 -7.91080991214874e-05 -1.77974491075243e-05 2.5068881697963e-05 2.32969753037291e-05 -1.13494802288163e-05 -8.30008908473013e-06 -1.45393337334588e-05 7.66693695536569e-06 -5.46366044923988e-06 -1.13494802288163e-05 2.36766457331611e-05 9.6493485461576e-06 4.04057526065341e-06 4.79137819312732e-07 1.97483342079742e-05 -8.30008908473013e-06 9.6493485461576e-06 5.444416540915e-05 -9.15994688437521e-06 2.03294022383428e-05 -7.91080991214874e-05 -1.45393337334588e-05 4.04057526065341e-06 -9.15994688437521e-06 6.30825554311168e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 894 0 0 0 0 0 2663 +1087 1129 0.999993704860523 0.00326519270343078 0.00138879657778422 0.00396400006039832 -0.00327095876250313 0.999985955735358 0.00417003127296575 0.00823277846119542 -0.00137516111747198 -0.0041745477183727 0.999990340994976 -0.00812137629705143 2.85209870977686e-05 -2.72396069586348e-06 -1.10227505083812e-05 6.40891425241389e-06 -3.60078159909186e-06 7.22840503326692e-06 -2.72396069586348e-06 0.000102472216490846 1.68362197962966e-05 -1.0928657809926e-05 1.160853012842e-05 -5.04889917771371e-05 -1.10227505083812e-05 1.68362197962966e-05 2.42143942704266e-05 -1.24284232256659e-05 -8.01901621848947e-06 -1.03377661531887e-05 6.40891425241389e-06 -1.0928657809926e-05 -1.24284232256659e-05 3.82077066700921e-05 -2.82773996879412e-05 4.64245571150831e-06 -3.60078159909186e-06 1.160853012842e-05 -8.01901621848947e-06 -2.82773996879412e-05 0.000168065651758712 -4.8390871093067e-06 7.22840503326692e-06 -5.04889917771371e-05 -1.03377661531887e-05 4.64245571150831e-06 -4.8390871093067e-06 6.14479728034971e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 930 0 0 0 0 0 2606 +1087 1131 0.999996021067368 0.00251904696180999 -0.00126974479190027 0.00566810449007633 -0.00251757765497451 0.999996161060124 0.00115744017766943 -0.000920096459973362 0.00127265556358939 -0.00115423889117733 0.99999852403911 -0.00425278180465034 2.44125191591337e-05 -1.30197622800913e-05 -1.22189319951639e-05 4.97744187829603e-06 -1.92081035500363e-06 1.76393581538481e-06 -1.30197622800913e-05 9.78219710095851e-05 1.98861247381989e-05 -7.24218710989491e-06 -5.66138699491789e-06 -4.10239208487218e-05 -1.22189319951639e-05 1.98861247381989e-05 2.32158830349704e-05 -1.13239919922077e-05 -7.95479843319752e-06 -6.75305387300259e-06 4.97744187829603e-06 -7.24218710989491e-06 -1.13239919922077e-05 4.17448241297773e-05 -4.73027971876375e-05 -3.81765045285286e-06 -1.92081035500363e-06 -5.66138699491789e-06 -7.95479843319752e-06 -4.73027971876375e-05 0.000179601381171366 8.87709262771627e-06 1.76393581538481e-06 -4.10239208487218e-05 -6.75305387300259e-06 -3.81765045285286e-06 8.87709262771627e-06 5.67995976105679e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 942 0 0 0 0 0 2496 +1087 1127 0.999973980929542 0.00300518000780475 -0.00655792322651311 0.00439743886326674 -0.00301042080318149 0.999995157071757 -0.00078942993354371 0.00024974529036912 0.00655551908790765 0.00080915150181741 0.99997818498372 -0.00291826163361622 5.89576373112796e-05 -4.24442530694961e-05 -1.33407635051644e-05 9.51913293022996e-06 -1.06426905507549e-05 6.77547866041937e-05 -4.24442530694961e-05 0.000172857083371154 2.43238164568827e-05 -1.19178912820586e-05 1.6283107223528e-05 -9.66634422228534e-05 -1.33407635051644e-05 2.43238164568827e-05 2.44222868664008e-05 -1.13403994875564e-05 -7.28304143572617e-06 -9.69556682919644e-06 9.51913293022996e-06 -1.19178912820586e-05 -1.13403994875564e-05 4.45853896191814e-05 -4.0816994814862e-05 1.13843358377225e-05 -1.06426905507549e-05 1.6283107223528e-05 -7.28304143572617e-06 -4.0816994814862e-05 0.00017328262363916 -2.74645993071669e-05 6.77547866041937e-05 -9.66634422228534e-05 -9.69556682919644e-06 1.13843358377225e-05 -2.74645993071669e-05 0.000170810434674211 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 822 0 0 0 0 0 2766 +1087 1138 0.999990381521732 0.00319401415136164 0.00300585056553003 -0.00241150316396167 -0.00320642236749396 0.999986321398298 0.00413229620205217 0.0314370545175871 -0.0029926108371504 -0.00414189448213761 0.999986944410014 -0.00688259351502797 2.7888003232188e-05 -1.95103057398182e-05 -1.30377914658776e-05 4.76678684085586e-06 1.92006671281653e-06 2.06751930578605e-05 -1.95103057398182e-05 0.000128727573835353 2.53572832556359e-05 -7.81603627380942e-06 1.03556727638941e-05 -5.85473145926584e-05 -1.30377914658776e-05 2.53572832556359e-05 2.78612473043177e-05 -1.47353477534042e-05 -7.89438739928844e-06 -1.25046381312126e-05 4.76678684085586e-06 -7.81603627380942e-06 -1.47353477534042e-05 3.55381558719343e-05 -6.98847118659183e-07 3.50679433662655e-06 1.92006671281653e-06 1.03556727638941e-05 -7.89438739928844e-06 -6.98847118659183e-07 7.33355525296663e-05 -5.07175273212423e-06 2.06751930578605e-05 -5.85473145926584e-05 -1.25046381312126e-05 3.50679433662655e-06 -5.07175273212423e-06 6.7155450939998e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 934 0 0 0 0 0 2505 +1088 1090 0.999987563949347 -0.00112347675611651 0.00485898617303157 -0.00289486830626048 0.00111749073980851 0.999998613627018 0.00123448713538627 0.00995270988849029 -0.00486036635426675 -0.0012290419111885 0.999987433068477 -0.00537796318119156 3.37948161041285e-05 -3.38492217951246e-05 -1.45458991770634e-05 7.79479270130225e-06 -1.06964761443706e-05 2.07458337403605e-05 -3.38492217951246e-05 0.000181964623222471 3.05851880587262e-05 -1.94802167312699e-05 4.76531616940962e-05 -0.000100804878568101 -1.45458991770634e-05 3.05851880587262e-05 2.82552830044409e-05 -1.89429293210155e-05 -1.56549246099666e-06 -1.41750498809318e-05 7.79479270130225e-06 -1.94802167312699e-05 -1.89429293210155e-05 3.55533850872861e-05 -2.82621848047477e-06 1.04179150631635e-05 -1.06964761443706e-05 4.76531616940962e-05 -1.56549246099666e-06 -2.82621848047477e-06 8.93016192183109e-05 -2.90648989582577e-05 2.07458337403605e-05 -0.000100804878568101 -1.41750498809318e-05 1.04179150631635e-05 -2.90648989582577e-05 7.98272209717748e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 922 0 0 0 0 0 2414 +1088 1092 0.999994357709817 -7.37386377238802e-05 -0.00335843879569051 -0.000934705952748837 7.26585468643936e-05 0.999999945606583 -0.000321725919371318 0.00508896960809908 0.00335846233664456 0.000321480084817694 0.999994308674449 0.000639331789837555 2.55377182782808e-05 -2.05273746198902e-05 -1.43967754620988e-05 7.42145558314205e-06 -3.51570631261923e-06 1.06736887759407e-05 -2.05273746198902e-05 0.000117903308283694 2.39883594645244e-05 -1.68644801289444e-05 2.02350176523817e-05 -5.78204610409386e-05 -1.43967754620988e-05 2.39883594645244e-05 2.78787320104463e-05 -1.81246776669266e-05 -9.16419031321534e-06 -1.09282415555114e-05 7.42145558314205e-06 -1.68644801289444e-05 -1.81246776669266e-05 3.0650556701574e-05 6.81979975250893e-06 1.07378871782269e-05 -3.51570631261923e-06 2.02350176523817e-05 -9.16419031321534e-06 6.81979975250893e-06 6.19930812597926e-05 -9.35249167025156e-06 1.06736887759407e-05 -5.78204610409386e-05 -1.09282415555114e-05 1.07378871782269e-05 -9.35249167025156e-06 4.88499724041536e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 801 0 0 0 0 0 2535 +1088 1091 0.999990922144445 -0.000252987274738875 -0.00425342522454719 -0.000735685493746889 0.000252533529650211 0.999999962365954 -0.000107214305309003 0.00201161934175001 0.0042534521883285 0.000106139199547968 0.99999094839851 0.00334026701669871 2.34715167622928e-05 -5.03581930446659e-06 -1.36884354109726e-05 8.42572647932331e-06 1.02804015434516e-05 1.29506667362826e-05 -5.03581930446659e-06 6.6072149493683e-05 3.82148326521066e-06 5.68724163316682e-07 4.38791491566005e-06 -4.00891913680459e-05 -1.36884354109726e-05 3.82148326521066e-06 1.93875952847053e-05 -1.24362275804075e-05 -1.08344985484009e-05 -9.34867097513482e-06 8.42572647932331e-06 5.68724163316682e-07 -1.24362275804075e-05 2.69543751104673e-05 1.03229412114285e-05 8.72134258177917e-06 1.02804015434516e-05 4.38791491566005e-06 -1.08344985484009e-05 1.03229412114285e-05 4.49143317147078e-05 5.89004967906593e-06 1.29506667362826e-05 -4.00891913680459e-05 -9.34867097513482e-06 8.72134258177917e-06 5.89004967906593e-06 5.46014071189225e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 903 0 0 0 0 0 2625 +1088 1123 0.999991670515394 0.00211616651602035 0.0034900915615191 0.00808892579473591 -0.00212537998981208 0.999994261045131 0.00263830185931998 -0.00374090467554222 -0.00348448844598729 -0.00264569765439272 0.999990429266296 -0.00576756558550816 2.67314323117671e-05 -2.59111672356082e-05 -1.51711176459259e-05 4.57820505181247e-06 3.39222710410252e-06 1.25843896448168e-05 -2.59111672356082e-05 0.000137236947271791 3.42178426131238e-05 -1.39022462344902e-05 -1.28729415707188e-05 -6.26409449402803e-05 -1.51711176459259e-05 3.42178426131238e-05 2.96634445283031e-05 -1.24199111716127e-05 -2.06409458890025e-05 -1.30470456838904e-05 4.57820505181247e-06 -1.39022462344902e-05 -1.24199111716127e-05 3.43915810837609e-05 -7.35502909304115e-06 7.35542291133697e-06 3.39222710410252e-06 -1.28729415707188e-05 -2.06409458890025e-05 -7.35502909304115e-06 0.000124354837644495 -4.46408611504387e-07 1.25843896448168e-05 -6.26409449402803e-05 -1.30470456838904e-05 7.35542291133697e-06 -4.46408611504387e-07 6.78496387267483e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 849 0 0 0 0 0 2583 +1088 1124 0.999996281150154 0.0027005252670713 0.000380590519623661 0.00793528352048866 -0.00270195326693475 0.999989118749687 0.00380287138469184 -0.00194480559843163 -0.000370316628061167 -0.00380388558018204 0.999992696633374 -0.00900794245670065 2.84440406526238e-05 -1.78969937526166e-05 -1.37320865172498e-05 8.32968850766548e-06 -1.03057692153684e-05 1.56110658377926e-05 -1.78969937526166e-05 0.000105437156579052 2.08704534127567e-05 -1.03750010307954e-05 4.22768910595628e-06 -4.41704191429009e-05 -1.37320865172498e-05 2.08704534127567e-05 2.22441792728288e-05 -1.0278510604072e-05 -6.78239663543915e-06 -1.12966881146132e-05 8.32968850766548e-06 -1.03750010307954e-05 -1.0278510604072e-05 4.2355248306839e-05 -4.33107456634389e-05 8.64824483220756e-06 -1.03057692153684e-05 4.22768910595628e-06 -6.78239663543915e-06 -4.33107456634389e-05 0.000184169056777411 -3.95777826756322e-06 1.56110658377926e-05 -4.41704191429009e-05 -1.12966881146132e-05 8.64824483220756e-06 -3.95777826756322e-06 5.89151936668604e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 931 0 0 0 0 0 2593 +1088 1121 0.999986729726349 0.00161032668961285 0.00489358959814804 0.00562263720405449 -0.00162830519760733 0.999991932013032 0.00367212895018269 -0.00676375109185668 -0.00488763678947476 -0.00368004847740426 0.999981283949764 -0.00906769721418875 2.74576377164549e-05 -2.65570576820584e-05 -1.27392424641827e-05 3.18846172236245e-06 -2.93438629006716e-06 2.28357074022693e-05 -2.65570576820584e-05 0.000124159681052666 2.20244297221304e-05 -9.79713844630025e-06 3.46268112719311e-06 -5.86733890616646e-05 -1.27392424641827e-05 2.20244297221304e-05 2.26245993385349e-05 -1.3594364529502e-05 -3.35300401608767e-06 -1.17589842749349e-05 3.18846172236245e-06 -9.79713844630025e-06 -1.3594364529502e-05 3.88023500316018e-05 -2.45575428526582e-05 6.02294724318357e-06 -2.93438629006716e-06 3.46268112719311e-06 -3.35300401608767e-06 -2.45575428526582e-05 0.000111006393747999 -4.74325081800935e-06 2.28357074022693e-05 -5.86733890616646e-05 -1.17589842749349e-05 6.02294724318357e-06 -4.74325081800935e-06 7.34498747489989e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 944 0 0 0 0 0 2574 +1088 1127 0.999997725086107 0.00203220899006856 -0.000648034900196043 0.00627021464235076 -0.00203339492332483 0.999996249641963 -0.00183466811565746 -0.00154842656169719 0.000644304040794716 0.00183598165282167 0.999998107020045 -0.000829911038598734 3.29858703093818e-05 -1.20849799933531e-05 -1.33359363971659e-05 8.37464909382129e-06 9.07749775468669e-07 1.68079783234885e-05 -1.20849799933531e-05 0.000111001336357335 1.71308543151075e-05 -1.18048458638155e-05 2.70914409933139e-06 -6.5509371873724e-05 -1.33359363971659e-05 1.71308543151075e-05 2.24539062091866e-05 -1.27687846939845e-05 -7.50853191403165e-06 -8.1332058848327e-06 8.37464909382129e-06 -1.18048458638155e-05 -1.27687846939845e-05 5.08399506446718e-05 -4.27100763695474e-05 6.353161036991e-06 9.07749775468669e-07 2.70914409933139e-06 -7.50853191403165e-06 -4.27100763695474e-05 0.000181035501183851 -1.23216491384556e-05 1.68079783234885e-05 -6.5509371873724e-05 -8.1332058848327e-06 6.353161036991e-06 -1.23216491384556e-05 9.95612822739458e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 852 0 0 0 0 0 2719 +1088 1125 0.999963361473368 0.00147277294946367 0.00843247595441455 0.0058431020113455 -0.00151538531429008 0.999986104466443 0.00504920601461807 0.00336239567266094 -0.00842492244662736 -0.00506179946937346 0.999951698267421 -0.0121778486142261 2.96574159589179e-05 -2.87481520115885e-05 -2.01153088969374e-05 6.14884084113404e-06 1.51114789466809e-05 2.41411486482814e-05 -2.87481520115885e-05 0.000132071148158347 3.2677504533315e-05 -8.17486413849371e-06 -3.63297592547314e-05 -6.66444314009141e-05 -2.01153088969374e-05 3.2677504533315e-05 3.13771862181661e-05 -1.60232809275628e-05 -2.06800862730147e-05 -1.73356816774458e-05 6.14884084113404e-06 -8.17486413849371e-06 -1.60232809275628e-05 4.14755282577466e-05 -1.80532198045949e-05 1.61137353336672e-07 1.51114789466809e-05 -3.63297592547314e-05 -2.06800862730147e-05 -1.80532198045949e-05 0.000143462429686053 2.58566348792204e-05 2.41411486482814e-05 -6.66444314009141e-05 -1.73356816774458e-05 1.61137353336672e-07 2.58566348792204e-05 7.55580762808054e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 923 0 0 0 0 0 2535 +1088 1129 0.999985555659605 0.00242553883994503 0.00479637712105764 0.00634000959142558 -0.00244878706593948 0.999985254320401 0.00484712117340195 -0.000369452295128335 -0.00478454951454937 -0.0048587964661912 0.999976749821136 -0.00931412216631524 2.9934805400587e-05 -1.41968110617699e-05 -9.04663020216501e-06 -3.88470495778994e-07 8.89306851508699e-06 2.64224127360437e-05 -1.41968110617699e-05 0.000119200927496004 1.69163172247309e-05 -3.96945537711304e-06 1.00182119302727e-05 -5.54968649609283e-05 -9.04663020216501e-06 1.69163172247309e-05 2.01030686869592e-05 -7.98988123280556e-06 -1.09056093923017e-05 -5.25723985191576e-06 -3.88470495778994e-07 -3.96945537711304e-06 -7.98988123280556e-06 3.67612381134157e-05 -1.99249318972629e-05 -5.06907507684633e-06 8.89306851508699e-06 1.00182119302727e-05 -1.09056093923017e-05 -1.99249318972629e-05 0.00013388032936887 1.05983679417116e-05 2.64224127360437e-05 -5.54968649609283e-05 -5.25723985191576e-06 -5.06907507684633e-06 1.05983679417116e-05 9.13410881048111e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 938 0 0 0 0 0 2552 +1088 1132 0.999979405682548 0.00247336211930856 0.00592205121600766 0.00433536818082281 -0.00250036057339997 0.999986495826871 0.00455591493524241 0.00368228153566202 -0.00591070281618314 -0.00457062837265811 0.999972086084655 -0.0133113165017399 2.46678357051292e-05 -1.57902372733753e-05 -1.33922381971391e-05 5.84401181893783e-06 -3.72602334240696e-07 1.54076144874574e-05 -1.57902372733753e-05 0.000110379764485348 2.17059336557979e-05 -1.25582744023834e-05 1.01183929777196e-05 -4.75821969534169e-05 -1.33922381971391e-05 2.17059336557979e-05 2.49969324013921e-05 -1.34551236259434e-05 -8.31278565360444e-06 -1.16494400123136e-05 5.84401181893783e-06 -1.25582744023834e-05 -1.34551236259434e-05 3.26049523601952e-05 -1.70656723884936e-05 6.68549180535738e-06 -3.72602334240696e-07 1.01183929777196e-05 -8.31278565360444e-06 -1.70656723884936e-05 0.000117739663800757 -3.68113316007263e-06 1.54076144874574e-05 -4.75821969534169e-05 -1.16494400123136e-05 6.68549180535738e-06 -3.68113316007263e-06 5.80643095019655e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 932 0 0 0 0 0 2489 +1088 1131 0.999968814189494 0.00188238475016208 0.00766989413943217 0.00424279353391926 -0.00191787801265113 0.999987475266872 0.00462288365795392 0.00431125528110171 -0.00766109603035545 -0.00463744941090955 0.999959900031284 -0.0136062418633983 2.77051839810537e-05 -1.91784797888743e-05 -1.8023468425926e-05 1.18939688313494e-05 9.42745974574769e-07 1.62352870831107e-05 -1.91784797888743e-05 0.000111256117496791 2.5867149263082e-05 -2.30012716562972e-05 2.07368785283807e-05 -5.06355956513598e-05 -1.8023468425926e-05 2.5867149263082e-05 2.97941219407231e-05 -1.87619713967491e-05 -9.6179468675205e-06 -1.40614527097777e-05 1.18939688313494e-05 -2.30012716562972e-05 -1.87619713967491e-05 4.55931475208628e-05 -3.33839521851241e-05 8.37423176367997e-06 9.42745974574769e-07 2.07368785283807e-05 -9.6179468675205e-06 -3.33839521851241e-05 0.000161424645504344 -9.41354958905831e-07 1.62352870831107e-05 -5.06355956513598e-05 -1.40614527097777e-05 8.37423176367997e-06 -9.41354958905831e-07 6.50812464844617e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 934 0 0 0 0 0 2478 +1088 1138 0.999996636921229 0.00241578852486039 -0.000943457490031635 -0.00291744364163208 -0.00241549877859016 0.99999703520641 0.000308129906893723 0.0203167643178481 0.000944199069568157 -0.000305849950213751 0.999999507471841 0.00138646410829949 4.73625930533278e-05 -1.93503853130854e-05 -1.20225411618994e-05 6.68423315991859e-06 -3.32800821436957e-06 4.44098392112685e-05 -1.93503853130854e-05 0.000114823901981913 1.78867225139028e-05 -1.60750057317142e-05 2.94359461254794e-05 -7.25340946970978e-05 -1.20225411618994e-05 1.78867225139028e-05 2.10846831717425e-05 -1.16749339206719e-05 -6.43968725171102e-06 -8.39247617357539e-06 6.68423315991859e-06 -1.60750057317142e-05 -1.16749339206719e-05 3.28661061743372e-05 -1.34563505889796e-05 1.21689292910179e-05 -3.32800821436957e-06 2.94359461254794e-05 -6.43968725171102e-06 -1.34563505889796e-05 0.000114799187517811 -2.69170708714039e-05 4.44098392112685e-05 -7.25340946970978e-05 -8.39247617357539e-06 1.21689292910179e-05 -2.69170708714039e-05 0.000113198129997978 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 919 0 0 0 0 0 2480 +1089 1091 0.999998970377834 -0.000982858495724424 -0.00104557756744319 -0.00458570964734448 0.000983346885956892 0.999999407614768 0.000466689419101374 0.0146135233709572 0.00104511825839805 -0.000467717104032575 0.999999344484053 0.000261493717863253 4.87325059163026e-05 -6.66675425491988e-05 -2.26408103329571e-05 1.14814363871179e-05 -1.3813864770858e-05 6.02263087419127e-05 -6.66675425491988e-05 0.000200632915838235 3.11162269589933e-05 -1.67574262816006e-05 3.90905266443353e-05 -0.000157792629929381 -2.26408103329571e-05 3.11162269589933e-05 2.53487336930106e-05 -1.61337179675483e-05 -8.43647809486462e-07 -2.61966385302161e-05 1.14814363871179e-05 -1.67574262816006e-05 -1.61337179675483e-05 3.37986562736781e-05 -1.68415502367548e-06 1.66065093798522e-05 -1.3813864770858e-05 3.90905266443353e-05 -8.43647809486462e-07 -1.68415502367548e-06 7.11375757093529e-05 -3.37212701008873e-05 6.02263087419127e-05 -0.000157792629929381 -2.61966385302161e-05 1.66065093798522e-05 -3.37212701008873e-05 0.000154924243576125 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 889 0 0 0 0 0 2661 +1089 1092 0.99998090461499 -0.00106453024811875 -0.00608746094336429 -0.00201241789583587 0.00105441849895023 0.999998059573561 -0.00166404649612253 0.005906439315906 0.00608922055892353 0.00165759598908369 0.999980086685991 0.00235723433200068 3.0235039322967e-05 -2.96264648113961e-05 -1.45840990404854e-05 6.11031033559164e-06 1.25363405204728e-06 1.39709673862828e-05 -2.96264648113961e-05 0.000142635495836302 2.49782655696921e-05 -3.56193045801579e-06 1.53363188410759e-06 -7.67341751531173e-05 -1.45840990404854e-05 2.49782655696921e-05 2.46592309670583e-05 -1.1741420896775e-05 -8.56097403699373e-06 -1.22085170067656e-05 6.11031033559164e-06 -3.56193045801579e-06 -1.1741420896775e-05 2.9361462215884e-05 2.56714281324845e-06 5.53436324018291e-07 1.25363405204728e-06 1.53363188410759e-06 -8.56097403699373e-06 2.56714281324845e-06 6.65027938008257e-05 -2.81705049756299e-06 1.39709673862828e-05 -7.67341751531173e-05 -1.22085170067656e-05 5.53436324018291e-07 -2.81705049756299e-06 6.87500528898001e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2503 +1089 1124 0.999989913268256 0.00250542404650159 0.00372776234406729 0.00404716816889965 -0.00252126433035863 0.99998778748354 0.00425065994287728 0.00515307446664285 -0.00371706711307392 -0.00426001574184085 0.999984017711261 -0.0126891612828581 2.86331975113523e-05 -8.49453876764613e-06 -1.41131788658142e-05 7.89971138145622e-06 -1.57242456165379e-06 1.22731104727494e-05 -8.49453876764613e-06 0.000106527472909101 1.67822506125837e-05 4.79125075923468e-06 -1.31233130503034e-05 -3.44488346439489e-05 -1.41131788658142e-05 1.67822506125837e-05 2.2126452987504e-05 -1.04625525069958e-05 -1.01092838282321e-05 -7.90358058335062e-06 7.89971138145622e-06 4.79125075923468e-06 -1.04625525069958e-05 3.83272606324389e-05 -2.88615738304499e-05 3.41337300160509e-06 -1.57242456165379e-06 -1.31233130503034e-05 -1.01092838282321e-05 -2.88615738304499e-05 0.000143363673024868 -7.33637443390637e-06 1.22731104727494e-05 -3.44488346439489e-05 -7.90358058335062e-06 3.41337300160509e-06 -7.33637443390637e-06 5.66334771072481e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 916 0 0 0 0 0 2530 +1088 1139 0.999963551093378 0.00221607539784825 0.00824533168237323 -0.000115902987074128 -0.00224796170649887 0.999990023718014 0.00385993945706244 0.0220387353364637 -0.00823669550775132 -0.00387833395636896 0.999958556827649 -0.0113742279733765 3.85958450574444e-05 -3.08562198976253e-05 -2.02061820275586e-05 1.11326933542005e-05 1.31173391261282e-05 3.83274850923151e-05 -3.08562198976253e-05 0.000113931833089568 1.95878475896828e-05 -7.79030529312227e-06 -2.49961900717732e-06 -7.28250454537044e-05 -2.02061820275586e-05 1.95878475896828e-05 2.68503395232416e-05 -1.87739329441076e-05 -1.09460643782006e-05 -1.53350720084181e-05 1.11326933542005e-05 -7.79030529312227e-06 -1.87739329441076e-05 4.52606520300296e-05 -1.17375555979273e-05 5.25071024030002e-06 1.31173391261282e-05 -2.49961900717732e-06 -1.09460643782006e-05 -1.17375555979273e-05 0.000111085191681154 2.16794752344121e-05 3.83274850923151e-05 -7.28250454537044e-05 -1.53350720084181e-05 5.25071024030002e-06 2.16794752344121e-05 0.000100997193813918 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 923 0 0 0 0 0 2587 +1088 1137 0.999968235849209 0.00176376994859627 0.0077727992505943 0.00692508722112919 -0.00180357195267399 0.99998528341634 0.00511664723763624 0.00511043955970542 -0.00776366027290854 -0.00513050351440398 0.999956700819018 -0.00671591463430244 2.8548876702502e-05 -9.02054342469662e-06 -1.12935780336245e-05 2.06446310382792e-06 8.67479096710165e-07 7.80791262015614e-06 -9.02054342469662e-06 0.000131045618726464 2.4522742092176e-05 -6.68117445248696e-06 4.82981170417821e-06 -5.62922307192453e-05 -1.12935780336245e-05 2.4522742092176e-05 2.64440241076221e-05 -1.13222044352844e-05 -1.32152830462116e-05 -9.34643579457055e-06 2.06446310382792e-06 -6.68117445248696e-06 -1.13222044352844e-05 2.75385485440185e-05 5.00663806281365e-06 4.25911834087006e-06 8.67479096710165e-07 4.82981170417821e-06 -1.32152830462116e-05 5.00663806281365e-06 7.99511841851287e-05 -8.52544221344661e-06 7.80791262015614e-06 -5.62922307192453e-05 -9.34643579457055e-06 4.25911834087006e-06 -8.52544221344661e-06 5.37874654813525e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 942 0 0 0 0 0 2526 +1089 1123 0.999978970526077 0.00163669712683975 0.00627532693355498 0.00541814573349692 -0.0016556421821524 0.999994084386063 0.00301496962584036 0.00382381574304028 -0.00627035521901939 -0.00302529591859322 0.999975764821344 -0.00874737152754626 3.20210377315212e-05 -3.35599450820429e-05 -1.28745268714162e-05 3.24424098345484e-06 -1.48778617029786e-05 2.09863198748551e-05 -3.35599450820429e-05 0.000161570923206914 3.13956099932248e-05 -1.57619762249417e-05 3.52624662748644e-05 -7.83103303419157e-05 -1.28745268714162e-05 3.13956099932248e-05 2.65928212581741e-05 -1.33346300756001e-05 -7.03214256267201e-07 -9.12967336768979e-06 3.24424098345484e-06 -1.57619762249417e-05 -1.33346300756001e-05 3.7386686384395e-05 -1.38104664965089e-05 1.12033434349653e-06 -1.48778617029786e-05 3.52624662748644e-05 -7.03214256267201e-07 -1.38104664965089e-05 0.000107296593911834 -2.239512037314e-05 2.09863198748551e-05 -7.83103303419157e-05 -9.12967336768979e-06 1.12033434349653e-06 -2.239512037314e-05 8.3254507571215e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 839 0 0 0 0 0 2601 +1089 1093 0.999972828506834 -0.000468609212605162 0.00735681000485582 0.00406854511590831 0.000455600949232825 0.999998330169906 0.00176976980838929 0.00258381576105215 -0.00735762705066948 -0.00176636995147949 0.999971372220914 -0.00704436787128344 2.25539188774369e-05 -1.85838123386784e-05 -1.15927272825918e-05 1.39859571739038e-06 3.29807409204541e-06 9.23392325801457e-06 -1.85838123386784e-05 0.00010731823156206 1.99722984373938e-05 -8.89877888813847e-07 1.85556675696259e-06 -4.82562314331027e-05 -1.15927272825918e-05 1.99722984373938e-05 2.10135216913284e-05 -9.63852395691689e-06 -8.26957898604633e-06 -8.76750359337119e-06 1.39859571739038e-06 -8.89877888813847e-07 -9.63852395691689e-06 2.43417338742198e-05 8.77733247857283e-06 1.72233069801648e-06 3.29807409204541e-06 1.85556675696259e-06 -8.26957898604633e-06 8.77733247857283e-06 4.72215545603729e-05 2.68724998378453e-06 9.23392325801457e-06 -4.82562314331027e-05 -8.76750359337119e-06 1.72233069801648e-06 2.68724998378453e-06 4.74750170081139e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 820 0 0 0 0 0 2492 +1089 1126 0.999992508111623 0.00201413768083385 0.00330559677331225 0.00558383787380619 -0.00201372238623612 0.999997964144016 -0.000128957255241369 0.00344978238485485 -0.00330584978126027 0.000122299734885718 0.999994528185029 -0.00384574968375365 2.7990019036469e-05 -5.84898448571646e-06 -1.03630047852851e-05 -3.60552136223139e-07 7.04856869245399e-06 1.21815929297568e-05 -5.84898448571646e-06 0.000104317786813136 1.95584957055657e-05 -1.23994942557981e-06 -1.08896328312786e-05 -3.78005090659629e-05 -1.03630047852851e-05 1.95584957055657e-05 2.46186892759363e-05 -9.66391220500491e-06 -9.59327498407419e-06 -7.40606446050077e-06 -3.60552136223139e-07 -1.23994942557981e-06 -9.66391220500491e-06 4.07673815795848e-05 -2.09841949770469e-05 1.48589106849952e-06 7.04856869245399e-06 -1.08896328312786e-05 -9.59327498407419e-06 -2.09841949770469e-05 0.000116858767014662 1.06256272221422e-05 1.21815929297568e-05 -3.78005090659629e-05 -7.40606446050077e-06 1.48589106849952e-06 1.06256272221422e-05 7.05144883550032e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 859 0 0 0 0 0 2559 +1089 1121 0.999994863462696 0.00225020268553906 0.00228246272661543 0.00382596765584027 -0.0022570923603437 0.999992891165544 0.0030204556698892 -0.000498452616909176 -0.00227564986350582 -0.00302559188438899 0.999992833580045 -0.00802469113911057 3.06744983240644e-05 -2.85165258074636e-05 -1.44935190831604e-05 6.66695953888376e-06 -2.4992020432779e-06 1.88984566808664e-05 -2.85165258074636e-05 0.000159162228098648 2.90604308626033e-05 -4.92599914267701e-06 -3.45145541687549e-06 -6.96564807141938e-05 -1.44935190831604e-05 2.90604308626033e-05 2.96297222916716e-05 -1.57022577190937e-05 -1.53422127094275e-05 -1.14141752910019e-05 6.66695953888376e-06 -4.92599914267701e-06 -1.57022577190937e-05 3.76448067986447e-05 -1.08318140586801e-05 1.09465560855952e-06 -2.4992020432779e-06 -3.45145541687549e-06 -1.53422127094275e-05 -1.08318140586801e-05 0.000122011672437041 -2.82836754442632e-06 1.88984566808664e-05 -6.96564807141938e-05 -1.14141752910019e-05 1.09465560855952e-06 -2.82836754442632e-06 7.02913470886498e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 926 0 0 0 0 0 2576 +1089 1120 0.999968280847023 0.00161643797045187 0.00779900173980218 0.00822253333046527 -0.00164620802191798 0.999991378324098 0.00381225348297935 -0.000775943777904557 -0.00779277222805395 -0.00382497134075495 0.999962320437747 -0.00899426227694211 2.54128799736906e-05 -1.60956166162386e-05 -1.52544966328159e-05 3.22404214110941e-06 7.60753914074282e-06 1.19864999762986e-05 -1.60956166162386e-05 0.000101108884795919 1.43504970739178e-05 -3.86086139887441e-06 -2.16605626745005e-05 -4.93399716782603e-05 -1.52544966328159e-05 1.43504970739178e-05 2.46155967047938e-05 -1.05900776472476e-05 -1.39480912941233e-05 -9.75147872197124e-06 3.22404214110941e-06 -3.86086139887441e-06 -1.05900776472476e-05 3.7617763381628e-05 -1.98575273795895e-05 5.63790791826198e-06 7.60753914074282e-06 -2.16605626745005e-05 -1.39480912941233e-05 -1.98575273795895e-05 0.000128577391248456 5.40931388909623e-06 1.19864999762986e-05 -4.93399716782603e-05 -9.75147872197124e-06 5.63790791826198e-06 5.40931388909623e-06 6.14541496857155e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 826 0 0 0 0 0 2563 +1089 1125 0.999989260231684 0.00235760952909883 0.00399012513552171 0.00874334131356094 -0.00237343391390928 0.999989319527294 0.0039658092232387 -0.00421453135046817 -0.00398073268948382 -0.00397523692968384 0.999984175504097 -0.00959759458342606 3.18927096208311e-05 -2.05271113360241e-05 -1.46265600918041e-05 6.458460349988e-06 2.61586128173073e-06 1.56197968614273e-05 -2.05271113360241e-05 0.000144231352940389 2.33380719982355e-05 -2.53105781078009e-06 1.66016429935656e-05 -6.39654584362857e-05 -1.46265600918041e-05 2.33380719982355e-05 2.34075713493822e-05 -1.05594047284777e-05 -7.84735766902335e-06 -9.56365130543661e-06 6.458460349988e-06 -2.53105781078009e-06 -1.05594047284777e-05 4.00320516022248e-05 -1.84342428529017e-05 3.62220868936728e-07 2.61586128173073e-06 1.66016429935656e-05 -7.84735766902335e-06 -1.84342428529017e-05 0.000122619566343175 -9.72186422866771e-06 1.56197968614273e-05 -6.39654584362857e-05 -9.56365130543661e-06 3.62220868936728e-07 -9.72186422866771e-06 7.31616016029123e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 920 0 0 0 0 0 2501 +1089 1122 0.999995032506784 0.00306103050551805 -0.000751700738680229 0.00813124188839213 -0.00305849083606238 0.999989688753455 0.00335678724003185 -0.00509560163700716 0.000761968215850856 -0.00335447149539329 0.999994083445209 -0.00636645590152 3.40743306432923e-05 -3.90170264622494e-05 -1.68599324577245e-05 4.49663440978101e-06 -1.3618745643606e-06 3.19825991774008e-05 -3.90170264622494e-05 0.000184422068752379 3.3620980000752e-05 -8.06461030871577e-06 3.72054762378966e-06 -0.000102714659522042 -1.68599324577245e-05 3.3620980000752e-05 2.77464248788838e-05 -1.41250262018755e-05 -1.18867262988069e-05 -1.65192102250671e-05 4.49663440978101e-06 -8.06461030871577e-06 -1.41250262018755e-05 3.29526758783049e-05 -1.66314412759332e-06 -4.78780816516004e-07 -1.3618745643606e-06 3.72054762378966e-06 -1.18867262988069e-05 -1.66314412759332e-06 8.76925011404547e-05 -4.4531540306469e-06 3.19825991774008e-05 -0.000102714659522042 -1.65192102250671e-05 -4.78780816516004e-07 -4.4531540306469e-06 0.000111793561820531 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 926 0 0 0 0 0 2624 +1089 1128 0.999994841693542 0.0014078404871655 0.00288696578955513 0.00682260316908627 -0.00140866703136623 0.999998967418049 0.000284288639003968 -0.00320478404096575 -0.00288656257547033 -0.000288353946084474 0.999995792295397 -0.00278068283444224 2.9281076762782e-05 -1.64080303330802e-05 -1.18450952241744e-05 3.25814611381214e-06 9.5484987596769e-06 1.63708378910106e-05 -1.64080303330802e-05 0.000143742172765998 2.23246864881212e-05 3.16448061613418e-06 -2.52916348914122e-05 -6.89147650771105e-05 -1.18450952241744e-05 2.23246864881212e-05 2.2332091384064e-05 -8.89395890032854e-06 -1.55133162879889e-05 -8.58021517412528e-06 3.25814611381214e-06 3.16448061613418e-06 -8.89395890032854e-06 4.20902744744987e-05 -2.88814905876629e-05 -2.78482657662224e-06 9.5484987596769e-06 -2.52916348914122e-05 -1.55133162879889e-05 -2.88814905876629e-05 0.00015778692211677 9.98055116123313e-06 1.63708378910106e-05 -6.89147650771105e-05 -8.58021517412528e-06 -2.78482657662224e-06 9.98055116123313e-06 7.67842639783384e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 841 0 0 0 0 0 2679 +1089 1127 0.999987517178462 0.00262661458267381 -0.00425045680951092 0.00503986770113386 -0.00263407748625194 0.999994997552558 -0.00175114409907531 0.00328800850452404 0.00424583596619713 0.00176231827244425 0.999989433499802 -0.00159686590674104 3.74174371546472e-05 -2.24810530209301e-05 -1.08669762944547e-05 3.58316065649022e-06 4.07406256079527e-06 1.46340089372379e-05 -2.24810530209301e-05 0.00013882281804603 1.76763212439185e-05 5.97802585655481e-06 -8.04256811831755e-06 -5.89083514733648e-05 -1.08669762944547e-05 1.76763212439185e-05 2.17258342240307e-05 -1.15571692619142e-05 -5.37114883176964e-06 -7.16930280642394e-06 3.58316065649022e-06 5.97802585655481e-06 -1.15571692619142e-05 6.39804754198395e-05 -7.14913668971951e-05 -6.14884148835582e-06 4.07406256079527e-06 -8.04256811831755e-06 -5.37114883176964e-06 -7.14913668971951e-05 0.000242710148141748 1.43147510441179e-05 1.46340089372379e-05 -5.89083514733648e-05 -7.16930280642394e-06 -6.14884148835582e-06 1.43147510441179e-05 7.27424999607182e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 856 0 0 0 0 0 2667 +1089 1131 0.999955776006075 0.00190781442579006 0.00920903231641796 0.00152410687512858 -0.00196308449007513 0.999980094425491 0.00599641993787569 0.00931175882889593 -0.00919740894887845 -0.00601423286074575 0.999939616512779 -0.0162977090292042 2.92025556722721e-05 -2.89989871464428e-06 -1.31795237487861e-05 6.7546134178295e-06 4.2105647859635e-06 7.85775788183007e-06 -2.89989871464428e-06 0.000108065785720428 1.59541192146167e-05 4.55529052965511e-06 -1.72473191105055e-05 -4.66493771691707e-05 -1.31795237487861e-05 1.59541192146167e-05 2.3767451081143e-05 -1.15043561195355e-05 -1.28125624245372e-05 -7.64321501286885e-06 6.7546134178295e-06 4.55529052965511e-06 -1.15043561195355e-05 5.00746148565771e-05 -6.04391330648198e-05 -5.34678738589055e-06 4.2105647859635e-06 -1.72473191105055e-05 -1.28125624245372e-05 -6.04391330648198e-05 0.000229716324269636 1.22723094219544e-05 7.85775788183007e-06 -4.66493771691707e-05 -7.64321501286885e-06 -5.34678738589055e-06 1.22723094219544e-05 6.32965555721067e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 918 0 0 0 0 0 2479 +1089 1129 0.999982091620073 0.00227435233370073 0.00553568068134329 0.00594946104811335 -0.00229718369653845 0.999988867855859 0.00412154235959102 -0.000669738192198561 -0.00552624521786404 -0.00413418502485498 0.999976184280392 -0.0100889551788931 4.33388521885037e-05 -3.31536363488429e-05 -1.85822487789695e-05 7.32395587179162e-06 1.11714300036795e-05 5.01387074913348e-05 -3.31536363488429e-05 0.000157563057482916 3.02503003410514e-05 -1.0408870115231e-05 -1.71002553261708e-05 -9.63534726917234e-05 -1.85822487789695e-05 3.02503003410514e-05 2.55585052019055e-05 -1.30108477257112e-05 -9.98014190200095e-06 -1.88988077537218e-05 7.32395587179162e-06 -1.0408870115231e-05 -1.30108477257112e-05 5.11871463136728e-05 -4.89121870370413e-05 7.5622428585968e-06 1.11714300036795e-05 -1.71002553261708e-05 -9.98014190200095e-06 -4.89121870370413e-05 0.000208044969572697 8.77611568898639e-06 5.01387074913348e-05 -9.63534726917234e-05 -1.88988077537218e-05 7.5622428585968e-06 8.77611568898639e-06 0.000138366658765937 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 910 0 0 0 0 0 2597 +1089 1139 0.999907326301829 0.00190744684738266 0.013479631094844 0.00148979050318685 -0.00200087848700156 0.99997404614764 0.00692123662341654 0.0194055374198575 -0.0134660793555114 -0.00694756631069312 0.99988519142407 -0.0162748313509913 3.41046553713485e-05 -3.88790239206051e-06 -1.27645063778047e-05 5.43750259952802e-06 1.09110530642796e-05 2.06215605799163e-05 -3.88790239206051e-06 0.000117799106062287 1.54926412253824e-05 7.29396012297369e-06 -1.28320533397744e-05 -6.34220972682203e-05 -1.27645063778047e-05 1.54926412253824e-05 2.1705940812584e-05 -8.45684006047342e-06 -7.77949860429012e-06 -8.99082587330309e-06 5.43750259952802e-06 7.29396012297369e-06 -8.45684006047342e-06 3.33757013920528e-05 -3.07577193485637e-06 -1.83906188410492e-06 1.09110530642796e-05 -1.28320533397744e-05 -7.77949860429012e-06 -3.07577193485637e-06 7.99934999283424e-05 1.97834960462661e-05 2.06215605799163e-05 -6.34220972682203e-05 -8.99082587330309e-06 -1.83906188410492e-06 1.97834960462661e-05 8.87396326065544e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 914 0 0 0 0 0 2570 +1090 1094 0.999996145230118 -0.00040681498635932 0.00274663912299581 0.00300182245252327 0.000399579500579292 0.999996450287538 0.00263434024886848 0.00269181545955874 -0.00274770106230909 -0.00263323259340399 0.999992758086268 -0.00233089366151064 4.04465202193035e-05 -4.1314891936706e-05 -1.70666002948732e-05 3.90129194471984e-06 1.3383312178714e-05 3.84762946193099e-05 -4.1314891936706e-05 0.000149941487488703 2.23239155019324e-05 5.28548720501656e-06 -1.93374103986904e-05 -0.000103773673192513 -1.70666002948732e-05 2.23239155019324e-05 2.3800526163526e-05 -1.28042078534613e-05 -9.27834482453682e-06 -1.53313380231395e-05 3.90129194471984e-06 5.28548720501656e-06 -1.28042078534613e-05 3.42012450755621e-05 4.18575064382944e-06 -4.64136488587343e-06 1.3383312178714e-05 -1.93374103986904e-05 -9.27834482453682e-06 4.18575064382944e-06 5.61286377366569e-05 1.7774729920501e-05 3.84762946193099e-05 -0.000103773673192513 -1.53313380231395e-05 -4.64136488587343e-06 1.7774729920501e-05 0.000112369839116067 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 784 0 0 0 0 0 2677 +1090 1092 0.999990929756951 -9.9768005197424e-05 -0.00425798663376733 -0.00315820077080836 9.71112740430863e-05 0.999999800507508 -0.000624142887897392 0.0137271408633661 0.00425804805382185 0.000623723728262838 0.999990739954867 0.0040749950343182 2.54592917752851e-05 -1.23248892676159e-05 -1.10567464401245e-05 4.72555139669866e-06 8.57944163603242e-07 1.12045605708708e-05 -1.23248892676159e-05 8.65907420827331e-05 1.48782629381627e-05 -1.14770196894907e-05 1.10156308260654e-05 -3.93810510162114e-05 -1.10567464401245e-05 1.48782629381627e-05 2.09538371623765e-05 -1.15510503918777e-05 -6.14508702025241e-06 -6.82962714162867e-06 4.72555139669866e-06 -1.14770196894907e-05 -1.15510503918777e-05 3.03000451562356e-05 -7.4312837826249e-06 4.61457654539516e-06 8.57944163603242e-07 1.10156308260654e-05 -6.14508702025241e-06 -7.4312837826249e-06 7.53577061124114e-05 -2.50311538306402e-06 1.12045605708708e-05 -3.93810510162114e-05 -6.82962714162867e-06 4.61457654539516e-06 -2.50311538306402e-06 4.90102370709621e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 799 0 0 0 0 0 2616 +1090 1093 0.999998992305479 0.000710397984979115 -0.00122911461245654 0.00248429334392178 -0.000710129026200153 0.999999723823992 0.000219245768035229 0.00680246090981195 0.0012292700247564 -0.000218372717139637 0.999999220603978 0.00221763220978172 3.22775276362426e-05 -1.79812577756462e-05 -1.25466791055483e-05 2.39591175440583e-06 2.8172194386869e-06 1.59884186306976e-05 -1.79812577756462e-05 0.00012468624680955 2.34618118092673e-05 -1.0657087694533e-05 5.93563411130126e-06 -7.17783232861816e-05 -1.25466791055483e-05 2.34618118092673e-05 2.6015969907614e-05 -1.57529044545664e-05 -8.95229473332676e-06 -1.20984276545876e-05 2.39591175440583e-06 -1.0657087694533e-05 -1.57529044545664e-05 3.33987568226489e-05 9.19758015936017e-06 2.677345017693e-06 2.8172194386869e-06 5.93563411130126e-06 -8.95229473332676e-06 9.19758015936017e-06 6.00198391196983e-05 1.22111799216017e-06 1.59884186306976e-05 -7.17783232861816e-05 -1.20984276545876e-05 2.677345017693e-06 1.22111799216017e-06 7.27628062592258e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 783 0 0 0 0 0 2674 +1089 1138 0.999997682267632 0.00204055448982948 0.000686729013489712 -0.00429437007960225 -0.00204310360314464 0.99999094905095 0.0037319624658209 0.0231374652086486 -0.000679107525174894 -0.00373335687465254 0.999992800403791 -0.00431075046846409 3.59178159269531e-05 1.63450741671379e-05 -5.77746748022395e-06 4.51227943961214e-06 3.57040842294361e-06 1.64868754723992e-05 1.63450741671379e-05 9.27617083197131e-05 1.63393632518004e-05 -3.42267857785612e-06 -1.03359814696755e-05 -2.24157616318996e-05 -5.77746748022395e-06 1.63393632518004e-05 2.10110479416725e-05 -9.23357895152174e-06 -1.40956915129365e-05 -1.88210105667127e-06 4.51227943961214e-06 -3.42267857785612e-06 -9.23357895152174e-06 2.64244802308474e-05 1.6850682357683e-06 2.47736992175445e-06 3.57040842294361e-06 -1.03359814696755e-05 -1.40956915129365e-05 1.6850682357683e-06 7.82949804632044e-05 -2.13355605412134e-06 1.64868754723992e-05 -2.24157616318996e-05 -1.88210105667127e-06 2.47736992175445e-06 -2.13355605412134e-06 6.56572005477603e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 915 0 0 0 0 0 2559 +1090 1122 0.999960867557561 0.00184216335030273 0.00865273296254155 0.0095500197161125 -0.00186842322571297 0.999993670804952 0.0030277623232423 -0.00563997749388479 -0.00864710056492163 -0.00304381080674057 0.999957980550979 -0.00877865396675534 2.17585306114315e-05 -1.00568109336962e-05 -1.22973248548711e-05 6.40083737649211e-06 -3.62489611469961e-08 9.27368521796832e-06 -1.00568109336962e-05 9.33241548039237e-05 1.75640891547774e-05 -7.11771199999884e-06 3.92431275705186e-06 -3.83323791170874e-05 -1.22973248548711e-05 1.75640891547774e-05 2.22889408679151e-05 -1.19027196338824e-05 -6.91113020241291e-06 -7.59846944867097e-06 6.40083737649211e-06 -7.11771199999884e-06 -1.19027196338824e-05 3.4580222618105e-05 -1.23416289053171e-05 4.3147346269846e-06 -3.62489611469961e-08 3.92431275705186e-06 -6.91113020241291e-06 -1.23416289053171e-05 9.87095531022504e-05 -5.85131673368997e-06 9.27368521796832e-06 -3.83323791170874e-05 -7.59846944867097e-06 4.3147346269846e-06 -5.85131673368997e-06 5.60685621703574e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 962 0 0 0 0 0 2458 +1090 1128 0.999984143968909 0.00269123586980115 0.00494662109545584 0.00767756662979184 -0.00273056160048869 0.999964586345425 0.00796053317112663 0.000106475753922785 -0.00492502224511218 -0.00797391400228058 0.999956079461178 -0.0155780848242346 3.67191604289532e-05 5.58265477654159e-06 -7.66742270139942e-06 5.91786425986943e-06 -1.18551002343454e-05 1.80142446945898e-05 5.58265477654159e-06 6.8836974566851e-05 1.28753999238121e-05 -1.4097527782705e-05 2.13996371159432e-05 -1.89483453366227e-05 -7.66742270139942e-06 1.28753999238121e-05 2.38315410440276e-05 -1.16790164040283e-05 -6.93641303512597e-06 -5.94251320724924e-07 5.91786425986943e-06 -1.4097527782705e-05 -1.16790164040283e-05 4.39807952373505e-05 -4.64506928204655e-05 1.21261069769872e-05 -1.18551002343454e-05 2.13996371159432e-05 -6.93641303512597e-06 -4.64506928204655e-05 0.000219491047884141 -4.06822229752286e-05 1.80142446945898e-05 -1.89483453366227e-05 -5.94251320724924e-07 1.21261069769872e-05 -4.06822229752286e-05 7.1295853082417e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 840 0 0 0 0 0 2618 +1090 1124 0.999968941642767 0.00169175781148485 0.0076976428438615 0.0103719562736911 -0.00172673657814165 0.999988204622182 0.00453971334948859 -0.00751775499893239 -0.00768987195173495 -0.00455286415491362 0.999960067851388 -0.008400908589555 2.45494184735924e-05 -1.27369095056275e-05 -1.1678687611206e-05 3.15684541351814e-06 4.34414524818328e-06 9.61289172406502e-06 -1.27369095056275e-05 9.60490546380794e-05 1.83536990269228e-05 -1.77785240028296e-06 -1.09762611165495e-05 -5.31632799044097e-05 -1.1678687611206e-05 1.83536990269228e-05 2.11287402811769e-05 -8.43732931533762e-06 -6.66953580124872e-06 -9.22020191191372e-06 3.15684541351814e-06 -1.77785240028296e-06 -8.43732931533762e-06 3.05578891473057e-05 -1.86893914509508e-05 -2.29171480758047e-06 4.34414524818328e-06 -1.09762611165495e-05 -6.66953580124872e-06 -1.86893914509508e-05 0.000107969379508263 2.46137284745464e-06 9.61289172406502e-06 -5.31632799044097e-05 -9.22020191191372e-06 -2.29171480758047e-06 2.46137284745464e-06 5.8882640420723e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 939 0 0 0 0 0 2708 +1090 1127 0.999952852452858 0.00167524504504483 0.009564853654506 0.00996704253468884 -0.00173381462617698 0.99997977925926 0.00611841151312228 -0.0028520882414584 -0.00955441040750914 -0.00613470672819045 0.999935537229838 -0.0182347257776697 3.94254958022568e-05 -1.74571586722629e-05 -1.13296163918088e-05 7.70686433925075e-06 -8.23217453798924e-06 3.87998520564716e-05 -1.74571586722629e-05 0.000101771164647405 1.89920105976228e-05 -9.05045216401121e-06 2.00041354036685e-05 -4.56769961644098e-05 -1.13296163918088e-05 1.89920105976228e-05 2.33112324656244e-05 -1.15634257820497e-05 -6.82828078569868e-06 -6.23733794809871e-06 7.70686433925075e-06 -9.05045216401121e-06 -1.15634257820497e-05 4.08688947846344e-05 -2.83050324920611e-05 2.68397566077128e-06 -8.23217453798924e-06 2.00041354036685e-05 -6.82828078569868e-06 -2.83050324920611e-05 0.000167521426655667 -1.55836866852698e-05 3.87998520564716e-05 -4.56769961644098e-05 -6.23733794809871e-06 2.68397566077128e-06 -1.55836866852698e-05 0.00010380537437054 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 841 0 0 0 0 0 2736 +1090 1129 0.999982192258563 0.00311987921431423 0.00508738827366571 0.00752975671837404 -0.00314951966252713 0.999978053180315 0.00582869484547612 0.0013506963212347 -0.00506909179777762 -0.00584461387898421 0.999970071950631 -0.0100453285554634 2.72373919873004e-05 -6.8181962585502e-06 -1.15396733225938e-05 7.92436716668868e-06 -3.46568581467668e-06 5.74005502896868e-06 -6.8181962585502e-06 0.000104335670488756 1.74837909488009e-05 -1.65156054300648e-05 1.96232994443399e-05 -4.34924903637038e-05 -1.15396733225938e-05 1.74837909488009e-05 2.22342395414915e-05 -1.13387041320402e-05 -7.84073281652065e-06 -4.8596503564111e-06 7.92436716668868e-06 -1.65156054300648e-05 -1.13387041320402e-05 4.05740236149269e-05 -2.94252774721514e-05 7.49066552479147e-06 -3.46568581467668e-06 1.96232994443399e-05 -7.84073281652065e-06 -2.94252774721514e-05 0.000161899769271995 -1.38427630352873e-05 5.74005502896868e-06 -4.34924903637038e-05 -4.8596503564111e-06 7.49066552479147e-06 -1.38427630352873e-05 6.34582419507505e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 932 0 0 0 0 0 2542 +1090 1131 0.999993241227947 0.00313064627412052 -0.00192783617852918 0.00650115439135395 -0.00312589842784083 0.999992086350863 0.00246089306305005 -0.0035678860341812 0.00193552510800891 -0.00245485021035519 0.999995113714563 -0.00303777468754108 2.34079167088572e-05 -1.34768550770042e-05 -1.2510906748294e-05 4.21206051264684e-06 5.04996081732405e-06 6.87861005203203e-06 -1.34768550770042e-05 0.000102234833948362 1.68857413675108e-05 -6.64313924691851e-06 -3.23251705250742e-06 -4.49374388467647e-05 -1.2510906748294e-05 1.68857413675108e-05 2.08420114728058e-05 -1.05079698111228e-05 -5.50655113212703e-06 -6.99146025457805e-06 4.21206051264684e-06 -6.64313924691851e-06 -1.05079698111228e-05 4.04341524521911e-05 -3.28924115161425e-05 -1.23001268398286e-07 5.04996081732405e-06 -3.23251705250742e-06 -5.50655113212703e-06 -3.28924115161425e-05 0.00013666299814211 -1.16460771158084e-06 6.87861005203203e-06 -4.49374388467647e-05 -6.99146025457805e-06 -1.23001268398286e-07 -1.16460771158084e-06 5.47190318166874e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 948 0 0 0 0 0 2668 +1091 1093 0.999952572180115 0.000431353131840267 0.00972971350288176 -0.00312458734611947 -0.000455048655566456 0.999996935998336 0.00243329502150456 0.019101105571229 -0.00972863408159517 -0.00243760710867509 0.999949704610432 -0.00677972907957576 2.72778525129669e-05 -1.35513814767107e-05 -1.22126610769209e-05 8.20561182254825e-06 2.40500531055842e-06 1.49864516315193e-05 -1.35513814767107e-05 0.000107696058672734 2.35103968531819e-05 -1.35382511392403e-05 -7.74814532820847e-08 -5.04305128716348e-05 -1.22126610769209e-05 2.35103968531819e-05 2.42776313363921e-05 -1.40625861258486e-05 -7.49799809994438e-06 -1.06922224877406e-05 8.20561182254825e-06 -1.35382511392403e-05 -1.40625861258486e-05 3.19826981993369e-05 2.60113178263512e-06 9.82671427485441e-06 2.40500531055842e-06 -7.74814532820847e-08 -7.49799809994438e-06 2.60113178263512e-06 6.28759244650207e-05 9.24175114381137e-06 1.49864516315193e-05 -5.04305128716348e-05 -1.06922224877406e-05 9.82671427485441e-06 9.24175114381137e-06 6.7342426395692e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 809 0 0 0 0 0 2578 +1091 1094 0.999939374400407 0.000253298187875597 0.0110083315607041 -0.00421879379275704 -0.00027324471335085 0.999998323745001 0.00181048184578392 0.0254275490976942 -0.0110078545161625 -0.00181338005263824 0.999937767459423 -0.00902278413708141 3.05803060384377e-05 -2.10373633041427e-05 -1.65215468996962e-05 9.23218622714303e-06 -6.53734297840368e-07 1.12385751105946e-05 -2.10373633041427e-05 0.000135328920386137 2.89475188505539e-05 -5.99984872046498e-06 5.4943790073095e-08 -7.41030104638104e-05 -1.65215468996962e-05 2.89475188505539e-05 2.86435885859876e-05 -1.65549593755329e-05 -1.98579182048357e-06 -1.40338777196902e-05 9.23218622714303e-06 -5.99984872046498e-06 -1.65549593755329e-05 4.01323013523169e-05 -2.51308205402551e-05 3.77625981511469e-06 -6.53734297840368e-07 5.4943790073095e-08 -1.98579182048357e-06 -2.51308205402551e-05 0.000136999819206238 6.29516887126496e-06 1.12385751105946e-05 -7.41030104638104e-05 -1.40338777196902e-05 3.77625981511469e-06 6.29516887126496e-06 6.75977555188169e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2562 +1091 1120 0.999960320490959 0.00274404161060897 0.00847512119428234 0.00734720467332314 -0.00277225732765097 0.999990648411264 0.00331928897959644 -0.00669350481180908 -0.00846593367135678 -0.00334265248867295 0.999958576462751 -0.00947136964023528 4.36980546107797e-05 -2.15310465815597e-05 -1.65472249047802e-05 1.50175737474436e-05 -1.3155149160547e-05 5.17940774323921e-05 -2.15310465815597e-05 0.000101143436843268 1.38005543780704e-05 -1.19681920977563e-05 2.06780590542844e-05 -6.51876563202905e-05 -1.65472249047802e-05 1.38005543780704e-05 2.5284545385733e-05 -1.55091768652658e-05 -1.3206778374851e-05 -8.10889974772933e-06 1.50175737474436e-05 -1.19681920977563e-05 -1.55091768652658e-05 3.79449679729072e-05 -1.40162334981019e-05 1.71893626948181e-05 -1.3155149160547e-05 2.06780590542844e-05 -1.3206778374851e-05 -1.40162334981019e-05 0.000151257134201412 -3.86779363179127e-05 5.17940774323921e-05 -6.51876563202905e-05 -8.10889974772933e-06 1.71893626948181e-05 -3.86779363179127e-05 0.000136058752130113 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 826 0 0 0 0 0 2663 +1091 1095 0.999972041594091 0.00066224830876765 0.00744831909382831 0.00104767927391051 -0.00067798100270228 0.999997544284526 0.00210992101197683 0.00269387839074694 -0.00744690351125405 -0.00211491184079642 0.999970034939047 -0.0033010948712621 3.62467731394642e-05 -3.52636142076836e-05 -1.65045460295195e-05 9.07648356000175e-06 2.99693948538801e-06 3.17704808154434e-05 -3.52636142076836e-05 0.000133229929031284 3.05961631188583e-05 -1.7599114206719e-05 -5.69714364519074e-06 -7.98880322608257e-05 -1.65045460295195e-05 3.05961631188583e-05 2.60120276195891e-05 -1.55041946418681e-05 -1.06531892738228e-05 -1.48535040233109e-05 9.07648356000175e-06 -1.7599114206719e-05 -1.55041946418681e-05 3.26606265122025e-05 1.24745274208619e-05 1.11254768117751e-05 2.99693948538801e-06 -5.69714364519074e-06 -1.06531892738228e-05 1.24745274208619e-05 4.66762318086879e-05 1.12136256440634e-06 3.17704808154434e-05 -7.98880322608257e-05 -1.48535040233109e-05 1.11254768117751e-05 1.12136256440634e-06 9.25077263193683e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 755 0 0 0 0 0 2589 +1090 1139 0.999978950189353 0.00174117560621902 0.00625039884395783 0.00299276524210282 -0.00178645303841777 0.9999721540556 0.00724566759823097 0.0159404652965213 -0.00623760881602633 -0.00725668112230612 0.999954215359557 -0.00902788080749855 2.5407505003985e-05 -6.06769521272104e-06 -1.04224705132073e-05 6.01485812057579e-06 -2.18328682292009e-06 1.94618206321986e-06 -6.06769521272104e-06 9.27227294404861e-05 1.51551944026129e-05 -8.66160975869948e-06 9.00671685669819e-06 -3.88483998727496e-05 -1.04224705132073e-05 1.51551944026129e-05 2.08103857475016e-05 -7.67336329616638e-06 -6.9767999246522e-06 -6.1201209568167e-06 6.01485812057579e-06 -8.66160975869948e-06 -7.67336329616638e-06 2.87257554376494e-05 -4.41131458071529e-06 4.42605558818127e-06 -2.18328682292009e-06 9.00671685669819e-06 -6.9767999246522e-06 -4.41131458071529e-06 9.03536225523152e-05 -4.47527272865187e-06 1.94618206321986e-06 -3.88483998727496e-05 -6.1201209568167e-06 4.42605558818127e-06 -4.47527272865187e-06 5.05900154863928e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 936 0 0 0 0 0 2620 +1090 1138 0.999963670962633 0.00217778852731662 0.00824099460406089 -0.00277180371094616 -0.00222534461080316 0.999980900879574 0.00576590994016088 0.0284423663353844 -0.0082282802757953 -0.00578403952313302 0.999949418866023 -0.00809163700687127 2.83846693120624e-05 -3.2982483940279e-05 -1.54454056727903e-05 1.13258196662566e-06 1.07968199930799e-05 2.44429464446269e-05 -3.2982483940279e-05 0.000147531051799943 2.62092303781199e-05 6.23870614830072e-06 -2.01680436661075e-05 -7.18055013833464e-05 -1.54454056727903e-05 2.62092303781199e-05 2.52754248860703e-05 -1.1846588474328e-05 -1.73865334131892e-05 -1.34599109232659e-05 1.13258196662566e-06 6.23870614830072e-06 -1.1846588474328e-05 3.25547797044629e-05 8.87840461896534e-07 -2.01366769275707e-06 1.07968199930799e-05 -2.01680436661075e-05 -1.73865334131892e-05 8.87840461896534e-07 7.35107170938363e-05 1.30821285853714e-05 2.44429464446269e-05 -7.18055013833464e-05 -1.34599109232659e-05 -2.01366769275707e-06 1.30821285853714e-05 6.76416251508079e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 943 0 0 0 0 0 2552 +1091 1119 0.999973561610696 0.00313569597370849 0.0065607537966469 0.00815081110878665 -0.00316210383560306 0.999986925761 0.00401863240385621 -0.00763314772289822 -0.00654806681033516 -0.00403927194243307 0.999970403113623 -0.00875795270966717 2.77916323150899e-05 -1.62514557769206e-05 -1.03330800479057e-05 3.67990871507998e-06 4.7114334476123e-06 1.67371602393552e-05 -1.62514557769206e-05 0.000149491745266841 2.09881227832238e-05 2.83794034889121e-06 -5.42983911089995e-06 -5.87670774831677e-05 -1.03330800479057e-05 2.09881227832238e-05 2.01391574227219e-05 -1.08946418798758e-05 -7.19691271288371e-06 -7.98462249494138e-06 3.67990871507998e-06 2.83794034889121e-06 -1.08946418798758e-05 3.26547363010822e-05 -2.48327092275719e-06 -6.97365041060768e-07 4.7114334476123e-06 -5.42983911089995e-06 -7.19691271288371e-06 -2.48327092275719e-06 6.55618787192156e-05 -4.03854378207352e-07 1.67371602393552e-05 -5.87670774831677e-05 -7.98462249494138e-06 -6.97365041060768e-07 -4.03854378207352e-07 6.94201938504182e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 864 0 0 0 0 0 2638 +1091 1127 0.99999219580603 0.00355368163604056 0.00172617318500445 0.005610016417209 -0.00356140052366072 0.999983580825216 0.00448937704912526 0.00152014205421492 -0.00171019102588848 -0.00449548960724097 0.999988432843023 -0.0105660433497452 2.36298232733334e-05 -1.3508286489905e-06 -9.78845953892148e-06 2.0667440346965e-06 8.83837605571172e-06 6.21102918523407e-06 -1.3508286489905e-06 7.89110592036703e-05 1.24631905461174e-05 1.87314814276627e-06 -2.84133751548989e-05 -2.12089787794013e-05 -9.78845953892148e-06 1.24631905461174e-05 2.06725080072851e-05 -7.99665416807316e-06 -1.4479278383696e-05 -5.18286111201826e-06 2.0667440346965e-06 1.87314814276627e-06 -7.99665416807316e-06 3.09069361218533e-05 -9.90536981651658e-06 1.9712212423961e-06 8.83837605571172e-06 -2.84133751548989e-05 -1.4479278383696e-05 -9.90536981651658e-06 9.11127718237823e-05 1.22963131434969e-05 6.21102918523407e-06 -2.12089787794013e-05 -5.18286111201826e-06 1.9712212423961e-06 1.22963131434969e-05 4.87132672150605e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 861 0 0 0 0 0 2630 +1091 1124 0.9999954494892 0.00300059071179088 -0.000312179873087373 0.00922278846871606 -0.00300138751980991 0.999992157191312 -0.00258403344081349 -0.012251210060078 0.00030442379797889 0.00258495865491643 0.999996612651715 0.00148304610416693 2.77387917586517e-05 -1.65914431213706e-05 -1.39040791542371e-05 6.61926467369272e-06 2.81867485456073e-06 2.03378125376353e-05 -1.65914431213706e-05 0.000113399347482016 2.03697915712733e-05 -2.22153894365366e-06 -1.88397932605261e-05 -4.33513215633574e-05 -1.39040791542371e-05 2.03697915712733e-05 2.25957361681344e-05 -1.04096170553793e-05 -8.89625236897612e-06 -9.62838640869941e-06 6.61926467369272e-06 -2.22153894365366e-06 -1.04096170553793e-05 3.98152591955841e-05 -2.66141752069292e-05 7.85125326673307e-06 2.81867485456073e-06 -1.88397932605261e-05 -8.89625236897612e-06 -2.66141752069292e-05 0.000138161989364668 -2.6291525122837e-06 2.03378125376353e-05 -4.33513215633574e-05 -9.62838640869941e-06 7.85125326673307e-06 -2.6291525122837e-06 6.55964040085464e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 944 0 0 0 0 0 2665 +1091 1123 0.999959205710256 0.00218023688014502 0.00876547103471895 0.00667606666323384 -0.00221044677995007 0.99999164612301 0.00343825671318551 -0.00552411432928745 -0.00875790159496268 -0.00345749205916838 0.999955671471648 -0.01054690679994 5.66538102403522e-05 -3.4883735786164e-05 -1.24301672220255e-05 5.87101295196597e-06 -3.31493813714213e-06 7.72560291057609e-05 -3.4883735786164e-05 0.000149993434458297 2.85605678418192e-05 -4.93665887216593e-06 1.92369428468385e-06 -8.75760921852505e-05 -1.24301672220255e-05 2.85605678418192e-05 2.64398905703824e-05 -1.39108342055721e-05 -9.53363399659569e-06 -1.09543111506219e-05 5.87101295196597e-06 -4.93665887216593e-06 -1.39108342055721e-05 3.7532618095632e-05 -6.50992808565181e-06 3.22996618317588e-06 -3.31493813714213e-06 1.92369428468385e-06 -9.53363399659569e-06 -6.50992808565181e-06 8.69243513295563e-05 -1.45903719778588e-05 7.72560291057609e-05 -8.75760921852505e-05 -1.09543111506219e-05 3.22996618317588e-06 -1.45903719778588e-05 0.000180657208228935 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 834 0 0 0 0 0 2678 +1091 1130 0.999982041420796 0.00363629220848199 0.00476384454744953 0.000558954318563074 -0.00366254806609189 0.999978088308116 0.00551440344099779 0.0163025415194875 -0.00474368818128869 -0.00553175221978126 0.99997344821741 -0.0126003438024587 2.64058793228085e-05 -1.51962730298474e-05 -1.3668269060213e-05 2.31864575555693e-06 5.26669589411132e-06 1.11985705623713e-05 -1.51962730298474e-05 0.00013064655153058 2.00325495859493e-05 7.71724940080287e-06 -3.38974521281442e-05 -5.75593104075572e-05 -1.3668269060213e-05 2.00325495859493e-05 2.46838376785619e-05 -6.27847871904298e-06 -1.86612216015856e-05 -6.94101043943927e-06 2.31864575555693e-06 7.71724940080287e-06 -6.27847871904298e-06 4.51463942052171e-05 -5.80804515571271e-05 -3.77942506906775e-06 5.26669589411132e-06 -3.38974521281442e-05 -1.86612216015856e-05 -5.80804515571271e-05 0.000251570653738028 1.26380717252951e-05 1.11985705623713e-05 -5.75593104075572e-05 -6.94101043943927e-06 -3.77942506906775e-06 1.26380717252951e-05 6.78754995906349e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 865 0 0 0 0 0 2622 +1091 1118 0.999994362787179 0.00320154068235031 0.00101219124779021 0.00630728410157106 -0.00320364826791949 0.999992689502094 0.00208748177102539 -0.00705425692516822 -0.00100550069035461 -0.00209071270818417 0.999997308940746 -0.00586979755838046 2.65833466555016e-05 -1.28588962012048e-05 -1.09005042685541e-05 4.50173704412911e-06 4.30040983971917e-06 1.68592006315051e-05 -1.28588962012048e-05 0.000108641480862729 1.6056430108541e-05 -6.07173853510133e-06 5.47601992449249e-06 -3.40382420984762e-05 -1.09005042685541e-05 1.6056430108541e-05 2.22275796441532e-05 -1.386989538675e-05 -4.94066216297263e-06 -3.26395921582276e-06 4.50173704412911e-06 -6.07173853510133e-06 -1.386989538675e-05 3.83196929608411e-05 -1.2351471877643e-05 3.03111580225621e-06 4.30040983971917e-06 5.47601992449249e-06 -4.94066216297263e-06 -1.2351471877643e-05 0.00010233389392445 -1.54180836381949e-07 1.68592006315051e-05 -3.40382420984762e-05 -3.26395921582276e-06 3.03111580225621e-06 -1.54180836381949e-07 5.83281885200974e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 859 0 0 0 0 0 2665 +1091 1128 0.999968538916795 0.00254399591125742 0.00751327235055991 0.00560021338400424 -0.00258605983643097 0.999981008332209 0.0055942174985767 0.00183327681917922 -0.00749889799454434 -0.00561347127030046 0.999956126772152 -0.0145003346612636 2.87562719614502e-05 -1.80257402210387e-05 -1.23393413695709e-05 7.68372036148855e-06 -1.13417239812613e-05 1.73489576841684e-05 -1.80257402210387e-05 0.000118218819643339 2.21822062032602e-05 -1.73329164861746e-05 2.73819525397532e-05 -4.52966284820695e-05 -1.23393413695709e-05 2.21822062032602e-05 2.38663680879468e-05 -1.51219701376923e-05 -1.81043459658408e-06 -6.18639824641115e-06 7.68372036148855e-06 -1.73329164861746e-05 -1.51219701376923e-05 3.7569588599655e-05 -2.18315209893005e-05 5.39870792116518e-06 -1.13417239812613e-05 2.73819525397532e-05 -1.81043459658408e-06 -2.18315209893005e-05 0.000132409908774282 -2.10070256351951e-05 1.73489576841684e-05 -4.52966284820695e-05 -6.18639824641115e-06 5.39870792116518e-06 -2.10070256351951e-05 6.08458065071511e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 861 0 0 0 0 0 2704 +1091 1126 0.999976821734523 0.0036469857450238 0.00574939028920573 0.0072716062297221 -0.00367486035057583 0.999981509618188 0.00484518556244573 -0.00138624202158105 -0.00573161365810586 -0.00486620146586226 0.999971733944599 -0.0126249293073315 2.84663507846554e-05 -2.57597034674365e-06 -1.0257715311384e-05 3.13746554078926e-06 8.50605957659297e-06 8.04063733290313e-06 -2.57597034674365e-06 9.22625633784019e-05 1.7965049631117e-05 4.39525549734139e-06 -3.61237169833341e-05 -3.45204943379299e-05 -1.0257715311384e-05 1.7965049631117e-05 2.41308496491946e-05 -9.21036897021239e-06 -1.46340193158572e-05 -5.1330376545049e-06 3.13746554078926e-06 4.39525549734139e-06 -9.21036897021239e-06 3.55519091597212e-05 -1.76255671555198e-05 -3.06343027219247e-06 8.50605957659297e-06 -3.61237169833341e-05 -1.46340193158572e-05 -1.76255671555198e-05 0.000125529369078117 1.6211659086943e-05 8.04063733290313e-06 -3.45204943379299e-05 -5.1330376545049e-06 -3.06343027219247e-06 1.6211659086943e-05 5.94864036502174e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 864 0 0 0 0 0 2652 +1091 1129 0.999984019239191 0.00256975121155549 0.00503563749141308 0.00496557347387456 -0.00258079492890791 0.999994276404645 0.00218784265564084 0.00265327691561184 -0.0050299864581467 -0.00220080363995233 0.999984927736198 -0.00604194883317582 2.19021301113187e-05 -1.38919634168566e-05 -1.29588997695142e-05 4.53321060024073e-06 4.8573863983169e-06 1.17646222682442e-05 -1.38919634168566e-05 9.36718307213478e-05 2.00717798578442e-05 -3.73259811005784e-06 -2.28547907130212e-05 -4.50266551088232e-05 -1.29588997695142e-05 2.00717798578442e-05 2.19994475161348e-05 -9.07171624921881e-06 -1.11735994542186e-05 -1.05521617976883e-05 4.53321060024073e-06 -3.73259811005784e-06 -9.07171624921881e-06 3.73852382388156e-05 -2.99979321806594e-05 3.51459346558613e-06 4.8573863983169e-06 -2.28547907130212e-05 -1.11735994542186e-05 -2.99979321806594e-05 0.0001450391463651 5.18194349325973e-06 1.17646222682442e-05 -4.50266551088232e-05 -1.05521617976883e-05 3.51459346558613e-06 5.18194349325973e-06 5.25530399565397e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 957 0 0 0 0 0 2607 +1091 1138 0.999991718303179 0.00342466430198082 -0.00219886322320945 -0.00206415899468625 -0.00342354331305522 0.99999400788553 0.000513365579512473 0.0162210334481887 0.00220060815214333 -0.000505833424490243 0.999997450724904 0.00291230993882477 2.7320692164338e-05 -1.65671207451019e-05 -1.22865359725109e-05 1.65034724396206e-06 2.82378066216635e-06 8.88673513802337e-06 -1.65671207451019e-05 0.000131967418821048 1.79851916895914e-05 -4.29390225519187e-06 1.75174630221121e-05 -6.46501604594939e-05 -1.22865359725109e-05 1.79851916895914e-05 2.30114532371403e-05 -1.14432620230079e-05 -1.0171574059414e-05 -8.13037730482127e-06 1.65034724396206e-06 -4.29390225519187e-06 -1.14432620230079e-05 2.88524025238424e-05 -2.48825337276861e-06 2.89763208511314e-06 2.82378066216635e-06 1.75174630221121e-05 -1.0171574059414e-05 -2.48825337276861e-06 8.24885422462841e-05 -1.45372864469254e-05 8.88673513802337e-06 -6.46501604594939e-05 -8.13037730482127e-06 2.89763208511314e-06 -1.45372864469254e-05 5.45501895638304e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 941 0 0 0 0 0 2553 +1092 1094 0.999967543486678 -9.11551420796164e-05 0.00805628102530863 -0.0053870389669907 9.56514012590994e-05 0.999999839898194 -0.000557722508498835 0.0273873091350603 -0.00805622889620899 0.000558475001339815 0.999967392109185 0.00131944999366822 2.74953826431843e-05 -2.51590343886369e-05 -1.65443992453262e-05 6.67172502713412e-06 4.30820005072398e-06 2.40864899214102e-05 -2.51590343886369e-05 0.000123262579739637 2.51543763743225e-05 -1.28873034123109e-05 8.69709494252083e-06 -6.45926281845863e-05 -1.65443992453262e-05 2.51543763743225e-05 2.49175095720586e-05 -1.53767244986312e-05 -5.79180963780058e-06 -1.76199988416319e-05 6.67172502713412e-06 -1.28873034123109e-05 -1.53767244986312e-05 3.82953352762524e-05 -1.60995569671671e-05 1.06302465841312e-05 4.30820005072398e-06 8.69709494252083e-06 -5.79180963780058e-06 -1.60995569671671e-05 0.000111819049768904 3.40804647312667e-06 2.40864899214102e-05 -6.45926281845863e-05 -1.76199988416319e-05 1.06302465841312e-05 3.40804647312667e-06 6.95003185491883e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 863 0 0 0 0 0 2714 +1091 1131 0.99999256990754 0.00264398582571968 0.00280525732626864 0.00468983284562146 -0.00263927132830036 0.999995100923154 -0.00168296659110836 -0.00469666453829225 -0.00280969332290948 0.00167555025128125 0.999994649063077 -0.000111756229689786 2.64308931878601e-05 1.43076011916198e-06 -9.71552714091962e-06 9.61419440590222e-06 -5.61274287504981e-06 7.32469228567709e-06 1.43076011916198e-06 7.92779602242008e-05 1.03861271749447e-05 -5.68348563626311e-06 9.6669481382675e-06 -2.21684518376657e-05 -9.71552714091962e-06 1.03861271749447e-05 1.90239853151667e-05 -1.11074162039078e-05 -5.35810902625508e-06 -2.81680818423791e-06 9.61419440590222e-06 -5.68348563626311e-06 -1.11074162039078e-05 4.61112393663321e-05 -5.06672323526386e-05 -1.603972337453e-06 -5.61274287504981e-06 9.6669481382675e-06 -5.35810902625508e-06 -5.06672323526386e-05 0.000193060181177116 9.36045568657132e-08 7.32469228567709e-06 -2.21684518376657e-05 -2.81680818423791e-06 -1.603972337453e-06 9.36045568657132e-08 5.12748156937293e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 962 0 0 0 0 0 2576 +1091 1139 0.999960460066303 0.0029604173818204 0.0083853582459497 0.000698364921203844 -0.00298185257965967 0.999992315945943 0.00254491733891882 0.0173311516472839 -0.00837775979487822 -0.00256982061517303 0.99996160384428 -0.00650248694304026 2.36427254367681e-05 -1.8011588285158e-05 -1.48465889427381e-05 7.84190200313053e-06 9.5623584535005e-07 9.33181422477443e-06 -1.8011588285158e-05 0.000122418737416656 2.47955463406932e-05 -1.33889852221644e-05 1.37236426111616e-05 -5.86639944238384e-05 -1.48465889427381e-05 2.47955463406932e-05 2.44693775617259e-05 -1.316353897258e-05 -8.27159128264946e-06 -1.34063763416135e-05 7.84190200313053e-06 -1.33889852221644e-05 -1.316353897258e-05 2.82654686276277e-05 4.16918193095509e-06 8.86856536828811e-06 9.5623584535005e-07 1.37236426111616e-05 -8.27159128264946e-06 4.16918193095509e-06 6.18240806204056e-05 -1.05634425404542e-05 9.33181422477443e-06 -5.86639944238384e-05 -1.34063763416135e-05 8.86856536828811e-06 -1.05634425404542e-05 5.60069339623284e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 964 0 0 0 0 0 2638 +1091 1132 0.999996818650889 0.00249952203221241 0.000339231059358439 0.00338445715516919 -0.00249894280117373 0.999995437221359 -0.00169729824706825 -0.00400879276943654 -0.00034347194588599 0.00169644512835627 0.999998502049353 -6.33476622624182e-05 2.99813245435004e-05 -1.08631485098611e-05 -1.0563409768389e-05 7.68881006453142e-06 -6.35860659029445e-06 1.32455947895166e-05 -1.08631485098611e-05 0.000101894722089384 1.39093253472534e-05 -9.90839929097427e-06 1.84948189923305e-05 -4.12172896081242e-05 -1.0563409768389e-05 1.39093253472534e-05 2.13739920973932e-05 -1.5928996909871e-05 -3.15655238157644e-06 -4.2408291040088e-06 7.68881006453142e-06 -9.90839929097427e-06 -1.5928996909871e-05 4.31568552355501e-05 -2.87932088282205e-05 2.96791712938641e-06 -6.35860659029445e-06 1.84948189923305e-05 -3.15655238157644e-06 -2.87932088282205e-05 0.000134676247741203 -1.07667750810303e-05 1.32455947895166e-05 -4.12172896081242e-05 -4.2408291040088e-06 2.96791712938641e-06 -1.07667750810303e-05 6.14562325662437e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 960 0 0 0 0 0 2506 +1091 1136 0.999944479235678 0.00284010814333996 0.0101475234329597 0.0057631468598964 -0.00290403438419978 0.999975997697613 0.00629051770191749 0.00643846731007562 -0.0101294141184828 -0.00631963720453049 0.999928726037621 -0.0139396499107504 2.32709790409408e-05 -1.03085800561517e-05 -1.16127917048388e-05 5.43106291062321e-06 3.51056237130674e-06 1.2009307134019e-05 -1.03085800561517e-05 8.44421304925893e-05 1.99505727897805e-05 -1.16060955311608e-05 -1.37738303858639e-05 -2.31576276859615e-05 -1.16127917048388e-05 1.99505727897805e-05 2.33301858714143e-05 -1.34699774620313e-05 -1.24312295674429e-05 -3.17013061524721e-06 5.43106291062321e-06 -1.16060955311608e-05 -1.34699774620313e-05 3.4793949764124e-05 -2.12177989972128e-06 1.20825701637922e-06 3.51056237130674e-06 -1.37738303858639e-05 -1.24312295674429e-05 -2.12177989972128e-06 8.72537750309519e-05 9.34706400866069e-07 1.2009307134019e-05 -2.31576276859615e-05 -3.17013061524721e-06 1.20825701637922e-06 9.34706400866069e-07 5.23897395678594e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 879 0 0 0 0 0 2644 +1092 1096 0.999998228549791 0.00141224635410736 -0.00124437032891483 -0.00522588874312292 -0.00141251128841697 0.999998979922129 -0.000212053205806161 0.0167088427786713 0.00124406958819342 0.000213810517301029 0.999999203287644 -0.00088635970111734 2.84125163221827e-05 -2.03510815823726e-05 -1.22374609324694e-05 2.40895243553212e-06 5.50182293372682e-06 7.68524450854959e-06 -2.03510815823726e-05 0.000130602406832236 2.48197429852081e-05 -6.56155285481301e-07 -1.45262251671119e-05 -6.87630709079906e-05 -1.22374609324694e-05 2.48197429852081e-05 2.11683929573579e-05 -1.12469040178681e-05 -5.97170363038904e-06 -1.14941740665309e-05 2.40895243553212e-06 -6.56155285481301e-07 -1.12469040178681e-05 3.64625998638665e-05 -1.90822875175963e-05 8.43638548706079e-07 5.50182293372682e-06 -1.45262251671119e-05 -5.97170363038904e-06 -1.90822875175963e-05 9.16385836651797e-05 2.68342210123276e-06 7.68524450854959e-06 -6.87630709079906e-05 -1.14941740665309e-05 8.43638548706079e-07 2.68342210123276e-06 5.56217654023043e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 896 0 0 0 0 0 2538 +1092 1124 0.999996459152124 0.0026046495601224 0.000545420831834706 0.00637255963706145 -0.00260708742694168 0.999986396480857 0.00451773708600697 -0.00248874669473313 -0.000533646290278162 -0.00451914304918028 0.999989646230269 -0.0102397081980027 2.44893044033082e-05 -7.45855010249291e-06 -1.1562310036901e-05 3.81615664116406e-06 9.06705298089704e-06 1.29057840535035e-05 -7.45855010249291e-06 9.09099971718197e-05 2.01918697037524e-05 4.11627793216568e-06 -3.76652860853345e-05 -2.94271689395041e-05 -1.1562310036901e-05 2.01918697037524e-05 2.59537233938813e-05 -1.20678331637341e-05 -1.66835535003655e-05 -8.53997915425935e-06 3.81615664116406e-06 4.11627793216568e-06 -1.20678331637341e-05 4.55762843905419e-05 -2.72860289616378e-05 3.7692508781749e-07 9.06705298089704e-06 -3.76652860853345e-05 -1.66835535003655e-05 -2.72860289616378e-05 0.000166791860557421 1.54059772241475e-05 1.29057840535035e-05 -2.94271689395041e-05 -8.53997915425935e-06 3.7692508781749e-07 1.54059772241475e-05 6.69473661787711e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 933 0 0 0 0 0 2668 +1092 1122 0.999993047404944 0.00292591430483223 0.00231174549960751 0.00636274621794315 -0.00293708036213068 0.999983966097731 0.00484160163562873 -0.00218335438354719 -0.00229754232182212 -0.00484835775624227 0.999985607259598 -0.0108949699056767 2.83902709111199e-05 -1.54936868281438e-05 -1.29673495335122e-05 3.30812550673338e-06 5.07910773391857e-06 1.37954334630083e-05 -1.54936868281438e-05 0.000138209030931541 2.5496238603304e-05 1.50635073763178e-06 -1.88453652729543e-05 -5.87892392340047e-05 -1.29673495335122e-05 2.5496238603304e-05 2.48350899691455e-05 -9.83582863466926e-06 -1.25391501940495e-05 -1.11920252787575e-05 3.30812550673338e-06 1.50635073763178e-06 -9.83582863466926e-06 3.51624685075413e-05 -1.16374877273995e-05 -2.26548671697217e-06 5.07910773391857e-06 -1.88453652729543e-05 -1.25391501940495e-05 -1.16374877273995e-05 0.000104573902599103 8.57475625680492e-06 1.37954334630083e-05 -5.87892392340047e-05 -1.11920252787575e-05 -2.26548671697217e-06 8.57475625680492e-06 6.58689811618155e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 948 0 0 0 0 0 2534 +1092 1125 0.999973381470267 0.00321155532203814 0.00655150847767014 0.00570000605935408 -0.00324274647486879 0.999983433069724 0.00475585758707144 0.00579442271514379 -0.00653612623954137 -0.0047769758741559 0.999967229240678 -0.0121762989124789 2.488848736721e-05 -1.41929921612165e-05 -1.37906718378427e-05 6.61269181257191e-06 -1.40001976165297e-06 1.70570148483816e-05 -1.41929921612165e-05 8.56858896389231e-05 1.39067835272002e-05 -3.21849909842931e-06 -4.64079942731803e-06 -3.83360739214677e-05 -1.37906718378427e-05 1.39067835272002e-05 2.3002265512825e-05 -9.95807015103632e-06 -9.59669619144294e-06 -8.54496079688821e-06 6.61269181257191e-06 -3.21849909842931e-06 -9.95807015103632e-06 3.78399271261696e-05 -2.60106545078892e-05 4.10809653460879e-06 -1.40001976165297e-06 -4.64079942731803e-06 -9.59669619144294e-06 -2.60106545078892e-05 0.000151490583901909 -4.56335406080124e-06 1.70570148483816e-05 -3.83360739214677e-05 -8.54496079688821e-06 4.10809653460879e-06 -4.56335406080124e-06 7.43128021511262e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 941 0 0 0 0 0 2516 +1092 1123 0.999994914685599 0.00293164810105399 0.00125540525480159 0.00734307220171893 -0.00293529197379569 0.999991456172751 0.00291060861829248 -0.00377004024925735 -0.00124686164860724 -0.00291427879790084 0.999994976144939 -0.00482128073144394 2.92040631175176e-05 -2.83746120584174e-05 -1.37153588123413e-05 -2.45792178342539e-07 8.51352215377607e-06 2.04172049041277e-05 -2.83746120584174e-05 0.000138672175671054 2.67248651203966e-05 -1.59887018748939e-07 -1.97378479879998e-05 -5.9547774019038e-05 -1.37153588123413e-05 2.67248651203966e-05 2.54694867042405e-05 -1.34378936400822e-05 -1.29245116844321e-05 -8.97579183918721e-06 -2.45792178342539e-07 -1.59887018748939e-07 -1.34378936400822e-05 4.16050756695523e-05 -1.29397740696339e-05 -3.00859452293154e-06 8.51352215377607e-06 -1.97378479879998e-05 -1.29245116844321e-05 -1.29397740696339e-05 0.000112886246073712 2.34382485902112e-06 2.04172049041277e-05 -5.9547774019038e-05 -8.97579183918721e-06 -3.00859452293154e-06 2.34382485902112e-06 7.12737307746725e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 854 0 0 0 0 0 2727 +1092 1095 0.999974293536648 0.00064361214592592 0.00714129044969187 0.00202256664507267 -0.000660189717646474 0.999997092599238 0.00231925475275001 0.00891214960461499 -0.00713977698657021 -0.00232390973943832 0.999971811116746 -0.00358072267899359 2.92657850308937e-05 -1.09762790357638e-05 -1.02278923972721e-05 -1.77105380605593e-06 8.43387238315925e-06 4.71277404216623e-07 -1.09762790357638e-05 0.000119168588463609 2.44123849684028e-05 -1.50384670362493e-05 -6.72862757193479e-06 -6.57997049337193e-05 -1.02278923972721e-05 2.44123849684028e-05 2.2970064107546e-05 -1.22966131525086e-05 -1.02841159531904e-05 -8.23992978984177e-06 -1.77105380605593e-06 -1.50384670362493e-05 -1.22966131525086e-05 3.18878902690223e-05 3.91647084060931e-06 6.18614720404899e-06 8.43387238315925e-06 -6.72862757193479e-06 -1.02841159531904e-05 3.91647084060931e-06 7.04899451036187e-05 3.03850144100824e-06 4.71277404216623e-07 -6.57997049337193e-05 -8.23992978984177e-06 6.18614720404899e-06 3.03850144100824e-06 5.51330345900134e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 807 0 0 0 0 0 2598 +1092 1120 0.999994946088992 0.0024789080387492 0.00199068114210884 0.0101222290866428 -0.00248480396407876 0.999992517911549 0.00296477152257924 -0.013206588376479 -0.00198331685169608 -0.00296970299128094 0.999993623638876 -0.00375456288185089 2.59927761622667e-05 -1.81551047242922e-05 -1.52940451588731e-05 6.55345423585485e-06 -4.75140186348475e-07 1.72445234826331e-05 -1.81551047242922e-05 0.000108126300988648 1.61845726895577e-05 -1.03387147806731e-05 1.35185416245854e-05 -4.81267077182744e-05 -1.52940451588731e-05 1.61845726895577e-05 2.29555377122069e-05 -1.0427083111716e-05 -1.08325987194315e-05 -1.02140008251857e-05 6.55345423585485e-06 -1.03387147806731e-05 -1.0427083111716e-05 3.51784969520615e-05 -2.87298808943485e-05 8.65351517236758e-06 -4.75140186348475e-07 1.35185416245854e-05 -1.08325987194315e-05 -2.87298808943485e-05 0.000169712461448362 -5.81973420333714e-06 1.72445234826331e-05 -4.81267077182744e-05 -1.02140008251857e-05 8.65351517236758e-06 -5.81973420333714e-06 6.13013225057003e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 851 0 0 0 0 0 2625 +1092 1126 0.999973021886203 0.00188620835553189 0.00709913500468933 0.00794844601189495 -0.00189257661988197 0.999997812635507 0.000890436936848052 -0.00635180903846486 -0.00709743992670314 -0.000903848571470301 0.999974404374555 -0.00436971047934476 2.57116154144332e-05 -1.04395911925226e-05 -1.0440647913682e-05 4.65220214408657e-06 3.34998482886125e-06 1.94930147060405e-05 -1.04395911925226e-05 9.78886432434785e-05 2.02432233767575e-05 -1.14526438502349e-05 6.52490389561151e-06 -2.33875693317233e-05 -1.0440647913682e-05 2.02432233767575e-05 2.319442074603e-05 -1.34865350648573e-05 -6.73053678493683e-06 -4.12100005520598e-06 4.65220214408657e-06 -1.14526438502349e-05 -1.34865350648573e-05 3.69913243496166e-05 -8.90436200171775e-06 4.10584483927227e-06 3.34998482886125e-06 6.52490389561151e-06 -6.73053678493683e-06 -8.90436200171775e-06 8.99600174027627e-05 1.36300135730161e-06 1.94930147060405e-05 -2.33875693317233e-05 -4.12100005520598e-06 4.10584483927227e-06 1.36300135730161e-06 6.56275785073359e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 869 0 0 0 0 0 2743 +1092 1121 0.999996459285608 0.00262837354589161 -0.00041601532498019 0.00343942878255921 -0.00262734715713144 0.999993550188382 0.00244880145191456 -0.00414933066683633 0.000422449006715067 -0.00244769976472661 0.999996915146591 -0.00850854426449908 2.22851095987912e-05 -8.62003257291758e-06 -9.19257684965526e-06 4.6943573963075e-06 -6.29088370841349e-06 1.60140533642165e-05 -8.62003257291758e-06 8.47647652824727e-05 1.39954174054438e-05 -7.42231776932111e-06 6.31847679969168e-06 -2.64488002941868e-05 -9.19257684965526e-06 1.39954174054438e-05 1.83104904484985e-05 -9.18816002663537e-06 -6.74040515523664e-06 -4.32638306294398e-06 4.6943573963075e-06 -7.42231776932111e-06 -9.18816002663537e-06 3.36307431605206e-05 -1.94893329203229e-05 3.61625288278126e-06 -6.29088370841349e-06 6.31847679969168e-06 -6.74040515523664e-06 -1.94893329203229e-05 0.000117859372176588 -9.72854519241642e-06 1.60140533642165e-05 -2.64488002941868e-05 -4.32638306294398e-06 3.61625288278126e-06 -9.72854519241642e-06 6.44587121042831e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 958 0 0 0 0 0 2686 +1092 1119 0.999992104564198 0.00292358963585545 0.00269136264865649 0.00861487286419582 -0.00291860108801552 0.999994019230888 -0.00185560506137963 -0.0108609816247434 -0.00269677157996358 0.00184773539661438 0.999994656634199 -0.000438054081849808 2.48854148871711e-05 -1.44611322079782e-05 -1.07557934990918e-05 3.27061303186616e-06 8.02710828902763e-06 1.61362742644722e-05 -1.44611322079782e-05 0.000124255480723361 2.45043690572703e-05 -4.75200756083683e-06 -2.73061091991339e-05 -3.68739303722987e-05 -1.07557934990918e-05 2.45043690572703e-05 2.46704090464251e-05 -1.05133898045031e-05 -1.64162197612917e-05 -7.60662023533106e-06 3.27061303186616e-06 -4.75200756083683e-06 -1.05133898045031e-05 3.64648800787159e-05 -3.97885174939793e-06 -3.49178682202803e-06 8.02710828902763e-06 -2.73061091991339e-05 -1.64162197612917e-05 -3.97885174939793e-06 0.000106108691388409 1.06179665869744e-05 1.61362742644722e-05 -3.68739303722987e-05 -7.60662023533106e-06 -3.49178682202803e-06 1.06179665869744e-05 6.46223834054965e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 851 0 0 0 0 0 2697 +1092 1128 0.999991440904975 0.00208415838601723 0.00357412935051673 0.00710655888111003 -0.00208234929949267 0.999997701955912 -0.000509808091296151 -0.00633292326671616 -0.00357518365781864 0.000502361142050908 0.999993482826311 -0.00332480670152256 3.01522866971041e-05 -2.27940387284548e-05 -1.31172670795261e-05 7.42369275058605e-06 -4.05015506744379e-06 2.74094293470085e-05 -2.27940387284548e-05 0.000112020802996737 2.47044686499035e-05 -1.26040827175143e-05 1.90266747139398e-05 -4.87335522264503e-05 -1.31172670795261e-05 2.47044686499035e-05 2.67589925848813e-05 -1.28837820552206e-05 -5.80650088698921e-06 -1.17184493614683e-05 7.42369275058605e-06 -1.26040827175143e-05 -1.28837820552206e-05 3.78873228910629e-05 -8.50499697026792e-06 1.02531143871979e-05 -4.05015506744379e-06 1.90266747139398e-05 -5.80650088698921e-06 -8.50499697026792e-06 9.93871953815036e-05 -1.65181577604506e-05 2.74094293470085e-05 -4.87335522264503e-05 -1.17184493614683e-05 1.02531143871979e-05 -1.65181577604506e-05 8.12027852645816e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 873 0 0 0 0 0 2684 +1092 1130 0.999993127968885 0.00165444349993539 0.00331765454981333 0.00599338563560256 -0.00165450065811713 0.999998631207956 1.44840248177904e-05 -0.00519601366850453 -0.00331762604563346 -1.99729869191926e-05 0.999994496464106 -0.00360094783182996 2.35291230461537e-05 -8.41419499162079e-06 -1.16868490013848e-05 4.17757444383565e-07 1.27713318000584e-05 1.8935219085136e-05 -8.41419499162079e-06 8.90226327061205e-05 1.80752507640758e-05 -7.80728262835531e-07 -2.47050254656938e-05 -3.1757339866952e-05 -1.16868490013848e-05 1.80752507640758e-05 2.29857308808696e-05 -1.04915554378642e-05 -1.61222400785665e-05 -9.45105071962002e-06 4.17757444383565e-07 -7.80728262835531e-07 -1.04915554378642e-05 4.53241959663395e-05 -2.6545513603043e-05 2.47569710966282e-06 1.27713318000584e-05 -2.47050254656938e-05 -1.61222400785665e-05 -2.6545513603043e-05 0.000151568118041651 1.3215101024086e-05 1.8935219085136e-05 -3.1757339866952e-05 -9.45105071962002e-06 2.47569710966282e-06 1.3215101024086e-05 7.27442562231724e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 855 0 0 0 0 0 2735 +1092 1129 0.999993912322066 0.00343460859142566 -0.00061545319283729 0.00393021458700423 -0.00343292517776485 0.999990419856484 0.00271573562359659 0.00247984864353095 0.00062477478561222 -0.00271360628631133 0.99999612299118 -0.0059413839266435 3.14129740962208e-05 -6.50290043772378e-07 -1.02861157124462e-05 4.8157430973835e-06 8.21573109444358e-06 2.71793118865194e-05 -6.50290043772378e-07 8.7908220150398e-05 1.70005980291241e-05 -4.47381552444374e-06 -8.79814920560332e-06 -1.83666865562864e-05 -1.02861157124462e-05 1.70005980291241e-05 2.56077073281258e-05 -1.18524308558742e-05 -1.22256809448964e-05 -1.93690497772132e-07 4.8157430973835e-06 -4.47381552444374e-06 -1.18524308558742e-05 3.78123629836117e-05 -1.72989888273108e-05 -1.16515609585081e-06 8.21573109444358e-06 -8.79814920560332e-06 -1.22256809448964e-05 -1.72989888273108e-05 0.000124123704636967 8.10474430752288e-06 2.71793118865194e-05 -1.83666865562864e-05 -1.93690497772132e-07 -1.16515609585081e-06 8.10474430752288e-06 8.63080930587017e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 937 0 0 0 0 0 2450 +1092 1132 0.999977684684374 0.00196318057976375 0.00638561314909471 0.0017434677835759 -0.00200132936295643 0.999980157085204 0.00597328357209666 0.00381472427068232 -0.00637375980561091 -0.00598592999148419 0.999961771183318 -0.0151629865014645 2.62198649163249e-05 -1.65050122171813e-05 -1.16266642720541e-05 5.39473675098942e-06 -6.39579306238066e-06 1.84284504923308e-05 -1.65050122171813e-05 0.000102829100327581 1.90572673530954e-05 -1.36360466267205e-05 1.54852266013383e-05 -4.34128876211255e-05 -1.16266642720541e-05 1.90572673530954e-05 2.1362942036582e-05 -1.08178631332647e-05 -3.78831138963323e-06 -5.8624137686367e-06 5.39473675098942e-06 -1.36360466267205e-05 -1.08178631332647e-05 3.71036623102245e-05 -3.2194780697863e-05 5.38616200298409e-07 -6.39579306238066e-06 1.54852266013383e-05 -3.78831138963323e-06 -3.2194780697863e-05 0.000146154392920049 -6.49174441745642e-06 1.84284504923308e-05 -4.34128876211255e-05 -5.8624137686367e-06 5.38616200298409e-07 -6.49174441745642e-06 6.77373366030908e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 934 0 0 0 0 0 2468 +1092 1134 0.999991624597848 0.00334626043410969 0.0023565388313591 0.00737705278946784 -0.00334946447555388 0.999993469788294 0.00135700718304251 -0.00130289387470746 -0.00235198254321622 -0.00136488896066252 0.999996302621285 -0.00845365438038415 2.79293199808702e-05 -3.62854735761811e-05 -1.99071208641635e-05 9.37829018960857e-06 1.32640647479074e-06 2.3201802437469e-05 -3.62854735761811e-05 0.000167500424142288 3.54606468093697e-05 -1.36324370194016e-05 -1.51733067093093e-06 -7.01435854542164e-05 -1.99071208641635e-05 3.54606468093697e-05 3.03425025478913e-05 -1.76121446433095e-05 -1.07481301114047e-05 -1.71252224843681e-05 9.37829018960857e-06 -1.36324370194016e-05 -1.76121446433095e-05 3.69440603788736e-05 -4.50813510802888e-07 8.1894307541874e-06 1.32640647479074e-06 -1.51733067093093e-06 -1.07481301114047e-05 -4.50813510802888e-07 8.20762795615147e-05 -5.27609359557845e-06 2.3201802437469e-05 -7.01435854542164e-05 -1.71252224843681e-05 8.1894307541874e-06 -5.27609359557845e-06 7.29416885176669e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 842 0 0 0 0 0 2728 +1092 1139 0.999941176674831 0.00161073318779275 0.0107260770439288 0.00124918281104896 -0.00166844969450283 0.999984167108742 0.00537417970041641 0.0163179674507099 -0.0107172508495168 -0.00539175949326353 0.999928032142211 -0.0127174925004465 3.50392585229066e-05 -2.06324301389517e-05 -1.59919353267733e-05 7.64629756100767e-06 2.12789699792864e-06 3.46018764393654e-05 -2.06324301389517e-05 0.000115232924843762 1.93423308285687e-05 -7.35199348758588e-06 5.39744717766148e-06 -5.75254162743245e-05 -1.59919353267733e-05 1.93423308285687e-05 2.54663513512186e-05 -1.17853123651227e-05 -9.29462809351058e-06 -1.04374873364426e-05 7.64629756100767e-06 -7.35199348758588e-06 -1.17853123651227e-05 3.23933552807943e-05 8.49974756498241e-06 6.29237514359176e-06 2.12789699792864e-06 5.39744717766148e-06 -9.29462809351058e-06 8.49974756498241e-06 5.23600678507685e-05 -6.96919819392361e-06 3.46018764393654e-05 -5.75254162743245e-05 -1.04374873364426e-05 6.29237514359176e-06 -6.96919819392361e-06 9.40716901852237e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 937 0 0 0 0 0 2563 +1092 1138 0.999969669716134 0.00145474575286199 0.00765136344713378 -0.00408652159759334 -0.00146432826636459 0.999998150440051 0.00124693993639301 0.0211631207057302 -0.00764953531490185 -0.00125810622412264 0.999969950437609 -0.0032515743590056 5.03647630902224e-05 -3.95307014815899e-06 -1.05866054145019e-05 6.1368529912053e-06 -5.02483972172629e-06 5.06779954455198e-05 -3.95307014815899e-06 0.000103861109066256 1.65497546275696e-05 -7.9067314644415e-06 5.00143281921889e-06 -4.10955755463358e-05 -1.05866054145019e-05 1.65497546275696e-05 2.50153943698372e-05 -1.42371748502077e-05 -1.0998480180223e-05 -6.44773467902669e-06 6.1368529912053e-06 -7.9067314644415e-06 -1.42371748502077e-05 3.11544893531611e-05 3.55313235734473e-06 1.17683804198703e-05 -5.02483972172629e-06 5.00143281921889e-06 -1.0998480180223e-05 3.55313235734473e-06 7.26605703734952e-05 -1.48488823460114e-05 5.06779954455198e-05 -4.10955755463358e-05 -6.44773467902669e-06 1.17683804198703e-05 -1.48488823460114e-05 0.000121904256013814 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 933 0 0 0 0 0 2444 +1092 1131 0.999995072167594 0.00282147811293798 0.00137655431699754 -0.000786993215870414 -0.00282725651992528 0.99998712431929 0.00421400239764608 0.0119016250899517 -0.00136464687739085 -0.00421787350391626 0.999990173592723 -0.011799452544301 2.36632168609525e-05 -8.34734090014409e-06 -1.06796343616803e-05 5.1817958225523e-06 1.00980555614213e-06 1.58384775792219e-05 -8.34734090014409e-06 8.96459357408515e-05 1.52110359109314e-05 -3.28980656898715e-06 -1.40858799755324e-05 -3.39765291066771e-05 -1.06796343616803e-05 1.52110359109314e-05 2.1590775600513e-05 -1.01450770561908e-05 -1.41062038661404e-05 -8.06053112683141e-06 5.1817958225523e-06 -3.28980656898715e-06 -1.01450770561908e-05 4.42589663025031e-05 -4.53801852756571e-05 4.1709947992541e-06 1.00980555614213e-06 -1.40858799755324e-05 -1.41062038661404e-05 -4.53801852756571e-05 0.000201114081135637 -4.72200652568618e-06 1.58384775792219e-05 -3.39765291066771e-05 -8.06053112683141e-06 4.1709947992541e-06 -4.72200652568618e-06 6.78998549535189e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 943 0 0 0 0 0 2600 +1092 1127 0.999977817179767 0.00201559028490735 0.0063484284820738 0.00633743544583908 -0.00201726124677394 0.999997932349049 0.000256816449104489 -0.000300413683620965 -0.0063478977189998 -0.000269617190946169 0.999979815546854 -0.00594864200466263 2.97763282146243e-05 -2.47620340788655e-05 -1.23684144999432e-05 4.49719558096576e-06 -6.76463374796333e-06 2.90465340471368e-05 -2.47620340788655e-05 0.000146398986707589 2.48057300596844e-05 -1.73519464270237e-05 3.1183235863579e-05 -6.94280999269861e-05 -1.23684144999432e-05 2.48057300596844e-05 2.51605758808462e-05 -1.33700715449316e-05 -7.06423440530237e-06 -1.07023150457723e-05 4.49719558096576e-06 -1.73519464270237e-05 -1.33700715449316e-05 3.78837290600901e-05 -1.47761293910665e-05 8.43584422699524e-06 -6.76463374796333e-06 3.1183235863579e-05 -7.06423440530237e-06 -1.47761293910665e-05 0.000135345004949759 -1.47417384307985e-05 2.90465340471368e-05 -6.94280999269861e-05 -1.07023150457723e-05 8.43584422699524e-06 -1.47417384307985e-05 9.00633814271123e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 867 0 0 0 0 0 2776 +1092 1137 0.999970168932783 0.00274016236308195 0.00722168642108817 0.00481945175578497 -0.0027660142752131 0.999989794196167 0.0035722077958955 0.00714269172202562 -0.00721182428861779 -0.00359207652085647 0.999967542761613 -0.00837236776478496 2.71199390813415e-05 -8.17467894507933e-06 -1.19284796438858e-05 5.9654452837082e-06 2.97711152050226e-06 1.27830621770347e-05 -8.17467894507933e-06 0.000120532548571716 2.37162208517526e-05 -8.33249016315604e-06 -1.27823361539417e-05 -3.36460478736924e-05 -1.19284796438858e-05 2.37162208517526e-05 2.68430907859299e-05 -1.24527483117729e-05 -1.47338542726126e-05 -5.40074186059322e-06 5.9654452837082e-06 -8.33249016315604e-06 -1.24527483117729e-05 3.29972620351514e-05 4.35408949863767e-06 3.5868656321027e-06 2.97711152050226e-06 -1.27823361539417e-05 -1.47338542726126e-05 4.35408949863767e-06 7.77778588460693e-05 2.98940705380468e-06 1.27830621770347e-05 -3.36460478736924e-05 -5.40074186059322e-06 3.5868656321027e-06 2.98940705380468e-06 5.41784259944456e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 935 0 0 0 0 0 2569 +1093 1095 0.999999405207371 0.000621032543611646 -0.000896606649123956 -0.01036813205959 -0.000621014860119834 0.999999806970234 2.00009548491883e-05 0.0293786132152337 0.000896618897296049 -1.94441368999796e-05 0.999999597848159 -0.000382766523974582 2.82134387866693e-05 -3.86173603452478e-05 -1.58738682865348e-05 7.10040912006717e-06 -9.38168795205005e-07 2.05151526395801e-05 -3.86173603452478e-05 0.000169759808362269 3.93202058543358e-05 -2.21855690037472e-05 1.0541482777004e-05 -9.84562786499192e-05 -1.58738682865348e-05 3.93202058543358e-05 2.83867837305946e-05 -2.05581760304898e-05 -5.33645700317119e-06 -1.93958073833586e-05 7.10040912006717e-06 -2.21855690037472e-05 -2.05581760304898e-05 4.47889595845297e-05 -2.47111693358193e-05 1.0349598398975e-05 -9.38168795205005e-07 1.0541482777004e-05 -5.33645700317119e-06 -2.47111693358193e-05 0.000116205333045704 -8.55523851978972e-06 2.05151526395801e-05 -9.84562786499192e-05 -1.93958073833586e-05 1.0349598398975e-05 -8.55523851978972e-06 7.69479433474636e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 886 0 0 0 0 0 2628 +1093 1097 0.999994002876089 -0.000146275641915839 0.00346017561591422 -0.00270289777371009 0.000139558119570409 0.999998105464001 0.00194154370009365 0.00587128512687694 -0.00346045306103799 -0.00194104916081316 0.999992128765406 -0.00462846838174873 3.41274600536059e-05 -3.65653010175163e-05 -1.68541906621989e-05 5.19735022056456e-06 7.71184091762621e-06 2.81896565397586e-05 -3.65653010175163e-05 0.000182741992154383 2.7486932762472e-05 -1.35515412272058e-05 1.18575699701647e-05 -0.000131972597007977 -1.68541906621989e-05 2.7486932762472e-05 2.78730735776496e-05 -1.7281573617921e-05 -1.33831945802974e-05 -1.79085750101896e-05 5.19735022056456e-06 -1.35515412272058e-05 -1.7281573617921e-05 3.45189067136622e-05 1.03222219974052e-05 9.03229467710842e-06 7.71184091762621e-06 1.18575699701647e-05 -1.33831945802974e-05 1.03222219974052e-05 6.90022712134149e-05 -1.41329181292723e-05 2.81896565397586e-05 -0.000131972597007977 -1.79085750101896e-05 9.03229467710842e-06 -1.41329181292723e-05 0.0001202352651312 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 892 0 0 0 0 0 2569 +1093 1120 0.99999375447371 0.0015782306540739 0.00316230953197302 0.00659472782563512 -0.00158596261215347 0.999995755732628 0.00244402113806415 -0.00696007137149064 -0.00315843888120655 -0.00244902117855164 0.999992013247656 -0.0058620554749666 2.21378989295291e-05 -1.50201988797615e-05 -1.6638222228863e-05 9.22226096108377e-06 3.47857205597616e-06 1.06898002193266e-05 -1.50201988797615e-05 8.94832358344138e-05 1.71372123637125e-05 -1.70658245623164e-05 7.77904319524203e-06 -3.90123730203014e-05 -1.6638222228863e-05 1.71372123637125e-05 2.37453106912525e-05 -1.35508609306758e-05 -1.07781822783869e-05 -9.04506685618727e-06 9.22226096108377e-06 -1.70658245623164e-05 -1.35508609306758e-05 3.44460460070539e-05 -1.64610149957934e-05 8.80695311124575e-06 3.47857205597616e-06 7.77904319524203e-06 -1.07781822783869e-05 -1.64610149957934e-05 0.000123718088475502 -1.2962016847179e-05 1.06898002193266e-05 -3.90123730203014e-05 -9.04506685618727e-06 8.80695311124575e-06 -1.2962016847179e-05 5.60811194989074e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2683 +1093 1123 0.999993103261404 0.00129721744608067 0.00348003685693418 0.00479021251318999 -0.00130585937802004 0.99999606678471 0.00248216566640221 -0.00447139548616771 -0.00347680326059348 -0.00248669298631994 0.999990864056807 -0.00655441424323205 2.30541394722809e-05 -1.55548917472009e-05 -1.13048756092301e-05 6.75566057601621e-06 -8.60953417915854e-06 1.3099311427549e-05 -1.55548917472009e-05 9.80854057858057e-05 2.1528377500665e-05 -2.01527341780062e-05 5.64410004363196e-07 -3.95285046788453e-05 -1.13048756092301e-05 2.1528377500665e-05 2.39317227199168e-05 -1.37546260656952e-05 -1.35222040768766e-05 -4.82817519634101e-06 6.75566057601621e-06 -2.01527341780062e-05 -1.37546260656952e-05 4.75636749352049e-05 -4.90492293553701e-05 8.91264508119026e-06 -8.60953417915854e-06 5.64410004363196e-07 -1.35222040768766e-05 -4.90492293553701e-05 0.000226930662345051 -2.30353324748961e-05 1.3099311427549e-05 -3.95285046788453e-05 -4.82817519634101e-06 8.91264508119026e-06 -2.30353324748961e-05 5.6933154694535e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 820 0 0 0 0 0 2756 +1093 1119 0.999955639356101 0.000599623651158925 0.00939998784081993 0.00697376366905583 -0.000611305159329276 0.999999044487316 0.00123989130892883 -0.01231665117986 -0.00939923539085861 -0.00124558256761673 0.999955050438836 -0.00108990064612584 2.95560139661285e-05 -1.83431805353147e-05 -1.39260816349359e-05 5.3762588232418e-06 1.64989972701063e-06 1.71670331527057e-05 -1.83431805353147e-05 0.000139597399197472 3.27314866711833e-05 -1.28411048266467e-05 -5.12323246429673e-07 -5.75528460828103e-05 -1.39260816349359e-05 3.27314866711833e-05 3.06443956385977e-05 -1.67669050527779e-05 -8.8687923364905e-06 -1.19048080326367e-05 5.3762588232418e-06 -1.28411048266467e-05 -1.67669050527779e-05 3.58245594309548e-05 -1.20161477685759e-05 4.98574209314642e-06 1.64989972701063e-06 -5.12323246429673e-07 -8.8687923364905e-06 -1.20161477685759e-05 9.84220370690009e-05 -9.33924075099091e-06 1.71670331527057e-05 -5.75528460828103e-05 -1.19048080326367e-05 4.98574209314642e-06 -9.33924075099091e-06 6.64478911333543e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 833 0 0 0 0 0 2625 +1093 1122 0.999980045297684 0.00202585351063458 -0.00598372158398336 0.00393722553853868 -0.00201333658473351 0.99999577428735 0.00209711307291798 -0.00582763589267754 0.00598794474237633 -0.002085023980073 0.999979898394345 -0.00362004310345706 2.74917968761424e-05 -1.55492569552023e-05 -1.24547660867593e-05 2.34902906543175e-06 4.26132349683158e-06 1.35158120985276e-05 -1.55492569552023e-05 0.000120249845702951 2.2328923944418e-05 -8.35493443758579e-06 -3.99017034979186e-06 -5.36427725130996e-05 -1.24547660867593e-05 2.2328923944418e-05 2.50139879131051e-05 -1.35168160871723e-05 -8.55519114838194e-06 -7.75922752186407e-06 2.34902906543175e-06 -8.35493443758579e-06 -1.35168160871723e-05 3.64908415681425e-05 -9.70683190719191e-06 -8.83050166724935e-07 4.26132349683158e-06 -3.99017034979186e-06 -8.55519114838194e-06 -9.70683190719191e-06 8.31659354778412e-05 -9.95353550878835e-08 1.35158120985276e-05 -5.36427725130996e-05 -7.75922752186407e-06 -8.83050166724935e-07 -9.95353550878835e-08 7.52259215639139e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 911 0 0 0 0 0 2467 +1093 1125 0.999996005702446 0.00199317123967229 0.00200395797428081 0.00476134296907531 -0.00199926274621408 0.999993373525184 0.00304234353652286 -0.00335589487133459 -0.00199788078346556 -0.00304633782302047 0.999993364127104 -0.0103767058314052 2.96657868052911e-05 -2.23290191031908e-05 -1.56648264557262e-05 7.4268872301523e-06 -1.58197619221071e-07 2.45641640353276e-05 -2.23290191031908e-05 0.000110736415682311 1.58287441032996e-05 -8.12835210562612e-06 6.95396010812624e-06 -4.66362173035808e-05 -1.56648264557262e-05 1.58287441032996e-05 2.40280162602985e-05 -1.20018628859094e-05 -1.21724493999955e-05 -8.36049586731293e-06 7.4268872301523e-06 -8.12835210562612e-06 -1.20018628859094e-05 3.56834472485592e-05 -1.30663708496097e-05 4.33555917450271e-06 -1.58197619221071e-07 6.95396010812624e-06 -1.21724493999955e-05 -1.30663708496097e-05 0.000123732412182252 -7.68060898624064e-06 2.45641640353276e-05 -4.66362173035808e-05 -8.36049586731293e-06 4.33555917450271e-06 -7.68060898624064e-06 7.11154641429663e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 902 0 0 0 0 0 2573 +1093 1121 0.999970228855414 0.00125614226472899 0.00761337700776717 0.00377725180733271 -0.0012832259085294 0.999992862832646 0.00355353556855463 -0.00438151895249827 -0.00760885892360445 -0.00356319945836119 0.99996470381484 -0.0122777900137232 2.68019218579884e-05 -1.52865628654615e-05 -1.2314047069457e-05 2.14994579618777e-06 1.01702586908906e-05 1.57235038088169e-05 -1.52865628654615e-05 9.9753424929004e-05 1.76840355907674e-05 1.55936609318288e-06 -1.68902436063548e-05 -4.13794337965197e-05 -1.2314047069457e-05 1.76840355907674e-05 2.22322446960372e-05 -1.04758106548559e-05 -1.22961594066561e-05 -7.42050988805352e-06 2.14994579618777e-06 1.55936609318288e-06 -1.04758106548559e-05 3.83054973120365e-05 -1.9500214649454e-05 -5.15553618621914e-06 1.01702586908906e-05 -1.68902436063548e-05 -1.22961594066561e-05 -1.9500214649454e-05 0.000113013356770138 7.91869549933494e-06 1.57235038088169e-05 -4.13794337965197e-05 -7.42050988805352e-06 -5.15553618621914e-06 7.91869549933494e-06 7.14225240933747e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 910 0 0 0 0 0 2604 +1093 1096 0.999935718981198 -0.000918842809062406 0.0113010456793633 -0.011272351560267 0.00087325982600384 0.999991466788478 0.00403779240474556 0.0371449737019114 -0.0113046593416657 -0.00402766410215245 0.999927988706711 -0.0102379482611551 3.60082541156682e-05 -2.31166261941778e-06 -1.21700714642162e-05 2.3946326223367e-06 6.52556791223934e-06 9.96638445441225e-07 -2.31166261941778e-06 0.000105428194477989 2.20446779314128e-05 -5.4570642910737e-06 -1.18321362015422e-05 -6.36639927781429e-05 -1.21700714642162e-05 2.20446779314128e-05 2.4291880411757e-05 -1.12162444587109e-05 -1.22193901844038e-05 -1.16350341730267e-05 2.3946326223367e-06 -5.4570642910737e-06 -1.12162444587109e-05 4.63501237123054e-05 -3.99843632608739e-05 7.92889135416517e-06 6.52556791223934e-06 -1.18321362015422e-05 -1.22193901844038e-05 -3.99843632608739e-05 0.000157778333061197 -4.29295089969765e-06 9.96638445441225e-07 -6.36639927781429e-05 -1.16350341730267e-05 7.92889135416517e-06 -4.29295089969765e-06 5.84983538628081e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 933 0 0 0 0 0 2555 +1093 1124 0.999996492842113 0.00242403864052137 -0.00106693024316635 0.00312875013035674 -0.00242043678615628 0.999991411289714 0.00336434727240688 -0.000135902051765693 0.00107507638740004 -0.00336175303590099 0.999993771394246 -0.0082601683860346 2.65014835300961e-05 -1.59768674029959e-05 -1.31766351762243e-05 5.25905503063526e-06 5.56309063746356e-06 1.61937562787015e-05 -1.59768674029959e-05 9.80823598781567e-05 1.87036782465331e-05 -7.79462404423371e-06 -1.44454552563626e-05 -3.7984150166593e-05 -1.31766351762243e-05 1.87036782465331e-05 1.97930925965517e-05 -9.45045518614353e-06 -1.2201593356468e-05 -7.91892975008706e-06 5.25905503063526e-06 -7.79462404423371e-06 -9.45045518614353e-06 3.44953120263684e-05 -1.29865294129277e-05 -1.04779730251786e-07 5.56309063746356e-06 -1.44454552563626e-05 -1.2201593356468e-05 -1.29865294129277e-05 0.000105656594920845 1.67127498186061e-05 1.61937562787015e-05 -3.7984150166593e-05 -7.91892975008706e-06 -1.04779730251786e-07 1.67127498186061e-05 6.21214523931659e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 904 0 0 0 0 0 2768 +1093 1129 0.999993441389767 0.00201456711923935 0.00300976689690418 0.00436485794872863 -0.00202698002918128 0.999989430101959 0.00412686761615808 -0.00317254553203582 -0.00300142123216999 -0.00413294128703442 0.999986955048367 -0.0103892957520213 3.67085655497719e-05 -1.21058630985594e-05 -1.28260118560072e-05 1.22530991308541e-05 -9.7338851835704e-06 3.54603605194965e-05 -1.21058630985594e-05 0.00011988446608763 1.91159275714712e-05 -1.8490836392782e-05 2.13736559603984e-05 -4.99898862484225e-05 -1.28260118560072e-05 1.91159275714712e-05 2.34526904988218e-05 -1.45947527096201e-05 -8.55823162242534e-06 -7.25322905461575e-06 1.22530991308541e-05 -1.8490836392782e-05 -1.45947527096201e-05 4.16087207580186e-05 -1.98287720676833e-05 1.48302662038168e-05 -9.7338851835704e-06 2.13736559603984e-05 -8.55823162242534e-06 -1.98287720676833e-05 0.000131065929318265 -3.31188849246038e-05 3.54603605194965e-05 -4.99898862484225e-05 -7.25322905461575e-06 1.48302662038168e-05 -3.31188849246038e-05 0.000102709159071614 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 902 0 0 0 0 0 2565 +1093 1127 0.999985500757814 0.002508815319702 -0.00476488403169881 0.00381340223491538 -0.00252223925850521 0.999992861665571 -0.00281334800992978 -0.00328758471193113 0.00475779184777611 0.0028253253960826 0.999984690359377 0.00169755332484304 2.69080361427413e-05 -2.60632905287037e-06 -9.72074311999743e-06 4.67164280167661e-06 -6.13363524275497e-07 8.30502882421361e-06 -2.60632905287037e-06 8.50219618655877e-05 1.32482942503588e-05 -4.27375590810622e-06 -7.03908657952226e-06 -3.22128525981291e-05 -9.72074311999743e-06 1.32482942503588e-05 2.01289734816714e-05 -1.03345972703863e-05 -5.44826218872578e-06 -4.13168096161149e-06 4.67164280167661e-06 -4.27375590810622e-06 -1.03345972703863e-05 3.5347101694262e-05 -1.77621148077625e-05 6.20911960236618e-07 -6.13363524275497e-07 -7.03908657952226e-06 -5.44826218872578e-06 -1.77621148077625e-05 9.64715386270192e-05 -4.98831601484011e-06 8.30502882421361e-06 -3.22128525981291e-05 -4.13168096161149e-06 6.20911960236618e-07 -4.98831601484011e-06 6.87598522715565e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 846 0 0 0 0 0 2717 +1093 1128 0.999991975288107 0.0012742360580201 0.00379811556662562 0.00470786202999426 -0.00127346613762149 0.999999168103999 -0.000205122659363794 -0.00668860757610749 -0.00379837378167735 0.000200284241752679 0.999992766095254 -0.00424077387352859 3.13374097715339e-05 -1.4980446410101e-05 -1.440595577742e-05 5.90436668446698e-06 1.07523606298429e-05 1.82639092415148e-05 -1.4980446410101e-05 0.000110423657245088 2.42908985430655e-05 -3.78377348797927e-06 -3.0973737242529e-05 -4.50492914121934e-05 -1.440595577742e-05 2.42908985430655e-05 2.714880973003e-05 -1.46823181590464e-05 -1.03602027761668e-05 -1.00589626645674e-05 5.90436668446698e-06 -3.78377348797927e-06 -1.46823181590464e-05 4.23109075344554e-05 -2.57578303937087e-05 -2.34014902020306e-07 1.07523606298429e-05 -3.0973737242529e-05 -1.03602027761668e-05 -2.57578303937087e-05 0.000115341620643093 1.41097244633552e-05 1.82639092415148e-05 -4.50492914121934e-05 -1.00589626645674e-05 -2.34014902020306e-07 1.41097244633552e-05 7.12182379975534e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 830 0 0 0 0 0 2567 +1093 1135 0.999997725794296 0.00207508231336267 -0.000492381588267954 0.00415927978286488 -0.00207355750039775 0.999993115043626 0.00307737300930694 -0.00954135260308454 0.000498764000545431 -0.00307634502919228 0.999995143656074 -0.00571666209003477 4.44193827828962e-05 -7.53536113009228e-06 -1.05820868134702e-05 6.74409312648855e-06 -3.47423667009995e-06 3.8358724761995e-05 -7.53536113009228e-06 0.000119566038428422 2.08428149712057e-05 -6.4509062923785e-06 7.35596303352574e-07 -5.41480449302948e-05 -1.05820868134702e-05 2.08428149712057e-05 2.12232277028576e-05 -8.37672949077821e-06 -5.84846948159826e-06 -7.04373214213409e-06 6.74409312648855e-06 -6.4509062923785e-06 -8.37672949077821e-06 3.53700229044184e-05 -2.33936883125839e-05 1.00516867062589e-05 -3.47423667009995e-06 7.35596303352574e-07 -5.84846948159826e-06 -2.33936883125839e-05 0.000119040998904327 -2.12857690239311e-05 3.8358724761995e-05 -5.41480449302948e-05 -7.04373214213409e-06 1.00516867062589e-05 -2.12857690239311e-05 0.000115902699792934 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 896 0 0 0 0 0 2617 +1093 1126 0.999995966028926 0.00145208043982821 0.00244118583308913 0.00481084625381321 -0.00144966273002436 0.999998457343422 -0.00099186125329271 -0.0054979151878461 -0.00244262232950267 0.000988318356033812 0.999996528405465 -0.00256505409738367 2.73206364153873e-05 -1.58541773386281e-05 -1.08470417892589e-05 3.23651420073399e-06 2.25550642880715e-06 1.94820884750452e-05 -1.58541773386281e-05 0.000116511021470435 2.47217797359525e-05 -1.54749150178347e-05 -3.46550661592068e-06 -5.12525406395829e-05 -1.08470417892589e-05 2.47217797359525e-05 2.38701897820257e-05 -1.25197901382258e-05 -7.32980323281376e-06 -1.06793367478487e-05 3.23651420073399e-06 -1.54749150178347e-05 -1.25197901382258e-05 3.34837243574115e-05 -1.19523266366337e-05 8.35840719443261e-06 2.25550642880715e-06 -3.46550661592068e-06 -7.32980323281376e-06 -1.19523266366337e-05 8.82836439195906e-05 -1.75419243783368e-06 1.94820884750452e-05 -5.12525406395829e-05 -1.06793367478487e-05 8.35840719443261e-06 -1.75419243783368e-06 7.38700552032529e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 846 0 0 0 0 0 2758 +1093 1130 0.999994487895934 0.00163260781182711 0.00289115365932905 0.00593003029277194 -0.00162953952742613 0.99999810699068 -0.00106330427672504 -0.0107463882774752 -0.00289288414521676 0.00105858716651348 0.999995255296011 -0.00469456480629439 3.06010976010059e-05 -1.66897986200862e-05 -1.17506584056441e-05 2.41821795011533e-06 1.16620246282476e-05 2.06556505163911e-05 -1.66897986200862e-05 0.000130921269370211 2.42311555608512e-05 1.96558128003716e-07 -2.89452989686224e-05 -6.00473334036345e-05 -1.17506584056441e-05 2.42311555608512e-05 2.50772032119792e-05 -9.18590083765107e-06 -1.76123480329098e-05 -7.71467340830318e-06 2.41821795011533e-06 1.96558128003716e-07 -9.18590083765107e-06 3.77991926946853e-05 -2.00768693835247e-05 -7.09571069892743e-06 1.16620246282476e-05 -2.89452989686224e-05 -1.76123480329098e-05 -2.00768693835247e-05 0.000143016912664553 1.12311023263582e-05 2.06556505163911e-05 -6.00473334036345e-05 -7.71467340830318e-06 -7.09571069892743e-06 1.12311023263582e-05 8.66164720282e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 825 0 0 0 0 0 2644 +1093 1137 0.999997418228176 0.00217660541996126 0.000652629931563892 0.00689235394504836 -0.00217833514982193 0.999994085600419 0.00266150712146269 -0.00743036192353196 -0.000646833020823857 -0.00266292189677835 0.999996245219958 -0.00237609365343214 3.84368559182747e-05 -4.61678456976555e-05 -1.893997921723e-05 5.87367702832528e-06 7.25541237129711e-06 3.01340753089425e-05 -4.61678456976555e-05 0.00022293328372282 4.45020857627189e-05 -7.34175326733707e-06 -1.28719536206218e-05 -0.000122302722640349 -1.893997921723e-05 4.45020857627189e-05 2.94829348408649e-05 -1.39668314639904e-05 -1.38782167539691e-05 -2.02452839357509e-05 5.87367702832528e-06 -7.34175326733707e-06 -1.39668314639904e-05 3.7681139131932e-05 -7.1967486497406e-06 1.63660110606705e-06 7.25541237129711e-06 -1.28719536206218e-05 -1.38782167539691e-05 -7.1967486497406e-06 0.000102811122653827 4.15786362052162e-06 3.01340753089425e-05 -0.000122302722640349 -2.02452839357509e-05 1.63660110606705e-06 4.15786362052162e-06 0.000103410517912939 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 903 0 0 0 0 0 2641 +1093 1133 0.999988455541568 0.00201071324685851 -0.00436415121517511 0.00665798584956034 -0.00200801471884542 0.999997790099874 0.000622633324582772 -0.0108613347435583 0.00436539350791047 -0.000613862856742899 0.999990283208749 -0.00332611108966865 2.75390736473505e-05 -1.78009108237651e-05 -1.51992802457982e-05 3.97599467483772e-06 5.33657292131471e-06 1.26811616982658e-05 -1.78009108237651e-05 0.000100522581852885 1.46155463959043e-05 -3.08450103276609e-06 -1.57761333792796e-05 -4.94761990777151e-05 -1.51992802457982e-05 1.46155463959043e-05 2.3756981094819e-05 -1.542508264193e-05 -6.57581003972382e-06 -8.46093890449403e-06 3.97599467483772e-06 -3.08450103276609e-06 -1.542508264193e-05 4.30960682869646e-05 -2.33199599048983e-05 -3.01333418369437e-06 5.33657292131471e-06 -1.57761333792796e-05 -6.57581003972382e-06 -2.33199599048983e-05 0.000122436855600362 1.06292292111892e-05 1.26811616982658e-05 -4.94761990777151e-05 -8.46093890449403e-06 -3.01333418369437e-06 1.06292292111892e-05 6.1527104261266e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 812 0 0 0 0 0 2527 +1094 1096 0.999997227129236 0.000745402164283012 0.00223385528895693 -0.0111365174712833 -0.000742578756790675 0.999998924833095 -0.00126447991035374 0.0321286722540965 -0.00223479543325152 0.00126281759063104 0.999996705485125 0.000524706229107072 4.29434936225862e-05 -3.96973122247991e-05 -1.82642496785557e-05 4.80891478119675e-06 -3.62583099817271e-06 3.11234708602227e-05 -3.96973122247991e-05 0.000172764268342998 3.47937130287144e-05 -9.91075425827539e-06 3.33947486083403e-06 -0.00011485885047319 -1.82642496785557e-05 3.47937130287144e-05 2.93014160365645e-05 -1.55081901255547e-05 -1.07112505941862e-05 -1.94339872767962e-05 4.80891478119675e-06 -9.91075425827539e-06 -1.55081901255547e-05 3.48205979458663e-05 -7.54559106483888e-06 6.78080570551311e-06 -3.62583099817271e-06 3.33947486083403e-06 -1.07112505941862e-05 -7.54559106483888e-06 7.81680429915211e-05 -1.31140423603384e-05 3.11234708602227e-05 -0.00011485885047319 -1.94339872767962e-05 6.78080570551311e-06 -1.31140423603384e-05 0.000106091098702612 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 975 0 0 0 0 0 2518 +1093 1131 0.999976504513496 0.00159164790710184 0.00666761410920513 0.00107195042212204 -0.00162627541134436 0.999985203282857 0.00519118903816496 0.00754959675082172 -0.00665925290523717 -0.00520191044553111 0.999964296601864 -0.0135474556744924 2.73786354338034e-05 -1.1283012215552e-05 -1.13029873966051e-05 5.83207954447129e-06 -7.81097271089483e-07 1.17515563880067e-05 -1.1283012215552e-05 9.35822160896754e-05 1.83181731040822e-05 -1.5122358548967e-05 3.66810390034069e-06 -3.8173414810775e-05 -1.13029873966051e-05 1.83181731040822e-05 2.17409591532501e-05 -1.09199733803615e-05 -1.17958545013077e-05 -5.84382071852479e-06 5.83207954447129e-06 -1.5122358548967e-05 -1.09199733803615e-05 3.62176111511217e-05 -2.38423868668097e-05 4.67604549900542e-06 -7.81097271089483e-07 3.66810390034069e-06 -1.17958545013077e-05 -2.38423868668097e-05 0.000152977624533361 -8.50492884547015e-06 1.17515563880067e-05 -3.8173414810775e-05 -5.84382071852479e-06 4.67604549900542e-06 -8.50492884547015e-06 5.68509294901857e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 907 0 0 0 0 0 2646 +1094 1097 0.999975652398249 -3.23856027798121e-05 0.0069780772329728 -0.00868818992971113 2.88585461446708e-05 0.999999871794039 0.000505548305317303 0.0243862715650944 -0.00697809271082831 -0.00050533461926467 0.999975525130011 -0.00411282842302927 3.13461492084424e-05 -1.73918012986705e-05 -1.76535462038993e-05 1.03487827683568e-05 -3.83870278334338e-06 1.12049228215359e-05 -1.73918012986705e-05 0.000106281692788825 2.09908253148543e-05 -1.89737640723117e-05 1.99386356799348e-05 -6.72447427306268e-05 -1.76535462038993e-05 2.09908253148543e-05 2.72397786402548e-05 -1.55094894814976e-05 -7.13011216091871e-06 -1.36885046957435e-05 1.03487827683568e-05 -1.89737640723117e-05 -1.55094894814976e-05 3.74328984208813e-05 -1.14970509880909e-05 1.72428776026289e-05 -3.83870278334338e-06 1.99386356799348e-05 -7.13011216091871e-06 -1.14970509880909e-05 0.0001030422705185 -1.73836281670442e-05 1.12049228215359e-05 -6.72447427306268e-05 -1.36885046957435e-05 1.72428776026289e-05 -1.73836281670442e-05 6.15243109479944e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 927 0 0 0 0 0 2626 +1093 1132 0.999997554113253 0.00189886217949033 0.0011340590527658 0.000826212199712071 -0.00190230231244667 0.999993569396288 0.00304013354692165 0.00454519640766374 -0.00112827896546859 -0.00304228343425783 0.999994735735185 -0.0131880270759979 2.69508566635678e-05 -1.20561090754642e-05 -1.28965298081436e-05 5.89820868536794e-06 -1.41749518947895e-06 1.30092349789098e-05 -1.20561090754642e-05 0.000106875557918657 2.02550943858683e-05 -9.96339177499689e-06 -3.08128419132467e-06 -4.76110247846536e-05 -1.28965298081436e-05 2.02550943858683e-05 2.5328577884337e-05 -1.39119295346537e-05 -9.80730688696373e-06 -6.33856766903965e-06 5.89820868536794e-06 -9.96339177499689e-06 -1.39119295346537e-05 3.47799195349822e-05 -9.26530977226041e-06 -1.10991251984968e-06 -1.41749518947895e-06 -3.08128419132467e-06 -9.80730688696373e-06 -9.26530977226041e-06 9.28494928753211e-05 2.89391862004617e-06 1.30092349789098e-05 -4.76110247846536e-05 -6.33856766903965e-06 -1.10991251984968e-06 2.89391862004617e-06 7.84434589447105e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 915 0 0 0 0 0 2396 +1094 1120 0.999976188140985 0.00253010970479066 -0.00642041244060608 0.00276469945002026 -0.0025105450666559 0.999992186657714 0.00305348767671152 -0.00449464753774631 0.00642808793453037 -0.00303729623271479 0.999974726939187 -0.00298831664983669 2.15609476759748e-05 -5.45966558450785e-06 -1.02565297794035e-05 5.27549193160313e-06 -1.82763047397343e-06 8.88783676756008e-06 -5.45966558450785e-06 0.000107545447886284 2.00325310139352e-05 -1.19866877237597e-05 7.46653678571385e-06 -4.42738096095106e-05 -1.02565297794035e-05 2.00325310139352e-05 2.48987907271395e-05 -1.31954143009449e-05 -5.06727005298439e-06 -7.18685467707138e-06 5.27549193160313e-06 -1.19866877237597e-05 -1.31954143009449e-05 4.10696179123681e-05 -2.63848757001565e-05 6.27545255722248e-06 -1.82763047397343e-06 7.46653678571385e-06 -5.06727005298439e-06 -2.63848757001565e-05 0.000131910454176963 -9.15922533063096e-06 8.88783676756008e-06 -4.42738096095106e-05 -7.18685467707138e-06 6.27545255722248e-06 -9.15922533063096e-06 5.68313454669799e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 818 0 0 0 0 0 2653 +1094 1124 0.999998255095367 0.00145349952981764 0.00117351835874946 0.00233238552526158 -0.0014610635043506 0.999977997866743 0.00647063179729028 -0.00212844684109892 -0.00116408747856717 -0.00647233509150053 0.999978376655618 -0.010120769084641 3.1743496392664e-05 1.88957408280184e-06 -8.49147828891623e-06 6.98316442856555e-06 -6.83355035015669e-06 1.59172677384847e-05 1.88957408280184e-06 9.31997390083166e-05 1.17648657646925e-05 -1.19557081145968e-06 1.38805621654172e-06 -3.56241271966186e-05 -8.49147828891623e-06 1.17648657646925e-05 1.8583720423776e-05 -6.66833690691861e-06 -2.18557847193987e-06 -6.27941075083548e-06 6.98316442856555e-06 -1.19557081145968e-06 -6.66833690691861e-06 3.65732746622839e-05 -2.90760777882301e-05 1.09508925823995e-05 -6.83355035015669e-06 1.38805621654172e-06 -2.18557847193987e-06 -2.90760777882301e-05 0.000138921597610098 -1.82571200283225e-05 1.59172677384847e-05 -3.56241271966186e-05 -6.27941075083548e-06 1.09508925823995e-05 -1.82571200283225e-05 7.49769517273581e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 902 0 0 0 0 0 2685 +1094 1123 0.999998063485893 0.00181082857937719 -0.000770664855140547 0.00251307472023016 -0.00180674937750755 0.999984527185523 0.00526127800377936 -0.00232643793453689 0.000780180203359512 -0.005259875416993 0.999985862414788 -0.00686500400657697 2.75309883047942e-05 -5.5763273684406e-06 -9.41276158902634e-06 2.76395268766066e-06 4.77818458227585e-06 7.14881976421075e-06 -5.5763273684406e-06 8.18255642741697e-05 1.71451390688619e-05 -8.11067072626757e-06 -1.25001318766588e-05 -3.65137755405488e-05 -9.41276158902634e-06 1.71451390688619e-05 2.49296673561303e-05 -1.48294561650039e-05 -2.5364790178077e-06 -7.27247671891253e-06 2.76395268766066e-06 -8.11067072626757e-06 -1.48294561650039e-05 4.45777615776769e-05 -3.18316244712624e-05 5.58235526438081e-06 4.77818458227585e-06 -1.25001318766588e-05 -2.5364790178077e-06 -3.18316244712624e-05 0.000131410190656847 3.70345678203378e-06 7.14881976421075e-06 -3.65137755405488e-05 -7.27247671891253e-06 5.58235526438081e-06 3.70345678203378e-06 5.38761855877054e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 824 0 0 0 0 0 2719 +1094 1121 0.999994253120908 0.0020725923988883 0.00268292487867593 0.003668921599974 -0.00208303950921455 0.999990237098365 0.00389700581960539 -0.00939150563465381 -0.00267482178090411 -0.00390257206250666 0.999988807567233 -0.00839601386022982 3.40786692891474e-05 -1.74706201863861e-05 -1.28569012805728e-05 5.64679864231609e-06 4.57952489129359e-06 3.30740755098205e-05 -1.74706201863861e-05 0.000100176469359654 1.88280368924137e-05 -9.13538865143666e-06 -3.76776171353946e-06 -5.04488365858312e-05 -1.28569012805728e-05 1.88280368924137e-05 2.27632116156203e-05 -1.32683251845664e-05 -1.10869960240661e-05 -9.46043549300249e-06 5.64679864231609e-06 -9.13538865143666e-06 -1.32683251845664e-05 3.90285365184877e-05 -2.48343909641511e-05 3.16466946135427e-06 4.57952489129359e-06 -3.76776171353946e-06 -1.10869960240661e-05 -2.48343909641511e-05 0.000135306654249472 5.98423353152466e-06 3.30740755098205e-05 -5.04488365858312e-05 -9.46043549300249e-06 3.16466946135427e-06 5.98423353152466e-06 0.000101526659387666 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 902 0 0 0 0 0 2664 +1093 1138 0.999983566260583 0.00140750346906095 0.00555753027433597 -0.00391310412839253 -0.00143351051101004 0.999988028752385 0.00467839711166554 0.0215483949120555 -0.00555087888360061 -0.00468628700617004 0.999973612880718 -0.00730953781760857 4.1345412277747e-05 -2.4940489525947e-05 -1.38342547987785e-05 1.00714503438808e-05 -2.0094506766451e-06 3.22270147767254e-05 -2.4940489525947e-05 0.000148017682723016 2.42919213313075e-05 -1.54483142017427e-05 1.8249226560597e-05 -8.12780412436828e-05 -1.38342547987785e-05 2.42919213313075e-05 2.45125793286547e-05 -1.41794050004198e-05 -5.13695565576826e-06 -1.31900781955457e-05 1.00714503438808e-05 -1.54483142017427e-05 -1.41794050004198e-05 3.43658030901131e-05 -1.92722497518539e-06 9.208275588257e-06 -2.0094506766451e-06 1.8249226560597e-05 -5.13695565576826e-06 -1.92722497518539e-06 8.9407434391268e-05 -1.57514098176305e-05 3.22270147767254e-05 -8.12780412436828e-05 -1.31900781955457e-05 9.208275588257e-06 -1.57514098176305e-05 9.84844481512634e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 910 0 0 0 0 0 2518 +1094 1122 0.999997832087832 0.00192874517929533 0.000784704829743896 0.00546233082431251 -0.00193269238499721 0.999985325850487 0.00506090741276133 -0.0141673858244791 -0.000774932114092677 -0.00506241303420749 0.999986885641252 -0.0107410062745438 3.71564327334903e-05 -2.3423496006252e-06 -1.2109249982672e-05 4.22731571073367e-06 8.45100719144305e-06 1.72873287967332e-05 -2.3423496006252e-06 0.0001310549647687 2.23800576989338e-05 -7.58447861307434e-06 -7.56426967597528e-07 -6.32223775198927e-05 -1.2109249982672e-05 2.23800576989338e-05 2.61328850635323e-05 -1.31384412730622e-05 -1.18521412308754e-05 -1.22880859196774e-05 4.22731571073367e-06 -7.58447861307434e-06 -1.31384412730622e-05 3.38659603619313e-05 -8.44166560694581e-06 5.27706600047664e-06 8.45100719144305e-06 -7.56426967597528e-07 -1.18521412308754e-05 -8.44166560694581e-06 0.000101286403825526 -1.49885017002859e-06 1.72873287967332e-05 -6.32223775198927e-05 -1.22880859196774e-05 5.27706600047664e-06 -1.49885017002859e-06 8.57950811437253e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 897 0 0 0 0 0 2530 +1094 1125 0.9999977601196 0.00129825060526243 0.00167161632839874 0.00424636162093801 -0.00130434819267073 0.999992481448076 0.00365181093605206 -0.00930748760432665 -0.00166686279450655 -0.00365398312616911 0.999991934955347 -0.010942475506676 3.6038609235174e-05 -2.22391626973203e-05 -1.46396544854187e-05 7.48168646686453e-06 -4.18844630288121e-06 4.06969267920015e-05 -2.22391626973203e-05 0.000109634980969077 2.15969241409712e-05 -8.75578865247537e-06 9.54203868207292e-06 -6.37528097903055e-05 -1.46396544854187e-05 2.15969241409712e-05 2.45767622566947e-05 -1.21132056044671e-05 -5.85468433126659e-06 -1.45236785341133e-05 7.48168646686453e-06 -8.75578865247537e-06 -1.21132056044671e-05 3.73262710255142e-05 -1.902285100318e-05 7.70235056207342e-06 -4.18844630288121e-06 9.54203868207292e-06 -5.85468433126659e-06 -1.902285100318e-05 0.000115866164691683 -1.18175385438587e-05 4.06969267920015e-05 -6.37528097903055e-05 -1.45236785341133e-05 7.70235056207342e-06 -1.18175385438587e-05 0.000108456812763867 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 891 0 0 0 0 0 2508 +1093 1139 0.999965730862918 0.00161754913059516 0.00811915233265641 -0.00163274774682839 -0.00165602582020197 0.999987420871891 0.004734519665814 0.0151018243378698 -0.00811139188262986 -0.00474780294381158 0.99995583086901 -0.0121324744403812 3.57189455678345e-05 -3.18201024394183e-05 -1.36214840824961e-05 7.80525690540694e-06 6.14299415484931e-07 4.09608933628162e-05 -3.18201024394183e-05 0.000135832705684736 2.17455979931884e-05 -1.1502237669636e-05 2.14767463988455e-06 -8.07924572714446e-05 -1.36214840824961e-05 2.17455979931884e-05 2.25702351292508e-05 -1.37283793190769e-05 -1.18107327781448e-05 -9.11216186809594e-06 7.80525690540694e-06 -1.1502237669636e-05 -1.37283793190769e-05 2.97286880186888e-05 8.71683564999459e-06 6.27177444187386e-06 6.14299415484931e-07 2.14767463988455e-06 -1.18107327781448e-05 8.71683564999459e-06 6.49111692409068e-05 -9.95387829092928e-06 4.09608933628162e-05 -8.07924572714446e-05 -9.11216186809594e-06 6.27177444187386e-06 -9.95387829092928e-06 0.000115971416013547 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 904 0 0 0 0 0 2647 +1094 1127 0.999972599390872 0.00189243059421066 0.00715675722020841 0.00283795472506039 -0.00192023976749965 0.999990625799316 0.00388084948521558 0.00146975779049966 -0.00714934589303264 -0.00389448583739634 0.999966859367531 -0.00867235040054557 2.9677249770422e-05 -3.38789225334704e-05 -1.65257589491199e-05 5.52599437315281e-06 2.22592194841127e-06 2.41437026345873e-05 -3.38789225334704e-05 0.000155439729198053 3.29308823631837e-05 -1.10046135060005e-05 2.15938795801663e-06 -8.27694903902867e-05 -1.65257589491199e-05 3.29308823631837e-05 2.52880837424198e-05 -1.25096869115061e-05 -1.15071741018564e-05 -1.4951225292973e-05 5.52599437315281e-06 -1.10046135060005e-05 -1.25096869115061e-05 4.06350083626619e-05 -3.97840200602117e-05 -6.75219515451108e-07 2.22592194841127e-06 2.15938795801663e-06 -1.15071741018564e-05 -3.97840200602117e-05 0.000188376285650083 1.82824223849924e-06 2.41437026345873e-05 -8.27694903902867e-05 -1.4951225292973e-05 -6.75219515451108e-07 1.82824223849924e-06 8.21675631307972e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 832 0 0 0 0 0 2793 +1094 1098 0.999985096746905 0.00064924531921659 0.00542077158692927 -0.00479697875091448 -0.000654004013081204 0.999999402331732 0.000876136364435521 0.0142195532693689 -0.0054201995196725 -0.000879668513525384 0.999984923696589 -0.00341230924326835 2.59008813787361e-05 -2.6857700584511e-05 -1.54504096967377e-05 6.82671954726437e-06 1.59129642803561e-06 1.76951968630087e-05 -2.6857700584511e-05 0.000104392289314986 1.71084489000884e-05 -7.94621342877838e-06 4.21539768659407e-06 -6.56233158647821e-05 -1.54504096967377e-05 1.71084489000884e-05 2.06319290927222e-05 -1.10753807322315e-05 -4.14127234935531e-06 -1.32534903293575e-05 6.82671954726437e-06 -7.94621342877838e-06 -1.10753807322315e-05 2.95815047983056e-05 -1.62844561698296e-06 1.09196621113518e-05 1.59129642803561e-06 4.21539768659407e-06 -4.14127234935531e-06 -1.62844561698296e-06 6.19900483617395e-05 -4.68106855041162e-06 1.76951968630087e-05 -6.56233158647821e-05 -1.32534903293575e-05 1.09196621113518e-05 -4.68106855041162e-06 5.89296950116868e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 907 0 0 0 0 0 2583 +1094 1129 0.99994478846457 0.0028500648871532 -0.010114205489603 0.00422807128960806 -0.0028711499742203 0.999993734137733 -0.00207079286693704 -0.0104937386805552 0.0101082402213458 0.00209971793611403 0.999946705911978 0.00481093340723039 2.79341748659967e-05 -1.41539297079541e-05 -1.36907000300932e-05 2.89121751426568e-06 1.00401778089934e-05 1.49252475757508e-05 -1.41539297079541e-05 0.000109611720054322 2.13974679758766e-05 -6.70997673441902e-06 -1.3802662883299e-05 -4.64477823752575e-05 -1.36907000300932e-05 2.13974679758766e-05 2.56968076164167e-05 -1.3556592097175e-05 -1.06227171502835e-05 -8.81933576734333e-06 2.89121751426568e-06 -6.70997673441902e-06 -1.3556592097175e-05 3.8625943173761e-05 -2.61007964125841e-05 -1.01966232308482e-06 1.00401778089934e-05 -1.3802662883299e-05 -1.06227171502835e-05 -2.61007964125841e-05 0.000118420069702151 1.1456175062304e-05 1.49252475757508e-05 -4.64477823752575e-05 -8.81933576734333e-06 -1.01966232308482e-06 1.1456175062304e-05 6.42882774990054e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 924 0 0 0 0 0 2431 +1094 1126 0.999996757047711 0.00243218294268804 -0.000755235192238474 0.00460109722135857 -0.00243125915243531 0.999996298206464 0.00122170057825519 -0.00373537899940727 0.000758203795821225 -0.00121986044386513 0.999998968533219 -0.00328698178882334 3.336863434901e-05 -4.31342891095866e-05 -1.83391355590408e-05 4.93936606155241e-06 6.57400449998771e-06 3.01455941370876e-05 -4.31342891095866e-05 0.000186689267790953 3.96969934784621e-05 -1.09471909970661e-05 -3.3137845670444e-05 -9.8774723357316e-05 -1.83391355590408e-05 3.96969934784621e-05 2.8681079241021e-05 -1.41694176682124e-05 -1.63726477493029e-05 -1.81205247071021e-05 4.93936606155241e-06 -1.09471909970661e-05 -1.41694176682124e-05 4.02876644571458e-05 -1.48272536986906e-05 5.17075417147167e-08 6.57400449998771e-06 -3.3137845670444e-05 -1.63726477493029e-05 -1.48272536986906e-05 0.000116059501409402 1.46302607615513e-05 3.01455941370876e-05 -9.8774723357316e-05 -1.81205247071021e-05 5.17075417147167e-08 1.46302607615513e-05 9.44209703528873e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 841 0 0 0 0 0 2732 +1094 1134 0.999986301851138 0.00182952857527262 0.00490397137801091 0.00322533215136589 -0.00185226255368199 0.999987541461626 0.00463530419346818 -0.00398244360065379 -0.00489542986021827 -0.00464432414092913 0.999977232250694 -0.0136088220727828 2.15722204987668e-05 -8.91627996812248e-06 -1.19317647714013e-05 7.82604311129835e-06 -1.01812173575049e-06 1.21642532155721e-05 -8.91627996812248e-06 8.26257784203082e-05 1.42163303830659e-05 -1.26880392980575e-05 4.13192508202683e-06 -2.799337211198e-05 -1.19317647714013e-05 1.42163303830659e-05 2.137289951494e-05 -1.2259739257938e-05 -1.31215652211482e-05 -6.32822448546994e-06 7.82604311129835e-06 -1.26880392980575e-05 -1.2259739257938e-05 4.33828972905039e-05 -3.13144397409334e-05 6.7022641038551e-06 -1.01812173575049e-06 4.13192508202683e-06 -1.31215652211482e-05 -3.13144397409334e-05 0.00016000558953979 -4.83882320871797e-06 1.21642532155721e-05 -2.799337211198e-05 -6.32822448546994e-06 6.7022641038551e-06 -4.83882320871797e-06 4.98235691306638e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 817 0 0 0 0 0 2746 +1094 1128 0.999994138927288 0.00201167742236572 0.0027704268661753 0.00344539491614745 -0.00201870568633787 0.999994745653586 0.00253643304112435 -0.000611786222917936 -0.00276530982431066 -0.00254201085137419 0.999992945596321 -0.00620660805792024 2.46999278218431e-05 -2.09089052537505e-05 -1.41275102516796e-05 7.50373546971114e-06 -7.78311653611803e-07 1.07431913850817e-05 -2.09089052537505e-05 0.000112934176471053 2.54615345749798e-05 -1.18084397334281e-05 -1.66705081758665e-06 -4.10056605280327e-05 -1.41275102516796e-05 2.54615345749798e-05 2.67586475453252e-05 -1.34197180751663e-05 -1.47418148385874e-05 -9.81302806847289e-06 7.50373546971114e-06 -1.18084397334281e-05 -1.34197180751663e-05 3.68289365634504e-05 -1.94353109832615e-05 5.7255581448418e-06 -7.78311653611803e-07 -1.66705081758665e-06 -1.47418148385874e-05 -1.94353109832615e-05 0.000134793054539847 -8.17901232827996e-06 1.07431913850817e-05 -4.10056605280327e-05 -9.81302806847289e-06 5.7255581448418e-06 -8.17901232827996e-06 5.21980097953389e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 833 0 0 0 0 0 2714 +1094 1136 0.999997703994921 0.00212794217118823 0.000252719215778987 0.00661567437739422 -0.0021286735535662 0.999993442106433 0.0029299305502798 -0.0116382335965845 -0.000246482835696674 -0.00293046177985548 0.999995675810635 -0.00260600525024506 3.05781765454901e-05 -3.40086632051811e-05 -1.65536368764093e-05 5.00988313768588e-06 -1.03475165612378e-06 2.15876533748612e-05 -3.40086632051811e-05 0.000158551462156308 3.83511654669056e-05 -1.72560796183081e-05 1.05912688137953e-05 -7.60543595523707e-05 -1.65536368764093e-05 3.83511654669056e-05 3.11461037073021e-05 -1.73185215884041e-05 -9.96521190604406e-06 -1.43174449322351e-05 5.00988313768588e-06 -1.72560796183081e-05 -1.73185215884041e-05 3.49861423017771e-05 -1.0527776185988e-05 6.80347585902638e-06 -1.03475165612378e-06 1.05912688137953e-05 -9.96521190604406e-06 -1.0527776185988e-05 0.000101528857450011 -1.66872458579791e-05 2.15876533748612e-05 -7.60543595523707e-05 -1.43174449322351e-05 6.80347585902638e-06 -1.66872458579791e-05 8.42564885369862e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 850 0 0 0 0 0 2503 +1094 1138 0.999992377388404 0.00111650655911749 0.00374146738475996 -0.00379414381869813 -0.00111664683796993 0.999999375922994 3.54042571425527e-05 0.0165998258716599 -0.00374142552071088 -3.95818849942116e-05 0.999993000059674 0.000796819478901331 2.78464799101389e-05 -1.66667613958763e-05 -1.32387998617126e-05 5.10977424762686e-06 1.48872677301704e-06 1.90137480324719e-05 -1.66667613958763e-05 0.000103243267996657 1.90314556744615e-05 -8.4744877217381e-06 -5.63363777526286e-06 -4.76189577010661e-05 -1.32387998617126e-05 1.90314556744615e-05 2.28187038102739e-05 -1.34368628837697e-05 -7.64077277420426e-06 -8.92784150779928e-06 5.10977424762686e-06 -8.4744877217381e-06 -1.34368628837697e-05 3.06632665136401e-05 2.263102949059e-06 4.92956527684433e-06 1.48872677301704e-06 -5.63363777526286e-06 -7.64077277420426e-06 2.263102949059e-06 6.13169199582868e-05 1.16395656771134e-06 1.90137480324719e-05 -4.76189577010661e-05 -8.92784150779928e-06 4.92956527684433e-06 1.16395656771134e-06 6.10935121679419e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 919 0 0 0 0 0 2466 +1094 1137 0.999981051106361 0.000932090535794323 0.00608511589453419 0.00384891121052383 -0.000944279338874516 0.999997553192653 0.00200048625012075 -0.00415482034802261 -0.00608323637112719 -0.00200619439233344 0.999979484499214 -0.00381549203267075 3.97193746230554e-05 -2.74774129183556e-05 -1.36462636191374e-05 -6.28019669235472e-07 1.41573826046009e-05 3.55799881963292e-05 -2.74774129183556e-05 0.000165721588197521 3.03525247847607e-05 6.68782095804036e-07 -1.88992065127801e-05 -7.79152293645582e-05 -1.36462636191374e-05 3.03525247847607e-05 2.44444963886097e-05 -8.91298121739968e-06 -1.42753735283911e-05 -1.29109333927126e-05 -6.28019669235472e-07 6.68782095804036e-07 -8.91298121739968e-06 3.26939166233493e-05 -1.12002318349183e-05 -2.21619932227543e-06 1.41573826046009e-05 -1.88992065127801e-05 -1.42753735283911e-05 -1.12002318349183e-05 0.000107550247317993 1.9987175312369e-05 3.55799881963292e-05 -7.79152293645582e-05 -1.29109333927126e-05 -2.21619932227543e-06 1.9987175312369e-05 9.51238802423308e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 919 0 0 0 0 0 2603 +1094 1139 0.999996596480424 0.00237428286846839 -0.00108157682462498 -0.000540340884600545 -0.00237468995083121 0.999997110013361 -0.000375250001306992 0.00949665736477787 0.00108068274923291 0.000377817133752756 0.99999934468929 0.000266017259585408 3.11666282367488e-05 -2.89779486456954e-05 -1.71478941743134e-05 9.09804685291085e-06 1.70485680234289e-06 2.43232188846497e-05 -2.89779486456954e-05 0.000135688042642276 2.64869525104817e-05 -1.12782012021297e-05 -2.8262951354224e-07 -7.00787569044515e-05 -1.71478941743134e-05 2.64869525104817e-05 2.94024063994535e-05 -1.78722004722083e-05 -1.27780688163058e-05 -1.32728390618319e-05 9.09804685291085e-06 -1.12782012021297e-05 -1.78722004722083e-05 3.48842972949092e-05 -1.44461807150883e-06 3.68709232485623e-06 1.70485680234289e-06 -2.8262951354224e-07 -1.27780688163058e-05 -1.44461807150883e-06 8.2147416465394e-05 -4.98775082251371e-06 2.43232188846497e-05 -7.00787569044515e-05 -1.32728390618319e-05 3.68709232485623e-06 -4.98775082251371e-06 7.29732847222302e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 925 0 0 0 0 0 2572 +1094 1131 0.999997571394324 0.0021057117971969 -0.000650525389126696 0.000312776886071155 -0.00210408022389675 0.999994664731287 0.00249867072096555 0.00303084068615195 0.000655783398813388 -0.00249729589507325 0.999996666725118 -0.00694792411500238 3.73150968353016e-05 -3.37611691794817e-05 -1.72209843284233e-05 2.82412701472992e-06 1.03186024650954e-05 3.8288813963466e-05 -3.37611691794817e-05 0.00013737117406123 2.43159861509032e-05 -7.42984334749252e-06 -1.42933721526383e-05 -7.83023523097521e-05 -1.72209843284233e-05 2.43159861509032e-05 2.6710782391051e-05 -1.80229025852045e-05 -5.67048942884665e-06 -1.01365222021283e-05 2.82412701472992e-06 -7.42984334749252e-06 -1.80229025852045e-05 6.22185783825299e-05 -5.894100426472e-05 -4.84478301227929e-06 1.03186024650954e-05 -1.42933721526383e-05 -5.67048942884665e-06 -5.894100426472e-05 0.000210313453632956 1.82570846666958e-05 3.8288813963466e-05 -7.83023523097521e-05 -1.01365222021283e-05 -4.84478301227929e-06 1.82570846666958e-05 0.000103337283025175 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 898 0 0 0 0 0 2607 +1094 1130 0.999994964077757 0.00277671141664225 -0.00153678002154236 0.00190096296218724 -0.00277527035240218 0.999995708014829 0.000939056118194524 0.000338832701680611 0.00153938091354955 -0.000934786409148981 0.999998378239071 -0.00365380136772025 2.24518052102259e-05 -1.05000147675885e-05 -1.33351348085382e-05 4.07675705365718e-06 2.17448042330322e-06 7.61433286232373e-06 -1.05000147675885e-05 9.41678036957939e-05 1.63523809556908e-05 -1.29388593812295e-06 -3.17884851030236e-05 -3.91134535557491e-05 -1.33351348085382e-05 1.63523809556908e-05 2.20688581372004e-05 -8.6767661397911e-06 -1.17293262002723e-05 -6.32539237249481e-06 4.07675705365718e-06 -1.29388593812295e-06 -8.6767661397911e-06 4.00334524042474e-05 -4.41442586251658e-05 1.3206289275348e-06 2.17448042330322e-06 -3.17884851030236e-05 -1.17293262002723e-05 -4.41442586251658e-05 0.000180421586803818 6.62853359667677e-06 7.61433286232373e-06 -3.91134535557491e-05 -6.32539237249481e-06 1.3206289275348e-06 6.62853359667677e-06 5.15614389679051e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 837 0 0 0 0 0 2751 +1095 1123 0.999957364899682 0.000727443421645623 0.009205390211859 0.006187292531943 -0.000765244546144164 0.999991287575723 0.00410355619337138 -0.00606886177835056 -0.00920232490563562 -0.00411042561249617 0.999949209518971 -0.00937061350271165 3.0996226257966e-05 -3.96618188014002e-05 -1.66402997074556e-05 4.98934883913934e-06 1.16236189883858e-06 2.25785720299369e-05 -3.96618188014002e-05 0.000158356061799643 3.4085137484412e-05 -1.600113663333e-05 -1.15989077524437e-05 -7.91642606268041e-05 -1.66402997074556e-05 3.4085137484412e-05 2.36534634456759e-05 -1.17452633915415e-05 -6.37590282638845e-06 -1.38157311486414e-05 4.98934883913934e-06 -1.600113663333e-05 -1.17452633915415e-05 3.82744354184807e-05 -2.47786120840991e-05 7.7469569576746e-06 1.16236189883858e-06 -1.15989077524437e-05 -6.37590282638845e-06 -2.47786120840991e-05 0.000115328326930492 -1.11914063533705e-05 2.25785720299369e-05 -7.91642606268041e-05 -1.38157311486414e-05 7.7469569576746e-06 -1.11914063533705e-05 7.77194498038385e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2768 +1094 1132 0.999997055805753 0.00217110554016371 0.00108382681200329 0.000667032628800392 -0.00217500210278816 0.999991129235872 0.00360705079226393 0.000345948454707939 -0.00107598590967255 -0.00360939749800091 0.999992907226858 -0.0112479682940039 3.13265473487081e-05 -1.66790851587224e-05 -1.33863648963395e-05 6.66802729639613e-06 -4.2041892451307e-06 2.78505579201666e-05 -1.66790851587224e-05 9.94802844884693e-05 1.68688122289999e-05 -4.99953088020746e-06 -8.86126138533354e-06 -4.79904531076978e-05 -1.33863648963395e-05 1.68688122289999e-05 2.27433836391936e-05 -1.19461562680019e-05 -1.30858757002966e-05 -8.13735956162745e-06 6.66802729639613e-06 -4.99953088020746e-06 -1.19461562680019e-05 3.87234398500001e-05 -2.28935152055836e-05 1.13605212570495e-05 -4.2041892451307e-06 -8.86126138533354e-06 -1.30858757002966e-05 -2.28935152055836e-05 0.000144179673881175 -1.75431348013642e-05 2.78505579201666e-05 -4.79904531076978e-05 -8.13735956162745e-06 1.13605212570495e-05 -1.75431348013642e-05 8.69631173373836e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 914 0 0 0 0 0 2451 +1095 1124 0.99999688569551 0.00104002200615148 0.00226868982180588 0.00326993452309619 -0.00104635155064396 0.999995558964664 0.00279055538962302 -0.000954720564375876 -0.00226577750745962 -0.00279292054609682 0.999993532902643 -0.0088619762201686 3.67233224206004e-05 -4.60876780380132e-05 -1.87265584669804e-05 1.07816083084842e-05 -7.73536646399622e-06 3.83863184498009e-05 -4.60876780380132e-05 0.000192301573980489 3.15222683411318e-05 -2.07661116081526e-05 3.30943959740916e-05 -0.000103883288116262 -1.87265584669804e-05 3.15222683411318e-05 2.55325336714889e-05 -1.6162305410911e-05 -1.10386406555596e-05 -1.91522573406155e-05 1.07816083084842e-05 -2.07661116081526e-05 -1.6162305410911e-05 4.20330168596377e-05 -1.9564790835987e-05 1.41073028093661e-05 -7.73536646399622e-06 3.30943959740916e-05 -1.10386406555596e-05 -1.9564790835987e-05 0.000165364435509065 -2.34962654179753e-05 3.83863184498009e-05 -0.000103883288116262 -1.91522573406155e-05 1.41073028093661e-05 -2.34962654179753e-05 0.000109327409719698 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 907 0 0 0 0 0 2739 +1094 1133 0.99997975500314 0.00268409980630624 -0.00576933203156963 0.00435520721962739 -0.00266489193857195 0.999990889961336 0.00333441828359556 -0.0105423089767737 0.0057782293842009 -0.003318976131886 0.999977797984845 -0.00557510022707289 3.63670859667846e-05 -3.24111482395072e-06 -1.3412014577976e-05 6.04227670455512e-06 7.35741846141313e-06 9.05931535635438e-06 -3.24111482395072e-06 8.94526770825893e-05 1.27455608203237e-05 -4.75180821245799e-06 -6.97125715319525e-06 -3.74636855290099e-05 -1.3412014577976e-05 1.27455608203237e-05 2.92170007083061e-05 -1.88772462447605e-05 -9.90351921226894e-06 -5.11554531771823e-06 6.04227670455512e-06 -4.75180821245799e-06 -1.88772462447605e-05 5.01369917553943e-05 -2.83710339071615e-05 2.82711292894565e-07 7.35741846141313e-06 -6.97125715319525e-06 -9.90351921226894e-06 -2.83710339071615e-05 0.000136329760129616 5.22966347455157e-06 9.05931535635438e-06 -3.74636855290099e-05 -5.11554531771823e-06 2.82711292894565e-07 5.22966347455157e-06 5.96016087237969e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2418 +1094 1135 0.999991283893856 0.00122895247751212 0.00399021454621324 0.00521455928522094 -0.00122641305434368 0.999999043924144 -0.000638797165788798 -0.0127602342438962 -0.00399099578262498 0.000633897946755789 0.999991835029695 -0.00152829789760877 3.1979255034219e-05 -2.76867929407896e-05 -1.21973889029303e-05 4.18551796716116e-06 -2.02113462490922e-06 1.73926899939874e-05 -2.76867929407896e-05 0.000148741880342719 2.87803045568027e-05 -1.42791767890737e-05 5.56279217046463e-06 -6.30305972687909e-05 -1.21973889029303e-05 2.87803045568027e-05 2.37460910248314e-05 -1.2670544854737e-05 -6.35929928571936e-06 -1.05140291752708e-05 4.18551796716116e-06 -1.42791767890737e-05 -1.2670544854737e-05 3.61286216074079e-05 -8.61261275925877e-06 1.54722221457372e-06 -2.02113462490922e-06 5.56279217046463e-06 -6.35929928571936e-06 -8.61261275925877e-06 9.25985174325304e-05 -5.54933222971648e-06 1.73926899939874e-05 -6.30305972687909e-05 -1.05140291752708e-05 1.54722221457372e-06 -5.54933222971648e-06 7.33718406152642e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 921 0 0 0 0 0 2656 +1095 1097 0.999990601542935 0.000825426542502006 -0.00425623035348485 -0.00834108171956059 -0.000833335555917144 0.999997928954548 -0.00185678174963216 0.0211071508230117 0.00425468890169856 0.00186031116683634 0.999989218374234 0.00354550108155278 3.51901726129492e-05 -4.17700020940709e-05 -1.73130305886721e-05 7.62839286724179e-06 2.62745868500768e-06 3.40047422098291e-05 -4.17700020940709e-05 0.000148967518979185 2.10881586652738e-05 -9.92973706019641e-06 1.04610698319705e-06 -0.000104092652930946 -1.73130305886721e-05 2.10881586652738e-05 2.33553514531534e-05 -1.6302406793772e-05 -7.62204818317945e-06 -1.31190526840635e-05 7.62839286724179e-06 -9.92973706019641e-06 -1.6302406793772e-05 3.81187759510447e-05 2.78206159834156e-07 9.85388823355413e-06 2.62745868500768e-06 1.04610698319705e-06 -7.62204818317945e-06 2.78206159834156e-07 6.07202386145027e-05 -3.33666370140367e-06 3.40047422098291e-05 -0.000104092652930946 -1.31190526840635e-05 9.85388823355413e-06 -3.33666370140367e-06 0.000100854798277629 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 964 0 0 0 0 0 2579 +1095 1121 0.999997584103227 0.00197100650506167 0.000973098693586075 0.00509337905966852 -0.00197245942408164 0.999996938096738 0.00149438983162021 -0.0106432399693116 -0.00097015026197279 -0.00149630561901736 0.999998409937718 -0.00676713531743247 3.22562630977152e-05 -1.25165789922264e-05 -1.13996460761348e-05 4.99200975007229e-06 8.23000065038133e-06 1.17519043933094e-05 -1.25165789922264e-05 0.000113359430539704 1.99474456857158e-05 -6.56284827536492e-06 2.33382486570431e-06 -4.96926135337471e-05 -1.13996460761348e-05 1.99474456857158e-05 2.35295095952806e-05 -1.33108746017861e-05 -9.18799175169667e-06 -7.58744835054638e-06 4.99200975007229e-06 -6.56284827536492e-06 -1.33108746017861e-05 3.50716906020906e-05 -1.75866102276851e-05 1.82902638945746e-06 8.23000065038133e-06 2.33382486570431e-06 -9.18799175169667e-06 -1.75866102276851e-05 0.000117286020677577 -8.44716973153398e-07 1.17519043933094e-05 -4.96926135337471e-05 -7.58744835054638e-06 1.82902638945746e-06 -8.44716973153398e-07 7.23183903293047e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 909 0 0 0 0 0 2571 +1095 1122 0.999999461672631 0.000951147779013876 0.000414695490800307 0.00567688046992259 -0.000952025751948121 0.999997295125362 0.00212211897103846 -0.0108590298534283 -0.000412675920354885 -0.00212251262943019 0.999997662316629 -0.00653889488638206 2.70293466632099e-05 -1.93928710939887e-05 -1.32411148703729e-05 3.47744670630825e-06 6.15553520717879e-06 1.66415535135204e-05 -1.93928710939887e-05 0.000109602665766505 2.17254771714462e-05 -1.7000923719793e-06 -2.86737577803737e-05 -4.2506376900455e-05 -1.32411148703729e-05 2.17254771714462e-05 2.27324201673919e-05 -9.76870556699043e-06 -1.17192985674024e-05 -7.34799183808484e-06 3.47744670630825e-06 -1.7000923719793e-06 -9.76870556699043e-06 3.28355061514814e-05 -2.09470825229145e-05 -1.94768549036253e-06 6.15553520717879e-06 -2.86737577803737e-05 -1.17192985674024e-05 -2.09470825229145e-05 0.0001216776028668 1.16440088171444e-05 1.66415535135204e-05 -4.2506376900455e-05 -7.34799183808484e-06 -1.94768549036253e-06 1.16440088171444e-05 6.13592814709236e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 911 0 0 0 0 0 2454 +1095 1125 0.999995788082388 0.00172147190696005 -0.00233673959993272 0.00478752382807829 -0.00171668364039776 0.999996426094424 0.00204958426451776 -0.00690057774392971 0.00234025955037835 -0.00204556418919463 0.999995169414525 -0.00626819731223536 3.4439017745244e-05 -1.7382457893173e-05 -1.41362173366023e-05 7.21053623798153e-06 -1.72280515340024e-07 1.69953592387728e-05 -1.7382457893173e-05 0.000135893592372505 2.32779398322458e-05 -1.49060426292917e-05 2.66391393182562e-05 -7.27220023468028e-05 -1.41362173366023e-05 2.32779398322458e-05 2.57719522817549e-05 -1.69569932085805e-05 -6.49136040393743e-06 -1.4177099370801e-05 7.21053623798153e-06 -1.49060426292917e-05 -1.69569932085805e-05 4.55278647739757e-05 -2.85192255635203e-05 1.05433719799914e-05 -1.72280515340024e-07 2.66391393182562e-05 -6.49136040393743e-06 -2.85192255635203e-05 0.000161607765338742 -1.42671486618726e-05 1.69953592387728e-05 -7.27220023468028e-05 -1.4177099370801e-05 1.05433719799914e-05 -1.42671486618726e-05 7.52160427404346e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 899 0 0 0 0 0 2574 +1095 1126 0.999995431037857 0.000864100473210858 0.00289676263846423 0.00694056102832313 -0.000866247642971177 0.999999350964282 0.000740058129456755 -0.0130140452358357 -0.00289612127378195 -0.000742564061966994 0.999995530530103 -0.00227046538677868 2.92839103426915e-05 -2.16310045596251e-06 -8.14441093943358e-06 6.53365407520144e-06 -4.26279946888222e-06 8.42814045788191e-06 -2.16310045596251e-06 8.66363840023458e-05 1.28528623497996e-05 -1.80261668203482e-05 2.19197278261245e-05 -4.68542131060426e-05 -8.14441093943358e-06 1.28528623497996e-05 2.07156265398263e-05 -1.41325756358241e-05 -5.00304860977901e-06 -4.56204821532971e-06 6.53365407520144e-06 -1.80261668203482e-05 -1.41325756358241e-05 4.69147120475789e-05 -4.223283851999e-05 1.35621822579562e-05 -4.26279946888222e-06 2.19197278261245e-05 -5.00304860977901e-06 -4.223283851999e-05 0.000191760360435501 -3.37375793271235e-05 8.42814045788191e-06 -4.68542131060426e-05 -4.56204821532971e-06 1.35621822579562e-05 -3.37375793271235e-05 6.52726040220833e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 831 0 0 0 0 0 2755 +1095 1127 0.999995851668336 0.0021932066556025 -0.00186721468653169 0.00710135104073446 -0.00219467614959416 0.999997283336362 -0.000785312991826574 -0.010180736824464 0.00186548726025704 0.000789407665626526 0.999997948394305 -0.000102496945428865 2.78386976065356e-05 -2.09680239586589e-05 -1.46949648168399e-05 8.51141993570045e-06 -4.85683219454015e-07 1.50099479312605e-05 -2.09680239586589e-05 0.000161418775390348 3.52570761387548e-05 -1.51870912484566e-05 -8.43341471805575e-06 -8.03881678550343e-05 -1.46949648168399e-05 3.52570761387548e-05 3.00139685658162e-05 -1.49615825866357e-05 -1.45359157022561e-05 -1.57031879679835e-05 8.51141993570045e-06 -1.51870912484566e-05 -1.49615825866357e-05 5.36166811894716e-05 -5.40886097106173e-05 1.05893580906998e-05 -4.85683219454015e-07 -8.43341471805575e-06 -1.45359157022561e-05 -5.40886097106173e-05 0.000233425362485951 -1.99333534161352e-05 1.50099479312605e-05 -8.03881678550343e-05 -1.57031879679835e-05 1.05893580906998e-05 -1.99333534161352e-05 7.90920874273612e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 825 0 0 0 0 0 2719 +1095 1133 0.999992063141844 0.00249248234237666 -0.00310824469603738 0.00777054170443655 -0.00249265910943683 0.99999689191607 -5.29977652370427e-05 -0.0139602345349869 0.00310810293935795 6.07451390572337e-05 0.999995167991399 -0.00214816163325932 2.13642903292501e-05 -9.61172393140943e-06 -1.22830553179091e-05 3.8795515819099e-07 1.32386171177049e-05 1.01406330168773e-05 -9.61172393140943e-06 6.83354132219334e-05 6.69875781774142e-06 4.02035571214358e-06 -3.02943068600042e-05 -3.2092427115105e-05 -1.22830553179091e-05 6.69875781774142e-06 1.81112988528769e-05 -7.11953677225097e-06 -1.07369493699423e-05 -5.95346325309198e-06 3.8795515819099e-07 4.02035571214358e-06 -7.11953677225097e-06 3.73918528267376e-05 -2.59669060087444e-05 -5.30672917370765e-06 1.32386171177049e-05 -3.02943068600042e-05 -1.07369493699423e-05 -2.59669060087444e-05 0.000130922539648415 2.73864317833308e-05 1.01406330168773e-05 -3.2092427115105e-05 -5.95346325309198e-06 -5.30672917370765e-06 2.73864317833308e-05 5.50278450113014e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 819 0 0 0 0 0 2540 +1095 1130 0.999998435681721 0.00147440465612445 0.000977120780889247 0.00432345499104825 -0.00147386620316525 0.99999876175366 -0.000551551956948099 -0.00929067126500237 -0.000977932781746436 0.000550110948849928 0.999999370512511 -0.00222688143310608 3.76054779071668e-05 -1.73816070612648e-05 -1.28769717293387e-05 3.0378915376822e-06 1.63989058993157e-05 1.70282106548299e-05 -1.73816070612648e-05 0.000139247582436103 2.56847027006781e-05 -8.50561263737594e-06 -8.1160170353391e-06 -8.13202293416067e-05 -1.28769717293387e-05 2.56847027006781e-05 2.60102308171974e-05 -1.51605721312155e-05 -7.75576089230327e-06 -1.35249742481953e-05 3.0378915376822e-06 -8.50561263737594e-06 -1.51605721312155e-05 4.50893458678051e-05 -2.68041592270232e-05 -7.49613247812458e-07 1.63989058993157e-05 -8.1160170353391e-06 -7.75576089230327e-06 -2.68041592270232e-05 0.00013545003634357 7.01885291171683e-06 1.70282106548299e-05 -8.13202293416067e-05 -1.35249742481953e-05 -7.49613247812458e-07 7.01885291171683e-06 9.53723395966471e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 830 0 0 0 0 0 2660 +1095 1132 0.999998394218941 0.0013638779368082 0.00116249581193522 0.00323584220024691 -0.00136700624967804 0.99999543547548 0.0026944984912832 -0.00287939612522884 -0.00115881553865156 -0.0026960833035487 0.999995694131414 -0.00967172094365835 3.03836770547763e-05 -8.09167592063004e-06 -1.06203772700964e-05 4.91568455164273e-06 2.74450828175834e-06 9.7758226801022e-06 -8.09167592063004e-06 9.7446346652228e-05 2.07282412303556e-05 -2.26212203899038e-05 2.13617210944963e-05 -4.51421768842481e-05 -1.06203772700964e-05 2.07282412303556e-05 2.35860804803726e-05 -1.5689155274589e-05 -2.65352346884191e-06 -8.01074346116102e-06 4.91568455164273e-06 -2.26212203899038e-05 -1.5689155274589e-05 4.13112342610261e-05 -2.56282887738391e-05 1.00492498805732e-05 2.74450828175834e-06 2.13617210944963e-05 -2.65352346884191e-06 -2.56282887738391e-05 0.000132470547028837 -2.05293511730617e-05 9.7758226801022e-06 -4.51421768842481e-05 -8.01074346116102e-06 1.00492498805732e-05 -2.05293511730617e-05 6.16288030938883e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 900 0 0 0 0 0 2418 +1095 1136 0.999997525043639 0.00144911555256966 -0.00168818562699065 0.00628956910633627 -0.00145216289226061 0.999997316103637 -0.00180527240511908 -0.0114557698234584 0.0016855650477565 0.00180771945767142 0.999996945505751 0.00212969247678078 2.75613108329763e-05 -1.05123198419918e-05 -1.11297615552168e-05 5.88337544274728e-06 -6.16988876107219e-07 1.85273164428238e-05 -1.05123198419918e-05 7.81403608209509e-05 1.5107139919229e-05 -1.26539582128791e-05 -2.48143476187313e-06 -3.87495311142764e-05 -1.11297615552168e-05 1.5107139919229e-05 2.56245673071746e-05 -1.62300106226652e-05 -7.89432154614053e-06 -6.72436281204391e-06 5.88337544274728e-06 -1.26539582128791e-05 -1.62300106226652e-05 3.76949293053289e-05 -8.2813726298584e-06 1.15897706617463e-05 -6.16988876107219e-07 -2.48143476187313e-06 -7.89432154614053e-06 -8.2813726298584e-06 8.58608631205486e-05 -5.05655529885827e-06 1.85273164428238e-05 -3.87495311142764e-05 -6.72436281204391e-06 1.15897706617463e-05 -5.05655529885827e-06 7.46720174163808e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 826 0 0 0 0 0 2576 +1095 1131 0.999994689708652 0.00153185590805857 0.00287645128130656 0.00287997430003138 -0.00154201230433173 0.999992573611059 0.00353198538851141 -0.000189331000422332 -0.002871019426976 -0.00353640215590854 0.999989625499806 -0.00975704163992902 3.24260894981069e-05 -1.35422897374422e-05 -1.18261125735424e-05 5.15781759444696e-06 8.73609806678892e-06 1.70376283325361e-05 -1.35422897374422e-05 0.000123345695720968 2.05201203260103e-05 -1.2208843580359e-05 1.09060468208836e-05 -6.56885362812062e-05 -1.18261125735424e-05 2.05201203260103e-05 2.22709736972302e-05 -1.24160283259417e-05 -5.8757111448656e-06 -9.52694755100219e-06 5.15781759444696e-06 -1.2208843580359e-05 -1.24160283259417e-05 3.75853570493971e-05 -2.37218579282285e-05 1.88821642867442e-06 8.73609806678892e-06 1.09060468208836e-05 -5.8757111448656e-06 -2.37218579282285e-05 0.000147828495934057 -8.6099559642131e-06 1.70376283325361e-05 -6.56885362812062e-05 -9.52694755100219e-06 1.88821642867442e-06 -8.6099559642131e-06 8.12812806652599e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 906 0 0 0 0 0 2634 +1095 1128 0.999993351764569 4.52446966401559e-05 0.00364614585278933 0.004791849851574 -4.59793158267432e-05 0.999999978663037 0.000201394705615905 -0.00862218776541191 -0.00364613666294929 -0.000201561013988204 0.999993332508069 -0.00407504722649674 2.7794200551104e-05 -9.64944620355976e-06 -1.10400229443319e-05 4.06487871129426e-06 6.10869965040717e-06 6.75957076563222e-06 -9.64944620355976e-06 0.000133267163567398 2.26419696671375e-05 -1.12665343081685e-05 7.49493824658008e-06 -7.1043197414933e-05 -1.10400229443319e-05 2.26419696671375e-05 2.31510091323374e-05 -1.26834355303992e-05 -9.05173003613083e-06 -8.70274032110188e-06 4.06487871129426e-06 -1.12665343081685e-05 -1.26834355303992e-05 3.47729166426064e-05 -1.40375785765452e-05 3.99959755301247e-06 6.10869965040717e-06 7.49493824658008e-06 -9.05173003613083e-06 -1.40375785765452e-05 0.000112274096201458 -1.28149292075727e-05 6.75957076563222e-06 -7.1043197414933e-05 -8.70274032110188e-06 3.99959755301247e-06 -1.28149292075727e-05 7.74518694417683e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 826 0 0 0 0 0 2554 +1095 1138 0.999990056827837 0.00186608058841391 -0.00405018378554083 -0.0032439779926102 -0.00187239968547326 0.999997034978373 -0.00155696945376467 0.015284426749514 0.00404726634618389 0.0015645375353955 0.999990585884399 0.00483514721691484 4.16823726780082e-05 -1.0070963986606e-05 -1.21143761178311e-05 6.97247265152785e-06 1.10892164137824e-05 2.18373697967594e-05 -1.0070963986606e-05 9.76992268259566e-05 1.90294991302848e-05 -1.79517063944969e-05 1.89806933239641e-05 -5.64969803023858e-05 -1.21143761178311e-05 1.90294991302848e-05 2.24998735774114e-05 -1.24155618216703e-05 -7.34838733842064e-06 -1.04936387514995e-05 6.97247265152785e-06 -1.79517063944969e-05 -1.24155618216703e-05 3.08816078312796e-05 -5.40556834692789e-06 1.25757314338619e-05 1.10892164137824e-05 1.89806933239641e-05 -7.34838733842064e-06 -5.40556834692789e-06 0.000101995153924305 -7.88597127626656e-06 2.18373697967594e-05 -5.64969803023858e-05 -1.04936387514995e-05 1.25757314338619e-05 -7.88597127626656e-06 7.82970737856021e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 902 0 0 0 0 0 2526 +1095 1129 0.999999182078206 0.00126854817873086 0.000163182219604615 0.0042574599112242 -0.00126863698893109 0.999999046607893 0.000545292118369811 -0.00580098346040865 -0.000162490334704341 -0.00054549869136323 0.999999838014021 -0.00550542698446261 2.99046427975019e-05 -2.74672529568786e-05 -1.58423960663824e-05 1.09319960814965e-05 8.92152618176275e-07 2.79824875250463e-05 -2.74672529568786e-05 0.000118213826003509 2.55972047858398e-05 -2.4901486125069e-05 2.76075622649371e-06 -6.2110297445152e-05 -1.58423960663824e-05 2.55972047858398e-05 2.611777020814e-05 -1.83560734557336e-05 -1.05371429567137e-05 -1.33707992684804e-05 1.09319960814965e-05 -2.4901486125069e-05 -1.83560734557336e-05 4.35889853920207e-05 -1.29343476665379e-05 1.52962789701955e-05 8.92152618176275e-07 2.76075622649371e-06 -1.05371429567137e-05 -1.29343476665379e-05 0.000113456578384195 -6.41513753363346e-06 2.79824875250463e-05 -6.2110297445152e-05 -1.33707992684804e-05 1.52962789701955e-05 -6.41513753363346e-06 9.49890780559542e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 903 0 0 0 0 0 2548 +1095 1098 0.999984499747186 0.000176294602104408 0.00556499645852602 -0.0111629138626214 -0.000177775938176979 0.999999948901046 0.000265694600180668 0.0313111941112904 -0.0055649493336367 -0.00026667980431356 0.999984479989963 -0.00365105556970555 4.31063164162653e-05 -2.36938697884851e-05 -1.8479643442372e-05 7.94971709735486e-06 8.35153970373431e-06 2.2858730947755e-05 -2.36938697884851e-05 0.000134558071072501 2.28019027776246e-05 -6.14368901165356e-06 -5.48805805637771e-06 -9.26031536913048e-05 -1.8479643442372e-05 2.28019027776246e-05 2.47768394543221e-05 -1.37621746192302e-05 -9.35723090297514e-06 -1.73049851323458e-05 7.94971709735486e-06 -6.14368901165356e-06 -1.37621746192302e-05 3.81702029037696e-05 -1.58341720658475e-05 9.23087800442935e-06 8.35153970373431e-06 -5.48805805637771e-06 -9.35723090297514e-06 -1.58341720658475e-05 0.000103974196699334 1.12242991656438e-06 2.2858730947755e-05 -9.26031536913048e-05 -1.73049851323458e-05 9.23087800442935e-06 1.12242991656438e-06 9.28566432760633e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 929 0 0 0 0 0 2440 +1095 1134 0.999997616227634 0.00182940347663975 0.00119198236934566 0.00812667192324375 -0.00183188251203153 0.999996154741108 0.00208199650823561 -0.0124127156054388 -0.00118816897421434 -0.00208417511688692 0.999997122230145 -0.00654141314721063 3.2657248257448e-05 -2.81115204667361e-05 -1.76479842778336e-05 8.78595844246335e-06 4.20729225051697e-06 1.66305572168182e-05 -2.81115204667361e-05 0.000133814152383289 2.73379028890917e-05 -1.39039609195717e-05 -4.72165067095519e-06 -7.11951375127371e-05 -1.76479842778336e-05 2.73379028890917e-05 2.79634442353391e-05 -1.72341594180318e-05 -7.8154133654873e-06 -1.43873047725145e-05 8.78595844246335e-06 -1.39039609195717e-05 -1.72341594180318e-05 4.11489445018293e-05 -1.55494648715864e-05 4.23603199955595e-06 4.20729225051697e-06 -4.72165067095519e-06 -7.8154133654873e-06 -1.55494648715864e-05 0.00010276457136081 -2.03467722911327e-07 1.66305572168182e-05 -7.11951375127371e-05 -1.43873047725145e-05 4.23603199955595e-06 -2.03467722911327e-07 7.51939108493687e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 809 0 0 0 0 0 2649 +1095 1099 0.999997874741392 0.000341168980972401 0.00203325267131107 -0.00689398740954526 -0.000341677900857561 0.999999910389027 0.000249956294618397 0.0195638595862714 -0.002033167211775 -0.000250650480901277 0.999997901700511 -0.00300964890140361 3.19709599100015e-05 -3.86723368480854e-05 -1.66878858673685e-05 2.79606966941732e-06 4.39432774346386e-06 1.79144192063362e-05 -3.86723368480854e-05 0.000178459783666753 4.14236588580404e-05 -1.06042626008911e-05 -7.8653822531017e-06 -9.54696251267977e-05 -1.66878858673685e-05 4.14236588580404e-05 2.7248678823539e-05 -1.24420676024275e-05 -8.22842965027994e-06 -1.86037793995804e-05 2.79606966941732e-06 -1.06042626008911e-05 -1.24420676024275e-05 3.1322273366272e-05 -9.70258606870247e-06 3.37318108358858e-06 4.39432774346386e-06 -7.8653822531017e-06 -8.22842965027994e-06 -9.70258606870247e-06 7.63754948258852e-05 1.00397475810725e-06 1.79144192063362e-05 -9.54696251267977e-05 -1.86037793995804e-05 3.37318108358858e-06 1.00397475810725e-06 7.10676654925064e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 822 0 0 0 0 0 2545 +1095 1135 0.999988400279073 0.00182969328018685 -0.00445550556057126 0.00160894331567971 -0.00182125964925858 0.999996543754513 0.00189617834563111 -0.0046451556201155 0.00445895958602731 -0.00188804171799696 0.999988276420219 -0.00376028559097082 4.48065557531949e-05 -3.37447317033802e-05 -1.73582535206349e-05 6.16157409740268e-06 4.80506452468363e-06 3.89271174384143e-05 -3.37447317033802e-05 0.000188744276076802 3.76445949636044e-05 -1.58122177897177e-05 1.3538488886065e-05 -0.000101749499481335 -1.73582535206349e-05 3.76445949636044e-05 3.17487393734178e-05 -1.95336789443976e-05 -9.52154055062805e-06 -1.71234850137735e-05 6.16157409740268e-06 -1.58122177897177e-05 -1.95336789443976e-05 3.88619428890976e-05 -4.78165817931767e-06 3.34939931713489e-06 4.80506452468363e-06 1.3538488886065e-05 -9.52154055062805e-06 -4.78165817931767e-06 9.53173856543152e-05 -2.4658966107233e-06 3.89271174384143e-05 -0.000101749499481335 -1.71234850137735e-05 3.34939931713489e-06 -2.4658966107233e-06 0.000127236602640075 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 896 0 0 0 0 0 2626 +1096 1122 0.999982223820736 0.000680899617703947 0.00592354777532583 0.00849266382679661 -0.000692752924574638 0.999997761589938 0.00199922697549645 -0.0125182504779894 -0.00592217324311357 -0.00200329499192456 0.999980457145665 -0.00732781635960239 2.55240819568642e-05 -2.02276143634206e-05 -1.56775148487167e-05 5.73910651564492e-06 7.68812203210024e-06 1.49617268490506e-05 -2.02276143634206e-05 0.000108805389507566 2.31405841703169e-05 -1.46101003899556e-05 -3.79983174696292e-06 -5.15004354810146e-05 -1.56775148487167e-05 2.31405841703169e-05 2.57017689114965e-05 -1.51215157305935e-05 -8.84429583788281e-06 -1.09878703982888e-05 5.73910651564492e-06 -1.46101003899556e-05 -1.51215157305935e-05 3.76175229146433e-05 -1.27873863081813e-05 4.9791698175077e-06 7.68812203210024e-06 -3.79983174696292e-06 -8.84429583788281e-06 -1.27873863081813e-05 0.000104461372219265 2.54675021782519e-06 1.49617268490506e-05 -5.15004354810146e-05 -1.09878703982888e-05 4.9791698175077e-06 2.54675021782519e-06 6.62517793298834e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 921 0 0 0 0 0 2482 +1095 1137 0.999998861556142 0.0014958907568774 -0.000197982989026613 0.00564496679343207 -0.0014955155992266 0.999997111366811 0.00188167242796572 -0.00625444236929471 0.000200797193518845 -0.00188137419913883 0.999998210054203 -0.00228563678949395 2.6944323762274e-05 -1.49972164724423e-05 -1.26496387889297e-05 4.92567444271427e-06 8.99741589595345e-06 8.54254981257415e-06 -1.49972164724423e-05 0.000131886942821203 2.99295077269463e-05 -1.17557475199455e-05 -2.03707037830303e-05 -6.06520291020175e-05 -1.26496387889297e-05 2.99295077269463e-05 2.85616861446623e-05 -1.90568768953372e-05 -1.24948150198314e-05 -1.00064835683869e-05 4.92567444271427e-06 -1.17557475199455e-05 -1.90568768953372e-05 4.23616714455613e-05 -5.83753656282755e-06 3.93187271665976e-06 8.99741589595345e-06 -2.03707037830303e-05 -1.24948150198314e-05 -5.83753656282755e-06 9.72109590577621e-05 6.55986469025782e-06 8.54254981257415e-06 -6.06520291020175e-05 -1.00064835683869e-05 3.93187271665976e-06 6.55986469025782e-06 6.22904095704254e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 906 0 0 0 0 0 2655 +1095 1139 0.999992370790027 0.00120479119564634 0.0037157556319975 -0.000676015445730753 -0.00121254780898743 0.999997089272189 0.00208594701754548 0.00896505488589285 -0.00371323168584292 -0.002090436634768 0.999990920951347 -0.00577260139930843 3.61061896000445e-05 -1.0828315949941e-05 -1.07068514216798e-05 1.98013919542838e-06 1.19390363947086e-05 2.25601530877936e-05 -1.0828315949941e-05 0.000114592830939726 1.12238517822019e-05 2.42047350696595e-06 -2.93984220535794e-06 -6.89778075388866e-05 -1.07068514216798e-05 1.12238517822019e-05 1.84788830064836e-05 -9.534936193913e-06 -6.52366577911398e-06 -8.79939337185625e-06 1.98013919542838e-06 2.42047350696595e-06 -9.534936193913e-06 3.10042846925168e-05 -1.46477543949313e-06 -1.96366845678493e-06 1.19390363947086e-05 -2.93984220535794e-06 -6.52366577911398e-06 -1.46477543949313e-06 7.65865457947243e-05 1.16462361516845e-05 2.25601530877936e-05 -6.89778075388866e-05 -8.79939337185625e-06 -1.96366845678493e-06 1.16462361516845e-05 0.000100044831982227 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 906 0 0 0 0 0 2636 +1096 1127 0.999999346364949 0.00106415209975289 0.000418150670655527 0.00458518795544055 -0.00106380664848358 0.999999093435115 -0.000825496434453203 -0.00472802499285316 -0.000419028745338874 0.000825051063416288 0.999999571852735 -0.00570505866619104 6.93877887938751e-05 -9.3012062661309e-05 -2.41053939706129e-05 2.14077247469453e-06 1.40564789634461e-05 7.91028588201789e-05 -9.3012062661309e-05 0.000275435590554035 4.13960426515284e-05 3.95189777738748e-06 -2.9876956274544e-05 -0.000172881568271697 -2.41053939706129e-05 4.13960426515284e-05 2.62124459754402e-05 -1.04665144207696e-05 -1.56312931053318e-05 -2.63288663897298e-05 2.14077247469453e-06 3.95189777738748e-06 -1.04665144207696e-05 3.61957833708754e-05 -6.92869145049754e-06 -2.6009156681147e-06 1.40564789634461e-05 -2.9876956274544e-05 -1.56312931053318e-05 -6.92869145049754e-06 0.000113722038268483 2.33293004120159e-05 7.91028588201789e-05 -0.000172881568271697 -2.63288663897298e-05 -2.6009156681147e-06 2.33293004120159e-05 0.000174843830262941 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2734 +1095 1140 0.999964100679047 0.000387934664061414 0.00846444681245287 0.00113682994742148 -0.000424458362292959 0.999990606368825 0.00431358426471575 0.00805120893691721 -0.00846269391169877 -0.0043170222152015 0.999954872047209 -0.00652054656469906 2.91450562482394e-05 -9.72358152326671e-06 -1.35606618898131e-05 6.47053881148425e-06 4.08902312216083e-06 5.18159409430622e-06 -9.72358152326671e-06 0.00011756665877163 2.14145911344046e-05 -1.3010702603793e-05 -3.01588349990716e-07 -5.66813809063623e-05 -1.35606618898131e-05 2.14145911344046e-05 2.54111274309964e-05 -1.33773410705011e-05 -1.28097777527912e-05 -6.81139220586789e-06 6.47053881148425e-06 -1.3010702603793e-05 -1.33773410705011e-05 3.38783540248004e-05 -9.5047173787743e-07 3.58891004250951e-06 4.08902312216083e-06 -3.01588349990716e-07 -1.28097777527912e-05 -9.5047173787743e-07 9.49651736245376e-05 -1.53886108987315e-06 5.18159409430622e-06 -5.66813809063623e-05 -6.81139220586789e-06 3.58891004250951e-06 -1.53886108987315e-06 5.74943552010521e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 887 0 0 0 0 0 2610 +1096 1123 0.999986627947882 0.000200974136483233 0.00516754630573123 0.00380377998871827 -0.000199819291322951 0.99999995494909 -0.000223995689967585 -0.00288448557856047 -0.00516759109026893 0.000222960119244854 0.999986623056083 -0.00523014921088761 3.73428880225942e-05 -3.66948086963341e-05 -1.4423180947428e-05 8.1085003554334e-06 -5.35921105191707e-06 2.7648559744771e-05 -3.66948086963341e-05 0.000128592420125529 2.55265553497767e-05 -1.9634474737874e-05 2.3431047479394e-05 -7.39981871757886e-05 -1.4423180947428e-05 2.55265553497767e-05 2.16619742553449e-05 -1.05107988773835e-05 -6.63196420564184e-06 -1.03932654345617e-05 8.1085003554334e-06 -1.9634474737874e-05 -1.05107988773835e-05 3.11976002201035e-05 -1.20264147867327e-05 8.67670711602982e-06 -5.35921105191707e-06 2.3431047479394e-05 -6.63196420564184e-06 -1.20264147867327e-05 0.000119333109987021 -2.63584531506091e-05 2.7648559744771e-05 -7.39981871757886e-05 -1.03932654345617e-05 8.67670711602982e-06 -2.63584531506091e-05 9.12602287501017e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 797 0 0 0 0 0 2771 +1096 1130 0.999966098239022 0.000656385983546477 0.00820801620770586 0.0036609191986232 -0.000662214906479065 0.999999530491141 0.000707452411545601 -0.00232707084367398 -0.00820754799212257 -0.000712863898348406 0.999966063414664 -0.00980953672902455 6.60158138226911e-05 -2.04662861716206e-05 -1.62044641406603e-05 4.27549780054804e-06 1.56687769574018e-05 3.59445930597131e-05 -2.04662861716206e-05 0.000175473599952932 2.35665562142987e-05 -7.50094208245077e-06 1.03618427639661e-05 -0.000101671742377863 -1.62044641406603e-05 2.35665562142987e-05 2.42721413287508e-05 -1.36354415556556e-05 -6.03292960194327e-06 -9.77986935250795e-06 4.27549780054804e-06 -7.50094208245077e-06 -1.36354415556556e-05 4.6307598355216e-05 -3.55687934104904e-05 -1.85736641138893e-06 1.56687769574018e-05 1.03618427639661e-05 -6.03292960194327e-06 -3.55687934104904e-05 0.000170869560630619 8.20649244495901e-07 3.59445930597131e-05 -0.000101671742377863 -9.77986935250795e-06 -1.85736641138893e-06 8.20649244495901e-07 0.000125483317854031 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2677 +1096 1129 0.999925704869657 0.000805055052351816 0.0121629201790881 0.00235487194843651 -0.000846440463627471 0.999993869146942 0.00339782387262284 0.00746064300482062 -0.012160110174736 -0.00340786661865079 0.999920255903263 -0.0120499156810651 3.31040317847789e-05 -2.04374128681828e-05 -1.49877853840171e-05 4.94054189256871e-08 1.39024520497239e-05 1.82859767871797e-05 -2.04374128681828e-05 0.00012278752266322 2.08421292554171e-05 6.77111360693414e-06 -4.01568815077824e-05 -5.22031684832402e-05 -1.49877853840171e-05 2.08421292554171e-05 2.29231495761316e-05 -9.54629990000125e-06 -1.39836173827482e-05 -1.19397526627439e-05 4.94054189256871e-08 6.77111360693414e-06 -9.54629990000125e-06 4.82526911352087e-05 -4.40555667505098e-05 -4.99519728384391e-08 1.39024520497239e-05 -4.01568815077824e-05 -1.39836173827482e-05 -4.40555667505098e-05 0.000189593336830878 1.71088167869687e-05 1.82859767871797e-05 -5.22031684832402e-05 -1.19397526627439e-05 -4.99519728384391e-08 1.71088167869687e-05 6.33236512589391e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 906 0 0 0 0 0 2564 +1096 1124 0.999962448078174 0.000671135496373127 0.00864013950416963 0.00436940958380268 -0.000689082851254095 0.999997611017535 0.00207439727308677 0.00179751252438407 -0.00863872666138431 -0.00208027314744731 0.999960521653381 -0.00995376225578279 3.17662857864193e-05 -2.4209002588993e-05 -1.48975903347244e-05 1.90656051429754e-06 7.30118849620019e-06 1.56756450143574e-05 -2.4209002588993e-05 0.000123033432026888 1.92960766768666e-05 -1.39244049728647e-06 -5.89524824193175e-06 -6.50796463650277e-05 -1.48975903347244e-05 1.92960766768666e-05 2.16817686422435e-05 -1.0178543524374e-05 -1.02817991245378e-05 -8.50006068463147e-06 1.90656051429754e-06 -1.39244049728647e-06 -1.0178543524374e-05 3.51745876834911e-05 -1.73719066296159e-05 -4.55776112346538e-06 7.30118849620019e-06 -5.89524824193175e-06 -1.02817991245378e-05 -1.73719066296159e-05 0.000127627905362681 3.4269030465958e-06 1.56756450143574e-05 -6.50796463650277e-05 -8.50006068463147e-06 -4.55776112346538e-06 3.4269030465958e-06 6.36293992869827e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 927 0 0 0 0 0 2703 +1096 1126 0.999996824640891 0.000379663317438354 0.00249129763403728 0.00277223809731017 -0.00038241305157682 0.999999318186869 0.00110335218946915 -0.00591925684139088 -0.00249087703308529 -0.00110430139066034 0.999996288018133 -0.00663961778093321 4.6497955248005e-05 -3.77555248333563e-06 -1.19742932018296e-05 2.69475507828863e-06 1.72084590991373e-05 2.42657270474794e-05 -3.77555248333563e-06 0.000137133693057416 2.26267103401554e-05 -1.0171585848571e-05 -1.39604641254282e-05 -6.99022931077093e-05 -1.19742932018296e-05 2.26267103401554e-05 2.18961217793313e-05 -1.10944029967185e-05 -1.21236254936776e-05 -1.28106022407282e-05 2.69475507828863e-06 -1.0171585848571e-05 -1.10944029967185e-05 3.59312060242742e-05 -5.45672598455138e-06 7.61483828080131e-06 1.72084590991373e-05 -1.39604641254282e-05 -1.21236254936776e-05 -5.45672598455138e-06 9.28504494502485e-05 4.70167487154611e-06 2.42657270474794e-05 -6.99022931077093e-05 -1.28106022407282e-05 7.61483828080131e-06 4.70167487154611e-06 9.93314709380561e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 819 0 0 0 0 0 2757 +1096 1125 0.999987579302049 0.00193727667218967 0.00459218909937958 0.00822537862115182 -0.00194479814200046 0.999996773922909 0.00163398407643961 -0.0118648491762531 -0.00458900880538952 -0.00164289466204513 0.9999881208771 -0.00615988983527598 2.91706534262559e-05 -1.45617934671958e-05 -1.41560772699857e-05 5.22255956667645e-06 3.095373598261e-06 1.10941615467167e-05 -1.45617934671958e-05 0.000144981836768555 1.86121126175352e-05 -1.37691916648037e-05 4.2465138200818e-05 -8.81652428036788e-05 -1.41560772699857e-05 1.86121126175352e-05 2.19452397451156e-05 -1.11598052322199e-05 -4.9645658579187e-06 -9.89806371300348e-06 5.22255956667645e-06 -1.37691916648037e-05 -1.11598052322199e-05 3.59810532922964e-05 -2.40028032145407e-05 4.83319236370873e-06 3.095373598261e-06 4.2465138200818e-05 -4.9645658579187e-06 -2.40028032145407e-05 0.000158345796054863 -2.43664708174381e-05 1.10941615467167e-05 -8.81652428036788e-05 -9.89806371300348e-06 4.83319236370873e-06 -2.43664708174381e-05 8.96559113953801e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 913 0 0 0 0 0 2560 +1096 1128 0.999990981625705 0.00142055441183547 0.00400233587069058 0.00459289184097983 -0.00142622989202723 0.999997981048492 0.00141554485437611 -0.00528052652070981 -0.00400031693168051 -0.0014212403395195 0.99999098872957 -0.00831308664922733 4.1931647291279e-05 -1.02788866355568e-05 -1.3487854505142e-05 4.47344761412669e-06 1.12339727976556e-05 2.03308758679855e-05 -1.02788866355568e-05 0.000162357193813318 2.52364180294606e-05 -4.21231785159122e-06 1.23570120633568e-05 -8.30942283339034e-05 -1.3487854505142e-05 2.52364180294606e-05 2.62070935653405e-05 -1.03095708660422e-05 -1.9878805753626e-05 -1.04355713795116e-05 4.47344761412669e-06 -4.21231785159122e-06 -1.03095708660422e-05 4.54375702616683e-05 -4.93497438814267e-05 -2.47482799170697e-06 1.12339727976556e-05 1.23570120633568e-05 -1.9878805753626e-05 -4.93497438814267e-05 0.000274061577062642 1.38718125877357e-06 2.03308758679855e-05 -8.30942283339034e-05 -1.04355713795116e-05 -2.47482799170697e-06 1.38718125877357e-06 0.000100464071725709 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 817 0 0 0 0 0 2581 +1096 1098 0.999961654166858 -0.000355190338912863 0.00875008775403811 -0.00668908428351678 0.000319929856820176 0.999991825118066 0.00403079916704061 0.019681845185709 -0.00875144792402604 -0.00402784518836601 0.999953593234392 -0.00687213046435282 2.51937841558361e-05 -1.01813862912987e-05 -1.31193783016765e-05 4.45203544852744e-06 3.33197308963026e-06 6.48141164352396e-06 -1.01813862912987e-05 9.76692613171799e-05 1.50287255772233e-05 -2.49548508064798e-06 -4.51876671869859e-06 -5.32545103124509e-05 -1.31193783016765e-05 1.50287255772233e-05 2.11106998395514e-05 -1.0125343370339e-05 -4.98940078990002e-06 -9.83534834727793e-06 4.45203544852744e-06 -2.49548508064798e-06 -1.0125343370339e-05 2.75151404640723e-05 -1.96328279091715e-06 2.49619935900086e-06 3.33197308963026e-06 -4.51876671869859e-06 -4.98940078990002e-06 -1.96328279091715e-06 4.9209429027493e-05 4.44639093964555e-06 6.48141164352396e-06 -5.32545103124509e-05 -9.83534834727793e-06 2.49619935900086e-06 4.44639093964555e-06 4.78421261105945e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 970 0 0 0 0 0 2478 +1096 1132 0.999998842102646 0.00139741049152172 -0.000602525754860873 0.00329534567472234 -0.00139761824550053 0.999998963983355 -0.000344522070960828 -0.00609597241598208 0.00060204369187764 0.000345363773028011 0.9999997591336 -0.0048767806859129 2.52982986159546e-05 -1.56522785265397e-05 -1.14191077565604e-05 3.70102929885087e-06 -2.23771251653412e-06 9.02723437468675e-06 -1.56522785265397e-05 0.000145548058606259 2.26095677090171e-05 -1.90662259921428e-05 3.76458813897072e-05 -7.79689354949352e-05 -1.14191077565604e-05 2.26095677090171e-05 2.38654799946589e-05 -1.34562929880369e-05 -6.68062984066259e-06 -8.76377078457895e-06 3.70102929885087e-06 -1.90662259921428e-05 -1.34562929880369e-05 3.24144436616326e-05 -1.4517386134596e-05 8.64914295241903e-06 -2.23771251653412e-06 3.76458813897072e-05 -6.68062984066259e-06 -1.4517386134596e-05 0.000118037316179853 -3.36094131028931e-05 9.02723437468675e-06 -7.79689354949352e-05 -8.76377078457895e-06 8.64914295241903e-06 -3.36094131028931e-05 7.76090730617699e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 915 0 0 0 0 0 2480 +1096 1137 0.999987849282192 0.00141496846344629 0.00472219781706095 0.00775826876527815 -0.00142016476366193 0.999998389611204 0.00109722697871779 -0.00911230715828757 -0.00472063767091437 -0.00110391994556923 0.999988248401317 -0.00123957549488089 2.73814538450901e-05 -2.94250734285763e-05 -1.71191393378428e-05 5.66938236840301e-06 1.001674682631e-05 1.96822903837972e-05 -2.94250734285763e-05 0.000131964147654677 3.47659296524509e-05 -1.5554301402777e-05 -2.09390601661305e-05 -6.99397959937772e-05 -1.71191393378428e-05 3.47659296524509e-05 3.08007728595799e-05 -1.67350882272593e-05 -2.04763562883669e-05 -1.77364303663626e-05 5.66938236840301e-06 -1.5554301402777e-05 -1.67350882272593e-05 3.33772415307031e-05 6.49759083382295e-06 9.40146663089639e-06 1.001674682631e-05 -2.09390601661305e-05 -2.04763562883669e-05 6.49759083382295e-06 8.64279013305385e-05 1.41836708505394e-05 1.96822903837972e-05 -6.99397959937772e-05 -1.77364303663626e-05 9.40146663089639e-06 1.41836708505394e-05 6.57393930746011e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 910 0 0 0 0 0 2647 +1096 1099 0.999960315748024 -0.000309382387701384 0.0089034381926426 -0.0114047067575263 0.000301340639887184 0.999999545495452 0.000904545581395352 0.0322898143339657 -0.00890371399646121 -0.00090182671741841 0.999959954490999 -0.00676919904621543 4.40779852315668e-05 -3.77502866566293e-05 -1.68395644823701e-05 5.17122433338155e-06 9.43886730796771e-06 1.66023908335876e-05 -3.77502866566293e-05 0.000165326456569681 3.6133785057001e-05 -1.07496307778558e-05 -1.63437326555849e-05 -7.96223017618856e-05 -1.68395644823701e-05 3.6133785057001e-05 3.15792426758065e-05 -1.80894140843182e-05 -9.60908741476287e-06 -1.3711033511187e-05 5.17122433338155e-06 -1.07496307778558e-05 -1.80894140843182e-05 4.26130022829312e-05 -1.38906192855407e-05 7.5063027973215e-07 9.43886730796771e-06 -1.63437326555849e-05 -9.60908741476287e-06 -1.38906192855407e-05 9.73230367802966e-05 1.32445016972042e-05 1.66023908335876e-05 -7.96223017618856e-05 -1.3711033511187e-05 7.5063027973215e-07 1.32445016972042e-05 7.14035424609567e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 849 0 0 0 0 0 2588 +1096 1131 0.999995750866599 0.00144565038583769 0.00253147066117657 0.00295329598073689 -0.00144941269972025 0.999997846966805 0.00148501332667111 -0.00291128093964581 -0.00252931840074753 -0.00148867616237666 0.999995693186581 -0.00553985994237832 3.75378812132537e-05 -2.22629027358612e-05 -1.76743268411242e-05 1.04028420485322e-05 -5.1726451075234e-06 1.50423855103888e-05 -2.22629027358612e-05 0.000145971165823031 1.96709268871146e-05 -1.47657295792891e-05 4.63718643895982e-05 -8.57069604615032e-05 -1.76743268411242e-05 1.96709268871146e-05 2.24302132385156e-05 -1.59330026919816e-05 2.32358776930494e-06 -8.49133577412699e-06 1.04028420485322e-05 -1.47657295792891e-05 -1.59330026919816e-05 4.55911935112343e-05 -4.54122074750788e-05 3.93637176402629e-06 -5.1726451075234e-06 4.63718643895982e-05 2.32358776930494e-06 -4.54122074750788e-05 0.000204220343403684 -2.95659286309323e-05 1.50423855103888e-05 -8.57069604615032e-05 -8.49133577412699e-06 3.93637176402629e-06 -2.95659286309323e-05 8.86207923196329e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 920 0 0 0 0 0 2599 +1096 1100 0.999987587163005 -9.03716437478372e-05 0.00498170180540005 -0.0107312676999171 7.87385257821796e-05 0.999997270045662 0.00233531613856769 0.0262814374890044 -0.00498189925193971 -0.00233489489881309 0.999984864358284 -0.00326309429523831 3.61518999904191e-05 -2.93992285029575e-05 -1.70043435610939e-05 6.36690533203792e-06 1.4841449366232e-06 2.58803488809804e-05 -2.93992285029575e-05 0.000146659719515877 2.22031355039656e-05 -1.28721125467661e-05 1.4407902533007e-05 -9.40170560610872e-05 -1.70043435610939e-05 2.22031355039656e-05 2.51660808348075e-05 -1.37465543329835e-05 -9.0120540090097e-06 -1.33974732250303e-05 6.36690533203792e-06 -1.28721125467661e-05 -1.37465543329835e-05 3.7747090124515e-05 -1.85253645856156e-05 1.42516164021869e-05 1.4841449366232e-06 1.4407902533007e-05 -9.0120540090097e-06 -1.85253645856156e-05 0.000116373093038224 -2.61104158413837e-05 2.58803488809804e-05 -9.40170560610872e-05 -1.33974732250303e-05 1.42516164021869e-05 -2.61104158413837e-05 9.23618408192807e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 786 0 0 0 0 0 2537 +1096 1136 0.999976375876902 0.000246467536685539 0.00686927520554565 0.00635991276141571 -0.000253311107535156 0.999999472500216 0.000995405833046552 -0.0102073914195239 -0.00686902624678079 -0.0009971223811669 0.999975910822545 -0.00620852408094936 3.82105234670107e-05 -1.28603275779624e-05 -1.55478886214525e-05 7.6911950385731e-06 1.32603961284188e-05 2.60337921624685e-05 -1.28603275779624e-05 0.000104008410553529 1.6850241979158e-05 -8.61917147401823e-06 1.30256440798821e-06 -5.83806068032286e-05 -1.55478886214525e-05 1.6850241979158e-05 2.60551926425006e-05 -1.32032018588059e-05 -1.27842755351643e-05 -1.06120638486061e-05 7.6911950385731e-06 -8.61917147401823e-06 -1.32032018588059e-05 3.46655328091869e-05 1.30483896490418e-06 9.79924828300057e-06 1.32603961284188e-05 1.30256440798821e-06 -1.27842755351643e-05 1.30483896490418e-06 9.74401584843466e-05 6.35580429421374e-06 2.60337921624685e-05 -5.83806068032286e-05 -1.06120638486061e-05 9.79924828300057e-06 6.35580429421374e-06 9.61705865981228e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 814 0 0 0 0 0 2591 +1096 1133 0.999997865206096 0.00152922682722084 -0.00138962173361038 0.0060658084945053 -0.00153152338820052 0.999997460856052 -0.0016530933306323 -0.0150067192499786 0.00138709025049167 0.00165521803980451 0.99999766811422 -0.00116665385464656 2.75834740922902e-05 -2.55238491917864e-05 -1.73203959801406e-05 5.26066559892114e-06 1.44532970230705e-05 2.41623227428178e-05 -2.55238491917864e-05 0.000118494192543305 1.84077534059057e-05 1.45300625452399e-06 -3.35650366480515e-05 -5.65936694565058e-05 -1.73203959801406e-05 1.84077534059057e-05 2.3745007279296e-05 -1.45562958683447e-05 -1.02321730452844e-05 -1.12491567446952e-05 5.26066559892114e-06 1.45300625452399e-06 -1.45562958683447e-05 3.83779396329935e-05 -1.67324142329678e-05 -1.77785319081801e-06 1.44532970230705e-05 -3.35650366480515e-05 -1.02321730452844e-05 -1.67324142329678e-05 9.49370070993391e-05 2.37350333938994e-05 2.41623227428178e-05 -5.65936694565058e-05 -1.12491567446952e-05 -1.77785319081801e-06 2.37350333938994e-05 8.1067522030276e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 796 0 0 0 0 0 2545 +1096 1134 0.999997916711364 0.00169091284310121 0.00114341011441097 0.00834814397073442 -0.00169148568593082 0.999998444329971 0.000500213765749887 -0.0132595059373169 -0.00114256251776132 -0.000502146785501908 0.999999221199446 -0.00359833857514937 3.69660356635875e-05 -3.91377569307173e-05 -2.36303984200704e-05 1.38582658671278e-05 6.55529568370909e-06 2.86086293298914e-05 -3.91377569307173e-05 0.000146684227667699 3.58942301151684e-05 -2.68925873093878e-05 -1.01858967306408e-06 -6.71404557144917e-05 -2.36303984200704e-05 3.58942301151684e-05 3.29803710640259e-05 -2.21037439280097e-05 -9.9341529435576e-06 -1.45667479659208e-05 1.38582658671278e-05 -2.68925873093878e-05 -2.21037439280097e-05 4.27075677109706e-05 -9.59815397720114e-06 5.19319756213358e-06 6.55529568370909e-06 -1.01858967306408e-06 -9.9341529435576e-06 -9.59815397720114e-06 0.000102700477268981 8.12664153304346e-06 2.86086293298914e-05 -6.71404557144917e-05 -1.45667479659208e-05 5.19319756213358e-06 8.12664153304346e-06 8.09278677826776e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 801 0 0 0 0 0 2652 +1096 1139 0.999938414628119 0.000794166052874159 0.0110696093555213 -0.00152676959566791 -0.000828006761594331 0.999994997289748 0.00305283479417815 0.0183928402301214 -0.0110671295197145 -0.00306181249560664 0.999934069800822 -0.0100067732551036 3.37110292856595e-05 -6.46117244355254e-06 -1.35277406101239e-05 7.70559614500077e-06 2.49211049356644e-06 5.47077320782329e-06 -6.46117244355254e-06 9.65208526621245e-05 1.40133624072799e-05 -1.42258588591416e-05 1.8272625503341e-05 -5.14170480201654e-05 -1.35277406101239e-05 1.40133624072799e-05 2.37338439822632e-05 -1.30088729999723e-05 -4.09941258338447e-06 -6.2832648904521e-06 7.70559614500077e-06 -1.42258588591416e-05 -1.30088729999723e-05 3.34790347221987e-05 -1.52488981072496e-05 6.53364782759206e-06 2.49211049356644e-06 1.8272625503341e-05 -4.09941258338447e-06 -1.52488981072496e-05 0.000119178597515431 -9.68320917766016e-06 5.47077320782329e-06 -5.14170480201654e-05 -6.2832648904521e-06 6.53364782759206e-06 -9.68320917766016e-06 5.66779383136315e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 913 0 0 0 0 0 2601 +1096 1135 0.999984133833631 0.000593111074773833 0.00560181222955127 0.00532514189729047 -0.000611678764018179 0.99999432341739 0.00331345470549835 -0.00565702404299102 -0.00559981518371979 -0.00331682864325557 0.999978820134536 -0.0112406968227735 3.39864634650607e-05 -2.55912939781479e-05 -1.55491423711252e-05 5.65351129648339e-06 3.14292145296935e-06 2.02321238805328e-05 -2.55912939781479e-05 0.000118653612229448 2.65552286745782e-05 -5.75126462992184e-06 -1.57224207500971e-07 -4.92965898835593e-05 -1.55491423711252e-05 2.65552286745782e-05 2.70244823751563e-05 -1.15345900522703e-05 -8.23571327198132e-06 -8.7746766787945e-06 5.65351129648339e-06 -5.75126462992184e-06 -1.15345900522703e-05 3.07017536342003e-05 -4.86179345531566e-06 -1.30548424276531e-06 3.14292145296935e-06 -1.57224207500971e-07 -8.23571327198132e-06 -4.86179345531566e-06 8.24100531070151e-05 3.70744499404194e-06 2.02321238805328e-05 -4.92965898835593e-05 -8.7746766787945e-06 -1.30548424276531e-06 3.70744499404194e-06 6.80115169190889e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 904 0 0 0 0 0 2584 +1096 1138 0.999980999167204 -0.000162788695798854 0.00616237003118025 -0.005448457341376 0.000138829977800182 0.999992431539341 0.00388813454933647 0.018933852626762 -0.00616295633587748 -0.00388720514984739 0.999973453450303 -0.00470495730061019 2.62660456467964e-05 -2.14836581172816e-05 -1.60406560068439e-05 7.45916727749244e-06 5.08753962168261e-06 1.69421449150989e-05 -2.14836581172816e-05 0.000119891088498109 2.99841195187914e-05 -2.10733686941419e-05 -4.35651522781316e-06 -5.88356301748938e-05 -1.60406560068439e-05 2.99841195187914e-05 2.99820509006063e-05 -1.9655481054418e-05 -1.33776184066478e-05 -1.46753718473735e-05 7.45916727749244e-06 -2.10733686941419e-05 -1.9655481054418e-05 3.65598750119027e-05 4.13251883393061e-06 1.31048510446876e-05 5.08753962168261e-06 -4.35651522781316e-06 -1.33776184066478e-05 4.13251883393061e-06 7.41739092186162e-05 3.69099641415925e-06 1.69421449150989e-05 -5.88356301748938e-05 -1.46753718473735e-05 1.31048510446876e-05 3.69099641415925e-06 5.87626634535655e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 903 0 0 0 0 0 2552 +1097 1128 0.999959778182989 -3.90457161502413e-06 0.00896894648114361 0.00328715230183866 -3.12396543566226e-05 0.999992322981615 0.00391829068825447 -0.00399252569402521 -0.00896889292562318 -0.00391841327427142 0.99995210135141 -0.0151707690292239 3.48341024821094e-05 -1.43738130033626e-05 -1.43642846162589e-05 1.57402308035856e-06 1.79770910473862e-05 1.38900472059805e-05 -1.43738130033626e-05 0.000144419222407035 2.45539687127738e-05 5.77016548556616e-06 -2.73986243171255e-05 -7.88099934659576e-05 -1.43642846162589e-05 2.45539687127738e-05 2.53052038681733e-05 -1.24204130183115e-05 -1.52079945320621e-05 -1.14560956970327e-05 1.57402308035856e-06 5.77016548556616e-06 -1.24204130183115e-05 4.3204053936355e-05 -2.21679417813369e-05 -6.89590519312838e-06 1.79770910473862e-05 -2.73986243171255e-05 -1.52079945320621e-05 -2.21679417813369e-05 0.000132985069199382 1.43008174101185e-05 1.38900472059805e-05 -7.88099934659576e-05 -1.14560956970327e-05 -6.89590519312838e-06 1.43008174101185e-05 8.1224810065555e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 828 0 0 0 0 0 2731 +1097 1130 0.999994045674822 0.00111473809553627 0.00326588026123966 0.00262050025750757 -0.00112118763896675 0.999997423797672 0.00197366063357275 0.00167760302789731 -0.00326367173297542 -0.00197731054633479 0.999992719318407 -0.0145889587963245 3.3375522934718e-05 -1.4869720812059e-05 -1.20952228294801e-05 9.66026704118084e-08 1.27224213230737e-05 1.73705898802641e-05 -1.4869720812059e-05 0.000137304579318443 2.68868688058703e-05 8.24736347492924e-06 -3.67092720560546e-05 -6.46558990134198e-05 -1.20952228294801e-05 2.68868688058703e-05 2.72987700950114e-05 -9.35359279798612e-06 -2.04877050566815e-05 -8.48680164515805e-06 9.66026704118084e-08 8.24736347492924e-06 -9.35359279798612e-06 3.67538201263517e-05 -2.29511180657624e-05 -1.26683385199859e-05 1.27224213230737e-05 -3.67092720560546e-05 -2.04877050566815e-05 -2.29511180657624e-05 0.000153052410740191 1.52429630504095e-05 1.73705898802641e-05 -6.46558990134198e-05 -8.48680164515805e-06 -1.26683385199859e-05 1.52429630504095e-05 7.94589442465035e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 835 0 0 0 0 0 2678 +1096 1140 0.999972507852576 0.000661111133456634 0.00738555827947707 0.003180018444263 -0.000681784772966063 0.999995855884951 0.00279703100575882 0.00240986934388978 -0.00738367852453533 -0.00280198947054486 0.999968814586962 -0.00354868188101331 3.53774531803521e-05 -5.25963548842974e-05 -1.95719446053837e-05 5.84088489978992e-06 -6.19647737020402e-06 3.05970751834775e-05 -5.25963548842974e-05 0.000181978236597131 3.6304076024082e-05 -1.77565516085776e-05 2.23312618715104e-05 -9.50128654648826e-05 -1.95719446053837e-05 3.6304076024082e-05 2.83435363631424e-05 -1.49045418952602e-05 -1.05657760204841e-05 -1.60686199070075e-05 5.84088489978992e-06 -1.77565516085776e-05 -1.49045418952602e-05 3.46452945397844e-05 -7.14982853882366e-06 5.63569936605489e-06 -6.19647737020402e-06 2.23312618715104e-05 -1.05657760204841e-05 -7.14982853882366e-06 0.000117371725278534 -1.0385002405911e-05 3.05970751834775e-05 -9.50128654648826e-05 -1.60686199070075e-05 5.63569936605489e-06 -1.0385002405911e-05 7.7976047666247e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 905 0 0 0 0 0 2629 +1097 1125 0.99999991471579 0.000393784867225556 0.00012450658881266 0.00634637077298147 -0.000393477104347064 0.999996891129603 -0.00246229707747202 -0.0187542314166265 -0.000125475817065534 0.00246224787698492 0.999996960790987 0.000409168590584091 4.23095751024129e-05 -2.91903762422257e-05 -1.74146461942124e-05 1.03162038757782e-05 -6.42435369341035e-06 2.64546701176914e-05 -2.91903762422257e-05 0.000178200035996003 3.28096483465175e-05 -2.28037909544152e-05 3.29482966042545e-05 -9.82294980264695e-05 -1.74146461942124e-05 3.28096483465175e-05 2.70249813241737e-05 -1.92775769818918e-05 9.08969155173681e-07 -1.97537316783213e-05 1.03162038757782e-05 -2.28037909544152e-05 -1.92775769818918e-05 4.38751151474227e-05 -2.11147578188602e-05 1.32628632191755e-05 -6.42435369341035e-06 3.29482966042545e-05 9.08969155173681e-07 -2.11147578188602e-05 0.000112849241426016 -2.07790899383454e-05 2.64546701176914e-05 -9.82294980264695e-05 -1.97537316783213e-05 1.32628632191755e-05 -2.07790899383454e-05 9.97044112175004e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 914 0 0 0 0 0 2592 +1097 1127 0.999988569807514 0.000299587602576968 0.00477184467388863 0.00424622360523332 -0.000317234458191527 0.999993112821637 0.003697792799805 -0.00871417330890711 -0.00477070399646352 -0.00369926432688122 0.999981777747384 -0.0109844477171423 3.17688967276161e-05 -6.13836643983196e-06 -1.18930646698879e-05 2.36645557104276e-06 8.59523889792208e-06 1.23133708154212e-05 -6.13836643983196e-06 9.15052902276063e-05 1.54296912016142e-05 -5.67999499714325e-06 -4.40631656132127e-06 -3.56706882683709e-05 -1.18930646698879e-05 1.54296912016142e-05 2.30700428677488e-05 -1.31189914493228e-05 -1.02271387061105e-05 -4.60148129519513e-06 2.36645557104276e-06 -5.67999499714325e-06 -1.31189914493228e-05 3.99134528314777e-05 -2.77143350681682e-05 2.76664460417364e-06 8.59523889792208e-06 -4.40631656132127e-06 -1.02271387061105e-05 -2.77143350681682e-05 0.000144984583158017 -4.73501746108972e-06 1.23133708154212e-05 -3.56706882683709e-05 -4.60148129519513e-06 2.76664460417364e-06 -4.73501746108972e-06 5.70613374871977e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 825 0 0 0 0 0 2717 +1097 1124 0.999991618212132 -0.000473920145699965 0.00406680527894195 0.00572894476894242 0.000479560537373363 0.999998924413524 -0.00138607124122501 -0.0130799570074316 -0.0040661440176566 0.00138800990279485 0.999990769908071 -0.00195057866863547 3.5030645759306e-05 -3.64800766117278e-05 -1.5801494267834e-05 2.83311334852261e-06 7.19103789686173e-06 3.55115701328302e-05 -3.64800766117278e-05 0.000157523080750064 2.88697756742224e-05 -1.66544320284475e-06 -1.56612568285157e-05 -9.37404158492285e-05 -1.5801494267834e-05 2.88697756742224e-05 2.44757104006714e-05 -1.22948281263441e-05 -1.05066914576798e-05 -1.5212235166854e-05 2.83311334852261e-06 -1.66544320284475e-06 -1.22948281263441e-05 3.88043336748404e-05 -2.11573110631178e-05 -7.39302761221473e-06 7.19103789686173e-06 -1.56612568285157e-05 -1.05066914576798e-05 -2.11573110631178e-05 0.000118133011154706 1.01612962327903e-05 3.55115701328302e-05 -9.37404158492285e-05 -1.5212235166854e-05 -7.39302761221473e-06 1.01612962327903e-05 0.000107064320029341 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 926 0 0 0 0 0 2622 +1097 1129 0.999984753886878 -0.000106523853060419 0.00552092804413791 0.00406052148122853 9.81842935625439e-05 0.999998853943862 0.00151078483141294 -0.00648235440207439 -0.00552108265146583 -0.00151021972939668 0.999983618307182 -0.00818102684921575 2.18963234569773e-05 -1.59342264597571e-05 -1.24329740202957e-05 2.66150183224052e-06 3.4325688887523e-06 9.22915728355497e-06 -1.59342264597571e-05 0.000112732702544237 1.76907680497094e-05 -1.72332755376016e-06 -1.74052900111285e-05 -5.71840086974984e-05 -1.24329740202957e-05 1.76907680497094e-05 2.23462074889573e-05 -9.96206070925055e-06 -7.39408715555925e-06 -8.58633346217575e-06 2.66150183224052e-06 -1.72332755376016e-06 -9.96206070925055e-06 3.90683853742658e-05 -2.72826347746564e-05 -1.37646858472695e-06 3.4325688887523e-06 -1.74052900111285e-05 -7.39408715555925e-06 -2.72826347746564e-05 0.000119281865449692 2.04936589006801e-06 9.22915728355497e-06 -5.71840086974984e-05 -8.58633346217575e-06 -1.37646858472695e-06 2.04936589006801e-06 6.46279107925807e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 924 0 0 0 0 0 2579 +1097 1131 0.999998678330611 -0.000311086651612933 0.00159579513934277 0.00313073658311565 0.000315318241835038 0.999996433339445 -0.00265214682748639 -0.0102508162455088 -0.00159496440020704 0.00265264650554278 0.999995209766066 -0.00155268849756456 3.49268228048722e-05 -1.21209026338107e-05 -1.34701096226175e-05 6.07275641277176e-06 1.09643342557712e-07 1.56696824371912e-05 -1.21209026338107e-05 0.000126298645255918 1.98768349178066e-05 -1.84957774555839e-05 3.96030043913113e-05 -6.298215845152e-05 -1.34701096226175e-05 1.98768349178066e-05 2.49634565396805e-05 -1.71957417961879e-05 1.8154066967071e-06 -9.44192036734491e-06 6.07275641277176e-06 -1.84957774555839e-05 -1.71957417961879e-05 4.33133142129847e-05 -3.31569160524804e-05 2.78132134230019e-06 1.09643342557712e-07 3.96030043913113e-05 1.8154066967071e-06 -3.31569160524804e-05 0.000129977910611099 -1.10747936333021e-05 1.56696824371912e-05 -6.298215845152e-05 -9.44192036734491e-06 2.78132134230019e-06 -1.10747936333021e-05 8.08061728604194e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 926 0 0 0 0 0 2540 +1097 1132 0.99999767951688 0.000319409185209117 -0.00213047849740041 0.00372104066004868 -0.000327770136614981 0.999992242444881 -0.00392525372368609 -0.0120686106323366 0.00212920820800241 0.00392594292242923 0.999990026672555 -0.0011408431059262 3.12113751376069e-05 -1.21737902471413e-05 -1.1147932251893e-05 4.96853286773847e-06 5.76021297982752e-07 1.19912770457615e-05 -1.21737902471413e-05 0.000111016518882349 2.17103709659101e-05 -1.91456923700978e-05 1.97450847517045e-05 -5.50218213944767e-05 -1.1147932251893e-05 2.17103709659101e-05 2.73586631265112e-05 -1.86852058451878e-05 -6.22328203795101e-06 -7.91488757584048e-06 4.96853286773847e-06 -1.91456923700978e-05 -1.86852058451878e-05 4.41773146029432e-05 -2.70184499205009e-05 3.43296554352322e-06 5.76021297982752e-07 1.97450847517045e-05 -6.22328203795101e-06 -2.70184499205009e-05 0.000137333809176086 -2.86494270529646e-06 1.19912770457615e-05 -5.50218213944767e-05 -7.91488757584048e-06 3.43296554352322e-06 -2.86494270529646e-06 7.58090271053386e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 923 0 0 0 0 0 2557 +1097 1126 0.9999572928258 0.000265846525339747 0.00923806528027001 0.00222460564114198 -0.00030002745005974 0.999993114332839 0.00369882014138673 -0.00111586523069985 -0.00923701835154484 -0.00370143384840014 0.999950487213962 -0.0154128678323584 3.22762471681183e-05 -1.8340034296824e-05 -1.35697243787442e-05 5.88776956439641e-06 -3.81227163136025e-06 1.07738763130548e-05 -1.8340034296824e-05 0.00014375949447256 2.63173747877999e-05 -1.0288910207344e-05 2.83242099747163e-05 -7.12951586402506e-05 -1.35697243787442e-05 2.63173747877999e-05 2.57269612612197e-05 -1.33462898109097e-05 -6.22050012233615e-06 -9.35620869792435e-06 5.88776956439641e-06 -1.0288910207344e-05 -1.33462898109097e-05 3.52361885265136e-05 -2.03621390294871e-05 4.56688098943871e-06 -3.81227163136025e-06 2.83242099747163e-05 -6.22050012233615e-06 -2.03621390294871e-05 0.000152016407018802 -2.28203953169882e-05 1.07738763130548e-05 -7.12951586402506e-05 -9.35620869792435e-06 4.56688098943871e-06 -2.28203953169882e-05 7.31068840887254e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 826 0 0 0 0 0 2693 +1097 1099 0.999994880999021 -0.000737899394117394 0.00311343543981974 -0.0111859860821517 0.000738808169775149 0.999999684813888 -0.000290748368209024 0.0209403681130911 -0.00311321991546339 0.000293047111406849 0.999995110980623 -0.00358603382010137 4.06326223058107e-05 -4.05717468061325e-05 -1.63759186163419e-05 7.32041316065348e-06 -1.02657217883196e-06 3.82413624937719e-05 -4.05717468061325e-05 0.000176566349158957 3.54436940246411e-05 -1.03497385728106e-05 -4.28456476062645e-06 -0.000119616623967686 -1.63759186163419e-05 3.54436940246411e-05 2.76990871721711e-05 -1.78122811474634e-05 -8.42526242053673e-06 -1.91047734069742e-05 7.32041316065348e-06 -1.03497385728106e-05 -1.78122811474634e-05 3.83792741658199e-05 -5.35373419756508e-06 6.39046924194387e-06 -1.02657217883196e-06 -4.28456476062645e-06 -8.42526242053673e-06 -5.35373419756508e-06 7.60008850667424e-05 -3.0468647140717e-06 3.82413624937719e-05 -0.000119616623967686 -1.91047734069742e-05 6.39046924194387e-06 -3.0468647140717e-06 0.000126980276382662 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 873 0 0 0 0 0 2624 +1097 1134 0.999998822623612 -0.000191210759256322 0.00152256028935578 0.00537080834150381 0.000189990272100813 0.999999660585416 0.000801706148769449 -0.0181981209853251 -0.00152271306741802 -0.000801415933215895 0.999998519537612 -0.00795162678764863 4.43090664504004e-05 -2.44893747004822e-05 -1.81609611633778e-05 7.47304115212973e-06 7.07756941366339e-06 4.51931980932776e-05 -2.44893747004822e-05 0.000168449021259765 2.55272608377387e-05 -1.38718543860093e-05 1.19572752093832e-05 -9.24219364808727e-05 -1.81609611633778e-05 2.55272608377387e-05 2.8103646482831e-05 -1.91220485158444e-05 -7.68777684028523e-06 -1.17629912802021e-05 7.47304115212973e-06 -1.38718543860093e-05 -1.91220485158444e-05 4.91476902377639e-05 -2.65428674788652e-05 2.19021720727717e-06 7.07756941366339e-06 1.19572752093832e-05 -7.68777684028523e-06 -2.65428674788652e-05 0.00015314654887225 -2.25437551828821e-07 4.51931980932776e-05 -9.24219364808727e-05 -1.17629912802021e-05 2.19021720727717e-06 -2.25437551828821e-07 0.000145024400477542 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 790 0 0 0 0 0 2657 +1097 1137 0.999996655079963 0.000391301202256825 0.0025566994846528 0.0070116007665094 -0.000386758773764714 0.999998346467954 -0.00177692965773907 -0.015745124697048 -0.00255739057177967 0.00177593488809388 0.999995152892621 0.00474736436906658 2.66532174438974e-05 -1.308423177321e-05 -1.13332238287148e-05 5.47719752549426e-06 3.48632324730734e-06 1.4465548828482e-05 -1.308423177321e-05 0.00014492460872129 3.01496767884783e-05 -1.75967343343016e-05 1.28323799693215e-05 -6.57763873137674e-05 -1.13332238287148e-05 3.01496767884783e-05 2.81746044953137e-05 -1.8606230715371e-05 -1.00611573907077e-05 -9.30104806769823e-06 5.47719752549426e-06 -1.75967343343016e-05 -1.8606230715371e-05 3.78621074066941e-05 -1.01209739705358e-05 5.35991183705797e-06 3.48632324730734e-06 1.28323799693215e-05 -1.00611573907077e-05 -1.01209739705358e-05 0.000107625844814386 -1.23995608468765e-05 1.4465548828482e-05 -6.57763873137674e-05 -9.30104806769823e-06 5.35991183705797e-06 -1.23995608468765e-05 7.02996746267082e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 913 0 0 0 0 0 2598 +1097 1133 0.999995752224816 0.00073310192874879 -0.00282100937353903 0.00479573769378418 -0.000733336467191335 0.999999727738043 -8.21064233379177e-05 -0.014129429401853 0.00282094841310819 8.4174823616195e-05 0.999996017574395 -0.00578421468978144 4.42736416701483e-05 -1.82927457416275e-05 -1.72207460437208e-05 1.37353209930868e-05 -2.12405098396485e-06 4.50153838075401e-05 -1.82927457416275e-05 0.000103671044928754 1.72249674538225e-05 -1.56958466131816e-05 1.78969588927646e-05 -5.22942601304641e-05 -1.72207460437208e-05 1.72249674538225e-05 2.60722479921067e-05 -1.82566137093316e-05 -9.63296208084319e-06 -9.76640731568868e-06 1.37353209930868e-05 -1.56958466131816e-05 -1.82566137093316e-05 4.16760936112358e-05 -8.71855743241626e-06 9.16759433650008e-06 -2.12405098396485e-06 1.78969588927646e-05 -9.63296208084319e-06 -8.71855743241626e-06 0.000116956607141755 -9.79365457181286e-06 4.50153838075401e-05 -5.22942601304641e-05 -9.76640731568868e-06 9.16759433650008e-06 -9.79365457181286e-06 0.000123167906134392 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 791 0 0 0 0 0 2501 +1097 1101 0.999999495686327 0.00058366798958494 -0.000817287445942502 -0.00646340504599165 -0.000583430841256044 0.999999787645819 0.000290373500640893 0.0145995272392563 0.000817456754105444 -0.000289896523499432 0.99999962386216 -0.000239962556573936 4.5861077970201e-05 -5.24198638940498e-05 -2.08337646955599e-05 1.19394369853733e-05 -5.06535119246504e-06 5.72743561608555e-05 -5.24198638940498e-05 0.000168791547597968 2.71004251405515e-05 -9.11983971551203e-06 1.81120236438896e-06 -0.000135768712261965 -2.08337646955599e-05 2.71004251405515e-05 2.4461032679191e-05 -1.48312150154779e-05 -1.26884273971714e-05 -2.4493026069981e-05 1.19394369853733e-05 -9.11983971551203e-06 -1.48312150154779e-05 3.75902031974975e-05 -9.56203358426853e-06 1.72071109566113e-05 -5.06535119246504e-06 1.81120236438896e-06 -1.26884273971714e-05 -9.56203358426853e-06 0.00010901381594705 -1.02980759143373e-05 5.72743561608555e-05 -0.000135768712261965 -2.4493026069981e-05 1.72071109566113e-05 -1.02980759143373e-05 0.000154059676100453 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 795 0 0 0 0 0 2596 +1097 1140 0.999999882266574 0.000474716215409766 0.000100555224997308 -0.00049448171057 -0.000474443317218373 0.999996251157872 -0.00269677098420865 0.0039159138417086 -0.000101835048947095 0.00269672295895405 0.999996358650823 0.00478251215570947 3.05553316489596e-05 -1.39906807713266e-05 -1.40567993732301e-05 4.62553325805457e-06 8.88334458659293e-06 1.43911162739033e-05 -1.39906807713266e-05 0.000136385023361603 2.32482275532876e-05 -1.4536287044625e-06 -2.37280004824747e-05 -7.63407202637559e-05 -1.40567993732301e-05 2.32482275532876e-05 2.41345114601756e-05 -1.30013592874211e-05 -1.44286964954031e-05 -1.19320014199861e-05 4.62553325805457e-06 -1.4536287044625e-06 -1.30013592874211e-05 3.45702517939404e-05 -2.89794451709973e-06 -7.9443932582084e-07 8.88334458659293e-06 -2.37280004824747e-05 -1.44286964954031e-05 -2.89794451709973e-06 8.28906375016611e-05 1.53804256141196e-05 1.43911162739033e-05 -7.63407202637559e-05 -1.19320014199861e-05 -7.9443932582084e-07 1.53804256141196e-05 7.84095554528973e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 911 0 0 0 0 0 2638 +1097 1135 0.999999471067457 0.000290589910367499 0.000986621664972306 0.00647310554238831 -0.000291790250296263 0.999999217261229 0.00121669033836544 -0.0187384189251554 -0.000986267334768906 -0.00121697758140089 0.999998773120403 -0.00254232859582889 2.66007029813767e-05 -9.94765957293239e-06 -1.24736341246636e-05 5.5339918510935e-06 4.39997037198752e-06 3.93197660282049e-06 -9.94765957293239e-06 8.39947920988285e-05 1.46824761112906e-05 -6.01986394586244e-06 -5.15532266432515e-06 -3.28599009085742e-05 -1.24736341246636e-05 1.46824761112906e-05 2.1209956382045e-05 -1.14165114147935e-05 -8.60546135924021e-06 -1.39515690357604e-06 5.5339918510935e-06 -6.01986394586244e-06 -1.14165114147935e-05 3.77213713936699e-05 -3.34698122813199e-05 -1.27175096256299e-06 4.39997037198752e-06 -5.15532266432515e-06 -8.60546135924021e-06 -3.34698122813199e-05 0.000151954608231515 -2.63968193815056e-06 3.93197660282049e-06 -3.28599009085742e-05 -1.39515690357604e-06 -1.27175096256299e-06 -2.63968193815056e-06 4.92575300756945e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 917 0 0 0 0 0 2579 +1097 1136 0.999981807780621 0.000496640166850472 0.00601144378223458 0.0054066864343485 -0.000517369528302935 0.999993924369798 0.0034472528572491 -0.00876272384720848 -0.00600969521469098 -0.0034503002819029 0.999975989207437 -0.0112656583654031 3.47695903146046e-05 -2.9369700689222e-05 -1.37425216960158e-05 3.16615791572187e-06 2.58117566040868e-06 2.88853793550435e-05 -2.9369700689222e-05 0.00013270439148305 2.49593371594461e-05 -4.20484140150589e-06 -3.41438458172244e-06 -6.63093363780286e-05 -1.37425216960158e-05 2.49593371594461e-05 2.50439938606866e-05 -1.44660187078153e-05 -1.07427707311254e-05 -1.00969860881817e-05 3.16615791572187e-06 -4.20484140150589e-06 -1.44660187078153e-05 3.73832651359608e-05 -1.18805544126057e-05 -1.0541609742729e-06 2.58117566040868e-06 -3.41438458172244e-06 -1.07427707311254e-05 -1.18805544126057e-05 9.02690375563676e-05 -4.16743588942339e-06 2.88853793550435e-05 -6.63093363780286e-05 -1.00969860881817e-05 -1.0541609742729e-06 -4.16743588942339e-06 8.40830052168295e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 830 0 0 0 0 0 2638 +1097 1139 0.999998592009386 0.0015257574791198 0.000698601002297703 -0.00420676163859814 -0.00152516345410576 0.999998475643522 -0.000850051216088142 0.0182074672453762 -0.000699896909381321 0.000848984538506302 0.999999394684602 -0.00311768620145452 3.24917218183771e-05 -3.22335628654939e-05 -1.57672438245712e-05 5.38818248256668e-06 -6.04547274652357e-08 1.81095924649983e-05 -3.22335628654939e-05 0.000184738302736845 3.10049655394671e-05 -4.80154973148167e-06 8.26995558855012e-06 -0.000104274368857318 -1.57672438245712e-05 3.10049655394671e-05 2.55300770157645e-05 -1.28515782048708e-05 -7.41896028075208e-06 -1.68217249646501e-05 5.38818248256668e-06 -4.80154973148167e-06 -1.28515782048708e-05 3.45675683076713e-05 -6.45732092315184e-06 3.63483974454146e-06 -6.04547274652357e-08 8.26995558855012e-06 -7.41896028075208e-06 -6.45732092315184e-06 8.94464263037138e-05 -1.25099266150665e-05 1.81095924649983e-05 -0.000104274368857318 -1.68217249646501e-05 3.63483974454146e-06 -1.25099266150665e-05 8.66257474445849e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 932 0 0 0 0 0 2678 +1098 1130 0.999999475447791 0.000999868068505474 0.00022218908180823 -0.00834206092752401 -0.00100096805687143 0.999986963992749 0.00500698587114934 0.033714396219216 -0.000217179860057729 -0.00500720564889732 0.999987440283376 -0.0114872117906449 2.56295955282052e-05 -1.16934665980325e-05 -1.17285696553743e-05 6.08774571519389e-07 8.60615471231005e-06 1.28263926035905e-05 -1.16934665980325e-05 9.1571391811916e-05 1.88619513057811e-05 7.14168290560136e-06 -6.49974631021217e-05 -4.11680801884406e-05 -1.17285696553743e-05 1.88619513057811e-05 2.77877426339668e-05 -6.57191952981836e-06 -2.88844143722384e-05 -7.07775651338823e-06 6.08774571519389e-07 7.14168290560136e-06 -6.57191952981836e-06 6.93295011240847e-05 -0.000118866891620107 -3.23926201714381e-06 8.60615471231005e-06 -6.49974631021217e-05 -2.88844143722384e-05 -0.000118866891620107 0.000436140935275499 2.18159159981278e-05 1.28263926035905e-05 -4.11680801884406e-05 -7.07775651338823e-06 -3.23926201714381e-06 2.18159159981278e-05 6.39189113912723e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 855 0 0 0 0 0 2716 +1098 1125 0.999999656741033 2.19533224651303e-05 0.000828272822353143 0.0023044031630871 -2.14770639789994e-05 0.999999834453139 -0.00057500646063568 -0.00360612834091186 -0.000828285308537427 0.000574988474391158 0.999999491665722 0.000327639173348955 2.37809477421497e-05 -1.26376103155019e-05 -1.1608820599868e-05 6.90419235299619e-06 -3.25093541986692e-06 1.81986529277653e-05 -1.26376103155019e-05 8.82692856913153e-05 1.55590748596996e-05 -9.03529686452376e-06 8.27671715101376e-06 -3.54704869905901e-05 -1.1608820599868e-05 1.55590748596996e-05 1.81848309419803e-05 -9.65182426473019e-06 -6.10587620093863e-06 -7.84152399916086e-06 6.90419235299619e-06 -9.03529686452376e-06 -9.65182426473019e-06 5.72900090511322e-05 -8.38719739683202e-05 2.41165043187886e-06 -3.25093541986692e-06 8.27671715101376e-06 -6.10587620093863e-06 -8.38719739683202e-05 0.000276608107158825 -9.75349949560721e-07 1.81986529277653e-05 -3.54704869905901e-05 -7.84152399916086e-06 2.41165043187886e-06 -9.75349949560721e-07 6.71608943338331e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 928 0 0 0 0 0 2593 +1098 1132 0.999973442194181 0.00138381862605778 -0.0071554141969901 -4.10563373848439e-05 -0.00140294789074501 0.999995453892775 -0.0026690693133401 0.000312396980805396 0.00715168815987988 0.00267903710197063 0.999970837633113 0.00409493908172833 3.06033729993432e-05 -2.98568089341318e-05 -1.43635189811859e-05 5.52289850668328e-06 -6.58963683041417e-06 2.80899526344113e-05 -2.98568089341318e-05 0.000142478061695372 2.79155860358998e-05 -2.19251963690147e-05 2.27914924578923e-05 -7.16341142161791e-05 -1.43635189811859e-05 2.79155860358998e-05 2.41476648265096e-05 -1.4166913803787e-05 -2.38663949052195e-06 -1.10153264218957e-05 5.52289850668328e-06 -2.19251963690147e-05 -1.4166913803787e-05 4.260957377584e-05 -3.31159504819097e-05 6.84864212028358e-06 -6.58963683041417e-06 2.27914924578923e-05 -2.38663949052195e-06 -3.31159504819097e-05 0.000152869618848011 -2.0553725867137e-05 2.80899526344113e-05 -7.16341142161791e-05 -1.10153264218957e-05 6.84864212028358e-06 -2.0553725867137e-05 8.98380942816677e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 930 0 0 0 0 0 2559 +1098 1124 0.999990746423729 -0.000642438143026357 0.00425374425015367 0.000655343654894671 0.000650594672120464 0.999997952089712 -0.00191638799678071 0.00279691184546723 -0.00425250437812109 0.00191913772668393 0.999989116499225 -0.00287511572565176 3.28042075375331e-05 -6.94668933356114e-06 -1.11690630282184e-05 8.9299633936561e-06 -2.51611084333119e-06 1.19269316231425e-05 -6.94668933356114e-06 0.000104974249795455 1.56025658287008e-05 4.58842581326263e-06 -2.10273832762323e-05 -5.39826026410141e-05 -1.11690630282184e-05 1.56025658287008e-05 1.9209317653852e-05 -6.06296164280924e-06 -1.00012231251727e-05 -9.04062765553237e-06 8.9299633936561e-06 4.58842581326263e-06 -6.06296164280924e-06 4.7039068223244e-05 -7.04672898420171e-05 -1.48719235331569e-06 -2.51611084333119e-06 -2.10273832762323e-05 -1.00012231251727e-05 -7.04672898420171e-05 0.000261616919872603 6.66279787676648e-06 1.19269316231425e-05 -5.39826026410141e-05 -9.04062765553237e-06 -1.48719235331569e-06 6.66279787676648e-06 7.80735239983693e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 924 0 0 0 0 0 2600 +1098 1134 0.999992600770171 -0.000727873753971285 0.00377738066748481 0.0004801465679657 0.00071371886134217 0.999992724247583 0.00374727331338911 -0.000364974401962646 -0.00378008072609206 -0.00374454959862378 0.999985844568816 -0.0116698608121636 6.36806843219675e-05 -7.93508533510587e-05 -2.78015708718677e-05 1.18647602747971e-05 -1.16694001617464e-05 9.61610235339581e-05 -7.93508533510587e-05 0.000217854282689765 3.73208785115966e-05 -8.28662841954918e-06 -1.32914010924265e-06 -0.000171740991005988 -2.78015708718677e-05 3.73208785115966e-05 3.13167761602824e-05 -1.78120133479802e-05 -1.31697408464326e-05 -3.12869952862799e-05 1.18647602747971e-05 -8.28662841954918e-06 -1.78120133479802e-05 5.24096249545724e-05 -4.25091857057133e-05 1.84283815662735e-05 -1.16694001617464e-05 -1.32914010924265e-06 -1.31697408464326e-05 -4.25091857057133e-05 0.000193917125957221 -3.77785112998547e-05 9.61610235339581e-05 -0.000171740991005988 -3.12869952862799e-05 1.84283815662735e-05 -3.77785112998547e-05 0.000238404247733099 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 800 0 0 0 0 0 2722 +1098 1129 0.999913462561379 -0.00103446873038054 0.0131147726995 -0.00347277045617191 0.000982083424777387 0.999991516980034 0.00400018501047658 0.0180623961939117 -0.0131187995129304 -0.00398695904382387 0.999905996210105 -0.0127916619435995 2.82331906642953e-05 -2.01938974134198e-05 -1.50002275806111e-05 8.57026611977858e-06 -7.8294679337902e-06 9.53120794191504e-06 -2.01938974134198e-05 0.000132789516682321 2.71391504259976e-05 -9.06050219233719e-06 -8.82980553596609e-06 -6.30444207581937e-05 -1.50002275806111e-05 2.71391504259976e-05 2.49316297403559e-05 -9.43385191161254e-06 -9.44511965819096e-06 -1.32646701203256e-05 8.57026611977858e-06 -9.06050219233719e-06 -9.43385191161254e-06 5.97444190398294e-05 -9.98551235608347e-05 3.87465348366361e-06 -7.8294679337902e-06 -8.82980553596609e-06 -9.44511965819096e-06 -9.98551235608347e-05 0.000352470155714633 4.6161718286682e-07 9.53120794191504e-06 -6.30444207581937e-05 -1.32646701203256e-05 3.87465348366361e-06 4.6161718286682e-07 6.15196062731673e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 931 0 0 0 0 0 2578 +1098 1131 0.999989510304556 0.000810994025636809 -0.00450794515763611 -0.002655646847365 -0.000821355833075518 0.99999702414267 -0.00229718967435599 0.00882326913665638 0.00450606873553282 0.00230086820458634 0.999987200593116 0.00349119394587429 3.50755419279139e-05 -3.75882872308358e-05 -2.17623730625616e-05 1.74902057102551e-05 -1.37416609701828e-05 3.2243209458339e-05 -3.75882872308358e-05 0.000165971265989333 3.57365493607429e-05 -2.49725636853231e-05 3.37420050570104e-05 -9.2436758000233e-05 -2.17623730625616e-05 3.57365493607429e-05 3.29385853696893e-05 -2.3652024700071e-05 -3.57382667103802e-07 -2.02367727090631e-05 1.74902057102551e-05 -2.49725636853231e-05 -2.3652024700071e-05 6.33557440629433e-05 -6.96916212563952e-05 1.46828516778778e-05 -1.37416609701828e-05 3.37420050570104e-05 -3.57382667103802e-07 -6.96916212563952e-05 0.000234874790653559 -2.7529997896812e-05 3.2243209458339e-05 -9.2436758000233e-05 -2.02367727090631e-05 1.46828516778778e-05 -2.7529997896812e-05 0.000104406653620789 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 938 0 0 0 0 0 2506 +1098 1136 0.99995910374739 0.000748724913099808 0.0090127822408292 -0.000750967034937759 -0.000798711523194492 0.999984313661196 0.00554386971791856 0.0149624950610162 -0.00900849002990062 -0.00555084160745393 0.999944016065314 -0.0144959341288699 3.19493972896753e-05 -1.78129808424368e-05 -1.21997212383018e-05 8.7390734016795e-07 5.76414841658193e-06 1.37297965579462e-05 -1.78129808424368e-05 0.000149013796722082 2.77684028366936e-05 -3.98818698314356e-06 -1.4370512344791e-05 -6.47715419213736e-05 -1.21997212383018e-05 2.77684028366936e-05 2.665451132859e-05 -1.42874329583907e-05 -8.7212904252788e-06 -9.42410695860325e-06 8.7390734016795e-07 -3.98818698314356e-06 -1.42874329583907e-05 4.82030302982762e-05 -4.6962079537042e-05 2.32910352054569e-07 5.76414841658193e-06 -1.4370512344791e-05 -8.7212904252788e-06 -4.6962079537042e-05 0.000186659281172601 2.27432768255548e-06 1.37297965579462e-05 -6.47715419213736e-05 -9.42410695860325e-06 2.32910352054569e-07 2.27432768255548e-06 7.78357733576249e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 845 0 0 0 0 0 2613 +1098 1128 0.999986426124736 0.000249240463381862 0.00520436792221939 -0.00238362236079579 -0.000283165720452516 0.999978711696885 0.00651889332730934 0.0174468625233923 -0.00520263235806391 -0.00652027853925665 0.999965208686941 -0.0133351686069275 2.6317404087671e-05 -1.14500607109505e-05 -1.10614875599263e-05 7.43642262987631e-06 -6.99070790197681e-06 1.1179319626419e-05 -1.14500607109505e-05 0.000113658157858393 2.21527807402701e-05 -1.42089853751435e-05 8.57812012517738e-06 -3.33375040618159e-05 -1.10614875599263e-05 2.21527807402701e-05 2.48369708336716e-05 -1.16478752131848e-05 -1.29756820452843e-05 -6.09364354397732e-06 7.43642262987631e-06 -1.42089853751435e-05 -1.16478752131848e-05 5.78611937846495e-05 -8.89950042600268e-05 2.97874915426546e-06 -6.99070790197681e-06 8.57812012517738e-06 -1.29756820452843e-05 -8.89950042600268e-05 0.000341674419066796 -1.8677008478071e-06 1.1179319626419e-05 -3.33375040618159e-05 -6.09364354397732e-06 2.97874915426546e-06 -1.8677008478071e-06 5.47617886592186e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 844 0 0 0 0 0 2729 +1098 1100 0.99999933062707 -0.000108414564438648 0.00115195125539934 -0.015370097072332 0.000106170979416528 0.999998097941984 0.00194752153686445 0.0342189660091283 -0.00115216020402037 -0.00194739792945323 0.999997440080808 -0.00478808952191018 3.73662192635629e-05 -3.1845978482688e-05 -1.6531509203551e-05 7.17016143811497e-06 2.01371018431349e-06 3.49987957841727e-05 -3.1845978482688e-05 0.000127813823124878 2.1289302809248e-05 -2.06807742604807e-06 -1.65905612542175e-05 -9.08875377765733e-05 -1.6531509203551e-05 2.1289302809248e-05 2.34919009034595e-05 -1.24168610901672e-05 -7.24304544965475e-06 -1.4792226803535e-05 7.17016143811497e-06 -2.06807742604807e-06 -1.24168610901672e-05 3.74460346407652e-05 -1.78704258850724e-05 8.04335254520584e-06 2.01371018431349e-06 -1.65905612542175e-05 -7.24304544965475e-06 -1.78704258850724e-05 8.97592013544364e-05 2.90067679882742e-06 3.49987957841727e-05 -9.08875377765733e-05 -1.4792226803535e-05 8.04335254520584e-06 2.90067679882742e-06 0.00010343640437372 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 863 0 0 0 0 0 2652 +1098 1126 0.999992319485254 0.000573317571166519 0.00387714810956922 -0.00200070965821401 -0.000594099095734637 0.999985453380724 0.00536097688978774 0.0146615726362492 -0.00387401816792226 -0.00536323912491162 0.999978113585154 -0.0128515739941069 3.18512433031026e-05 -2.48014254773636e-05 -1.38192197287735e-05 3.29559030424298e-06 -2.3664455389636e-07 2.04875194447111e-05 -2.48014254773636e-05 0.00015631737284983 3.11710569071391e-05 -1.26805163213039e-05 1.99640302931374e-06 -6.99958020491443e-05 -1.38192197287735e-05 3.11710569071391e-05 2.74458577558364e-05 -1.28599729094731e-05 -1.09047983051401e-05 -1.08361613557442e-05 3.29559030424298e-06 -1.26805163213039e-05 -1.28599729094731e-05 4.81784125949775e-05 -4.54147047115089e-05 1.77008065032718e-06 -2.3664455389636e-07 1.99640302931374e-06 -1.09047983051401e-05 -4.54147047115089e-05 0.000203249142000287 -7.44222623853825e-06 2.04875194447111e-05 -6.99958020491443e-05 -1.08361613557442e-05 1.77008065032718e-06 -7.44222623853825e-06 8.52136960978877e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 851 0 0 0 0 0 2679 +1098 1133 0.999963488270156 0.000187338860915603 0.00854324474262895 -0.000843744415781363 -0.00022138215651806 0.999992039140876 0.00398404879651991 0.00727873780175118 -0.00854243036389772 -0.00398579465395135 0.999955569175178 -0.0158138272156703 4.57884449820568e-05 -2.62747902051716e-05 -1.54088407514761e-05 1.49484737055432e-05 -2.712908980001e-05 5.83804728343008e-05 -2.62747902051716e-05 0.000123447479709059 1.47869213779828e-05 -2.4648466613631e-05 6.58070662308928e-05 -9.08279728781926e-05 -1.54088407514761e-05 1.47869213779828e-05 2.25134094842982e-05 -1.38579152717125e-05 -7.92956141697335e-07 -1.2832360314396e-05 1.49484737055432e-05 -2.4648466613631e-05 -1.38579152717125e-05 4.98138644127463e-05 -6.18878280761854e-05 3.19258707874974e-05 -2.712908980001e-05 6.58070662308928e-05 -7.92956141697335e-07 -6.18878280761854e-05 0.000253499609376749 -9.27278598339162e-05 5.83804728343008e-05 -9.08279728781926e-05 -1.2832360314396e-05 3.19258707874974e-05 -9.27278598339162e-05 0.000171131471500017 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 812 0 0 0 0 0 2564 +1098 1137 0.999998443462397 1.9676249454403e-05 0.00176428048480818 0.00316416817745465 -1.54602945857583e-05 0.999997144784898 -0.00238959892690099 -0.00549108538012408 -0.00176432246575248 0.00238956793110438 0.999995588555939 0.00524107279228412 2.47107671429555e-05 -1.08032496232788e-05 -1.16848858802526e-05 3.16698227214184e-06 1.28009868524985e-05 1.48725785618575e-05 -1.08032496232788e-05 9.88414300166293e-05 1.98092849006931e-05 1.3086036728388e-07 -2.90697412953938e-05 -3.41658690411967e-05 -1.16848858802526e-05 1.98092849006931e-05 2.40477369932111e-05 -1.01187588972229e-05 -1.91040787677155e-05 -6.42970537678286e-06 3.16698227214184e-06 1.3086036728388e-07 -1.01187588972229e-05 3.99529856866153e-05 -3.53890303023267e-05 1.15677354146103e-06 1.28009868524985e-05 -2.90697412953938e-05 -1.91040787677155e-05 -3.53890303023267e-05 0.000178276706704029 1.78000131775159e-05 1.48725785618575e-05 -3.41658690411967e-05 -6.42970537678286e-06 1.15677354146103e-06 1.78000131775159e-05 5.18669535887645e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 930 0 0 0 0 0 2570 +1098 1135 0.999999576655103 0.000590691772285471 0.000705530187288604 0.00123388556684326 -0.000590956186703471 0.999999755213637 0.000374624414045609 -0.000425514522935428 -0.000705308727025362 -0.000375041192879359 0.999999680941801 -0.00569944031889197 2.3834336776189e-05 -2.47139654586572e-05 -1.21110253785899e-05 7.71547133152864e-06 -6.53474933152879e-08 8.98275801579942e-06 -2.47139654586572e-05 0.000113910809180285 2.13054773519742e-05 -7.85570230274174e-06 -1.30765139225854e-05 -3.50926049434827e-05 -1.21110253785899e-05 2.13054773519742e-05 2.41952641092215e-05 -1.37590118815897e-05 -9.85741897064558e-06 -6.95568885252987e-06 7.71547133152864e-06 -7.85570230274174e-06 -1.37590118815897e-05 4.49825201345331e-05 -3.15061736481434e-05 2.51043969481412e-06 -6.53474933152879e-08 -1.30765139225854e-05 -9.85741897064558e-06 -3.15061736481434e-05 0.000140212483701433 -1.69281383805879e-06 8.98275801579942e-06 -3.50926049434827e-05 -6.95568885252987e-06 2.51043969481412e-06 -1.69281383805879e-06 4.91488808685286e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 919 0 0 0 0 0 2663 +1098 1140 0.999999496359885 0.000177628713860441 0.000987789459427764 -0.00484001022514598 -0.000175537525629166 0.999997744334115 -0.00211672229140396 0.0217265751582247 -0.000988163221963001 0.00211654783122015 0.999997271875641 0.00531827253845715 2.93717123450427e-05 -2.61144900730181e-05 -1.41272897677604e-05 2.09898866581992e-06 9.08451038401776e-06 2.28984157712169e-05 -2.61144900730181e-05 0.000124753002207758 2.53835259566644e-05 -2.18887774512282e-06 -3.4608633036588e-05 -5.93321974550395e-05 -1.41272897677604e-05 2.53835259566644e-05 2.44204594237584e-05 -1.27162358775192e-05 -1.16240055356984e-05 -1.00806817744034e-05 2.09898866581992e-06 -2.18887774512282e-06 -1.27162358775192e-05 4.07562471714309e-05 -2.03514375522129e-05 2.58952972415822e-06 9.08451038401776e-06 -3.4608633036588e-05 -1.16240055356984e-05 -2.03514375522129e-05 0.00011441714107312 8.87885853251689e-06 2.28984157712169e-05 -5.93321974550395e-05 -1.00806817744034e-05 2.58952972415822e-06 8.87885853251689e-06 6.66403832662024e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 914 0 0 0 0 0 2651 +1098 1102 0.999989456569693 -0.000652473719483372 0.00454544029713575 -0.00359289672577039 0.000654482641046693 0.999999688810166 -0.000440490685942614 0.00668782490810137 -0.00454515147404468 0.000443460953430156 0.999989572415863 -0.00219662952900678 3.85542182130887e-05 -4.06719966782525e-05 -1.64350599007779e-05 8.58379636807969e-06 -1.7747058764388e-06 4.15776148282142e-05 -4.06719966782525e-05 0.000152163953145187 2.80266264885029e-05 -1.77543169928065e-05 1.35850230020619e-05 -0.000114987480234179 -1.64350599007779e-05 2.80266264885029e-05 2.55587438437727e-05 -1.57057701811167e-05 -9.49246112174738e-06 -1.79513244378594e-05 8.58379636807969e-06 -1.77543169928065e-05 -1.57057701811167e-05 3.31424665893201e-05 5.32522653656744e-07 1.43584032977348e-05 -1.7747058764388e-06 1.35850230020619e-05 -9.49246112174738e-06 5.32522653656744e-07 8.48915874104973e-05 -1.20269123893035e-05 4.15776148282142e-05 -0.000114987480234179 -1.79513244378594e-05 1.43584032977348e-05 -1.20269123893035e-05 0.000132035683361401 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 701 0 0 0 0 0 2602 +1098 1138 0.999997374150936 -9.29703428456756e-05 0.00228977023915621 -0.00805087049979519 8.86287635310275e-05 0.999998198463969 0.00189610489154634 0.0298186403150053 -0.00228994239557446 -0.00189589697315602 0.999995580859482 -0.000857334280514758 2.31153579221768e-05 -1.93552717632707e-05 -1.2008700023246e-05 3.48364200768001e-06 2.61728935552739e-06 1.19265714449652e-05 -1.93552717632707e-05 9.10486989502628e-05 2.01031915736228e-05 -5.53595537725765e-06 -1.97623003655846e-05 -4.64716932143051e-05 -1.2008700023246e-05 2.01031915736228e-05 2.14883382386075e-05 -1.08406147949776e-05 -1.11914372675524e-05 -1.09757023262462e-05 3.48364200768001e-06 -5.53595537725765e-06 -1.08406147949776e-05 4.23650925346861e-05 -4.5002795069776e-05 3.28642573714339e-06 2.61728935552739e-06 -1.97623003655846e-05 -1.11914372675524e-05 -4.5002795069776e-05 0.000192951267604679 9.5030083219095e-06 1.19265714449652e-05 -4.64716932143051e-05 -1.09757023262462e-05 3.28642573714339e-06 9.5030083219095e-06 4.41115219304187e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 944 0 0 0 0 0 2546 +1099 1133 0.999995075445231 0.000751253137383976 -0.0030470812281032 -0.00249682586798317 -0.000748907593886497 0.999999422475038 0.000770835265184013 0.0125363909752176 0.0030476585607491 -0.000768549486892616 0.999995060542293 -0.00470026927631428 2.55410197495887e-05 -1.43883443686108e-05 -1.37902027021448e-05 8.69392032122393e-06 -2.91506666645298e-06 1.04575668408662e-05 -1.43883443686108e-05 0.000110649515231764 1.55398660308678e-05 -9.84955848768174e-06 5.97622653563301e-06 -4.30986692336895e-05 -1.37902027021448e-05 1.55398660308678e-05 2.28471326156323e-05 -1.3880361085193e-05 -1.02004040361956e-05 -7.15280193778925e-06 8.69392032122393e-06 -9.84955848768174e-06 -1.3880361085193e-05 4.53284610438275e-05 -3.67143420018003e-05 5.19376047743573e-06 -2.91506666645298e-06 5.97622653563301e-06 -1.02004040361956e-05 -3.67143420018003e-05 0.000164457981191381 -1.14033005961509e-05 1.04575668408662e-05 -4.30986692336895e-05 -7.15280193778925e-06 5.19376047743573e-06 -1.14033005961509e-05 5.45910040439579e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 871 0 0 0 0 0 2485 +1099 1134 0.999998564241712 -0.00040460184658498 0.00164554302896658 -0.00429885746006402 0.000401465954393837 0.99999810380764 0.0019055724104967 0.01844471515549 -0.00164631090681655 -0.0019049090450527 0.999996830485941 -0.00927220568953158 2.77219092784503e-05 -2.38658774072463e-05 -1.57302706597306e-05 9.94105487984795e-06 -1.09424589097824e-05 1.45041917999025e-05 -2.38658774072463e-05 0.000116969142553029 1.78626435829278e-05 -1.664292696181e-05 3.09050211971786e-05 -6.28081260930205e-05 -1.57302706597306e-05 1.78626435829278e-05 2.21257258734588e-05 -1.32387173982363e-05 -4.52081604072852e-06 -9.35876837776713e-06 9.94105487984795e-06 -1.664292696181e-05 -1.32387173982363e-05 4.14648122195955e-05 -4.08183396825021e-05 1.31780741833638e-05 -1.09424589097824e-05 3.09050211971786e-05 -4.52081604072852e-06 -4.08183396825021e-05 0.000186327489209905 -3.81248176714324e-05 1.45041917999025e-05 -6.28081260930205e-05 -9.35876837776713e-06 1.31780741833638e-05 -3.81248176714324e-05 6.88403601338696e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 873 0 0 0 0 0 2734 +1098 1139 0.999998800186529 0.00151279059214609 -0.000333301855318927 -0.00518282437499497 -0.0015122555233692 0.999997576853 0.00159980353825477 0.0248979113339462 0.00033572121542149 -0.00159929758121728 0.999998664768365 -0.00250079047352522 2.49084623195336e-05 -2.4537586472599e-05 -1.57932707462028e-05 7.03459565386871e-06 1.60608341689416e-06 1.31447029817672e-05 -2.4537586472599e-05 0.00013222211486766 2.41276270583588e-05 -8.91391440310209e-06 -8.12732493292952e-06 -5.8143052510859e-05 -1.57932707462028e-05 2.41276270583588e-05 2.56818347487238e-05 -1.55726649569453e-05 -3.42147440397554e-06 -9.56569246915589e-06 7.03459565386871e-06 -8.91391440310209e-06 -1.55726649569453e-05 4.46855865359558e-05 -3.31367010419954e-05 2.8930958016053e-06 1.60608341689416e-06 -8.12732493292952e-06 -3.42147440397554e-06 -3.31367010419954e-05 0.0001257932106419 4.04833434692106e-06 1.31447029817672e-05 -5.8143052510859e-05 -9.56569246915589e-06 2.8930958016053e-06 4.04833434692106e-06 5.31363786388721e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 944 0 0 0 0 0 2668 +1099 1130 0.999998959077973 -0.000937044204289641 0.00109717415650831 -0.0114744722852704 0.000937633637823593 0.999999416324047 -0.000536837709054803 0.0329347764983436 -0.00109667047545023 0.000537865897644299 0.999999254006794 -0.00461101519729875 2.7063138789797e-05 -1.64055540668205e-05 -1.34981113808387e-05 2.48685858271223e-06 4.21370455684429e-06 1.6799865990709e-05 -1.64055540668205e-05 0.000114514549876979 2.64839424722328e-05 -1.32617109268385e-05 -6.4716901319299e-06 -5.46958908065936e-05 -1.34981113808387e-05 2.64839424722328e-05 2.71156953541158e-05 -1.489721462028e-05 -1.29274068396455e-05 -7.75826168208905e-06 2.48685858271223e-06 -1.32617109268385e-05 -1.489721462028e-05 6.11784761455338e-05 -7.82291316734494e-05 2.51960339210581e-06 4.21370455684429e-06 -6.4716901319299e-06 -1.29274068396455e-05 -7.82291316734494e-05 0.000273668170616938 -1.09099156029679e-05 1.6799865990709e-05 -5.46958908065936e-05 -7.75826168208905e-06 2.51960339210581e-06 -1.09099156029679e-05 7.72256151326176e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 898 0 0 0 0 0 2722 +1099 1136 0.999997614438763 -0.000488832142848472 0.00212888701401401 -0.00383125244111506 0.000488846526963418 0.999999880495084 -6.23629125348637e-06 0.0137174862761169 -0.00212888371110193 7.27697539952997e-06 0.999997733898027 -0.001997136426726 3.00547138922691e-05 -2.67070667209369e-05 -1.4368313484084e-05 8.30948676315438e-06 -3.20828434307832e-06 2.75660312095166e-05 -2.67070667209369e-05 0.000127754010963083 2.74383931693069e-05 -6.77803584386248e-06 -2.32744105272032e-05 -5.97412045023757e-05 -1.4368313484084e-05 2.74383931693069e-05 2.56515736769747e-05 -1.50091943807275e-05 -1.32267613055625e-05 -9.40816853447668e-06 8.30948676315438e-06 -6.77803584386248e-06 -1.50091943807275e-05 5.28238281856121e-05 -5.86048305524037e-05 8.05919323728039e-06 -3.20828434307832e-06 -2.32744105272032e-05 -1.32267613055625e-05 -5.86048305524037e-05 0.000225073711823411 -1.66693744949169e-05 2.75660312095166e-05 -5.97412045023757e-05 -9.40816853447668e-06 8.05919323728039e-06 -1.66693744949169e-05 9.1092758500788e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 886 0 0 0 0 0 2556 +1098 1101 0.999944940197353 -0.000415228465854669 0.0104854260301255 -0.0141555215484806 0.000366550689153709 0.999989149776492 0.00464391751446271 0.0432076212402869 -0.0104872405476546 -0.00463981838114344 0.999934242773536 -0.0138725093340072 3.01904958531686e-05 -2.80335704537474e-05 -1.45791046996229e-05 9.84275085172631e-06 -1.21682354531541e-05 2.80348695137e-05 -2.80335704537474e-05 0.000125689071837395 1.90236414683509e-05 -1.25194007552601e-05 2.66819756839549e-05 -8.19262489515363e-05 -1.45791046996229e-05 1.90236414683509e-05 2.10002999633294e-05 -1.25225418327109e-05 -4.49451633766846e-06 -1.27613545337676e-05 9.84275085172631e-06 -1.25194007552601e-05 -1.25225418327109e-05 4.92387942272755e-05 -4.72385052079919e-05 1.75282526217793e-05 -1.21682354531541e-05 2.66819756839549e-05 -4.49451633766846e-06 -4.72385052079919e-05 0.000212048377807832 -3.59348842059058e-05 2.80348695137e-05 -8.19262489515363e-05 -1.27613545337676e-05 1.75282526217793e-05 -3.59348842059058e-05 9.35347015030036e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 826 0 0 0 0 0 2610 +1099 1132 0.999963572258411 -0.000309526483902243 0.00852985050003153 -0.00802003738667047 0.000260211908359959 0.999983250734364 0.00578191495067317 0.0311481862365129 -0.00853149728710458 -0.00577948475989282 0.99994690414539 -0.0168148116437662 3.53815837137125e-05 -3.93117424597706e-05 -2.20988682866111e-05 1.90401974357092e-05 -2.81406246133095e-05 2.66734177095253e-05 -3.93117424597706e-05 0.000171353138897005 4.07749444479515e-05 -4.17239959258688e-05 6.7958650256624e-05 -8.29539981021604e-05 -2.20988682866111e-05 4.07749444479515e-05 3.51789750989415e-05 -2.6583095551221e-05 5.31832517384956e-06 -1.86611768768797e-05 1.90401974357092e-05 -4.17239959258688e-05 -2.6583095551221e-05 6.76799429474362e-05 -9.35732915117333e-05 2.0279820487692e-05 -2.81406246133095e-05 6.7958650256624e-05 5.31832517384956e-06 -9.35732915117333e-05 0.000365007943347421 -4.80879505584193e-05 2.66734177095253e-05 -8.29539981021604e-05 -1.86611768768797e-05 2.0279820487692e-05 -4.80879505584193e-05 8.20001314821738e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 969 0 0 0 0 0 2493 +1099 1135 0.99999315347787 0.000157779345713889 0.00369703977028696 -0.00520594187131686 -0.000173282418430656 0.999991192521947 0.00419342959131199 0.0172591486901452 -0.00369634557211311 -0.00419404151289593 0.999984373400505 -0.0114106117587273 3.86915801748538e-05 -9.32207388206055e-06 -1.0730998213929e-05 3.91560726780908e-06 9.15493481866731e-06 3.26054763980164e-05 -9.32207388206055e-06 0.000118092793458313 2.07345664931899e-05 -3.88025218955459e-06 -1.77240827600025e-05 -5.52939873507281e-05 -1.0730998213929e-05 2.07345664931899e-05 2.33024865412419e-05 -1.21873748859692e-05 -1.58160761039796e-05 -8.69934888605699e-06 3.91560726780908e-06 -3.88025218955459e-06 -1.21873748859692e-05 4.47742621551729e-05 -3.84222271312e-05 8.26340845886958e-06 9.15493481866731e-06 -1.77240827600025e-05 -1.58160761039796e-05 -3.84222271312e-05 0.000190786216007882 -1.00714444230466e-05 3.26054763980164e-05 -5.52939873507281e-05 -8.69934888605699e-06 8.26340845886958e-06 -1.00714444230466e-05 0.000100881279321672 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 955 0 0 0 0 0 2683 +1099 1101 0.999999342823911 0.000504898168073164 -0.0010292859588354 -0.0142928468836474 -0.000503041217078724 0.999998247028186 0.0018035770262932 0.0421939177544133 0.00103019477726268 -0.00180305806776405 0.999997843837838 -0.0048635555666579 2.04638975888685e-05 -7.01209489867788e-06 -1.22426984476822e-05 8.05750030636423e-06 -2.32199267842103e-06 5.17435745973029e-06 -7.01209489867788e-06 8.3442894074736e-05 1.76019657449609e-05 -1.19344745377413e-05 9.30049091083184e-06 -4.38051506287388e-05 -1.22426984476822e-05 1.76019657449609e-05 2.1629965113006e-05 -1.37143849209086e-05 -3.61256062046779e-07 -9.82938923642104e-06 8.05750030636423e-06 -1.19344745377413e-05 -1.37143849209086e-05 3.8405831876032e-05 -3.35119682679315e-05 1.44125603486569e-05 -2.32199267842103e-06 9.30049091083184e-06 -3.61256062046779e-07 -3.35119682679315e-05 0.000129460355164265 -2.54421140940716e-05 5.17435745973029e-06 -4.38051506287388e-05 -9.82938923642104e-06 1.44125603486569e-05 -2.54421140940716e-05 4.96847713070399e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 869 0 0 0 0 0 2564 +1099 1137 0.999976424534062 -0.00025959433530899 0.00686170436948086 -0.00282582482782346 0.00023282701405892 0.999992362079237 0.00390148366250169 0.020173072314769 -0.00686266476338467 -0.0038997940930668 0.999968847233941 -0.00870697013553164 2.83437591309185e-05 -2.13965808368889e-05 -1.29796139810371e-05 4.08647700608943e-06 1.86180178036793e-06 1.69397931433675e-05 -2.13965808368889e-05 0.000140892690046721 2.51354967388757e-05 -8.80315477055062e-06 1.18078566883384e-05 -6.40096410187955e-05 -1.29796139810371e-05 2.51354967388757e-05 2.42096670055066e-05 -1.30265593195928e-05 -9.73194524154733e-06 -7.49953652212773e-06 4.08647700608943e-06 -8.80315477055062e-06 -1.30265593195928e-05 3.63141135889511e-05 -2.26234614186664e-05 3.66604748366259e-06 1.86180178036793e-06 1.18078566883384e-05 -9.73194524154733e-06 -2.26234614186664e-05 0.000145524421286886 -2.02089739097035e-05 1.69397931433675e-05 -6.40096410187955e-05 -7.49953652212773e-06 3.66604748366259e-06 -2.02089739097035e-05 7.08972979993676e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 964 0 0 0 0 0 2594 +1099 1128 0.999999755222677 -0.00038869447513231 0.000581782769038703 -0.00930316733756257 0.000388970441989856 0.999999811866491 -0.000474308947504088 0.0305686829301648 -0.000581598298318468 0.000474535127704829 0.999999718279876 -0.00386898955993223 3.46344416195843e-05 -2.7257338198058e-05 -1.54977102208316e-05 4.37104189040257e-06 9.00946543771879e-06 3.01877529454431e-05 -2.7257338198058e-05 0.000133324153963091 2.7248335483704e-05 3.91021915106491e-06 -4.90917435299771e-05 -6.91475461249773e-05 -1.54977102208316e-05 2.7248335483704e-05 2.60845288595217e-05 -1.2085800972836e-05 -1.69852433327484e-05 -1.4794179541867e-05 4.37104189040257e-06 3.91021915106491e-06 -1.2085800972836e-05 5.27850564418185e-05 -4.58243715561848e-05 5.51343310905352e-07 9.00946543771879e-06 -4.90917435299771e-05 -1.69852433327484e-05 -4.58243715561848e-05 0.000191219047375067 1.14815364783537e-05 3.01877529454431e-05 -6.91475461249773e-05 -1.4794179541867e-05 5.51343310905352e-07 1.14815364783537e-05 8.99525066254174e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 897 0 0 0 0 0 2715 +1099 1139 0.999973456969022 -0.000212924195896909 0.00728285800432474 -0.0119049059848328 0.000184907721296244 0.999992581773557 0.00384736364151273 0.0421662974591816 -0.0072836231752446 -0.0038459148641423 0.999966078310809 -0.01050221167942 3.90861128366521e-05 -3.04098875834447e-05 -2.06048195749785e-05 1.09132450446173e-05 1.05355563431603e-05 3.16919181480741e-05 -3.04098875834447e-05 0.000126875962739809 2.32167561170894e-05 -6.62610151615916e-08 -2.750075470415e-05 -7.68643934237517e-05 -2.06048195749785e-05 2.32167561170894e-05 2.65204546820977e-05 -1.19542389255332e-05 -1.53568071710046e-05 -1.38567539680238e-05 1.09132450446173e-05 -6.62610151615916e-08 -1.19542389255332e-05 5.31299549283819e-05 -5.67012731118511e-05 7.5513336957351e-07 1.05355563431603e-05 -2.750075470415e-05 -1.53568071710046e-05 -5.67012731118511e-05 0.000227444034992559 1.75922927206697e-05 3.16919181480741e-05 -7.68643934237517e-05 -1.38567539680238e-05 7.5513336957351e-07 1.75922927206697e-05 9.04581391493352e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 961 0 0 0 0 0 2584 +1099 1140 0.999998768444087 0.000472692384071499 0.00149655344675609 -0.0086510402466697 -0.000476649992585218 0.999996387773417 0.00264523059512421 0.0339285477393681 -0.00149529766050952 -0.00264594066956413 0.999995381530775 -0.00427876475021668 3.02888933026786e-05 -1.81528844515849e-05 -1.40377479154616e-05 5.47693164193946e-06 -5.33776495864721e-06 1.23572338473886e-05 -1.81528844515849e-05 0.000129946040552024 2.083100996671e-05 3.61337496853869e-07 -3.28358691200383e-06 -5.62977529822554e-05 -1.40377479154616e-05 2.083100996671e-05 2.52818633729852e-05 -1.16986210924961e-05 -1.03077898984198e-05 -6.30293797491061e-06 5.47693164193946e-06 3.61337496853869e-07 -1.16986210924961e-05 4.23895875651358e-05 -3.04114907604213e-05 1.89725307844999e-06 -5.33776495864721e-06 -3.28358691200383e-06 -1.03077898984198e-05 -3.04114907604213e-05 0.000144880601223132 -1.15702146677608e-05 1.23572338473886e-05 -5.62977529822554e-05 -6.30293797491061e-06 1.89725307844999e-06 -1.15702146677608e-05 5.636677421446e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 958 0 0 0 0 0 2538 +1099 1102 0.999997731172479 -0.000585333539499888 0.00204817834721527 -0.00564143784830427 0.00058176657451221 0.999998314025009 0.00174169308196913 0.017358315814804 -0.00204919436541419 -0.00174049756866688 0.999996385728802 -0.000845314528599649 3.79060193121901e-05 -3.85378436304074e-05 -1.44727846719739e-05 4.62157412081264e-06 -7.14883891733164e-06 1.98286712993416e-05 -3.85378436304074e-05 0.000147833614733394 2.81838146704062e-05 -9.8217168637484e-06 1.74280209340469e-05 -8.11581290334162e-05 -1.44727846719739e-05 2.81838146704062e-05 2.27965856607845e-05 -1.12026614195317e-05 -9.24597370109525e-06 -1.3124709237819e-05 4.62157412081264e-06 -9.8217168637484e-06 -1.12026614195317e-05 2.86373766842685e-05 -4.03896711841014e-06 2.61655083456847e-06 -7.14883891733164e-06 1.74280209340469e-05 -9.24597370109525e-06 -4.03896711841014e-06 9.52992200741555e-05 -4.50116278570038e-06 1.98286712993416e-05 -8.11581290334162e-05 -1.3124709237819e-05 2.61655083456847e-06 -4.50116278570038e-06 6.81436536551712e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 737 0 0 0 0 0 2529 +1099 1126 0.999999922589912 -0.000238139639415986 0.0003132246523052 -0.00634119672619573 0.000238683184189996 0.999998463922657 -0.00173642813368993 0.0220272897583913 -0.00031281065879828 0.00173650276073025 0.999998443352615 -0.00261117905631058 2.91173941999545e-05 -2.07384216088615e-05 -1.3459745045616e-05 5.92084306023801e-06 -3.78465677500891e-06 1.67284473916713e-05 -2.07384216088615e-05 0.000135580564417835 2.97613282470346e-05 -1.39885839775632e-05 -9.22284483489634e-06 -5.3530623014629e-05 -1.3459745045616e-05 2.97613282470346e-05 2.86903003552503e-05 -2.01441203306898e-05 -5.39670368856275e-06 -1.06286421110463e-05 5.92084306023801e-06 -1.39885839775632e-05 -2.01441203306898e-05 5.50862849891735e-05 -5.04543668555086e-05 7.01451468405642e-06 -3.78465677500891e-06 -9.22284483489634e-06 -5.39670368856275e-06 -5.04543668555086e-05 0.000187128511235356 -4.02618558642838e-06 1.67284473916713e-05 -5.3530623014629e-05 -1.06286421110463e-05 7.01451468405642e-06 -4.02618558642838e-06 6.74551658982192e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 891 0 0 0 0 0 2732 +1099 1103 0.999992089706519 -0.00174871421784914 0.00357246735099569 -0.0045255775652571 0.00173835797770717 0.999994284168999 0.00289995532245365 0.00416506466232917 -0.00357751812447956 -0.00289372215583627 0.999989413812043 -0.00736568236352565 4.05847859440102e-05 3.02003121783368e-05 7.94054769099472e-06 -1.77245771771453e-06 -1.25927024008627e-05 3.99426998168662e-05 3.02003121783368e-05 6.65413087336594e-05 1.51216475874155e-05 -3.91445305725765e-06 -1.65505710003124e-05 2.06617194517514e-05 7.94054769099472e-06 1.51216475874155e-05 1.79648016519209e-05 -6.74701293370419e-06 -5.53038800239254e-06 9.7251043596335e-06 -1.77245771771453e-06 -3.91445305725765e-06 -6.74701293370419e-06 2.47875794357369e-05 2.72666721004018e-06 6.4584134440707e-06 -1.25927024008627e-05 -1.65505710003124e-05 -5.53038800239254e-06 2.72666721004018e-06 5.12510860198088e-05 -2.46809445239006e-05 3.99426998168662e-05 2.06617194517514e-05 9.7251043596335e-06 6.4584134440707e-06 -2.46809445239006e-05 9.89266383407309e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 628 0 0 0 0 0 2725 +1100 1102 0.999985264184979 -0.00116965979759884 0.00530125540378084 -0.00578168436708466 0.00115514327509232 0.999995577496721 0.00274055304890444 0.0201943069923835 -0.00530443747368593 -0.00273438895509243 0.999982192871518 -0.00666181940705703 2.92656333267101e-05 -3.01159225383495e-05 -1.35761092325592e-05 2.88571459010733e-06 3.46543852684946e-06 1.90656486533851e-05 -3.01159225383495e-05 0.000161062879050474 3.0765780414318e-05 -5.9168991335685e-06 -6.71112314923257e-06 -8.468428498867e-05 -1.35761092325592e-05 3.0765780414318e-05 2.4784996437615e-05 -1.33239898231965e-05 -6.4129108618355e-06 -1.30934029911593e-05 2.88571459010733e-06 -5.9168991335685e-06 -1.33239898231965e-05 3.55864740921914e-05 -1.35011052867401e-05 -2.33994009358861e-07 3.46543852684946e-06 -6.71112314923257e-06 -6.4129108618355e-06 -1.35011052867401e-05 9.51475231234579e-05 6.9896934645297e-06 1.90656486533851e-05 -8.468428498867e-05 -1.30934029911593e-05 -2.33994009358861e-07 6.9896934645297e-06 7.36901969979849e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 741 0 0 0 0 0 2536 +1100 1103 0.999997082590323 -0.00192764043473592 -0.00145568306877838 -0.00178685793705867 0.00192739381245144 0.999998127987764 -0.000170804154204297 -0.00270566969445097 0.00145600959271593 0.000167997981358951 0.999998925905795 -0.00158471308616203 2.83303163208115e-05 2.03163670918414e-05 6.90346025908575e-06 -3.82531437567058e-06 -5.32226960010775e-06 1.37465042208466e-05 2.03163670918414e-05 5.77686520109601e-05 1.35223353424785e-05 -4.56292544625157e-06 -9.39490245314801e-06 -4.67335231863131e-06 6.90346025908575e-06 1.35223353424785e-05 1.88642454254315e-05 -5.83080053716644e-06 -4.24015991331273e-06 5.27482665106914e-06 -3.82531437567058e-06 -4.56292544625157e-06 -5.83080053716644e-06 2.29378109172447e-05 5.12071769071916e-06 -1.35308320693231e-07 -5.32226960010775e-06 -9.39490245314801e-06 -4.24015991331273e-06 5.12071769071916e-06 4.89946910603117e-05 -3.15757220339023e-06 1.37465042208466e-05 -4.67335231863131e-06 5.27482665106914e-06 -1.35308320693231e-07 -3.15757220339023e-06 6.23397667546789e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 624 0 0 0 0 0 2638 +1100 1104 0.999987561600872 -0.000517827907460733 0.0049606952941217 -3.14741532349338e-05 0.000501741292565839 0.999994613933528 0.00324351038389441 0.00643153322218537 -0.00496234815568202 -0.00324098105414878 0.999982435417037 -0.00936152520128304 2.64448995184058e-05 1.45626829126304e-05 1.12196469109965e-05 -9.68237319681973e-06 -4.10545112727912e-06 1.38546411053361e-05 1.45626829126304e-05 5.66663323331951e-05 2.03275349117306e-05 -1.0332256450365e-05 -1.17233085251909e-05 -3.74298738811306e-06 1.12196469109965e-05 2.03275349117306e-05 2.40223223507347e-05 -1.22440392289865e-05 -1.12807201325875e-05 6.98050659926422e-06 -9.68237319681973e-06 -1.0332256450365e-05 -1.22440392289865e-05 2.85600044172602e-05 1.48997488907524e-05 -8.19203666508486e-06 -4.10545112727912e-06 -1.17233085251909e-05 -1.12807201325875e-05 1.48997488907524e-05 4.20633966539297e-05 -1.67157307227648e-07 1.38546411053361e-05 -3.74298738811306e-06 6.98050659926422e-06 -8.19203666508486e-06 -1.67157307227648e-07 4.98965139141087e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 720 0 0 0 0 0 2674 +1101 1103 0.999974061779713 -0.00220961559061651 0.00685517080198025 -0.00396365704165919 0.00219003593822413 0.999993505239193 0.00286238048169117 0.00411669316012799 -0.00686145103982422 -0.00284729316621669 0.999972406324921 -0.00950869846615679 3.13554594588222e-05 2.02612558240938e-05 6.36008824764754e-06 -1.97141658771239e-06 -4.93509348171047e-06 1.79703165160554e-05 2.02612558240938e-05 3.70837362832841e-05 1.05800450733165e-05 -3.28597750219078e-07 -1.13315612070136e-05 5.12118451793554e-06 6.36008824764754e-06 1.05800450733165e-05 1.75949209693286e-05 -9.02679399174685e-06 -8.06060894244656e-06 5.76206414799971e-06 -1.97141658771239e-06 -3.28597750219078e-07 -9.02679399174685e-06 2.79036615093119e-05 4.11741944687385e-06 3.41120853214052e-07 -4.93509348171047e-06 -1.13315612070136e-05 -8.06060894244656e-06 4.11741944687385e-06 5.51022662352604e-05 -9.40427277787727e-06 1.79703165160554e-05 5.12118451793554e-06 5.76206414799971e-06 3.41120853214052e-07 -9.40427277787727e-06 5.73784182956674e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 626 0 0 0 0 0 2661 +1101 1104 0.999989478207896 -0.00133292070366428 0.00438939584664007 -0.000309446347436072 0.00131130030582708 0.999987013347122 0.00492479731679928 -0.0030521386295184 -0.00439590320738477 -0.00491898968298966 0.999978239550986 -0.00711838570217788 2.6923521486524e-05 1.31910976709685e-05 1.30785755658929e-05 -1.04714475638006e-05 -7.80212495098368e-06 1.33909504076043e-05 1.31910976709685e-05 5.28097671235023e-05 2.03845732144808e-05 -8.45376287189984e-06 -1.61528431355714e-05 -1.10607496584119e-05 1.30785755658929e-05 2.03845732144808e-05 2.44368886508755e-05 -1.44508315959416e-05 -1.4098892854876e-05 5.32865702124722e-06 -1.04714475638006e-05 -8.45376287189984e-06 -1.44508315959416e-05 2.94229686644003e-05 1.05043268056934e-05 -5.8514123696712e-06 -7.80212495098368e-06 -1.61528431355714e-05 -1.4098892854876e-05 1.05043268056934e-05 5.3188548893724e-05 -1.89814591915789e-06 1.33909504076043e-05 -1.10607496584119e-05 5.32865702124722e-06 -5.8514123696712e-06 -1.89814591915789e-06 5.72215738690333e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 727 0 0 0 0 0 2695 +1101 1105 0.999997442825838 -0.000632106926434085 -0.00217135501886435 -0.00662572514020042 0.000634272598076815 0.999999302005108 0.000996838787684058 0.0194826393811452 0.0021707233945674 -0.000998213469582829 0.999997145760833 0.00131933329872161 2.97433808413884e-05 5.26500559000066e-06 -9.36993196888209e-07 -7.7066691447895e-06 2.45919965168711e-06 1.00309146739094e-05 5.26500559000066e-06 0.000100084252298914 2.38038953242451e-05 -1.94444575017107e-05 -2.68840384858426e-06 -4.17890383100445e-05 -9.36993196888209e-07 2.38038953242451e-05 2.41851189618142e-05 -1.74553336056961e-05 -5.89329525160501e-06 -3.40761236655154e-06 -7.7066691447895e-06 -1.94444575017107e-05 -1.74553336056961e-05 3.8425098219151e-05 -8.32892938192475e-06 -1.60002734617811e-06 2.45919965168711e-06 -2.68840384858426e-06 -5.89329525160501e-06 -8.32892938192475e-06 6.89578238254111e-05 9.35216834910555e-06 1.00309146739094e-05 -4.17890383100445e-05 -3.40761236655154e-06 -1.60002734617811e-06 9.35216834910555e-06 6.38194943699397e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 816 0 0 0 0 0 2582 +1102 1106 0.999999903847068 -0.000221800316420446 0.000378299451639705 -0.000184503866423379 0.000220668153671122 0.999995505026591 0.0029901893216755 -0.000632502545414218 -0.000378960976131433 -0.0029901055555185 0.999995457818357 -0.00451131163366339 3.810204680054e-05 -1.46985167747787e-05 -1.68140693766294e-05 7.32665380208827e-06 1.03123261722704e-06 1.72655372261709e-05 -1.46985167747787e-05 0.000114055405742745 1.98306038060254e-05 -1.1476397359851e-05 4.71322193122373e-06 -6.33120869212672e-05 -1.68140693766294e-05 1.98306038060254e-05 2.36280138663037e-05 -1.31820989632285e-05 -8.77649639891684e-06 -1.33570149554769e-05 7.32665380208827e-06 -1.1476397359851e-05 -1.31820989632285e-05 2.79897983527785e-05 6.08000547606614e-06 8.12290534301406e-06 1.03123261722704e-06 4.71322193122373e-06 -8.77649639891684e-06 6.08000547606614e-06 5.21307004018089e-05 4.06525301810085e-06 1.72655372261709e-05 -6.33120869212672e-05 -1.33570149554769e-05 8.12290534301406e-06 4.06525301810085e-06 7.12688076446655e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 827 0 0 0 0 0 2548 +1102 1138 0.999997457316455 0.000124357615893516 0.00225164291327419 -0.00456510691415302 -0.000131427195600924 0.999995061968402 0.00313986714758267 0.018242443846462 -0.00225124132819765 -0.00314015509100773 0.999992535641385 -0.00270760893826192 3.42663695492583e-05 -1.17933510186894e-05 -7.71279344031813e-06 2.04345422831555e-06 1.72373736325634e-06 4.32736648220215e-05 -1.17933510186894e-05 8.33043461534224e-05 9.89561884219988e-06 -2.66249876924673e-06 2.49932377724697e-06 -5.12941189183552e-05 -7.71279344031813e-06 9.89561884219988e-06 2.05534437891066e-05 -1.12159553404601e-05 -7.70281526979537e-06 -1.90966799186706e-06 2.04345422831555e-06 -2.66249876924673e-06 -1.12159553404601e-05 3.29691473144369e-05 -7.38931575182122e-06 -5.41434647035373e-07 1.72373736325634e-06 2.49932377724697e-06 -7.70281526979537e-06 -7.38931575182122e-06 8.60435614046065e-05 -8.39444831471928e-06 4.32736648220215e-05 -5.12941189183552e-05 -1.90966799186706e-06 -5.41434647035373e-07 -8.39444831471928e-06 0.000133102738850986 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 989 0 0 0 0 0 2553 +1102 1104 0.999944937750977 -0.00148525131002819 0.0103882382886183 0.000796931533614621 0.00140770830951742 0.999971124499765 0.00746783261669176 0.000339195632724898 -0.0103990299312182 -0.00745279781167242 0.999918154641303 -0.0136556180061852 2.61487345315194e-05 1.42801901708086e-05 1.10778491047253e-05 -9.4023987449064e-06 -9.84972591256896e-06 1.14576910783024e-05 1.42801901708086e-05 6.23258627562582e-05 2.28903701490419e-05 -1.29246301251129e-05 -1.59085030453853e-05 -1.82647453784385e-06 1.10778491047253e-05 2.28903701490419e-05 2.3615684819148e-05 -1.36570174080893e-05 -8.8280839691465e-06 8.65833413578659e-06 -9.4023987449064e-06 -1.29246301251129e-05 -1.36570174080893e-05 2.99248068407858e-05 2.74550713376036e-06 -7.57942247436901e-06 -9.84972591256896e-06 -1.59085030453853e-05 -8.8280839691465e-06 2.74550713376036e-06 5.82413402187642e-05 -7.18658863515567e-06 1.14576910783024e-05 -1.82647453784385e-06 8.65833413578659e-06 -7.57942247436901e-06 -7.18658863515567e-06 5.31182304385716e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 716 0 0 0 0 0 2650 +1102 1139 0.999978524611085 1.98663409730217e-05 0.00655361899765001 -0.00274133512507534 -5.29260658718818e-05 0.999987275713353 0.00504436420363818 0.0141629400036042 -0.00655343539446404 -0.00504460273122585 0.999965801649144 -0.0107283239059632 3.93972509954346e-05 -1.19248201845511e-05 -1.33166964795487e-05 7.17429212777191e-06 -4.06805843902543e-06 3.38575794505773e-05 -1.19248201845511e-05 0.000128436599344191 1.71619235891588e-05 -6.6619860632436e-06 2.33307050612113e-05 -6.64408755980546e-05 -1.33166964795487e-05 1.71619235891588e-05 2.17906264564405e-05 -1.19348718914436e-05 -5.3006575158376e-06 -1.2508101856277e-05 7.17429212777191e-06 -6.6619860632436e-06 -1.19348718914436e-05 3.13905766369107e-05 -6.29763201637929e-06 7.79526940529551e-06 -4.06805843902543e-06 2.33307050612113e-05 -5.3006575158376e-06 -6.29763201637929e-06 9.89977974098208e-05 -1.04146901307312e-05 3.38575794505773e-05 -6.64408755980546e-05 -1.2508101856277e-05 7.79526940529551e-06 -1.04146901307312e-05 0.00010505158602041 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 993 0 0 0 0 0 2603 +1102 1140 0.999980652293347 0.000294543498654327 0.00621355639706112 0.00119100265589848 -0.000325726023418217 0.999987356450284 0.00501805162699673 0.00979178818555808 -0.00621199980116926 -0.00501997845622238 0.999968104928737 -0.00776319493742427 2.9787009754789e-05 -2.35616333427044e-05 -1.43602126732108e-05 4.74130427906977e-06 2.74317584261146e-06 2.12756381517836e-05 -2.35616333427044e-05 0.000114869368396431 2.23387754427684e-05 -9.09163336427864e-06 -5.62312956510493e-06 -6.43173456422525e-05 -1.43602126732108e-05 2.23387754427684e-05 2.45276000256337e-05 -1.22042335227641e-05 -1.24226037427902e-05 -1.05247541712404e-05 4.74130427906977e-06 -9.09163336427864e-06 -1.22042335227641e-05 2.70090977042693e-05 6.07141011362337e-06 2.31186049665641e-06 2.74317584261146e-06 -5.62312956510493e-06 -1.24226037427902e-05 6.07141011362337e-06 6.93164519942352e-05 1.27665881570672e-06 2.12756381517836e-05 -6.43173456422525e-05 -1.05247541712404e-05 2.31186049665641e-06 1.27665881570672e-06 6.95253002459485e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 999 0 0 0 0 0 2649 +1102 1105 0.999987672833538 0.00107324014850163 -0.004847920848118 0.000693502232638804 -0.00107679667577842 0.999999153023493 -0.000731068543639232 0.00489248099510117 0.00484713212993059 0.000736279756689289 0.999987981528896 0.00407171865402308 2.89537799958997e-05 -7.68161259604023e-06 -2.57813874502987e-06 -1.73007849308297e-06 -8.70140879706164e-06 1.73671604222504e-05 -7.68161259604023e-06 0.00010124437940322 2.24498342386032e-05 -2.13536096317517e-05 1.40634644059559e-05 -5.09454134909589e-05 -2.57813874502987e-06 2.24498342386032e-05 2.34186728815613e-05 -1.53929099428163e-05 -7.48860098372507e-06 -2.98618716385964e-06 -1.73007849308297e-06 -2.13536096317517e-05 -1.53929099428163e-05 3.1354235022518e-05 9.19798406916821e-06 3.98014879012845e-06 -8.70140879706164e-06 1.40634644059559e-05 -7.48860098372507e-06 9.19798406916821e-06 5.37416236940013e-05 -1.64404059303067e-05 1.73671604222504e-05 -5.09454134909589e-05 -2.98618716385964e-06 3.98014879012845e-06 -1.64404059303067e-05 7.24803885297579e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 797 0 0 0 0 0 2624 +1102 1134 0.999994419980953 0.00105240587255005 -0.00317055970400208 0.00525472279996315 -0.00105086714647133 0.999999329281812 0.000486943698838354 -0.00809342646322861 0.00317107003985828 -0.000483609144654378 0.999994855205264 -0.00311912862277547 2.6332933054412e-05 -2.16489544152215e-05 -1.5856186149335e-05 4.9517200304067e-06 8.94158398541409e-06 1.24219429392712e-05 -2.16489544152215e-05 9.70599139131296e-05 1.88463497310103e-05 -5.64868654474101e-06 -2.11521424691216e-05 -4.24402455623219e-05 -1.5856186149335e-05 1.88463497310103e-05 2.39866586916115e-05 -1.30677337599682e-05 -1.36663828384125e-05 -9.24330256445684e-06 4.9517200304067e-06 -5.64868654474101e-06 -1.30677337599682e-05 3.99451530187315e-05 -2.51500326150532e-05 1.71250135137069e-06 8.94158398541409e-06 -2.11521424691216e-05 -1.36663828384125e-05 -2.51500326150532e-05 0.000139262505872672 1.42884104875982e-05 1.24219429392712e-05 -4.24402455623219e-05 -9.24330256445684e-06 1.71250135137069e-06 1.42884104875982e-05 5.59960534064028e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 905 0 0 0 0 0 2627 +1102 1133 0.999997247229459 0.000785738614238546 0.00221091572304496 0.00571474105079333 -0.000788397405761157 0.999998966859897 0.00120196034422834 -0.00670158487964914 -0.00220996901220401 -0.00120370011572771 0.999996833566485 -0.00787163451364882 1.9296219525912e-05 -8.25422393329244e-06 -1.40370572753748e-05 9.63576080812937e-06 -1.6638274828071e-06 8.75643494952667e-06 -8.25422393329244e-06 6.82434932819326e-05 1.04224040036481e-05 -1.31394271594244e-05 1.13405893839069e-05 -2.58855768810653e-05 -1.40370572753748e-05 1.04224040036481e-05 1.94144725516541e-05 -1.27167607238709e-05 -5.61427491701464e-06 -7.69585864079547e-06 9.63576080812937e-06 -1.31394271594244e-05 -1.27167607238709e-05 3.8002949372387e-05 -2.05504511175032e-05 1.0088687207041e-05 -1.6638274828071e-06 1.13405893839069e-05 -5.61427491701464e-06 -2.05504511175032e-05 0.000113893635475818 -1.36511392625846e-05 8.75643494952667e-06 -2.58855768810653e-05 -7.69585864079547e-06 1.0088687207041e-05 -1.36511392625846e-05 5.16540642746001e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 910 0 0 0 0 0 2472 +1102 1136 0.999993604478437 -7.16636435643484e-05 0.0035757330082636 0.00662070077921415 8.01717314114436e-05 0.999997166223607 -0.00237931024663697 -0.0116268500997467 -0.00357555236539437 0.00237958170241332 0.999990776465565 0.00242441889523157 4.08191544993364e-05 -5.0323490897206e-05 -1.7083043492989e-05 3.38682075215805e-06 -4.36219886785972e-06 4.16374513153128e-05 -5.0323490897206e-05 0.00019619473155003 3.29820891198261e-05 -1.13263872421781e-05 1.24023990977877e-05 -0.000113068068389716 -1.7083043492989e-05 3.29820891198261e-05 3.12168634626832e-05 -1.87691735230364e-05 -1.08283171282693e-05 -1.65637929847898e-05 3.38682075215805e-06 -1.13263872421781e-05 -1.87691735230364e-05 4.0772385389828e-05 -4.92920609492595e-07 5.19245573068384e-06 -4.36219886785972e-06 1.24023990977877e-05 -1.08283171282693e-05 -4.92920609492595e-07 8.46963822340707e-05 -1.89158707205709e-05 4.16374513153128e-05 -0.000113068068389716 -1.65637929847898e-05 5.19245573068384e-06 -1.89158707205709e-05 0.000117252883165511 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 920 0 0 0 0 0 2631 +1103 1107 0.999997925805637 0.000549770178923854 0.00196115710078444 0.00408888012052701 -0.000555222404001743 0.999995979859951 0.00278064597152392 -0.00215592570366734 -0.00195962050042495 -0.00278172908228385 0.999994210918647 -0.00466444657376591 3.28142974219515e-05 -1.02475662652961e-05 -1.54474098249422e-05 5.88144672335229e-06 3.67862931176164e-06 2.98272427166862e-05 -1.02475662652961e-05 6.5713794292785e-05 9.24055584672909e-06 -4.54709088858059e-06 -5.9234250167049e-06 -4.77072491551853e-05 -1.54474098249422e-05 9.24055584672909e-06 2.28691753924247e-05 -1.15096614101188e-05 -1.06626586438235e-05 -9.97626586106011e-06 5.88144672335229e-06 -4.54709088858059e-06 -1.15096614101188e-05 2.98943532206628e-05 5.57478958681289e-06 -9.68893295018654e-07 3.67862931176164e-06 -5.9234250167049e-06 -1.06626586438235e-05 5.57478958681289e-06 5.88050608888043e-05 1.16639405167913e-06 2.98272427166862e-05 -4.77072491551853e-05 -9.97626586106011e-06 -9.68893295018654e-07 1.16639405167913e-06 9.45188436842287e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 680 0 0 0 0 0 2417 +1102 1135 0.999999871141172 -0.000302740161728612 -0.000407512005004394 0.00336203373212194 0.000303605941209075 0.999997693615917 0.00212616703951468 -0.006979913456026 0.000406867388971787 -0.00212629048860512 0.999997656671097 -0.00819465312792269 3.80949092063119e-05 -4.4389763791425e-06 -1.01750540703663e-05 8.45603282210807e-06 5.34597871889813e-06 4.06668260484546e-05 -4.4389763791425e-06 8.99887486392865e-05 1.62587671265913e-05 -4.60965881749308e-06 -1.29552052848273e-05 -3.45038248447025e-05 -1.01750540703663e-05 1.62587671265913e-05 2.35834682618267e-05 -1.31307308261984e-05 -9.93405274608126e-06 -2.61702250463932e-06 8.45603282210807e-06 -4.60965881749308e-06 -1.31307308261984e-05 3.49683739656871e-05 -5.71520222308652e-06 6.89251505906685e-06 5.34597871889813e-06 -1.29552052848273e-05 -9.93405274608126e-06 -5.71520222308652e-06 9.08078630990388e-05 -1.60473080720508e-06 4.06668260484546e-05 -3.45038248447025e-05 -2.61702250463932e-06 6.89251505906685e-06 -1.60473080720508e-06 0.000128720933247502 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 988 0 0 0 0 0 2604 +1102 1137 0.999989205651124 0.000803156692261997 0.00457640913408552 0.00667240595589957 -0.000819636055573133 0.999993183353113 0.00360020055603248 -0.00600193552291185 -0.00457348641315038 -0.003603912684143 0.999983047374001 -0.00649584219030003 2.49296827058748e-05 -1.8097711936927e-05 -1.2534048172746e-05 7.00776013070708e-06 4.08824669643873e-06 1.6347717501425e-05 -1.8097711936927e-05 0.000124737811621407 2.74807417249756e-05 -1.6454739812923e-05 -7.34467416950588e-06 -5.58712762785186e-05 -1.2534048172746e-05 2.74807417249756e-05 2.49428180435384e-05 -1.55121539354243e-05 -1.0835234550813e-05 -1.13679098639635e-05 7.00776013070708e-06 -1.6454739812923e-05 -1.55121539354243e-05 3.26718091332741e-05 1.72462390791572e-06 8.66981141861587e-06 4.08824669643873e-06 -7.34467416950588e-06 -1.0835234550813e-05 1.72462390791572e-06 7.64967829985902e-05 3.91860163520937e-06 1.6347717501425e-05 -5.58712762785186e-05 -1.13679098639635e-05 8.66981141861587e-06 3.91860163520937e-06 6.66745263150378e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 998 0 0 0 0 0 2577 +1102 1131 0.999999075667353 0.000608657764831958 0.00121581255295543 0.00230667480753392 -0.000614001025671312 0.999990134627374 0.00439927842561802 0.000158384157943873 -0.00121312290353814 -0.00440002086937589 0.999989584020339 -0.0107123940550587 2.61469687027836e-05 -2.90889444828336e-06 -9.948067582172e-06 8.50870718626451e-06 -6.60740666239645e-06 1.9880385880758e-06 -2.90889444828336e-06 9.66300875173417e-05 1.3915093123415e-05 -4.43237544854593e-06 -2.8210463698608e-06 -3.89798768774845e-05 -9.948067582172e-06 1.3915093123415e-05 2.14682925727696e-05 -1.1860010947817e-05 -1.09406465086691e-05 -5.11663719229376e-06 8.50870718626451e-06 -4.43237544854593e-06 -1.1860010947817e-05 4.23605465455765e-05 -3.59701712199372e-05 -1.33299489083553e-06 -6.60740666239645e-06 -2.8210463698608e-06 -1.09406465086691e-05 -3.59701712199372e-05 0.00017117037104173 1.07620720181941e-05 1.9880385880758e-06 -3.89798768774845e-05 -5.11663719229376e-06 -1.33299489083553e-06 1.07620720181941e-05 5.55296907025192e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1005 0 0 0 0 0 2473 +1103 1106 0.999999472825164 -0.000715559910977229 -0.000736426105404529 -0.000394946941101211 0.000713383597049939 0.999995390536453 -0.00295126916590195 -0.00337730861331094 0.000738534520776864 0.00295074225576308 0.99999537383275 0.00497337414715309 3.58672023274908e-05 -3.69266156703429e-05 -1.54953788694976e-05 5.79690056216807e-06 -5.15910488642624e-06 3.81026784514021e-05 -3.69266156703429e-05 0.000134051726446 2.48769753727561e-05 -1.295372475194e-05 3.87778836836685e-06 -0.000102312293413367 -1.54953788694976e-05 2.48769753727561e-05 2.28061960415111e-05 -1.31449085165569e-05 -5.16670370826217e-06 -1.37961380286045e-05 5.79690056216807e-06 -1.295372475194e-05 -1.31449085165569e-05 2.99421235133662e-05 3.61596675406698e-06 4.72593956822343e-06 -5.15910488642624e-06 3.87778836836685e-06 -5.16670370826217e-06 3.61596675406698e-06 6.08236007972473e-05 -1.08664375322003e-05 3.81026784514021e-05 -0.000102312293413367 -1.37961380286045e-05 4.72593956822343e-06 -1.08664375322003e-05 0.00011431928381048 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 784 0 0 0 0 0 2632 +1102 1132 0.999987896228236 -0.000292692228295851 0.0049113876131731 0.00143519733735965 0.000266020769572599 0.999985220378964 0.00543030906910774 0.00262738755406934 -0.00491290443398719 -0.00542893681077363 0.9999731946483 -0.0128947888200094 2.86169176139678e-05 -1.6836143827444e-05 -1.10329772520685e-05 6.90880327999858e-06 -1.09527839339387e-05 1.46784976504034e-05 -1.6836143827444e-05 0.000124873148787397 2.24062639644264e-05 -2.06736720250594e-05 2.49597912754027e-05 -5.62328593350756e-05 -1.10329772520685e-05 2.24062639644264e-05 2.32175125752958e-05 -1.41646381103995e-05 -5.13683605850119e-06 -3.72400802929017e-06 6.90880327999858e-06 -2.06736720250594e-05 -1.41646381103995e-05 3.57275746475008e-05 -1.61377732035506e-05 8.27605683516265e-07 -1.09527839339387e-05 2.49597912754027e-05 -5.13683605850119e-06 -1.61377732035506e-05 0.000116257784114393 -1.68180684882704e-05 1.46784976504034e-05 -5.62328593350756e-05 -3.72400802929017e-06 8.27605683516265e-07 -1.68180684882704e-05 7.63332838277796e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 990 0 0 0 0 0 2502 +1102 1130 0.999999389642301 -0.000717985487737273 -0.000839768935853174 0.00139568965671995 0.000716582269670056 0.99999834869279 -0.00167006632923903 -0.0057630267426962 0.000840966632524627 0.00166946354637114 0.999998252831769 0.00200298372340263 3.22591315316617e-05 -1.93257200883012e-05 -1.42689195324606e-05 9.33984614081273e-06 -5.96853021693489e-06 1.77334692290219e-05 -1.93257200883012e-05 0.00013222942151898 2.54077980040159e-05 -1.60739503710787e-05 6.95605436755882e-07 -6.6116796234157e-05 -1.42689195324606e-05 2.54077980040159e-05 2.64374545126281e-05 -1.60674578539562e-05 -1.26652134814296e-05 -8.25356952885561e-06 9.33984614081273e-06 -1.60739503710787e-05 -1.60674578539562e-05 4.27974080346162e-05 -2.60391165242841e-05 3.71217169760981e-06 -5.96853021693489e-06 6.95605436755882e-07 -1.26652134814296e-05 -2.60391165242841e-05 0.000150391079236686 -4.42040524381674e-06 1.77334692290219e-05 -6.6116796234157e-05 -8.25356952885561e-06 3.71217169760981e-06 -4.42040524381674e-06 7.72764804722332e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 919 0 0 0 0 0 2636 +1102 1129 0.999938873826759 -0.00101272235714465 0.0110101318566115 0.0026741839192507 0.000979544946792223 0.999994965081779 0.00301832781342574 -0.000957847365425186 -0.0110131331495559 -0.00300735839557326 0.999934831223371 -0.0119104748424558 3.80518771138753e-05 -2.08117994563987e-05 -1.29981669877582e-05 9.14036327843426e-06 -5.43075806549127e-06 4.42463189797943e-05 -2.08117994563987e-05 0.000121052716046625 2.49793375028231e-05 -1.13403499070867e-05 -8.30662087378924e-07 -7.47270977219066e-05 -1.29981669877582e-05 2.49793375028231e-05 2.80314921911575e-05 -1.66688571083061e-05 -1.2278973475374e-05 -1.14712321760395e-05 9.14036327843426e-06 -1.13403499070867e-05 -1.66688571083061e-05 3.95966650255372e-05 -7.73608024342651e-06 1.08474205369462e-05 -5.43075806549127e-06 -8.30662087378924e-07 -1.2278973475374e-05 -7.73608024342651e-06 9.52228908931656e-05 -1.78041953454568e-05 4.42463189797943e-05 -7.47270977219066e-05 -1.14712321760395e-05 1.08474205369462e-05 -1.78041953454568e-05 0.00012861882355689 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 995 0 0 0 0 0 2606 +1102 1128 0.999998938617466 -0.000447909647956504 -0.00138641295715799 0.0019033044245688 0.00044490912862483 0.999997560043583 -0.00216378435800398 -0.00250131887238903 0.00138737875426084 0.00216316523362037 0.99999669794273 0.00276758202411082 2.62373039241128e-05 -3.08326237574417e-06 -9.65641232194577e-06 9.2734505037206e-06 -5.19839634051346e-06 1.42080986945937e-05 -3.08326237574417e-06 8.62054439124025e-05 1.61301358760715e-05 -1.25758380026444e-05 6.72553680498603e-06 -3.99580414885504e-05 -9.65641232194577e-06 1.61301358760715e-05 2.26035459309106e-05 -1.38361058320589e-05 -5.21556730133445e-06 -7.27634197729936e-06 9.2734505037206e-06 -1.25758380026444e-05 -1.38361058320589e-05 4.36100002442137e-05 -3.57468637092682e-05 9.96224505589766e-06 -5.19839634051346e-06 6.72553680498603e-06 -5.21556730133445e-06 -3.57468637092682e-05 0.000173242058716499 -2.04431864654406e-05 1.42080986945937e-05 -3.99580414885504e-05 -7.27634197729936e-06 9.96224505589766e-06 -2.04431864654406e-05 6.39048094284445e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 918 0 0 0 0 0 2699 +1103 1105 0.999995513705257 -0.000688919028870071 -0.00291512605757595 -0.000174180435780298 0.000681163978331837 0.999996229038803 -0.0026604367703169 -0.00286045157713959 0.00291694789026488 0.00265843915595068 0.999992212027804 0.00399283242106811 2.91090330917386e-05 -1.46805261784065e-05 -8.4232708715553e-06 1.55352976304495e-07 2.53029556172533e-06 1.66527597122894e-05 -1.46805261784065e-05 0.000105492348611687 2.54686473810282e-05 -9.69353823538595e-06 -1.64945342171579e-05 -5.45364447345771e-05 -8.4232708715553e-06 2.54686473810282e-05 2.60420590456519e-05 -1.32041271119235e-05 -1.0479020614866e-05 -5.8359584247029e-06 1.55352976304495e-07 -9.69353823538595e-06 -1.32041271119235e-05 2.7266600543274e-05 8.67947791503585e-06 1.47134561045529e-06 2.53029556172533e-06 -1.64945342171579e-05 -1.0479020614866e-05 8.67947791503585e-06 3.82689332839524e-05 2.64251562652238e-06 1.66527597122894e-05 -5.45364447345771e-05 -5.8359584247029e-06 1.47134561045529e-06 2.64251562652238e-06 6.57407978059069e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 765 0 0 0 0 0 2491 +1103 1140 0.999997678334938 -0.000800773788558482 0.00200052145058184 0.00120825417412335 0.000806900233229987 0.999994981939256 -0.0030634960945585 -0.003133901094469 -0.0019980582444698 0.0030651032033717 0.9999933064304 0.00585070686396184 2.74398455542213e-05 -1.16411107153896e-05 -1.15138350173296e-05 4.16864593581378e-06 3.13129470993431e-06 1.48306454617379e-05 -1.16411107153896e-05 0.000124952306816379 2.04831854080927e-05 -4.52579436283927e-06 -1.40509691267172e-06 -6.72968584855388e-05 -1.15138350173296e-05 2.04831854080927e-05 2.12727182556585e-05 -1.0123211250354e-05 -8.19226378009826e-06 -8.16364308146559e-06 4.16864593581378e-06 -4.52579436283927e-06 -1.0123211250354e-05 2.87687054213405e-05 -5.55278271561436e-06 6.14834563340929e-08 3.13129470993431e-06 -1.40509691267172e-06 -8.19226378009826e-06 -5.55278271561436e-06 8.22381410435863e-05 -2.05296036058039e-06 1.48306454617379e-05 -6.72968584855388e-05 -8.16364308146559e-06 6.14834563340929e-08 -2.05296036058039e-06 7.7924813078011e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 822 0 0 0 0 0 2558 +1103 1137 0.999999186839189 -0.00094372185907437 -0.000857735398046295 0.00457020430550732 0.00094183223851923 0.999997134767093 -0.00220077478157085 -0.0124284123109778 0.000859809859702875 0.00219996514913705 0.999997210436283 0.00776586661079867 3.20269112312503e-05 -1.615061098263e-05 -1.37296032754092e-05 5.4035133587246e-06 1.09688247996958e-06 1.85340748059135e-05 -1.615061098263e-05 0.000157818250858251 3.06925063968522e-05 -1.20618410609413e-05 -5.9511243064303e-06 -7.68834070715855e-05 -1.37296032754092e-05 3.06925063968522e-05 2.62425443167589e-05 -1.28907639537467e-05 -7.3153633012581e-06 -1.45413932657331e-05 5.4035133587246e-06 -1.20618410609413e-05 -1.28907639537467e-05 3.15275616116852e-05 -8.32509069101649e-06 8.00066331320092e-06 1.09688247996958e-06 -5.9511243064303e-06 -7.3153633012581e-06 -8.32509069101649e-06 8.96507156636511e-05 8.16321541015867e-07 1.85340748059135e-05 -7.68834070715855e-05 -1.45413932657331e-05 8.00066331320092e-06 8.16321541015867e-07 8.26471564466387e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 814 0 0 0 0 0 2611 +1103 1138 0.999999475316159 -0.000769115601772623 0.000676630326277571 -0.00223687518402283 0.000768172956084375 0.999998735696608 0.00139230581919706 0.0120209824562782 -0.000677700314939538 -0.00139178531955878 0.999998801827236 -0.00176332480696008 2.52689643873921e-05 -1.36641087800291e-05 -1.01343712865056e-05 2.52387236916216e-06 1.07920461846926e-07 6.83367558384463e-06 -1.36641087800291e-05 0.000104703560397529 1.67557813687477e-05 -5.47157662172108e-06 8.79235818876505e-06 -6.72907859424682e-05 -1.01343712865056e-05 1.67557813687477e-05 2.3092343503185e-05 -1.23078417812606e-05 -5.37061549077547e-06 -6.26760644163725e-06 2.52387236916216e-06 -5.47157662172108e-06 -1.23078417812606e-05 3.23897483991532e-05 -4.49996902392264e-08 -1.16406280385363e-06 1.07920461846926e-07 8.79235818876505e-06 -5.37061549077547e-06 -4.49996902392264e-08 7.10422417680114e-05 -1.60801575734177e-05 6.83367558384463e-06 -6.72907859424682e-05 -6.26760644163725e-06 -1.16406280385363e-06 -1.60801575734177e-05 7.00054017163023e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 812 0 0 0 0 0 2488 +1103 1135 0.999992492570482 -0.000503096169881144 0.00384209538133581 0.00583494700720477 0.000496214013245745 0.999998271262928 0.00179199408728254 -0.0162945147325655 -0.00384299028472485 -0.00179007413244478 0.999991013489757 -0.00655052163773834 2.91818463228251e-05 -2.4458080487868e-05 -1.49975916960051e-05 5.31594253258665e-06 -8.9103457986633e-06 1.69533764427402e-05 -2.4458080487868e-05 0.000162935373933489 3.38187761832736e-05 -2.34358994222204e-05 3.29930713303106e-05 -8.80045886401051e-05 -1.49975916960051e-05 3.38187761832736e-05 3.04344302212008e-05 -1.74962271636511e-05 -2.59454232831959e-06 -1.08207616556064e-05 5.31594253258665e-06 -2.34358994222204e-05 -1.74962271636511e-05 3.27698417744361e-05 -4.92607578102977e-06 6.23315767763778e-06 -8.9103457986633e-06 3.29930713303106e-05 -2.59454232831959e-06 -4.92607578102977e-06 8.54941024081166e-05 -2.83090544328973e-05 1.69533764427402e-05 -8.80045886401051e-05 -1.08207616556064e-05 6.23315767763778e-06 -2.83090544328973e-05 9.47702826672757e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 819 0 0 0 0 0 2670 +1103 1139 0.999995880936492 -0.000279508169671091 0.00285656878653598 0.00030424089267087 0.000276414681969703 0.99999937505413 0.0010832757146008 0.00615122994688033 -0.00285686978574736 -0.00108248165496668 0.999995333253358 -0.00608729507334271 2.42507415386355e-05 -2.29436311769124e-05 -1.37780506931415e-05 1.76757850955133e-06 7.74794648460535e-06 1.66105604944503e-05 -2.29436311769124e-05 0.000128882584825754 2.67136556161386e-05 -2.77496070355744e-06 -1.85339774466817e-05 -7.54875673427684e-05 -1.37780506931415e-05 2.67136556161386e-05 2.4174906389931e-05 -8.10405355880135e-06 -1.07625955725809e-05 -1.14959088754593e-05 1.76757850955133e-06 -2.77496070355744e-06 -8.10405355880135e-06 2.36318813973323e-05 3.19838051824366e-06 -3.7407227936336e-06 7.74794648460535e-06 -1.85339774466817e-05 -1.07625955725809e-05 3.19838051824366e-06 5.90591328779109e-05 1.09529055442206e-05 1.66105604944503e-05 -7.54875673427684e-05 -1.14959088754593e-05 -3.7407227936336e-06 1.09529055442206e-05 7.96385205526344e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 820 0 0 0 0 0 2595 +1103 1131 0.999998505953616 -0.00103634831459624 0.00138350016508952 0.00252968267391135 0.00103833422756757 0.999998430627071 -0.00143548090483041 -0.0078385529339054 -0.00138201033564546 0.00143691529573062 0.999998012658958 -0.000999018920782908 2.87157324174977e-05 -1.50014025050827e-05 -1.01828739451265e-05 3.95884537475877e-06 8.56793823249143e-07 2.41342229287094e-05 -1.50014025050827e-05 9.5605497761198e-05 1.59901807265097e-05 1.77349721704236e-07 -1.95434395679164e-05 -4.55015402868469e-05 -1.01828739451265e-05 1.59901807265097e-05 1.95685351513563e-05 -6.53042792290715e-06 -1.06814380961488e-05 -4.8437985389488e-06 3.95884537475877e-06 1.77349721704236e-07 -6.53042792290715e-06 3.39073240992334e-05 -3.53280645145916e-05 5.09705631699954e-06 8.56793823249143e-07 -1.95434395679164e-05 -1.06814380961488e-05 -3.53280645145916e-05 0.000162753264431994 -1.20408393467205e-05 2.41342229287094e-05 -4.55015402868469e-05 -4.8437985389488e-06 5.09705631699954e-06 -1.20408393467205e-05 9.14894138841513e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 820 0 0 0 0 0 2649 +1103 1130 0.999981791160137 0.00111242298863094 0.00593126152342311 0.00440087590404661 -0.00114205298390763 0.999986875159809 0.00499451930651618 0.000580321986177081 -0.00592562765846976 -0.00500120217703509 0.999969937004927 -0.0168814426084067 3.10907357031394e-05 -2.54406599745182e-05 -1.44021097120228e-05 5.11515955668088e-06 7.33549032513145e-06 2.47386369778855e-05 -2.54406599745182e-05 0.000146549959362672 3.09980600974456e-05 -2.96832624757821e-06 -2.84691077748362e-05 -5.91218201300653e-05 -1.44021097120228e-05 3.09980600974456e-05 2.62522614066751e-05 -9.26219842618407e-06 -1.36049578887164e-05 -1.1859537675906e-05 5.11515955668088e-06 -2.96832624757821e-06 -9.26219842618407e-06 3.00240437273549e-05 -9.63099752956082e-06 -1.04765287071823e-06 7.33549032513145e-06 -2.84691077748362e-05 -1.36049578887164e-05 -9.63099752956082e-06 9.69604380505846e-05 -8.18081820694052e-07 2.47386369778855e-05 -5.91218201300653e-05 -1.1859537675906e-05 -1.04765287071823e-06 -8.18081820694052e-07 8.87647387253276e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 731 0 0 0 0 0 2736 +1103 1132 0.999993345348484 -0.000102973321931973 -0.00364673213205851 0.00389510250749468 8.85701385824117e-05 0.999992196554782 -0.00394955502206349 -0.0146582031830863 0.00364711037378487 0.00394920574758087 0.999985551075557 0.0013333698058314 2.38721119274225e-05 -2.34128615852504e-06 -9.63110450516707e-06 5.0774309577088e-06 -5.01968420243577e-07 7.49753216086613e-06 -2.34128615852504e-06 7.80706440283397e-05 1.80096425343936e-05 -1.28386445068705e-05 -1.72815699061463e-05 -1.83178994605379e-05 -9.63110450516707e-06 1.80096425343936e-05 2.31816482602607e-05 -1.09517488690717e-05 -1.03260909437107e-05 -3.40001775184876e-06 5.0774309577088e-06 -1.28386445068705e-05 -1.09517488690717e-05 3.65080301796129e-05 -2.78803622810215e-05 -1.71425351531871e-06 -5.01968420243577e-07 -1.72815699061463e-05 -1.03260909437107e-05 -2.78803622810215e-05 0.000144356514211155 1.66956660030943e-05 7.49753216086613e-06 -1.83178994605379e-05 -3.40001775184876e-06 -1.71425351531871e-06 1.66956660030943e-05 5.83118274756003e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 812 0 0 0 0 0 2467 +1104 1106 0.999993662806306 0.000297375421805894 -0.00354766332766308 0.000154274067420147 -0.000297291710654215 0.999999955517848 2.41234612841763e-05 -0.00128500916751966 0.00354767034357985 -2.30686175096234e-05 0.999993706731683 0.00308881588972751 2.70605634894753e-05 -1.80953479168547e-05 -1.33054149589059e-05 3.48863647988495e-06 1.00311042948384e-05 1.60573096035467e-05 -1.80953479168547e-05 8.63294706574481e-05 1.77726510584821e-05 -4.91960572868989e-06 -1.5534936377805e-05 -5.57821182408507e-05 -1.33054149589059e-05 1.77726510584821e-05 2.1165429438745e-05 -1.23106814225674e-05 -9.24998904505428e-06 -9.61288113715457e-06 3.48863647988495e-06 -4.91960572868989e-06 -1.23106814225674e-05 2.75470505539365e-05 5.57890980906214e-07 1.57749419544712e-06 1.00311042948384e-05 -1.5534936377805e-05 -9.24998904505428e-06 5.57890980906214e-07 5.788514406932e-05 8.48307509999133e-06 1.60573096035467e-05 -5.57821182408507e-05 -9.61288113715457e-06 1.57749419544712e-06 8.48307509999133e-06 6.5996876895655e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 824 0 0 0 0 0 2677 +1103 1136 0.999998972420403 0.00142439720600653 -0.000162020794580414 0.00560103814731724 -0.00142367857758372 0.999989515416859 0.00435226328058873 -0.00616598012188903 0.000168218447516598 -0.00435202814275742 0.999990515731824 -0.00880651558246337 3.126960463613e-05 -1.95665959888083e-05 -1.30015779882796e-05 4.02880305862154e-06 6.071366905896e-06 2.9421445498715e-05 -1.95665959888083e-05 0.000105139738611284 1.86521674478949e-05 -2.1494093123576e-06 -2.19691455210646e-05 -5.96638214697421e-05 -1.30015779882796e-05 1.86521674478949e-05 2.30195442736204e-05 -1.26548624534632e-05 -9.87760511371652e-06 -1.14363927999468e-05 4.02880305862154e-06 -2.1494093123576e-06 -1.26548624534632e-05 3.69765970367952e-05 -1.45263827104718e-05 6.37616387876081e-06 6.071366905896e-06 -2.19691455210646e-05 -9.87760511371652e-06 -1.45263827104718e-05 9.51022015147529e-05 -3.87858557758066e-07 2.9421445498715e-05 -5.96638214697421e-05 -1.14363927999468e-05 6.37616387876081e-06 -3.87858557758066e-07 9.32783317426558e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 737 0 0 0 0 0 2540 +1104 1108 0.999952652668737 -0.000688828881806481 0.00970659237462065 0.00278514305582953 0.000659174109286998 0.999995107097151 0.00305798483504947 -0.00337610167011384 -0.00970865130948167 -0.00305144171324573 0.999948214055719 -0.00477853210234027 2.42040954576689e-05 -2.24795881110139e-05 -1.44451912719011e-05 6.90378357836895e-06 2.93277498307903e-06 2.16946134079821e-05 -2.24795881110139e-05 8.83097957803862e-05 1.1951026813637e-05 -5.85603588793825e-06 -4.23394660923718e-06 -6.04672509233933e-05 -1.44451912719011e-05 1.1951026813637e-05 1.77694381082449e-05 -9.78524757463851e-06 -8.55632911376635e-06 -1.1988725283753e-05 6.90378357836895e-06 -5.85603588793825e-06 -9.78524757463851e-06 2.50867999196688e-05 8.86823814722773e-06 8.68825576436743e-06 2.93277498307903e-06 -4.23394660923718e-06 -8.55632911376635e-06 8.86823814722773e-06 4.14987044055495e-05 -4.83847765182363e-07 2.16946134079821e-05 -6.04672509233933e-05 -1.1988725283753e-05 8.68825576436743e-06 -4.83847765182363e-07 7.17491706950886e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 713 0 0 0 0 0 2592 +1103 1133 0.999963767913615 0.00161991552377364 -0.00835695720349852 0.00692534255268204 -0.00161352998577264 0.999998401205158 0.000770784089159743 -0.0153918838205201 0.00835819244754996 -0.000757271961006377 0.999964782958973 -0.00442274895928015 3.85409610719146e-05 3.66301196299309e-06 -1.32390233477016e-05 8.7215763465987e-06 -3.17834384942143e-08 3.5256860056122e-05 3.66301196299309e-06 8.64874286779121e-05 1.49689687401675e-05 -1.32675352539927e-05 1.49867251778211e-05 -2.39567383234282e-05 -1.32390233477016e-05 1.49689687401675e-05 2.64896372085517e-05 -1.61733573606742e-05 -6.64253852022297e-06 -3.65629647128686e-06 8.7215763465987e-06 -1.32675352539927e-05 -1.61733573606742e-05 3.87702729053896e-05 -1.65099096722466e-05 5.75648106015909e-06 -3.17834384942143e-08 1.49867251778211e-05 -6.64253852022297e-06 -1.65099096722466e-05 0.000125267049630429 -2.18701927913136e-05 3.5256860056122e-05 -2.39567383234282e-05 -3.65629647128686e-06 5.75648106015909e-06 -2.18701927913136e-05 0.00011468141990047 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 689 0 0 0 0 0 2456 +1103 1134 0.999995479040999 0.000616904472353219 -0.00294301315573422 0.00709303737915149 -0.000615651048535497 0.999999719414109 0.000426785063373613 -0.0168966368364818 0.00294327561558058 -0.000424971264760657 0.999995578254262 -0.00646911676817723 6.78018927264446e-05 -4.9094301986736e-05 -1.16330452681414e-05 7.72325593962076e-06 -2.56696137272124e-05 9.1276152864034e-05 -4.9094301986736e-05 0.00016862830627651 1.76622765628308e-05 -9.89774255405783e-06 4.87202828131894e-05 -0.000133779120535576 -1.16330452681414e-05 1.76622765628308e-05 2.22221576926352e-05 -1.21633630798857e-05 -8.60144771849138e-06 -7.56002639905863e-06 7.72325593962076e-06 -9.89774255405783e-06 -1.21633630798857e-05 3.77739876582475e-05 -1.67130760905921e-05 4.74836452619812e-06 -2.56696137272124e-05 4.87202828131894e-05 -8.60144771849138e-06 -1.67130760905921e-05 0.000151719756501967 -6.60451330844088e-05 9.1276152864034e-05 -0.000133779120535576 -7.56002639905863e-06 4.74836452619812e-06 -6.60451330844088e-05 0.000226282596630558 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 695 0 0 0 0 0 2754 +1104 1140 0.999995391275706 -2.66958093570912e-05 0.00303590426087395 0.000730072752848426 2.25443140519187e-05 0.999999064728503 0.00136749181829456 0.00462494909863051 -0.00303593792778011 -0.0013674170735227 0.999994456610358 -0.00293747200168979 2.87435158585688e-05 -3.42393471826633e-05 -1.5600301433706e-05 3.29208015966355e-06 -1.95120313921813e-06 2.63012049791966e-05 -3.42393471826633e-05 0.000119484062520351 2.56657606624789e-05 -4.19977073322421e-06 -3.49381509448256e-06 -7.45368327079643e-05 -1.5600301433706e-05 2.56657606624789e-05 2.05391749091535e-05 -9.51481135525579e-06 -3.60453415215091e-06 -1.40054506653939e-05 3.29208015966355e-06 -4.19977073322421e-06 -9.51481135525579e-06 2.99233332883598e-05 -1.45887544887006e-05 -2.0724507378751e-06 -1.95120313921813e-06 -3.49381509448256e-06 -3.60453415215091e-06 -1.45887544887006e-05 8.24702786853275e-05 -3.70468972079566e-07 2.63012049791966e-05 -7.45368327079643e-05 -1.40054506653939e-05 -2.0724507378751e-06 -3.70468972079566e-07 7.81765467851765e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 978 0 0 0 0 0 2659 +1103 1129 0.999999792816296 -0.000148809199127999 0.000626277244669728 0.00689640304009974 0.00014774783293509 0.999998553541502 0.00169442777388671 -0.0149980706403924 -0.000626528485225698 -0.00169433489172317 0.999998368344335 -0.00549005772407276 2.52797431117829e-05 -2.8032494777715e-05 -1.63794934067096e-05 8.4244130723062e-06 -5.52315685872698e-06 1.98164289349118e-05 -2.8032494777715e-05 0.000114288292074332 2.84245258382892e-05 -1.91482585704568e-05 9.04957647523208e-06 -5.86917058237441e-05 -1.63794934067096e-05 2.84245258382892e-05 2.44042895186309e-05 -1.20761102389934e-05 -3.43696509151069e-06 -1.47437668904185e-05 8.4244130723062e-06 -1.91482585704568e-05 -1.20761102389934e-05 4.11837366767648e-05 -4.06352784413321e-05 6.91093139154859e-06 -5.52315685872698e-06 9.04957647523208e-06 -3.43696509151069e-06 -4.06352784413321e-05 0.000168019110954998 -6.54065629156984e-06 1.98164289349118e-05 -5.86917058237441e-05 -1.47437668904185e-05 6.91093139154859e-06 -6.54065629156984e-06 6.56602418425829e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 811 0 0 0 0 0 2479 +1104 1107 0.999994672655946 -0.000517564110717455 0.00322285387806772 0.00175196486357897 0.000519549799386335 0.999999675724173 -0.000615320693057328 -0.000916240073069527 -0.0032225343650668 0.000616991848118094 0.999994617282176 0.00129075140506535 3.36167202694823e-05 -3.95230855372779e-06 -1.2294274442705e-05 4.99057318003934e-06 7.73499638507229e-06 1.45101522198518e-05 -3.95230855372779e-06 9.75653272893529e-05 1.01188363710098e-05 1.93184533292635e-06 -7.09967116865141e-06 -6.24597837817719e-05 -1.2294274442705e-05 1.01188363710098e-05 1.8389319661111e-05 -8.6729821631166e-06 -8.1413046212333e-06 -6.38728483059983e-06 4.99057318003934e-06 1.93184533292635e-06 -8.6729821631166e-06 2.7675097622394e-05 7.97516666374299e-06 -5.77795557275126e-06 7.73499638507229e-06 -7.09967116865141e-06 -8.1413046212333e-06 7.97516666374299e-06 4.24014611562369e-05 3.71284819912624e-06 1.45101522198518e-05 -6.24597837817719e-05 -6.38728483059983e-06 -5.77795557275126e-06 3.71284819912624e-06 8.59727686940223e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 690 0 0 0 0 0 2535 +1104 1138 0.999994509767451 0.0007205481548208 0.00323438484298452 -0.00271947449743067 -0.000733453193066159 0.999991768784199 0.0039905400967107 0.0168584052112966 -0.00323148284376147 -0.00399289045760826 0.999986807085186 -0.0099924191723763 2.47343999343268e-05 -1.24225248135813e-05 -1.1545809706405e-05 4.8420689500255e-06 4.82032267004451e-06 1.63549418773165e-05 -1.24225248135813e-05 7.84774673081407e-05 1.62875513207366e-05 -6.50844342264637e-06 -8.36117003300147e-06 -3.1043038190276e-05 -1.1545809706405e-05 1.62875513207366e-05 2.14189475729452e-05 -1.30354497977318e-05 -5.53424787913267e-06 -7.1185692405388e-06 4.8420689500255e-06 -6.50844342264637e-06 -1.30354497977318e-05 3.41151263355046e-05 -6.4444446279514e-06 9.99028825891627e-07 4.82032267004451e-06 -8.36117003300147e-06 -5.53424787913267e-06 -6.4444446279514e-06 7.16496174483245e-05 3.90640178035978e-06 1.63549418773165e-05 -3.1043038190276e-05 -7.1185692405388e-06 9.99028825891627e-07 3.90640178035978e-06 5.53453183656517e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 962 0 0 0 0 0 2577 +1104 1137 0.999998998290681 0.000558459185938792 -0.00130059254641323 0.00499230515241955 -0.000559502165490949 0.999999522116532 -0.00080170071319564 -0.00803088620632986 0.0013001442077539 0.000802427594470705 0.999998832866816 0.000840972943513645 2.26489756085158e-05 -2.5724164220163e-05 -1.36534588486453e-05 4.08342336888793e-06 4.28084956863705e-06 1.75457045713769e-05 -2.5724164220163e-05 0.000109212093838972 2.67097521359818e-05 -1.11514621407077e-05 -1.11933415365077e-05 -5.67110104960921e-05 -1.36534588486453e-05 2.67097521359818e-05 2.22635477259845e-05 -1.2415760242425e-05 -9.68224620604208e-06 -1.19326509706794e-05 4.08342336888793e-06 -1.11514621407077e-05 -1.2415760242425e-05 2.88233093274296e-05 -1.90448545348859e-06 6.77549072233811e-06 4.28084956863705e-06 -1.11933415365077e-05 -9.68224620604208e-06 -1.90448545348859e-06 6.27250197896548e-05 2.02459000195384e-06 1.75457045713769e-05 -5.67110104960921e-05 -1.19326509706794e-05 6.77549072233811e-06 2.02459000195384e-06 6.5357345237682e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 989 0 0 0 0 0 2668 +1104 1135 0.999983726647183 0.000106788100965029 0.00570394925580212 0.00388596449474592 -0.000138471493541958 0.999984563862402 0.00555453531516804 -0.00694878879164528 -0.00570326805057851 -0.00555523475862766 0.999968305547891 -0.0146763919552826 2.29645640424045e-05 -9.34927646167908e-06 -1.17599684607345e-05 5.18530879282594e-06 4.09296179044639e-06 1.46712543791226e-05 -9.34927646167908e-06 7.05983769574803e-05 1.45134156253667e-05 -8.04426936578642e-06 -5.5027787356344e-06 -2.68565621470335e-05 -1.17599684607345e-05 1.45134156253667e-05 2.03758403976219e-05 -1.14172184070144e-05 -5.8888688583181e-06 -5.52035394150144e-06 5.18530879282594e-06 -8.04426936578642e-06 -1.14172184070144e-05 3.02436948820464e-05 -5.07342084232713e-06 2.61264589757217e-06 4.09296179044639e-06 -5.5027787356344e-06 -5.8888688583181e-06 -5.07342084232713e-06 6.79129610330311e-05 4.11582357053265e-06 1.46712543791226e-05 -2.68565621470335e-05 -5.52035394150144e-06 2.61264589757217e-06 4.11582357053265e-06 5.85178875251579e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 986 0 0 0 0 0 2618 +1104 1136 0.999975183474091 -5.78765457336808e-05 0.00704479142800359 0.00438860076081088 3.32173952721516e-06 0.999970016658334 0.00774375705310487 -0.00689624498613626 -0.00704502838352447 -0.00774354147899518 0.999945201068758 -0.0180365785055606 5.81948916046992e-05 -7.13158613676184e-06 -9.16127853048659e-06 1.00731061392628e-05 -1.77874024043818e-05 5.38112413385302e-05 -7.13158613676184e-06 0.000115105936357255 1.55003224116474e-05 -2.86369535314663e-06 2.28801202300153e-05 -6.5722418214634e-05 -9.16127853048659e-06 1.55003224116474e-05 2.04698007678797e-05 -1.04949691773281e-05 -5.0497745578104e-06 -6.3815500604137e-06 1.00731061392628e-05 -2.86369535314663e-06 -1.04949691773281e-05 3.39982878265661e-05 -1.45584098437906e-05 9.44962939247859e-06 -1.77874024043818e-05 2.28801202300153e-05 -5.0497745578104e-06 -1.45584098437906e-05 0.000116134825349163 -3.49306476197075e-05 5.38112413385302e-05 -6.5722418214634e-05 -6.3815500604137e-06 9.44962939247859e-06 -3.49306476197075e-05 0.000147375329955477 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 906 0 0 0 0 0 2629 +1104 1133 0.998848419988182 0.00104069887085752 -0.047966142569232 -0.00412268076748937 -0.00136239510645671 0.999976796992675 -0.00667453038375614 -0.00563599987236247 0.0479580834342408 0.00673219296588986 0.998826661544026 0.0240293504923514 0.000190968991336329 -0.000445419589314121 -1.48451756155105e-05 -8.39308166449389e-05 7.77851014986289e-06 0.000363634994138989 -0.000445419589314121 0.0151835416302933 0.000573969277081766 0.00221012236977172 -0.00174034023054882 -0.00661797863302237 -1.48451756155105e-05 0.000573969277081766 5.40407163583431e-05 6.23071293524988e-05 -6.65847113034385e-05 -0.000172282058863716 -8.39308166449389e-05 0.00221012236977172 6.23071293524988e-05 0.000373993254518439 -0.000269764670185428 -0.00107360371020065 7.77851014986289e-06 -0.00174034023054882 -6.65847113034385e-05 -0.000269764670185428 0.00033079016267903 0.00078969972044236 0.000363634994138989 -0.00661797863302237 -0.000172282058863716 -0.00107360371020065 0.00078969972044236 0.00359406521559911 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 861 0 0 0 0 0 2565 +1104 1131 0.999999882100062 0.000477965292369199 -8.57265526993089e-05 0.00517125757333929 -0.000477745391016806 0.999996642056551 0.00254708361933776 -0.0113200285838845 8.69436824011985e-05 -0.00254704236357131 0.999996752502724 -0.00468200294204263 2.86295284798021e-05 -3.52581218263091e-05 -1.51513685937635e-05 5.05875805807049e-06 -2.43367209850509e-06 2.44919846591094e-05 -3.52581218263091e-05 0.000156913233433275 3.15021281618058e-05 -1.46341965545582e-05 1.17103847334452e-05 -8.52743996032448e-05 -1.51513685937635e-05 3.15021281618058e-05 2.55272288612774e-05 -1.34812430389748e-05 -1.02601111356018e-05 -1.33340416188911e-05 5.05875805807049e-06 -1.46341965545582e-05 -1.34812430389748e-05 3.36491701913556e-05 -1.42403040385822e-05 1.6441436427291e-06 -2.43367209850509e-06 1.17103847334452e-05 -1.02601111356018e-05 -1.42403040385822e-05 0.000107693913679065 -1.41808224304129e-05 2.44919846591094e-05 -8.52743996032448e-05 -1.33340416188911e-05 1.6441436427291e-06 -1.41808224304129e-05 8.56471915865075e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 999 0 0 0 0 0 2621 +1104 1139 0.999999233145486 0.000810443356759895 -0.000936424051742909 -0.00212779645051823 -0.000806765659657868 0.999991986980823 0.00392110995966061 0.0102096893413671 0.000939594385676956 -0.00392035147797191 0.999991873970324 -0.00789202476721789 2.37507537936605e-05 -6.23174518017741e-06 -1.09525342447614e-05 6.47078071010031e-06 3.02618880545593e-06 1.08508767388111e-05 -6.23174518017741e-06 7.75010457040656e-05 1.47280603964908e-05 -7.79873314319626e-06 -5.63397357067239e-06 -3.42696525199848e-05 -1.09525342447614e-05 1.47280603964908e-05 2.11652538625937e-05 -1.17310902193476e-05 -6.43589753052762e-06 -4.69809952197237e-06 6.47078071010031e-06 -7.79873314319626e-06 -1.17310902193476e-05 3.25536739174021e-05 -1.44733350786735e-05 2.97586639306898e-06 3.02618880545593e-06 -5.63397357067239e-06 -6.43589753052762e-06 -1.44733350786735e-05 8.85084501689117e-05 3.62058910049386e-07 1.08508767388111e-05 -3.42696525199848e-05 -4.69809952197237e-06 2.97586639306898e-06 3.62058910049386e-07 5.65818521919352e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 956 0 0 0 0 0 2696 +1104 1134 0.999999267380551 0.000201520414640117 -0.00119357776569026 0.0066435659954758 -0.000203834975075345 0.999998098637146 -0.00193937448545977 -0.0159438178240554 0.00119318467271539 0.00193961635753042 0.999997407096 -0.002190445340642 3.61259690479036e-05 -3.49101342404814e-05 -1.83700805877392e-05 6.44889605766872e-06 3.4411235888064e-06 3.79109978471074e-05 -3.49101342404814e-05 0.000131084627251571 2.46824559678247e-05 -4.95742168846848e-06 -4.60501973230459e-06 -7.01488702715988e-05 -1.83700805877392e-05 2.46824559678247e-05 2.52183906985696e-05 -1.34302493745318e-05 -9.95798332209395e-06 -1.15927631217893e-05 6.44889605766872e-06 -4.95742168846848e-06 -1.34302493745318e-05 3.95039822639725e-05 -2.39481683551471e-05 -4.42490414561353e-06 3.4411235888064e-06 -4.60501973230459e-06 -9.95798332209395e-06 -2.39481683551471e-05 0.000114460907655969 3.20858834169798e-06 3.79109978471074e-05 -7.01488702715988e-05 -1.15927631217893e-05 -4.42490414561353e-06 3.20858834169798e-06 0.000104598554289548 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 866 0 0 0 0 0 2638 +1105 1107 0.999999092806428 -0.000126515279407584 0.00134103698883774 0.00275418660271016 0.000125976671417455 0.999999911378546 0.000401712307618698 -0.00551331116864163 -0.00134108769273793 -0.000401543003811773 0.999999020123028 0.00242133769529946 2.66678824829715e-05 -5.4428926367335e-06 -1.45729693163739e-05 9.04254103888846e-06 3.48739972579121e-06 1.95149022352045e-05 -5.4428926367335e-06 8.12127436376446e-05 8.0618080864715e-06 -1.80660947283006e-06 -2.24775998152652e-06 -4.13579070734149e-05 -1.45729693163739e-05 8.0618080864715e-06 2.1737879190754e-05 -1.44739340612095e-05 -8.63875278160405e-06 -1.09817037510716e-05 9.04254103888846e-06 -1.80660947283006e-06 -1.44739340612095e-05 2.99554870579022e-05 4.77409741561718e-06 1.06118539834829e-05 3.48739972579121e-06 -2.24775998152652e-06 -8.63875278160405e-06 4.77409741561718e-06 4.3173500928281e-05 -3.78083018400229e-06 1.95149022352045e-05 -4.13579070734149e-05 -1.09817037510716e-05 1.06118539834829e-05 -3.78083018400229e-06 6.7756037656452e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 724 0 0 0 0 0 2554 +1104 1132 0.999973381942323 0.000570535209648142 -0.00727391891680681 0.00417302798218651 -0.000569034524489939 0.999999816389076 0.000208378318872622 -0.0116141832653604 0.00727403646840368 -0.000204233661254508 0.999973522990518 -0.00320866766219694 2.83025602311652e-05 -2.77509087236164e-05 -1.38980861921847e-05 5.69748498351238e-06 2.44743917262436e-07 1.61911558001966e-05 -2.77509087236164e-05 0.000131148942532306 3.09871157476705e-05 -1.51350587673143e-05 -9.72472967838747e-06 -6.78259831862064e-05 -1.38980861921847e-05 3.09871157476705e-05 2.60521346488304e-05 -1.42858927723231e-05 -9.23592815434729e-06 -1.0627841402259e-05 5.69748498351238e-06 -1.51350587673143e-05 -1.42858927723231e-05 3.69503053048738e-05 -1.86452192527121e-05 -3.94476564593968e-07 2.44743917262436e-07 -9.72472967838747e-06 -9.23592815434729e-06 -1.86452192527121e-05 0.000103739190144815 7.0852810461639e-07 1.61911558001966e-05 -6.78259831862064e-05 -1.0627841402259e-05 -3.94476564593968e-07 7.0852810461639e-07 7.95115263993138e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 985 0 0 0 0 0 2543 +1104 1130 0.999996051887901 0.000725975416819409 -0.00271462120836973 0.00271188999965783 -0.000708245140196626 0.999978450272057 0.00652666686115816 -0.00527367852914585 0.0027193009087162 -0.00652471847586746 0.999975016413599 -0.016682449424334 3.5319631733663e-05 3.24436027981741e-06 -1.00348735974563e-05 4.39087408754251e-06 -2.70798537012072e-07 2.50741551334605e-05 3.24436027981741e-06 8.58883995976317e-05 1.19427028359087e-05 -2.52080492130372e-07 -3.67672290255722e-06 -3.78978119810459e-05 -1.00348735974563e-05 1.19427028359087e-05 2.02688076865277e-05 -8.92447001119359e-06 -4.94805477789324e-06 -5.80269989185235e-06 4.39087408754251e-06 -2.52080492130372e-07 -8.92447001119359e-06 3.15717981650779e-05 -1.02513329777987e-05 5.60740361660246e-06 -2.70798537012072e-07 -3.67672290255722e-06 -4.94805477789324e-06 -1.02513329777987e-05 9.14726519390629e-05 -1.72441105122631e-05 2.50741551334605e-05 -3.78978119810459e-05 -5.80269989185235e-06 5.60740361660246e-06 -1.72441105122631e-05 0.000106427792771098 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 900 0 0 0 0 0 2688 +1105 1109 0.999999048855578 0.000672843181651262 -0.00120398089354343 0.0024649088385086 -0.000672589477847466 0.999999751527259 0.000211113275716332 -0.00500086787631221 0.00120412264051512 -0.000210303290036591 0.999999252930317 0.00272686963859732 2.52621440566849e-05 -1.70036231083474e-05 -1.43842830380916e-05 5.83021920829406e-06 3.44038490991974e-06 9.95198626179846e-06 -1.70036231083474e-05 8.29556761791766e-05 1.76484659643265e-05 -9.67387935061377e-06 -3.08955243751058e-06 -5.05798855919472e-05 -1.43842830380916e-05 1.76484659643265e-05 2.19042729468822e-05 -1.3170706787556e-05 -6.42384711592874e-06 -1.02781726449434e-05 5.83021920829406e-06 -9.67387935061377e-06 -1.3170706787556e-05 2.82818838639599e-05 -9.73520957221834e-07 5.87481754650081e-06 3.44038490991974e-06 -3.08955243751058e-06 -6.42384711592874e-06 -9.73520957221834e-07 5.27617625320282e-05 -2.09280663138514e-06 9.95198626179846e-06 -5.05798855919472e-05 -1.02781726449434e-05 5.87481754650081e-06 -2.09280663138514e-06 4.64890393817931e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 880 0 0 0 0 0 2531 +1105 1138 0.99999646426682 0.000839551311814916 0.00252321371531587 -0.00512372068139095 -0.000842530743209736 0.999998948897217 0.00117997729148498 0.019707416007291 -0.00252222041167593 -0.00118209900452696 0.999996120515544 -0.00575689441526086 2.56257545265742e-05 -2.10909751964733e-05 -1.22119294053194e-05 3.3091764606442e-06 5.0130008603238e-06 1.69201588200569e-05 -2.10909751964733e-05 0.000113084670962938 2.30206038983539e-05 -4.57101175758473e-06 -1.24623820558794e-05 -5.36213766585369e-05 -1.22119294053194e-05 2.30206038983539e-05 2.29515642581196e-05 -1.36130502698916e-05 -1.06294620041138e-05 -9.23772568145924e-06 3.3091764606442e-06 -4.57101175758473e-06 -1.36130502698916e-05 3.23979075979071e-05 -4.99632721222701e-06 -4.56929354009758e-07 5.0130008603238e-06 -1.24623820558794e-05 -1.06294620041138e-05 -4.99632721222701e-06 7.81230056314207e-05 3.52804742863016e-06 1.69201588200569e-05 -5.36213766585369e-05 -9.23772568145924e-06 -4.56929354009758e-07 3.52804742863016e-06 5.8063558402191e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1055 0 0 0 0 0 2602 +1105 1108 0.999992345050631 0.000379120611697996 0.00389436871669837 0.000698645346645743 -0.000374679200048833 0.999999278711216 -0.00114113651462144 0.00203815284478686 -0.00389479853610735 0.00113966864032373 0.999991765815976 -0.000912416641216565 2.7916832526824e-05 -2.22052607549723e-05 -1.43542028948284e-05 5.25599450788279e-06 2.63933157754886e-06 1.42378351737155e-05 -2.22052607549723e-05 0.000114195954418355 1.1135820276211e-05 -8.72547703927299e-07 8.38625493656551e-06 -6.19325645638632e-05 -1.43542028948284e-05 1.1135820276211e-05 2.08451178544031e-05 -1.10353774023845e-05 -5.72086705448195e-06 -9.44859584573918e-06 5.25599450788279e-06 -8.72547703927299e-07 -1.10353774023845e-05 3.24085974609136e-05 -4.23773055188705e-06 3.06517861397673e-06 2.63933157754886e-06 8.38625493656551e-06 -5.72086705448195e-06 -4.23773055188705e-06 6.98455951414112e-05 -4.29508134658822e-06 1.42378351737155e-05 -6.19325645638632e-05 -9.44859584573918e-06 3.06517861397673e-06 -4.29508134658822e-06 5.94414750031814e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 751 0 0 0 0 0 2568 +1105 1139 0.999994951016133 0.00114993095089217 0.0029623640980503 -0.00168846585067864 -0.00115740763597123 0.999996146385802 0.00252341457342583 0.0110595486755775 -0.00295945092972204 -0.00252683049557397 0.999992428360256 -0.00697267714855632 2.98427737554817e-05 -3.41646319767994e-05 -1.81213359727724e-05 8.5642253650281e-06 -1.2023644174394e-06 2.0376329719577e-05 -3.41646319767994e-05 0.000134842858249716 2.44002959216667e-05 -9.98784298090498e-06 6.03515280057595e-06 -5.90321408453867e-05 -1.81213359727724e-05 2.44002959216667e-05 2.5552717405533e-05 -1.51336406996571e-05 -9.15992045449986e-06 -1.26255595748356e-05 8.5642253650281e-06 -9.98784298090498e-06 -1.51336406996571e-05 3.47506758132087e-05 -6.77061911419426e-06 6.66456902568925e-06 -1.2023644174394e-06 6.03515280057595e-06 -9.15992045449986e-06 -6.77061911419426e-06 8.31371111769121e-05 -3.97499377296742e-06 2.0376329719577e-05 -5.90321408453867e-05 -1.26255595748356e-05 6.66456902568925e-06 -3.97499377296742e-06 6.53508694902732e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1030 0 0 0 0 0 2668 +1105 1134 0.999983254886115 0.000177144789337986 0.00578433808607212 0.00747378349206261 -0.000183327685019537 0.999999412466536 0.0010683901641157 -0.0143599650410845 -0.00578414542782937 -0.00106943270311142 0.999982699838034 -0.00813721996698114 2.57199128039832e-05 -4.52231409963938e-06 -1.21347525532104e-05 5.4804655872937e-06 8.66529445462436e-06 1.3287381831582e-05 -4.52231409963938e-06 9.39053669139803e-05 1.84431952493482e-05 -2.30461732242458e-06 -2.40189619606671e-05 -3.41703103284461e-05 -1.21347525532104e-05 1.84431952493482e-05 2.3143039391584e-05 -1.32088003699543e-05 -1.00678963818406e-05 -7.65454309570847e-06 5.4804655872937e-06 -2.30461732242458e-06 -1.32088003699543e-05 4.39768956931977e-05 -4.3801236816938e-05 1.25808269525353e-06 8.66529445462436e-06 -2.40189619606671e-05 -1.00678963818406e-05 -4.3801236816938e-05 0.000164636216436041 1.2919861722303e-05 1.3287381831582e-05 -3.41703103284461e-05 -7.65454309570847e-06 1.25808269525353e-06 1.2919861722303e-05 6.22292153867242e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 958 0 0 0 0 0 2567 +1105 1136 0.999998943233081 0.00104084540457832 -0.00101497466177743 0.00261451285190364 -0.00103449412908025 0.999980007481598 0.00623814547768763 -0.00309247776918716 0.00102144731493137 -0.00623708890009308 0.999980027484267 -0.0125046354240221 3.44901531917606e-05 -1.27766136216424e-05 -1.28000058424866e-05 9.78180748985073e-06 -1.90915355843926e-07 2.35399955916921e-05 -1.27766136216424e-05 9.34053521263618e-05 1.56573783577593e-05 -1.04026372168711e-05 1.89765553169789e-05 -4.08419137577839e-05 -1.28000058424866e-05 1.56573783577593e-05 2.16469552976307e-05 -1.18173342051893e-05 -1.22348015396058e-05 -7.18582042296245e-06 9.78180748985073e-06 -1.04026372168711e-05 -1.18173342051893e-05 2.94045536724368e-05 -4.37729702135962e-06 9.95770660509157e-06 -1.90915355843926e-07 1.89765553169789e-05 -1.22348015396058e-05 -4.37729702135962e-06 9.73087050715135e-05 -1.4368616388241e-05 2.35399955916921e-05 -4.08419137577839e-05 -7.18582042296245e-06 9.95770660509157e-06 -1.4368616388241e-05 7.24743553844377e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1003 0 0 0 0 0 2658 +1105 1137 0.999971995774166 0.000116052455874311 0.00748292718518293 0.00638020182428377 -0.00011478612859848 0.999999979020134 -0.000169658117246908 -0.00905017802795886 -0.00748294671743329 0.000168794429860507 0.999971988116099 -0.00216587511635616 2.56572713130949e-05 -1.9233346677981e-05 -8.98075171820228e-06 2.11340905412472e-06 3.00390429580096e-06 1.60290267001779e-05 -1.9233346677981e-05 0.00010615007369424 1.94695545359848e-05 -1.70980514457383e-06 -1.43783155342682e-05 -4.81330052278597e-05 -8.98075171820228e-06 1.94695545359848e-05 2.00587368531649e-05 -1.1141245899876e-05 -8.9521342046121e-06 -6.39416149595103e-06 2.11340905412472e-06 -1.70980514457383e-06 -1.1141245899876e-05 3.16048713256728e-05 -1.33648059810256e-05 1.09641057161855e-06 3.00390429580096e-06 -1.43783155342682e-05 -8.9521342046121e-06 -1.33648059810256e-05 8.38449515954605e-05 1.83239883193728e-06 1.60290267001779e-05 -4.81330052278597e-05 -6.39416149595103e-06 1.09641057161855e-06 1.83239883193728e-06 5.62987111636187e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1082 0 0 0 0 0 2657 +1105 1132 0.999997053290261 0.000512295171336414 -0.00237296532897934 0.00387417795812733 -0.000513042237291725 0.999999819024895 -0.000314225780006109 -0.00738584522213609 0.00237280392318188 0.000315442285515338 0.99999713514475 -0.00306507727335303 2.32561568008198e-05 -1.16093228862126e-05 -1.12571805775617e-05 8.80341133563677e-06 -7.92762445790501e-06 1.60897237071284e-05 -1.16093228862126e-05 8.33160910256752e-05 1.93763839479605e-05 -1.35687537720971e-05 -6.23515208027756e-06 -2.59316844396106e-05 -1.12571805775617e-05 1.93763839479605e-05 2.1333291472236e-05 -1.07133346207589e-05 -1.28383249606813e-05 -3.54061330964745e-06 8.80341133563677e-06 -1.35687537720971e-05 -1.07133346207589e-05 3.0870300268938e-05 -1.65591920879598e-05 8.76089600027816e-06 -7.92762445790501e-06 -6.23515208027756e-06 -1.28383249606813e-05 -1.65591920879598e-05 0.000117871025491537 -2.21930588524463e-05 1.60897237071284e-05 -2.59316844396106e-05 -3.54061330964745e-06 8.76089600027816e-06 -2.21930588524463e-05 5.84078487622311e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1081 0 0 0 0 0 2537 +1105 1140 0.999996582943753 9.45373318095351e-06 0.00261419422480004 -0.00256980405542333 -8.87943090954775e-06 0.999999975827044 -0.000219697671637186 0.0132214510239556 -0.00261419623857041 0.000219673708360882 0.999996558854823 -0.00304959492542997 3.6851475584581e-05 -3.93989978730759e-05 -1.66504671624552e-05 8.6507676546274e-06 -3.50997403665491e-06 4.08832705204389e-05 -3.93989978730759e-05 0.000150755919989971 2.62532324387124e-05 -1.49397855289164e-05 1.28735365842051e-05 -9.57118531084138e-05 -1.66504671624552e-05 2.62532324387124e-05 2.52563894275228e-05 -1.70417434996153e-05 -8.16573183902804e-06 -1.56336715526606e-05 8.6507676546274e-06 -1.49397855289164e-05 -1.70417434996153e-05 3.90714022953638e-05 -1.18413635920376e-05 6.11020424145493e-06 -3.50997403665491e-06 1.28735365842051e-05 -8.16573183902804e-06 -1.18413635920376e-05 0.000100179297920144 -6.44285380846212e-06 4.08832705204389e-05 -9.57118531084138e-05 -1.56336715526606e-05 6.11020424145493e-06 -6.44285380846212e-06 0.000112545666628032 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1050 0 0 0 0 0 2673 +1105 1131 0.999996286678968 0.000541218777427236 0.00267090069255682 0.00580550593276616 -0.000541955904143674 0.999999815255568 0.000275268282862877 -0.0117497915454991 -0.00267075121875927 -0.000276714771103086 0.999996395251934 -0.00551455231090212 2.89600751637758e-05 -1.62515051959953e-05 -1.39361429602607e-05 6.89546579915305e-06 3.86329694755275e-06 2.07873076892956e-05 -1.62515051959953e-05 9.28348900539533e-05 1.6117738011575e-05 -6.72616781328938e-06 -2.75314638802767e-06 -4.55798999733139e-05 -1.39361429602607e-05 1.6117738011575e-05 2.18315683983971e-05 -1.1775723693828e-05 -1.01907274093849e-05 -1.00314602757122e-05 6.89546579915305e-06 -6.72616781328938e-06 -1.1775723693828e-05 3.70810189249416e-05 -3.25002657152396e-05 2.69995189279645e-06 3.86329694755275e-06 -2.75314638802767e-06 -1.01907274093849e-05 -3.25002657152396e-05 0.000157713142817845 1.03356421689311e-06 2.07873076892956e-05 -4.55798999733139e-05 -1.00314602757122e-05 2.69995189279645e-06 1.03356421689311e-06 7.17587538213519e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1085 0 0 0 0 0 2581 +1105 1135 0.999980886084032 -0.000549466993293577 0.00615837256243843 0.00321206334891965 0.000534158943377526 0.999996764501263 0.00248709895839441 -0.0023272918682618 -0.00615971921581847 -0.00248376187041304 0.999977944149846 -0.0127471480713585 2.62361949608143e-05 -3.01044175571913e-05 -1.27979979219645e-05 3.02442463754978e-06 3.86453758267008e-06 2.04649888734657e-05 -3.01044175571913e-05 0.0001503488918021 2.60253200030746e-05 -1.71132895651356e-06 -1.77976642350056e-05 -7.27127027692222e-05 -1.27979979219645e-05 2.60253200030746e-05 2.51577006099014e-05 -1.31672623590081e-05 -1.14201773574378e-05 -1.25018029069486e-05 3.02442463754978e-06 -1.71132895651356e-06 -1.31672623590081e-05 3.9222979182504e-05 -1.38011631694924e-05 4.67139418613804e-06 3.86453758267008e-06 -1.77976642350056e-05 -1.14201773574378e-05 -1.38011631694924e-05 0.00010401838146342 -6.25473892745695e-07 2.04649888734657e-05 -7.27127027692222e-05 -1.25018029069486e-05 4.67139418613804e-06 -6.25473892745695e-07 8.27509411984611e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1082 0 0 0 0 0 2571 +1105 1133 0.999978895857066 -0.000357058563154215 0.00648693684762732 0.00677389789303222 0.000343891168794546 0.999997878723012 0.00203083439493536 -0.0129822608457223 -0.00648764821384853 -0.00202856073562159 0.999976897414133 -0.00794780451940262 3.663084320011e-05 5.6531062019465e-06 -1.27561028368962e-05 6.83634004604383e-06 1.17325346597062e-05 1.95300363318902e-05 5.6531062019465e-06 8.73493467930765e-05 1.27591278409857e-05 1.40706266574386e-06 -2.3750431884049e-05 -1.80258186086827e-05 -1.27561028368962e-05 1.27591278409857e-05 2.26464413202576e-05 -1.14287899220502e-05 -1.28300255811634e-05 -4.11847236739562e-06 6.83634004604383e-06 1.40706266574386e-06 -1.14287899220502e-05 4.44129521992858e-05 -3.46563219745973e-05 3.44281456840622e-06 1.17325346597062e-05 -2.3750431884049e-05 -1.28300255811634e-05 -3.46563219745973e-05 0.000145245361265021 6.23023369740173e-06 1.95300363318902e-05 -1.80258186086827e-05 -4.11847236739562e-06 3.44281456840622e-06 6.23023369740173e-06 7.20881016060036e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 959 0 0 0 0 0 2529 +1106 1109 0.999985732768375 0.000450524411301381 -0.00532271429348952 0.00316739371110521 -0.000452575930617362 0.999999823771498 -0.000384229096815252 -0.00891126465819578 0.00532254025088791 0.000386632547304517 0.999985760438893 0.00407787381746389 2.34568149495228e-05 -1.41359365509704e-05 -1.4048543121639e-05 5.42936643117247e-06 3.54278311878851e-06 6.68194907239597e-06 -1.41359365509704e-05 8.52767142550832e-05 1.47787730572053e-05 -7.46856909895387e-06 -3.59708637019212e-06 -5.01026294584033e-05 -1.4048543121639e-05 1.47787730572053e-05 2.04890675602614e-05 -1.09091178759967e-05 -7.38816629183979e-06 -1.00056562593163e-05 5.42936643117247e-06 -7.46856909895387e-06 -1.09091178759967e-05 2.59370451191229e-05 3.56943711448279e-06 7.52310360745515e-06 3.54278311878851e-06 -3.59708637019212e-06 -7.38816629183979e-06 3.56943711448279e-06 5.05500186981795e-05 9.6174849091679e-07 6.68194907239597e-06 -5.01026294584033e-05 -1.00056562593163e-05 7.52310360745515e-06 9.6174849091679e-07 4.52102261114673e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 901 0 0 0 0 0 2601 +1106 1108 0.999987780044032 -0.000356421660119135 0.00493079366927554 0.0023903008658105 0.000353650189878143 0.999999779018213 0.000562934337597671 -0.00174851393200936 -0.00493099322165109 -0.000561183682447463 0.999987685113533 -0.00288856709627142 3.82189385454922e-05 -3.57077960338303e-05 -1.95448371710769e-05 6.99507708758242e-06 5.5342913065984e-06 2.8248234631639e-05 -3.57077960338303e-05 0.00016699876433132 1.43450980544816e-05 6.86980932135384e-06 5.23982441280459e-06 -9.42839214518511e-05 -1.95448371710769e-05 1.43450980544816e-05 2.44949570274408e-05 -1.4331477529926e-05 -1.16358447496678e-05 -1.49494584889739e-05 6.99507708758242e-06 6.86980932135384e-06 -1.4331477529926e-05 2.98132005984406e-05 1.55601852706336e-05 2.93394900700215e-06 5.5342913065984e-06 5.23982441280459e-06 -1.16358447496678e-05 1.55601852706336e-05 4.04073954272835e-05 -1.44067728945353e-06 2.8248234631639e-05 -9.42839214518511e-05 -1.49494584889739e-05 2.93394900700215e-06 -1.44067728945353e-06 8.43346070688032e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 765 0 0 0 0 0 2585 +1106 1139 0.999998935665343 0.000435056343546406 0.00139262132663126 -0.00131688560693284 -0.000440055374795295 0.999993454205039 0.00359136441233623 0.00893392167271343 -0.00139104976494803 -0.00359197342042246 0.999992581326231 -0.00871379694383143 2.69910548156302e-05 -2.30182401119073e-05 -1.50627780849383e-05 7.79924990295258e-06 5.35996931490891e-06 1.99202074864742e-05 -2.30182401119073e-05 0.000115635360729394 1.79780639037355e-05 -8.96238153256561e-06 6.89722170571281e-06 -4.61244605611307e-05 -1.50627780849383e-05 1.79780639037355e-05 2.15023484198673e-05 -1.24165658087357e-05 -9.75223207392421e-06 -8.53884374083107e-06 7.79924990295258e-06 -8.96238153256561e-06 -1.24165658087357e-05 3.09682647149522e-05 -6.76664170960788e-06 2.86263704850442e-06 5.35996931490891e-06 6.89722170571281e-06 -9.75223207392421e-06 -6.76664170960788e-06 9.0886259472423e-05 8.23200126198281e-06 1.99202074864742e-05 -4.61244605611307e-05 -8.53884374083107e-06 2.86263704850442e-06 8.23200126198281e-06 5.89113197015314e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 997 0 0 0 0 0 2693 +1106 1140 0.999999815711091 0.000589932446543502 0.000143378842696786 0.0023387515034143 -0.000589813328522327 0.999999482091756 -0.000829419348882602 0.000865742245983493 -0.000143868069825398 0.000829334629277365 0.999999645752963 -0.00340959487785953 2.72201878083103e-05 -2.74074829620315e-05 -1.41716068162163e-05 3.94427242004201e-06 3.3486588529044e-06 1.65635642983042e-05 -2.74074829620315e-05 0.000118938515601246 2.47207830454926e-05 -1.07962415037054e-05 -1.59428692309352e-07 -6.59600027767595e-05 -1.41716068162163e-05 2.47207830454926e-05 2.54419158543748e-05 -1.38193214754658e-05 -1.36116279837019e-05 -1.19126704388927e-05 3.94427242004201e-06 -1.07962415037054e-05 -1.38193214754658e-05 3.0217793561409e-05 1.97094060328721e-06 -3.01260274210553e-07 3.3486588529044e-06 -1.59428692309352e-07 -1.36116279837019e-05 1.97094060328721e-06 7.06813784161353e-05 4.36590689236103e-06 1.65635642983042e-05 -6.59600027767595e-05 -1.19126704388927e-05 -3.01260274210553e-07 4.36590689236103e-06 6.98878124620887e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1040 0 0 0 0 0 2617 +1106 1134 0.999997898728605 -0.000161844729334619 0.00204361069149511 0.00892566835376836 0.000166797011632455 0.999997049742382 -0.00242336239299497 -0.0218733287061375 -0.00204321245388652 0.00242369816900917 0.999994975472404 -0.00330444264402255 2.5989839376837e-05 -1.5271940642236e-05 -1.16836968167474e-05 4.89127179858306e-06 7.01990161404769e-06 1.52773299110649e-05 -1.5271940642236e-05 0.000106004051193024 1.23483817287705e-05 5.50309198129889e-07 -5.98208893306885e-06 -4.44277609182028e-05 -1.16836968167474e-05 1.23483817287705e-05 2.31284358705648e-05 -1.43739814188228e-05 -1.16034212634859e-05 -8.2420904749497e-06 4.89127179858306e-06 5.50309198129889e-07 -1.43739814188228e-05 3.40364762704278e-05 -4.44542463049356e-06 2.05862865863121e-06 7.01990161404769e-06 -5.98208893306885e-06 -1.16034212634859e-05 -4.44542463049356e-06 7.98998261034627e-05 3.502393800611e-06 1.52773299110649e-05 -4.44277609182028e-05 -8.2420904749497e-06 2.05862865863121e-06 3.502393800611e-06 7.3097243224251e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 925 0 0 0 0 0 2664 +1106 1138 0.999988736545239 0.000120800884927599 0.00474470123422029 -0.00405532250844301 -0.000138326966517405 0.999993168819679 0.00369366750355236 0.0165188055861659 -0.00474422262400754 -0.0036942822202243 0.999981922151881 -0.0102997426491268 2.35132996907338e-05 -5.25678035000175e-06 -9.89737635043973e-06 4.49676795244238e-06 5.99188389344635e-06 1.17105217944036e-05 -5.25678035000175e-06 7.70996892798843e-05 1.22318974107186e-05 -1.92448423283328e-06 2.00242967269287e-06 -3.14660446686109e-05 -9.89737635043973e-06 1.22318974107186e-05 2.05007471998935e-05 -1.31295347352182e-05 -6.70320303194117e-06 -5.6113202887967e-06 4.49676795244238e-06 -1.92448423283328e-06 -1.31295347352182e-05 3.33206066264948e-05 -6.51956083281576e-06 1.45255043359241e-06 5.99188389344635e-06 2.00242967269287e-06 -6.70320303194117e-06 -6.51956083281576e-06 7.32457445549193e-05 2.26606163721349e-06 1.17105217944036e-05 -3.14660446686109e-05 -5.6113202887967e-06 1.45255043359241e-06 2.26606163721349e-06 5.18391733519505e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1026 0 0 0 0 0 2569 +1106 1110 0.999996333747925 -0.00040356677360087 -0.00267761546293629 -0.000339719177063506 0.000344332754959408 0.999756023463334 -0.0220856284432839 -0.00204461999988258 0.00268587521340292 0.0220846254810937 0.999752497066998 0.00982790602895452 0.00458591744625486 0.000693129253482329 8.19675910074676e-05 -0.000505145357699192 0.00108444816524501 0.00036154636990265 0.000693129253482329 0.000337352817225507 2.88032404372781e-05 -6.62692945327929e-05 0.000171722783391367 -0.00012674910358823 8.19675910074676e-05 2.88032404372781e-05 2.75717132209886e-05 -2.77964211750076e-05 8.59144626369534e-06 -5.82754989971492e-06 -0.000505145357699192 -6.62692945327929e-05 -2.77964211750076e-05 9.99283085441092e-05 -0.000117481842974324 -8.94054807245618e-05 0.00108444816524501 0.000171722783391367 8.59144626369534e-06 -0.000117481842974324 0.000330129936727871 0.000186626891724071 0.00036154636990265 -0.00012674910358823 -5.82754989971492e-06 -8.94054807245618e-05 0.000186626891724071 0.000559690403746875 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 750 0 0 0 0 0 2529 +1106 1132 0.999999230590042 0.000311426413617942 0.001200763471126 0.0059835636467012 -0.000313255698000296 0.999998790336341 0.00152354741421332 -0.0119060130338378 -0.00120028754569888 -0.00152392238798005 0.999998118483411 -0.00693794422983303 1.80416424524572e-05 -1.17755972634737e-05 -9.66147989971903e-06 1.27484670790736e-06 5.74543271019276e-06 7.24079689834955e-06 -1.17755972634737e-05 9.03871045419115e-05 1.41296964331601e-05 -1.19845816155271e-06 -2.07241865234183e-05 -3.1760430633106e-05 -9.66147989971903e-06 1.41296964331601e-05 1.7653785889889e-05 -8.65427229842949e-06 -1.01215444173918e-05 -3.92532244144065e-06 1.27484670790736e-06 -1.19845816155271e-06 -8.65427229842949e-06 2.96546283460009e-05 -1.29576322863984e-05 -4.17323738288218e-06 5.74543271019276e-06 -2.07241865234183e-05 -1.01215444173918e-05 -1.29576322863984e-05 8.18821064271798e-05 9.69242526919144e-06 7.24079689834955e-06 -3.1760430633106e-05 -3.92532244144065e-06 -4.17323738288218e-06 9.69242526919144e-06 5.15418649866916e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1069 0 0 0 0 0 2512 +1106 1135 0.999934686361529 -0.000694110023802683 0.0114079455795347 0.00505867890600643 0.00063983776508828 0.999988464675948 0.00476037001440839 -0.00817595582434323 -0.0114111182057297 -0.00475275986291842 0.999923595908698 -0.0157298118800574 2.20585511580477e-05 -7.26921651580197e-06 -9.85732943060774e-06 3.76248274000313e-06 6.62593506796231e-07 1.13533594254792e-05 -7.26921651580197e-06 8.31715210899239e-05 1.65680960860315e-05 -3.96749801522424e-06 -3.73183444480764e-06 -2.70230886948907e-05 -9.85732943060774e-06 1.65680960860315e-05 2.47977292357331e-05 -1.56715804824245e-05 -7.25827468813119e-06 -6.18894595951686e-06 3.76248274000313e-06 -3.96749801522424e-06 -1.56715804824245e-05 3.59849368473169e-05 -1.34081890285511e-05 2.10740540427338e-07 6.62593506796231e-07 -3.73183444480764e-06 -7.25827468813119e-06 -1.34081890285511e-05 8.33060860230154e-05 5.62945936074383e-06 1.13533594254792e-05 -2.70230886948907e-05 -6.18894595951686e-06 2.10740540427338e-07 5.62945936074383e-06 5.08893774295155e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1054 0 0 0 0 0 2555 +1106 1137 0.999995164441429 0.000114760129535265 0.00310772004403671 0.00739404181364234 -0.000114470005543237 0.999999989074041 -9.35336067794483e-05 -0.0135818083961996 -0.00310773074401072 9.31774137615467e-05 0.999995166652116 -0.00344488087840613 2.38910603190003e-05 -2.41542254639488e-05 -1.23558607615478e-05 5.48157162087098e-06 -4.15820183248282e-06 1.44062050710991e-05 -2.41542254639488e-05 0.000122088690036856 2.90667740246061e-05 -1.67768972800004e-05 8.58896651054749e-06 -6.40943550572849e-05 -1.23558607615478e-05 2.90667740246061e-05 2.4882885244757e-05 -1.54013735355084e-05 -9.24230846155055e-06 -1.37329641190551e-05 5.48157162087098e-06 -1.67768972800004e-05 -1.54013735355084e-05 3.09035099117842e-05 -4.20893763570718e-06 1.04562975682404e-05 -4.15820183248282e-06 8.58896651054749e-06 -9.24230846155055e-06 -4.20893763570718e-06 7.92542390254101e-05 -1.18241221808334e-05 1.44062050710991e-05 -6.40943550572849e-05 -1.37329641190551e-05 1.04562975682404e-05 -1.18241221808334e-05 6.13223790675394e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1044 0 0 0 0 0 2592 +1106 1133 0.999996083318522 3.27964919119445e-06 0.00279880990051665 0.00840418749975218 -3.73223578894922e-07 0.999999460810152 -0.0010384504160884 -0.0194460819550982 -0.00279881179717983 0.00103844530422704 0.99999554413201 -0.00234231412427152 3.08979714855831e-05 -1.31715149603876e-05 -1.26789803939255e-05 7.13883588342752e-06 -3.10910957468922e-06 1.92006811421818e-05 -1.31715149603876e-05 0.000114105631373261 1.11590261188302e-05 -8.73570082445202e-06 2.23567543408625e-05 -4.50419358053368e-05 -1.26789803939255e-05 1.11590261188302e-05 1.87436499818945e-05 -1.07588740379403e-05 -8.47412617673146e-06 -3.99123084752392e-06 7.13883588342752e-06 -8.73570082445202e-06 -1.07588740379403e-05 3.18515722370008e-05 -1.49450377767497e-05 4.8399818392115e-06 -3.10910957468922e-06 2.23567543408625e-05 -8.47412617673146e-06 -1.49450377767497e-05 0.000116358286399819 -1.71462755151996e-05 1.92006811421818e-05 -4.50419358053368e-05 -3.99123084752392e-06 4.8399818392115e-06 -1.71462755151996e-05 6.97038305743261e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 919 0 0 0 0 0 2573 +1106 1136 0.999999920675213 -0.00039695742295641 -3.27776277179137e-05 0.00484819223745509 0.000397136378275694 0.99998394171397 0.00565319351231475 -0.0142149065519712 3.05330242372701e-05 -0.00565320608106473 0.99998402003669 -0.0107753718255792 4.3151010440971e-05 -2.26161686625492e-06 -8.7514082316043e-06 7.87115933277917e-06 -6.80974545320382e-06 3.56018838280225e-05 -2.26161686625492e-06 0.000108064291167415 1.38657451777834e-05 -8.12755163666997e-06 1.91857599076002e-05 -3.4972266022602e-05 -8.7514082316043e-06 1.38657451777834e-05 2.07357250412832e-05 -1.32508069473463e-05 -6.52403688737053e-06 -3.52863665889474e-06 7.87115933277917e-06 -8.12755163666997e-06 -1.32508069473463e-05 3.50727929350588e-05 -5.29918345015088e-06 1.07288032194055e-05 -6.80974545320382e-06 1.91857599076002e-05 -6.52403688737053e-06 -5.29918345015088e-06 9.00484093651544e-05 -1.71888664431986e-05 3.56018838280225e-05 -3.4972266022602e-05 -3.52863665889474e-06 1.07288032194055e-05 -1.71888664431986e-05 0.000112064591645476 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 950 0 0 0 0 0 2620 +1107 1140 0.999986034884629 0.000118483574546017 0.00528355915639321 0.00270104301655122 -0.000140216035093582 0.999991531572685 0.0041130429584955 0.00242119391120575 -0.00528302708492455 -0.00411372635909215 0.999977583188875 -0.0101987486060228 3.47333739249505e-05 -3.53028371135495e-05 -1.35701905568526e-05 5.24777177083715e-06 -4.79181673691286e-06 2.16104738893821e-05 -3.53028371135495e-05 0.000173916317770726 2.37131788490209e-05 -9.4531101105989e-06 3.29729463212595e-05 -9.19163616295541e-05 -1.35701905568526e-05 2.37131788490209e-05 2.2175647836235e-05 -1.18183163468048e-05 -7.2320069023182e-06 -1.0838403482377e-05 5.24777177083715e-06 -9.4531101105989e-06 -1.18183163468048e-05 2.88501858890587e-05 2.94375768502488e-06 2.3915250070971e-06 -4.79181673691286e-06 3.29729463212595e-05 -7.2320069023182e-06 2.94375768502488e-06 8.09845924969227e-05 -1.58172984055798e-05 2.16104738893821e-05 -9.19163616295541e-05 -1.0838403482377e-05 2.3915250070971e-06 -1.58172984055798e-05 8.28003661030365e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 993 0 0 0 0 0 2667 +1107 1111 0.999989711878063 0.000582965228422622 -0.00449847636112342 0.00409544995408118 -0.000586197790598995 0.999999570922456 -0.000717305411938584 -0.0103608489450194 0.00449805626681491 0.000719935029116993 0.999989624537862 0.00528719628892207 2.53297734184079e-05 -2.6775893453066e-05 -1.63276472808789e-05 7.63243261672681e-06 4.70936152424382e-06 1.45211380335095e-05 -2.6775893453066e-05 0.000124406440088908 1.84396746142562e-05 -1.06449972986255e-05 2.87003835673502e-06 -6.05756264416318e-05 -1.63276472808789e-05 1.84396746142562e-05 2.20240065774525e-05 -1.29125725010465e-05 -7.7241252612743e-06 -1.26978214739944e-05 7.63243261672681e-06 -1.06449972986255e-05 -1.29125725010465e-05 2.76717886171174e-05 6.40504867940041e-06 1.04964890855749e-05 4.70936152424382e-06 2.87003835673502e-06 -7.7241252612743e-06 6.40504867940041e-06 4.93939577292185e-05 -2.59768109476094e-08 1.45211380335095e-05 -6.05756264416318e-05 -1.26978214739944e-05 1.04964890855749e-05 -2.59768109476094e-08 5.22020143471163e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 756 0 0 0 0 0 2600 +1107 1109 0.999979580470757 -0.000491273570801102 0.00637160041175519 0.00354622530992638 0.000478635454984115 0.999997915576611 0.00198488048343453 -0.00473588747628745 -0.00637256224996498 -0.0019817902792474 0.999977731230881 -0.00314483379201845 2.18013090519596e-05 -1.58894911025455e-05 -1.31157960836646e-05 5.09792369652208e-06 -1.94121849933664e-07 1.12380626447796e-05 -1.58894911025455e-05 9.01635455199766e-05 1.45645596953839e-05 -9.7994966577451e-06 7.01805708876318e-06 -5.02151438069311e-05 -1.31157960836646e-05 1.45645596953839e-05 1.90559213053102e-05 -1.12920292739882e-05 -4.11933376648383e-06 -7.80629528366417e-06 5.09792369652208e-06 -9.7994966577451e-06 -1.12920292739882e-05 2.63002015463808e-05 7.57950101373305e-06 6.75043537175558e-06 -1.94121849933664e-07 7.01805708876318e-06 -4.11933376648383e-06 7.57950101373305e-06 3.84193010223301e-05 -5.94718915336188e-06 1.12380626447796e-05 -5.02151438069311e-05 -7.80629528366417e-06 6.75043537175558e-06 -5.94718915336188e-06 5.25054867249131e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 890 0 0 0 0 0 2587 +1107 1139 0.999976494459584 -0.000471955238302775 0.00684015983539998 -0.00266114097204492 0.000445803714885316 0.999992588145188 0.00382425335671459 0.0144033353247397 -0.00684191401353269 -0.00382111409690773 0.99996929317839 -0.014458619964922 4.22878857820698e-05 -4.18290742920954e-05 -1.84444497978125e-05 1.09328906885114e-05 2.07105106226821e-06 4.17623300560717e-05 -4.18290742920954e-05 0.000191089905746912 2.55041868625539e-05 -1.25844876313429e-05 2.61009079576624e-05 -9.7802867179988e-05 -1.84444497978125e-05 2.55041868625539e-05 2.54809782578114e-05 -1.54036413685477e-05 -1.11994890932945e-05 -1.46307676155468e-05 1.09328906885114e-05 -1.25844876313429e-05 -1.54036413685477e-05 3.33272566612987e-05 9.09553917325377e-06 1.06278404090825e-05 2.07105106226821e-06 2.61009079576624e-05 -1.11994890932945e-05 9.09553917325377e-06 7.13114365611906e-05 -7.44554416823902e-06 4.17623300560717e-05 -9.7802867179988e-05 -1.46307676155468e-05 1.06278404090825e-05 -7.44554416823902e-06 0.000120744202194076 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 979 0 0 0 0 0 2683 +1107 1136 0.999987592035269 -1.92000054050366e-06 -0.00498154311605756 0.0095923695990306 -1.85033034402175e-05 0.999991595837506 -0.00409974535612394 -0.0251415829092659 0.00498150912187305 0.00409978666163203 0.999979187941528 0.00577034504867558 2.75654953905946e-05 -2.21376704900943e-05 -1.39825125218192e-05 5.98995187865111e-06 4.8003364749183e-06 1.91839203890017e-05 -2.21376704900943e-05 0.000121226955299119 2.44932105189345e-05 -1.23506717430417e-05 -1.7069566636308e-05 -4.80329002765245e-05 -1.39825125218192e-05 2.44932105189345e-05 2.31413881932697e-05 -1.17261773782265e-05 -1.67688225390647e-05 -7.0638657547223e-06 5.98995187865111e-06 -1.23506717430417e-05 -1.17261773782265e-05 3.38011262244854e-05 -5.94081952343306e-06 5.18313446132585e-06 4.8003364749183e-06 -1.7069566636308e-05 -1.67688225390647e-05 -5.94081952343306e-06 9.33358725948051e-05 -5.04487397360242e-07 1.91839203890017e-05 -4.80329002765245e-05 -7.0638657547223e-06 5.18313446132585e-06 -5.04487397360242e-07 7.6604750851651e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 928 0 0 0 0 0 2684 +1107 1135 0.999999980448255 3.1733648942031e-05 0.000195183160279486 0.00889966590403679 -3.15933032602245e-05 0.999999741015282 -0.0007190071150592 -0.022403535249135 -0.000195205926449407 0.000719000934520582 0.999999722466113 -0.007787313439329 5.28626469465986e-05 6.92351856664286e-07 -1.2065735777799e-05 1.70091383227115e-05 -2.04741173665825e-05 4.38093827266194e-05 6.92351856664286e-07 0.000121273167306534 1.90457882132935e-05 -1.23462477984194e-05 2.73676003329092e-05 -4.31042911371282e-05 -1.2065735777799e-05 1.90457882132935e-05 2.794933161399e-05 -1.72624931990208e-05 -5.61742001640471e-06 -4.34531873670553e-06 1.70091383227115e-05 -1.23462477984194e-05 -1.72624931990208e-05 4.92421595549009e-05 -3.27275161767782e-05 2.44672004310422e-05 -2.04741173665825e-05 2.73676003329092e-05 -5.61742001640471e-06 -3.27275161767782e-05 0.000163817353356556 -6.40670588226107e-05 4.38093827266194e-05 -4.31042911371282e-05 -4.34531873670553e-06 2.44672004310422e-05 -6.40670588226107e-05 0.000133282966632362 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 994 0 0 0 0 0 2570 +1107 1110 0.999977599539843 -0.000586039003472935 0.00666760652860962 0.00539458311026015 0.000585534089295109 0.999999825557943 7.76782761237467e-05 -0.00830772638268383 -0.00666765088799815 -7.37724251781098e-05 0.999977768247507 -0.00108150096317659 2.81007176860989e-05 -2.99215672770949e-05 -1.55749759916331e-05 7.02796315519672e-06 2.916280216268e-06 2.02453027929545e-05 -2.99215672770949e-05 0.000140674837647597 2.60355147954602e-05 -1.62494030660235e-05 -1.08086074634936e-06 -8.05630425181819e-05 -1.55749759916331e-05 2.60355147954602e-05 2.45726921834659e-05 -1.34914381658185e-05 -1.21596583620694e-05 -1.44299348453125e-05 7.02796315519672e-06 -1.62494030660235e-05 -1.34914381658185e-05 2.92425583835541e-05 8.34365664697087e-06 1.15277798189785e-05 2.916280216268e-06 -1.08086074634936e-06 -1.21596583620694e-05 8.34365664697087e-06 5.99593487556852e-05 4.19557264911176e-06 2.02453027929545e-05 -8.05630425181819e-05 -1.44299348453125e-05 1.15277798189785e-05 4.19557264911176e-06 7.21367685760732e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 805 0 0 0 0 0 2606 +1107 1137 0.999978300793416 -1.92477859216055e-05 0.00658768334355205 0.00625912907357001 -3.6694872437561e-06 0.999993949032484 0.00347877635847561 -0.00992827679738963 -0.00658771044043675 -0.00347872504520874 0.999972249886572 -0.00970705967935328 2.9173465323156e-05 -1.27181187740784e-05 -1.22589686849534e-05 4.83832653366553e-06 5.40135160791461e-06 1.42527269616564e-05 -1.27181187740784e-05 0.00011246600666524 2.50214448271143e-05 -1.23915486358058e-05 -8.63588689475347e-06 -5.45458601377996e-05 -1.22589686849534e-05 2.50214448271143e-05 2.53120985196852e-05 -1.56653678603425e-05 -1.01797563601248e-05 -9.40365497377292e-06 4.83832653366553e-06 -1.23915486358058e-05 -1.56653678603425e-05 3.56556179242508e-05 -7.88553673432171e-06 4.22154220290825e-06 5.40135160791461e-06 -8.63588689475347e-06 -1.01797563601248e-05 -7.88553673432171e-06 8.54870648360951e-05 7.86480666042606e-06 1.42527269616564e-05 -5.45458601377996e-05 -9.40365497377292e-06 4.22154220290825e-06 7.86480666042606e-06 6.93301703825367e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1007 0 0 0 0 0 2626 +1107 1138 0.999999716417248 -0.000451182648572837 0.000602992240462224 -0.0043794604868793 0.000449950315136288 0.99999781333156 0.00204227246257071 0.0125830798342869 -0.000603912359816892 -0.00204200056686884 0.999997732759203 -0.00267672990223422 4.93353718754218e-05 -1.61556439547799e-05 -1.25474176378122e-05 6.3039489823121e-06 6.92143620778167e-06 5.24394844100389e-05 -1.61556439547799e-05 0.000140114491596747 2.16513175984255e-05 -4.70025528105727e-06 2.75316925242915e-07 -7.79650496968908e-05 -1.25474176378122e-05 2.16513175984255e-05 2.260448794994e-05 -1.16852523507997e-05 -1.04468191950044e-05 -1.0158785094584e-05 6.3039489823121e-06 -4.70025528105727e-06 -1.16852523507997e-05 2.92635621771874e-05 1.80199431093261e-06 4.27820278467073e-06 6.92143620778167e-06 2.75316925242915e-07 -1.04468191950044e-05 1.80199431093261e-06 7.19674507301162e-05 2.74012254694168e-06 5.24394844100389e-05 -7.79650496968908e-05 -1.0158785094584e-05 4.27820278467073e-06 2.74012254694168e-06 0.000146049051501235 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 982 0 0 0 0 0 2583 +1107 1134 0.999955030686717 -0.000333373154150213 0.0094776298021673 0.011451520450678 0.000303040832529456 0.999994828730379 0.00320166812059796 -0.0211304707341703 -0.00947864814098813 -0.00319865203495556 0.999949960675322 -0.0130588667230031 2.74661689482419e-05 -2.44633784659216e-05 -1.50038976242137e-05 8.33261285806146e-06 -7.66883294178469e-06 1.21870011576483e-05 -2.44633784659216e-05 0.000132508719720796 2.06425280282654e-05 -1.28742711769074e-05 1.61542315245087e-05 -5.8648480468924e-05 -1.50038976242137e-05 2.06425280282654e-05 2.09341771320378e-05 -1.33654824362304e-05 -4.97411890386629e-07 -9.46654560409696e-06 8.33261285806146e-06 -1.28742711769074e-05 -1.33654824362304e-05 4.10568796185941e-05 -3.21339902247967e-05 1.87801137192459e-06 -7.66883294178469e-06 1.61542315245087e-05 -4.97411890386629e-07 -3.21339902247967e-05 0.000128099362743467 -6.88061514647571e-06 1.21870011576483e-05 -5.8648480468924e-05 -9.46654560409696e-06 1.87801137192459e-06 -6.88061514647571e-06 7.3632665319714e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 914 0 0 0 0 0 2607 +1107 1133 0.999998914685957 0.000750260710238185 0.00126796521006228 0.0129022421338854 -0.000752959378294504 0.999997449755219 0.00212921000195255 -0.0291314519428195 -0.00126636451383231 -0.0021301624173873 0.999996929359782 -0.00784810125780292 2.64141116973411e-05 -2.02326410502014e-05 -1.6541721732446e-05 8.18263583728727e-06 6.50693189954323e-06 1.50847429412252e-05 -2.02326410502014e-05 0.000110689828803065 1.80123765348028e-05 -1.31523356263009e-05 -6.08081903584714e-06 -4.82299119962922e-05 -1.6541721732446e-05 1.80123765348028e-05 2.31191761102335e-05 -1.16865594673979e-05 -1.1176625887441e-05 -1.04983798749117e-05 8.18263583728727e-06 -1.31523356263009e-05 -1.16865594673979e-05 3.54353438285305e-05 -1.64563931255678e-05 2.80108503643088e-06 6.50693189954323e-06 -6.08081903584714e-06 -1.1176625887441e-05 -1.64563931255678e-05 0.000110520216015922 9.58529477540024e-06 1.50847429412252e-05 -4.82299119962922e-05 -1.04983798749117e-05 2.80108503643088e-06 9.58529477540024e-06 6.59601343463099e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 908 0 0 0 0 0 2578 +1108 1110 0.999999984573009 5.62340546130364e-05 0.000166408269611289 0.00615487258722232 -5.63783338542799e-05 0.999999622443029 0.000867142019995774 -0.00620508213911876 -0.000166359443870978 -0.000867151388439362 0.999999610186426 0.00255443586533692 2.92469228565938e-05 -3.44734748891855e-05 -1.48296135157286e-05 4.02901301227215e-06 2.84967190126298e-06 2.14403272930463e-05 -3.44734748891855e-05 0.000165997053013074 2.89502207356602e-05 -8.81680756304568e-06 -4.02400020155783e-06 -9.40004669659104e-05 -1.48296135157286e-05 2.89502207356602e-05 2.27368099626384e-05 -1.13659792170435e-05 -1.135297437569e-05 -1.54609340417528e-05 4.02901301227215e-06 -8.81680756304568e-06 -1.13659792170435e-05 2.84007172849674e-05 1.50765055911496e-05 7.86786407316088e-06 2.84967190126298e-06 -4.02400020155783e-06 -1.135297437569e-05 1.50765055911496e-05 4.71162121023272e-05 -6.05049830694764e-08 2.14403272930463e-05 -9.40004669659104e-05 -1.54609340417528e-05 7.86786407316088e-06 -6.05049830694764e-08 7.7782999091884e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 819 0 0 0 0 0 2546 +1108 1111 0.999972791514209 -0.000559723051185798 0.00735547016761449 0.00425901971877766 0.000548065223979822 0.999998590781494 0.00158683948038337 -0.00154120305007932 -0.00735634799278551 -0.00158276502747903 0.999971689098785 -0.00334687005478332 2.64309873655287e-05 -3.03317310210452e-05 -1.43969125939376e-05 5.87841102675559e-06 3.40652479380704e-06 1.64603806933659e-05 -3.03317310210452e-05 0.000150104116897688 2.6392804262033e-05 -1.37932852621819e-05 -2.09898667931438e-06 -7.7028097731989e-05 -1.43969125939376e-05 2.6392804262033e-05 2.46153829270761e-05 -1.41648530993975e-05 -1.1561592245136e-05 -1.23646344210454e-05 5.87841102675559e-06 -1.37932852621819e-05 -1.41648530993975e-05 3.15909590357275e-05 1.75603970018135e-05 7.2470934917146e-06 3.40652479380704e-06 -2.09898667931438e-06 -1.1561592245136e-05 1.75603970018135e-05 4.12454300058338e-05 -1.32334014408339e-06 1.64603806933659e-05 -7.7028097731989e-05 -1.23646344210454e-05 7.2470934917146e-06 -1.32334014408339e-06 5.81542484506478e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 755 0 0 0 0 0 2583 +1108 1140 0.99987756407433 0.000150844336269838 0.0156471756802826 0.00761212927913953 -0.000263621390825151 0.999974003928939 0.00720569011879019 0.00743254590929605 -0.0156456819776483 -0.00720893281366573 0.999851610951916 -0.0150946353045439 2.67616697443489e-05 -2.58420624302923e-05 -1.40769721332709e-05 3.10162205572471e-06 1.05799936795777e-06 1.86245739289285e-05 -2.58420624302923e-05 0.00013352693995204 2.373910772918e-05 -9.71271841176985e-07 -1.91524568811273e-06 -6.27069686821144e-05 -1.40769721332709e-05 2.373910772918e-05 2.40946966409164e-05 -1.26677762839175e-05 -7.45519460173186e-06 -1.01130223421704e-05 3.10162205572471e-06 -9.71271841176985e-07 -1.26677762839175e-05 3.53221648743672e-05 7.06511314140417e-06 -3.00930389310642e-06 1.05799936795777e-06 -1.91524568811273e-06 -7.45519460173186e-06 7.06511314140417e-06 5.68733130724266e-05 8.24466309749487e-06 1.86245739289285e-05 -6.27069686821144e-05 -1.01130223421704e-05 -3.00930389310642e-06 8.24466309749487e-06 6.72435915270668e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 994 0 0 0 0 0 2586 +1108 1136 0.999942304798865 -0.000457126441947805 0.0107321064544534 0.0139585312296376 0.00046206503408626 0.999999788505641 -0.000457694852719429 -0.0215470295807026 -0.0107318949602539 0.000462627377057538 0.999942304538853 -0.0027001954181003 2.7461835086097e-05 -6.54060683069825e-06 -9.80207835570496e-06 7.20043210678605e-08 7.53652227777438e-06 7.64094759062021e-06 -6.54060683069825e-06 0.000121661135253289 1.95421154962569e-05 -6.52289307558106e-06 -2.11718956139252e-06 -4.74775190405402e-05 -9.80207835570496e-06 1.95421154962569e-05 2.30282899108206e-05 -1.1960424186766e-05 -8.36643074631495e-06 -2.36771957514496e-06 7.20043210678605e-08 -6.52289307558106e-06 -1.1960424186766e-05 3.7643551907411e-05 -1.02102738181964e-05 3.69238810063501e-06 7.53652227777438e-06 -2.11718956139252e-06 -8.36643074631495e-06 -1.02102738181964e-05 9.09706368425845e-05 -5.04774177456004e-06 7.64094759062021e-06 -4.74775190405402e-05 -2.36771957514496e-06 3.69238810063501e-06 -5.04774177456004e-06 7.23385858992019e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 936 0 0 0 0 0 2576 +1108 1112 0.999993824876132 -0.00136833720673716 0.00323695271718031 0.00379093379221095 0.00137461214544401 0.999997179033016 -0.00193710285213236 -0.0090261960184434 -0.00323429297593772 0.00194154044480157 0.999992884859511 0.00436771487145353 2.75601261078557e-05 -1.96995575475264e-05 -1.30649079754936e-05 3.36914011216814e-06 7.74333063084094e-07 2.08368068989993e-05 -1.96995575475264e-05 0.000110403316418546 8.57941239771951e-06 4.97790877553963e-06 6.95656436459269e-06 -5.40338270251012e-05 -1.30649079754936e-05 8.57941239771951e-06 2.04903616696139e-05 -9.47287430911394e-06 -7.62842350124567e-06 -8.72427905574212e-06 3.36914011216814e-06 4.97790877553963e-06 -9.47287430911394e-06 2.80275946119241e-05 1.20487531562141e-05 2.21410462684904e-06 7.74333063084094e-07 6.95656436459269e-06 -7.62842350124567e-06 1.20487531562141e-05 5.0780489990536e-05 -6.30879019952475e-06 2.08368068989993e-05 -5.40338270251012e-05 -8.72427905574212e-06 2.21410462684904e-06 -6.30879019952475e-06 6.95939501129978e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2499 +1108 1134 0.999942382603632 0.000185480128313257 0.0107329898021493 0.0119043130741488 -0.000228435809790395 0.999991969384871 0.00400112269849224 -0.0164546398284793 -0.0107321614808875 -0.00400334396343673 0.99993439482151 -0.0141509012652067 2.4893310771265e-05 -2.01643110537426e-05 -1.40670063225314e-05 6.59811152124422e-06 -7.04656757982319e-07 1.28281429871266e-05 -2.01643110537426e-05 0.000103206356158837 1.55441312892504e-05 -8.14051485604563e-06 7.6396609127261e-06 -3.82826043775902e-05 -1.40670063225314e-05 1.55441312892504e-05 2.26834916194965e-05 -1.38558998813368e-05 -7.28217457619498e-06 -1.0248873702371e-05 6.59811152124422e-06 -8.14051485604563e-06 -1.38558998813368e-05 4.12235734787856e-05 -2.17856334715641e-05 8.58657743333071e-08 -7.04656757982319e-07 7.6396609127261e-06 -7.28217457619498e-06 -2.17856334715641e-05 0.0001278273725594 2.21277004835089e-06 1.28281429871266e-05 -3.82826043775902e-05 -1.0248873702371e-05 8.58657743333071e-08 2.21277004835089e-06 6.70028628442146e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 914 0 0 0 0 0 2563 +1108 1135 0.99999179758475 -0.000148466692391536 0.00404755739436844 0.00856314703753151 0.000133186416726314 0.999992865065566 0.00377519262275617 -0.0139965103921265 -0.00404808900567365 -0.00377462257739278 0.999984682482587 -0.0118811643054778 3.45645337253871e-05 -2.12785989793569e-05 -1.33447425281769e-05 7.69277406961146e-06 -4.93540851267157e-06 3.23893336021218e-05 -2.12785989793569e-05 0.000126985763186275 2.50281634520435e-05 -4.64193246844051e-06 -2.38097488776771e-06 -5.26104552138177e-05 -1.33447425281769e-05 2.50281634520435e-05 2.749444111968e-05 -1.40016568081803e-05 -1.33227875855977e-05 -7.10771467729129e-06 7.69277406961146e-06 -4.64193246844051e-06 -1.40016568081803e-05 4.93484672852352e-05 -3.55219883184684e-05 4.61697561993373e-06 -4.93540851267157e-06 -2.38097488776771e-06 -1.33227875855977e-05 -3.55219883184684e-05 0.000199602416181345 -9.54281921636107e-06 3.23893336021218e-05 -5.26104552138177e-05 -7.10771467729129e-06 4.61697561993373e-06 -9.54281921636107e-06 0.000102657008967031 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1005 0 0 0 0 0 2562 +1108 1139 0.999947039979004 0.000333520837417997 0.0102862044058826 0.00250181571241686 -0.000403572649379847 0.999976737429806 0.00680894473161577 0.013685530562522 -0.0102836941973818 -0.00681273536052397 0.999923913240684 -0.0166746142253088 3.78927223343957e-05 -2.65191124374286e-05 -1.29846100526062e-05 1.87064994370068e-06 7.2801391591563e-06 3.64232379137976e-05 -2.65191124374286e-05 0.000126215067656325 1.82143338436314e-05 -7.17853743623836e-07 -3.88114104021409e-06 -7.51631775811048e-05 -1.29846100526062e-05 1.82143338436314e-05 2.24448582246735e-05 -1.23329665880437e-05 -9.87230674150003e-06 -8.80745720786813e-06 1.87064994370068e-06 -7.17853743623836e-07 -1.23329665880437e-05 3.41046584084648e-05 6.20754834003407e-06 -2.46018305157869e-06 7.2801391591563e-06 -3.88114104021409e-06 -9.87230674150003e-06 6.20754834003407e-06 5.87805449180662e-05 6.55793625751955e-06 3.64232379137976e-05 -7.51631775811048e-05 -8.80745720786813e-06 -2.46018305157869e-06 6.55793625751955e-06 0.000118877508834517 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 997 0 0 0 0 0 2619 +1108 1144 0.999969085669337 -0.000650314332415765 0.00783612129177914 0.00174438284293855 0.000640843673511486 0.999999061349785 0.00121104043524345 0.0113301273792807 -0.00783690149335437 -0.00120598126798428 0.999968563797965 0.00585932956267244 2.78742494648579e-05 -9.0416902518529e-06 -8.72019947017879e-06 2.83508698461445e-06 -1.52633889502163e-06 8.44972657020608e-06 -9.0416902518529e-06 0.000113413170678168 1.96600395491007e-05 -2.77297197925945e-06 -1.49795449792821e-05 -3.56817783501936e-05 -8.72019947017879e-06 1.96600395491007e-05 2.23194087450316e-05 -9.25375192016378e-06 -1.39007214232582e-05 -3.43963910390448e-06 2.83508698461445e-06 -2.77297197925945e-06 -9.25375192016378e-06 3.81828866063536e-05 -1.70767152679318e-05 5.13550656794042e-06 -1.52633889502163e-06 -1.49795449792821e-05 -1.39007214232582e-05 -1.70767152679318e-05 0.00013338976240923 -1.12407883727939e-05 8.44972657020608e-06 -3.56817783501936e-05 -3.43963910390448e-06 5.13550656794042e-06 -1.12407883727939e-05 6.11658509565812e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 948 0 0 0 0 0 2596 +1109 1111 0.999986232159539 0.000140607116647321 -0.00524554296594812 0.00289504545184163 -0.000149214437687738 0.999998643201376 -0.00164052749376958 -0.006472223470276 0.00524530517896196 0.00164128761799281 0.999984896360207 0.00842893658248957 3.04915525699043e-05 -2.55173672065308e-05 -1.66928801708808e-05 6.83610501012199e-06 7.58052032598731e-07 2.22946098495392e-05 -2.55173672065308e-05 0.00014782161498321 2.40027077085998e-05 -1.2639945764016e-05 6.7411432826185e-06 -7.53976176698058e-05 -1.66928801708808e-05 2.40027077085998e-05 2.61855206054644e-05 -1.47548039997817e-05 -5.3359029062114e-06 -1.28935812414462e-05 6.83610501012199e-06 -1.2639945764016e-05 -1.47548039997817e-05 2.96386066976319e-05 4.70338689682915e-06 6.79929203922916e-06 7.58052032598731e-07 6.7411432826185e-06 -5.3359029062114e-06 4.70338689682915e-06 4.33157682398274e-05 -9.98354005187668e-07 2.22946098495392e-05 -7.53976176698058e-05 -1.28935812414462e-05 6.79929203922916e-06 -9.98354005187668e-07 7.23006581282827e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 784 0 0 0 0 0 2565 +1109 1140 0.999985027919055 0.000828897411754251 0.00540896171249612 0.00743351190029829 -0.000841439576830415 0.99999696194582 0.00231691142886132 0.000726866942482341 -0.00540702479789074 -0.00232142805433032 0.999982687377448 -0.00681134695522723 2.96092372220332e-05 -3.52189953076295e-05 -1.41305582410809e-05 3.54346028062587e-06 -8.30667796249375e-06 1.45207335833802e-05 -3.52189953076295e-05 0.000176993063583306 2.81327789346146e-05 -9.70770866906319e-06 2.53863957571841e-05 -8.48968165227934e-05 -1.41305582410809e-05 2.81327789346146e-05 2.66242298228134e-05 -1.40763634690592e-05 -1.20946020675556e-05 -1.28918948985711e-05 3.54346028062587e-06 -9.70770866906319e-06 -1.40763634690592e-05 3.19039332042816e-05 6.54608883381338e-06 9.86539272535179e-07 -8.30667796249375e-06 2.53863957571841e-05 -1.20946020675556e-05 6.54608883381338e-06 9.13295573974677e-05 -4.53586530971018e-06 1.45207335833802e-05 -8.48968165227934e-05 -1.28918948985711e-05 9.86539272535179e-07 -4.53586530971018e-06 7.72794983129165e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1029 0 0 0 0 0 2603 +1108 1137 0.999946117468023 0.000231654889137004 0.0103782704069417 0.0087574629249446 -0.000281193808620608 0.99998857380603 0.00477212609046974 -0.00393254437924134 -0.0103770463364705 -0.00477478726161569 0.999934757029646 -0.0113696261453518 2.66398134998296e-05 -2.3192159885574e-05 -1.26013385426578e-05 4.61688551847957e-06 5.53296357715573e-06 2.04564696791381e-05 -2.3192159885574e-05 0.000115243078061198 2.57924541608352e-05 -9.89018758862846e-06 -1.02692860247377e-05 -5.11562129505218e-05 -1.26013385426578e-05 2.57924541608352e-05 2.43154165065374e-05 -1.36929697939332e-05 -1.06091415441531e-05 -9.34068180303419e-06 4.61688551847957e-06 -9.89018758862846e-06 -1.36929697939332e-05 3.44074027335891e-05 2.10591335822498e-06 3.94530946664773e-06 5.53296357715573e-06 -1.02692860247377e-05 -1.06091415441531e-05 2.10591335822498e-06 7.3263931691292e-05 3.55597533739789e-06 2.04564696791381e-05 -5.11562129505218e-05 -9.34068180303419e-06 3.94530946664773e-06 3.55597533739789e-06 6.80820611409735e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1006 0 0 0 0 0 2594 +1108 1138 0.999996676001447 0.000349145193201593 0.0025546200679176 -0.00159003824189607 -0.00035259020344369 0.999999028997676 0.00134821506212153 0.0125206849775625 -0.00255414686456724 -0.00134911131466608 0.999995828107525 -0.00413243719722965 4.5018898127417e-05 -3.19600430554652e-05 -1.44919548727439e-05 5.51679939370226e-06 1.61151259831713e-06 5.11098029262252e-05 -3.19600430554652e-05 0.000135397191765088 2.5257416652725e-05 -6.16749733642665e-06 -7.08029167242345e-06 -8.30213671676873e-05 -1.44919548727439e-05 2.5257416652725e-05 2.47385260106569e-05 -1.41128277068315e-05 -1.35501677588342e-05 -1.17421468765596e-05 5.51679939370226e-06 -6.16749733642665e-06 -1.41128277068315e-05 3.19856561394137e-05 5.49800685524653e-06 -6.69010533172e-07 1.61151259831713e-06 -7.08029167242345e-06 -1.35501677588342e-05 5.49800685524653e-06 6.8214736445923e-05 -2.71049801273166e-06 5.11098029262252e-05 -8.30213671676873e-05 -1.17421468765596e-05 -6.69010533172e-07 -2.71049801273166e-06 0.00012537981155853 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 990 0 0 0 0 0 2565 +1109 1139 0.999909595131319 -0.000142634172503536 0.0134454906870442 0.000886278435917642 5.29972817048623e-05 0.99997777518069 0.00666680852924391 0.0198693285098861 -0.0134461427781609 -0.0066654932428367 0.999887379880464 -0.0200629512276666 2.66184892596715e-05 -2.18446399781827e-05 -1.39824652055195e-05 5.42534028454496e-06 -2.18038706556149e-06 1.69071039100109e-05 -2.18446399781827e-05 0.00014012686900927 2.47328538384901e-05 -1.5817775428515e-05 2.77486458849635e-05 -4.50629396613734e-05 -1.39824652055195e-05 2.47328538384901e-05 2.27565522481027e-05 -9.79099871063743e-06 -6.67700995899248e-06 -9.22325659520359e-06 5.42534028454496e-06 -1.5817775428515e-05 -9.79099871063743e-06 2.72854288871445e-05 6.10791562609638e-06 4.60734157527714e-06 -2.18038706556149e-06 2.77486458849635e-05 -6.67700995899248e-06 6.10791562609638e-06 6.8918122471335e-05 -1.41096095192799e-05 1.69071039100109e-05 -4.50629396613734e-05 -9.22325659520359e-06 4.60734157527714e-06 -1.41096095192799e-05 6.18597824889553e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1076 0 0 0 0 0 2682 +1109 1112 0.999978773945223 -0.000885357905681888 0.00645506006073451 0.00335098719539667 0.000892194210134043 0.999999044153132 -0.00105625863917735 -0.005874023279972 -0.00645411872374894 0.00106199538618587 0.999978608029842 -0.00095433345131259 4.25340270619179e-05 -2.9786205333303e-06 -1.25703492287351e-05 9.47315035865712e-06 5.02964183295815e-06 3.18500667898635e-05 -2.9786205333303e-06 8.18917501180849e-05 3.54180623769078e-06 3.1666684723013e-06 7.74381885216083e-06 -4.9459886641638e-05 -1.25703492287351e-05 3.54180623769078e-06 2.233693894653e-05 -1.24914965303109e-05 -8.91711498954687e-06 -4.14044575790646e-06 9.47315035865712e-06 3.1666684723013e-06 -1.24914965303109e-05 3.032843626111e-05 1.23217615935544e-05 6.40916529159871e-06 5.02964183295815e-06 7.74381885216083e-06 -8.91711498954687e-06 1.23217615935544e-05 4.01485951274032e-05 -8.77902822891577e-07 3.18500667898635e-05 -4.9459886641638e-05 -4.14044575790646e-06 6.40916529159871e-06 -8.77902822891577e-07 0.00010404232442373 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 856 0 0 0 0 0 2584 +1109 1138 0.999985354530538 -0.000441084780089464 0.00539408645193291 -0.00449672045166654 0.000410358017848205 0.999983692551152 0.00569615993985032 0.0219524105588626 -0.00539651097759844 -0.00569386301028935 0.999969228323196 -0.0104597646307856 2.86003138866288e-05 -7.04366175368844e-06 -1.00685346736505e-05 5.80078679021932e-06 -3.42553016077099e-06 1.13487760803957e-05 -7.04366175368844e-06 0.000118293764938319 1.96020862330876e-05 -6.04712269634828e-06 1.5013933773587e-05 -5.80662679635077e-05 -1.00685346736505e-05 1.96020862330876e-05 2.17743911129335e-05 -1.28162109084426e-05 -7.5206472260316e-06 -8.51206759803811e-06 5.80078679021932e-06 -6.04712269634828e-06 -1.28162109084426e-05 3.03206950402811e-05 -2.16851268082227e-06 2.73302509437937e-06 -3.42553016077099e-06 1.5013933773587e-05 -7.5206472260316e-06 -2.16851268082227e-06 8.16380023731921e-05 -5.76316648332289e-06 1.13487760803957e-05 -5.80662679635077e-05 -8.51206759803811e-06 2.73302509437937e-06 -5.76316648332289e-06 6.84013388345483e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1078 0 0 0 0 0 2553 +1109 1136 0.999979213757551 0.000276265469352413 0.00644171795571418 0.010444575400851 -0.000312310992858784 0.999984297394577 0.00559530393441674 -0.0158498266044294 -0.00644007101469126 -0.00559719944840305 0.999963597759269 -0.0133642286430573 4.8039257010796e-05 -2.56467305109274e-05 -1.41860164576001e-05 1.07986796806096e-05 -1.47406878501159e-05 5.83663655799461e-05 -2.56467305109274e-05 0.000118232462240991 1.58006053856491e-05 -5.78647870383025e-06 1.79924975943567e-05 -7.26343144288076e-05 -1.41860164576001e-05 1.58006053856491e-05 2.42797317878027e-05 -1.32522524170242e-05 -1.48667529813682e-05 -1.13920079892037e-05 1.07986796806096e-05 -5.78647870383025e-06 -1.32522524170242e-05 3.96696114080567e-05 -1.9227585013106e-05 1.99550197817092e-05 -1.47406878501159e-05 1.79924975943567e-05 -1.48667529813682e-05 -1.9227585013106e-05 0.000152830518292459 -4.59744835670286e-05 5.83663655799461e-05 -7.26343144288076e-05 -1.13920079892037e-05 1.99550197817092e-05 -4.59744835670286e-05 0.000157981170598956 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 998 0 0 0 0 0 2611 +1109 1135 0.999985989203973 0.000655024553576406 0.00525284100131773 0.00846863297131998 -0.0006799830561354 0.999988482498586 0.00475105180131181 -0.0110018759477054 -0.0052496684461289 -0.00475455707817158 0.999974917269526 -0.0142941709065257 2.7919484495789e-05 -7.12456202699725e-06 -1.27726896514725e-05 4.27372039118547e-06 -5.9870913096464e-06 1.1227096967237e-05 -7.12456202699725e-06 0.000104023324303693 2.08084795382303e-05 -8.0635967955595e-06 2.05980724759053e-05 -3.98112771004215e-05 -1.27726896514725e-05 2.08084795382303e-05 2.44521130241397e-05 -1.1748243193298e-05 -1.29595948829727e-06 -4.68527840752292e-06 4.27372039118547e-06 -8.0635967955595e-06 -1.1748243193298e-05 3.12929816707794e-05 -1.26439052087899e-05 -6.45662650192582e-07 -5.9870913096464e-06 2.05980724759053e-05 -1.29595948829727e-06 -1.26439052087899e-05 0.000105133385603347 -7.92477774304346e-06 1.1227096967237e-05 -3.98112771004215e-05 -4.68527840752292e-06 -6.45662650192582e-07 -7.92477774304346e-06 7.26915384909202e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1084 0 0 0 0 0 2566 +1109 1113 0.999930813397827 -0.00103166910308828 0.0117176822119775 0.00389283335246685 0.00100063320030655 0.999995976989926 0.00265419237482759 -0.00448159511640564 -0.0117203733198907 -0.00264228363842372 0.999927822988448 -0.00932404283365529 6.42629212867728e-05 -6.20923439532728e-05 -2.18079151107006e-05 5.16134280533095e-06 9.66916011427876e-06 7.85159105040927e-05 -6.20923439532728e-05 0.000197601669506331 3.13108656839787e-05 -1.41059140392261e-06 4.4001626387302e-06 -0.000133409847787553 -2.18079151107006e-05 3.13108656839787e-05 3.18204206080972e-05 -1.821547129409e-05 -1.1647045773211e-05 -2.03587992526432e-05 5.16134280533095e-06 -1.41059140392261e-06 -1.821547129409e-05 3.79791933547875e-05 1.11563524038974e-05 -9.49670294753685e-07 9.66916011427876e-06 4.4001626387302e-06 -1.1647045773211e-05 1.11563524038974e-05 5.51964135794546e-05 7.83755169914357e-06 7.85159105040927e-05 -0.000133409847787553 -2.03587992526432e-05 -9.49670294753685e-07 7.83755169914357e-06 0.000180654416473277 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 800 0 0 0 0 0 2638 +1110 1139 0.999999917353671 0.000388052466933327 -0.000121276269118517 -0.00116070439209029 -0.000387991654027921 0.999999799199157 0.000501062991723726 0.00967357531229259 0.000121470683496167 -0.000501015896132459 0.999999867113964 -0.00505770017160356 2.61297686816901e-05 -1.55469755362778e-05 -1.20619451403572e-05 5.27417077307402e-06 -6.71887422670978e-07 2.30338369613961e-05 -1.55469755362778e-05 9.81541930889106e-05 1.52097668398612e-05 -1.19949127733151e-05 1.14084095665745e-05 -4.06207642543565e-05 -1.20619451403572e-05 1.52097668398612e-05 1.94647301513719e-05 -1.04936005133242e-05 -7.37985475629087e-06 -5.53576044602529e-06 5.27417077307402e-06 -1.19949127733151e-05 -1.04936005133242e-05 2.46874193085698e-05 1.84231844581692e-06 1.11813510094494e-06 -6.71887422670978e-07 1.14084095665745e-05 -7.37985475629087e-06 1.84231844581692e-06 5.53750244840065e-05 -1.34183873950841e-05 2.30338369613961e-05 -4.06207642543565e-05 -5.53576044602529e-06 1.11813510094494e-06 -1.34183873950841e-05 7.46308711188148e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1122 0 0 0 0 0 2674 +1110 1138 0.999990391560241 -6.9967759543045e-05 0.00438313719940677 -0.00186877082619585 7.52024721644596e-05 0.999999284197583 -0.00119413102715353 0.0108895036660988 -0.00438305051127399 0.00119444917617073 0.99998968102645 -0.00254457654730838 2.35051472067742e-05 -8.53075514964188e-06 -1.11153646930566e-05 4.83580476512187e-06 6.64666986960019e-06 1.8596920072832e-05 -8.53075514964188e-06 9.68793255052562e-05 1.90532947693891e-05 -2.42506086466665e-06 -1.23238686267184e-05 -4.9090407851855e-05 -1.11153646930566e-05 1.90532947693891e-05 2.26882018616926e-05 -1.09563759094613e-05 -1.23277353473792e-05 -1.12168255492552e-05 4.83580476512187e-06 -2.42506086466665e-06 -1.09563759094613e-05 3.0020768397291e-05 -2.99374397125341e-06 1.45845093642413e-06 6.64666986960019e-06 -1.23238686267184e-05 -1.23277353473792e-05 -2.99374397125341e-06 7.26172332746414e-05 4.51546062234199e-06 1.8596920072832e-05 -4.9090407851855e-05 -1.12168255492552e-05 1.45845093642413e-06 4.51546062234199e-06 6.89823503421547e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1154 0 0 0 0 0 2611 +1110 1112 0.999983539234129 -0.000827459604494128 0.00567772589928681 0.000869749173548213 0.000826672865679654 0.999999648377933 0.000140911263435778 -0.00339923636604315 -0.0056778405012514 -0.000136215321988755 0.999983871656252 -0.0036847938707322 2.74970841999338e-05 -1.44127883315811e-05 -1.27507278914653e-05 3.67688089362361e-06 4.85704771690033e-06 6.51262439198071e-06 -1.44127883315811e-05 8.62315746095008e-05 1.62017136694122e-05 -7.94419783492078e-06 -4.58988899260875e-06 -4.40974040850082e-05 -1.27507278914653e-05 1.62017136694122e-05 2.31090964854734e-05 -1.13481010364431e-05 -8.17560695213413e-06 -9.20496060995661e-06 3.67688089362361e-06 -7.94419783492078e-06 -1.13481010364431e-05 2.38958021465205e-05 4.74164780803269e-06 2.24812264075016e-06 4.85704771690033e-06 -4.58988899260875e-06 -8.17560695213413e-06 4.74164780803269e-06 4.07400792276032e-05 1.16732503386339e-06 6.51262439198071e-06 -4.40974040850082e-05 -9.20496060995661e-06 2.24812264075016e-06 1.16732503386339e-06 4.91435634490318e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 944 0 0 0 0 0 2606 +1110 1136 0.999974419305836 0.00106589491571342 -0.00707280722096867 0.015558976351702 -0.0010693472177252 0.999999310952781 -0.000484345425027504 -0.0374050013791963 0.00707228608614454 0.000491896321858566 0.999974870088006 0.00362307745904201 2.44997432507793e-05 -1.67472665162943e-05 -1.63168420466726e-05 8.77284901277564e-06 6.02185694233317e-06 1.38868456383074e-05 -1.67472665162943e-05 0.000116708207932268 2.59002526564597e-05 -1.93326477556761e-05 7.31526402918048e-07 -5.47152461402444e-05 -1.63168420466726e-05 2.59002526564597e-05 2.94304873413904e-05 -1.85142809652436e-05 -1.23568613540971e-05 -1.16964213403942e-05 8.77284901277564e-06 -1.93326477556761e-05 -1.85142809652436e-05 4.18838702092341e-05 -2.39712474679458e-05 1.14676300054636e-05 6.02185694233317e-06 7.31526402918048e-07 -1.23568613540971e-05 -2.39712474679458e-05 0.000126789992754144 -1.66202705640072e-06 1.38868456383074e-05 -5.47152461402444e-05 -1.16964213403942e-05 1.14676300054636e-05 -1.66202705640072e-06 7.17175917754054e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1078 0 0 0 0 0 2688 +1110 1140 0.99997757846428 0.000131655971665622 0.00669516507787287 0.000469935094694571 -0.000144439654489324 0.999998167536078 0.00190894255346853 0.00646488420614033 -0.00669490148553768 -0.00190986679937548 0.999975765057788 -0.00934344643499488 4.92465039215443e-05 -3.20510066823386e-05 -1.46226548940025e-05 7.11286999906316e-06 -7.83500133003885e-06 5.12719579179226e-05 -3.20510066823386e-05 0.000160454937470704 2.97216588556259e-05 -2.18194113443135e-05 3.43057810395716e-05 -8.20779475753468e-05 -1.46226548940025e-05 2.97216588556259e-05 3.01788757240216e-05 -2.1153536652932e-05 -5.28840499953979e-06 -8.49763455924707e-06 7.11286999906316e-06 -2.18194113443135e-05 -2.1153536652932e-05 4.08973125734565e-05 -6.0094866629659e-06 2.40856830522989e-06 -7.83500133003885e-06 3.43057810395716e-05 -5.28840499953979e-06 -6.0094866629659e-06 8.31476853963718e-05 -1.89195149802255e-05 5.12719579179226e-05 -8.20779475753468e-05 -8.49763455924707e-06 2.40856830522989e-06 -1.89195149802255e-05 0.000131076964101676 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1013 0 0 0 0 0 2680 +1109 1144 0.999838344197852 -0.0006569987471023 0.0179681335798469 5.60672301921332e-05 0.000525240740872179 0.999972948791108 0.00733660740261376 0.0196569148329018 -0.0179724676619835 -0.00732598380166548 0.999811642444454 -0.0144903900795792 3.84835101279633e-05 -1.01118600346842e-05 -8.77285668250534e-06 2.00734775023828e-06 -1.46761214830917e-06 3.25735633442057e-05 -1.01118600346842e-05 0.000113650183417552 1.85537743498414e-05 -6.4641151007534e-06 -1.89114578041493e-08 -3.61448651612904e-05 -8.77285668250534e-06 1.85537743498414e-05 2.44742591153498e-05 -1.29362673276697e-05 -1.0953673177653e-05 -3.61681536242789e-07 2.00734775023828e-06 -6.4641151007534e-06 -1.29362673276697e-05 3.72842184813564e-05 4.2509490577724e-06 3.14076183407852e-06 -1.46761214830917e-06 -1.89114578041493e-08 -1.0953673177653e-05 4.2509490577724e-06 8.55783248137886e-05 -6.02276563180783e-06 3.25735633442057e-05 -3.61448651612904e-05 -3.61681536242789e-07 3.14076183407852e-06 -6.02276563180783e-06 0.00010774881675028 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1001 0 0 0 0 0 2671 +1109 1137 0.999990678306803 0.000463300544235921 0.00429286059697502 0.00899192231959594 -0.000471224329915182 0.999998187000401 0.00184497792449007 -0.0089261777076385 -0.00429199803474396 -0.00184698362653014 0.999989083642593 -0.00390177032452266 3.4179219873019e-05 -5.03678679863548e-05 -2.00065063114234e-05 5.2615944061119e-07 1.04603930514178e-05 2.74099082813413e-05 -5.03678679863548e-05 0.00027239043232903 4.51106833228063e-05 1.13352574341901e-05 -2.68837473606379e-05 -0.000143675032071312 -2.00065063114234e-05 4.51106833228063e-05 2.97301239419002e-05 -1.09868835170248e-05 -1.24834926173058e-05 -2.29567464529429e-05 5.2615944061119e-07 1.13352574341901e-05 -1.09868835170248e-05 3.7770306857348e-05 -1.25438744940431e-05 -3.93998739742293e-06 1.04603930514178e-05 -2.68837473606379e-05 -1.24834926173058e-05 -1.25438744940431e-05 0.00010052120419711 8.8346579175708e-06 2.74099082813413e-05 -0.000143675032071312 -2.29567464529429e-05 -3.93998739742293e-06 8.8346579175708e-06 0.000106878140015336 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1078 0 0 0 0 0 2569 +1110 1113 0.999979269489201 -0.000824916682611054 0.0063859301836657 0.00201924600327485 0.000809887738602783 0.999996897434515 0.00235567467919279 -0.00836530198999586 -0.0063878536062408 -0.00235045395829809 0.999976835077941 -0.00155220747376544 3.0997381445529e-05 -4.26773474238674e-05 -2.20850183339869e-05 8.69733417117767e-06 3.08612397557497e-06 3.11198900749197e-05 -4.26773474238674e-05 0.000157317758917068 3.80983763097025e-05 -2.04043881785297e-05 1.97452537565012e-06 -9.84696235702311e-05 -2.20850183339869e-05 3.80983763097025e-05 3.02076179523229e-05 -1.79616240814129e-05 -9.95905301829764e-06 -2.25581928895576e-05 8.69733417117767e-06 -2.04043881785297e-05 -1.79616240814129e-05 2.88624938770723e-05 6.94135577881496e-06 9.75722685201377e-06 3.08612397557497e-06 1.97452537565012e-06 -9.95905301829764e-06 6.94135577881496e-06 4.95203052154966e-05 -3.32738159963364e-06 3.11198900749197e-05 -9.84696235702311e-05 -2.25581928895576e-05 9.75722685201377e-06 -3.32738159963364e-06 8.8267051040068e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 897 0 0 0 0 0 2671 +1110 1144 0.999991170626584 -4.44624676681718e-05 0.00420198666868331 -0.00484650215927911 3.56003449832748e-05 0.99999777524856 0.00210908286828874 0.0216808692821239 -0.00420207109533626 -0.00210891465423351 0.999988947477666 -0.00211886344813936 2.32241278311911e-05 -2.72449565689588e-05 -1.34936443496255e-05 5.70704641333414e-06 -5.73910365241555e-06 1.29763215486643e-05 -2.72449565689588e-05 0.000144993090433905 3.33215666750382e-05 -1.69297860950361e-05 1.67165038276377e-05 -7.12554829807549e-05 -1.34936443496255e-05 3.33215666750382e-05 2.81675712348833e-05 -1.63288436679943e-05 -3.56618257085523e-06 -1.11512458857572e-05 5.70704641333414e-06 -1.69297860950361e-05 -1.63288436679943e-05 3.72351489179597e-05 -2.21619067671567e-05 5.69029777823403e-06 -5.73910365241555e-06 1.67165038276377e-05 -3.56618257085523e-06 -2.21619067671567e-05 0.000125858032223496 -1.39959225996067e-05 1.29763215486643e-05 -7.12554829807549e-05 -1.11512458857572e-05 5.69029777823403e-06 -1.39959225996067e-05 6.25551078559442e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1085 0 0 0 0 0 2679 +1110 1137 0.999998096795939 0.000930812327181362 0.00171464075283279 0.0108157199380618 -0.000926242413556644 0.999996022315885 -0.00266409973522845 -0.0232725781094522 -0.0017171137094079 0.00266250649191373 0.999994981277251 0.00162547359579184 3.98255587428609e-05 -1.29297135074689e-05 -1.08913307575442e-05 3.37009629121735e-06 1.21346891245641e-05 3.90010854279371e-05 -1.29297135074689e-05 0.000112077693281371 2.02632985769985e-05 -6.3401542935638e-06 -1.25344168932582e-05 -5.61625305397211e-05 -1.08913307575442e-05 2.02632985769985e-05 2.55569496221788e-05 -1.49879043793664e-05 -1.43802960084755e-05 -1.02544665733514e-05 3.37009629121735e-06 -6.3401542935638e-06 -1.49879043793664e-05 4.05390536499616e-05 -1.45692952839655e-05 4.43246598301664e-06 1.21346891245641e-05 -1.25344168932582e-05 -1.43802960084755e-05 -1.45692952839655e-05 0.000102123463229371 6.58751576747441e-06 3.90010854279371e-05 -5.61625305397211e-05 -1.02544665733514e-05 4.43246598301664e-06 6.58751576747441e-06 0.00010893431403996 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1144 0 0 0 0 0 2667 +1110 1145 0.999874225373299 0.00102525571096111 -0.0158266321393203 -0.000202238564816767 -0.00115668353593062 0.999964907828486 -0.00829730045045811 0.00664489463223068 0.0158175698937584 0.0083145632654161 0.99984032351189 0.00290049596576138 3.23570134231643e-05 -1.07121698162655e-05 -8.51452477675805e-06 4.21485275934293e-06 -3.12261567508757e-06 8.61982997796511e-06 -1.07121698162655e-05 9.49468458786073e-05 1.71564250972848e-05 -1.34961566177819e-05 7.48193474237351e-06 -4.96387137270844e-05 -8.51452477675805e-06 1.71564250972848e-05 2.19954288537259e-05 -8.83285473523749e-06 -1.02285949555611e-05 -6.04743111268961e-06 4.21485275934293e-06 -1.34961566177819e-05 -8.83285473523749e-06 2.76527335547782e-05 -1.03640298139538e-05 8.09247269939214e-06 -3.12261567508757e-06 7.48193474237351e-06 -1.02285949555611e-05 -1.03640298139538e-05 0.000108552479075612 -1.72175945077427e-05 8.61982997796511e-06 -4.96387137270844e-05 -6.04743111268961e-06 8.09247269939214e-06 -1.72175945077427e-05 6.85673633732883e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1104 0 0 0 0 0 2544 +1111 1139 0.99998189663906 0.00130312182586515 0.00587437380958777 0.00242528132398291 -0.0013384073267634 0.999981063576835 0.00600675899038944 0.00762505443236078 -0.00586643503121639 -0.00601451255281025 0.999964704666508 -0.0213211572578417 3.24867752005103e-05 -1.61632227926839e-05 -1.56936011694276e-05 9.03698246536646e-06 6.32977197635269e-06 2.58404335054177e-05 -1.61632227926839e-05 0.000128541093478151 2.07472153824927e-05 -2.63321363094818e-06 -2.48777351745462e-06 -6.05804899412959e-05 -1.56936011694276e-05 2.07472153824927e-05 2.67687135276767e-05 -1.53992839880617e-05 -1.4574752508567e-05 -1.13021079342442e-05 9.03698246536646e-06 -2.63321363094818e-06 -1.53992839880617e-05 3.15370130867181e-05 5.67484759002376e-06 -2.24658934980835e-07 6.32977197635269e-06 -2.48777351745462e-06 -1.4574752508567e-05 5.67484759002376e-06 7.0303885519096e-05 9.0743361695386e-07 2.58404335054177e-05 -6.05804899412959e-05 -1.13021079342442e-05 -2.24658934980835e-07 9.0743361695386e-07 0.000108254945746827 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1082 0 0 0 0 0 2618 +1110 1114 0.999999796527647 -5.80127370910533e-05 -0.000635278826648103 0.00218932022398535 5.71561928835566e-05 0.999999089501888 -0.00134823164378602 -0.0105141151150064 0.000635356462835819 0.001348195059339 0.999998889345507 0.00374982030404664 5.29619266612431e-05 -2.1403848664171e-06 -9.48923940128993e-06 8.5712871230963e-06 -5.26018152017905e-06 4.56315462517712e-05 -2.1403848664171e-06 0.000112879152913704 1.61355078321599e-05 -1.2470052424669e-05 2.0459609990882e-05 -6.6543054624961e-05 -9.48923940128993e-06 1.61355078321599e-05 2.40400288852058e-05 -1.60572365594567e-05 -5.56579019319046e-06 -6.49898644657311e-06 8.5712871230963e-06 -1.2470052424669e-05 -1.60572365594567e-05 3.25196372315671e-05 9.08340564547328e-07 9.43750373125053e-06 -5.26018152017905e-06 2.0459609990882e-05 -5.56579019319046e-06 9.08340564547328e-07 5.64312269980234e-05 -2.1861162172315e-05 4.56315462517712e-05 -6.6543054624961e-05 -6.49898644657311e-06 9.43750373125053e-06 -2.1861162172315e-05 0.000120950196866276 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1008 0 0 0 0 0 2636 +1110 1146 0.999322528722857 0.00430364289025387 -0.0365508172935785 -0.0027891203727 -0.00406813765165693 0.999970501054188 0.00651515751799153 0.0129434522685028 0.0365777779943309 -0.00636204992987619 0.999310557573414 -0.0152078013274577 2.23131922766131e-05 8.89413266225803e-06 -5.22881971904756e-06 1.81336165225015e-06 1.7435122608887e-06 -1.86182174960843e-06 8.89413266225803e-06 5.0552317037651e-05 2.87355877012618e-06 -3.10766498809192e-06 2.74990496494456e-06 -1.98601914749873e-05 -5.22881971904756e-06 2.87355877012618e-06 1.55015749421397e-05 -3.11197634474576e-06 -3.82448183375785e-06 -2.96146659334171e-06 1.81336165225015e-06 -3.10766498809192e-06 -3.11197634474576e-06 3.2373747652044e-05 -3.39077508917219e-05 2.41326297769714e-06 1.7435122608887e-06 2.74990496494456e-06 -3.82448183375785e-06 -3.39077508917219e-05 0.000145113566428301 -1.42294422840276e-06 -1.86182174960843e-06 -1.98601914749873e-05 -2.96146659334171e-06 2.41326297769714e-06 -1.42294422840276e-06 4.43510000929966e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1122 0 0 0 0 0 2543 +1111 1137 0.999977211662036 -0.000228862969992683 0.00674713112078488 0.0135058993712404 0.000194950692450953 0.999987348535209 0.0050264066438127 -0.0265470416390913 -0.00674819611804596 -0.0050249767424753 0.999964605102546 -0.00798113337347063 2.40642895494204e-05 -1.59716414789707e-05 -1.0943129930548e-05 3.33387792823223e-06 6.39348636935657e-08 1.52047393832652e-05 -1.59716414789707e-05 0.000109584316385579 1.89257874147017e-05 3.69555228263001e-06 -2.62056661149587e-05 -4.71489572884919e-05 -1.0943129930548e-05 1.89257874147017e-05 2.27018275211828e-05 -9.35780188390657e-06 -1.49104325602359e-05 -5.82671297790864e-06 3.33387792823223e-06 3.69555228263001e-06 -9.35780188390657e-06 4.27552434581087e-05 -3.80087902054042e-05 -1.77844571480064e-06 6.39348636935657e-08 -2.62056661149587e-05 -1.49104325602359e-05 -3.80087902054042e-05 0.000157758399034499 2.3418879930485e-06 1.52047393832652e-05 -4.71489572884919e-05 -5.82671297790864e-06 -1.77844571480064e-06 2.3418879930485e-06 6.32694622218795e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1143 0 0 0 0 0 2624 +1111 1113 0.999996636404935 -0.000354006824255856 -0.0025694080999086 0.000713556064716479 0.000346151293809101 0.999995267050955 -0.0030571318209658 -0.00543684814935147 0.00257047818455826 0.00305623213407419 0.999992026011731 0.00812012692984106 3.26650156516547e-05 -1.68495539795946e-05 -1.58160232351412e-05 4.74992496475273e-06 3.13640174331071e-06 2.09733719571099e-05 -1.68495539795946e-05 0.000130148151816151 2.37916678404589e-05 -9.15693693424012e-06 4.46846209490799e-06 -8.15801235055161e-05 -1.58160232351412e-05 2.37916678404589e-05 2.78882658330162e-05 -1.66563663905878e-05 -1.06793501869371e-05 -1.33900011403525e-05 4.74992496475273e-06 -9.15693693424012e-06 -1.66563663905878e-05 3.02558369776103e-05 9.94330771306626e-06 1.7342369662445e-06 3.13640174331071e-06 4.46846209490799e-06 -1.06793501869371e-05 9.94330771306626e-06 5.18212243807187e-05 -3.15910337573525e-07 2.09733719571099e-05 -8.15801235055161e-05 -1.33900011403525e-05 1.7342369662445e-06 -3.15910337573525e-07 9.00099551303256e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 890 0 0 0 0 0 2678 +1111 1138 0.999999236724291 0.000940934434961068 -0.00080074541782326 0.00215907593544982 -0.000939150826829272 0.999997083896325 0.00222490327236306 0.00269442963109152 0.000802836570870028 -0.00222414955342721 0.999997204302194 -0.00520763445698898 4.81908434615245e-05 -3.08497874134466e-05 -1.34805973707872e-05 5.79693443845325e-06 -4.14461361612653e-06 6.00586613992315e-05 -3.08497874134466e-05 0.000135349882124502 2.12460102227638e-05 -5.96450103611851e-06 1.12869819004297e-05 -9.30620071257181e-05 -1.34805973707872e-05 2.12460102227638e-05 2.4889640529552e-05 -1.4156284074411e-05 -9.62662263053167e-06 -1.41028457754353e-05 5.79693443845325e-06 -5.96450103611851e-06 -1.4156284074411e-05 3.6097880206691e-05 -3.94254972311102e-06 -1.04153910236487e-06 -4.14461361612653e-06 1.12869819004297e-05 -9.62662263053167e-06 -3.94254972311102e-06 8.01983284152583e-05 -1.0966623715635e-05 6.00586613992315e-05 -9.30620071257181e-05 -1.41028457754353e-05 -1.04153910236487e-06 -1.0966623715635e-05 0.000161010232737789 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1148 0 0 0 0 0 2531 +1111 1140 0.999988022373727 0.000715913357459768 0.00484175351984481 0.0037866245652678 -0.000739442424791994 0.999987918809608 0.00485957402753985 0.00521218748013278 -0.00483821599174082 -0.00486309601934126 0.999976470704748 -0.0106667413503928 2.83054153932177e-05 -1.26456256836266e-05 -1.16946016928717e-05 -1.4679262361464e-06 5.79159222237774e-06 1.40262953368927e-05 -1.26456256836266e-05 0.000104382701263174 1.65213899535031e-05 2.41817918364649e-06 -1.53730351774768e-05 -4.59440394888725e-05 -1.16946016928717e-05 1.65213899535031e-05 2.39233592052511e-05 -1.21218372386929e-05 -1.09043825326613e-05 -3.96001004974433e-06 -1.4679262361464e-06 2.41817918364649e-06 -1.21218372386929e-05 3.71633414817669e-05 -7.09831199509572e-06 -1.33945065396596e-05 5.79159222237774e-06 -1.53730351774768e-05 -1.09043825326613e-05 -7.09831199509572e-06 9.16114370647431e-05 9.62597122899456e-06 1.40262953368927e-05 -4.59440394888725e-05 -3.96001004974433e-06 -1.33945065396596e-05 9.62597122899456e-06 6.6267305511104e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1004 0 0 0 0 0 2594 +1111 1145 0.999914439585744 0.000713951487867993 -0.0130615382402324 0.00138282571508238 -0.000745764953308353 0.999996767149568 -0.00243095146960482 0.00439122741833177 0.0130597604328142 0.00244048431384591 0.999911739451913 0.000908808132154148 3.32668345190724e-05 -2.13463550532656e-05 -1.16224402003869e-05 5.08186417692509e-06 -8.13415224624826e-06 2.84241556507132e-05 -2.13463550532656e-05 0.000110951791905119 1.69109221585395e-05 -6.52686162422261e-06 1.56855970960362e-06 -6.65909626602309e-05 -1.16224402003869e-05 1.69109221585395e-05 2.01348680674518e-05 -8.1214637840509e-06 -5.00885590550508e-06 -1.0888825946997e-05 5.08186417692509e-06 -6.52686162422261e-06 -8.1214637840509e-06 3.4082553409027e-05 -1.83388488754338e-05 1.56986509383986e-05 -8.13415224624826e-06 1.56855970960362e-06 -5.00885590550508e-06 -1.83388488754338e-05 0.000106824374257299 -3.01856884470396e-05 2.84241556507132e-05 -6.65909626602309e-05 -1.0888825946997e-05 1.56986509383986e-05 -3.01856884470396e-05 9.92193137899091e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1120 0 0 0 0 0 2683 +1111 1146 0.999375504623796 0.00463165503483134 -0.0350306798331355 -0.00256991409336688 -0.00446870549606499 0.999978835805472 0.00472848943346594 0.0203011451275201 0.0350518391689047 -0.00456899472217709 0.999375051148519 -0.0130338114362402 2.86577961468515e-05 9.72241240844112e-06 -6.45054639773623e-06 3.92842363710934e-06 -4.78239092656578e-06 1.47185216485631e-05 9.72241240844112e-06 5.43776083170759e-05 -1.2321401446778e-06 -2.43353760730786e-06 9.67489065196549e-06 -2.32110977073812e-05 -6.45054639773623e-06 -1.2321401446778e-06 1.44149677154753e-05 -3.53812953038694e-06 -9.18125611881133e-07 -3.31107974384551e-06 3.92842363710934e-06 -2.43353760730786e-06 -3.53812953038694e-06 3.22520540431185e-05 -2.0513328500891e-05 1.15048953492176e-05 -4.78239092656578e-06 9.67489065196549e-06 -9.18125611881133e-07 -2.0513328500891e-05 0.000100209950791335 -1.28417344205217e-05 1.47185216485631e-05 -2.32110977073812e-05 -3.31107974384551e-06 1.15048953492176e-05 -1.28417344205217e-05 6.69207312773514e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1133 0 0 0 0 0 2567 +1111 1115 0.999998970417841 -0.000177919870672463 -0.00142390581765651 0.00457562777186594 0.000179450470571464 0.99999940622044 0.00107487501364283 -0.0166379512531864 0.00142371373054692 -0.00107512942753972 0.999998408566697 0.00121452935238258 2.76753226919558e-05 -1.0026021655358e-05 -1.37777077097366e-05 8.47898424958605e-06 7.72727818672035e-06 1.44265552895375e-05 -1.0026021655358e-05 7.66167434329481e-05 1.16994864829751e-05 -8.48197469977604e-06 5.64417331038087e-06 -3.55062469223659e-05 -1.37777077097366e-05 1.16994864829751e-05 2.2544802045629e-05 -1.35097465684488e-05 -1.1979963859902e-05 -9.57417695435399e-06 8.47898424958605e-06 -8.48197469977604e-06 -1.35097465684488e-05 2.85253807993853e-05 5.63254784409649e-06 6.82981320273444e-06 7.72727818672035e-06 5.64417331038087e-06 -1.1979963859902e-05 5.63254784409649e-06 5.63174748676035e-05 -3.73698373397332e-06 1.44265552895375e-05 -3.55062469223659e-05 -9.57417695435399e-06 6.82981320273444e-06 -3.73698373397332e-06 5.3526420098657e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 981 0 0 0 0 0 2656 +1111 1114 0.999999061694606 -0.00016878424369564 0.00135945643098277 0.00320595931893158 0.000166699809378023 0.99999881067324 0.00153325251609775 -0.0070096553725173 -0.00135971360301118 -0.00153302445631074 0.999997900505263 -0.00168754187948007 2.84423844418511e-05 -2.20259593600417e-05 -1.4651137998525e-05 5.08750599694546e-06 -9.93888520932521e-07 1.98468294020827e-05 -2.20259593600417e-05 0.000132128519789631 3.06336235554348e-05 -2.18507639012677e-05 2.46848621948489e-05 -6.06713500720675e-05 -1.4651137998525e-05 3.06336235554348e-05 2.84602905036718e-05 -1.69102098562904e-05 -6.95637722104018e-06 -1.3145694581828e-05 5.08750599694546e-06 -2.18507639012677e-05 -1.69102098562904e-05 3.02518385866271e-05 4.61724700422808e-06 1.06088721089183e-05 -9.93888520932521e-07 2.46848621948489e-05 -6.95637722104018e-06 4.61724700422808e-06 6.28927412054438e-05 -1.22358728777374e-05 1.98468294020827e-05 -6.06713500720675e-05 -1.3145694581828e-05 1.06088721089183e-05 -1.22358728777374e-05 6.47595904373955e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1008 0 0 0 0 0 2583 +1112 1139 0.999986427599947 0.00161588507002161 -0.00495313348669725 0.00184357779546879 -0.00161179224155722 0.999998356452697 0.000830191348766882 0.0086525299433705 0.0049544668397938 -0.00082219665895252 0.999987388545969 -0.00884507751034858 2.83448433827321e-05 -8.4439779857611e-06 -1.2446557774929e-05 3.27201368389398e-06 5.96064815093996e-06 2.0481840245605e-05 -8.4439779857611e-06 9.89149318510526e-05 1.91567737096161e-05 -1.13820779641815e-06 -5.01743094153217e-06 -3.780974129209e-05 -1.2446557774929e-05 1.91567737096161e-05 2.53202510512105e-05 -1.04952606548395e-05 -1.19047799167213e-05 -5.62501845378134e-06 3.27201368389398e-06 -1.13820779641815e-06 -1.04952606548395e-05 2.99199370462136e-05 6.74085751368871e-06 -7.9822843994611e-06 5.96064815093996e-06 -5.01743094153217e-06 -1.19047799167213e-05 6.74085751368871e-06 5.52411131921534e-05 -1.70727396000939e-06 2.0481840245605e-05 -3.780974129209e-05 -5.62501845378134e-06 -7.9822843994611e-06 -1.70727396000939e-06 8.75879107092084e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1119 0 0 0 0 0 2589 +1111 1144 0.999982743756892 -0.000819353297664149 0.00581728876818183 -0.00301182590705867 0.000820969055367812 0.999999625090931 -0.000275368493619003 0.0182054691402976 -0.00581706096314419 0.000280139555858149 0.999983041517995 0.00484413090653778 4.11258308040105e-05 -1.4453787424085e-05 -1.32119553527168e-05 5.80908852281502e-06 -6.73710843545823e-06 2.01504912185791e-05 -1.4453787424085e-05 0.000123506479846077 2.68016053069478e-05 -1.56815144773852e-05 7.23858518611314e-06 -6.11827615420131e-05 -1.32119553527168e-05 2.68016053069478e-05 2.79288901778718e-05 -1.40595618025922e-05 -8.59897917106461e-06 -1.14869925914035e-05 5.80908852281502e-06 -1.56815144773852e-05 -1.40595618025922e-05 3.88773222462753e-05 -1.70119172035167e-05 7.23810503516034e-06 -6.73710843545823e-06 7.23858518611314e-06 -8.59897917106461e-06 -1.70119172035167e-05 0.000116574794512472 -1.05418215587031e-05 2.01504912185791e-05 -6.11827615420131e-05 -1.14869925914035e-05 7.23810503516034e-06 -1.05418215587031e-05 7.5285708322646e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1100 0 0 0 0 0 2670 +1112 1138 0.999998451338483 0.000391861583073184 0.00171574040431727 0.0036746570815439 -0.00039076101939445 0.99999971773814 -0.000641739405878165 0.00523819111868734 -0.00171599139304871 0.000641067967571636 0.999998322201292 -0.00327557990783111 2.42525500545566e-05 -8.98379473322089e-06 -9.86861427803969e-06 3.32234439401076e-06 1.81896786640705e-06 1.73682404419521e-05 -8.98379473322089e-06 7.49632806506987e-05 1.56852526219403e-05 -6.72445633712801e-06 -9.82209754294998e-06 -2.6208210759398e-05 -9.86861427803969e-06 1.56852526219403e-05 2.17546515991197e-05 -1.09486650314613e-05 -9.30681423221011e-06 -3.80052273593722e-06 3.32234439401076e-06 -6.72445633712801e-06 -1.09486650314613e-05 2.96175756911626e-05 -3.12040711229243e-06 -4.06820170086517e-06 1.81896786640705e-06 -9.82209754294998e-06 -9.30681423221011e-06 -3.12040711229243e-06 7.46463106692188e-05 -3.56818507630874e-06 1.73682404419521e-05 -2.6208210759398e-05 -3.80052273593722e-06 -4.06820170086517e-06 -3.56818507630874e-06 6.71573297287008e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1203 0 0 0 0 0 2488 +1112 1116 0.999999861109702 -0.000388206333390163 -0.00035647779548591 0.00574345314482988 0.00038833635058051 0.999999858083237 0.000364730563384552 -0.0123946407870645 0.000356336154181048 -0.000364868946013177 0.99999986994759 0.000676916129786331 2.77009153576229e-05 -1.92936761355828e-06 -3.79628214862961e-06 -1.55762716002715e-06 -3.20545562910542e-06 4.61862237446393e-06 -1.92936761355828e-06 9.68342768267129e-05 2.36074410285471e-05 -1.67241908019507e-05 6.62920984480025e-06 -5.20456593246365e-05 -3.79628214862961e-06 2.36074410285471e-05 2.59093346066419e-05 -1.39417085689753e-05 -9.38741700595932e-07 -4.23774417969665e-06 -1.55762716002715e-06 -1.67241908019507e-05 -1.39417085689753e-05 2.9467118903695e-05 6.39516167500835e-08 -1.2079976197206e-06 -3.20545562910542e-06 6.62920984480025e-06 -9.38741700595932e-07 6.39516167500835e-08 5.02373039938324e-05 -1.55946062847341e-05 4.61862237446393e-06 -5.20456593246365e-05 -4.23774417969665e-06 -1.2079976197206e-06 -1.55946062847341e-05 7.14917063267454e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 984 0 0 0 0 0 2682 +1112 1143 0.999972287174874 0.000144968097628118 0.00744337735857105 -0.00137579891484756 -0.000187803591300485 0.999983425264897 0.00575447002734301 0.0221778648743167 -0.00744241977199033 -0.00575570844772079 0.999955740124633 -0.0128754738189858 2.80923470538679e-05 -1.05072136907743e-05 -1.20240685467184e-05 4.19036897635657e-06 -4.77679687102647e-06 1.31827408850516e-05 -1.05072136907743e-05 0.000136390842882931 1.7975967655124e-05 1.40542652100588e-05 -3.67827841710441e-05 -5.04670743490289e-05 -1.20240685467184e-05 1.7975967655124e-05 2.01029377453449e-05 -4.6038235172778e-06 -8.9146134236481e-06 -8.40531175712143e-06 4.19036897635657e-06 1.40542652100588e-05 -4.6038235172778e-06 5.07696051550844e-05 -7.04744841744132e-05 6.42889028380096e-06 -4.77679687102647e-06 -3.67827841710441e-05 -8.9146134236481e-06 -7.04744841744132e-05 0.000268062077517714 -1.14126082794092e-05 1.31827408850516e-05 -5.04670743490289e-05 -8.40531175712143e-06 6.42889028380096e-06 -1.14126082794092e-05 6.31572566718188e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1091 0 0 0 0 0 2634 +1112 1144 0.999978688338045 -0.000642313194434009 0.00649694570418559 -8.84777822366225e-05 0.000612728730247121 0.999989440210074 0.00455456165240747 0.0145128586231324 -0.006499802552848 -0.00455048372183738 0.999968522336914 -0.00271444477008441 2.81026126865779e-05 -2.49719956781362e-05 -1.10827434875069e-05 3.57047341133599e-07 3.88783931089593e-07 1.29628531484705e-05 -2.49719956781362e-05 0.000134378200700378 2.4843986654235e-05 -1.72361861748791e-06 -1.14102805510943e-05 -6.78705129299936e-05 -1.10827434875069e-05 2.4843986654235e-05 2.4172263544075e-05 -9.86354428544046e-06 -1.12160093582442e-05 -7.90285682447647e-06 3.57047341133599e-07 -1.72361861748791e-06 -9.86354428544046e-06 2.8028067467207e-05 1.79528960728508e-06 -1.73668386774926e-06 3.88783931089593e-07 -1.14102805510943e-05 -1.12160093582442e-05 1.79528960728508e-06 7.01928057500186e-05 -1.3189082640945e-06 1.29628531484705e-05 -6.78705129299936e-05 -7.90285682447647e-06 -1.73668386774926e-06 -1.3189082640945e-06 6.88150179014374e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1139 0 0 0 0 0 2724 +1112 1145 0.999905450187079 0.00179480689985487 -0.0136333911543565 0.00404653364607553 -0.00185670982752212 0.999988019242128 -0.0045292384373182 0.00249271613549518 0.0136250987075998 0.00455412345001002 0.999896802997594 0.00224193606809456 2.73572117324071e-05 -2.18423688693064e-05 -1.10502759298905e-05 4.69596483449731e-06 -2.53735911041412e-06 2.10541375360941e-05 -2.18423688693064e-05 0.000118079810483315 2.28024453129739e-05 -9.61617622188734e-06 -9.65971794547891e-06 -5.8021153597678e-05 -1.10502759298905e-05 2.28024453129739e-05 2.2785690643615e-05 -1.31071307728405e-05 -6.25624277032109e-06 -8.94035492937986e-06 4.69596483449731e-06 -9.61617622188734e-06 -1.31071307728405e-05 3.88869290230092e-05 -1.00412892291969e-05 5.18661445447111e-06 -2.53735911041412e-06 -9.65971794547891e-06 -6.25624277032109e-06 -1.00412892291969e-05 8.90410055115963e-05 -1.76478682396409e-05 2.10541375360941e-05 -5.8021153597678e-05 -8.94035492937986e-06 5.18661445447111e-06 -1.76478682396409e-05 7.67096505622327e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1150 0 0 0 0 0 2672 +1112 1114 0.999999449938318 -0.00103814119275673 0.000149619268226878 0.00105382250151338 0.00103843211044745 0.999997544717811 -0.00195760493990876 -0.00632838650077854 -0.00014758663054209 0.00195775923255776 0.99999807269663 0.00504010460591825 3.95772516107776e-05 1.58201501011355e-06 -1.07213228522463e-05 5.78185832312311e-06 4.82686198077957e-06 3.17278529193308e-05 1.58201501011355e-06 8.31052560490647e-05 1.53739699494518e-05 -8.14641608024574e-06 4.39872269722343e-06 -4.29094254277944e-05 -1.07213228522463e-05 1.53739699494518e-05 2.20832703486691e-05 -1.31279893735948e-05 -7.54658553528492e-06 -6.31233515166776e-06 5.78185832312311e-06 -8.14641608024574e-06 -1.31279893735948e-05 2.78999938156329e-05 6.64857665959862e-06 6.22741159636776e-06 4.82686198077957e-06 4.39872269722343e-06 -7.54658553528492e-06 6.64857665959862e-06 4.8642983169976e-05 9.41417064594787e-07 3.17278529193308e-05 -4.29094254277944e-05 -6.31233515166776e-06 6.22741159636776e-06 9.41417064594787e-07 0.000103157268506942 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1070 0 0 0 0 0 2517 +1112 1140 0.999994380701593 0.00077371660539252 0.00326189022679118 0.0020358208610002 -0.000788376173183217 0.99998958528788 0.00449530630583354 0.00727849996571705 -0.00325837816200835 -0.00449785264190032 0.999984576027733 -0.012790538572141 3.58809796585487e-05 -2.1589057302836e-05 -1.42257695481168e-05 1.91072484775576e-06 3.09343699958401e-06 2.96780604806585e-05 -2.1589057302836e-05 0.00011836249125752 2.51451019196685e-05 -5.80493438595225e-06 -1.07183461461258e-05 -4.58314061437458e-05 -1.42257695481168e-05 2.51451019196685e-05 2.30451574901176e-05 -1.07587909981413e-05 -8.85385210594165e-06 -6.72703578699136e-06 1.91072484775576e-06 -5.80493438595225e-06 -1.07587909981413e-05 3.7362649885836e-05 -1.23649312951522e-05 -7.38452179608849e-06 3.09343699958401e-06 -1.07183461461258e-05 -8.85385210594165e-06 -1.23649312951522e-05 0.000110706211406498 5.0068982041645e-06 2.96780604806585e-05 -4.58314061437458e-05 -6.72703578699136e-06 -7.38452179608849e-06 5.0068982041645e-06 8.04070721974958e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1033 0 0 0 0 0 2530 +1112 1146 0.999412783072381 0.00380018359089833 -0.0340535994601717 -0.00252701640204711 -0.00356101552625131 0.999968587512329 0.00708118330649244 0.01841393609406 0.0340794395485039 -0.00695575971938487 0.999394921543424 -0.0186989030900257 2.34707620051465e-05 8.15502908945481e-06 -7.17450452130441e-06 2.04282082801469e-06 1.1642079736979e-06 1.28123041738245e-06 8.15502908945481e-06 5.9826574331186e-05 2.38955937240246e-07 -1.17948419525502e-06 1.23125306202105e-05 -2.34288798572773e-05 -7.17450452130441e-06 2.38955937240246e-07 1.53286626526558e-05 -4.87254219806157e-06 -9.79405899482932e-07 -4.04042007578694e-06 2.04282082801469e-06 -1.17948419525502e-06 -4.87254219806157e-06 2.72921378829523e-05 -7.80980589646084e-06 6.87694466144169e-06 1.1642079736979e-06 1.23125306202105e-05 -9.79405899482932e-07 -7.80980589646084e-06 7.63408939533497e-05 -6.55317865263648e-06 1.28123041738245e-06 -2.34288798572773e-05 -4.04042007578694e-06 6.87694466144169e-06 -6.55317865263648e-06 5.04259788951464e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1165 0 0 0 0 0 2545 +1113 1116 0.999998859297269 -0.000934327510764051 0.00118677557446209 0.00459235112317188 0.000933985977089416 0.999999522275244 0.000288304487361112 -0.0114338460493138 -0.00118704437832403 -0.000287195726746896 0.999999254221851 0.00228470638528859 1.97627654498619e-05 -9.43611550977264e-06 -2.34857185082489e-06 -2.67261432163296e-06 -2.59198831473627e-06 6.82096420439099e-06 -9.43611550977264e-06 8.6997135820715e-05 2.2352994042773e-05 -9.4366380405459e-06 -8.1575506698816e-06 -3.84501459607913e-05 -2.34857185082489e-06 2.2352994042773e-05 2.18687375396871e-05 -1.12081037279971e-05 -4.71576215969289e-06 -2.44938239062571e-06 -2.67261432163296e-06 -9.4366380405459e-06 -1.12081037279971e-05 2.76285730104046e-05 1.33576006341435e-06 -4.43410409103855e-06 -2.59198831473627e-06 -8.1575506698816e-06 -4.71576215969289e-06 1.33576006341435e-06 4.62096941458549e-05 -6.4553377675246e-06 6.82096420439099e-06 -3.84501459607913e-05 -2.44938239062571e-06 -4.43410409103855e-06 -6.4553377675246e-06 4.70736492608142e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1056 0 0 0 0 0 2701 +1112 1115 0.999989506208602 -0.00101074041333351 0.00446831920226059 0.00427910229772663 0.00100993777312479 0.999999473472207 0.000181881836396456 -0.0096276388299937 -0.00446850068488884 -0.000177367203421664 0.999990000471257 0.00239216523014671 5.00280303817427e-05 -3.3443926385701e-05 -1.80018184793703e-05 6.22591124809228e-06 1.24632791649271e-05 6.45546603495354e-05 -3.3443926385701e-05 0.000137111340909576 1.87770986116358e-05 2.96520380039704e-06 -8.87829674949468e-06 -8.84366927881556e-05 -1.80018184793703e-05 1.87770986116358e-05 2.38618558909448e-05 -1.25580319900981e-05 -9.8093875902673e-06 -1.810980952872e-05 6.22591124809228e-06 2.96520380039704e-06 -1.25580319900981e-05 3.27864864631112e-05 5.04506651437321e-06 -2.55486661117638e-07 1.24632791649271e-05 -8.87829674949468e-06 -9.8093875902673e-06 5.04506651437321e-06 6.09506406630834e-05 8.21372456161183e-06 6.45546603495354e-05 -8.84366927881556e-05 -1.810980952872e-05 -2.55486661117638e-07 8.21372456161183e-06 0.000156256770316488 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 995 0 0 0 0 0 2653 +1113 1115 0.999999397977375 -0.000835603325141417 0.00071120459111276 0.00179856240709126 0.000837285376169442 0.999996845592061 -0.00236807076064102 -0.00313990844586578 -0.000709223579881589 0.00236866481621244 0.999996943209779 0.00167606261288379 5.66599913001583e-05 -1.95327447690656e-05 -1.54221621810966e-05 6.66125833972932e-06 1.14821914765895e-05 4.66514084463398e-05 -1.95327447690656e-05 0.00011452417919281 1.37291445695252e-05 2.40613408664321e-06 -4.13391482744955e-06 -6.74345481410769e-05 -1.54221621810966e-05 1.37291445695252e-05 2.24792356933618e-05 -9.87623750365854e-06 -8.84753163139313e-06 -8.7408532322784e-06 6.66125833972932e-06 2.40613408664321e-06 -9.87623750365854e-06 2.58521719967047e-05 9.46148482717085e-06 -4.69048013683553e-06 1.14821914765895e-05 -4.13391482744955e-06 -8.84753163139313e-06 9.46148482717085e-06 4.50372305624339e-05 7.27810457097747e-06 4.66514084463398e-05 -6.74345481410769e-05 -8.7408532322784e-06 -4.69048013683553e-06 7.27810457097747e-06 0.000116651322118315 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1047 0 0 0 0 0 2630 +1113 1117 0.99999949374149 -0.00095169899647574 -0.000326780942165775 0.0090561654758357 0.000951460210596604 0.999999280837639 -0.000730101138353491 -0.027089575886277 0.000327475543677918 0.000729789849669524 0.999999680083221 0.00418319933286686 2.09311063340918e-05 -7.48817158450938e-06 -8.07588839808514e-06 2.0715399310973e-06 -2.94071196147795e-06 3.90048259383454e-06 -7.48817158450938e-06 6.45343856445442e-05 1.34688164967521e-05 -1.12773645369936e-05 4.40205750251523e-06 -3.01776108814343e-05 -8.07588839808514e-06 1.34688164967521e-05 1.88566842125639e-05 -1.09848839391619e-05 -3.36850473616581e-06 -1.37158781509817e-06 2.0715399310973e-06 -1.12773645369936e-05 -1.09848839391619e-05 2.67681720161155e-05 -6.2001441766746e-06 4.98321526618538e-06 -2.94071196147795e-06 4.40205750251523e-06 -3.36850473616581e-06 -6.2001441766746e-06 6.14786041642583e-05 -1.45471612700526e-05 3.90048259383454e-06 -3.01776108814343e-05 -1.37158781509817e-06 4.98321526618538e-06 -1.45471612700526e-05 4.31305376173322e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1080 0 0 0 0 0 2607 +1113 1145 0.999930011462345 0.00138023983809836 -0.0117501963772504 0.00162141636946194 -0.0014411935565512 0.999985542182801 -0.00518057781540288 0.00774842046835701 0.011742876055174 0.00519714954164448 0.999917543849789 0.00173486986823052 2.51494249575731e-05 -6.14005718944982e-06 -7.89317498134044e-06 3.69120546184171e-06 2.64395561401183e-06 7.77403522894631e-06 -6.14005718944982e-06 0.000103813933559701 1.83511495576019e-05 -2.6438583936543e-06 -2.02797234105831e-05 -3.81466286544928e-05 -7.89317498134044e-06 1.83511495576019e-05 2.03306767205801e-05 -9.02805082354408e-06 -1.00997650876776e-05 -6.24154803538598e-06 3.69120546184171e-06 -2.6438583936543e-06 -9.02805082354408e-06 3.86062336162517e-05 -2.32219330255132e-05 6.83982923984442e-06 2.64395561401183e-06 -2.02797234105831e-05 -1.00997650876776e-05 -2.32219330255132e-05 0.000129603550622368 -7.86823718242527e-06 7.77403522894631e-06 -3.81466286544928e-05 -6.24154803538598e-06 6.83982923984442e-06 -7.86823718242527e-06 5.9341096769035e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1202 0 0 0 0 0 2665 +1113 1140 0.999958943048768 -0.000450866267976819 0.00905035559516165 -0.000158115209292394 0.000419168328513719 0.999993773161928 0.00350398848222401 0.0155751932956075 -0.00905187907027287 -0.0035000509967125 0.999952905455211 -0.0130153378573238 3.960943249146e-05 -6.7154390353932e-06 -1.02390610246271e-05 -3.01480425918562e-06 9.10811078967085e-06 4.44290589563386e-05 -6.7154390353932e-06 7.10275889473303e-05 1.35650626048009e-05 -6.32836813621405e-06 1.72612170228353e-06 -4.22908378517608e-05 -1.02390610246271e-05 1.35650626048009e-05 2.18764747578837e-05 -1.18087670868022e-05 -6.43390939621644e-06 -2.64886274334599e-06 -3.01480425918562e-06 -6.32836813621405e-06 -1.18087670868022e-05 3.8095076596555e-05 -5.95422164852807e-06 -1.43779107721853e-05 9.10811078967085e-06 1.72612170228353e-06 -6.43390939621644e-06 -5.95422164852807e-06 7.67795809001164e-05 1.17794866250836e-05 4.44290589563386e-05 -4.22908378517608e-05 -2.64886274334599e-06 -1.43779107721853e-05 1.17794866250836e-05 0.0001403325741653 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1038 0 0 0 0 0 2601 +1114 1142 0.999999153500532 8.43837082274301e-05 0.00129841349676726 -0.00582628800983224 -8.42440816308183e-05 0.999999990663596 -0.000107590626321569 0.0229363148234375 -0.00129842256354077 0.000107481151593548 0.999999151272964 0.00160860885873972 2.77798235273284e-05 -1.19493574988049e-05 -1.24858950096024e-05 2.81741965649296e-06 6.92395124838701e-06 1.87428340503962e-05 -1.19493574988049e-05 8.19568552174916e-05 1.24254007442271e-05 -5.25815616315736e-07 -1.16805844189872e-05 -4.27568372152153e-05 -1.24858950096024e-05 1.24254007442271e-05 2.10275330049364e-05 -1.16208451365014e-05 -9.34017058820583e-06 -5.62847629511584e-06 2.81741965649296e-06 -5.25815616315736e-07 -1.16208451365014e-05 4.02289660562998e-05 -2.50215394342333e-05 2.00164031951044e-06 6.92395124838701e-06 -1.16805844189872e-05 -9.34017058820583e-06 -2.50215394342333e-05 0.00012320576968702 -3.88628753775893e-07 1.87428340503962e-05 -4.27568372152153e-05 -5.62847629511584e-06 2.00164031951044e-06 -3.88628753775893e-07 6.43146917217391e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1191 0 0 0 0 0 2621 +1114 1117 0.999978148833269 -0.000254969232697913 -0.00660581915270977 0.00487285168937593 0.000217943505336738 0.999984267382649 -0.00560513049051372 -0.0207693278901848 0.00660714436170509 0.00560356831649106 0.999962472128582 0.0101923028594278 5.89114913023566e-05 -1.7319826153345e-05 -1.07012645885949e-05 -1.31284899013683e-06 -3.4723068583193e-07 5.5642081367807e-05 -1.7319826153345e-05 0.000122660102048036 2.14505433996227e-05 1.17815356044636e-06 -7.67967621052775e-06 -7.20164225722886e-05 -1.07012645885949e-05 2.14505433996227e-05 2.18318974584962e-05 -8.12316213558735e-06 -8.59272218879861e-06 -1.00258726563412e-05 -1.31284899013683e-06 1.17815356044636e-06 -8.12316213558735e-06 2.61556052793993e-05 -1.21852550099651e-06 -2.17924474394287e-06 -3.4723068583193e-07 -7.67967621052775e-06 -8.59272218879861e-06 -1.21852550099651e-06 6.628780445831e-05 2.0373128039186e-06 5.5642081367807e-05 -7.20164225722886e-05 -1.00258726563412e-05 -2.17924474394287e-06 2.0373128039186e-06 0.000132795940901539 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1103 0 0 0 0 0 2615 +1114 1140 0.999999717392291 0.000751697238660119 1.29073340741622e-05 -0.000942165307807653 -0.000751705736478849 0.999999492015236 0.000671496653667029 0.0129945977947666 -1.24025653371021e-05 -0.000671506166413964 0.999999774462797 -0.00144342654462386 2.85839572110912e-05 -1.79690271932042e-05 -1.26034275879052e-05 3.50086325211344e-06 -7.66247113218088e-06 1.78907860705677e-05 -1.79690271932042e-05 0.000125139189845878 2.67272371007157e-05 -2.11736865106097e-05 1.72303956962571e-05 -5.5402856504292e-05 -1.26034275879052e-05 2.67272371007157e-05 2.5177230984781e-05 -1.59301170163429e-05 -4.98254055651216e-06 -8.7453282450176e-06 3.50086325211344e-06 -2.11736865106097e-05 -1.59301170163429e-05 3.38712498452209e-05 -7.01617670747592e-07 3.98613069454232e-06 -7.66247113218088e-06 1.72303956962571e-05 -4.98254055651216e-06 -7.01617670747592e-07 7.17367385267196e-05 -2.01479855179068e-05 1.78907860705677e-05 -5.5402856504292e-05 -8.7453282450176e-06 3.98613069454232e-06 -2.01479855179068e-05 7.52087094367647e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1070 0 0 0 0 0 2676 +1114 1145 0.999962015557502 0.000845386574160561 -0.00867483508305274 -0.000209391475292088 -0.000845838540386609 0.999999641105681 -4.84321512817697e-05 0.0140380257027205 0.00867479102581326 5.57678214582482e-05 0.999962371737361 -0.00723226744130801 3.74543152096023e-05 -1.48857094706818e-05 -9.30147361366487e-06 6.75433841319357e-07 3.11264771577561e-06 1.4657241518365e-05 -1.48857094706818e-05 0.000105806789956107 1.58307423321522e-05 1.03790533602986e-05 -3.57572154165235e-05 -4.35149565188349e-05 -9.30147361366487e-06 1.58307423321522e-05 1.93288358929303e-05 -5.72981029099121e-06 -1.19801546328852e-05 -6.42575563012534e-06 6.75433841319357e-07 1.03790533602986e-05 -5.72981029099121e-06 3.63890426649077e-05 -1.82126894444919e-05 -1.61841396254658e-06 3.11264771577561e-06 -3.57572154165235e-05 -1.19801546328852e-05 -1.82126894444919e-05 0.000118983754168684 9.7823424464624e-06 1.4657241518365e-05 -4.35149565188349e-05 -6.42575563012534e-06 -1.61841396254658e-06 9.7823424464624e-06 5.9828263598843e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1238 0 0 0 0 0 2564 +1113 1144 0.999989741914743 -0.000243615681507264 0.00452291020081821 -0.00181994745939897 0.000232011307365764 0.999996680812256 0.00256603492260097 0.0204314383316936 -0.00452352031477654 -0.00256495923368717 0.999986479282641 -0.00316415756182686 2.20513089166144e-05 -1.66875210961124e-05 -1.09799117135344e-05 6.44882684199735e-07 -2.61537351907747e-07 6.38762767633289e-06 -1.66875210961124e-05 8.45126656341176e-05 1.89934853422337e-05 -6.87765143667008e-06 -1.29236714604035e-05 -3.49514696735431e-05 -1.09799117135344e-05 1.89934853422337e-05 2.14175702573609e-05 -7.14772490240114e-06 -1.18045247727419e-05 -4.79647739322965e-06 6.44882684199735e-07 -6.87765143667008e-06 -7.14772490240114e-06 2.9764161153795e-05 -1.11368271218274e-05 3.53592849072883e-06 -2.61537351907747e-07 -1.29236714604035e-05 -1.18045247727419e-05 -1.11368271218274e-05 0.000103422982502683 -1.89246507603716e-06 6.38762767633289e-06 -3.49514696735431e-05 -4.79647739322965e-06 3.53592849072883e-06 -1.89246507603716e-06 4.3290263590367e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1194 0 0 0 0 0 2648 +1114 1116 0.999994349622871 -2.63407676383366e-05 -0.00336155150113299 0.000553257258594757 1.54171024986129e-05 0.999994719998905 -0.00324957483745327 -0.00847557808741295 0.0033616193484331 0.00324950465074589 0.999989070057709 0.005324964274219 5.00311655397755e-05 -3.95860193763712e-06 -1.21844964694098e-06 -5.60258181560691e-06 6.49474639792531e-06 4.3463125411343e-05 -3.95860193763712e-06 9.65115931395525e-05 1.66067497218756e-05 2.35572682774613e-06 -2.76337261643212e-06 -5.3131223801761e-05 -1.21844964694098e-06 1.66067497218756e-05 2.03043842231575e-05 -1.10143921568119e-05 -7.3763411909502e-06 -2.74493147267403e-07 -5.60258181560691e-06 2.35572682774613e-06 -1.10143921568119e-05 2.48702018479546e-05 6.15141373713911e-06 -1.14545221195032e-05 6.49474639792531e-06 -2.76337261643212e-06 -7.3763411909502e-06 6.15141373713911e-06 3.99953912911375e-05 6.65021216485119e-06 4.3463125411343e-05 -5.3131223801761e-05 -2.74493147267403e-07 -1.14545221195032e-05 6.65021216485119e-06 0.000115005264018306 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1092 0 0 0 0 0 2613 +1115 1117 0.999970345675035 -0.00146489228629295 0.00756054635196963 0.0059196295424771 0.0014473595327158 0.99999625224177 0.00232393046309102 -0.0151352793517915 -0.00756392232467908 -0.00231291871966681 0.999968718253757 -0.00150569416001193 4.86307690430978e-05 -4.14223498331117e-06 -7.55460094182702e-06 -2.35520226459285e-06 1.02337528956379e-05 4.09424655486832e-05 -4.14223498331117e-06 0.000113029753720964 1.44756865655111e-05 3.53246472206147e-06 2.08455232261397e-06 -6.24848175583582e-05 -7.55460094182702e-06 1.44756865655111e-05 2.10551446729982e-05 -8.92740893981632e-06 -4.95810441579895e-06 -3.16638377436892e-06 -2.35520226459285e-06 3.53246472206147e-06 -8.92740893981632e-06 2.76098863574531e-05 1.17667044828708e-06 -8.49089469533736e-06 1.02337528956379e-05 2.08455232261397e-06 -4.95810441579895e-06 1.17667044828708e-06 4.85615149265088e-05 1.08878477990711e-05 4.09424655486832e-05 -6.24848175583582e-05 -3.16638377436892e-06 -8.49089469533736e-06 1.08878477990711e-05 0.000122824463276594 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1135 0 0 0 0 0 2526 +1115 1118 0.999999638888843 -0.000499558457120222 0.000687505295572411 0.00815003659483166 0.000502495127279271 0.999990723217721 -0.00427796413560064 -0.0245918903560515 -0.000685361824572272 0.00427830805884107 0.999990613135605 0.0104181216415176 5.74668756934596e-05 -4.39328248699576e-06 -1.10181797776636e-05 -3.15407922686429e-06 2.07151587339831e-05 3.25237807475578e-05 -4.39328248699576e-06 0.000103473206956333 1.52827851083414e-05 5.03002914192228e-06 6.23429170829957e-06 -6.07692435608934e-05 -1.10181797776636e-05 1.52827851083414e-05 2.31477664488034e-05 -7.36879320672381e-06 -5.90158885163139e-06 -7.25820659691933e-06 -3.15407922686429e-06 5.03002914192228e-06 -7.36879320672381e-06 3.01287565622921e-05 -6.65895505842918e-06 -4.87177370196241e-06 2.07151587339831e-05 6.23429170829957e-06 -5.90158885163139e-06 -6.65895505842918e-06 7.26759201595628e-05 -1.90402996752378e-07 3.25237807475578e-05 -6.07692435608934e-05 -7.25820659691933e-06 -4.87177370196241e-06 -1.90402996752378e-07 0.000100629733071207 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1177 0 0 0 0 0 2650 +1114 1143 0.999984278561129 -0.000286836647538939 0.00560003172450133 -0.00264915580350741 0.000287680023834539 0.999999947400512 -0.000149797122662997 0.0199578195523485 -0.00559998846263805 0.000151405784896668 0.999984308479641 -0.00481343886892882 2.76228273023432e-05 -1.50394251974825e-05 -1.3211689842737e-05 4.92106535147109e-06 5.281158438822e-07 2.18627416196149e-05 -1.50394251974825e-05 0.000101007927079689 1.31716285686627e-05 1.77030990745561e-06 1.3740767992418e-05 -4.5708904715559e-05 -1.3211689842737e-05 1.31716285686627e-05 2.03266211277635e-05 -1.05291680997526e-05 -5.44542665613393e-06 -7.17834867550012e-06 4.92106535147109e-06 1.77030990745561e-06 -1.05291680997526e-05 3.4862403571286e-05 -1.08925550857344e-05 6.55974135337714e-06 5.281158438822e-07 1.3740767992418e-05 -5.44542665613393e-06 -1.08925550857344e-05 0.000105198214000503 -1.09207997764199e-05 2.18627416196149e-05 -4.5708904715559e-05 -7.17834867550012e-06 6.55974135337714e-06 -1.09207997764199e-05 7.07127224900022e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1181 0 0 0 0 0 2648 +1114 1118 0.999999252660639 -0.000137289714615231 -0.00121483731305792 0.00806140983690005 0.000131057304691319 0.99998683884758 -0.00512883569706263 -0.0281154219080061 0.00121552546078804 0.00512867265077795 0.999986109510875 0.0101797575595026 3.68580032056757e-05 -3.60408954473811e-06 -1.0297292833277e-05 4.28227464854093e-06 5.79468494155962e-06 2.81021711232766e-05 -3.60408954473811e-06 8.26850181911365e-05 1.31637445563703e-05 1.71280007626725e-06 -7.3599684414497e-06 -3.21444490258233e-05 -1.0297292833277e-05 1.31637445563703e-05 2.15733928773007e-05 -1.07479676336812e-05 -7.8089529156579e-06 -4.5637042900069e-06 4.28227464854093e-06 1.71280007626725e-06 -1.07479676336812e-05 2.95632935926631e-05 -9.47897610051086e-06 3.20079665499111e-06 5.79468494155962e-06 -7.3599684414497e-06 -7.8089529156579e-06 -9.47897610051086e-06 7.36095755193727e-05 -5.60256997505998e-06 2.81021711232766e-05 -3.21444490258233e-05 -4.5637042900069e-06 3.20079665499111e-06 -5.60256997505998e-06 8.20376990529724e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1140 0 0 0 0 0 2663 +1114 1144 0.999990237478538 0.000243694749870439 0.00441197920270371 -0.00492418657889455 -0.000269942279438278 0.999982264936412 0.00594953307493885 0.0234520534431333 -0.00441045108599746 -0.00595066597221734 0.999972568371605 -0.0117238696799301 4.62413411708533e-05 5.20866327987142e-06 -6.48880684757754e-06 -3.34420781061139e-06 2.65839016941149e-06 2.71974105849979e-05 5.20866327987142e-06 9.32283465866182e-05 9.75285144452535e-06 2.64605611586103e-06 -2.57506365996099e-06 -4.03615619529748e-05 -6.48880684757754e-06 9.75285144452535e-06 1.87967984775686e-05 -7.64797439274277e-06 -7.87122296333641e-06 -1.68827968594074e-06 -3.34420781061139e-06 2.64605611586103e-06 -7.64797439274277e-06 3.41967503620852e-05 -8.85911142688039e-06 -4.26785648520465e-06 2.65839016941149e-06 -2.57506365996099e-06 -7.87122296333641e-06 -8.85911142688039e-06 8.6343826788862e-05 2.06065606695496e-06 2.71974105849979e-05 -4.03615619529748e-05 -1.68827968594074e-06 -4.26785648520465e-06 2.06065606695496e-06 9.4991818527436e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1198 0 0 0 0 0 2682 +1115 1143 0.999957225815695 0.000216649020445447 0.00924659949285906 -0.00188968430761419 -0.00023139219294126 0.999998703762057 0.00159340260422923 0.0271057681294333 -0.00924624229795257 -0.00159547403866647 0.999955979764089 -0.00441675287664988 3.92961390371037e-05 -9.49549208408904e-06 -1.29064179241909e-05 4.28356754806126e-06 1.10293455640743e-05 2.13017173848073e-05 -9.49549208408904e-06 0.000131243982298141 1.64319743318456e-05 1.26148348893695e-05 -1.57142701983402e-05 -6.66599728217059e-05 -1.29064179241909e-05 1.64319743318456e-05 2.21968295123394e-05 -6.07054053159468e-06 -6.50948078127241e-06 -1.0374991176321e-05 4.28356754806126e-06 1.26148348893695e-05 -6.07054053159468e-06 3.65491445593399e-05 -6.26286969267645e-06 5.13668497413539e-08 1.10293455640743e-05 -1.57142701983402e-05 -6.50948078127241e-06 -6.26286969267645e-06 6.41929757015054e-05 3.88611455768459e-06 2.13017173848073e-05 -6.66599728217059e-05 -1.0374991176321e-05 5.13668497413539e-08 3.88611455768459e-06 8.29195714979383e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1234 0 0 0 0 0 2627 +1115 1119 0.99999471513184 0.000160341263635338 -0.00324715245540244 0.00522810956625969 -0.000164646636235284 0.999999107747755 -0.00132566782377936 -0.017432780510209 0.00324693699886935 0.00132619545052882 0.999993849283961 0.0067454250435118 4.69140184347535e-05 -1.26741240016869e-05 -9.17936781257815e-06 9.06050654043724e-07 2.42369862086731e-07 5.12049917470914e-05 -1.26741240016869e-05 0.000111533734381754 1.22950563301101e-05 1.23527930392997e-05 -1.86442298108563e-06 -6.30902862875585e-05 -9.17936781257815e-06 1.22950563301101e-05 2.08294422089413e-05 -6.72193815925368e-06 -8.35713709271865e-06 -6.23135535821642e-06 9.06050654043724e-07 1.23527930392997e-05 -6.72193815925368e-06 2.89524983564604e-05 -3.90462391071248e-06 -6.39399140421713e-06 2.42369862086731e-07 -1.86442298108563e-06 -8.35713709271865e-06 -3.90462391071248e-06 6.26128585330268e-05 -6.44965763313571e-06 5.12049917470914e-05 -6.30902862875585e-05 -6.23135535821642e-06 -6.39399140421713e-06 -6.44965763313571e-06 0.000130076387280896 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1229 0 0 0 0 0 2690 +1116 1142 0.999961689884546 3.06740977882442e-05 0.00875316070582194 -0.00848597540003874 -9.52134843674655e-05 0.999972814938395 0.00737294504075033 0.0428301063466887 -0.00875269659217175 -0.00737349600130461 0.999934508784992 -0.0128396255212904 2.77976702186556e-05 -7.18079108582845e-06 -1.03673131557131e-05 -2.67254265370882e-06 1.24908017349744e-05 1.04478405634315e-05 -7.18079108582845e-06 7.48775651834964e-05 1.22619803581286e-05 8.44110123017195e-06 -1.59238128216907e-05 -3.00131143826707e-05 -1.03673131557131e-05 1.22619803581286e-05 1.95680367838224e-05 8.80497879122743e-07 -1.79884751216065e-05 -4.73520206803743e-06 -2.67254265370882e-06 8.44110123017195e-06 8.80497879122743e-07 0.000117485289068895 -0.00026545111111416 1.70801653472456e-05 1.24908017349744e-05 -1.59238128216907e-05 -1.79884751216065e-05 -0.00026545111111416 0.000805747646574587 -5.12101421844687e-05 1.04478405634315e-05 -3.00131143826707e-05 -4.73520206803743e-06 1.70801653472456e-05 -5.12101421844687e-05 5.53769929134225e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1249 0 0 0 0 0 2503 +1116 1118 0.999993036779598 -0.000478656927667611 0.00370098363441271 0.00643034870421458 0.000476368458226376 0.999999694833624 0.000619197666396955 -0.0125830132333312 -0.00370127888824956 -0.000617430322919286 0.999992959632411 0.00130365044933832 3.00261729354557e-05 -3.10197237480612e-05 -1.59009346228428e-05 2.18398809152206e-06 -2.87250171595589e-06 2.14027437871055e-05 -3.10197237480612e-05 0.00013917291479574 2.56818419950994e-05 -1.93838509102471e-06 1.81446991297091e-05 -8.68767883111889e-05 -1.59009346228428e-05 2.56818419950994e-05 2.42691589297843e-05 -8.10845892778082e-06 -2.99195669154275e-06 -1.69623865346279e-05 2.18398809152206e-06 -1.93838509102471e-06 -8.10845892778082e-06 2.36052906763101e-05 4.60760559497225e-06 1.56764871020092e-06 -2.87250171595589e-06 1.81446991297091e-05 -2.99195669154275e-06 4.60760559497225e-06 4.8718209505329e-05 -1.37983775286539e-05 2.14027437871055e-05 -8.68767883111889e-05 -1.69623865346279e-05 1.56764871020092e-06 -1.37983775286539e-05 7.62373689193652e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1203 0 0 0 0 0 2673 +1116 1120 0.999990455011032 -0.00021574683366603 0.00436386756599349 0.0115957375476413 0.000200205125213946 0.999993637526312 0.00356157616820451 -0.024523929147744 -0.00436460819978208 -0.00356066850434681 0.999984135791696 -0.00333264933662787 3.39591123506074e-05 -2.79058014527714e-05 -1.56341782914265e-05 9.14211278899684e-07 3.62012174343979e-06 3.44945375683163e-05 -2.79058014527714e-05 0.000123597009395858 1.87407524798699e-05 5.35005468086082e-06 2.17636439651855e-06 -7.75244312931177e-05 -1.56341782914265e-05 1.87407524798699e-05 2.31430046274528e-05 -6.77633870196537e-06 -7.31937616389652e-06 -1.1940691466468e-05 9.14211278899684e-07 5.35005468086082e-06 -6.77633870196537e-06 2.76165150664016e-05 -9.91184754703257e-06 -1.23893571714963e-06 3.62012174343979e-06 2.17636439651855e-06 -7.31937616389652e-06 -9.91184754703257e-06 7.75578118705564e-05 -1.04387290661511e-05 3.44945375683163e-05 -7.75244312931177e-05 -1.1940691466468e-05 -1.23893571714963e-06 -1.04387290661511e-05 9.29807177725541e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1233 0 0 0 0 0 2578 +1116 1143 0.999890925274392 0.000937902186573296 0.0147396707361273 0.00268619406831596 -0.0010490487791108 0.99997106331889 0.0075347210663291 0.0285705247234062 -0.0147321773876122 -0.00754936185228648 0.999862975654686 -0.0157027681727048 6.23964393053178e-05 -0.000130418145700343 -1.69599023630825e-05 -3.75559169071798e-05 1.37330352803027e-05 7.32284453087628e-05 -0.000130418145700343 0.000483245493705991 2.39225309385324e-05 0.000141236002358754 -3.63957695423837e-05 -0.000218268184348833 -1.69599023630825e-05 2.39225309385324e-05 1.97074300228963e-05 1.17054089437154e-07 -8.02537207036272e-06 -1.29617512129033e-05 -3.75559169071798e-05 0.000141236002358754 1.17054089437154e-07 8.29683530861341e-05 -2.98644577688888e-05 -5.84764248444835e-05 1.37330352803027e-05 -3.63957695423837e-05 -8.02537207036272e-06 -2.98644577688888e-05 0.000125977948579321 1.26870412470153e-05 7.32284453087628e-05 -0.000218268184348833 -1.29617512129033e-05 -5.84764248444835e-05 1.26870412470153e-05 0.000147503440418682 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1263 0 0 0 0 0 2655 +1116 1144 0.999940953161124 -0.000136992348417979 0.0108660675646733 -0.0035758384349746 9.56704911348331e-05 0.999992762991903 0.003803263201017 0.0331973650379481 -0.0108665099448119 -0.00380199906832695 0.999933729686475 -0.00525681964047468 2.83444442881619e-05 -2.1022886492775e-05 -1.15860818320817e-05 1.60173087751065e-06 -7.12306181236342e-06 1.21249667979475e-05 -2.1022886492775e-05 9.67310047466645e-05 1.8982485217667e-05 -3.3265824231718e-06 1.61900895296343e-05 -4.39118014046308e-05 -1.15860818320817e-05 1.8982485217667e-05 1.99526412775582e-05 -6.72391231716554e-06 -3.20761808091088e-06 -7.57951016031886e-06 1.60173087751065e-06 -3.3265824231718e-06 -6.72391231716554e-06 2.95988929754382e-05 -1.39024886954268e-05 3.62226786875572e-06 -7.12306181236342e-06 1.61900895296343e-05 -3.20761808091088e-06 -1.39024886954268e-05 0.000106739581086615 -1.75328876480082e-05 1.21249667979475e-05 -4.39118014046308e-05 -7.57951016031886e-06 3.62226786875572e-06 -1.75328876480082e-05 5.145383661801e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1300 0 0 0 0 0 2683 +1115 1144 0.999983269695323 0.000418158117155482 0.00576935639737464 -0.0078715839173611 -0.000457989879602553 0.999976059266713 0.00690442891809005 0.0369998205843691 -0.00576633113175547 -0.00690695571173245 0.999959520874758 -0.0104208792211786 4.70564635893952e-05 -2.6255937931277e-06 -8.5196478366331e-06 7.4600670929991e-07 -1.65371626829981e-06 3.62174877869375e-05 -2.6255937931277e-06 0.000109787535294105 1.34227759387448e-05 2.0007275555328e-05 -1.61302406924721e-05 -4.24951598813487e-05 -8.5196478366331e-06 1.34227759387448e-05 2.20696587060078e-05 -7.06513946459454e-06 -9.59486557723864e-06 -4.90547738332031e-06 7.4600670929991e-07 2.0007275555328e-05 -7.06513946459454e-06 5.49929211295205e-05 -5.18352574589514e-05 -3.99720724564094e-06 -1.65371626829981e-06 -1.61302406924721e-05 -9.59486557723864e-06 -5.18352574589514e-05 0.000180975062310594 -1.02443861791468e-06 3.62174877869375e-05 -4.24951598813487e-05 -4.90547738332031e-06 -3.99720724564094e-06 -1.02443861791468e-06 0.000103856813824036 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1256 0 0 0 0 0 2680 +1117 1144 0.999990143018003 0.000599003184413736 0.00439943883002071 -0.00512987168229804 -0.000610514743696325 0.999996392632537 0.00261572048594541 0.0267287263578702 -0.0043978561347276 -0.00261838062510539 0.999986901386373 -0.00410900500079245 2.35267778851462e-05 -4.27612059991188e-07 -7.3819411320698e-06 9.92832828331634e-07 -4.05217372620692e-06 9.20100228364608e-07 -4.27612059991188e-07 6.61445184856081e-05 1.36635650312753e-05 -7.68317247255747e-06 4.3549367776778e-08 -2.57963688449797e-05 -7.3819411320698e-06 1.36635650312753e-05 1.96221469647085e-05 -8.43137556228647e-06 -4.40225455293217e-06 -1.21187186952673e-06 9.92832828331634e-07 -7.68317247255747e-06 -8.43137556228647e-06 2.99016674241445e-05 -1.54619814107421e-05 5.59386809615909e-06 -4.05217372620692e-06 4.3549367776778e-08 -4.40225455293217e-06 -1.54619814107421e-05 9.15182145386753e-05 -1.6287230778799e-05 9.20100228364608e-07 -2.57963688449797e-05 -1.21187186952673e-06 5.59386809615909e-06 -1.6287230778799e-05 4.67619347728966e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1304 0 0 0 0 0 2650 +1117 1120 0.999998583801497 0.000401495102005933 -0.00163437960213467 0.00510766181947364 -0.000400301000138387 0.999999652789388 0.000730876332708724 -0.0169680939149697 0.00163467247792848 -0.000730221053853415 0.999998397310267 -0.000349746191255164 3.11933733370554e-05 -6.73128467199568e-06 -1.28772312930341e-05 2.69010578354118e-06 4.04560295451418e-06 2.25330713532379e-05 -6.73128467199568e-06 8.41855921947859e-05 1.26805583847777e-05 2.17650413902014e-06 -3.88789709265101e-06 -3.29516171484074e-05 -1.28772312930341e-05 1.26805583847777e-05 2.08943514892681e-05 -8.41442832480892e-06 -6.3021696791116e-06 -6.42660949968789e-06 2.69010578354118e-06 2.17650413902014e-06 -8.41442832480892e-06 2.539287395633e-05 -1.47961109338852e-05 2.81583205457812e-06 4.04560295451418e-06 -3.88789709265101e-06 -6.3021696791116e-06 -1.47961109338852e-05 8.10042222702215e-05 -4.17832322132986e-06 2.25330713532379e-05 -3.29516171484074e-05 -6.42660949968789e-06 2.81583205457812e-06 -4.17832322132986e-06 6.15035592436182e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1245 0 0 0 0 0 2581 +1117 1119 0.999999509792825 0.000341663696942881 0.000929343868949458 0.0019262882939513 -0.000340686874266495 0.999999389619475 -0.0010510438292059 -0.00507638411017034 -0.000929702405216395 0.00105072669871885 0.999999015812937 0.00043339825635835 2.36631957692318e-05 -7.82251089080039e-06 -1.03082440099923e-05 3.78907382968175e-06 -6.79419986302271e-07 8.26791804475157e-06 -7.82251089080039e-06 6.71682537726529e-05 1.14949590107224e-05 -5.13611769472452e-07 -2.26152544763016e-06 -3.43502410310116e-05 -1.03082440099923e-05 1.14949590107224e-05 1.8504151974996e-05 -6.58236290418619e-06 -4.55490309529774e-06 -4.62673587568258e-06 3.78907382968175e-06 -5.13611769472452e-07 -6.58236290418619e-06 1.9200064548506e-05 1.43572818470484e-06 -1.97856242057492e-06 -6.79419986302271e-07 -2.26152544763016e-06 -4.55490309529774e-06 1.43572818470484e-06 4.23542795785676e-05 -1.29071037172085e-06 8.26791804475157e-06 -3.43502410310116e-05 -4.62673587568258e-06 -1.97856242057492e-06 -1.29071037172085e-06 4.65815810273012e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1256 0 0 0 0 0 2702 +1115 1145 0.999997017172276 0.00047235606430859 -0.00239635688066212 -0.0022419419609384 -0.000468547720230709 0.999998626919844 0.00158953498246042 0.0284334083074776 0.00239710441676044 -0.00158840743359812 0.999995865417573 -0.0102535647840681 2.83795767445375e-05 -9.82250084363007e-06 -9.01603333551884e-06 2.53589531516423e-06 -5.76079857017568e-06 1.1462458847383e-05 -9.82250084363007e-06 0.000103263389684083 1.76273705045749e-05 5.84840539682353e-06 -8.1742327042727e-06 -2.89496043041772e-05 -9.01603333551884e-06 1.76273705045749e-05 2.0850580715318e-05 -5.35469826457918e-06 -7.19420331838125e-06 -4.14067325023854e-06 2.53589531516423e-06 5.84840539682353e-06 -5.35469826457918e-06 3.93350161285303e-05 -2.6577185775491e-05 1.40994326288671e-06 -5.76079857017568e-06 -8.1742327042727e-06 -7.19420331838125e-06 -2.6577185775491e-05 0.000148041419185339 -8.07440868973221e-06 1.1462458847383e-05 -2.89496043041772e-05 -4.14067325023854e-06 1.40994326288671e-06 -8.07440868973221e-06 5.6563140567742e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1303 0 0 0 0 0 2639 +1118 1122 0.99999961321966 -0.000310306270855932 -0.000822964488132141 0.00574132756056075 0.000311943636590108 0.999997970869367 0.00199021313323913 -0.0137702757112214 0.000822345242614104 -0.00199046908199903 0.999997680887879 0.000931625966039732 4.44271170151429e-05 -1.38227591993766e-05 -1.25460907076047e-05 7.56774172718588e-06 -1.58612461727104e-06 4.37572490602666e-05 -1.38227591993766e-05 8.72489969791237e-05 1.32566420425849e-05 -8.11000946531459e-07 4.94577264306571e-06 -5.12877825220489e-05 -1.25460907076047e-05 1.32566420425849e-05 2.06801998119996e-05 -9.24686974452451e-06 -6.48127409572931e-06 -1.03422292134289e-05 7.56774172718588e-06 -8.11000946531459e-07 -9.24686974452451e-06 2.85381653640291e-05 -1.27197463925975e-05 8.41366087368293e-06 -1.58612461727104e-06 4.94577264306571e-06 -6.48127409572931e-06 -1.27197463925975e-05 7.75808705416726e-05 -1.06405230964761e-05 4.37572490602666e-05 -5.12877825220489e-05 -1.03422292134289e-05 8.41366087368293e-06 -1.06405230964761e-05 0.000106776133229627 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1340 0 0 0 0 0 2611 +1116 1119 0.999988682468788 0.000101771330727794 0.00475652992569969 0.00504095797723529 -0.00010163822388953 0.99999999443649 -2.82257376546279e-05 -0.00790992991605432 -0.00475653277180757 2.77419729554355e-05 0.999988687249198 -0.0012384954717355 2.92451828691214e-05 -2.10656238370504e-05 -1.32968456927224e-05 3.27534315255452e-06 7.12453188664467e-07 1.34586710037837e-05 -2.10656238370504e-05 0.000101808707995862 1.85222773270449e-05 2.44857973244627e-06 -2.53518667657178e-06 -5.40174389020017e-05 -1.32968456927224e-05 1.85222773270449e-05 2.05981220496421e-05 -7.53123332983282e-06 -3.19391820552719e-06 -8.04761298648305e-06 3.27534315255452e-06 2.44857973244627e-06 -7.53123332983282e-06 2.58806194232534e-05 -4.35363712348669e-06 -4.41339386430428e-06 7.12453188664467e-07 -2.53518667657178e-06 -3.19391820552719e-06 -4.35363712348669e-06 5.59104651640279e-05 -2.20256393609932e-06 1.34586710037837e-05 -5.40174389020017e-05 -8.04761298648305e-06 -4.41339386430428e-06 -2.20256393609932e-06 5.77105683463557e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1254 0 0 0 0 0 2671 +1117 1143 0.999982367442447 0.000676181883113497 0.00589979510314325 -0.0022408539752438 -0.000708918339772177 0.99998435611882 0.00554841891150574 0.0235365781978738 -0.00589595106710178 -0.00555250355163947 0.999967203194847 -0.00947609525327834 2.09125406975867e-05 7.54244089812194e-07 -9.1211254662953e-06 2.31286325597278e-06 2.95189001859432e-06 1.1150993236379e-05 7.54244089812194e-07 6.50210140883526e-05 5.72476780239537e-06 6.00609264799263e-06 -8.64269039780855e-06 -2.06608990105147e-05 -9.1211254662953e-06 5.72476780239537e-06 1.59596856860503e-05 -6.76713796773831e-06 -5.00196496546822e-06 -3.77346433518967e-06 2.31286325597278e-06 6.00609264799263e-06 -6.76713796773831e-06 3.11979503127368e-05 -2.2802790126824e-05 3.27554329733478e-06 2.95189001859432e-06 -8.64269039780855e-06 -5.00196496546822e-06 -2.2802790126824e-05 0.000119275061939757 2.05728742493297e-06 1.1150993236379e-05 -2.06608990105147e-05 -3.77346433518967e-06 3.27554329733478e-06 2.05728742493297e-06 4.67189155397718e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1259 0 0 0 0 0 2647 +1117 1121 0.999988204484617 -0.000265350346310503 -0.00484979183328725 0.00693923438298628 0.00024171200854689 0.999988092634179 -0.00487402966359104 -0.0258131040852498 0.00485102741050089 0.00487279991897411 0.999976361397614 0.00945718375396097 4.29401965089874e-05 -6.19803691665464e-06 -6.37165656843233e-06 3.10547887561265e-06 -1.39081196399871e-06 3.12912864847529e-05 -6.19803691665464e-06 0.000111066595484446 9.66976299147276e-06 1.3179833176345e-05 -1.03740908735398e-05 -5.34141722738496e-05 -6.37165656843233e-06 9.66976299147276e-06 1.63611370403895e-05 -4.84593966902119e-06 -7.72585543739092e-06 -3.37078823552039e-06 3.10547887561265e-06 1.3179833176345e-05 -4.84593966902119e-06 2.60343743414125e-05 -1.28966889392772e-05 -4.34874965046822e-06 -1.39081196399871e-06 -1.03740908735398e-05 -7.72585543739092e-06 -1.28966889392772e-05 7.69676520659048e-05 -3.00753627734258e-06 3.12912864847529e-05 -5.34141722738496e-05 -3.37078823552039e-06 -4.34874965046822e-06 -3.00753627734258e-06 9.33526745739994e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1336 0 0 0 0 0 2621 +1120 1123 0.999996619832873 0.000250879674084116 -0.00258793010290981 0.00118090496887229 -0.000252687083650135 0.999999724405317 -0.000698096359139523 -0.00150199135360186 0.00258775425150297 0.000698747935967553 0.999996407633175 0.0028947259804945 2.28955035384804e-05 -2.05296368203235e-05 -1.23553185605455e-05 4.66105339447779e-06 8.16848492564279e-08 1.34749257951322e-05 -2.05296368203235e-05 0.000101146663089293 2.28384690165339e-05 -8.46382732188823e-06 1.03363561769416e-06 -5.4046889849596e-05 -1.23553185605455e-05 2.28384690165339e-05 2.19547635414203e-05 -1.09096778658268e-05 -4.65128094798975e-06 -9.25218740914418e-06 4.66105339447779e-06 -8.46382732188823e-06 -1.09096778658268e-05 2.20735957040257e-05 2.25112015888884e-06 2.3707540242215e-06 8.16848492564279e-08 1.03363561769416e-06 -4.65128094798975e-06 2.25112015888884e-06 4.37918360287427e-05 -2.42980353606932e-06 1.34749257951322e-05 -5.4046889849596e-05 -9.25218740914418e-06 2.3707540242215e-06 -2.42980353606932e-06 5.55126288619838e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1243 0 0 0 0 0 2758 +1120 1122 0.999992210916057 0.00028716119539328 -0.00393645089701823 -0.000564521082418891 -0.000280882370911457 0.999998687730188 0.00159550712800149 0.000514107795494268 0.00393690389906669 -0.00159438902080161 0.999990979314983 0.00156376685365582 2.84628196642287e-05 -1.11515052082398e-05 -1.30815704607697e-05 3.10647028862097e-06 5.80084748000534e-06 1.71396952741907e-05 -1.11515052082398e-05 0.000118555274412145 1.63291237695418e-05 9.44745098193168e-06 -3.06186020810632e-06 -5.84002754234482e-05 -1.30815704607697e-05 1.63291237695418e-05 2.25672508266981e-05 -1.0506158167086e-05 -6.86487638528425e-06 -1.04702638063626e-05 3.10647028862097e-06 9.44745098193168e-06 -1.0506158167086e-05 2.63406773034767e-05 -3.91064377553724e-07 -4.30009648025545e-06 5.80084748000534e-06 -3.06186020810632e-06 -6.86487638528425e-06 -3.91064377553724e-07 4.33179080861316e-05 8.29278794787206e-06 1.71396952741907e-05 -5.84002754234482e-05 -1.04702638063626e-05 -4.30009648025545e-06 8.29278794787206e-06 6.73835952149093e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1353 0 0 0 0 0 2470 +1121 1123 0.999980034511077 -0.00163471956431602 0.00610395537101665 0.00299613593255914 0.00163019224951036 0.999998392526908 0.000746603529391105 0.000746869921390087 -0.00610516604646892 -0.00073663800234942 0.999981091977243 0.000652979645728871 3.10674082303395e-05 -1.52752464247704e-05 -1.27707090007033e-05 -6.56958152937949e-07 2.21904296203323e-06 1.89692528565413e-05 -1.52752464247704e-05 9.65918822034007e-05 1.65755351802719e-05 2.54690313578467e-06 4.60091356068579e-06 -4.25198246382188e-05 -1.27707090007033e-05 1.65755351802719e-05 2.31693756404925e-05 -4.90200744508692e-06 -5.12042729848984e-06 -5.26307174052148e-06 -6.56958152937949e-07 2.54690313578467e-06 -4.90200744508692e-06 2.00784104530367e-05 9.1926864366315e-06 -2.04096146023165e-06 2.21904296203323e-06 4.60091356068579e-06 -5.12042729848984e-06 9.1926864366315e-06 3.57225940344973e-05 -1.45057504467894e-06 1.89692528565413e-05 -4.25198246382188e-05 -5.26307174052148e-06 -2.04096146023165e-06 -1.45057504467894e-06 5.9801152210272e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1237 0 0 0 0 0 2731 +1120 1124 0.999991841337649 -6.41423490757049e-05 0.0040389533169694 0.0024831462297728 5.30977603772652e-05 0.999996259659357 0.00273456539953039 -0.00426579368895312 -0.00403911361135658 -0.00273432862975922 0.999988104433337 -0.0060383926657559 2.13673219462114e-05 -1.11310790796589e-05 -1.17293426836009e-05 4.24838157095923e-06 4.08003562922883e-06 1.38179083596752e-05 -1.11310790796589e-05 7.25555555326619e-05 1.31424288054086e-05 2.93278210546626e-06 -6.60535053832943e-06 -3.71315773078405e-05 -1.17293426836009e-05 1.31424288054086e-05 1.81794709576362e-05 -9.32638798513105e-06 -6.55658629701948e-06 -7.01594324961357e-06 4.24838157095923e-06 2.93278210546626e-06 -9.32638798513105e-06 2.45763663659256e-05 -6.41525554925114e-06 -4.08958086545137e-07 4.08003562922883e-06 -6.60535053832943e-06 -6.55658629701948e-06 -6.41525554925114e-06 6.16490353512739e-05 4.34747767986053e-06 1.38179083596752e-05 -3.71315773078405e-05 -7.01594324961357e-06 -4.08958086545137e-07 4.34747767986053e-06 4.68605862991027e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1356 0 0 0 0 0 2715 +1118 1121 0.999995979839688 -0.000201525698281446 0.0028283726515009 0.00397082412754399 0.000208980722505744 0.999996504563456 -0.0026357518711779 -0.0132768068898392 -0.00282783159336744 0.00263633235039306 0.999992526532183 0.00425952489841886 4.13191938102957e-05 -1.67616769939949e-05 -1.15449016077418e-05 3.42582752854338e-06 3.16925636852532e-06 4.0865106584201e-05 -1.67616769939949e-05 0.000105040573910857 1.56976211873298e-05 6.10751598486336e-06 -7.54524147695147e-06 -5.35833390024826e-05 -1.15449016077418e-05 1.56976211873298e-05 1.9997033404069e-05 -1.06146273082214e-05 -5.7457313945684e-06 -6.63476076896939e-06 3.42582752854338e-06 6.10751598486336e-06 -1.06146273082214e-05 3.01605460120334e-05 -1.02018390751357e-05 -1.18002495959629e-06 3.16925636852532e-06 -7.54524147695147e-06 -5.7457313945684e-06 -1.02018390751357e-05 7.05339158386982e-05 3.35223609245039e-06 4.0865106584201e-05 -5.35833390024826e-05 -6.63476076896939e-06 -1.18002495959629e-06 3.35223609245039e-06 0.000106276458596922 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1337 0 0 0 0 0 2656 +1121 1124 0.999990722925189 -0.00102835601060545 0.00418288745638417 0.00398760518350036 0.0010174135378332 0.999996057306463 0.00261729654821127 -0.000141139021711805 -0.00418556247717772 -0.00261301654103004 0.999987826531556 -0.000953740230555621 2.38641884380071e-05 -7.19466237775589e-06 -1.14975981279435e-05 3.16449294065072e-06 2.55625267928428e-06 7.06062441869008e-06 -7.19466237775589e-06 6.66054859400503e-05 8.60081911717243e-06 1.04000829325558e-06 3.79487346314149e-07 -3.43195258902709e-05 -1.14975981279435e-05 8.60081911717243e-06 1.8360385262633e-05 -6.22408460442287e-06 -3.90179853027441e-06 -5.71960983791387e-06 3.16449294065072e-06 1.04000829325558e-06 -6.22408460442287e-06 2.05932516624254e-05 5.74332101229678e-06 1.0763907821927e-06 2.55625267928428e-06 3.79487346314149e-07 -3.90179853027441e-06 5.74332101229678e-06 3.51124863476452e-05 1.21112146243245e-06 7.06062441869008e-06 -3.43195258902709e-05 -5.71960983791387e-06 1.0763907821927e-06 1.21112146243245e-06 4.17232527251532e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1365 0 0 0 0 0 2674 +1118 1120 0.999972584671144 -0.00141422099568755 0.00726841695882638 0.0045207090729304 0.0013801556417251 0.999988051130126 0.00468964469618039 -0.00604623797606319 -0.00727496230344961 -0.00467948458135669 0.999962587973938 -0.00789995260563695 3.02889540012465e-05 -1.83384146992622e-05 -1.37401800713227e-05 3.03368921564806e-07 4.84617869471168e-06 2.45215699591459e-05 -1.83384146992622e-05 0.000105672462451437 1.16341815813729e-05 8.84247627638941e-06 -5.61752018395962e-06 -5.64850662175204e-05 -1.37401800713227e-05 1.16341815813729e-05 2.23337719518618e-05 -7.64834926805745e-06 -7.92559578033263e-06 -1.09386019372894e-05 3.03368921564806e-07 8.84247627638941e-06 -7.64834926805745e-06 2.58252682119032e-05 1.62063897842934e-07 -4.43882894520768e-06 4.84617869471168e-06 -5.61752018395962e-06 -7.92559578033263e-06 1.62063897842934e-07 4.52058547409121e-05 6.88190326107819e-06 2.45215699591459e-05 -5.64850662175204e-05 -1.09386019372894e-05 -4.43882894520768e-06 6.88190326107819e-06 7.37507531677508e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1249 0 0 0 0 0 2596 +1119 1122 0.999998917536319 -0.000295038506392739 -0.00144148481436838 0.00614330146382682 0.000292147121770002 0.999997946033612 -0.00200563671111329 -0.0176933512365552 0.00144207359366664 0.0020052134144448 0.999996949766805 0.00483141659881694 4.05770654987741e-05 -1.42309654692742e-05 -1.25843477039537e-05 3.68819273092971e-06 1.45602251740491e-06 3.37527792090025e-05 -1.42309654692742e-05 0.000102560547178589 1.59322944797805e-05 3.29068494648548e-06 8.30929564391891e-06 -6.08432160811444e-05 -1.25843477039537e-05 1.59322944797805e-05 2.35904058358565e-05 -9.16637187839656e-06 -8.81130777951437e-06 -8.27034534144084e-06 3.68819273092971e-06 3.29068494648548e-06 -9.16637187839656e-06 2.84744879278069e-05 -9.58420464810018e-06 -4.541860177346e-08 1.45602251740491e-06 8.30929564391891e-06 -8.81130777951437e-06 -9.58420464810018e-06 7.26519504841467e-05 -8.06794245689645e-06 3.37527792090025e-05 -6.08432160811444e-05 -8.27034534144084e-06 -4.541860177346e-08 -8.06794245689645e-06 9.68643833343998e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1339 0 0 0 0 0 2599 +1119 1123 0.999999911569558 5.82593008186336e-05 -0.000416493374032224 0.00634700670487384 -5.68537375076947e-05 0.999994306526856 0.00337397118031161 -0.0178623491355754 0.000416687567940331 -0.00337394720274489 0.999994221409176 -0.00205030318257603 2.74886311059076e-05 -1.04758388264419e-05 -9.80739088239587e-06 1.90310476102726e-06 -2.77656755320046e-06 1.48250494949688e-05 -1.04758388264419e-05 0.00010776107066586 1.82456822371146e-05 -1.71505624413985e-06 9.0487509135613e-06 -5.75281883187704e-05 -9.80739088239587e-06 1.82456822371146e-05 2.190926462328e-05 -1.23523093194549e-05 4.2896589426989e-07 -9.46358437850907e-06 1.90310476102726e-06 -1.71505624413985e-06 -1.23523093194549e-05 3.12195470125302e-05 -1.99784600814489e-05 2.84582107653001e-06 -2.77656755320046e-06 9.0487509135613e-06 4.2896589426989e-07 -1.99784600814489e-05 8.21771270452724e-05 -7.76108570074729e-06 1.48250494949688e-05 -5.75281883187704e-05 -9.46358437850907e-06 2.84582107653001e-06 -7.76108570074729e-06 6.64483494896654e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1255 0 0 0 0 0 2721 +1119 1121 0.999988158136723 -0.000599712965800631 -0.00482948555061039 0.00414754238056405 0.000589138585254215 0.999997426934837 -0.0021906710007894 -0.0178474870563632 0.00483078689783234 0.00218779982287813 0.999985938416077 0.00718935567162811 3.69544625289568e-05 -1.57795608358466e-05 -1.18738025227903e-05 6.98851708040601e-06 -5.25998741183877e-06 3.18997952521799e-05 -1.57795608358466e-05 8.95912211577655e-05 9.24565247104876e-06 2.36976373807885e-06 5.79171494467328e-06 -4.93696154035087e-05 -1.18738025227903e-05 9.24565247104876e-06 1.90732928697427e-05 -9.11592717226793e-06 -5.49774587845145e-06 -3.68765118894457e-06 6.98851708040601e-06 2.36976373807885e-06 -9.11592717226793e-06 2.6305806972122e-05 -8.49473015839755e-06 3.90303108545959e-06 -5.25998741183877e-06 5.79171494467328e-06 -5.49774587845145e-06 -8.49473015839755e-06 6.944609269556e-05 -1.63145393317642e-05 3.18997952521799e-05 -4.93696154035087e-05 -3.68765118894457e-06 3.90303108545959e-06 -1.63145393317642e-05 8.8012085379288e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1353 0 0 0 0 0 2671 +1121 1125 0.999974944130469 -0.000633051062335514 0.0070505572557816 0.0063335766030023 0.000616622061434991 0.999997090537695 0.00233210063654998 -0.000458993716166889 -0.00705201308123648 -0.00232769467459138 0.999972425094314 -0.00350758411634676 2.42343028923085e-05 -1.05991218441791e-05 -1.39528554794827e-05 2.76474534819946e-06 2.08184532183683e-06 1.26353325409697e-05 -1.05991218441791e-05 6.85076540599209e-05 1.044336513924e-05 5.62614063130218e-06 -2.29378362578908e-07 -3.5848626992542e-05 -1.39528554794827e-05 1.044336513924e-05 2.09832472566555e-05 -4.97076522840545e-06 -3.76954891512733e-06 -8.87410100282692e-06 2.76474534819946e-06 5.62614063130218e-06 -4.97076522840545e-06 2.30804851498693e-05 8.17590419460931e-06 2.97809269857542e-07 2.08184532183683e-06 -2.29378362578908e-07 -3.76954891512733e-06 8.17590419460931e-06 3.81766443600359e-05 2.89671288239783e-06 1.26353325409697e-05 -3.5848626992542e-05 -8.87410100282692e-06 2.97809269857542e-07 2.89671288239783e-06 4.5398608902743e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1363 0 0 0 0 0 2551 +1122 1126 0.999999717361339 -0.000449834741302753 -0.000602433355788032 0.00207088926372611 0.000449177625568918 0.999999304567292 -0.00109046063385184 -0.00947067752163344 0.000602923463913301 0.00109018972606119 0.999999223984528 3.51120900071349e-05 6.26546140623374e-05 3.415472132264e-06 -1.0565874478735e-05 5.38291881205103e-06 8.92784380829018e-06 4.05089805088104e-05 3.415472132264e-06 9.96829119517902e-05 1.11319064811405e-05 3.10598421488282e-06 1.3120956947512e-05 -4.79349704927782e-05 -1.0565874478735e-05 1.11319064811405e-05 2.08518022854702e-05 -8.67545218688898e-06 -4.70861606222854e-06 -6.52923526601121e-06 5.38291881205103e-06 3.10598421488282e-06 -8.67545218688898e-06 2.3576638213268e-05 4.30225939854708e-06 2.90275043594023e-06 8.92784380829018e-06 1.3120956947512e-05 -4.70861606222854e-06 4.30225939854708e-06 4.57540806389135e-05 1.85517433002197e-06 4.05089805088104e-05 -4.79349704927782e-05 -6.52923526601121e-06 2.90275043594023e-06 1.85517433002197e-06 0.000104373217303808 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1257 0 0 0 0 0 2559 +1122 1124 0.999998469157702 0.000390605274931245 0.00170561126020579 0.0021765640260687 -0.000389878254940399 0.999999833019224 -0.000426563558984841 -0.00236707486923044 -0.00170577759337773 0.000425897925241566 0.999998454465685 -0.00269802831956251 2.81713505634118e-05 -1.2279931759136e-05 -1.13836001517539e-05 3.95509341413614e-06 -1.84329703698456e-07 1.03859555082322e-05 -1.2279931759136e-05 9.01878733108022e-05 1.15395670631811e-05 9.79531246238733e-07 4.91695844789132e-06 -4.94752648317177e-05 -1.13836001517539e-05 1.15395670631811e-05 1.99075169447161e-05 -9.13745484744293e-06 -6.58282591518185e-06 -9.30257300612926e-06 3.95509341413614e-06 9.79531246238733e-07 -9.13745484744293e-06 1.92808268513933e-05 4.82449061948026e-06 7.11858535451514e-07 -1.84329703698456e-07 4.91695844789132e-06 -6.58282591518185e-06 4.82449061948026e-06 3.59506180126391e-05 -2.14224351920907e-06 1.03859555082322e-05 -4.94752648317177e-05 -9.30257300612926e-06 7.11858535451514e-07 -2.14224351920907e-06 5.5596861598784e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1360 0 0 0 0 0 2553 +1123 1125 0.999995444672815 0.000562940750983427 0.00296542262241781 0.00392172865217826 -0.000567626314486648 0.999998591549988 0.0015794614292542 -0.00865312324047782 -0.00296452930256515 -0.00158113748620467 0.999994355769203 -0.00530232842457977 2.91110438822693e-05 -1.73974425143309e-05 -1.402021542202e-05 4.24853715671273e-06 5.77521487232304e-06 1.99401413662725e-05 -1.73974425143309e-05 0.000112685161056341 1.4596522144296e-05 8.18306077514071e-06 -7.3868279788056e-06 -5.55766668139066e-05 -1.402021542202e-05 1.4596522144296e-05 2.41135652488588e-05 -1.07921991678326e-05 -9.00284495104184e-06 -9.23458751477809e-06 4.24853715671273e-06 8.18306077514071e-06 -1.07921991678326e-05 2.49216634939329e-05 4.33347370102433e-06 -8.60428401214601e-07 5.77521487232304e-06 -7.3868279788056e-06 -9.00284495104184e-06 4.33347370102433e-06 3.94205866930272e-05 2.82081647577986e-06 1.99401413662725e-05 -5.55766668139066e-05 -9.23458751477809e-06 -8.60428401214601e-07 2.82081647577986e-06 6.50592925970707e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1347 0 0 0 0 0 2577 +1123 1127 0.999999965427474 -0.000239921734033607 0.000107622543628022 0.00709866115860771 0.000240253822207827 0.999995177440308 -0.00309634853153026 -0.0192539251378508 -0.000106879143303024 0.00309637428120913 0.999995200510062 0.00346590076012954 3.30953139429614e-05 9.59297574294732e-08 -1.19026355075828e-05 4.4540791842661e-06 8.61229148803864e-07 1.43390291876114e-05 9.59297574294732e-08 8.89336959249423e-05 1.02847351970622e-05 5.14252456095815e-06 -6.13617051663972e-07 -4.98801536154134e-05 -1.19026355075828e-05 1.02847351970622e-05 2.02356547627094e-05 -9.59873300780802e-06 -7.98070297287351e-06 -8.29066221342588e-06 4.4540791842661e-06 5.14252456095815e-06 -9.59873300780802e-06 2.32421883180991e-05 1.51696878877617e-06 -1.43876609171222e-06 8.61229148803864e-07 -6.13617051663972e-07 -7.98070297287351e-06 1.51696878877617e-06 4.85043339763837e-05 2.68019729390399e-06 1.43390291876114e-05 -4.98801536154134e-05 -8.29066221342588e-06 -1.43876609171222e-06 2.68019729390399e-06 6.6778210829895e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1285 0 0 0 0 0 2743 +1122 1125 0.999992045360693 -2.73470650953402e-05 0.00398854202373144 0.00321961752591945 2.28569808345801e-05 0.999999366040398 0.00112578699588654 -0.00558453264639777 -0.00398857028212718 -0.00112568687462845 0.999991412031206 -0.0027780841575699 2.6875472733236e-05 -5.51907231162288e-06 -1.31155084649918e-05 2.93798629512589e-06 4.82822565275486e-06 5.01863565373709e-06 -5.51907231162288e-06 0.000104938619308176 1.64088664173077e-05 7.51262690633089e-06 -2.52720439840641e-06 -5.88447528730244e-05 -1.31155084649918e-05 1.64088664173077e-05 2.05339499145122e-05 -6.61095198146405e-06 -7.28797228794047e-06 -9.60595059182158e-06 2.93798629512589e-06 7.51262690633089e-06 -6.61095198146405e-06 2.01422504429243e-05 2.84941994209367e-06 -3.19311077116266e-06 4.82822565275486e-06 -2.52720439840641e-06 -7.28797228794047e-06 2.84941994209367e-06 3.54540540939566e-05 1.45117638902373e-06 5.01863565373709e-06 -5.88447528730244e-05 -9.60595059182158e-06 -3.19311077116266e-06 1.45117638902373e-06 5.4622556522318e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1373 0 0 0 0 0 2547 +1123 1126 0.999999755797272 -0.000248721048906644 0.00065310277659229 0.00668630719604705 0.000250193007724674 0.999997426907695 -0.00225467989910408 -0.0159474460905123 -0.000652540309749108 0.00225484275025312 0.999997244933863 0.00415128199475847 2.72960843582894e-05 -1.00838152461839e-05 -1.21771778298918e-05 3.8447468806588e-06 2.32439887205036e-07 1.81659960399936e-05 -1.00838152461839e-05 8.21503307268742e-05 1.28678734927045e-05 2.95292805951734e-06 -1.64296054992365e-06 -4.6304123901678e-05 -1.21771778298918e-05 1.28678734927045e-05 2.01878451144106e-05 -8.55113854287736e-06 -5.4744609061229e-06 -6.35493807771117e-06 3.8447468806588e-06 2.95292805951734e-06 -8.55113854287736e-06 2.38397243541473e-05 -2.99245846310353e-06 -2.095486589731e-06 2.32439887205036e-07 -1.64296054992365e-06 -5.4744609061229e-06 -2.99245846310353e-06 4.97228768696379e-05 -2.0386426589377e-06 1.81659960399936e-05 -4.6304123901678e-05 -6.35493807771117e-06 -2.095486589731e-06 -2.0386426589377e-06 6.73059075321258e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1286 0 0 0 0 0 2797 +1125 1128 0.999971908915054 -0.000649122662944757 0.00746726325714363 0.00158791334755328 0.000614322852302077 0.999988945674682 0.0046616666409504 -0.0017197636345151 -0.00747020670505008 -0.00465694837921378 0.99996125367115 -0.00887232719636956 4.48188504574299e-05 -2.23229949085374e-05 -1.13754217489219e-05 3.8803092471482e-07 1.4152177050367e-06 4.73978858671593e-05 -2.23229949085374e-05 9.48224661679057e-05 1.30213650402334e-05 4.42812270523994e-06 5.48578525370233e-06 -7.01181653615103e-05 -1.13754217489219e-05 1.30213650402334e-05 1.82446590210502e-05 -7.85298676913564e-06 -7.99385846648528e-06 -7.62229994324833e-06 3.8803092471482e-07 4.42812270523994e-06 -7.85298676913564e-06 1.9633969461654e-05 1.0715994288925e-05 -5.10249629203111e-06 1.4152177050367e-06 5.48578525370233e-06 -7.99385846648528e-06 1.0715994288925e-05 3.40553163360269e-05 -5.35098192779234e-06 4.73978858671593e-05 -7.01181653615103e-05 -7.62229994324833e-06 -5.10249629203111e-06 -5.35098192779234e-06 0.00011974595028708 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1266 0 0 0 0 0 2697 +1125 1129 0.999990205356211 -4.46654307924293e-05 0.00442574249620512 0.00193880182848905 2.72110520966849e-05 0.999992222771673 0.00394381233431895 -0.00138516463682874 -0.00442588422827208 -0.00394365327697233 0.999982429419452 -0.00473913760770386 2.46796818960053e-05 -1.2268968019312e-06 -9.92282490255268e-06 4.12169307177423e-06 3.01060276012838e-06 1.10545628082789e-05 -1.2268968019312e-06 6.17290251734152e-05 1.06521221571544e-05 -4.31035524049999e-07 2.21421623210817e-07 -2.72519832175387e-05 -9.92282490255268e-06 1.06521221571544e-05 1.96829396945586e-05 -9.86909184746112e-06 -8.08870766643007e-06 -4.97617913869997e-06 4.12169307177423e-06 -4.31035524049999e-07 -9.86909184746112e-06 1.98295464769663e-05 8.59106865884651e-06 1.73366016395746e-06 3.01060276012838e-06 2.21421623210817e-07 -8.08870766643007e-06 8.59106865884651e-06 2.67582459394366e-05 8.84706328058687e-07 1.10545628082789e-05 -2.72519832175387e-05 -4.97617913869997e-06 1.73366016395746e-06 8.84706328058687e-07 4.41846967141135e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1359 0 0 0 0 0 2616 +1126 1128 0.999999966184042 -7.16188409708821e-05 -0.000250005312215165 9.54183276933771e-05 7.1812950321828e-05 0.999999695946603 0.000776498294192062 -7.41305325185955e-06 0.000249949624292355 -0.000776516221553094 0.999999667273816 0.000362763186996876 2.33566599753916e-05 -8.16431103917602e-06 -1.11991182850382e-05 2.95262170942841e-06 2.84446071857624e-06 9.28533370438206e-06 -8.16431103917602e-06 7.89445778301538e-05 1.47180293006793e-05 3.11273764177702e-06 -1.06100843578239e-05 -3.6203530105411e-05 -1.11991182850382e-05 1.47180293006793e-05 1.8972213761393e-05 -7.68132017045399e-06 -6.40894937537769e-06 -7.03440309763505e-06 2.95262170942841e-06 3.11273764177702e-06 -7.68132017045399e-06 1.78277836785067e-05 3.6788914511189e-06 -2.17221713698949e-06 2.84446071857624e-06 -1.06100843578239e-05 -6.40894937537769e-06 3.6788914511189e-06 3.63770126794988e-05 6.68694974420904e-06 9.28533370438206e-06 -3.6203530105411e-05 -7.03440309763505e-06 -2.17221713698949e-06 6.68694974420904e-06 3.95808729215292e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1286 0 0 0 0 0 2607 +1124 1126 0.999999339136486 2.4760201897092e-06 0.00114966101987433 0.000332355983772494 -2.09298132990776e-06 0.999999944494498 -0.000333176561544694 -0.00275036577112624 -0.00114966178101371 0.00033317393514141 0.999999283636202 -0.00191008552659427 5.76884385534081e-05 -1.84230561894964e-06 -7.09907839196578e-06 4.95303089075013e-06 -5.9263651683891e-06 5.21497848324497e-05 -1.84230561894964e-06 7.61122895186069e-05 9.43560021127632e-06 3.83584569845421e-06 -5.09352571060756e-07 -4.04812519140885e-05 -7.09907839196578e-06 9.43560021127632e-06 1.94412409858565e-05 -8.78079003506939e-06 -6.16507696830967e-06 -1.29260627135977e-06 4.95303089075013e-06 3.83584569845421e-06 -8.78079003506939e-06 2.23111015299163e-05 5.54725592028185e-06 -1.12404730754593e-07 -5.9263651683891e-06 -5.09352571060756e-07 -6.16507696830967e-06 5.54725592028185e-06 3.85405133783343e-05 -7.32067025351698e-06 5.21497848324497e-05 -4.04812519140885e-05 -1.29260627135977e-06 -1.12404730754593e-07 -7.32067025351698e-06 0.000118355932459112 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1260 0 0 0 0 0 2747 +1124 1128 0.999992636364411 -0.000119847947799587 0.00383573375302719 0.00134387684658234 0.000118706678247973 0.999999948623121 0.000297762457057784 -0.00320684552118465 -0.00383576924217857 -0.000297304937231093 0.999992599214662 -0.00371431010431241 5.03091462747243e-05 -7.46731107317848e-06 -9.47350957488942e-06 1.71673066704702e-06 -2.87433880835905e-08 4.73259586184997e-05 -7.46731107317848e-06 8.3963317570488e-05 1.5695601426857e-05 1.61229492098608e-06 4.27635972154831e-06 -4.2845277225494e-05 -9.47350957488942e-06 1.5695601426857e-05 2.32271125308141e-05 -9.20865270707518e-06 -9.14290423178603e-06 -3.62965255848673e-06 1.71673066704702e-06 1.61229492098608e-06 -9.20865270707518e-06 2.03103036365027e-05 9.37487787133208e-06 -2.57178013224071e-06 -2.87433880835905e-08 4.27635972154831e-06 -9.14290423178603e-06 9.37487787133208e-06 3.8657530465456e-05 -7.37773413468201e-06 4.73259586184997e-05 -4.2845277225494e-05 -3.62965255848673e-06 -2.57178013224071e-06 -7.37773413468201e-06 0.000110482251106446 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1268 0 0 0 0 0 2588 +1128 1130 0.999999080285756 0.000484770480305151 -0.00126665907938071 0.000528546106269901 -0.000485754542359543 0.999999580386904 -0.000776703638001803 -0.000172663607974573 0.00126628202487833 0.000777318209057833 0.999998896152508 -0.000543050363770538 2.46104787941186e-05 -2.04530792748514e-05 -1.51937333059455e-05 5.86594488296627e-06 2.06773858722108e-07 1.39472230805442e-05 -2.04530792748514e-05 9.3838988154126e-05 2.12643249344656e-05 -4.18923352790667e-06 1.73309012891016e-06 -5.4043894299043e-05 -1.51937333059455e-05 2.12643249344656e-05 2.32880156503587e-05 -1.06155446450947e-05 -6.31092796568624e-06 -1.11645708361847e-05 5.86594488296627e-06 -4.18923352790667e-06 -1.06155446450947e-05 2.15001180552587e-05 8.43371812008721e-06 -2.72462149885586e-06 2.06773858722108e-07 1.73309012891016e-06 -6.31092796568624e-06 8.43371812008721e-06 3.12020600533933e-05 -3.31235900930854e-06 1.39472230805442e-05 -5.4043894299043e-05 -1.11645708361847e-05 -2.72462149885586e-06 -3.31235900930854e-06 5.37732432698979e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1278 0 0 0 0 0 2699 +1126 1129 0.999984110663146 -0.000112033669200715 -0.00563612186656844 -0.00115755125738164 9.15852094329414e-05 0.999993413738173 -0.00362823544221705 -0.00144543205864446 0.00563649123012345 0.00362766160656038 0.999977534766597 0.00830839761950294 2.83937191679239e-05 -3.82362889557556e-06 -1.01122632754883e-05 3.46159293166648e-06 5.11266211048574e-06 1.90692898175142e-05 -3.82362889557556e-06 7.81191772836856e-05 5.51180892433535e-06 2.86816660677652e-06 8.48548562442519e-06 -3.98153309318916e-05 -1.01122632754883e-05 5.51180892433535e-06 1.78886944250382e-05 -7.66262031144812e-06 -5.22680968600515e-06 -6.47342889349588e-06 3.46159293166648e-06 2.86816660677652e-06 -7.66262031144812e-06 1.94528696564378e-05 6.58252260303766e-06 2.12840611126277e-06 5.11266211048574e-06 8.48548562442519e-06 -5.22680968600515e-06 6.58252260303766e-06 3.7743210967922e-05 -1.84325523047165e-06 1.90692898175142e-05 -3.98153309318916e-05 -6.47342889349588e-06 2.12840611126277e-06 -1.84325523047165e-06 6.41606236545377e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1371 0 0 0 0 0 2516 +1124 1127 0.999988248613143 1.31771125643534e-05 -0.00484793378479259 -0.000446627119605796 -2.76440644391433e-05 0.999995547202213 -0.00298409308705749 -0.00472459617587858 0.00484787287619325 0.00298419203641915 0.999983796231952 0.0130664404501578 8.28456914727278e-05 -7.23054791491612e-05 -7.38592365779203e-06 -1.1819431780141e-05 -1.28721017011952e-05 0.00013166198015366 -7.23054791491612e-05 0.000338879640593848 2.15892779357925e-06 6.11005797217495e-05 2.94169795324332e-05 -0.000515813168667912 -7.38592365779203e-06 2.15892779357925e-06 2.17034477182324e-05 -9.27710491172363e-06 -9.49298556443201e-06 -1.18505606701693e-05 -1.1819431780141e-05 6.11005797217495e-05 -9.27710491172363e-06 3.63134390849384e-05 1.08569823517742e-05 -0.000150248957105164 -1.28721017011952e-05 2.94169795324332e-05 -9.49298556443201e-06 1.08569823517742e-05 5.7501414055009e-05 5.34106267518106e-05 0.00013166198015366 -0.000515813168667912 -1.18505606701693e-05 -0.000150248957105164 5.34106267518106e-05 0.00253133891436293 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1261 0 0 0 0 0 2745 +1128 1132 0.999999391750023 -0.000107219964366021 0.00109772649787378 -0.00204778789701351 0.000107977779280942 0.999999755904013 -0.000690313489625574 0.00126304406403279 -0.00109765221453538 0.000690431599811908 0.999999159231557 -0.00147459571834689 4.38420027342133e-05 -2.51151669983266e-05 -1.15977938466411e-05 7.64488379257464e-07 -1.53255764315708e-06 4.97256765222652e-05 -2.51151669983266e-05 9.87963697579565e-05 1.12919324544986e-05 3.25331618726288e-06 1.00752492534368e-05 -7.43519693742242e-05 -1.15977938466411e-05 1.12919324544986e-05 1.94000037311362e-05 -7.65396015790469e-06 -6.31507410056322e-06 -9.36047833423206e-06 7.64488379257464e-07 3.25331618726288e-06 -7.65396015790469e-06 1.95885870214537e-05 8.28701393646169e-06 -4.36623953688465e-06 -1.53255764315708e-06 1.00752492534368e-05 -6.31507410056322e-06 8.28701393646169e-06 3.37098448052096e-05 -8.90065640990142e-06 4.97256765222652e-05 -7.43519693742242e-05 -9.36047833423206e-06 -4.36623953688465e-06 -8.90065640990142e-06 0.000122206605299863 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1354 0 0 0 0 0 2509 +1127 1129 0.999999648321418 -0.000836660737451225 5.79297079959058e-05 -0.000692584608225529 0.000836740393704285 0.999998685329949 -0.00138895784187656 0.000522038046997952 -5.67675453451805e-05 0.00138900582553652 0.999999033719664 0.00305330205466502 3.3209317701713e-05 -8.64738857714647e-06 -1.25631668593736e-05 2.68947398627073e-06 1.93834431663937e-06 1.55427388722783e-05 -8.64738857714647e-06 0.000119416758551941 1.57501880551747e-05 4.69203591287293e-06 1.56980328457978e-05 -6.70500498456504e-05 -1.25631668593736e-05 1.57501880551747e-05 2.36979173515035e-05 -9.65675419834994e-06 -3.68242374030103e-06 -8.69055123840028e-06 2.68947398627073e-06 4.69203591287293e-06 -9.65675419834994e-06 2.19859295221643e-05 7.49924077531858e-06 -3.22459643054109e-06 1.93834431663937e-06 1.56980328457978e-05 -3.68242374030103e-06 7.49924077531858e-06 3.84514136257788e-05 -1.00739049041063e-05 1.55427388722783e-05 -6.70500498456504e-05 -8.69055123840028e-06 -3.22459643054109e-06 -1.00739049041063e-05 7.45510539745208e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1367 0 0 0 0 0 2400 +1125 1127 0.999992457488113 0.000192999235377849 0.00387913884522172 0.00123344036164774 -0.000194170344403567 0.999999935690308 0.000301524887862564 -0.00142985545045409 -0.00387908040168269 -0.000302275827333079 0.999992430653633 -0.00495552291150031 5.02217878572507e-05 -2.49201859076495e-07 -8.75903372917164e-06 4.47683766589599e-06 5.71636512985499e-06 3.91177368724775e-05 -2.49201859076495e-07 7.78418609841875e-05 3.45691028779335e-06 6.0486678253306e-06 8.58362757853586e-06 -2.98220409114346e-05 -8.75903372917164e-06 3.45691028779335e-06 1.8177415359257e-05 -7.78646560035775e-06 -7.11768886909765e-06 -3.06899245758579e-08 4.47683766589599e-06 6.0486678253306e-06 -7.78646560035775e-06 1.98602239321723e-05 6.71681315468915e-06 3.77143932437359e-07 5.71636512985499e-06 8.58362757853586e-06 -7.11768886909765e-06 6.71681315468915e-06 3.45427337953456e-05 -2.8140602891578e-06 3.91177368724775e-05 -2.98220409114346e-05 -3.06899245758579e-08 3.77143932437359e-07 -2.8140602891578e-06 8.59767632847339e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1270 0 0 0 0 0 2677 +1129 1132 0.999997652873601 -0.000836487627507242 0.00199863346757 -0.00236444087711971 0.000840436606962819 0.999997694903054 -0.0019758175242145 0.0041897174164936 -0.00199697611361288 0.00197749261145107 0.999996050796889 0.00211150332832997 2.48568288248373e-05 -1.13788003065276e-05 -9.23763194557354e-06 2.30659815806043e-06 4.75473545913136e-06 1.60085114726592e-05 -1.13788003065276e-05 8.73609499675521e-05 1.01217036490005e-05 6.79722513385207e-06 1.30267886057388e-06 -4.60063016058763e-05 -9.23763194557354e-06 1.01217036490005e-05 1.89357043579762e-05 -8.04830775906365e-06 -6.09192580004459e-06 -4.43279693945946e-06 2.30659815806043e-06 6.79722513385207e-06 -8.04830775906365e-06 2.09449380193732e-05 4.27896177586498e-06 -4.22279694112404e-06 4.75473545913136e-06 1.30267886057388e-06 -6.09192580004459e-06 4.27896177586498e-06 3.64838867809145e-05 2.90017069673967e-06 1.60085114726592e-05 -4.60063016058763e-05 -4.43279693945946e-06 -4.22279694112404e-06 2.90017069673967e-06 6.11124655571766e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1382 0 0 0 0 0 2541 +1126 1130 0.999999930223272 0.000360406862906625 -9.82870510997275e-05 0.000527784468297133 -0.000360397624395034 0.999999930639082 9.39967239201214e-05 0.00161397281164008 9.8320921346839e-05 -9.39612949416124e-05 0.999999990752136 -0.000832206310783339 2.67910849243222e-05 -1.98828149130514e-05 -1.30805810742268e-05 2.55508540229377e-06 3.7098101195927e-07 1.56951553055939e-05 -1.98828149130514e-05 0.000107317475295312 1.76663714570228e-05 2.18027383961643e-06 5.35568754463939e-06 -5.87914384438073e-05 -1.30805810742268e-05 1.76663714570228e-05 1.94278051073075e-05 -7.27952269358481e-06 -5.6954232666608e-06 -1.04709590623329e-05 2.55508540229377e-06 2.18027383961643e-06 -7.27952269358481e-06 2.15461505119904e-05 1.02349746801708e-05 -2.33322694797215e-06 3.7098101195927e-07 5.35568754463939e-06 -5.6954232666608e-06 1.02349746801708e-05 3.11610176878288e-05 -4.18136157845332e-06 1.56951553055939e-05 -5.87914384438073e-05 -1.04709590623329e-05 -2.33322694797215e-06 -4.18136157845332e-06 5.76665451989473e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1285 0 0 0 0 0 2718 +1129 1131 0.999999670504022 -0.000320899023132375 0.000745664578503394 -0.00146486547850467 0.000323259509722193 0.999994930725338 -0.00316765321900881 0.00117532894498094 -0.000744644301701237 0.00316789321844588 0.999994704964691 0.00371680199269168 2.75563811634528e-05 1.3744087711104e-06 -1.10030144874549e-05 4.9891011609031e-06 -4.8654687324016e-08 7.46995259659639e-06 1.3744087711104e-06 6.40592757891042e-05 4.31815327170354e-06 4.47444892675237e-07 8.78633436845408e-06 -2.84872569877716e-05 -1.10030144874549e-05 4.31815327170354e-06 1.75064659978045e-05 -8.35551567080915e-06 -3.17868525907599e-06 -3.36266156904992e-06 4.9891011609031e-06 4.47444892675237e-07 -8.35551567080915e-06 1.81640483168387e-05 5.56528183501485e-06 2.08845693663462e-06 -4.8654687324016e-08 8.78633436845408e-06 -3.17868525907599e-06 5.56528183501485e-06 3.33359932297422e-05 -3.9297969081812e-06 7.46995259659639e-06 -2.84872569877716e-05 -3.36266156904992e-06 2.08845693663462e-06 -3.9297969081812e-06 4.26858534578561e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1376 0 0 0 0 0 2566 +1127 1130 0.999999609124615 -0.000328531604264169 0.000820863936767742 0.000139722334394813 0.000327827140642159 0.999999578023835 0.000858185013994716 0.00188580790203892 -0.000821145531282129 -0.000857915577074071 0.999999294850191 -0.0013309264451898 2.54810422078243e-05 -9.50442489127063e-06 -1.22629643846144e-05 3.33206606730324e-06 2.88423430825007e-06 7.91865037287405e-06 -9.50442489127063e-06 7.97539880261259e-05 1.62519527658671e-05 -8.33679047541443e-07 7.31891116977425e-07 -4.1298950635481e-05 -1.22629643846144e-05 1.62519527658671e-05 2.23021216597502e-05 -9.07937637283366e-06 -7.77870552486494e-06 -6.93099788523896e-06 3.33206606730324e-06 -8.33679047541443e-07 -9.07937637283366e-06 2.16284829143341e-05 7.00603771659473e-06 -3.75684039186444e-06 2.88423430825007e-06 7.31891116977425e-07 -7.77870552486494e-06 7.00603771659473e-06 3.76957388513104e-05 -3.26402330103306e-06 7.91865037287405e-06 -4.1298950635481e-05 -6.93099788523896e-06 -3.75684039186444e-06 -3.26402330103306e-06 4.93084651496878e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1274 0 0 0 0 0 2711 +1127 1131 0.999999553306888 -0.00083250171235728 -0.000447578957107338 -0.00148882305070715 0.0008334407886751 0.999997443382236 0.00210204791643291 -0.000232474861434717 0.000445827854329138 -0.00210242000802159 0.99999769053115 -0.000359886680394644 3.80438447547109e-05 -4.91460531118718e-06 -1.23372190635532e-05 4.19570371422119e-06 3.15785471647856e-06 2.75596503795506e-05 -4.91460531118718e-06 7.47511625175411e-05 5.46702820582616e-06 1.90729814341301e-06 -3.78618655501116e-07 -4.70036149368106e-05 -1.23372190635532e-05 5.46702820582616e-06 2.11602670961361e-05 -9.21760583836036e-06 -5.5034453801641e-06 -7.12186883110168e-06 4.19570371422119e-06 1.90729814341301e-06 -9.21760583836036e-06 2.18303283606581e-05 7.21000872897432e-06 1.36620110958028e-06 3.15785471647856e-06 -3.78618655501116e-07 -5.5034453801641e-06 7.21000872897432e-06 3.91151877574957e-05 3.97788536274725e-06 2.75596503795506e-05 -4.70036149368106e-05 -7.12186883110168e-06 1.36620110958028e-06 3.97788536274725e-06 7.82024805361402e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1343 0 0 0 0 0 2596 +1130 1132 0.999983749245125 -0.000544768292984633 -0.00567489851630028 -0.00265109942889825 0.000526651216923997 0.999994762088524 -0.00319349871020916 0.00379478952564274 0.00567660850852522 0.00319045812123489 0.999978798321653 0.00566179564079327 5.09949176760089e-05 -3.33008766504383e-05 -1.61232809984216e-05 4.00890830952959e-06 -9.97860478192942e-07 6.19133390422386e-05 -3.33008766504383e-05 0.000123877277395661 1.91922677972005e-05 5.36180241337636e-07 1.17267015842159e-05 -8.51884229791762e-05 -1.61232809984216e-05 1.91922677972005e-05 2.35207152877996e-05 -1.11239878279454e-05 -5.64840817983347e-06 -1.27053769009581e-05 4.00890830952959e-06 5.36180241337636e-07 -1.11239878279454e-05 2.21501736083476e-05 8.22163186070224e-06 -2.72461885720885e-06 -9.97860478192942e-07 1.17267015842159e-05 -5.64840817983347e-06 8.22163186070224e-06 3.30085911226685e-05 -5.12270366706749e-06 6.19133390422386e-05 -8.51884229791762e-05 -1.27053769009581e-05 -2.72461885720885e-06 -5.12270366706749e-06 0.000137289942943076 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1350 0 0 0 0 0 2455 +1128 1131 0.9999994742896 -0.000756377517639853 0.000692324760739503 -0.00116849807990079 0.000757524403219092 0.999998338907996 -0.00165781121594241 -0.000339712022335786 -0.000691069679592149 0.00165833479731502 0.999998386172897 0.00181848421381143 3.53825733154845e-05 -1.36588016306555e-06 -1.1240727537344e-05 3.98858478196678e-06 6.97150738110902e-06 2.99057205994209e-05 -1.36588016306555e-06 7.69513320527206e-05 4.90533311229057e-06 4.75063011943698e-06 5.0240279348296e-06 -3.4310936324293e-05 -1.1240727537344e-05 4.90533311229057e-06 2.0844633738024e-05 -8.75067632194611e-06 -1.08167824905812e-05 -5.47512068802999e-06 3.98858478196678e-06 4.75063011943698e-06 -8.75067632194611e-06 1.88218195628876e-05 9.72643566750398e-06 8.88114734538042e-07 6.97150738110902e-06 5.0240279348296e-06 -1.08167824905812e-05 9.72643566750398e-06 3.92246283803045e-05 7.53587097122867e-06 2.99057205994209e-05 -3.4310936324293e-05 -5.47512068802999e-06 8.88114734538042e-07 7.53587097122867e-06 8.11531886335875e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1355 0 0 0 0 0 2489 +1131 1133 0.999999795977591 -0.000459941233432992 -0.000443281894751516 -0.000750424245103342 0.000458915177537991 0.999997222001358 -0.00231200917518489 0.00315649532414129 0.000444344051666758 0.00231180527469378 0.999997229053529 0.00253839789651453 2.98788300250116e-05 -3.93564324092364e-06 -1.23168075353877e-05 4.57627594180714e-06 2.76878269419833e-06 1.48358677781216e-05 -3.93564324092364e-06 7.8900997109746e-05 6.65887687456523e-06 -1.05628834442589e-06 1.42658432433355e-05 -4.21639219658209e-05 -1.23168075353877e-05 6.65887687456523e-06 2.04502893980455e-05 -1.06319793158065e-05 -5.30263678817783e-06 -5.308332315504e-06 4.57627594180714e-06 -1.05628834442589e-06 -1.06319793158065e-05 2.13181773550107e-05 4.06799830099027e-06 -3.04264030371178e-07 2.76878269419833e-06 1.42658432433355e-05 -5.30263678817783e-06 4.06799830099027e-06 3.856820225405e-05 -2.25496824610863e-06 1.48358677781216e-05 -4.21639219658209e-05 -5.308332315504e-06 -3.04264030371178e-07 -2.25496824610863e-06 6.24966501206203e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1264 0 0 0 0 0 2522 +1131 1134 0.999999493266284 0.00030148967461579 0.00096050567535922 0.000458006651032481 -0.000299504579114434 0.999997820569175 -0.00206619309541454 0.0014109295290007 -0.000961126517887574 0.0020659043725568 0.999997404134101 -0.00753277484500539 3.08577270476655e-05 -7.38518421133102e-06 -9.77623241701098e-06 4.67467524213046e-06 -4.43501097740722e-07 1.91992379503787e-05 -7.38518421133102e-06 8.45313793329258e-05 9.3844766978404e-06 2.92397858823689e-07 1.53567586642264e-05 -2.40901910562972e-05 -9.77623241701098e-06 9.3844766978404e-06 1.77382440718221e-05 -5.56893930907611e-06 -4.91159252620708e-06 -5.31520547044264e-06 4.67467524213046e-06 2.92397858823689e-07 -5.56893930907611e-06 2.51431981017086e-05 -9.58210160752522e-06 3.2144170227555e-06 -4.43501097740722e-07 1.53567586642264e-05 -4.91159252620708e-06 -9.58210160752522e-06 7.54608429066026e-05 -1.49032674038403e-05 1.91992379503787e-05 -2.40901910562972e-05 -5.31520547044264e-06 3.2144170227555e-06 -1.49032674038403e-05 7.39823054116174e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1258 0 0 0 0 0 2721 +1130 1134 0.999998951267858 -7.19354795299263e-05 0.00144647449739181 -0.00113625010860316 6.79743247624319e-05 0.999996248397158 0.00273835189500144 0.00479591056018261 -0.00144666605545066 -0.00273825070007654 0.999995204558716 -0.0145148370910286 2.82417715154125e-05 -1.29819009272582e-05 -1.1619979426771e-05 4.9655493827675e-06 -1.12717874878408e-06 1.78207115146763e-05 -1.29819009272582e-05 9.41931059056942e-05 1.219907382968e-05 3.03229186809128e-06 6.39156325632508e-06 -3.8062568541378e-05 -1.1619979426771e-05 1.219907382968e-05 2.06321416331785e-05 -1.0189363027857e-05 -5.79040165849186e-06 -4.6274056687994e-06 4.9655493827675e-06 3.03229186809128e-06 -1.0189363027857e-05 2.89223734578308e-05 -1.36044433713379e-05 2.47738813969799e-06 -1.12717874878408e-06 6.39156325632508e-06 -5.79040165849186e-06 -1.36044433713379e-05 8.43759392313975e-05 -1.49920777594448e-05 1.78207115146763e-05 -3.8062568541378e-05 -4.6274056687994e-06 2.47738813969799e-06 -1.49920777594448e-05 7.17463230704247e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1262 0 0 0 0 0 2748 +1131 1135 0.999999889030457 8.77910367465724e-05 0.000462851819520939 0.00927321120593047 -8.86745611991915e-05 0.999998173551582 0.00190919625023502 -0.0201936089126979 -0.000462683363827805 -0.00190923708155438 0.999998070367074 -0.0104199830126995 2.8594302113386e-05 -9.91418303212724e-06 -1.02080663692908e-05 -3.87216650153324e-07 3.32804712945482e-06 1.73447206964566e-05 -9.91418303212724e-06 9.93777314202954e-05 1.72448872947322e-05 1.28884249114276e-05 -2.13988504458127e-05 -3.31130078019497e-05 -1.02080663692908e-05 1.72448872947322e-05 2.34296904111504e-05 -7.21652008780669e-06 -6.85821398825449e-06 -4.70690334907957e-06 -3.87216650153324e-07 1.28884249114276e-05 -7.21652008780669e-06 3.91836041995174e-05 -3.66120144959158e-05 2.07292022910269e-06 3.32804712945482e-06 -2.13988504458127e-05 -6.85821398825449e-06 -3.66120144959158e-05 0.00012234486746805 -1.11959108223599e-05 1.73447206964566e-05 -3.31130078019497e-05 -4.70690334907957e-06 2.07292022910269e-06 -1.11959108223599e-05 6.94296030004824e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1371 0 0 0 0 0 2609 +1132 1136 0.999998455745855 -8.65058438268706e-05 0.00175528420628677 0.0112897970538159 7.80564706385527e-05 0.999988413555917 0.00481317578199842 -0.0243823330256232 -0.00175568023661697 -0.00481303133794166 0.999986876072005 -0.00898350437726238 4.2194905611149e-05 7.38056931701239e-07 -1.05001376020088e-05 6.3103780529337e-06 -3.58685218414683e-06 3.83991048386686e-05 7.38056931701239e-07 7.41687749250956e-05 8.55791650499684e-06 4.29213538484614e-06 6.36803201006712e-06 -2.5315922624961e-05 -1.05001376020088e-05 8.55791650499684e-06 2.18037661314857e-05 -9.45905439558187e-06 -3.81794590863209e-06 -6.66126256252049e-06 6.3103780529337e-06 4.29213538484614e-06 -9.45905439558187e-06 3.82646230380541e-05 -2.9279336630236e-05 1.59663643641287e-05 -3.58685218414683e-06 6.36803201006712e-06 -3.81794590863209e-06 -2.9279336630236e-05 0.000111518703405599 -3.33838086964553e-05 3.83991048386686e-05 -2.5315922624961e-05 -6.66126256252049e-06 1.59663643641287e-05 -3.33838086964553e-05 0.00011224180189884 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1285 0 0 0 0 0 2687 +1132 1135 0.999988131100864 -0.000318943417182239 0.00486168000783724 0.0114678704816286 0.000311201672073575 0.999998682632672 0.00159307452399136 -0.020806238640648 -0.00486218170385135 -0.00159154265300299 0.999986913004897 -0.0174886416748003 2.91520017301121e-05 -5.04066971494961e-06 -1.04641568636213e-05 3.36021907000646e-06 4.77513905869305e-06 9.2512463075017e-06 -5.04066971494961e-06 8.77457487066968e-05 1.11492828422497e-05 1.86696070525896e-05 -3.78566759519127e-05 -8.61060184402122e-06 -1.04641568636213e-05 1.11492828422497e-05 2.10534807250703e-05 -7.74455295732184e-06 -6.9538704682822e-06 -8.10438147869319e-07 3.36021907000646e-06 1.86696070525896e-05 -7.74455295732184e-06 6.12104150365414e-05 -7.99629443059902e-05 1.20705378363479e-05 4.77513905869305e-06 -3.78566759519127e-05 -6.9538704682822e-06 -7.99629443059902e-05 0.000232563897875826 -1.74585546048291e-05 9.2512463075017e-06 -8.61060184402122e-06 -8.10438147869319e-07 1.20705378363479e-05 -1.74585546048291e-05 8.16533322181357e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1374 0 0 0 0 0 2606 +1130 1133 0.999996704066067 9.8829698913617e-05 0.0025655583588899 -0.000595429654769647 -0.000107559700065826 0.999994204492465 0.00340285356618666 0.00615653516257393 -0.0025652071871837 -0.00340311830129371 0.999990919207727 -0.00562480486363103 3.80577506185441e-05 -6.94778860052702e-06 -1.4562296569715e-05 5.85316837966838e-06 1.13485094282636e-06 1.70117815751224e-05 -6.94778860052702e-06 0.000107225514212157 1.14865299793975e-05 5.34217142368341e-06 1.3904288859661e-05 -5.30222461357008e-05 -1.4562296569715e-05 1.14865299793975e-05 2.07761844488269e-05 -7.73206499897673e-06 -6.40380087147134e-06 -9.07274835154872e-06 5.85316837966838e-06 5.34217142368341e-06 -7.73206499897673e-06 2.02111847644055e-05 9.52802532503503e-06 6.16214721237048e-07 1.13485094282636e-06 1.3904288859661e-05 -6.40380087147134e-06 9.52802532503503e-06 3.50138218889974e-05 -6.60928092811897e-06 1.70117815751224e-05 -5.30222461357008e-05 -9.07274835154872e-06 6.16214721237048e-07 -6.60928092811897e-06 6.39233356004301e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1268 0 0 0 0 0 2390 +1132 1134 0.99999671100467 -0.000149381683221571 0.00256040327996336 -0.00126621279100408 0.00015187562150698 0.99999951425106 -0.000973874447321125 0.00789328271235774 -0.002560256557246 0.000974260107092069 0.999996247944763 -0.00746521720128968 3.22856652909416e-05 -7.65134147462312e-06 -1.38215943358925e-05 1.77488697853303e-06 2.51509543887215e-06 2.11890249110716e-05 -7.65134147462312e-06 6.69495992873532e-05 8.03558854112444e-06 7.59155889717675e-06 -9.46973986858112e-06 -2.32243564574685e-05 -1.38215943358925e-05 8.03558854112444e-06 2.33146904062207e-05 -8.80920562940982e-06 -7.13220947226826e-06 -3.32381151979049e-06 1.77488697853303e-06 7.59155889717675e-06 -8.80920562940982e-06 2.7788231719894e-05 -5.17318971441989e-06 -1.95625246056769e-06 2.51509543887215e-06 -9.46973986858112e-06 -7.13220947226826e-06 -5.17318971441989e-06 5.03870906525218e-05 3.26659370314132e-06 2.11890249110716e-05 -2.32243564574685e-05 -3.32381151979049e-06 -1.95625246056769e-06 3.26659370314132e-06 7.52948951193983e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1269 0 0 0 0 0 2658 +1134 1136 0.999978345486236 0.000175162515550593 -0.00657859230413881 -0.0046949398864987 -0.000190320369535349 0.99999732868469 -0.00230356281456601 0.011948750113887 0.00657817123278714 0.00230476497215169 0.999975707565766 0.000340942100145852 2.91683749659133e-05 -3.0525845748547e-06 -9.97084610398101e-06 4.81098141061598e-07 6.05032788439955e-06 1.34789987079043e-05 -3.0525845748547e-06 8.06160954028553e-05 8.54488247085703e-06 4.78895439756464e-06 -6.59560811802159e-06 -2.64270486527776e-05 -9.97084610398101e-06 8.54488247085703e-06 1.86385884568973e-05 -7.4780277738974e-06 -6.93418156462545e-06 -2.15400995903518e-06 4.81098141061598e-07 4.78895439756464e-06 -7.4780277738974e-06 2.13368501690392e-05 2.66136187068267e-06 -3.33073990840856e-06 6.05032788439955e-06 -6.59560811802159e-06 -6.93418156462545e-06 2.66136187068267e-06 3.98483934835818e-05 4.07734221304638e-06 1.34789987079043e-05 -2.64270486527776e-05 -2.15400995903518e-06 -3.33073990840856e-06 4.07734221304638e-06 7.88355256240926e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1290 0 0 0 0 0 2451 +1133 1137 0.999964187876825 0.00144127201028835 -0.00833940638385365 -0.000923645481143331 -0.00142835441795901 0.999997771305299 0.00155473087431126 0.00705240396152969 0.00834162858795551 -0.00154276356814615 0.999964017909181 -0.011536721675131 2.64439581172498e-05 -5.87176867209562e-06 -1.0897857841898e-05 6.89859950104205e-06 -5.93470188161424e-06 1.19638293006333e-05 -5.87176867209562e-06 7.12085469466413e-05 1.10185511039699e-05 1.20998151286218e-06 -1.01198310489966e-05 -1.06559553746421e-05 -1.0897857841898e-05 1.10185511039699e-05 1.94387647905014e-05 -8.27002636623868e-06 -3.72680987832948e-06 -2.30293304063622e-06 6.89859950104205e-06 1.20998151286218e-06 -8.27002636623868e-06 5.57185192783651e-05 -8.43065581437379e-05 1.46105814922487e-05 -5.93470188161424e-06 -1.01198310489966e-05 -3.72680987832948e-06 -8.43065581437379e-05 0.000265663290996201 -3.32535365686365e-05 1.19638293006333e-05 -1.06559553746421e-05 -2.30293304063622e-06 1.46105814922487e-05 -3.32535365686365e-05 8.06757521864947e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1363 0 0 0 0 0 2601 +1133 1135 0.999993977723278 0.000148534236226978 -0.00346734116522928 -0.0025655680059375 -0.000133426718869859 0.999990499700579 0.00435691472230005 0.00847539150403826 0.0034679553754506 -0.00435642584779906 0.999984497299506 -0.0189438646582379 3.28462960549731e-05 -6.08238009480093e-06 -9.85988490000824e-06 2.11919020606602e-06 3.27282246554094e-06 2.23130989648946e-05 -6.08238009480093e-06 0.000108118076924691 1.53571027409978e-05 1.20114289899596e-05 3.25291413638176e-06 -1.63814710630171e-05 -9.85988490000824e-06 1.53571027409978e-05 2.18541046765183e-05 -6.65069044531494e-06 -5.12947310576019e-06 -1.98576799323832e-06 2.11919020606602e-06 1.20114289899596e-05 -6.65069044531494e-06 2.5276487924699e-05 5.48376723721004e-06 -1.2266867873224e-06 3.27282246554094e-06 3.25291413638176e-06 -5.12947310576019e-06 5.48376723721004e-06 4.32160469708472e-05 3.0925438784109e-06 2.23130989648946e-05 -1.63814710630171e-05 -1.98576799323832e-06 -1.2266867873224e-06 3.0925438784109e-06 9.44432451310418e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1342 0 0 0 0 0 2586 +1133 1136 0.999994453239038 0.000548422731156913 -0.00328522809930977 -0.000657959700581791 -0.000557229434237394 0.999996252515842 -0.00268038236655636 0.00707780011257211 0.0032837458053515 0.00268219812491121 0.999991011372955 -0.00921892084541305 3.23308617243444e-05 -5.90562895486197e-06 -9.79255941591259e-06 1.08770828924093e-06 4.16125048893053e-06 1.33219634737926e-05 -5.90562895486197e-06 8.17588580359264e-05 1.12427385572866e-05 4.07131188307948e-06 8.28190200426601e-06 -2.9347077821807e-06 -9.79255941591259e-06 1.12427385572866e-05 2.03487204243675e-05 -7.15586082760758e-06 -6.40107949411748e-06 3.12733189959794e-06 1.08770828924093e-06 4.07131188307948e-06 -7.15586082760758e-06 3.56847950738591e-05 -2.49116978733679e-05 6.67448531328912e-07 4.16125048893053e-06 8.28190200426601e-06 -6.40107949411748e-06 -2.49116978733679e-05 0.000128867147552545 -1.08458883595402e-05 1.33219634737926e-05 -2.9347077821807e-06 3.12733189959794e-06 6.67448531328912e-07 -1.08458883595402e-05 6.70647070125387e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1275 0 0 0 0 0 2626 +1135 1139 0.999997907125278 0.000453433124275603 -0.00199502969054171 -0.0058441390467243 -0.000448523262483161 0.999996871624287 0.00246080647798939 0.02292105484988 0.00199613926050883 -0.00245990651060417 0.999994982131416 -0.0063269858092496 2.80918323151097e-05 -1.35910699489256e-05 -1.53656364581534e-05 2.061047318062e-06 7.4943161902194e-06 1.19711704585903e-05 -1.35910699489256e-05 0.000134705796636582 2.46209519335659e-05 1.88865508130037e-05 -3.8462917932103e-05 -4.37036786094746e-05 -1.53656364581534e-05 2.46209519335659e-05 2.92636277179175e-05 -1.30645618140811e-05 -5.82938773192431e-06 -1.19772299247303e-05 2.061047318062e-06 1.88865508130037e-05 -1.30645618140811e-05 7.57560293723847e-05 -8.04616746535677e-05 -2.42272503090779e-06 7.4943161902194e-06 -3.8462917932103e-05 -5.82938773192431e-06 -8.04616746535677e-05 0.000194850965393906 5.12631283881736e-06 1.19711704585903e-05 -4.37036786094746e-05 -1.19772299247303e-05 -2.42272503090779e-06 5.12631283881736e-06 6.13075660386357e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1175 0 0 0 0 0 2592 +1134 1138 0.999976981127376 0.00025363095840738 -0.00678033087072091 -0.000597672194742249 -0.000253764109037389 0.999999967625591 -1.87774726464742e-05 0.00428655794634817 0.00678032588866333 2.04976450326104e-05 0.999977013116147 -0.00244507718983178 4.19099782822489e-05 -1.01086298143054e-05 -1.2579456117271e-05 1.41426146266483e-05 -1.83423927542271e-05 3.80270231045451e-05 -1.01086298143054e-05 8.77378432171284e-05 1.41122719577922e-05 -2.68903102348648e-07 1.4429954237787e-05 -2.68179407765431e-05 -1.2579456117271e-05 1.41122719577922e-05 2.13750991686861e-05 -8.68943960501864e-06 -5.31106859741618e-06 -5.45009418943114e-06 1.41426146266483e-05 -2.68903102348648e-07 -8.68943960501864e-06 4.88652274870004e-05 -5.47586488160817e-05 1.45809423043519e-05 -1.83423927542271e-05 1.4429954237787e-05 -5.31106859741618e-06 -5.47586488160817e-05 0.000175372502628841 -3.38322586681208e-05 3.80270231045451e-05 -2.68179407765431e-05 -5.45009418943114e-06 1.45809423043519e-05 -3.38322586681208e-05 0.000106494416574469 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1329 0 0 0 0 0 2458 +1138 1140 0.999978505025286 -0.000815416226913762 0.00650573468338242 -0.00170290682905976 0.00082570523446736 0.999998412484046 -0.00157899976354243 0.0116892867648973 -0.00650443681339534 0.00158433764216457 0.999977590836903 0.0045783519505711 3.10642932319249e-05 -1.10756558685369e-05 -9.49381986853585e-06 -2.59642043061358e-07 2.7933207233659e-06 2.75342996338513e-05 -1.10756558685369e-05 9.91609869929265e-05 1.37998919166642e-05 2.30960906034157e-06 -3.79631674398489e-06 -3.81105824463363e-05 -9.49381986853585e-06 1.37998919166642e-05 2.02050952692491e-05 -9.79083549801277e-06 -9.18013840254492e-06 -5.36760158284635e-06 -2.59642043061358e-07 2.30960906034157e-06 -9.79083549801277e-06 2.81883946945411e-05 6.38620666242438e-06 -3.35386836623018e-06 2.7933207233659e-06 -3.79631674398489e-06 -9.18013840254492e-06 6.38620666242438e-06 5.1285786680705e-05 3.20904422764587e-06 2.75342996338513e-05 -3.81105824463363e-05 -5.36760158284635e-06 -3.35386836623018e-06 3.20904422764587e-06 7.72098272821805e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1128 0 0 0 0 0 2691 +1135 1137 0.999998082257174 -0.000607794327872397 0.00186173790559376 -0.00969417910243348 0.000609769190951582 0.999999251888323 -0.00106037933201854 0.03181407682429 -0.0018610920202625 0.00106151252890015 0.999997704761187 0.00107248047746419 2.09235558478305e-05 -1.09521981157074e-06 -8.84891661939979e-06 2.82022688902827e-06 6.89284042481686e-06 1.33379395496292e-05 -1.09521981157074e-06 5.64706922392687e-05 9.8926130612555e-06 -3.3767771193163e-07 -1.24513151826026e-05 -1.96540843737655e-05 -8.84891661939979e-06 9.8926130612555e-06 1.90878511543085e-05 -8.57189306072979e-06 -7.38804662750948e-06 -3.52235758006022e-06 2.82022688902827e-06 -3.3767771193163e-07 -8.57189306072979e-06 2.83936723736989e-05 -1.76217834947089e-05 1.23658397321621e-06 6.89284042481686e-06 -1.24513151826026e-05 -7.38804662750948e-06 -1.76217834947089e-05 9.39433144206578e-05 4.27254115110866e-06 1.33379395496292e-05 -1.96540843737655e-05 -3.52235758006022e-06 1.23658397321621e-06 4.27254115110866e-06 4.89377807675345e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1381 0 0 0 0 0 2596 +1138 1141 0.999985846726112 -0.000886759261342054 0.00524595134104453 -0.00534846197356178 0.00087556309018506 0.999997335097772 0.00213616165800201 0.022861361855411 -0.00524783162223107 -0.00213153826295387 0.999983958275281 -0.00449378529292889 2.34592142556612e-05 -1.97975178691121e-05 -1.10733151555974e-05 1.80151663057147e-06 -1.89880265954248e-06 1.41451950555497e-05 -1.97975178691121e-05 0.000112901294565419 1.74347293846946e-05 4.46932865470002e-06 9.96711324684439e-06 -4.81024693810442e-05 -1.10733151555974e-05 1.74347293846946e-05 1.86973696679767e-05 -6.76231113641133e-06 -2.83911456401826e-06 -6.86466439352355e-06 1.80151663057147e-06 4.46932865470002e-06 -6.76231113641133e-06 2.84177022420472e-05 2.93497059690663e-07 1.72172080445814e-06 -1.89880265954248e-06 9.96711324684439e-06 -2.83911456401826e-06 2.93497059690663e-07 6.05423604326601e-05 -6.99141179964413e-06 1.41451950555497e-05 -4.81024693810442e-05 -6.86466439352355e-06 1.72172080445814e-06 -6.99141179964413e-06 5.00497807634051e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1319 0 0 0 0 0 2470 +1138 1142 0.999926609774896 -0.000455023366949535 0.0121065279010188 -0.00508617395620216 0.000386176110827292 0.999983745683528 0.00568851797502922 0.0284396157704165 -0.0121089195262848 -0.00568342524155409 0.999910532370486 -0.0134272507289301 4.02441322882259e-05 -2.8096810405061e-05 -1.27149266960025e-05 -1.94722671974393e-06 3.40157151529444e-06 3.77928036602936e-05 -2.8096810405061e-05 0.000155298193918895 2.10179828182983e-05 6.61111551978059e-06 6.88571423649789e-06 -7.58106492718378e-05 -1.27149266960025e-05 2.10179828182983e-05 2.16238569124333e-05 -8.55101659140771e-06 -6.70597690844179e-06 -9.73108693480856e-06 -1.94722671974393e-06 6.61111551978059e-06 -8.55101659140771e-06 3.15905585391405e-05 9.95070862040356e-07 -4.93397044026824e-06 3.40157151529444e-06 6.88571423649789e-06 -6.70597690844179e-06 9.95070862040356e-07 6.12384278973295e-05 -3.46204823615011e-06 3.77928036602936e-05 -7.58106492718378e-05 -9.73108693480856e-06 -4.93397044026824e-06 -3.46204823615011e-06 9.27205878097336e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1247 0 0 0 0 0 2589 +1139 1142 0.999999556976532 0.000522566741465762 0.000782924480072281 -0.00328889176136509 -0.000524631421830701 0.999996379532382 0.0026392582292004 0.0141099126984783 -0.000781542456946833 -0.00263966780673023 0.99999621066545 -0.00552931936908879 4.95833111138289e-05 -3.25429897970502e-05 -1.68156904883949e-05 7.61399382439228e-06 3.37922717002274e-06 5.93188611737537e-05 -3.25429897970502e-05 0.000164465123000303 1.57611928605637e-05 3.88156217120809e-06 2.13878137647247e-06 -0.000107323677776586 -1.68156904883949e-05 1.57611928605637e-05 2.45169152681943e-05 -1.35014198595205e-05 -1.20263115935151e-05 -1.20322280391912e-05 7.61399382439228e-06 3.88156217120809e-06 -1.35014198595205e-05 3.30477957196764e-05 8.62984010733284e-06 4.83001557191828e-06 3.37922717002274e-06 2.13878137647247e-06 -1.20263115935151e-05 8.62984010733284e-06 4.6973918130563e-05 -4.84465312919522e-06 5.93188611737537e-05 -0.000107323677776586 -1.20322280391912e-05 4.83001557191828e-06 -4.84465312919522e-06 0.000160533344727049 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1100 0 0 0 0 0 2586 +1139 1141 0.999989028710227 -0.000959735633818039 0.00458490639934776 -0.00493761749491262 0.000958377341678338 0.999999496222843 0.00029844083240943 0.0170867149927743 -0.0045851905138781 -0.000294043487721727 0.999989444727483 -0.00370362354270597 3.00652257292187e-05 -1.5217683892704e-05 -1.27198941053142e-05 5.7682649447811e-06 3.23010587111315e-06 1.31178707867879e-05 -1.5217683892704e-05 0.000106856740440861 2.03418719884536e-05 -1.04248677968257e-05 4.75570554446754e-06 -4.53668126242676e-05 -1.27198941053142e-05 2.03418719884536e-05 2.33779716937207e-05 -1.35664993805331e-05 -5.24431020238309e-06 -7.56727518753732e-06 5.7682649447811e-06 -1.04248677968257e-05 -1.35664993805331e-05 2.95382544133049e-05 -5.63288103492053e-06 6.86561076111958e-06 3.23010587111315e-06 4.75570554446754e-06 -5.24431020238309e-06 -5.63288103492053e-06 6.27709276562066e-05 -6.86837190362913e-07 1.31178707867879e-05 -4.53668126242676e-05 -7.56727518753732e-06 6.86561076111958e-06 -6.86837190362913e-07 4.96292398815996e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1185 0 0 0 0 0 2421 +1141 1143 0.999999762759036 0.000686187466040086 6.02381407867991e-05 -0.00182015145340828 -0.000686258164105039 0.999999066465576 0.00118157425006171 0.00846624888217728 -5.94273031118329e-05 -0.0011816153086598 0.999999300126584 -0.00406016368611687 5.36586948830265e-05 -4.20927383992108e-06 -1.26075501271907e-05 1.78901334829061e-06 8.56610414579384e-06 4.59817095114877e-05 -4.20927383992108e-06 0.000106768595121548 7.71292204913492e-06 7.01418126638839e-06 5.82123396793001e-06 -4.95906904416757e-05 -1.26075501271907e-05 7.71292204913492e-06 2.2748678778429e-05 -1.19807159324559e-05 -7.67562019417448e-06 -3.56641092994541e-06 1.78901334829061e-06 7.01418126638839e-06 -1.19807159324559e-05 2.67556161782653e-05 9.40983413594637e-06 -5.84957827203967e-06 8.56610414579384e-06 5.82123396793001e-06 -7.67562019417448e-06 9.40983413594637e-06 4.41699869706742e-05 7.27854316264569e-06 4.59817095114877e-05 -4.95906904416757e-05 -3.56641092994541e-06 -5.84957827203967e-06 7.27854316264569e-06 0.000112064594155892 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1237 0 0 0 0 0 2535 +1141 1145 0.99997693444709 0.000597618776623645 -0.00676560607770086 -0.00102182916154147 -0.000610897490038719 0.999997891065589 -0.00196078265762772 0.0131468916482249 0.00676442000894832 0.00196487052286304 0.999975190645133 -0.00507296831727095 2.8147511757333e-05 -1.96423703898797e-05 -9.70976526280634e-06 1.85409519730738e-06 1.94127037592131e-06 1.32155545451523e-05 -1.96423703898797e-05 0.000109654534543892 1.6507143934154e-05 5.30041602152247e-07 1.64364901920174e-06 -4.3117206496434e-05 -9.70976526280634e-06 1.6507143934154e-05 1.87104284491971e-05 -8.70115999802617e-06 -5.87740519165354e-06 -6.99623010177993e-06 1.85409519730738e-06 5.30041602152247e-07 -8.70115999802617e-06 2.59623693981529e-05 4.59295232205625e-06 -2.0142888387729e-06 1.94127037592131e-06 1.64364901920174e-06 -5.87740519165354e-06 4.59295232205625e-06 4.33421236220331e-05 3.72316978016271e-06 1.32155545451523e-05 -4.3117206496434e-05 -6.99623010177993e-06 -2.0142888387729e-06 3.72316978016271e-06 5.66537889441581e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1322 0 0 0 0 0 2613 +1142 1144 0.999997260296864 -0.00022356622199329 0.00233011092224987 -0.00143484467224706 0.000228748521208816 0.999997500684291 -0.00222402771712323 0.00728976556495373 -0.00232960788109272 0.00222455463337523 0.999994812128445 0.00396087318573857 2.70250242400483e-05 -8.73931307198221e-06 -9.27318561102825e-06 3.44952171961798e-06 1.28751533826397e-06 1.62579358556072e-05 -8.73931307198221e-06 0.000111314492189854 1.74872835768023e-05 -5.07970986554879e-06 1.14999728552595e-05 -4.92546850969031e-05 -9.27318561102825e-06 1.74872835768023e-05 2.17992504371155e-05 -1.14920372506873e-05 -6.42498812754761e-06 -6.84227581327507e-06 3.44952171961798e-06 -5.07970986554879e-06 -1.14920372506873e-05 2.72114819923169e-05 4.81366345935101e-06 4.81075038321665e-06 1.28751533826397e-06 1.14999728552595e-05 -6.42498812754761e-06 4.81366345935101e-06 4.48931477991515e-05 -5.19434858389634e-06 1.62579358556072e-05 -4.92546850969031e-05 -6.84227581327507e-06 4.81075038321665e-06 -5.19434858389634e-06 7.09297807223909e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1311 0 0 0 0 0 2646 +1142 1145 0.999791424384247 0.000942534213200183 -0.0204014547759544 -0.00324973790989964 -0.00106823440585039 0.999980509915524 -0.00615131403377115 0.008301803590732 0.0203952593259444 0.00617182455557994 0.999772945212403 0.00324993765525661 4.22409459370393e-05 -7.65035004606519e-06 -8.02835311739162e-06 1.33870338880493e-07 2.96498954780108e-06 2.67612956728637e-05 -7.65035004606519e-06 7.76711040390889e-05 8.85327121717201e-06 -2.698451945249e-07 6.15119928509352e-07 -4.07722004814794e-05 -8.02835311739162e-06 8.85327121717201e-06 1.93177361462459e-05 -6.8454910493959e-06 -7.62080363044982e-06 -3.34203939530427e-06 1.33870338880493e-07 -2.698451945249e-07 -6.8454910493959e-06 2.36135828435234e-05 5.65565574960578e-06 -5.79164775503218e-07 2.96498954780108e-06 6.15119928509352e-07 -7.62080363044982e-06 5.65565574960578e-06 4.72829729006945e-05 -1.5993531210453e-06 2.67612956728637e-05 -4.07722004814794e-05 -3.34203939530427e-06 -5.79164775503218e-07 -1.5993531210453e-06 8.45683574720927e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1330 0 0 0 0 0 2491 +1143 1097 0.999988248742591 -0.00120450352047796 -0.00469590757955075 -0.000149333453757771 0.00120928802763575 0.999998752518659 0.00101616120371285 -0.00925693247465108 0.00469467775174642 -0.00102182796735581 0.999988457867596 -0.00299873326281077 3.16930903423902e-05 -2.39452471742595e-05 -1.30834468051691e-05 5.28500412171266e-06 2.30105096332907e-06 2.07255452737006e-05 -2.39452471742595e-05 0.000115099328355584 2.09613295666251e-05 -7.60648090077015e-06 -1.75888532099397e-05 -5.99038173102077e-05 -1.30834468051691e-05 2.09613295666251e-05 2.36803007961835e-05 -1.51035208688167e-05 -1.00598220518763e-05 -1.00325201718552e-05 5.28500412171266e-06 -7.60648090077015e-06 -1.51035208688167e-05 3.87042492235758e-05 6.42500508545769e-06 7.32892172240673e-06 2.30105096332907e-06 -1.75888532099397e-05 -1.00598220518763e-05 6.42500508545769e-06 7.96705061794221e-05 7.66998478386464e-07 2.07255452737006e-05 -5.99038173102077e-05 -1.00325201718552e-05 7.32892172240673e-06 7.66998478386464e-07 7.46349147684591e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 862 0 0 0 0 0 2686 +1139 1143 0.999991710559801 -7.33934354865804e-05 0.00407104717329953 -0.00405846517754839 5.21512578940334e-05 0.999986386212521 0.0052177265038743 0.0198613689749502 -0.00407137469780204 -0.00521747094161144 0.999978100712732 -0.009674682828476 4.14667530056808e-05 6.03503111173816e-06 -8.95510247096036e-06 5.82303842778693e-06 1.68333623079979e-07 3.31874076037531e-05 6.03503111173816e-06 0.000104986587532432 1.55827365196759e-05 -1.69403452859032e-06 1.90544368849222e-06 -1.65052545028434e-05 -8.95510247096036e-06 1.55827365196759e-05 2.06774760847248e-05 -9.63622653718481e-06 -6.2156985732871e-06 -3.63138903967741e-06 5.82303842778693e-06 -1.69403452859032e-06 -9.63622653718481e-06 3.17212741951396e-05 4.67748734273888e-06 9.5560504410622e-06 1.68333623079979e-07 1.90544368849222e-06 -6.2156985732871e-06 4.67748734273888e-06 4.96336808142408e-05 -9.70438590370137e-06 3.31874076037531e-05 -1.65052545028434e-05 -3.63138903967741e-06 9.5560504410622e-06 -9.70438590370137e-06 8.65700152706184e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1111 0 0 0 0 0 2663 +1143 1146 0.999285217085187 0.00449592297007255 -0.0375345386498514 -0.0023219378197746 -0.00430936665850274 0.999977964789828 0.00504968254416406 0.011420854323178 0.0375564145521454 -0.00488432302795632 0.999282572205953 -0.0119590209977633 3.416550720261e-05 1.36610820914253e-05 -7.21156868674376e-06 3.76799361345626e-06 7.13283933172599e-06 1.57295758457242e-05 1.36610820914253e-05 4.59724440567053e-05 -1.90766082448785e-06 5.61401379447858e-06 -2.0627943414866e-06 -1.08776705837767e-05 -7.21156868674376e-06 -1.90766082448785e-06 1.32124602022758e-05 -2.93512940836588e-06 -9.00694699891829e-07 -1.71507175468796e-06 3.76799361345626e-06 5.61401379447858e-06 -2.93512940836588e-06 2.44850771440996e-05 -6.93482179039985e-06 1.38318703064747e-06 7.13283933172599e-06 -2.0627943414866e-06 -9.00694699891829e-07 -6.93482179039985e-06 5.96899956438001e-05 7.96400974382004e-06 1.57295758457242e-05 -1.08776705837767e-05 -1.71507175468796e-06 1.38318703064747e-06 7.96400974382004e-06 6.15742770504462e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1370 0 0 0 0 0 2477 +1140 1144 0.999998647390981 -9.0933841611517e-05 -0.00164223848571298 -0.00413540360693625 9.23224115676309e-05 0.999999638320946 0.000845478888074199 0.00756729059241939 0.00164216100910642 -0.0008456293598892 0.999998294107648 0.000990912494521552 3.82660126262898e-05 1.25225190852671e-05 -2.35377456924915e-06 3.8446256115393e-06 7.28126486706434e-07 2.93717374705904e-05 1.25225190852671e-05 7.02278609983026e-05 1.52878259498768e-05 -9.67959036489641e-06 2.35416011650133e-06 -1.25866021571532e-05 -2.35377456924915e-06 1.52878259498768e-05 2.09135286965659e-05 -1.22260129375217e-05 -6.54678876368077e-06 1.07806614384318e-06 3.8446256115393e-06 -9.67959036489641e-06 -1.22260129375217e-05 2.97167617895952e-05 1.27698293691649e-06 5.44115591984851e-06 7.28126486706434e-07 2.35416011650133e-06 -6.54678876368077e-06 1.27698293691649e-06 6.64866978911364e-05 -7.53658979685044e-06 2.93717374705904e-05 -1.25866021571532e-05 1.07806614384318e-06 5.44115591984851e-06 -7.53658979685044e-06 9.67360137156198e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1133 0 0 0 0 0 2662 +1140 1142 0.999996501646524 -0.000442518728448482 0.00260784813378742 -0.00257050358710389 0.000446036489792367 0.999998991317653 -0.00134848623501043 0.0112522688309513 -0.00260724877288299 0.00134964471295643 0.999995690347206 0.0023002079444101 2.4957043214916e-05 -5.09730827413105e-06 -9.27758661451542e-06 3.07184836692964e-06 3.51544555373085e-06 1.48386313119083e-05 -5.09730827413105e-06 7.56942584256095e-05 1.04810619596167e-05 -6.52263726364755e-06 -3.71840875237271e-06 -2.75048115167266e-05 -9.27758661451542e-06 1.04810619596167e-05 1.90739295971124e-05 -9.66395845151492e-06 -6.75602535235859e-06 -4.73011796191015e-06 3.07184836692964e-06 -6.52263726364755e-06 -9.66395845151492e-06 2.78505502139139e-05 -3.52518712735481e-07 1.00246612706561e-05 3.51544555373085e-06 -3.71840875237271e-06 -6.75602535235859e-06 -3.52518712735481e-07 5.73483362292121e-05 1.98695197121957e-06 1.48386313119083e-05 -2.75048115167266e-05 -4.73011796191015e-06 1.00246612706561e-05 1.98695197121957e-06 5.98102687289579e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1099 0 0 0 0 0 2608 +1140 1143 0.999997908630263 -0.000639643901817773 0.00194257323632359 -0.00352754694895486 0.000641411108488519 0.999999380938918 -0.000909237905981573 0.00945783461294744 -0.00194199044527024 0.000910481992481763 0.99999769984518 0.000153471298485055 2.92495088324858e-05 2.82087933183748e-06 -9.82257305451924e-06 4.86483709461799e-06 3.48596909057932e-06 1.22693475116018e-05 2.82087933183748e-06 7.67607877805151e-05 8.58192549981653e-06 -2.04998295507723e-06 -1.92426480330131e-06 -3.39820278958882e-05 -9.82257305451924e-06 8.58192549981653e-06 1.90354620811403e-05 -9.77117256498701e-06 -8.00423628138492e-06 -5.41339163846216e-06 4.86483709461799e-06 -2.04998295507723e-06 -9.77117256498701e-06 2.74889932708532e-05 -2.14953524458934e-06 7.03270150950407e-06 3.48596909057932e-06 -1.92426480330131e-06 -8.00423628138492e-06 -2.14953524458934e-06 7.33181885299442e-05 4.32682892140354e-06 1.22693475116018e-05 -3.39820278958882e-05 -5.41339163846216e-06 7.03270150950407e-06 4.32682892140354e-06 6.96365118050237e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1114 0 0 0 0 0 2650 +1143 1145 0.999876111471308 0.00123819101176648 -0.0156916726971486 -0.00138746579451349 -0.00128247719507564 0.999995222467555 -0.00281252454380678 0.00676992636913737 0.0156881152870627 0.00283230031666582 0.99987292248248 -0.00209565078420521 4.13874968111522e-05 -1.53177969542399e-05 -9.36958107489145e-06 2.59476182249903e-06 -3.26884368190559e-06 3.3514560033603e-05 -1.53177969542399e-05 0.000108173729596868 1.22926026249376e-05 3.79398803882639e-06 -1.59729334118012e-06 -5.62161239932748e-05 -9.36958107489145e-06 1.22926026249376e-05 1.65417996280668e-05 -5.83637594859252e-06 -4.11195079502535e-06 -3.62181263662027e-06 2.59476182249903e-06 3.79398803882639e-06 -5.83637594859252e-06 2.66747305006901e-05 5.511406375499e-06 -3.53416378467952e-06 -3.26884368190559e-06 -1.59729334118012e-06 -4.11195079502535e-06 5.511406375499e-06 4.98481035072991e-05 -7.61731474060091e-06 3.3514560033603e-05 -5.62161239932748e-05 -3.62181263662027e-06 -3.53416378467952e-06 -7.61731474060091e-06 0.000107004620935841 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1331 0 0 0 0 0 2610 +1144 1118 0.999973581258154 0.000959635724863407 -0.00720526786579808 0.00317122087989326 -0.000965545403186913 0.999999200316502 -0.000816754816506724 -0.0106906228473691 0.0072044783167639 0.000823690252138626 0.999973708167646 0.0023099969808759 2.83872496886589e-05 -2.28193996522883e-05 -1.27705750065946e-05 7.48854196010966e-07 2.46590836988021e-06 1.32778895543167e-05 -2.28193996522883e-05 0.000119502082390918 1.86414775921283e-05 4.836288105846e-06 2.19226521626433e-06 -5.56433371558144e-05 -1.27705750065946e-05 1.86414775921283e-05 1.99035948646778e-05 -8.11608308318254e-06 -7.60960893428512e-06 -8.41089411888404e-06 7.48854196010966e-07 4.836288105846e-06 -8.11608308318254e-06 2.10016642350778e-05 4.27628754420523e-06 -2.42647269640934e-06 2.46590836988021e-06 2.19226521626433e-06 -7.60960893428512e-06 4.27628754420523e-06 3.95876202152036e-05 -2.31584975837496e-06 1.32778895543167e-05 -5.56433371558144e-05 -8.41089411888404e-06 -2.42647269640934e-06 -2.31584975837496e-06 5.27633509070571e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1191 0 0 0 0 0 2562 +1145 1116 0.999906323654936 -0.00178066038637585 0.0135710413549642 0.00880245962467999 0.00171599740957239 0.999987127604328 0.00477493230688399 -0.0292069354843926 -0.0135793691959567 -0.00475119713686723 0.999896508073714 -0.00823873677868631 2.91424826810181e-05 1.43323127999849e-05 2.02292015114617e-07 -4.59925769827417e-06 -3.35944744291288e-06 2.84832524056458e-06 1.43323127999849e-05 6.93994166134017e-05 1.25307914774947e-05 -2.34865540042155e-06 3.90628432196048e-07 -1.13828304896099e-05 2.02292015114617e-07 1.25307914774947e-05 1.67145985281147e-05 -4.69375242733401e-06 -5.54581399994435e-06 2.38332134774382e-06 -4.59925769827417e-06 -2.34865540042155e-06 -4.69375242733401e-06 3.04876398284374e-05 -1.59650734291451e-05 -2.336282398032e-06 -3.35944744291288e-06 3.90628432196048e-07 -5.54581399994435e-06 -1.59650734291451e-05 0.000103050464842972 1.67939242338213e-06 2.84832524056458e-06 -1.13828304896099e-05 2.38332134774382e-06 -2.336282398032e-06 1.67939242338213e-06 4.98802442080792e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1100 0 0 0 0 0 2681 +1141 1144 0.999992440981373 0.00109255465938901 0.00373152843107242 0.000221872478451616 -0.00111057183235817 0.999987720197725 0.0048297084757845 0.00965519397985377 -0.00372620588814239 -0.00483381609829536 0.999981374632351 -0.00676211565004753 2.2211464830137e-05 -3.11122993997756e-06 -8.02632054166986e-06 2.68916912319611e-06 2.2952287033832e-06 8.02836373324422e-06 -3.11122993997756e-06 7.22859512000974e-05 1.38256516085946e-05 -2.31258461754083e-06 1.93999462412826e-06 -2.66735202456475e-05 -8.02632054166986e-06 1.38256516085946e-05 1.8688941069728e-05 -1.01464083133644e-05 -7.45699497060993e-06 -5.15629550158666e-06 2.68916912319611e-06 -2.31258461754083e-06 -1.01464083133644e-05 2.33327616865399e-05 6.71724082758249e-06 2.86309885608015e-06 2.2952287033832e-06 1.93999462412826e-06 -7.45699497060993e-06 6.71724082758249e-06 3.90871487323736e-05 -1.00671732103788e-06 8.02836373324422e-06 -2.66735202456475e-05 -5.15629550158666e-06 2.86309885608015e-06 -1.00671732103788e-06 4.32094933951967e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1285 0 0 0 0 0 2711 +1143 1096 0.999963197525622 -0.000589723854494398 -0.00855896139199771 0.00206869081013198 0.000603144118868201 0.999998592741185 0.00156548165814158 -0.00931709051824333 0.00855802614544626 -0.00157058633177017 0.999962146007072 -0.00463680255372228 2.8537638138094e-05 -1.50069280047561e-05 -1.25967718413536e-05 2.36768749552861e-06 9.76185703571057e-06 1.33280130987249e-05 -1.50069280047561e-05 0.000132058483420051 2.13950767968025e-05 -2.05333958922166e-06 -9.7239814050786e-06 -5.922102814227e-05 -1.25967718413536e-05 2.13950767968025e-05 2.37039205059572e-05 -1.51172872362235e-05 -7.34775164908348e-06 -1.05866858019262e-05 2.36768749552861e-06 -2.05333958922166e-06 -1.51172872362235e-05 4.10580613986168e-05 -7.74544105255815e-06 1.58287319624381e-06 9.76185703571057e-06 -9.7239814050786e-06 -7.34775164908348e-06 -7.74544105255815e-06 9.34144559236208e-05 2.47824828243157e-05 1.33280130987249e-05 -5.922102814227e-05 -1.05866858019262e-05 1.58287319624381e-06 2.47824828243157e-05 6.5914601733901e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 864 0 0 0 0 0 2477 +1142 1146 0.999235798865728 0.00459436967669234 -0.0388163629471517 -0.00272492209719634 -0.004423847786282 0.999980189280552 0.00447779155338171 0.00924381436502282 0.0388361665968067 -0.00430265193870231 0.999236328077777 -0.0147317306506397 2.67517405325423e-05 1.26983415238674e-05 -5.32188570893179e-06 2.12791211729248e-06 2.78628208527038e-06 1.65671166392724e-05 1.26983415238674e-05 5.31106161342531e-05 -1.19872492575354e-06 4.17519686723048e-06 2.75836574234945e-06 -3.01163327054124e-06 -5.32188570893179e-06 -1.19872492575354e-06 1.27002212450074e-05 -2.87861223034902e-06 -1.65773696633061e-06 -2.62739792393664e-06 2.12791211729248e-06 4.17519686723048e-06 -2.87861223034902e-06 2.30156911444852e-05 -1.25030341200662e-06 3.07800905804494e-06 2.78628208527038e-06 2.75836574234945e-06 -1.65773696633061e-06 -1.25030341200662e-06 5.0459715504008e-05 7.41139389019509e-06 1.65671166392724e-05 -3.01163327054124e-06 -2.62739792393664e-06 3.07800905804494e-06 7.41139389019509e-06 6.45113149016671e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1369 0 0 0 0 0 2536 +1144 1146 0.999353793641883 0.00433340730329281 -0.0356821624165403 -0.00381966021413145 -0.00413790993781257 0.999976032421877 0.00555088129472456 0.0122064145208184 0.0357053614310673 -0.00539964470547271 0.999347772800906 -0.0132536261265189 2.43619273974064e-05 1.51866588940564e-05 -4.56272446590251e-06 2.48848878648458e-06 3.22784237911281e-08 6.73402557608731e-08 1.51866588940564e-05 3.95271692920259e-05 -4.13328974208269e-07 8.67031360786217e-07 4.04344194920984e-06 -6.59609314995133e-06 -4.56272446590251e-06 -4.13328974208269e-07 1.23141770229119e-05 -2.8833850065968e-06 -5.32967396020318e-08 -9.49401113847557e-07 2.48848878648458e-06 8.67031360786217e-07 -2.8833850065968e-06 2.61688013725017e-05 -1.16707850346149e-05 -2.78867806079304e-07 3.22784237911281e-08 4.04344194920984e-06 -5.32967396020318e-08 -1.16707850346149e-05 6.11606385258823e-05 8.29696535368557e-06 6.73402557608731e-08 -6.59609314995133e-06 -9.49401113847557e-07 -2.78867806079304e-07 8.29696535368557e-06 3.99334013710114e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1382 0 0 0 0 0 2573 +1145 1098 0.999952231271657 -0.00114505368477596 0.00970690614427603 0.00270194190946559 0.00110808999383684 0.999992118451825 0.00381250190773324 -0.0091130108204617 -0.00971119515818529 -0.00380156366379572 0.999945618922504 -0.00535791507340785 2.4978825887881e-05 -2.11805491271254e-05 -1.25296265753983e-05 5.878171075792e-06 -8.94761635440064e-06 1.18656280872662e-05 -2.11805491271254e-05 0.000102764608782726 1.90161948785085e-05 -1.51594298927824e-05 1.77620871945733e-05 -4.22924954523977e-05 -1.25296265753983e-05 1.90161948785085e-05 1.96329138023095e-05 -6.23323389323868e-06 -8.72945859081808e-07 -7.27072916058087e-06 5.878171075792e-06 -1.51594298927824e-05 -6.23323389323868e-06 2.93972975154365e-05 -1.29500546278084e-05 5.14604192505846e-06 -8.94761635440064e-06 1.77620871945733e-05 -8.72945859081808e-07 -1.29500546278084e-05 0.000108073608507181 -1.17959951947497e-05 1.18656280872662e-05 -4.22924954523977e-05 -7.27072916058087e-06 5.14604192505846e-06 -1.17959951947497e-05 4.71701670618717e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 845 0 0 0 0 0 2602 +1144 1097 0.999944261031029 0.000129212126804619 -0.0105573735055249 0.00201429830765506 -0.000145825670901599 0.999998752376684 -0.00157288904515942 -0.0109768230005045 0.0105571570975608 0.00157434091002013 0.9999430323197 0.00508080376668767 3.18163200689521e-05 -1.62150262507291e-05 -1.24519972441123e-05 4.07900489636368e-06 9.95239459228894e-06 1.06115568093521e-05 -1.62150262507291e-05 0.000127641184195732 2.5698353626884e-05 -9.69487139196875e-06 -1.51935174986576e-05 -6.22045268295353e-05 -1.24519972441123e-05 2.5698353626884e-05 2.45604404105114e-05 -1.47688312554515e-05 -1.1743961324188e-05 -1.15686900686321e-05 4.07900489636368e-06 -9.69487139196875e-06 -1.47688312554515e-05 3.71866462226208e-05 -6.25316986131561e-06 6.38138777655739e-06 9.95239459228894e-06 -1.51935174986576e-05 -1.1743961324188e-05 -6.25316986131561e-06 9.9586815342266e-05 1.20601444512355e-06 1.06115568093521e-05 -6.22045268295353e-05 -1.15686900686321e-05 6.38138777655739e-06 1.20601444512355e-06 6.04433016520078e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 871 0 0 0 0 0 2640 +1145 1118 0.999900036120265 -0.000624696906834221 0.0141254210721911 0.0036238460074866 0.000576156459214536 0.999993916523002 0.00344019777372068 -0.0102102954923905 -0.0141274842214251 -0.0034317154256143 0.999894313174553 -0.00505786693757063 2.69493253752565e-05 1.77123834812276e-06 -7.59641167197556e-06 8.65717164288369e-07 1.5532001694995e-06 7.83630292580304e-06 1.77123834812276e-06 7.13540832438233e-05 9.61276582843183e-06 1.78295113564647e-06 1.72649169185067e-06 -2.85461010513704e-05 -7.59641167197556e-06 9.61276582843183e-06 1.69253261824614e-05 -5.55092653263943e-06 -3.97174925217353e-06 -3.04508883356185e-06 8.65717164288369e-07 1.78295113564647e-06 -5.55092653263943e-06 2.66280030076611e-05 -1.90413108329341e-06 -8.19902020887176e-07 1.5532001694995e-06 1.72649169185067e-06 -3.97174925217353e-06 -1.90413108329341e-06 6.83477218174765e-05 1.44940601876226e-06 7.83630292580304e-06 -2.85461010513704e-05 -3.04508883356185e-06 -8.19902020887176e-07 1.44940601876226e-06 5.04477786866447e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1144 0 0 0 0 0 2595 +1145 1117 0.999872697168006 -0.00129329061925294 0.0159033599390437 0.00938778858585378 0.00120756756534169 0.99998469795484 0.00539866990496162 -0.0239948607977679 -0.0159100986342562 -0.00537877825735137 0.999858958806644 -0.00546304135765115 2.89476145097587e-05 2.59721563133167e-06 -3.77129333959773e-06 -2.87885911298953e-06 -9.62364295155154e-07 5.17885790314072e-06 2.59721563133167e-06 7.81638863598278e-05 1.32623165244206e-05 -1.38010429152205e-06 -1.04914508296135e-06 -2.99383199247054e-05 -3.77129333959773e-06 1.32623165244206e-05 1.74831117969683e-05 -6.15671975685536e-06 -3.15228929454455e-06 -1.73670954284216e-06 -2.87885911298953e-06 -1.38010429152205e-06 -6.15671975685536e-06 2.79352913545006e-05 -7.54950009392128e-06 -3.53565049281392e-06 -9.62364295155154e-07 -1.04914508296135e-06 -3.15228929454455e-06 -7.54950009392128e-06 6.99929817576852e-05 -1.70305460237296e-07 5.17885790314072e-06 -2.99383199247054e-05 -1.73670954284216e-06 -3.53565049281392e-06 -1.70305460237296e-07 5.26857607876463e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1098 0 0 0 0 0 2536 +1145 1097 0.999929484670877 -0.00123982044503941 0.011810526283726 0.0020874614970503 0.00119664474204734 0.999992578642814 0.00366206235018717 -0.00641384501078887 -0.0118149789333647 -0.00364767111447705 0.999923547461627 -0.00471925209917164 5.04651349797469e-05 -1.65107059584554e-05 -1.29120306274786e-05 -1.48162495398003e-06 1.66542218571548e-05 1.39461580154523e-05 -1.65107059584554e-05 0.000140769369434142 2.84576358127376e-05 -1.13991260806043e-05 -1.26911374490992e-05 -6.12276059522207e-05 -1.29120306274786e-05 2.84576358127376e-05 2.36890763693222e-05 -1.03378616402967e-05 -1.11397931724055e-05 -1.12745984100399e-05 -1.48162495398003e-06 -1.13991260806043e-05 -1.03378616402967e-05 3.1498269758192e-05 -7.77320090501447e-06 2.13203730741415e-06 1.66542218571548e-05 -1.26911374490992e-05 -1.11397931724055e-05 -7.77320090501447e-06 0.000102399657589113 7.25278856806753e-06 1.39461580154523e-05 -6.12276059522207e-05 -1.12745984100399e-05 2.13203730741415e-06 7.25278856806753e-06 5.82534654949806e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 853 0 0 0 0 0 2626 +1146 1099 0.999313089995743 -0.00458542051209911 0.0367739320971585 0.00161692811588971 0.0047599530101501 0.999977813624783 -0.00465994694599925 -0.00456270499420141 -0.0367517484005913 0.00483178817060366 0.999312745246739 0.00283683841405787 2.3406498645146e-05 5.0856501364438e-06 -4.25779098058595e-06 1.0328871832276e-06 6.61733677592809e-06 1.28350833136429e-06 5.0856501364438e-06 6.39265439558736e-05 7.38795740132424e-06 8.77042236736049e-06 -1.2482809581517e-05 -1.23147172459487e-05 -4.25779098058595e-06 7.38795740132424e-06 1.70756461236684e-05 -5.40446542038478e-06 -5.00654464371098e-06 -2.72929120765235e-06 1.0328871832276e-06 8.77042236736049e-06 -5.40446542038478e-06 4.52435783628906e-05 -2.57005708096258e-05 -7.88626378566863e-07 6.61733677592809e-06 -1.2482809581517e-05 -5.00654464371098e-06 -2.57005708096258e-05 0.00013845973864919 4.94648414735947e-06 1.28350833136429e-06 -1.23147172459487e-05 -2.72929120765235e-06 -7.88626378566863e-07 4.94648414735947e-06 4.89011855560385e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 723 0 0 0 0 0 2599 +1145 1119 0.999889335021428 -0.00102425875792449 0.0148414488646913 0.00480126498456085 0.000922466435526177 0.999976017853321 0.00686387455373176 -0.0113621262583787 -0.0148481233185127 -0.00684942422476909 0.999866300373059 -0.00638526632652582 2.76987388527341e-05 -2.04256869954988e-06 -7.16542724765738e-06 3.42237503229734e-06 -5.11901007707341e-07 6.18419061920219e-06 -2.04256869954988e-06 6.66308736289999e-05 1.04325687018092e-05 -2.08576174900811e-06 3.6724067285668e-07 -2.23640583820508e-05 -7.16542724765738e-06 1.04325687018092e-05 1.72680384825351e-05 -6.05133262417635e-06 -3.06759722523356e-06 -3.03310460048339e-06 3.42237503229734e-06 -2.08576174900811e-06 -6.05133262417635e-06 2.8476099029485e-05 -1.22342870445849e-05 -6.86645696443809e-07 -5.11901007707341e-07 3.6724067285668e-07 -3.06759722523356e-06 -1.22342870445849e-05 7.57615457699148e-05 -2.83902585579316e-07 6.18419061920219e-06 -2.23640583820508e-05 -3.03310460048339e-06 -6.86645696443809e-07 -2.83902585579316e-07 4.95299446926479e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1208 0 0 0 0 0 2683 +1147 1103 0.997875939904024 -0.0157122302044989 0.0632197309600575 -0.000669871262229238 0.0175176267234754 0.999451463205224 -0.0281052566420244 0.0214189500111693 -0.0627434563491541 0.0291530190364207 0.99760380921808 0.0556470539649727 5.59665966364354e-05 5.42964795296895e-05 6.73455900545665e-06 1.89536448610386e-06 -2.34188051618304e-05 2.76480842739042e-05 5.42964795296895e-05 8.28684964329255e-05 1.10750004769089e-05 -5.11474741847491e-06 -1.33227034047351e-05 2.88551533796529e-05 6.73455900545665e-06 1.10750004769089e-05 1.55005442088106e-05 -5.21003243260743e-06 -1.3397987609092e-06 6.21208377787244e-06 1.89536448610386e-06 -5.11474741847491e-06 -5.21003243260743e-06 3.00329848291238e-05 -1.33330302773303e-05 5.21177317448281e-06 -2.34188051618304e-05 -1.33227034047351e-05 -1.3397987609092e-06 -1.33330302773303e-05 0.000115289178946839 -2.27000605722622e-05 2.76480842739042e-05 2.88551533796529e-05 6.21208377787244e-06 5.21177317448281e-06 -2.27000605722622e-05 7.33927731809958e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 614 0 0 0 0 0 2590 +1146 1098 0.999583551623068 -0.00344703232388858 0.0286503279697 0.0012793597276789 0.00363423125204283 0.999972371963634 -0.00648441767852792 -0.00489408934528679 -0.0286271844200575 0.00658583917059911 0.999568462404952 0.0114753413874196 2.59891525804335e-05 1.10641893462517e-05 -7.57780738924461e-06 1.98197943142897e-06 -3.96235555532017e-06 -2.49155242369005e-06 1.10641893462517e-05 5.54229878919044e-05 1.3682873488173e-07 1.10066946682307e-07 2.52697318208475e-06 -8.98389072833748e-06 -7.57780738924461e-06 1.3682873488173e-07 1.72396291808274e-05 -3.06277962134439e-06 -9.56335382550063e-07 -2.62007766482514e-08 1.98197943142897e-06 1.10066946682307e-07 -3.06277962134439e-06 2.89237889643808e-05 -8.71313585358059e-06 7.86880246893062e-06 -3.96235555532017e-06 2.52697318208475e-06 -9.56335382550063e-07 -8.71313585358059e-06 9.64090385615555e-05 -1.30689295885088e-05 -2.49155242369005e-06 -8.98389072833748e-06 -2.62007766482514e-08 7.86880246893062e-06 -1.30689295885088e-05 4.31926420610784e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 818 0 0 0 0 0 2523 +1146 1119 0.99919353824732 -0.00426328516950477 0.0399261508834005 0.00510488025066365 0.00441579803609404 0.999983284577014 -0.00373246490541315 -0.0090282324238166 -0.0399095709386233 0.00390576063388342 0.999195662110963 0.00879696330315863 2.82841462339002e-05 1.80605151988712e-05 -3.66720691607736e-06 9.03470286984378e-07 -9.50611008792485e-07 -2.04913385200472e-06 1.80605151988712e-05 3.64347961792925e-05 -1.39709168968016e-06 -7.94841209058531e-07 -3.49870543842526e-06 -2.30885686089258e-06 -3.66720691607736e-06 -1.39709168968016e-06 1.23701610896245e-05 7.15616660249102e-07 -6.7116024126706e-07 8.32457052288393e-07 9.03470286984378e-07 -7.94841209058531e-07 7.15616660249102e-07 1.91720358839198e-05 -3.29692174981091e-06 1.76648766840557e-06 -9.50611008792485e-07 -3.49870543842526e-06 -6.7116024126706e-07 -3.29692174981091e-06 5.91842028988388e-05 -4.19477758814074e-06 -2.04913385200472e-06 -2.30885686089258e-06 8.32457052288393e-07 1.76648766840557e-06 -4.19477758814074e-06 4.18610963146109e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1177 0 0 0 0 0 2609 +1146 1116 0.999562307495872 -0.00482431299886882 0.0291876589951548 0.00820325543783185 0.00498960764419589 0.999971910752773 -0.00559298855760541 -0.0337473906540588 -0.0291598568083843 0.00573617551487648 0.999558301972115 0.00949725716689371 2.51394416356445e-05 1.60350971084235e-05 -1.47557447474286e-06 -1.71256301696101e-06 1.23041486178119e-06 -4.94139852188217e-06 1.60350971084235e-05 3.88389885032184e-05 -1.80822099378312e-06 1.03195235405962e-06 8.45581146829197e-06 5.79543597062344e-06 -1.47557447474286e-06 -1.80822099378312e-06 1.11759546536396e-05 1.85982786682111e-06 1.88734358759637e-06 1.4820109368607e-06 -1.71256301696101e-06 1.03195235405962e-06 1.85982786682111e-06 2.28554203571121e-05 -1.2226795942041e-05 4.84206894808718e-06 1.23041486178119e-06 8.45581146829197e-06 1.88734358759637e-06 -1.2226795942041e-05 8.48004985809723e-05 5.58818000800524e-06 -4.94139852188217e-06 5.79543597062344e-06 1.4820109368607e-06 4.84206894808718e-06 5.58818000800524e-06 5.10558206826341e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1063 0 0 0 0 0 2619 +1146 1117 0.999294149321708 -0.00444662971428355 0.037301884879838 0.0116428181908841 0.00463583151416623 0.999976818086714 -0.00498721919945021 -0.0299476188733766 -0.0372788438336934 0.00515662422085924 0.999291597597552 0.0120865121016218 1.89113995256156e-05 1.46694426926279e-05 -1.29730337853848e-06 7.08141102151765e-07 -3.26664686748833e-06 -2.65568228091624e-06 1.46694426926279e-05 2.69790073259811e-05 -7.89236733672388e-07 8.64226517999804e-07 -3.98558022862543e-06 -3.140435955243e-06 -1.29730337853848e-06 -7.89236733672388e-07 1.03453418393427e-05 2.51385920397601e-06 2.46050248613131e-06 2.15870181064846e-06 7.08141102151765e-07 8.64226517999804e-07 2.51385920397601e-06 2.27757063809358e-05 -1.90927812668723e-05 -1.58710433546098e-06 -3.26664686748833e-06 -3.98558022862543e-06 2.46050248613131e-06 -1.90927812668723e-05 0.000100596437595468 4.66786802697347e-07 -2.65568228091624e-06 -3.140435955243e-06 2.15870181064846e-06 -1.58710433546098e-06 4.66786802697347e-07 3.70786893427244e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1061 0 0 0 0 0 2476 +1147 1102 0.998317968261327 -0.0146484521483472 0.0560950719424868 0.0162426228021488 0.0162604162492925 0.999464702749136 -0.0283884980578522 -0.0246792348648794 -0.0556491968493251 0.0292528769224245 0.998021761326769 0.0538193775331886 5.67642835317772e-05 1.27334954807441e-05 -9.86860965066438e-06 1.23852841787572e-06 1.76006939650415e-05 2.70239744012178e-05 1.27334954807441e-05 0.000128700805515411 1.23782313790098e-05 -4.23754993937265e-06 -2.9219480050024e-07 -2.64229185373406e-05 -9.86860965066438e-06 1.23782313790098e-05 1.87983300469767e-05 -6.89114012033964e-06 -7.41922578350275e-06 -5.0968865073252e-06 1.23852841787572e-06 -4.23754993937265e-06 -6.89114012033964e-06 4.82585934031357e-05 -6.36444246942581e-05 -5.27757227332882e-06 1.76006939650415e-05 -2.9219480050024e-07 -7.41922578350275e-06 -6.36444246942581e-05 0.000241225383790989 4.04281444020499e-05 2.70239744012178e-05 -2.64229185373406e-05 -5.0968865073252e-06 -5.27757227332882e-06 4.04281444020499e-05 0.000106867729816353 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 677 0 0 0 0 0 2434 +1146 1118 0.999178035040801 -0.00439133577006709 0.0402985168729235 0.00566056017158829 0.00459629618327208 0.999976962683486 -0.00499481368078683 -0.011783875565932 -0.040275654599254 0.00517593203825805 0.999175200539994 0.0100008594911221 2.14069381688047e-05 9.09112174513955e-06 -4.22242797776687e-06 -7.11876666596273e-07 1.80394988894042e-06 1.79740500550901e-06 9.09112174513955e-06 3.62060092115224e-05 1.9978021808444e-06 -9.63196169961926e-07 3.47408027338223e-07 -5.00168901880702e-06 -4.22242797776687e-06 1.9978021808444e-06 1.35680783522068e-05 -1.42029753533856e-06 -8.02842510906746e-07 -6.10705824563515e-07 -7.11876666596273e-07 -9.63196169961926e-07 -1.42029753533856e-06 2.10524190379202e-05 1.19378826285536e-06 -1.69802303648898e-06 1.80394988894042e-06 3.47408027338223e-07 -8.02842510906746e-07 1.19378826285536e-06 3.6062331900582e-05 4.80177905013532e-06 1.79740500550901e-06 -5.00168901880702e-06 -6.10705824563515e-07 -1.69802303648898e-06 4.80177905013532e-06 3.94318277380688e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1109 0 0 0 0 0 2575 +1147 1110 0.999121102805741 -0.0138871129608806 0.0395495894018114 0.01240598548458 0.0151066082049576 0.999414339876115 -0.0307045214672293 -0.0161249500818889 -0.0391000296263575 0.0312749955012208 0.998745744591493 0.0611732249604317 5.27634742550843e-05 2.15031389588178e-05 -1.3844032527489e-05 3.23170767980559e-06 7.72445822330691e-06 1.5101288182337e-05 2.15031389588178e-05 0.000183015615267373 1.26619136583165e-05 1.30264514514523e-05 -1.8985173346347e-05 -1.58990070753162e-05 -1.3844032527489e-05 1.26619136583165e-05 2.15640742806408e-05 -5.16329062901854e-06 -1.00506298242524e-05 -3.93900639796299e-06 3.23170767980559e-06 1.30264514514523e-05 -5.16329062901854e-06 3.59111498068793e-05 -1.6121057969373e-05 2.77816677603163e-06 7.72445822330691e-06 -1.8985173346347e-05 -1.00506298242524e-05 -1.6121057969373e-05 0.000117363728847586 1.47536604165391e-06 1.5101288182337e-05 -1.58990070753162e-05 -3.93900639796299e-06 2.77816677603163e-06 1.47536604165391e-06 7.20101820163195e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 808 0 0 0 0 0 2377 +1147 1108 0.998224123856269 -0.0144511452538232 0.0577906822267754 0.010042166732762 0.0163006748796668 0.99936571309231 -0.0316616407339438 0.00159865664061164 -0.0572964793844319 0.0325474407035458 0.997826526783989 0.062866923489963 5.6384447466886e-05 3.46311972497695e-07 -1.68573600358262e-05 6.26958311516795e-06 1.59619050772728e-05 1.90474551121067e-05 3.46311972497695e-07 0.000167306494624226 1.27994296498966e-05 1.0396112253484e-05 -2.12724824145179e-05 -4.16363407298356e-05 -1.68573600358262e-05 1.27994296498966e-05 2.23217041840866e-05 -9.08571803758627e-06 -1.178376770266e-05 -8.52445143885373e-06 6.26958311516795e-06 1.0396112253484e-05 -9.08571803758627e-06 3.36708686880734e-05 1.4234686448576e-06 -4.03801388037846e-06 1.59619050772728e-05 -2.12724824145179e-05 -1.178376770266e-05 1.4234686448576e-06 7.76506399804068e-05 9.69296902415483e-06 1.90474551121067e-05 -4.16363407298356e-05 -8.52445143885373e-06 -4.03801388037846e-06 9.69296902415483e-06 8.24723829851166e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 727 0 0 0 0 0 2379 +1147 1109 0.999308180987758 -0.0127723548402317 0.0349288757731257 0.00850990801023746 0.0140574362797687 0.99922389283007 -0.0367967455457726 -0.00615325663047104 -0.0344317861311243 0.0372622993031201 0.998712157307833 0.0707596003270311 4.06251009590641e-05 1.83078053513975e-05 -1.04059266447779e-05 3.66081036596027e-06 5.97458445199143e-06 1.30471739435314e-05 1.83078053513975e-05 0.000108609016320715 5.55096594388962e-06 6.16080679806781e-06 -1.29365326308233e-05 8.0089991218189e-06 -1.04059266447779e-05 5.55096594388962e-06 1.76012936092625e-05 -4.39936634624383e-06 -8.55334799614572e-06 -2.44829617276234e-06 3.66081036596027e-06 6.16080679806781e-06 -4.39936634624383e-06 3.35763094852696e-05 -1.75849878160497e-05 5.63876597316504e-07 5.97458445199143e-06 -1.29365326308233e-05 -8.55334799614572e-06 -1.75849878160497e-05 0.000113507649563579 6.50262134377684e-06 1.30471739435314e-05 8.0089991218189e-06 -2.44829617276234e-06 5.63876597316504e-07 6.50262134377684e-06 5.86327531596251e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 864 0 0 0 0 0 2379 +1147 1099 0.998234027380918 -0.0130949288787739 0.0579426390193981 0.00618324371856843 0.0149577270347258 0.999381273287824 -0.0318329546784837 0.0135590643554355 -0.0574899380833468 0.0326434287302609 0.997812263694882 0.0644056207076657 4.74025282851746e-05 -2.32151738831933e-05 -1.37995054826647e-05 1.95437427982876e-06 1.19047033747619e-05 2.93574745306752e-05 -2.32151738831933e-05 0.000182790033822124 2.74524591349528e-05 -1.3444357324584e-06 -4.99386365740391e-06 -6.63522954200535e-05 -1.37995054826647e-05 2.74524591349528e-05 2.11884361866981e-05 -7.91242948115795e-06 -4.65618544261798e-06 -9.84312840005591e-06 1.95437427982876e-06 -1.3444357324584e-06 -7.91242948115795e-06 3.28969723693301e-05 -1.00839013153971e-05 -1.55862901681434e-06 1.19047033747619e-05 -4.99386365740391e-06 -4.65618544261798e-06 -1.00839013153971e-05 9.00747918651234e-05 1.64037835135329e-05 2.93574745306752e-05 -6.63522954200535e-05 -9.84312840005591e-06 -1.55862901681434e-06 1.64037835135329e-05 9.29874165224117e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 728 0 0 0 0 0 2567 +1147 1104 0.998218377748606 -0.0162616587965907 0.0574075672548923 0.00665095196327656 0.0184107537023469 0.999141670131677 -0.037107508062314 -0.00638555853155146 -0.0567548629903486 0.0380983130816371 0.997660966494771 0.0746350332299125 4.8237836300505e-05 3.4780824262903e-05 4.83794830105132e-06 -8.49811774960456e-06 3.57990981214e-06 2.43797959710631e-05 3.4780824262903e-05 8.57403151952474e-05 1.0132936829062e-05 -3.41607344603608e-07 -1.67917950771576e-05 1.16482100419203e-05 4.83794830105132e-06 1.0132936829062e-05 1.89351955119554e-05 -6.35266203418443e-06 -1.00974334468709e-05 4.11210821461247e-07 -8.49811774960456e-06 -3.41607344603608e-07 -6.35266203418443e-06 3.0212326815405e-05 -4.54422466269476e-06 5.71211590234474e-07 3.57990981214e-06 -1.67917950771576e-05 -1.00974334468709e-05 -4.54422466269476e-06 0.000117669062718795 2.27294720348338e-05 2.43797959710631e-05 1.16482100419203e-05 4.11210821461247e-07 5.71211590234474e-07 2.27294720348338e-05 8.83892858453221e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 723 0 0 0 0 0 2540 +1147 1112 0.998790166100512 -0.0134681668282955 0.0472949530414949 0.0165057645997258 0.0149013216000936 0.999436358770263 -0.0300818114914776 -0.0278054553888085 -0.0468631488003377 0.0307501748015099 0.998427900268314 0.0573283176255688 4.77044684733258e-05 2.64283475974203e-05 -1.0112134528351e-05 7.77282853017334e-06 2.66471622555392e-06 2.18136306422063e-05 2.64283475974203e-05 0.000117871945954678 8.30430603544662e-06 -8.5055546988318e-06 2.41175926591921e-05 7.48913820004298e-06 -1.0112134528351e-05 8.30430603544662e-06 1.88460513824889e-05 -9.09343056318402e-06 -2.29676670952948e-06 -5.34461288213848e-07 7.77282853017334e-06 -8.5055546988318e-06 -9.09343056318402e-06 4.41837672620912e-05 -5.26902977142319e-05 7.9864555842525e-06 2.66471622555392e-06 2.41175926591921e-05 -2.29676670952948e-06 -5.26902977142319e-05 0.00020927227745297 -7.48851678363246e-06 2.18136306422063e-05 7.48913820004298e-06 -5.34461288213848e-07 7.9864555842525e-06 -7.48851678363246e-06 7.08537499505429e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 867 0 0 0 0 0 2622 +1147 1098 0.998500588711652 -0.0137659910254758 0.0529818066280376 0.00834121073640404 0.0155527737622413 0.999318996137927 -0.0334612490231064 0.001287012630337 -0.052485098559351 0.0342350909005996 0.99803470529849 0.0650866904379386 4.10739130821893e-05 9.19097810264145e-07 -1.21736861133032e-05 4.38521104448812e-06 9.50652277252827e-06 8.35453789799441e-06 9.19097810264145e-07 0.000189692062031881 2.03804128502983e-05 5.7242939513033e-06 -3.98855926207969e-05 -6.581805230367e-05 -1.21736861133032e-05 2.03804128502983e-05 2.03585485149998e-05 -7.04804519240457e-06 -8.22500023637196e-06 -7.3697348877831e-06 4.38521104448812e-06 5.7242939513033e-06 -7.04804519240457e-06 3.68503802765135e-05 -1.73603613818088e-05 -7.51760677787746e-06 9.50652277252827e-06 -3.98855926207969e-05 -8.22500023637196e-06 -1.73603613818088e-05 0.000109933587693152 2.50049289558402e-05 8.35453789799441e-06 -6.581805230367e-05 -7.3697348877831e-06 -7.51760677787746e-06 2.50049289558402e-05 7.37357124051624e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 826 0 0 0 0 0 2503 +1147 1106 0.998037920379324 -0.0157558876679774 0.0605975369854937 0.0170354505460244 0.0179171305287345 0.999216521073239 -0.0352890981453237 -0.0253097634505211 -0.05999404902597 0.0363055921049097 0.997538278996541 0.0682149002145498 5.44093363219612e-05 -1.56561765159514e-05 -1.1988004442116e-05 1.342206223982e-06 -2.70743103339287e-07 2.30722388098659e-05 -1.56561765159514e-05 0.000183974433467855 2.03259653562385e-05 5.74235733626549e-06 -2.31457509026612e-05 -5.63716400503785e-05 -1.1988004442116e-05 2.03259653562385e-05 2.37605212395817e-05 -9.23668093884211e-06 -9.52449000324553e-06 -6.69610074485889e-06 1.342206223982e-06 5.74235733626549e-06 -9.23668093884211e-06 3.83881569912507e-05 -1.6782459427223e-05 -1.01359105473637e-05 -2.70743103339287e-07 -2.31457509026612e-05 -9.52449000324553e-06 -1.6782459427223e-05 0.00011208641944105 5.68707142635976e-06 2.30722388098659e-05 -5.63716400503785e-05 -6.69610074485889e-06 -1.01359105473637e-05 5.68707142635976e-06 8.22700691670357e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 828 0 0 0 0 0 2489 +1148 1068 0.998984925063805 -0.0067953389891938 0.0445302466115512 0.0333609690165593 0.00413573689312714 0.998216881071825 0.0595479136795688 0.00407889475460047 -0.0448554921454938 -0.0593033027011185 0.997231719869121 0.0918787457546753 3.08057754303213e-05 1.47368937701152e-05 -3.75760528975347e-06 2.01415565937785e-06 4.12332375679458e-06 1.27084101372338e-05 1.47368937701152e-05 5.35299724181814e-05 1.01625558100527e-06 1.28926192935498e-06 2.32083399647965e-06 -2.53315314611044e-06 -3.75760528975347e-06 1.01625558100527e-06 2.24552948060401e-05 -4.71362773969936e-06 -4.09498844895307e-06 -5.73245265897055e-06 2.01415565937785e-06 1.28926192935498e-06 -4.71362773969936e-06 2.43547799996795e-05 -7.18505647696874e-06 2.73528003566892e-06 4.12332375679458e-06 2.32083399647965e-06 -4.09498844895307e-06 -7.18505647696874e-06 7.09702068899892e-05 -4.28823786682457e-06 1.27084101372338e-05 -2.53315314611044e-06 -5.73245265897055e-06 2.73528003566892e-06 -4.28823786682457e-06 5.67134959515168e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 971 0 0 0 0 0 2403 +1148 1070 0.999988884340571 -0.00468711038712414 0.000512046403132721 0.0481433943030567 0.00465483502290552 0.998683566351094 0.0510829405102042 -0.00462910040002075 -0.000750803709088059 -0.0510799891981042 0.99869428305028 0.114296753915047 5.31903417779402e-05 4.76189017692093e-05 -8.85977421329578e-06 6.49475617106186e-06 1.00812315414959e-05 2.36235161950503e-05 4.76189017692093e-05 0.00010633725202092 -1.04563749262965e-05 4.36227306102879e-06 2.19941391126912e-05 2.24551360853574e-05 -8.85977421329578e-06 -1.04563749262965e-05 2.00575518528614e-05 -2.05993307215188e-06 -3.69780581655621e-06 -5.04174826514338e-06 6.49475617106186e-06 4.36227306102879e-06 -2.05993307215188e-06 2.31550889750058e-05 -8.7248488768389e-06 4.55532045833271e-06 1.00812315414959e-05 2.19941391126912e-05 -3.69780581655621e-06 -8.7248488768389e-06 9.90347452443955e-05 -8.28327842071938e-07 2.36235161950503e-05 2.24551360853574e-05 -5.04174826514338e-06 4.55532045833271e-06 -8.28327842071938e-07 6.39468630962585e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 890 0 0 0 0 0 2247 +1147 1117 0.998416013742975 -0.0137295100454005 0.0545615620698401 0.0233372226133441 0.0155454071590333 0.999334522187907 -0.0329977738601877 -0.0367184698759273 -0.0540722092932002 0.0337936875374893 0.99796502086234 0.0664736207837979 3.48069220827638e-05 1.45046543520543e-05 -4.32767467480445e-06 -3.58114970628806e-06 1.13630176662988e-05 5.79297991886444e-06 1.45046543520543e-05 7.37083947254252e-05 9.74211338040855e-06 -4.67361732217455e-06 2.36745676393269e-06 -2.23206734593704e-05 -4.32767467480445e-06 9.74211338040855e-06 1.69930042888311e-05 -4.51453940179168e-06 -5.17979738872892e-06 -5.61334833111568e-07 -3.58114970628806e-06 -4.67361732217455e-06 -4.51453940179168e-06 2.36096166438215e-05 -1.66765341914393e-05 -1.0333017236379e-06 1.13630176662988e-05 2.36745676393269e-06 -5.17979738872892e-06 -1.66765341914393e-05 9.50907697762325e-05 1.40911184810868e-06 5.79297991886444e-06 -2.23206734593704e-05 -5.61334833111568e-07 -1.0333017236379e-06 1.40911184810868e-06 5.35820764898475e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1068 0 0 0 0 0 2494 +1148 1146 0.999416183377214 0.00618403567701263 0.0336013408433227 0.0384707091756703 -0.00510689960169699 0.999473279589819 -0.0320481350850506 -0.00145355526539071 -0.0337818291420387 0.0318578261768894 0.998921351724499 0.118464610474856 3.30391268357629e-05 2.57087437427934e-05 -9.38813033282955e-06 3.68519789877871e-06 -2.40229925714561e-07 4.91584202471965e-06 2.57087437427934e-05 5.56764084411326e-05 -6.74409176591148e-06 3.7792813873377e-06 6.46756621030267e-06 9.23071649692158e-06 -9.38813033282955e-06 -6.74409176591148e-06 1.69185316941346e-05 -4.26456885709736e-06 9.75574468804966e-07 -1.36450938716762e-06 3.68519789877871e-06 3.7792813873377e-06 -4.26456885709736e-06 2.70820366283489e-05 -1.82771576323826e-05 6.59488153839147e-07 -2.40229925714561e-07 6.46756621030267e-06 9.75574468804966e-07 -1.82771576323826e-05 8.26820480684818e-05 2.44104020934371e-06 4.91584202471965e-06 9.23071649692158e-06 -1.36450938716762e-06 6.59488153839147e-07 2.44104020934371e-06 4.79938679361366e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1297 0 0 0 0 0 2463 +1147 1111 0.99882361134538 -0.0130757481918554 0.046694948636827 0.0221049037748778 0.0145673466631513 0.999389762868105 -0.0317473508442465 -0.0357487730234664 -0.046251333279899 0.0323902251251098 0.998404571046315 0.0612366654320956 5.20723449763625e-05 2.06105780001501e-05 -1.27402634606233e-05 8.84532280382238e-06 7.35672369460256e-06 2.7439818565897e-05 2.06105780001501e-05 0.00011165802715444 9.48456729458431e-06 3.59550540669658e-06 -7.99059653482691e-06 1.31334559884446e-05 -1.27402634606233e-05 9.48456729458431e-06 1.99504765687357e-05 -6.73868318323575e-06 -3.92729672992991e-06 -4.38495129127004e-06 8.84532280382238e-06 3.59550540669658e-06 -6.73868318323575e-06 3.56344930034712e-05 -1.5094094272447e-05 6.22817532983248e-06 7.35672369460256e-06 -7.99059653482691e-06 -3.92729672992991e-06 -1.5094094272447e-05 0.000100940416949626 5.98669722350389e-06 2.7439818565897e-05 1.31334559884446e-05 -4.38495129127004e-06 6.22817532983248e-06 5.98669722350389e-06 7.37963131983515e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 780 0 0 0 0 0 2596 +1148 1069 0.999955903737934 -0.00214203502437737 0.00914342745399219 0.0325411157637904 0.00161560486569857 0.998361509862069 0.0571986489949629 0.0170156165555368 -0.00925096754777621 -0.0571813545824631 0.998320946533501 0.112370678943467 3.05889887769285e-05 1.45077941940544e-05 -8.63515413215528e-06 7.40608618355642e-06 -7.58614552483779e-06 5.72955350984365e-06 1.45077941940544e-05 5.98810868140911e-05 -8.01360819616455e-06 1.7709394948261e-06 1.78630866431708e-05 -6.56964754625584e-06 -8.63515413215528e-06 -8.01360819616455e-06 2.08613272781299e-05 -7.50690471913563e-06 -1.0916442724654e-06 -3.13713058638686e-06 7.40608618355642e-06 1.7709394948261e-06 -7.50690471913563e-06 3.1481361021882e-05 -2.90121692863027e-05 6.84955688740877e-06 -7.58614552483779e-06 1.78630866431708e-05 -1.0916442724654e-06 -2.90121692863027e-05 0.00013567196821712 -9.63937541266346e-06 5.72955350984365e-06 -6.56964754625584e-06 -3.13713058638686e-06 6.84955688740877e-06 -9.63937541266346e-06 4.30588986351325e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 906 0 0 0 0 0 2460 +1147 1116 0.99837069600926 -0.0141486961621667 0.0552789991488404 0.0224647995705035 0.0159846813353376 0.999330377367938 -0.0329133230206662 -0.0387672271526759 -0.0547763024728259 0.0337433143980507 0.997928326795487 0.0664749736785915 3.95600424583968e-05 2.59634069231335e-05 2.46802393764783e-07 4.29560175363158e-06 -8.98033689328185e-06 8.2207703619647e-06 2.59634069231335e-05 6.54142198862373e-05 1.07046582864303e-05 1.47007008154329e-07 2.14625100878648e-08 3.65445384162346e-07 2.46802393764783e-07 1.07046582864303e-05 1.57758367510611e-05 -3.25940520865751e-06 -1.55537231569234e-06 2.31786392067836e-06 4.29560175363158e-06 1.47007008154329e-07 -3.25940520865751e-06 3.15953331791227e-05 -3.21564118687318e-05 4.23037978364562e-06 -8.98033689328185e-06 2.14625100878648e-08 -1.55537231569234e-06 -3.21564118687318e-05 0.000117580472494513 2.77768093554796e-06 8.2207703619647e-06 3.65445384162346e-07 2.31786392067836e-06 4.23037978364562e-06 2.77768093554796e-06 4.5382766564186e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1086 0 0 0 0 0 2592 +1148 1071 0.998981228333829 -0.0139341324564796 -0.0429225510579094 0.0481945255111401 0.0157872561652116 0.998944221158585 0.0431416916293489 0.0320646842406354 0.0422760922911229 -0.0437753694051018 0.998146506808514 0.117375533542154 7.21478361920869e-05 3.85827499145413e-05 -1.13776232646044e-05 8.91780609645121e-06 1.0104600217371e-05 3.51804696028269e-05 3.85827499145413e-05 7.53808121756826e-05 -7.22737106867277e-06 4.54215326460499e-07 2.73861427711328e-05 1.53225593440176e-05 -1.13776232646044e-05 -7.22737106867277e-06 1.81373627794977e-05 -5.11792994934067e-06 -1.09757136621517e-05 -4.33075929592374e-06 8.91780609645121e-06 4.54215326460499e-07 -5.11792994934067e-06 3.22639345785797e-05 -2.71056451417598e-05 6.98819330825682e-06 1.0104600217371e-05 2.73861427711328e-05 -1.09757136621517e-05 -2.71056451417598e-05 0.000176463279483708 9.3369528499439e-06 3.51804696028269e-05 1.53225593440176e-05 -4.33075929592374e-06 6.98819330825682e-06 9.3369528499439e-06 6.38140109829611e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 883 0 0 0 0 0 2244 +1147 1145 0.998850819075113 -0.0138198072404535 0.0458917657190549 0.00805812362492682 0.0154799268718893 0.999231222534554 -0.0360185476684092 0.00577591176083028 -0.045358715777862 0.0366875570178394 0.998296854679532 0.0708060971803481 2.81018286502258e-05 5.37849766436919e-06 -6.1054988154546e-06 8.50449829118306e-07 9.71367580490055e-07 2.08039657780145e-06 5.37849766436919e-06 7.25205175341913e-05 7.87946440808761e-06 2.55850444477873e-06 3.73969486202983e-06 -2.5749815326275e-05 -6.1054988154546e-06 7.87946440808761e-06 1.52536875728011e-05 -3.10547690816967e-06 -2.72822992276002e-06 -3.28335955209226e-06 8.50449829118306e-07 2.55850444477873e-06 -3.10547690816967e-06 2.3105501163598e-05 -3.570489454646e-06 -1.35530582808851e-06 9.71367580490055e-07 3.73969486202983e-06 -2.72822992276002e-06 -3.570489454646e-06 5.24156486198548e-05 -1.71611226529565e-06 2.08039657780145e-06 -2.5749815326275e-05 -3.28335955209226e-06 -1.35530582808851e-06 -1.71611226529565e-06 4.65678222086976e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1318 0 0 0 0 0 2561 +1147 1097 0.99849537343534 -0.0151356907014485 0.0527057880617648 0.00857365182032986 0.016982086444456 0.999251314363273 -0.0347623285075028 -0.00535281399662105 -0.0521401761429189 0.035605078433569 0.998004849898799 0.0669142810514717 3.97156963882242e-05 -1.10714665134738e-05 -1.15501337631723e-05 -1.54849320896424e-06 8.31914736477334e-06 1.7244186459847e-05 -1.10714665134738e-05 0.000179404956958855 2.26435550470959e-05 -7.77501392183872e-06 2.93043344098625e-06 -6.45757474301304e-05 -1.15501337631723e-05 2.26435550470959e-05 2.24376034811043e-05 -1.10579125065211e-05 -6.42435494969214e-06 -7.89902531102303e-06 -1.54849320896424e-06 -7.77501392183872e-06 -1.10579125065211e-05 3.6817340076411e-05 -1.14578452192968e-05 -1.9075779266972e-07 8.31914736477334e-06 2.93043344098625e-06 -6.42435494969214e-06 -1.14578452192968e-05 9.77857786391912e-05 2.84193279730464e-07 1.7244186459847e-05 -6.45757474301304e-05 -7.89902531102303e-06 -1.9075779266972e-07 2.84193279730464e-07 7.2744659499281e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 837 0 0 0 0 0 2606 +1148 1067 0.997060806102842 0.00281697132930043 0.0765624817131835 0.0309215241728125 -0.0096581725968884 0.995973005467701 0.0891318802770621 0.00317839724620952 -0.0760030830666781 -0.0896093580613416 0.993072854483594 0.0660154184366236 9.34266716550757e-05 3.71949923221716e-05 -5.44836919101494e-06 1.64252105817527e-05 -2.7857602191185e-05 3.94976351893501e-05 3.71949923221716e-05 8.70047268136888e-05 3.85064599279812e-06 -5.71999095837168e-06 3.89638789175556e-05 2.22676613698331e-05 -5.44836919101494e-06 3.85064599279812e-06 2.01849228169246e-05 -6.96768263309701e-06 -8.24185923054787e-07 -3.98924762971431e-06 1.64252105817527e-05 -5.71999095837168e-06 -6.96768263309701e-06 4.62287192861693e-05 -6.26955295403849e-05 -1.46987323752477e-05 -2.7857602191185e-05 3.89638789175556e-05 -8.24185923054787e-07 -6.26955295403849e-05 0.000246390424870328 5.70270861316924e-05 3.94976351893501e-05 2.22676613698331e-05 -3.98924762971431e-06 -1.46987323752477e-05 5.70270861316924e-05 9.26911413858893e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 974 0 0 0 0 0 2660 +1147 1143 0.997899510896343 -0.0141434033075941 0.0632181168314804 0.0134865800261985 0.0163663712675725 0.999260797854037 -0.0347850508644957 -0.00535650668642435 -0.0626794068604031 0.0357466364150855 0.997393337625952 0.0709988943120521 4.87551963519571e-05 2.18242311138094e-05 -9.8575826058334e-06 2.23917979291677e-06 2.10582966481311e-06 9.60938345006116e-06 2.18242311138094e-05 6.54688880296004e-05 -1.81030960238465e-07 3.78724080710892e-06 2.27652692281355e-08 -1.40500627084236e-05 -9.8575826058334e-06 -1.81030960238465e-07 1.39283926052844e-05 -3.39466819651212e-06 -2.23047419750592e-06 -2.47475499878397e-06 2.23917979291677e-06 3.78724080710892e-06 -3.39466819651212e-06 2.53297315188245e-05 -1.07815162720055e-05 1.19895630139366e-06 2.10582966481311e-06 2.27652692281355e-08 -2.23047419750592e-06 -1.07815162720055e-05 7.04152232214979e-05 4.7359490927489e-06 9.60938345006116e-06 -1.40500627084236e-05 -2.47475499878397e-06 1.19895630139366e-06 4.7359490927489e-06 4.56055422285668e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1169 0 0 0 0 0 2557 +1147 1144 0.998033408076499 -0.0144187165905413 0.0610034177328614 0.0107611396068463 0.0162863043954741 0.999410313261115 -0.0302288279041257 0.00170348481731062 -0.0605315839239839 0.0311629003656742 0.997679708618178 0.0660040965473028 4.54420539368461e-05 2.52953778995128e-05 -5.69535244217088e-06 7.17615000185095e-07 -8.70891710435215e-06 1.78832403860171e-05 2.52953778995128e-05 9.878888540574e-05 8.12180125126784e-06 6.11808260825433e-06 -6.32783421568016e-06 -1.57902994802773e-05 -5.69535244217088e-06 8.12180125126784e-06 1.61692320346775e-05 -2.97667279162684e-06 3.24231922293097e-07 -3.59465190299997e-07 7.17615000185095e-07 6.11808260825433e-06 -2.97667279162684e-06 2.45819108008611e-05 -8.749527951148e-06 -6.7745532603755e-07 -8.70891710435215e-06 -6.32783421568016e-06 3.24231922293097e-07 -8.749527951148e-06 5.4929893292959e-05 -2.97115136308222e-06 1.78832403860171e-05 -1.57902994802773e-05 -3.59465190299997e-07 -6.7745532603755e-07 -2.97115136308222e-06 5.64701142237728e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1222 0 0 0 0 0 2661 +1148 1102 0.99745637838551 0.00110908128245509 0.0712709138202387 0.0354020577855262 0.00127105313835095 0.999443207220618 -0.0333415651174878 0.0016237210185877 -0.0712682091958432 0.0333473459104784 0.996899592175032 0.124609497888834 7.160596815804e-05 4.87752926638454e-05 -6.96308558768e-06 -4.68126842216358e-06 1.9979048059587e-05 4.21452498379866e-05 4.87752926638454e-05 0.000117375515550635 5.22839146063905e-06 1.36663815322809e-05 -4.0816555061803e-05 1.67453147866976e-05 -6.96308558768e-06 5.22839146063905e-06 1.5421417695048e-05 -4.99872375341933e-07 -9.80938441067579e-06 -2.24202814127559e-06 -4.68126842216358e-06 1.36663815322809e-05 -4.99872375341933e-07 4.53555691732089e-05 -6.21988371034832e-05 -5.91464198408571e-06 1.9979048059587e-05 -4.0816555061803e-05 -9.80938441067579e-06 -6.21988371034832e-05 0.000225995383235758 3.08381933203136e-05 4.21452498379866e-05 1.67453147866976e-05 -2.24202814127559e-06 -5.91464198408571e-06 3.08381933203136e-05 9.03981023605233e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 656 0 0 0 0 0 2377 +1148 1100 0.998176890782196 0.00354528820905985 0.0602521836940557 0.0264750020333437 -0.000866883137616768 0.999012507627054 -0.0444213700636337 0.0220791101407067 -0.0603501716817214 0.0442881534523542 0.997194272066265 0.148060147721452 3.99749819921484e-05 6.67423474544242e-06 -1.0407282162811e-05 1.02080574695911e-06 1.91273298090143e-07 1.14652366349411e-05 6.67423474544242e-06 0.000146807065649339 1.37342466309741e-05 1.46605562180931e-05 -7.28445535566071e-05 -3.73220656921031e-05 -1.0407282162811e-05 1.37342466309741e-05 2.22740937858617e-05 -7.83695794850771e-06 -8.14023297743808e-06 -5.6970724229077e-06 1.02080574695911e-06 1.46605562180931e-05 -7.83695794850771e-06 4.74777211223241e-05 -4.93021537080728e-05 -4.32374797667833e-07 1.91273298090143e-07 -7.28445535566071e-05 -8.14023297743808e-06 -4.93021537080728e-05 0.000199898437645467 1.76083134633297e-05 1.14652366349411e-05 -3.73220656921031e-05 -5.6970724229077e-06 -4.32374797667833e-07 1.76083134633297e-05 5.17956586342707e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 690 0 0 0 0 0 2426 +1148 1109 0.99841880005307 0.00277983320997053 0.0561442092108543 0.0408230657357006 -0.000499495122388427 0.999175802538623 -0.0405889902057405 -0.0226286408045707 -0.0562107659190848 0.04049676713793 0.997597294325805 0.140860754958188 5.66838031420244e-05 4.21888934735241e-05 -1.06832616973706e-05 7.45124969516435e-06 8.76011839771379e-06 2.36709623335206e-05 4.21888934735241e-05 0.000141108157458661 2.85457568091104e-06 1.47477011955202e-05 -1.29326519914789e-05 1.3998028441448e-05 -1.06832616973706e-05 2.85457568091104e-06 1.97494548808805e-05 -6.97119651719687e-06 -3.01827831503026e-06 5.64147086466058e-07 7.45124969516435e-06 1.47477011955202e-05 -6.97119651719687e-06 4.11079168078735e-05 -4.32048079690684e-05 -3.76327995452909e-06 8.76011839771379e-06 -1.29326519914789e-05 -3.01827831503026e-06 -4.32048079690684e-05 0.000153248677716205 2.1511486259539e-05 2.36709623335206e-05 1.3998028441448e-05 5.64147086466058e-07 -3.76327995452909e-06 2.1511486259539e-05 7.05699318375113e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 818 0 0 0 0 0 2400 +1148 1108 0.998393060730788 0.00359836444580837 0.0565539393669731 0.0310856144012732 -0.00134896133670005 0.999208251472702 -0.039762425632466 0.011524008230341 -0.0566522425674413 0.039622240751634 0.997607438549803 0.141297253686666 7.53241527784259e-05 2.31257144966199e-05 -1.26397841575583e-05 1.8659627309452e-06 -4.77680992780141e-06 3.52209815251997e-05 2.31257144966199e-05 0.000109248520581103 7.95024259832904e-06 -7.67652131215822e-06 6.32240013738973e-06 -7.91379632969529e-06 -1.26397841575583e-05 7.95024259832904e-06 2.06625645831183e-05 -3.01225708967863e-06 -1.15460912543337e-05 -2.79813090212481e-06 1.8659627309452e-06 -7.67652131215822e-06 -3.01225708967863e-06 3.43600840968725e-05 -3.33692181165138e-05 -5.96345242861231e-07 -4.77680992780141e-06 6.32240013738973e-06 -1.15460912543337e-05 -3.33692181165138e-05 0.000167920556000731 -3.50713611580045e-06 3.52209815251997e-05 -7.91379632969529e-06 -2.79813090212481e-06 -5.96345242861231e-07 -3.50713611580045e-06 7.54557641731202e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 669 0 0 0 0 0 2416 +1148 1104 0.997674646525096 0.000187195476875853 0.0681561782883865 0.0275701440501279 0.00249898891920039 0.999223356049849 -0.0393247985227968 0.0129949645424169 -0.0681106066292659 0.0394036760002196 0.996899340747231 0.141446534605942 0.000234084522599394 0.000131193636115525 5.27025520486393e-06 8.33728798352183e-06 -0.000127312833984847 0.000253324753291482 0.000131193636115525 0.00025460166010098 2.44433760498953e-05 -2.62392278726173e-05 2.40848082796518e-05 0.000129830620879638 5.27025520486393e-06 2.44433760498953e-05 1.98251815753233e-05 -8.64527920957972e-06 2.00405496219457e-06 -9.71878963874254e-07 8.33728798352183e-06 -2.62392278726173e-05 -8.64527920957972e-06 4.14775953545068e-05 -3.27959980123285e-05 2.87229939123521e-05 -0.000127312833984847 2.40848082796518e-05 2.00405496219457e-06 -3.27959980123285e-05 0.000244002560448073 -0.000156226053323859 0.000253324753291482 0.000129830620879638 -9.71878963874254e-07 2.87229939123521e-05 -0.000156226053323859 0.000343346768108971 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 693 0 0 0 0 0 2528 +1148 1111 0.997850892236693 0.00172696388438736 0.0655027820644029 0.0432640384682749 0.000724144318329644 0.999300946464218 -0.0373777207802249 -0.0227776838049601 -0.0655215420868654 0.0373448254977882 0.997152090471207 0.137771422479001 7.27111868848861e-05 4.42400704074264e-05 -1.21130382721388e-05 4.35320949211106e-07 3.08446091724682e-06 4.68567559977416e-05 4.42400704074264e-05 0.000120241977595279 1.82549745361812e-06 -4.18227600508218e-06 8.17394426087896e-06 2.27555329470565e-05 -1.21130382721388e-05 1.82549745361812e-06 1.88760434119706e-05 -2.79807404867885e-06 -6.55610155181291e-07 -5.23398363847045e-06 4.35320949211106e-07 -4.18227600508218e-06 -2.79807404867885e-06 3.12927009424815e-05 -2.36473326523243e-05 4.39088776098246e-06 3.08446091724682e-06 8.17394426087896e-06 -6.55610155181291e-07 -2.36473326523243e-05 0.000110106675455005 -2.78519192073126e-07 4.68567559977416e-05 2.27555329470565e-05 -5.23398363847045e-06 4.39088776098246e-06 -2.78519192073126e-07 8.4377671573281e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 753 0 0 0 0 0 2466 +1148 1099 0.997757770644526 0.00355714660182143 0.0668339571364632 0.0266357790970008 -0.000785242922722452 0.999140061109556 -0.0414550561396878 0.0313891034095487 -0.0669239457295949 0.0413096235040397 0.9969025531585 0.144091888415296 5.52298298321972e-05 2.08512549743269e-05 -1.0578806944707e-05 4.24883310898131e-06 6.53469955187535e-07 2.08205706697105e-05 2.08512549743269e-05 0.000120390655260032 1.08160449851511e-05 5.19560050740156e-07 -1.28439929741949e-05 -1.34127917106168e-05 -1.0578806944707e-05 1.08160449851511e-05 2.05353482997828e-05 -6.92592094775491e-06 -4.44466662305101e-06 -4.95131697262045e-06 4.24883310898131e-06 5.19560050740156e-07 -6.92592094775491e-06 2.78547343170914e-05 -3.22460169613005e-07 5.33021960159593e-06 6.53469955187535e-07 -1.28439929741949e-05 -4.44466662305101e-06 -3.22460169613005e-07 5.28354902877062e-05 -1.38411315694877e-06 2.08205706697105e-05 -1.34127917106168e-05 -4.95131697262045e-06 5.33021960159593e-06 -1.38411315694877e-06 5.61063587355003e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 688 0 0 0 0 0 2425 +1148 1103 0.997564273086716 0.000742299843827876 0.069749337286558 0.0219253308731085 0.00210034919552772 0.999170302155391 -0.0406730355882392 0.0300504985399505 -0.0697216579997136 0.0407204651452703 0.996735037070597 0.141870470294412 4.48764996896342e-05 3.87225337049229e-05 2.31302068427316e-06 -1.19987859065654e-06 -1.55750499546839e-05 2.31435561672133e-05 3.87225337049229e-05 7.96248339693194e-05 6.29736923007105e-06 -2.98544260399535e-07 -1.45155248924472e-05 2.15119386657231e-05 2.31302068427316e-06 6.29736923007105e-06 1.76429252479986e-05 -2.43814217878797e-06 -2.06590390399741e-06 4.4175535854236e-06 -1.19987859065654e-06 -2.98544260399535e-07 -2.43814217878797e-06 2.85920197289802e-05 3.57622182849005e-07 8.66139921418204e-06 -1.55750499546839e-05 -1.45155248924472e-05 -2.06590390399741e-06 3.57622182849005e-07 7.60717213611435e-05 -2.29440422049449e-05 2.31435561672133e-05 2.15119386657231e-05 4.4175535854236e-06 8.66139921418204e-06 -2.29440422049449e-05 7.47841856197115e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 614 0 0 0 0 0 2489 +1148 1107 0.997478368623251 0.00142605422693295 0.0709568213637004 0.0409061770495031 0.00131371679504062 0.999255802616251 -0.0385501632413543 -0.0164955930912686 -0.0709589901061216 0.0385461711080943 0.996734174399586 0.135198585106161 7.70101677020888e-05 3.88807214057021e-05 -1.67356454369032e-05 -3.19815750438839e-06 3.23738302368661e-05 5.75930753800929e-05 3.88807214057021e-05 0.000126679030325998 -3.6649303671267e-06 8.40534956351943e-06 -5.12902774113317e-06 1.38762847198849e-05 -1.67356454369032e-05 -3.6649303671267e-06 1.96083462291539e-05 -6.8540830553115e-06 -1.06899200282206e-05 -1.15588931609809e-05 -3.19815750438839e-06 8.40534956351943e-06 -6.8540830553115e-06 3.76734936112097e-05 -2.14234013289489e-05 2.49961705101034e-06 3.23738302368661e-05 -5.12902774113317e-06 -1.06899200282206e-05 -2.14234013289489e-05 0.000141147280706699 3.73888549838595e-05 5.75930753800929e-05 1.38762847198849e-05 -1.15588931609809e-05 2.49961705101034e-06 3.73888549838595e-05 0.000110224588677219 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 662 0 0 0 0 0 2385 +1148 1112 0.997966922818705 0.00227223475525461 0.0636934683384509 0.0366190409834081 -0.00015836932631807 0.999449594662555 -0.0331735232981075 -0.00208041043508285 -0.0637337891461093 0.0330959918731954 0.99741799635008 0.130484040954635 6.77994008296938e-05 4.21018246105646e-05 -7.86639514524569e-06 -7.47175113081545e-06 2.86841301016929e-05 3.86831358489153e-05 4.21018246105646e-05 8.95999707658532e-05 2.11318062607772e-06 -8.3791250453558e-06 2.67095918337552e-05 2.06895464662934e-05 -7.86639514524569e-06 2.11318062607772e-06 1.71720863851969e-05 -3.86897176582281e-06 -1.96616869063405e-06 -4.72663699705265e-06 -7.47175113081545e-06 -8.3791250453558e-06 -3.86897176582281e-06 3.4989407006917e-05 -3.12469677747509e-05 3.65139395681954e-07 2.86841301016929e-05 2.67095918337552e-05 -1.96616869063405e-06 -3.12469677747509e-05 0.000138054268050184 2.17143971044879e-05 3.86831358489153e-05 2.06895464662934e-05 -4.72663699705265e-06 3.65139395681954e-07 2.17143971044879e-05 7.04913185966223e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 818 0 0 0 0 0 2470 +1148 1096 0.998219461165389 0.00139585281552743 0.0596318618323926 0.0282048925058273 0.000725830575790069 0.999367876380318 -0.0355432247983966 0.0187267032581697 -0.0596437802344505 0.035523221334945 0.997587449913707 0.136104725890541 8.00673414344259e-05 4.99906684928876e-05 -1.08395874821302e-05 1.77098572967138e-05 -2.28447289152983e-05 4.13548338943103e-05 4.99906684928876e-05 0.000115582879047214 4.48021455639476e-06 -3.96001411238395e-06 1.07271673182659e-05 1.44689894006495e-05 -1.08395874821302e-05 4.48021455639476e-06 1.87509447173441e-05 -5.1998237856002e-06 7.37668782369728e-07 -2.98875145255284e-06 1.77098572967138e-05 -3.96001411238395e-06 -5.1998237856002e-06 3.19217000598699e-05 -2.31507621860762e-05 1.59852468883689e-05 -2.28447289152983e-05 1.07271673182659e-05 7.37668782369728e-07 -2.31507621860762e-05 0.000128522342586188 -2.1388167434096e-05 4.13548338943103e-05 1.44689894006495e-05 -2.98875145255284e-06 1.59852468883689e-05 -2.1388167434096e-05 8.11854718310717e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 807 0 0 0 0 0 2379 +1148 1098 0.997247728544619 0.00162824659493113 0.0741236583394542 0.0247836998625384 0.00116206730353288 0.999292745252046 -0.0375853546772025 0.0359591165032884 -0.0741324322559304 0.0375680462581586 0.99654052822159 0.138070265819924 5.89953032304339e-05 2.14717482335505e-05 -1.39156471170502e-05 7.18390794129415e-06 -8.04135883997056e-06 1.85645506883509e-05 2.14717482335505e-05 0.000121514708033121 5.84634777481749e-06 -1.19103705897561e-06 1.07420249180442e-06 -1.89347703897222e-05 -1.39156471170502e-05 5.84634777481749e-06 2.05939509340801e-05 -6.80530412488573e-06 -7.28084078187525e-07 -5.66316309814742e-06 7.18390794129415e-06 -1.19103705897561e-06 -6.80530412488573e-06 2.77644905816287e-05 -4.28793802002241e-06 9.45238682208904e-06 -8.04135883997056e-06 1.07420249180442e-06 -7.28084078187525e-07 -4.28793802002241e-06 7.04648942800974e-05 -1.04093973481106e-05 1.85645506883509e-05 -1.89347703897222e-05 -5.66316309814742e-06 9.45238682208904e-06 -1.04093973481106e-05 6.17295840622417e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 805 0 0 0 0 0 2393 +1148 1117 0.997399196573751 0.00238200961641672 0.0720358848368161 0.0510885832658806 0.00061969760316288 0.999133379386589 -0.0416185796299526 -0.0356273989458257 -0.0720725929110114 0.0415549783506305 0.996533353744551 0.142769094339322 8.10514612331153e-05 4.5632881468019e-05 -5.63944769371633e-06 -9.56747025109124e-07 -7.00935879645681e-07 6.05113477212354e-05 4.5632881468019e-05 7.74699824556276e-05 7.36311254423661e-07 2.88549738028489e-07 7.86789683167709e-06 1.84629736061561e-05 -5.63944769371633e-06 7.36311254423661e-07 1.47529004274872e-05 -2.33752197178061e-06 5.23906601162998e-08 -1.3958424153858e-06 -9.56747025109124e-07 2.88549738028489e-07 -2.33752197178061e-06 2.60960185158023e-05 -2.16282194130688e-05 3.3050695697436e-06 -7.00935879645681e-07 7.86789683167709e-06 5.23906601162998e-08 -2.16282194130688e-05 9.73944126805225e-05 -4.45644769002893e-06 6.05113477212354e-05 1.84629736061561e-05 -1.3958424153858e-06 3.3050695697436e-06 -4.45644769002893e-06 9.97452793664421e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1017 0 0 0 0 0 2422 +1148 1097 0.997113761632175 0.00116330726483661 0.0759130626436641 0.028712007758177 0.00168746353824797 0.999296022434244 -0.037478153822017 0.0322932573101262 -0.0759032201592289 0.0374980834617886 0.996409852874886 0.14029017148271 6.70407388501734e-05 1.36070698377337e-05 -1.50042419856124e-05 3.15904883912382e-06 -4.0930524265889e-06 3.41483571149656e-05 1.36070698377337e-05 0.00015522762917613 1.55093716775005e-05 2.25384158574166e-06 -2.57662935962745e-05 -1.0909721737447e-05 -1.50042419856124e-05 1.55093716775005e-05 2.118851502238e-05 -4.49701546335765e-06 -9.98439651051022e-06 -7.2808364224679e-06 3.15904883912382e-06 2.25384158574166e-06 -4.49701546335765e-06 2.56409651722215e-05 -6.7258320869273e-06 7.0539660546938e-06 -4.0930524265889e-06 -2.57662935962745e-05 -9.98439651051022e-06 -6.7258320869273e-06 0.000103660541698709 -1.55561210412795e-05 3.41483571149656e-05 -1.0909721737447e-05 -7.2808364224679e-06 7.0539660546938e-06 -1.55561210412795e-05 6.82254388797159e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 797 0 0 0 0 0 2481 +1148 1120 0.997085953039192 0.0019128707954157 0.0762623313126953 0.0435399591370613 0.0012900810520963 0.999119811906429 -0.0419277610532737 -0.0117266992069089 -0.0762754085063219 0.0419039661772181 0.996205862096691 0.145934597470442 6.05372417211519e-05 1.72257920083191e-05 -1.18011968181432e-05 4.19480597467839e-06 -5.52700403725695e-06 3.18370258570532e-05 1.72257920083191e-05 7.77853353256777e-05 3.60508877590127e-06 3.62522431908561e-06 -1.43305450847851e-08 -7.06268150551198e-06 -1.18011968181432e-05 3.60508877590127e-06 1.73694898962736e-05 -2.32716143158002e-06 -2.06724910886362e-06 -6.20945725185816e-06 4.19480597467839e-06 3.62522431908561e-06 -2.32716143158002e-06 2.87955462731979e-05 -1.97885545787481e-05 1.07069462220181e-05 -5.52700403725695e-06 -1.43305450847851e-08 -2.06724910886362e-06 -1.97885545787481e-05 9.10273769678004e-05 -1.47306070143658e-05 3.18370258570532e-05 -7.06268150551198e-06 -6.20945725185816e-06 1.07069462220181e-05 -1.47306070143658e-05 6.35554555250967e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1098 0 0 0 0 0 2472 +1148 1122 0.997640298465725 0.00244066049777398 0.0686139785579727 0.0406795915004154 0.000687134770936142 0.998962969085626 -0.0455248749744196 -0.0119070186917842 -0.068653934505066 0.0454645969075342 0.996604037572099 0.148886595822877 3.81139458322263e-05 1.21443284493514e-05 -8.30777613149995e-06 -1.81147845359532e-06 6.37897281364672e-06 7.79009826345254e-06 1.21443284493514e-05 9.57668947869392e-05 8.6495292350139e-06 2.98010855895315e-06 -1.02175797865155e-05 -2.21895127071116e-05 -8.30777613149995e-06 8.6495292350139e-06 1.70108760215555e-05 -3.34704689040084e-06 -2.5468909134903e-06 -1.42493367382489e-06 -1.81147845359532e-06 2.98010855895315e-06 -3.34704689040084e-06 2.79425364145054e-05 -1.52497081274496e-05 5.31478512181307e-07 6.37897281364672e-06 -1.02175797865155e-05 -2.5468909134903e-06 -1.52497081274496e-05 8.16320242499733e-05 9.08985036199655e-06 7.79009826345254e-06 -2.21895127071116e-05 -1.42493367382489e-06 5.31478512181307e-07 9.08985036199655e-06 4.56301578122229e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1217 0 0 0 0 0 2381 +1148 1116 0.997842189643274 0.00295544563597881 0.0655913859360227 0.0485523422011157 5.4353097910422e-05 0.998948887081992 -0.0458379541798031 -0.0376618329351653 -0.0656579135645982 0.0457426096625647 0.996793184189981 0.147568048729675 8.67415372595834e-05 5.39960555788212e-05 1.64243994818762e-06 6.57466429775854e-06 -3.3900181624827e-05 4.97584799652418e-05 5.39960555788212e-05 8.27311025929032e-05 6.88634586070375e-06 9.68776780753508e-07 -6.63261327536871e-06 1.95540557669139e-05 1.64243994818762e-06 6.88634586070375e-06 1.45313436323268e-05 -3.76583551742123e-06 -1.3920688858721e-06 1.20848147587701e-06 6.57466429775854e-06 9.68776780753508e-07 -3.76583551742123e-06 3.16184361869902e-05 -3.67197118052973e-05 7.79891264438343e-06 -3.3900181624827e-05 -6.63261327536871e-06 -1.3920688858721e-06 -3.67197118052973e-05 0.000160426024633604 -2.03077582115675e-05 4.97584799652418e-05 1.95540557669139e-05 1.20848147587701e-06 7.79891264438343e-06 -2.03077582115675e-05 9.17197479706801e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1018 0 0 0 0 0 2454 +1149 1065 0.991446529896791 0.0500379638682331 0.120540368870902 0.035855663248204 -0.0542347742186568 0.998022060574133 0.0317892414633237 0.044973540133967 -0.118711278407163 -0.0380548128268104 0.992199306389424 0.0984479627524173 4.55513595468084e-05 1.3742783246996e-05 -5.45725116318443e-06 7.1121518992238e-06 -4.51883843519765e-06 2.8592573795682e-05 1.3742783246996e-05 8.12642820714927e-05 7.13890841182785e-06 -7.47428830141694e-06 2.03555273641041e-05 -1.58345948221064e-06 -5.45725116318443e-06 7.13890841182785e-06 1.68003321297256e-05 -4.01420281601992e-06 1.13367637985977e-07 -5.77757446259236e-06 7.1121518992238e-06 -7.47428830141694e-06 -4.01420281601992e-06 3.65198039002411e-05 -2.92052063207469e-05 4.31856650397452e-06 -4.51883843519765e-06 2.03555273641041e-05 1.13367637985977e-07 -2.92052063207469e-05 0.000121611598748621 5.12213606647937e-07 2.8592573795682e-05 -1.58345948221064e-06 -5.77757446259236e-06 4.31856650397452e-06 5.12213606647937e-07 7.73398227251729e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1012 0 0 0 0 0 3052 +1149 1066 0.993092416422897 0.0147484952420102 0.116404185197217 0.040949982009831 -0.0219807890927323 0.997889967244466 0.0610938473473275 0.0658506634014249 -0.115257526236652 -0.0632304923350604 0.991321142458322 0.133633851555319 7.02095958932634e-05 4.08135683302331e-05 1.53293236833337e-06 -2.26833697127758e-06 -6.17095583451039e-06 6.26212228689094e-05 4.08135683302331e-05 7.12540606701282e-05 3.78479205060589e-06 -6.2437176247872e-06 4.48077253184582e-06 2.32072166028839e-05 1.53293236833337e-06 3.78479205060589e-06 1.58044037741049e-05 -6.02401287150941e-07 1.29247614404976e-06 -1.3306453802209e-06 -2.26833697127758e-06 -6.2437176247872e-06 -6.02401287150941e-07 3.03601163846189e-05 -2.26752239201505e-05 -4.35452580261284e-06 -6.17095583451039e-06 4.48077253184582e-06 1.29247614404976e-06 -2.26752239201505e-05 0.000118134622231562 -1.47769744570558e-05 6.26212228689094e-05 2.32072166028839e-05 -1.3306453802209e-06 -4.35452580261284e-06 -1.47769744570558e-05 0.00012320659666583 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 942 0 0 0 0 0 2873 +1148 1121 0.997758901437303 0.00251403988957472 0.0668644465023136 0.0405310156362441 0.000625120382185142 0.998900059886792 -0.0468858143010368 -0.0154018581944719 -0.0669087724228662 0.046822536898348 0.996659854820725 0.150816850913162 3.38859976981397e-05 7.98544333289882e-06 -6.04753012563475e-06 -2.22261533131659e-06 5.95650378228423e-06 4.76003926131603e-06 7.98544333289882e-06 8.63073917536793e-05 5.54441724483748e-06 2.00446676397384e-06 -5.80429024795781e-07 -2.29483464096438e-05 -6.04753012563475e-06 5.54441724483748e-06 1.55451069283336e-05 -4.14463362771472e-06 -2.32220291281805e-06 -1.46807323083014e-06 -2.22261533131659e-06 2.00446676397384e-06 -4.14463362771472e-06 2.53705869911807e-05 -1.47001585214919e-05 -2.42692953774438e-06 5.95650378228423e-06 -5.80429024795781e-07 -2.32220291281805e-06 -1.47001585214919e-05 7.3126416250448e-05 2.32785664978698e-06 4.76003926131603e-06 -2.29483464096438e-05 -1.46807323083014e-06 -2.42692953774438e-06 2.32785664978698e-06 4.72471771408623e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1204 0 0 0 0 0 2411 +1148 1119 0.997685178187005 0.00275354642915399 0.0679463259347107 0.0420592616114408 0.000155690600588187 0.999084748719507 -0.0427742987846227 -0.0137104607871438 -0.0680019189905722 0.0426858625090531 0.996771616848844 0.146573192611948 9.9370195717026e-05 1.8834164222494e-05 -1.16057886245454e-05 1.61353846112259e-06 -1.5334211068832e-06 5.45436382760054e-05 1.8834164222494e-05 0.000119473298276701 6.87957020924676e-06 7.0795002995162e-06 -1.6822296833214e-05 -2.22827854202052e-05 -1.16057886245454e-05 6.87957020924676e-06 1.83889036504928e-05 -1.95592302311911e-06 -3.91345776813365e-06 -4.37214586315141e-06 1.61353846112259e-06 7.0795002995162e-06 -1.95592302311911e-06 2.62316059207615e-05 -1.54229921585058e-05 8.74775716665436e-07 -1.5334211068832e-06 -1.6822296833214e-05 -3.91345776813365e-06 -1.54229921585058e-05 9.35736313909896e-05 1.84580246843226e-06 5.45436382760054e-05 -2.22827854202052e-05 -4.37214586315141e-06 8.74775716665436e-07 1.84580246843226e-06 9.0347542437263e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1123 0 0 0 0 0 2502 +1149 1069 0.999596393428373 -0.0127325483313891 0.0253955204313259 0.0648261499901728 0.0114038603584851 0.998592604334349 0.0517953910851845 0.0302082622772353 -0.0260192662062792 -0.0514848791562326 0.99833476600004 0.199453820562615 4.3004613300018e-05 2.82656755788457e-05 -2.27621484544951e-06 4.42640970343447e-06 -4.48963290278887e-06 1.78264531349581e-05 2.82656755788457e-05 6.16951993988538e-05 1.69904560232289e-07 7.22325883271015e-07 -5.92456335356529e-07 8.96055421631833e-06 -2.27621484544951e-06 1.69904560232289e-07 2.05510008035528e-05 -1.73712069719378e-06 -7.30444669059082e-06 -5.21465169272891e-06 4.42640970343447e-06 7.22325883271015e-07 -1.73712069719378e-06 2.84448286190522e-05 -2.89898749899659e-05 7.84689340208388e-06 -4.48963290278887e-06 -5.92456335356529e-07 -7.30444669059082e-06 -2.89898749899659e-05 0.000126124332157484 -7.03558058218253e-06 1.78264531349581e-05 8.96055421631833e-06 -5.21465169272891e-06 7.84689340208388e-06 -7.03558058218253e-06 6.10690894202666e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 886 0 0 0 0 0 2278 +1149 1071 0.999193783364216 -0.0211213820123586 -0.0341419171721914 0.0770843453580623 0.0224839913067177 0.998945413218989 0.0400316317886506 0.0531686397959738 0.0332603881700771 -0.0407670041900392 0.998614939778164 0.213324413850407 4.83407564659172e-05 2.25046590320969e-05 -8.13558672939458e-06 6.01715773719419e-06 2.72703392757132e-06 3.55826644759066e-05 2.25046590320969e-05 9.47673854645855e-05 3.53774944857748e-06 -5.81347517162177e-07 3.55962448288165e-06 -3.64276360989601e-06 -8.13558672939458e-06 3.53774944857748e-06 2.00426999183587e-05 -7.20970201375065e-06 -2.59004503542608e-06 -6.79230643796877e-06 6.01715773719419e-06 -5.81347517162177e-07 -7.20970201375065e-06 2.72218587078602e-05 -1.10096054198267e-05 5.73622546800839e-06 2.72703392757132e-06 3.55962448288165e-06 -2.59004503542608e-06 -1.10096054198267e-05 8.99897070854341e-05 8.1118663646598e-06 3.55826644759066e-05 -3.64276360989601e-06 -6.79230643796877e-06 5.73622546800839e-06 8.1118663646598e-06 8.51321289110125e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 839 0 0 0 0 0 2179 +1149 1067 0.995154034259864 -0.00714265470562683 0.0980684994280679 0.0536665405193598 -0.00173569056399071 0.99592671888746 0.0901496421752409 0.0505335755207787 -0.098312946627506 -0.0898829966668563 0.991088094689671 0.160025501609492 2.72332220087748e-05 1.66470179563026e-05 -2.50162876890993e-06 -2.48045074802197e-06 1.14060333307349e-05 2.16109348191548e-05 1.66470179563026e-05 5.01236816615319e-05 -2.04616672752263e-06 8.71503323097021e-06 -1.9756117006313e-05 1.28903759120343e-05 -2.50162876890993e-06 -2.04616672752263e-06 1.81868745175232e-05 -6.69379586009096e-07 -1.04138718534456e-05 -2.36474582053316e-06 -2.48045074802197e-06 8.71503323097021e-06 -6.69379586009096e-07 4.23608550672724e-05 -5.17641736405964e-05 -9.92865231254427e-06 1.14060333307349e-05 -1.9756117006313e-05 -1.04138718534456e-05 -5.17641736405964e-05 0.000199420848686373 3.17943739212709e-05 2.16109348191548e-05 1.28903759120343e-05 -2.36474582053316e-06 -9.92865231254427e-06 3.17943739212709e-05 5.21689623731853e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 982 0 0 0 0 0 2457 +1149 1102 0.996181840020916 -0.00663058813633549 0.0870504274171515 0.0595208146457683 0.00947540698896433 0.999433053756521 -0.0323077037455173 0.0410808814772104 -0.0867868554271669 0.0330091859924009 0.995679885990062 0.218039136146108 5.38302349661125e-05 3.68390014429525e-05 -4.75532171703504e-06 -3.49367170385372e-06 9.44040584038934e-06 2.7186734984764e-05 3.68390014429525e-05 7.90977096590613e-05 -2.57788765959427e-06 1.4090088756287e-05 -3.51196023876749e-05 9.21855552923335e-06 -4.75532171703504e-06 -2.57788765959427e-06 1.39359655823208e-05 3.87599114397178e-06 4.24588834854021e-07 2.97589280126857e-06 -3.49367170385372e-06 1.4090088756287e-05 3.87599114397178e-06 3.40557382009993e-05 -4.22575129566445e-05 -7.67181631198107e-06 9.44040584038934e-06 -3.51196023876749e-05 4.24588834854021e-07 -4.22575129566445e-05 0.00016786213653144 3.53007268723218e-05 2.7186734984764e-05 9.21855552923335e-06 2.97589280126857e-06 -7.67181631198107e-06 3.53007268723218e-05 8.3496849842349e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 639 0 0 0 0 0 2286 +1149 1068 0.998037351029682 -0.0169469300129838 0.0602847203923964 0.0606330598123047 0.013763228788075 0.998508152771368 0.052839780302706 0.0298756184370237 -0.0610902568580416 -0.0519063619631174 0.996781676248501 0.185558716990913 6.99543915950943e-05 4.37698328148173e-05 8.30743427799418e-06 2.5770948076832e-06 -2.08220032467668e-06 1.39247824830699e-05 4.37698328148173e-05 8.75122968189714e-05 2.4343841374136e-06 -4.75896448792491e-06 1.55352971769317e-05 1.17902798862893e-05 8.30743427799418e-06 2.4343841374136e-06 2.05499831703816e-05 -5.44623242135127e-07 -2.2828953105319e-06 4.80825730386287e-07 2.5770948076832e-06 -4.75896448792491e-06 -5.44623242135127e-07 2.64333098616227e-05 -1.48485407582149e-05 -3.76376921440272e-07 -2.08220032467668e-06 1.55352971769317e-05 -2.2828953105319e-06 -1.48485407582149e-05 8.62138975943035e-05 -5.93218344992952e-06 1.39247824830699e-05 1.17902798862893e-05 4.80825730386287e-07 -3.76376921440272e-07 -5.93218344992952e-06 4.88817372969933e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 917 0 0 0 0 0 2306 +1149 1070 0.999850973024478 -0.0137399037861078 0.0104521187303831 0.0798346579180174 0.0132501445448725 0.998873476936675 0.0455654555774159 0.0116085599588884 -0.0110664091531766 -0.0454201730114051 0.998906673554676 0.207181851476622 5.77168042914187e-05 2.91900013907702e-05 1.01609378922904e-06 8.57411005591085e-06 -5.68759177217846e-06 1.73904673050513e-05 2.91900013907702e-05 7.64482113398462e-05 -2.06027258090351e-06 1.13669467525495e-07 8.97456166652137e-06 9.43208973515092e-06 1.01609378922904e-06 -2.06027258090351e-06 2.09785932463005e-05 -1.2411943127241e-06 3.21956582807122e-07 -4.23500942327947e-06 8.57411005591085e-06 1.13669467525495e-07 -1.2411943127241e-06 2.76198199606788e-05 -2.05331454978234e-05 8.44296867499707e-06 -5.68759177217846e-06 8.97456166652137e-06 3.21956582807122e-07 -2.05331454978234e-05 0.000106513829540308 -2.16900653397901e-05 1.73904673050513e-05 9.43208973515092e-06 -4.23500942327947e-06 8.44296867499707e-06 -2.16900653397901e-05 5.69974347835356e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 869 0 0 0 0 0 2144 +1149 1103 0.996723095415291 -0.00679311686114589 0.0806035025856335 0.0505973947964393 0.0104844869913822 0.998911039968751 -0.0454621794580485 0.0541939326955348 -0.0802068986951182 0.0461582906080705 0.995708926147522 0.244097122258231 6.38777471386619e-05 3.92648139244779e-05 -4.09580966918509e-06 -1.83791924250417e-06 -1.8227107145951e-05 3.65627898312921e-05 3.92648139244779e-05 9.55865393422093e-05 -7.93351957508614e-06 3.9879582367156e-06 1.17457634789491e-05 4.78606693781135e-06 -4.09580966918509e-06 -7.93351957508614e-06 1.65284108566931e-05 -2.58994240012963e-07 -1.66465152652994e-06 3.2466682006397e-06 -1.83791924250417e-06 3.9879582367156e-06 -2.58994240012963e-07 2.542996814762e-05 -1.91674814589722e-06 7.93609244212127e-06 -1.8227107145951e-05 1.17457634789491e-05 -1.66465152652994e-06 -1.91674814589722e-06 8.33132104313316e-05 -2.66711361858796e-05 3.65627898312921e-05 4.78606693781135e-06 3.2466682006397e-06 7.93609244212127e-06 -2.66711361858796e-05 8.76143718444477e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 588 0 0 0 0 0 2364 +1149 1112 0.996841000146364 -0.00598784689496052 0.0791970082563668 0.0714943501039454 0.0084208617478637 0.999501645957147 -0.0304228337992626 0.00296047085645146 -0.0789753728362196 0.0309936351291148 0.996394643234729 0.212619324999509 0.000170539120597133 6.87024442363025e-05 -1.78190174998423e-05 -2.09734210503938e-05 6.80950307739333e-05 0.000177847515863145 6.87024442363025e-05 0.000153120608456473 5.35761630205438e-07 -7.82947828777423e-07 2.47315839970822e-05 6.89607750919992e-05 -1.78190174998423e-05 5.35761630205438e-07 1.87217631850164e-05 3.76540525240877e-06 -4.86666960951211e-06 -1.14301570850746e-05 -2.09734210503938e-05 -7.82947828777423e-07 3.76540525240877e-06 4.95064701192811e-05 -8.17268272914655e-05 -4.13819807117834e-05 6.80950307739333e-05 2.47315839970822e-05 -4.86666960951211e-06 -8.17268272914655e-05 0.000311232310121493 0.000124907558775322 0.000177847515863145 6.89607750919992e-05 -1.14301570850746e-05 -4.13819807117834e-05 0.000124907558775322 0.000278489255442107 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 780 0 0 0 0 0 2396 +1149 1108 0.996940435829307 -0.00565916931102353 0.0779598692352671 0.0577568032816545 0.0081056868839323 0.999483374788892 -0.0311011472577354 0.0412914875758905 -0.0777435865432669 0.0316379095914516 0.996471262720643 0.219536247425741 0.000108491924747541 9.30747021889516e-05 -6.4553580749671e-06 1.66180506474108e-09 -2.46592650722607e-05 0.000100346013443352 9.30747021889516e-05 0.000121724831887881 -5.30428256968945e-06 3.0314338377871e-06 -3.22387663580662e-05 9.75779430017419e-05 -6.4553580749671e-06 -5.30428256968945e-06 1.35636088688173e-05 5.335668731621e-07 -3.08898033702253e-06 -6.11975985226033e-07 1.66180506474108e-09 3.0314338377871e-06 5.335668731621e-07 3.51064924767622e-05 -4.79477299227028e-05 -8.30891053455364e-09 -2.46592650722607e-05 -3.22387663580662e-05 -3.08898033702253e-06 -4.79477299227028e-05 0.000213174827377865 -2.1332901230716e-05 0.000100346013443352 9.75779430017419e-05 -6.11975985226033e-07 -8.30891053455364e-09 -2.1332901230716e-05 0.000166351947123451 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 648 0 0 0 0 0 2340 +1149 1107 0.996009170470059 -0.00768527090160201 0.0889194520378666 0.0705745958859578 0.010632960963705 0.999407862344182 -0.0327240710452783 0.0044553367295363 -0.0886153061309941 0.0335389519186436 0.995501113120176 0.218103161421529 4.81008004758681e-05 3.87271158145527e-05 -4.26801899701675e-06 -8.73469855179714e-06 2.64383399851147e-05 2.2928632699189e-05 3.87271158145527e-05 8.77413707693403e-05 -5.14576255458368e-07 8.51711070623573e-06 -2.18261569070438e-05 2.24431588502144e-05 -4.26801899701675e-06 -5.14576255458368e-07 1.43747626138999e-05 1.76024103386188e-06 -7.83219042618977e-06 1.26713253081303e-06 -8.73469855179714e-06 8.51711070623573e-06 1.76024103386188e-06 4.55934156986092e-05 -7.38237453997915e-05 -1.09235659273517e-05 2.64383399851147e-05 -2.18261569070438e-05 -7.83219042618977e-06 -7.38237453997915e-05 0.000296947650397583 4.26453209558834e-05 2.2928632699189e-05 2.24431588502144e-05 1.26713253081303e-06 -1.09235659273517e-05 4.26453209558834e-05 7.47233137784087e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 642 0 0 0 0 0 2317 +1149 1123 0.995781400760643 -0.00586253523868934 0.0915698235214354 0.0821510329648647 0.0094525645736913 0.999201469798431 -0.0388210223414391 -0.0149796612537917 -0.0912691126403226 0.0395228216759563 0.995041655230885 0.227997725472913 3.20563179635496e-05 2.20828232336423e-05 -4.51398561935858e-06 2.2066912908943e-06 -1.62757811090678e-05 5.16926006289835e-06 2.20828232336423e-05 5.01594446236059e-05 -3.75525913300591e-06 6.30469844312959e-06 -9.12308789035398e-06 -6.91627827431646e-06 -4.51398561935858e-06 -3.75525913300591e-06 1.18375078403217e-05 1.22341169219989e-06 1.83650387613571e-06 1.03968184117214e-06 2.2066912908943e-06 6.30469844312959e-06 1.22341169219989e-06 3.49171359351399e-05 -4.79185693886121e-05 4.99099711772522e-06 -1.62757811090678e-05 -9.12308789035398e-06 1.83650387613571e-06 -4.79185693886121e-05 0.000170628260882047 -3.08459133044409e-06 5.16926006289835e-06 -6.91627827431646e-06 1.03968184117214e-06 4.99099711772522e-06 -3.08459133044409e-06 4.15216368370295e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1037 0 0 0 0 0 2508 +1149 1120 0.995933980236102 -0.00585935737556877 0.0898953555097354 0.0812525492506724 0.00952085653621599 0.999139999322423 -0.0403561029437388 -0.0156168214243971 -0.0895815846136534 0.041047895014656 0.995133262439244 0.230614229784555 4.10063331446581e-05 1.89340667174368e-05 -7.07305889839889e-06 -2.22816074520073e-06 1.13414590391578e-05 2.03446356033051e-05 1.89340667174368e-05 5.18304827502404e-05 -2.81673227249697e-06 5.20923791798059e-06 -1.73748970204177e-06 -8.08338668151925e-06 -7.07305889839889e-06 -2.81673227249697e-06 1.3251545709247e-05 1.27982129208895e-06 6.67459595676835e-07 -2.66494540032871e-06 -2.22816074520073e-06 5.20923791798059e-06 1.27982129208895e-06 2.84434239538025e-05 -2.82356039648678e-05 7.08702652720132e-07 1.13414590391578e-05 -1.73748970204177e-06 6.67459595676835e-07 -2.82356039648678e-05 0.000110452778502868 1.71050737533078e-05 2.03446356033051e-05 -8.08338668151925e-06 -2.66494540032871e-06 7.08702652720132e-07 1.71050737533078e-05 6.12303111778987e-05 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1035 0 0 0 0 0 2452 +1150 1064 0.988356628902216 0.0622330612815006 0.138846030510711 0.0418775920898039 -0.0670705662184663 0.997283974910479 0.0304337400575376 0.0903229503067118 -0.136574936398238 -0.039391870611694 0.989846234158381 0.162225052921637 2.37143413666677e-05 1.15527306343449e-05 -1.58031343269839e-06 -8.44914498444486e-07 -4.90126302497917e-07 4.90256687410356e-06 1.15527306343449e-05 6.19455074840102e-05 4.37913625541238e-06 -8.96612953625129e-08 4.46069516303433e-06 1.49398402714931e-06 -1.58031343269839e-06 4.37913625541238e-06 1.61211047601837e-05 -2.0398283679217e-06 -4.535711844688e-07 -2.78666646316073e-07 -8.44914498444486e-07 -8.96612953625129e-08 -2.0398283679217e-06 2.25930209410767e-05 4.17849932658833e-06 7.27964330431215e-07 -4.90126302497917e-07 4.46069516303433e-06 -4.535711844688e-07 4.17849932658833e-06 4.13865151000483e-05 2.85005617641778e-06 4.90256687410356e-06 1.49398402714931e-06 -2.78666646316073e-07 7.27964330431215e-07 2.85005617641778e-06 5.05498452658175e-05 0 34 0 0 0 0 101 0 0 49 0 0 0 0 0 0 0 0 1023 0 0 0 0 0 2512 +1150 1065 0.991492428716543 0.00239799976258708 0.130142281349719 0.0573226691256538 -0.00741847304112009 0.999246175343668 0.0381057386595359 0.101011128272685 -0.129952799336948 -0.0387470083772839 0.990762806773802 0.209346749811638 0.000110813129150889 1.37020882920016e-05 -8.7456834073497e-06 3.33169370887032e-05 -9.79227628119952e-05 0.00012289293206692 1.37020882920016e-05 6.77924002343977e-05 5.72702165178708e-06 -1.9396830541423e-05 5.75590249992834e-05 -1.42049574032343e-05 -8.7456834073497e-06 5.72702165178708e-06 1.68738105909984e-05 -3.1198060234809e-06 1.48218794616536e-05 -1.35989221660295e-05 3.33169370887032e-05 -1.9396830541423e-05 -3.1198060234809e-06 4.95234623482028e-05 -7.89136732219007e-05 5.46616112014746e-05 -9.79227628119952e-05 5.75590249992834e-05 1.48218794616536e-05 -7.89136732219007e-05 0.000272269995882693 -0.000166980306123977 0.00012289293206692 -1.42049574032343e-05 -1.35989221660295e-05 5.46616112014746e-05 -0.000166980306123977 0.000250264563936951 0 0 0 0 42 0 0 0 0 159 0 0 0 0 0 0 0 0 988 0 0 0 0 0 2348 +1150 1068 0.995792783738814 -0.0645021794414063 0.0650861022109395 0.0841843566796735 0.0603827951449914 0.996160478763015 0.0633894202617373 0.0822919531432909 -0.0689249584996773 -0.0591926464854358 0.995864238085628 0.276281811122615 3.39688616607714e-05 2.78457033471865e-05 -8.50604605687154e-09 -9.65727083980894e-07 5.80095759142972e-06 1.25128266033099e-05 2.78457033471865e-05 7.15645024579824e-05 3.57091017870114e-06 1.04489827077779e-06 -1.17041225636261e-05 1.01937441170479e-05 -8.50604605687154e-09 3.57091017870114e-06 1.82804173700106e-05 -1.81514571262603e-06 -3.72118798625223e-06 -1.06456168536629e-07 -9.65727083980894e-07 1.04489827077779e-06 -1.81514571262603e-06 2.74040264232008e-05 -1.57222777935623e-05 5.83478280040649e-07 5.80095759142972e-06 -1.17041225636261e-05 -3.72118798625223e-06 -1.57222777935623e-05 0.000100289619998794 -1.44459906549577e-05 1.25128266033099e-05 1.01937441170479e-05 -1.06456168536629e-07 5.83478280040649e-07 -1.44459906549577e-05 0.000112965053570162 0 0 0 0 18 0 0 0 0 92 0 0 0 0 0 0 0 0 883 0 0 0 0 0 1697 +1150 1070 0.99790763260768 -0.0612127935721173 0.0208170767984438 0.0952710138628548 0.0600528763733462 0.996818820231596 0.0524012563911999 0.0909478967826038 -0.0239584812252894 -0.051041488371579 0.998409113360947 0.29287830227669 5.02661951848722e-05 3.9430757870071e-05 -2.23473688185856e-06 9.04478944683504e-06 -2.56587128292315e-05 1.93407053239104e-05 3.9430757870071e-05 8.12903054003288e-05 -5.51889321220386e-06 -7.44898235263729e-07 -1.25554107749316e-05 2.33101639014175e-05 -2.23473688185856e-06 -5.51889321220386e-06 1.65356768238938e-05 4.89717284858831e-07 1.12570158206185e-05 -8.565601753962e-07 9.04478944683504e-06 -7.44898235263729e-07 4.89717284858831e-07 3.58745162283777e-05 -4.1798104424638e-05 -2.75205469533485e-06 -2.56587128292315e-05 -1.25554107749316e-05 1.12570158206185e-05 -4.1798104424638e-05 0.000161112411477447 4.32246552693111e-07 1.93407053239104e-05 2.33101639014175e-05 -8.565601753962e-07 -2.75205469533485e-06 4.32246552693111e-07 0.000104597635582454 0 0 0 0 11 0 0 0 0 82 0 0 0 0 0 0 0 0 859 0 0 0 0 0 1666 +1150 1067 0.993221019770613 -0.0564581309609125 0.101609474628227 0.0846619693070821 0.0470917075277714 0.994614280169651 0.0923298692987551 0.0778090158385439 -0.106275006318243 -0.086919003278954 0.990530519419291 0.250625851106219 7.17731016485716e-05 3.88426252543401e-05 1.3328159451434e-06 1.02230419830453e-06 -7.71110096420347e-06 6.99541288892642e-05 3.88426252543401e-05 0.000102735955721104 7.98970419205074e-06 -8.98594971236598e-06 1.02051898494786e-05 4.36483328687525e-05 1.3328159451434e-06 7.98970419205074e-06 2.09323638186798e-05 -2.70853460531822e-06 3.47989716852432e-06 -1.15843583629809e-06 1.02230419830453e-06 -8.98594971236598e-06 -2.70853460531822e-06 3.05534594162682e-05 -1.242424435048e-05 -2.55610311068945e-06 -7.71110096420347e-06 1.02051898494786e-05 3.47989716852432e-06 -1.242424435048e-05 0.000101966519247661 -9.50411884133559e-06 6.99541288892642e-05 4.36483328687525e-05 -1.15843583629809e-06 -2.55610311068945e-06 -9.50411884133559e-06 0.000166871284240257 0 0 0 0 21 0 0 0 0 108 0 0 0 0 0 0 0 0 925 0 0 0 0 0 1898 +1150 1066 0.989525030775138 -0.0357932868472483 0.139853688139184 0.0783760944747157 0.0262221230060711 0.997223962641486 0.069690520149204 0.0841942696932611 -0.141959901854418 -0.0652932534821381 0.987716648293022 0.223024546339449 4.76400467558585e-05 2.84187898701667e-05 -3.02221078075174e-07 -3.85282967940902e-06 -5.16949550424211e-06 2.73372377274728e-05 2.84187898701667e-05 8.56834747469447e-05 5.28283881288388e-06 -1.26146014439561e-05 1.97428915719213e-05 2.87380753097912e-05 -3.02221078075174e-07 5.28283881288388e-06 1.94299590497629e-05 -6.34301436926674e-06 2.19068372272518e-06 3.71539346090891e-06 -3.85282967940902e-06 -1.26146014439561e-05 -6.34301436926674e-06 3.24272973378454e-05 -1.70806017138315e-05 -1.00054352009772e-05 -5.16949550424211e-06 1.97428915719213e-05 2.19068372272518e-06 -1.70806017138315e-05 0.00010797780309368 -3.41672705404738e-06 2.73372377274728e-05 2.87380753097912e-05 3.71539346090891e-06 -1.00054352009772e-05 -3.41672705404738e-06 8.7469495977659e-05 0 0 0 0 9 0 0 0 0 81 0 0 0 0 0 0 0 0 954 0 0 0 0 0 2164 +1150 1069 0.997205306442284 -0.0616026463991057 0.0422692649566624 0.0891051201668011 0.0587415577973231 0.996096840118476 0.0658825811086003 0.0925342876747538 -0.0461628226053556 -0.0632154970131082 0.996931690110457 0.284121582030089 3.68944662861087e-05 3.24750671085134e-05 3.17472425417263e-06 -8.31283593907337e-07 -7.65976564727477e-06 7.51249387641695e-06 3.24750671085134e-05 8.86577773182855e-05 6.21157400807864e-06 9.43106721924094e-06 -5.04711808031244e-05 3.46490591756767e-06 3.17472425417263e-06 6.21157400807864e-06 1.61701109828335e-05 3.60196969101949e-06 -2.56475222382516e-06 4.2609258885881e-07 -8.31283593907337e-07 9.43106721924094e-06 3.60196969101949e-06 2.6763695138689e-05 -1.97144224548758e-05 4.99904506453005e-06 -7.65976564727477e-06 -5.04711808031244e-05 -2.56475222382516e-06 -1.97144224548758e-05 0.000121568806974637 -1.21891933112598e-05 7.51249387641695e-06 3.46490591756767e-06 4.2609258885881e-07 4.99904506453005e-06 -1.21891933112598e-05 8.75707523645715e-05 0 0 0 0 20 0 0 0 0 90 0 0 0 0 0 0 0 0 870 0 0 0 0 0 1833 +1150 1101 0.993819938692841 -0.0529083389496499 0.0975840003594129 0.105305199128593 0.0574502518972533 0.997363474155217 -0.0443347378246179 0.0392852487694722 -0.0949810402843592 0.0496669718286148 0.99423930413954 0.347179130015984 3.47151223639416e-05 1.92907572699219e-05 -7.15575517828142e-06 8.45925906663833e-06 -1.46652594809435e-05 1.42456479628408e-05 1.92907572699219e-05 7.00144330417652e-05 2.74407760349586e-07 -1.18691212649081e-05 3.93440614663734e-05 -6.74754776257589e-06 -7.15575517828142e-06 2.74407760349586e-07 1.62827056320056e-05 -5.50564750368994e-07 1.85801096789685e-06 -2.98397961884294e-06 8.45925906663833e-06 -1.18691212649081e-05 -5.50564750368994e-07 5.30793011023181e-05 -7.45895285558426e-05 3.37806276031148e-05 -1.46652594809435e-05 3.93440614663734e-05 1.85801096789685e-06 -7.45895285558426e-05 0.000253397030288625 -5.98868900998556e-05 1.42456479628408e-05 -6.74754776257589e-06 -2.98397961884294e-06 3.37806276031148e-05 -5.98868900998556e-05 9.37101604162853e-05 0 0 0 0 0 0 0 0 0 68 0 0 0 0 0 0 0 0 636 0 0 0 0 0 2079 +1150 1071 0.997342330332971 -0.0712463072487188 -0.0152394169646028 0.110194673445702 0.071757847130299 0.996765958595765 0.0361722982389818 0.0827401911489699 0.0126129893849361 -0.0371697119720662 0.99922936556663 0.30659847636978 4.77793054042185e-05 2.73551863559755e-05 -6.19800977060019e-06 1.09538092004016e-05 -8.56550763194903e-06 3.34516598433069e-05 2.73551863559755e-05 7.59018717701427e-05 1.3299306299955e-06 2.41498470101908e-06 -6.71424329815267e-06 1.14372304121219e-05 -6.19800977060019e-06 1.3299306299955e-06 1.69833020895165e-05 -5.49190431280631e-06 -1.0935445686732e-06 -7.37954374367374e-06 1.09538092004016e-05 2.41498470101908e-06 -5.49190431280631e-06 3.36706909261048e-05 -1.98562517193515e-05 2.0175626084531e-05 -8.56550763194903e-06 -6.71424329815267e-06 -1.0935445686732e-06 -1.98562517193515e-05 0.000116404190881982 -2.04802486825611e-05 3.34516598433069e-05 1.14372304121219e-05 -7.37954374367374e-06 2.0175626084531e-05 -2.04802486825611e-05 0.000104396382713977 0 0 0 0 6 0 0 0 0 63 0 0 0 0 0 0 0 0 831 0 0 0 0 0 1853 +1150 1102 0.993406826964676 -0.0538143536393722 0.101226930618043 0.086806466336301 0.0574428667342195 0.997794057537287 -0.0332766555505896 0.0869772193878993 -0.0992128681236873 0.038872021887914 0.99430667940682 0.317462258387394 3.6913589652621e-05 1.63166835936799e-05 -6.66046943209188e-06 6.74596781706783e-06 -8.4857925515493e-06 1.43487694670537e-05 1.63166835936799e-05 8.54530710140564e-05 2.0451670046198e-06 -7.05182243779732e-06 1.1097948919979e-05 -1.79564376987883e-05 -6.66046943209188e-06 2.0451670046198e-06 1.65676288187746e-05 -2.74383334412088e-06 6.20950414885229e-07 -3.07316694056577e-06 6.74596781706783e-06 -7.05182243779732e-06 -2.74383334412088e-06 3.37675940855146e-05 -2.08823136914636e-05 9.70107392612019e-06 -8.4857925515493e-06 1.1097948919979e-05 6.20950414885229e-07 -2.08823136914636e-05 0.000110861537131351 -1.5907288481541e-05 1.43487694670537e-05 -1.79564376987883e-05 -3.07316694056577e-06 9.70107392612019e-06 -1.5907288481541e-05 0.000101682981310172 0 0 0 0 7 0 0 0 0 75 0 0 0 0 0 0 0 0 624 0 0 0 0 0 1956 +1150 1100 0.993256798609454 -0.0529308080312436 0.103146796252999 0.0843191542181208 0.0569793491271868 0.99770039188121 -0.0367053376652896 0.0946044081510503 -0.100966755861225 0.042335063496355 0.993988660201724 0.333656906736009 3.92951649770721e-05 9.84552172129136e-06 -6.944114535355e-06 2.00869807775409e-06 -4.41246702583503e-06 1.14109352519265e-05 9.84552172129136e-06 0.000110193049186457 6.3887084627128e-06 -6.45974724088947e-06 -6.39523724875978e-06 -5.33618386794031e-06 -6.944114535355e-06 6.3887084627128e-06 1.64721931494876e-05 -1.97167452078659e-06 -5.94337955320027e-07 -7.01786993059954e-07 2.00869807775409e-06 -6.45974724088947e-06 -1.97167452078659e-06 2.68460467129903e-05 9.71483344570161e-06 9.51092514144046e-06 -4.41246702583503e-06 -6.39523724875978e-06 -5.94337955320027e-07 9.71483344570161e-06 4.94624304735806e-05 -1.7435504862373e-05 1.14109352519265e-05 -5.33618386794031e-06 -7.01786993059954e-07 9.51092514144046e-06 -1.7435504862373e-05 7.57296564637852e-05 0 0 0 0 14 0 0 0 0 88 0 0 0 0 0 0 0 0 616 0 0 0 0 0 1958 +1150 1103 0.993957672339394 -0.0541586376260382 0.0954724440252024 0.0772258871610287 0.0581825171193638 0.997509179946857 -0.0398776958136363 0.099217989516165 -0.0930749176701697 0.0451915688181041 0.994632988497993 0.331677819618856 2.93301255310612e-05 1.69636443397108e-05 8.15927330444535e-08 -1.75089027260662e-06 -9.87123926351988e-06 6.89942279382177e-06 1.69636443397108e-05 6.04868158492207e-05 -4.29383660496656e-07 1.65126948813765e-06 6.69924496716333e-06 -2.52444392610194e-06 8.15927330444535e-08 -4.29383660496656e-07 1.29978910688755e-05 8.25557805686765e-08 9.55075355987758e-07 4.44699449556704e-06 -1.75089027260662e-06 1.65126948813765e-06 8.25557805686765e-08 2.22396781124571e-05 8.77768080967681e-06 4.86186852863822e-06 -9.87123926351988e-06 6.69924496716333e-06 9.55075355987758e-07 8.77768080967681e-06 4.39745261411305e-05 -2.1493124859885e-05 6.89942279382177e-06 -2.52444392610194e-06 4.44699449556704e-06 4.86186852863822e-06 -2.1493124859885e-05 7.87478740676946e-05 0 0 0 0 15 0 0 0 0 85 0 0 0 0 0 0 0 0 580 0 0 0 0 0 2034 +1150 1112 0.993468936800942 -0.0545163821175381 0.100236897859122 0.0999048835353319 0.0577468581033952 0.997891982991398 -0.0296123396691687 0.049954046708914 -0.0984112391487463 0.0352073055247126 0.9945228371671 0.29658450801316 5.31493364952187e-05 3.14729997456786e-05 -7.84397512137252e-06 -1.2374915238952e-06 2.27128875699818e-05 7.17631175430539e-05 3.14729997456786e-05 9.7355358361074e-05 1.06167649651987e-06 -8.44935171343801e-06 3.3202859022346e-05 6.03882874571643e-05 -7.84397512137252e-06 1.06167649651987e-06 1.43521308564316e-05 -1.1604727881111e-06 3.48362540550825e-06 -6.3409000343962e-06 -1.2374915238952e-06 -8.44935171343801e-06 -1.1604727881111e-06 5.74882640874548e-05 -8.80855720496081e-05 -2.34632752976746e-05 2.27128875699818e-05 3.3202859022346e-05 3.48362540550825e-06 -8.80855720496081e-05 0.000290053973368249 7.95118404242573e-05 7.17631175430539e-05 6.03882874571643e-05 -6.3409000343962e-06 -2.34632752976746e-05 7.95118404242573e-05 0.000275218759463307 0 0 0 0 0 0 0 0 0 72 0 0 0 0 0 0 0 0 769 0 0 0 0 0 2148 +1150 1104 0.993349539156518 -0.0552188837997839 0.101032509270228 0.0799638221042174 0.058851713531251 0.997710014524323 -0.0333347076229919 0.100915841808778 -0.0989604409446939 0.0390589527481312 0.99432450907048 0.324289678541297 0.000126424961620292 9.55559473593091e-05 2.79957263914789e-07 1.60793315808639e-05 -9.80131029282475e-05 0.000201750169437173 9.55559473593091e-05 0.000156789098048555 6.08807657823201e-06 1.22144605209651e-06 -4.34417259484513e-05 0.000163005549819936 2.79957263914789e-07 6.08807657823201e-06 1.44160809953217e-05 4.99393420315298e-07 2.60235020679561e-06 1.93434261402822e-06 1.60793315808639e-05 1.22144605209651e-06 4.99393420315298e-07 3.60983995513746e-05 -2.9598889710269e-05 5.79935243799466e-05 -9.80131029282475e-05 -4.34417259484513e-05 2.60235020679561e-06 -2.9598889710269e-05 0.000199564831516934 -0.0002474585464293 0.000201750169437173 0.000163005549819936 1.93434261402822e-06 5.79935243799466e-05 -0.0002474585464293 0.000562397968303921 0 0 0 0 13 0 0 0 0 87 0 0 0 0 0 0 0 0 674 0 0 0 0 0 2047 +1151 1066 0.987564982598825 -0.108166229775957 0.114085371019412 0.0804528098957509 0.100633076257309 0.992468027996331 0.0698584094298166 0.150350193218753 -0.120782403965034 -0.0575089570512986 0.991011771247597 0.308961282492128 0.000149521161793389 8.25053997316655e-05 -6.5572631069281e-07 2.55758810103395e-05 -0.000127141229648952 0.000209149441634611 8.25053997316655e-05 0.000112701879496263 6.58459353956358e-06 -3.35314736578215e-06 -4.36524830509986e-05 0.000118223214088777 -6.5572631069281e-07 6.58459353956358e-06 1.62012587668941e-05 -1.42071399486534e-06 -3.72560199773649e-06 4.62009349048971e-06 2.55758810103395e-05 -3.35314736578215e-06 -1.42071399486534e-06 4.38363892736464e-05 -6.6835734757717e-05 4.69522651387672e-05 -0.000127141229648952 -4.36524830509986e-05 -3.72560199773649e-06 -6.6835734757717e-05 0.00029882053715518 -0.000234092627487492 0.000209149441634611 0.000118223214088777 4.62009349048971e-06 4.69522651387672e-05 -0.000234092627487492 0.000419102069508748 0 0 0 0 218 0 0 0 0 282 0 0 0 0 0 0 0 0 868 0 0 0 0 0 1836 +1150 1108 0.993889832988227 -0.0529648425638933 0.0968386562010072 0.085053813020869 0.0563303088410454 0.997887816046141 -0.0323543334429095 0.0907795795602793 -0.0949204729682028 0.0376115944735733 0.994774080770427 0.309408795212892 3.68762117189425e-05 2.25359807854545e-05 -5.98078607891483e-06 -1.83992280074289e-06 -3.44918696245731e-07 1.88670855230518e-05 2.25359807854545e-05 7.63546733279445e-05 2.45623237094743e-07 -5.03688222539415e-06 -3.32054436832504e-06 1.17051194743502e-05 -5.98078607891483e-06 2.45623237094743e-07 1.69851329293167e-05 6.05972405779164e-07 -9.02176521214836e-07 -3.71656107192398e-07 -1.83992280074289e-06 -5.03688222539415e-06 6.05972405779164e-07 2.95650388837253e-05 -1.67462231320976e-05 -2.02761716983825e-07 -3.44918696245731e-07 -3.32054436832504e-06 -9.02176521214836e-07 -1.67462231320976e-05 0.000108288275130286 -1.48341412686109e-05 1.88670855230518e-05 1.17051194743502e-05 -3.71656107192398e-07 -2.02761716983825e-07 -1.48341412686109e-05 0.00012002318247847 0 0 0 0 17 0 0 0 0 91 0 0 0 0 0 0 0 0 628 0 0 0 0 0 1954 +1151 1065 0.990269128791936 -0.0719029855764175 0.119151219997352 0.0666077002900407 0.0672569513829838 0.996827081792614 0.0425707821808327 0.156767098606123 -0.121834129259115 -0.0341427835716194 0.991963061448184 0.287924539057973 5.55995834509925e-05 3.36822662803247e-05 -2.72222878100583e-06 1.78082648955508e-06 2.43013408755925e-06 1.76464403429273e-05 3.36822662803247e-05 6.66114453508483e-05 4.9037313955992e-06 -7.05299864233469e-06 9.22156577009161e-06 1.76795565205169e-05 -2.72222878100583e-06 4.9037313955992e-06 1.51593376043818e-05 -7.70106668193624e-07 2.84530712879053e-06 5.25365585365983e-07 1.78082648955508e-06 -7.05299864233469e-06 -7.70106668193624e-07 2.37294256386538e-05 -3.55725986839274e-06 -7.84361146653517e-08 2.43013408755925e-06 9.22156577009161e-06 2.84530712879053e-06 -3.55725986839274e-06 6.8930246736506e-05 -2.28789999443365e-05 1.76464403429273e-05 1.76795565205169e-05 5.25365585365983e-07 -7.84361146653517e-08 -2.28789999443365e-05 0.00012397885212698 0 0 0 0 291 0 0 0 0 375 0 0 0 0 0 0 0 0 939 0 0 0 0 0 1977 +1151 1063 0.990805912051551 0.0496288702870929 0.125859524382232 0.0118647711136125 -0.0528749093187829 0.998345809460053 0.0225807151809418 0.163728820753362 -0.124530673362932 -0.029027917038245 0.991791052300935 0.216452047166136 2.15390733194205e-05 1.37958044567551e-05 -4.26388646564578e-07 -2.26930010805418e-07 -9.00855019924416e-07 4.35546544926086e-06 1.37958044567551e-05 3.61033189703089e-05 -6.00368109532577e-07 -2.85789308715759e-07 -3.99287895543277e-06 1.21362206523126e-05 -4.26388646564578e-07 -6.00368109532577e-07 1.27510481174083e-05 8.74736192459782e-07 1.38095281686921e-06 -3.98924732950163e-08 -2.26930010805418e-07 -2.85789308715759e-07 8.74736192459782e-07 2.70002510014626e-05 -7.14859814442157e-06 5.68648725169832e-06 -9.00855019924416e-07 -3.99287895543277e-06 1.38095281686921e-06 -7.14859814442157e-06 5.5502828294635e-05 -1.58006966591645e-05 4.35546544926086e-06 1.21362206523126e-05 -3.98924732950163e-08 5.68648725169832e-06 -1.58006966591645e-05 0.000100558086779963 256 362 0 0 16 256 363 0 0 89 0 0 0 0 0 0 0 0 1051 0 0 0 0 0 2443 +1151 1064 0.992279843075313 -0.0104299656811922 0.123579645744436 0.0511461901630984 0.00736586001071915 0.999654647269886 0.025225588160083 0.142010995464459 -0.12380006919519 -0.0241205722902419 0.992013982189595 0.276744636360365 3.99315365583766e-05 3.05278263491305e-05 -3.54849230368005e-06 4.39868708542709e-06 -1.15663178640247e-05 2.94487039585647e-05 3.05278263491305e-05 5.87876657288228e-05 -2.1291315448147e-06 -3.7406536102369e-06 -2.05609422370664e-06 2.0240885695563e-05 -3.54849230368005e-06 -2.1291315448147e-06 1.48967701327677e-05 -2.75120113867196e-06 -7.45008261299663e-07 -4.73629948101111e-06 4.39868708542709e-06 -3.7406536102369e-06 -2.75120113867196e-06 3.10286955243284e-05 -2.16511955414764e-05 1.07717684995929e-05 -1.15663178640247e-05 -2.05609422370664e-06 -7.45008261299663e-07 -2.16511955414764e-05 8.51728086577562e-05 -3.52242997080692e-05 2.94487039585647e-05 2.0240885695563e-05 -4.73629948101111e-06 1.07717684995929e-05 -3.52242997080692e-05 0.000140207579255529 0 101 0 0 179 0 101 0 0 247 0 0 0 0 0 0 0 0 949 0 0 0 0 0 2216 +1151 1070 0.990818469308467 -0.134267911705679 0.0158394685334479 0.109950851433186 0.133461412317592 0.990071539336031 0.0441180056096738 0.145462881802817 -0.0216058394750057 -0.0415989769462854 0.998900752235978 0.3904753549478 3.86041436481258e-05 2.01070014859674e-05 1.93990428288033e-07 4.39812748026532e-06 7.49383952917379e-07 1.87928525745579e-05 2.01070014859674e-05 9.31238229270667e-05 2.51713962703647e-07 2.81527812090939e-06 -1.42399086815604e-05 1.96094532986368e-05 1.93990428288033e-07 2.51713962703647e-07 1.72801444819791e-05 8.89496428033065e-07 5.03487624446851e-06 -5.94634466154175e-06 4.39812748026532e-06 2.81527812090939e-06 8.89496428033065e-07 2.43080795874326e-05 -7.35572760086892e-06 1.12631350403064e-05 7.49383952917379e-07 -1.42399086815604e-05 5.03487624446851e-06 -7.35572760086892e-06 8.90172346124146e-05 -1.20179114095307e-05 1.87928525745579e-05 1.96094532986368e-05 -5.94634466154175e-06 1.12631350403064e-05 -1.20179114095307e-05 0.00013771986760268 0 0 0 0 134 0 0 0 0 195 0 0 0 0 0 0 0 0 759 0 0 0 0 0 1555 +1151 1071 0.989130847152342 -0.144875851257593 -0.0251227970989943 0.113939684975537 0.145511984131999 0.989023558743663 0.0256644252612299 0.152222005296478 0.0211288827356848 -0.0290411427531386 0.999354883083049 0.397402291266245 5.70737784053071e-05 4.60261268863801e-05 -2.4777512517099e-06 1.03735377697214e-05 -1.13818865843563e-05 3.5227016373218e-05 4.60261268863801e-05 8.60706174973381e-05 1.58255694234668e-06 7.89600081151903e-06 -1.99527319170679e-05 3.47651538085442e-05 -2.4777512517099e-06 1.58255694234668e-06 1.60029807174799e-05 -1.82890337216061e-07 -1.52664414645646e-06 -5.20051413004822e-06 1.03735377697214e-05 7.89600081151903e-06 -1.82890337216061e-07 2.90674742686653e-05 -2.14419077387522e-05 2.25218873025548e-05 -1.13818865843563e-05 -1.99527319170679e-05 -1.52664414645646e-06 -2.14419077387522e-05 0.00012185715734853 -2.34390756965805e-05 3.5227016373218e-05 3.47651538085442e-05 -5.20051413004822e-06 2.25218873025548e-05 -2.34390756965805e-05 0.000142970703244441 0 0 0 0 109 0 0 0 0 175 0 0 0 0 0 0 0 0 715 0 0 0 0 0 1508 +1151 1067 0.98787133239318 -0.128576530673208 0.087053468602716 0.0925010248637464 0.120319549427918 0.988250218570711 0.0942587477129068 0.140012483324343 -0.0981500721404993 -0.0826412805744458 0.991734330394905 0.342261111827578 4.18209283445391e-05 3.00419463879515e-05 2.4860855113095e-06 -4.35160929478009e-06 -2.39149977204527e-06 3.25551296835926e-05 3.00419463879515e-05 5.97886747636136e-05 4.69568731408697e-06 2.14821060028211e-06 -2.04136214566562e-05 3.94368756375818e-05 2.4860855113095e-06 4.69568731408697e-06 1.71586282434849e-05 -1.55476632550256e-06 -1.00958590473375e-05 4.80064065348746e-06 -4.35160929478009e-06 2.14821060028211e-06 -1.55476632550256e-06 3.25162995440667e-05 -2.83888464831103e-05 -4.64048378504369e-06 -2.39149977204527e-06 -2.04136214566562e-05 -1.00958590473375e-05 -2.83888464831103e-05 0.00015127905685296 -2.04114336160056e-05 3.25551296835926e-05 3.94368756375818e-05 4.80064065348746e-06 -4.64048378504369e-06 -2.04114336160056e-05 0.000140848337416118 0 0 0 0 185 0 0 0 0 264 0 0 0 0 0 0 0 0 895 0 0 0 0 0 1471 +1151 1069 0.990385941202553 -0.134949157030328 0.0304041524324614 0.0987694808200747 0.133042163527694 0.989421366764505 0.0578372000854916 0.147159549752038 -0.0378875994515739 -0.0532361156233496 0.997862939386534 0.387260337985017 5.12152630190836e-05 3.24558590839224e-05 -1.96023825958715e-06 8.47117480468001e-06 -1.9713934598279e-05 6.45475363749669e-05 3.24558590839224e-05 6.5924346707496e-05 -1.7070838535414e-06 2.06577012651528e-08 -5.03865823980639e-06 3.75434503895701e-05 -1.96023825958715e-06 -1.7070838535414e-06 1.76545467718267e-05 9.47863832449784e-07 3.85412646474632e-06 -3.29444042589526e-06 8.47117480468001e-06 2.06577012651528e-08 9.47863832449784e-07 3.32734580151224e-05 -3.69613753387888e-05 1.21122985142306e-05 -1.9713934598279e-05 -5.03865823980639e-06 3.85412646474632e-06 -3.69613753387888e-05 0.000174795851120045 -5.23352334274975e-05 6.45475363749669e-05 3.75434503895701e-05 -3.29444042589526e-06 1.21122985142306e-05 -5.23352334274975e-05 0.000293814124605303 0 0 0 0 145 0 0 0 0 210 0 0 0 0 0 0 0 0 780 0 0 0 0 0 1618 +1151 1068 0.988585254642605 -0.138043540601428 0.0603587210056538 0.0982978311423256 0.134528521807379 0.989158711505512 0.0588822577104319 0.135814941527453 -0.0678326700310269 -0.0500901622175242 0.996438510157794 0.369386784790221 3.56424677875684e-05 2.14051890491714e-05 2.18754272561818e-06 3.89672136430274e-07 2.0469641321749e-06 1.36580664525396e-05 2.14051890491714e-05 5.78120324454359e-05 1.71868209757617e-07 4.72529794382675e-06 -1.84443233852961e-05 -1.07651396976698e-05 2.18754272561818e-06 1.71868209757617e-07 1.63302188872279e-05 -1.99145672715933e-07 2.14449443561693e-06 -4.46733874437303e-06 3.89672136430274e-07 4.72529794382675e-06 -1.99145672715933e-07 2.75493901244374e-05 -1.69067455769718e-05 -5.91551966924601e-06 2.0469641321749e-06 -1.84443233852961e-05 2.14449443561693e-06 -1.69067455769718e-05 9.64702570851467e-05 4.99454324214353e-06 1.36580664525396e-05 -1.07651396976698e-05 -4.46733874437303e-06 -5.91551966924601e-06 4.99454324214353e-06 0.00014431622017871 0 0 0 0 153 0 0 0 0 223 0 0 0 0 0 0 0 0 814 0 0 0 0 0 1517 +1151 1113 0.987581820062594 -0.127392990131227 0.0919411482812765 0.11317367861603 0.13102810814053 0.990773859993803 -0.0346235935467818 0.111002663363111 -0.0866820832638902 0.0462405062516019 0.995162314410382 0.405848079601095 4.71712125864477e-05 3.15581439085557e-05 -2.28441678846349e-06 -8.66285927464705e-06 1.60107148482953e-05 3.45922152434279e-05 3.15581439085557e-05 6.11244811728037e-05 1.38828506002918e-06 -1.56192465734988e-05 2.43243453304095e-05 1.24377483678707e-05 -2.28441678846349e-06 1.38828506002918e-06 1.5522482137342e-05 -1.57509296663495e-06 7.20869992871138e-06 1.42059621000792e-06 -8.66285927464705e-06 -1.56192465734988e-05 -1.57509296663495e-06 6.03708110502546e-05 -9.70308263243216e-05 -3.06060224294174e-05 1.60107148482953e-05 2.43243453304095e-05 7.20869992871138e-06 -9.70308263243216e-05 0.000293540573267502 5.27799562766101e-05 3.45922152434279e-05 1.24377483678707e-05 1.42059621000792e-06 -3.06060224294174e-05 5.27799562766101e-05 0.000219727765597537 0 0 0 0 137 0 0 0 0 191 0 0 0 0 0 0 0 0 626 0 0 0 0 0 1763 +1151 1101 0.986245626880059 -0.128026465557219 0.104540841669106 0.11158171093145 0.132654026277696 0.99041228663461 -0.0385540114063313 0.120180578973413 -0.0986026002308003 0.0518914887060442 0.993773012627932 0.440142611038691 4.0409357684776e-05 2.61433787587547e-05 -5.75815537555298e-06 1.05102578937602e-05 -3.31033650696126e-05 1.54140431288242e-05 2.61433787587547e-05 5.29980308067183e-05 -2.83540905270234e-06 3.57133468431346e-07 -1.45927897074184e-05 1.50605386531931e-06 -5.75815537555298e-06 -2.83540905270234e-06 1.4026376117512e-05 -1.67688210434729e-06 7.51757917133008e-06 -6.11224537659652e-06 1.05102578937602e-05 3.57133468431346e-07 -1.67688210434729e-06 5.06981034135136e-05 -7.27870575344458e-05 5.5369559900286e-05 -3.31033650696126e-05 -1.45927897074184e-05 7.51757917133008e-06 -7.27870575344458e-05 0.000259750842981371 -0.000139733030259223 1.54140431288242e-05 1.50605386531931e-06 -6.11224537659652e-06 5.5369559900286e-05 -0.000139733030259223 0.000170779961496098 0 0 0 0 130 0 0 0 0 193 0 0 0 0 0 0 0 0 551 0 0 0 0 0 1806 +1151 1102 0.987278731804041 -0.127741527497682 0.0946721071908892 0.0984593732778381 0.13150628623202 0.990710272738136 -0.034630220510278 0.137564830560379 -0.0893689118702154 0.0466396574139151 0.994905995532968 0.411276197234238 3.6514433609485e-05 2.75267089662931e-05 -1.89953868038537e-06 -1.38852876758951e-05 1.92207117003029e-05 1.13478880985735e-05 2.75267089662931e-05 4.73698357581819e-05 -3.399265560157e-06 -3.55385514878808e-06 -3.70560398207673e-06 -3.43405841932983e-06 -1.89953868038537e-06 -3.399265560157e-06 1.15214581053015e-05 5.16337317933671e-07 9.34327975181395e-07 2.88035087109588e-06 -1.38852876758951e-05 -3.55385514878808e-06 5.16337317933671e-07 4.28487721186615e-05 -5.10746193527953e-05 -3.19087191001837e-05 1.92207117003029e-05 -3.70560398207673e-06 9.34327975181395e-07 -5.10746193527953e-05 0.000170366628871078 6.37772509051254e-05 1.13478880985735e-05 -3.43405841932983e-06 2.88035087109588e-06 -3.19087191001837e-05 6.37772509051254e-05 0.000159196701466909 0 0 0 0 144 0 0 0 0 202 0 0 0 0 0 0 0 0 553 0 0 0 0 0 1777 +1152 1064 0.990137037885399 -0.0890989519198012 0.108120409610399 0.0535515448876503 0.0858236960709888 0.995709838453958 0.0345862804983032 0.197682865268277 -0.110738156929949 -0.0249658641505898 0.99353599140996 0.377354748335408 5.00697146198895e-05 4.19521297103104e-05 -1.68037529431561e-06 -9.1581286280426e-07 -3.79751901866034e-06 7.51070275082585e-06 4.19521297103104e-05 7.402520002392e-05 4.63842818364925e-07 -4.82923205649843e-06 -3.52362809169114e-06 3.14123767785356e-06 -1.68037529431561e-06 4.63842818364925e-07 1.48471360878907e-05 -6.79288367945519e-07 -6.1045943908656e-07 1.91686013827682e-06 -9.1581286280426e-07 -4.82923205649843e-06 -6.79288367945519e-07 2.43942512692718e-05 -2.67373749278427e-06 3.73596957694951e-06 -3.79751901866034e-06 -3.52362809169114e-06 -6.1045943908656e-07 -2.67373749278427e-06 4.75453197443265e-05 -2.27460417746758e-05 7.51070275082585e-06 3.14123767785356e-06 1.91686013827682e-06 3.73596957694951e-06 -2.27460417746758e-05 0.000111996052371098 0 92 0 0 334 0 92 0 0 351 0 0 0 0 0 0 0 0 824 0 0 0 0 0 2012 +1152 1068 0.97640176876365 -0.213558326439065 0.0321314046341025 0.0973325003334381 0.211518932934331 0.97569447100828 0.0572716356863846 0.188579458895427 -0.0435812685168358 -0.0491237259622867 0.997841436593032 0.465888489471255 4.31365332354819e-05 3.1335929026756e-05 2.63000610011015e-06 -1.83498935984909e-06 4.72668155364075e-06 -3.37605573717385e-06 3.1335929026756e-05 6.11996086782072e-05 8.6403053192131e-07 1.01636965926508e-06 -1.51129024483391e-05 8.62922359227589e-06 2.63000610011015e-06 8.6403053192131e-07 1.85846680287108e-05 5.32319190601871e-07 -3.54945883315011e-07 -2.02357621048884e-06 -1.83498935984909e-06 1.01636965926508e-06 5.32319190601871e-07 2.62498051051258e-05 -1.59490662476118e-05 9.68072218693934e-06 4.72668155364075e-06 -1.51129024483391e-05 -3.54945883315011e-07 -1.59490662476118e-05 0.000109406956028529 -4.98075466778969e-05 -3.37605573717385e-06 8.62922359227589e-06 -2.02357621048884e-06 9.68072218693934e-06 -4.98075466778969e-05 0.000147028869081241 0 0 0 0 251 0 0 0 0 265 0 0 0 0 0 0 0 0 735 0 0 0 0 0 1274 +1152 1067 0.976251773695612 -0.204975966284682 0.0701236593585396 0.0874584412083547 0.197676905782587 0.975278447708298 0.0987714045456247 0.208329805110554 -0.0886358577348566 -0.0825639308739247 0.992636329197281 0.442311905263002 4.24867646880675e-05 3.34090992058143e-05 -3.71730034143694e-07 2.5290105805785e-07 -1.61943321434348e-06 3.08765985163916e-05 3.34090992058143e-05 4.90705316847159e-05 -2.94213673047114e-07 -2.29974468105655e-06 -2.97129954429531e-06 4.12529870481085e-05 -3.71730034143694e-07 -2.94213673047114e-07 1.61915627927644e-05 2.88135860584972e-06 -2.62917102436007e-07 1.32723747796796e-06 2.5290105805785e-07 -2.29974468105655e-06 2.88135860584972e-06 2.53467567657943e-05 -1.198547255877e-05 -5.46275858879994e-06 -1.61943321434348e-06 -2.97129954429531e-06 -2.62917102436007e-07 -1.198547255877e-05 8.64264422914966e-05 -1.15012390620574e-05 3.08765985163916e-05 4.12529870481085e-05 1.32723747796796e-06 -5.46275858879994e-06 -1.15012390620574e-05 0.000172736941427194 0 0 0 0 278 0 0 0 0 293 0 0 0 0 0 0 0 0 776 0 0 0 0 0 1306 +1152 1065 0.983362761850107 -0.149890094524036 0.102618897724083 0.0651929231621515 0.145383545186965 0.98810545741406 0.0501121723478496 0.215396262787113 -0.108909611125006 -0.0343593450479842 0.993457664932167 0.384741365498584 9.06947156467992e-05 8.3445510361413e-05 1.7695445475105e-06 -6.35667902298305e-06 1.33012336563538e-05 2.55482168945504e-05 8.3445510361413e-05 0.000120935322865087 5.20430608794549e-06 6.55014236176195e-07 -1.92193641056319e-05 7.9254570283994e-05 1.7695445475105e-06 5.20430608794549e-06 1.37907652273067e-05 5.51937838707967e-06 -1.8226872600411e-06 2.38242928478086e-06 -6.35667902298305e-06 6.55014236176195e-07 5.51937838707967e-06 2.76519445221249e-05 -1.58911210031437e-05 -2.99664874709686e-06 1.33012336563538e-05 -1.92193641056319e-05 -1.8226872600411e-06 -1.58911210031437e-05 0.000103737886022433 -4.52356771521869e-05 2.55482168945504e-05 7.9254570283994e-05 2.38242928478086e-06 -2.99664874709686e-06 -4.52356771521869e-05 0.000251610921261561 0 0 0 0 414 0 0 0 0 432 0 0 0 0 0 0 0 0 886 0 0 0 0 0 1754 +1152 1062 0.995548177806222 0.0515132248630602 0.078931700418261 -0.026181878890458 -0.0529628834455394 0.998462090474547 0.0163825169717789 0.223713172303515 -0.0779663943237374 -0.0204900353685446 0.996745403704853 0.245925020509261 4.13026537163336e-05 2.06923565792806e-05 -3.45192963618578e-06 -3.4589277350672e-06 -2.79135631576433e-08 3.24864375922896e-05 2.06923565792806e-05 5.4096963419415e-05 -4.22756777035814e-07 -5.29762184320614e-06 6.74049262616352e-06 8.18563503240733e-06 -3.45192963618578e-06 -4.22756777035814e-07 1.33471434504306e-05 3.32492296904241e-06 3.54971329034766e-06 5.48714434088284e-07 -3.4589277350672e-06 -5.29762184320614e-06 3.32492296904241e-06 2.7312761594081e-05 -9.14089359834646e-06 3.49158695465838e-06 -2.79135631576433e-08 6.74049262616352e-06 3.54971329034766e-06 -9.14089359834646e-06 4.2954239752674e-05 -1.41640407745917e-05 3.24864375922896e-05 8.18563503240733e-06 5.48714434088284e-07 3.49158695465838e-06 -1.41640407745917e-05 0.000170754844850678 615 653 0 0 61 615 653 0 0 85 0 0 0 0 0 0 0 0 1116 0 0 0 0 0 2232 +1152 1063 0.994062110894795 -0.0270692360151875 0.105393435018212 0.00542493327155692 0.0244329380789785 0.999357423768869 0.0262253902712301 0.229135687991011 -0.106035612980794 -0.023494595540328 0.994084731177471 0.317044007602996 2.50229807137014e-05 1.35123258299847e-05 -2.67921771089829e-07 9.56157132872535e-07 -6.45955904353147e-09 2.6927810850287e-06 1.35123258299847e-05 2.86601915776974e-05 -6.48280397898496e-07 1.41299052531817e-06 -2.3535607039985e-06 -1.2867493462183e-06 -2.67921771089829e-07 -6.48280397898496e-07 1.21655424723878e-05 3.20702349253229e-06 5.34501265554704e-06 1.86104064651686e-06 9.56157132872535e-07 1.41299052531817e-06 3.20702349253229e-06 2.82238382419499e-05 -1.51775799195557e-05 1.43665167698388e-05 -6.45955904353147e-09 -2.3535607039985e-06 5.34501265554704e-06 -1.51775799195557e-05 6.80642283055773e-05 -2.42178207561032e-05 2.6927810850287e-06 -1.2867493462183e-06 1.86104064651686e-06 1.43665167698388e-05 -2.42178207561032e-05 8.95519156361657e-05 256 363 0 0 252 256 363 0 0 270 0 0 0 0 0 0 0 0 995 0 0 0 0 0 2202 +1152 1071 0.974285355527326 -0.220853911855813 -0.0446272968369991 0.109427373745829 0.222040232460133 0.974752110230183 0.0235893783482179 0.214809493832445 0.0382907452792829 -0.0328918412344167 0.998725160194819 0.507605020036012 7.06281375312903e-05 5.88814514923661e-05 -1.10041136715033e-06 5.41977064112606e-06 -1.48992076806826e-05 7.35823718974269e-05 5.88814514923661e-05 0.000102733782212173 -3.70294062283976e-07 9.16129231924452e-06 -4.13836143487535e-05 8.25911833851314e-05 -1.10041136715033e-06 -3.70294062283976e-07 1.4684245957021e-05 1.08970489518691e-06 -3.5716909078287e-06 8.65156739021654e-07 5.41977064112606e-06 9.16129231924452e-06 1.08970489518691e-06 3.05993170034409e-05 -2.08466727927889e-05 4.19128774417732e-05 -1.48992076806826e-05 -4.13836143487535e-05 -3.5716909078287e-06 -2.08466727927889e-05 0.000134012404559948 -9.85135172995887e-05 7.35823718974269e-05 8.25911833851314e-05 8.65156739021654e-07 4.19128774417732e-05 -9.85135172995887e-05 0.00031484648867087 0 0 0 0 174 0 0 0 0 182 0 0 0 0 0 0 0 0 658 0 0 0 0 0 1380 +1152 1066 0.977636967872576 -0.185035087660932 0.0999398588313316 0.082751135888093 0.177958862620953 0.981123665568654 0.0756769190426278 0.205474633602514 -0.112056245981972 -0.0561993700626507 0.992111399259674 0.433110941656718 5.27185242190419e-05 2.75488145475757e-05 -1.1216624059518e-06 -5.00254339481413e-06 -1.75268900454076e-06 4.11452592212495e-05 2.75488145475757e-05 6.8002552572095e-05 5.01576009209856e-06 -6.35768762736603e-06 -1.85961608445126e-05 2.62304998021072e-05 -1.1216624059518e-06 5.01576009209856e-06 1.49185849815231e-05 2.17711938581861e-06 -2.92615799956636e-06 4.45890936966353e-06 -5.00254339481413e-06 -6.35768762736603e-06 2.17711938581861e-06 3.10610402627618e-05 -2.29413396731495e-05 -6.63158853502284e-06 -1.75268900454076e-06 -1.85961608445126e-05 -2.92615799956636e-06 -2.29413396731495e-05 0.000133330871553379 -5.94725150166844e-06 4.11452592212495e-05 2.62304998021072e-05 4.45890936966353e-06 -6.63158853502284e-06 -5.94725150166844e-06 0.000156139744718818 0 0 0 0 313 0 0 0 0 332 0 0 0 0 0 0 0 0 748 0 0 0 0 0 1693 +1152 1070 0.977543436819756 -0.210515936996576 -0.00958485268917019 0.107924434987642 0.210727662654723 0.976855720455069 0.0366981417279675 0.198413626282587 0.00163747448723885 -0.0378938211937345 0.999280429605544 0.493289178217933 7.37192140245618e-05 5.39668091834904e-05 -2.51704238251228e-06 -1.75485589629358e-07 -9.20937547611614e-06 8.24702109476875e-06 5.39668091834904e-05 7.35374536726073e-05 -1.47489041412066e-06 2.64562775992759e-06 -3.03862781211473e-05 1.17549000232082e-05 -2.51704238251228e-06 -1.47489041412066e-06 1.69845482656008e-05 3.25449904385235e-06 -3.23021915129945e-07 -5.21951779226512e-07 -1.75485589629358e-07 2.64562775992759e-06 3.25449904385235e-06 3.23376690391016e-05 -3.55045326849394e-05 2.9735129088403e-05 -9.20937547611614e-06 -3.03862781211473e-05 -3.23021915129945e-07 -3.55045326849394e-05 0.000189020891099087 -4.87652868461018e-05 8.24702109476875e-06 1.17549000232082e-05 -5.21951779226512e-07 2.9735129088403e-05 -4.87652868461018e-05 0.000331499748590778 0 0 0 0 209 0 0 0 0 221 0 0 0 0 0 0 0 0 683 0 0 0 0 0 1310 +1152 1069 0.977691075936428 -0.210007902493027 0.00410376957793899 0.0950012746438859 0.209529999506095 0.976465104031282 0.0511182933611216 0.207598375089689 -0.014742433355635 -0.0491180363986303 0.99868417388036 0.487746518722196 5.49243491052266e-05 3.17297943796502e-05 -1.67295287313743e-06 2.72785942824644e-06 -5.56272223874524e-06 3.27657222837911e-05 3.17297943796502e-05 7.70528581990097e-05 -1.43844170253606e-07 -4.38067949801652e-06 -3.18517265962049e-06 6.07836358644629e-06 -1.67295287313743e-06 -1.43844170253606e-07 1.68772388150847e-05 3.48813939715653e-06 3.02487020621534e-06 -2.97853405152077e-06 2.72785942824644e-06 -4.38067949801652e-06 3.48813939715653e-06 2.93534254811208e-05 -1.82694287710254e-05 2.71995181181005e-05 -5.56272223874524e-06 -3.18517265962049e-06 3.02487020621534e-06 -1.82694287710254e-05 0.000113912770992538 -7.72498496418112e-05 3.27657222837911e-05 6.07836358644629e-06 -2.97853405152077e-06 2.71995181181005e-05 -7.72498496418112e-05 0.000246966272951802 0 0 0 0 210 0 0 0 0 221 0 0 0 0 0 0 0 0 708 0 0 0 0 0 1389 +1152 1120 0.974383087775836 -0.206681262656021 0.0886592010077921 0.131306562173164 0.210224963858182 0.977109703166405 -0.0325897614119351 0.142102159007691 -0.0798940725414172 0.0503932896819975 0.995528730639037 0.541837083427754 4.42392338580166e-05 2.74913661993114e-05 -6.81380576584296e-06 -3.04498343182832e-06 1.02569436498951e-06 2.04559712438224e-05 2.74913661993114e-05 4.5032614300946e-05 -4.7830712425209e-06 6.50243865587508e-06 -2.19379478097127e-05 -3.07083623501897e-06 -6.81380576584296e-06 -4.7830712425209e-06 1.42426761471543e-05 3.9904484579196e-06 -2.09060395741438e-06 2.65022336636132e-06 -3.04498343182832e-06 6.50243865587508e-06 3.9904484579196e-06 8.42238209311917e-05 -0.000190426844396289 3.72612882290596e-05 1.02569436498951e-06 -2.19379478097127e-05 -2.09060395741438e-06 -0.000190426844396289 0.000624926572710554 -0.000119907011269815 2.04559712438224e-05 -3.07083623501897e-06 2.65022336636132e-06 3.72612882290596e-05 -0.000119907011269815 0.000228288057782408 0 0 0 0 250 0 0 0 0 269 0 0 0 0 0 0 0 0 558 0 0 0 0 0 1711 +1152 1116 0.975197542367749 -0.205385548166873 0.0825016967346448 0.100355433932921 0.208940373556959 0.97722968621407 -0.036960258113665 0.191130518043235 -0.0730320043390611 0.0532814882125434 0.995905321481955 0.548130579510408 4.25413686490586e-05 3.52787399748944e-05 -2.32736367730086e-06 -6.98861466730336e-06 3.31710905536244e-06 4.04773368212512e-06 3.52787399748944e-05 6.09269204486311e-05 -1.98186790687827e-06 -3.11726875840371e-07 -7.44421268132162e-06 7.98145946402906e-07 -2.32736367730086e-06 -1.98186790687827e-06 1.22862076522044e-05 2.68924557687531e-06 3.65468142579553e-06 1.01440808986159e-06 -6.98861466730336e-06 -3.11726875840371e-07 2.68924557687531e-06 3.55894220336837e-05 -4.43617266117187e-05 -1.01478206211283e-06 3.31710905536244e-06 -7.44421268132162e-06 3.65468142579553e-06 -4.43617266117187e-05 0.000173898535938914 -1.20551353727126e-06 4.04773368212512e-06 7.98145946402906e-07 1.01440808986159e-06 -1.01478206211283e-06 -1.20551353727126e-06 0.000135649603449866 0 0 0 0 241 0 0 0 0 258 0 0 0 0 0 0 0 0 545 0 0 0 0 0 1692 +1153 1062 0.99779186750375 -0.0164283358692609 0.064354478662678 -0.0444205355147125 0.0151454177855504 0.999677735182611 0.0203725820716426 0.291780884336228 -0.0646684270991606 -0.0193529212454202 0.997719128300039 0.325429651287111 3.32031591229656e-05 2.10415556081059e-05 -2.97928813069247e-06 2.8086157142815e-06 -4.61631094673153e-06 7.8347981389984e-06 2.10415556081059e-05 3.83016748906721e-05 -2.46508995409305e-06 2.0190665492449e-06 -5.36350841156126e-06 5.45223108713655e-06 -2.97928813069247e-06 -2.46508995409305e-06 1.26643804831734e-05 4.66357555113936e-06 3.05979518932626e-06 4.09184728473939e-06 2.8086157142815e-06 2.0190665492449e-06 4.66357555113936e-06 4.81825893541186e-05 -4.59511718841005e-05 1.31049266938023e-05 -4.61631094673153e-06 -5.36350841156126e-06 3.05979518932626e-06 -4.59511718841005e-05 0.000101584433327892 -2.58812295409023e-05 7.8347981389984e-06 5.45223108713655e-06 4.09184728473939e-06 1.31049266938023e-05 -2.58812295409023e-05 0.000152703936411042 465 497 0 0 190 465 497 0 0 183 0 0 0 0 0 0 0 0 991 0 0 0 0 0 2085 +1153 1064 0.983177012224006 -0.156868559506797 0.093569320145759 0.021103939475018 0.152848638567968 0.987047547876922 0.0487281429778976 0.289949305633936 -0.100001281602766 -0.0336064468282239 0.994419604799396 0.430684813195037 5.57222054911005e-05 4.17271833017988e-05 -2.82930212070915e-06 -6.78657323530558e-06 -2.81440051587493e-06 4.68007355422074e-05 4.17271833017988e-05 6.3826421963589e-05 -1.47662727628718e-06 -1.11927401168871e-05 8.83906479024077e-06 6.63678547890964e-06 -2.82930212070915e-06 -1.47662727628718e-06 1.25283715297438e-05 2.90828420727066e-06 3.3291874077352e-06 -3.8184209897799e-06 -6.78657323530558e-06 -1.11927401168871e-05 2.90828420727066e-06 3.2073662742148e-05 -2.18955391451106e-05 -5.56146225381342e-06 -2.81440051587493e-06 8.83906479024077e-06 3.3291874077352e-06 -2.18955391451106e-05 0.000100085145529336 -4.45511574659092e-05 4.68007355422074e-05 6.63678547890964e-06 -3.8184209897799e-06 -5.56146225381342e-06 -4.45511574659092e-05 0.000401623745910133 0 74 0 0 322 0 74 0 0 312 0 0 0 0 0 0 0 0 733 0 0 0 0 0 1915 +1153 1061 0.996957223508592 0.0721841383504122 0.0294235392950744 -0.0748750926847917 -0.0728292586471332 0.99711317313587 0.0214760108918169 0.272947895724937 -0.0277883712899697 -0.0235535587443811 0.999336297895521 0.271910544131774 2.26859096552497e-05 1.43184992234809e-05 2.17741147652379e-07 -9.44354065014357e-08 -1.19766436835469e-07 1.62477577734091e-07 1.43184992234809e-05 3.05894963075856e-05 2.00859872065286e-07 -4.01743878404389e-07 -2.18759891156076e-06 -2.22104946490888e-06 2.17741147652379e-07 2.00859872065286e-07 1.22261762062181e-05 3.27621416815135e-06 5.1469092617691e-06 2.18745051030634e-06 -9.44354065014357e-08 -4.01743878404389e-07 3.27621416815135e-06 4.43244226790496e-05 -3.10896093266741e-05 5.18368298183045e-06 -1.19766436835469e-07 -2.18759891156076e-06 5.1469092617691e-06 -3.10896093266741e-05 5.97883802497149e-05 -7.56190421352292e-06 1.62477577734091e-07 -2.22104946490888e-06 2.18745051030634e-06 5.18368298183045e-06 -7.56190421352292e-06 7.97136357398028e-05 947 946 0 0 11 935 934 0 0 10 0 0 0 0 0 0 0 0 1197 0 82 53 0 0 2366 +1153 1065 0.972578921340993 -0.215424378495362 0.087650321808182 0.0482505581904301 0.211380231091391 0.97595634424312 0.053175295348081 0.284913265969933 -0.0969981425953139 -0.033189626112577 0.994731023468941 0.480547353715201 7.25832891187001e-05 5.61858208895993e-05 4.84376214658927e-07 -2.86011160652756e-06 4.95166858966592e-06 2.33097483903783e-05 5.61858208895993e-05 0.000121613179536876 5.69236193039135e-06 -1.60068562735231e-05 1.65748869243402e-05 -6.57419695338436e-06 4.84376214658927e-07 5.69236193039135e-06 1.45805305460224e-05 1.97712245674056e-06 5.31006198705633e-06 -1.59592422378402e-06 -2.86011160652756e-06 -1.60068562735231e-05 1.97712245674056e-06 3.34535833953814e-05 -2.74116881751765e-05 1.17114320490548e-05 4.95166858966592e-06 1.65748869243402e-05 5.31006198705633e-06 -2.74116881751765e-05 0.000108670677793019 -5.11670293039081e-05 2.33097483903783e-05 -6.57419695338436e-06 -1.59592422378402e-06 1.17114320490548e-05 -5.11670293039081e-05 0.000266181299357836 0 0 0 0 392 0 0 0 0 384 0 0 0 0 0 0 0 0 684 0 0 0 0 0 1678 +1153 1068 0.960026837802089 -0.279387623434399 0.0170595009129663 0.070618413115273 0.27799843999618 0.958811935964654 0.058279831943841 0.276336583327028 -0.0326395168378979 -0.0512076881277649 0.998154514400049 0.562439476691119 6.26866223651124e-05 2.89978822240438e-05 5.6960476555234e-06 -6.85452990109227e-06 1.72001415361335e-05 2.78384382319451e-05 2.89978822240438e-05 8.79358909737488e-05 7.64854036022978e-06 -1.39333073676556e-05 2.04698449485218e-06 -2.24982961514995e-06 5.6960476555234e-06 7.64854036022978e-06 1.95369406482516e-05 1.37245000347623e-06 4.28446709667003e-06 1.45311270152983e-06 -6.85452990109227e-06 -1.39333073676556e-05 1.37245000347623e-06 3.15882644404536e-05 -1.40574157208042e-05 9.36655465698583e-06 1.72001415361335e-05 2.04698449485218e-06 4.28446709667003e-06 -1.40574157208042e-05 0.000104488830867827 -5.89252549795234e-05 2.78384382319451e-05 -2.24982961514995e-06 1.45311270152983e-06 9.36655465698583e-06 -5.89252549795234e-05 0.000364499274081589 0 0 0 0 208 0 0 0 0 206 0 0 0 0 0 0 0 0 554 0 0 0 0 0 1194 +1153 1066 0.964152995891805 -0.251803526931232 0.0836898102390611 0.0602044009537771 0.245343892949228 0.966105309016086 0.0802926278275382 0.281797298327558 -0.101071136856057 -0.0568815938237132 0.993251785590491 0.510497018071434 7.38899721436196e-05 4.56973680633233e-05 6.83479413302222e-07 -7.44716185075122e-07 -1.06446455625624e-05 5.16819486760091e-05 4.56973680633233e-05 7.33418145509436e-05 2.07207770242404e-06 -1.09923786932388e-06 -2.04714859526696e-05 3.23184491324347e-05 6.83479413302222e-07 2.07207770242404e-06 1.55909166681588e-05 4.06558037021263e-06 -8.69123436939086e-07 3.72386324285388e-06 -7.44716185075122e-07 -1.09923786932388e-06 4.06558037021263e-06 3.02259779204848e-05 -2.63476325940434e-05 1.55955552944597e-06 -1.06446455625624e-05 -2.04714859526696e-05 -8.69123436939086e-07 -2.63476325940434e-05 0.000148869931493112 -4.83277399173142e-05 5.16819486760091e-05 3.23184491324347e-05 3.72386324285388e-06 1.55955552944597e-06 -4.83277399173142e-05 0.000186587022690123 0 0 0 0 320 0 0 0 0 317 0 0 0 0 0 0 0 0 591 0 0 0 0 0 1553 +1153 1067 0.962431032138047 -0.268392171884045 0.0411357563326422 0.0624625436253485 0.263596068380397 0.959884530886433 0.0955970716043589 0.283841771871077 -0.0651430818436654 -0.0811623646544194 0.994569781087085 0.540815280306381 5.14875243323751e-05 4.43867286794366e-05 3.46277783293808e-06 -2.87295258626713e-06 -3.60108234429573e-06 5.51024424564676e-05 4.43867286794366e-05 8.21446224777004e-05 7.04567278351051e-06 -4.75082173718097e-06 -2.24473423096719e-05 7.39490674761474e-05 3.46277783293808e-06 7.04567278351051e-06 1.50199577906482e-05 -9.51237555478827e-07 -5.76225814750183e-07 1.08966892846563e-05 -2.87295258626713e-06 -4.75082173718097e-06 -9.51237555478827e-07 3.62930035838089e-05 -3.59330350031391e-05 -1.22171136171415e-05 -3.60108234429573e-06 -2.24473423096719e-05 -5.76225814750183e-07 -3.59330350031391e-05 0.000166532080740108 -3.27499047486185e-05 5.51024424564676e-05 7.39490674761474e-05 1.08966892846563e-05 -1.22171136171415e-05 -3.27499047486185e-05 0.000281879132500088 0 0 0 0 245 0 0 0 0 241 0 0 0 0 0 0 0 0 605 0 0 0 0 0 1254 +1153 1070 0.960709364933931 -0.277170443022653 -0.0146308455965 0.0839187844589575 0.277532946009384 0.959977098886702 0.0376753698379243 0.286654088849344 0.00360277776096759 -0.0402556223116483 0.999182918621364 0.568685896351424 7.13309973171235e-05 3.9987290853476e-05 3.09279920308386e-06 -1.77474192575727e-06 9.27734124094651e-06 1.34454228667066e-05 3.9987290853476e-05 7.71163558331606e-05 5.31227062348455e-06 -6.82908173919588e-06 -6.74778804425452e-06 9.38219897648228e-06 3.09279920308386e-06 5.31227062348455e-06 1.83977185180188e-05 3.43213774241899e-06 4.45863423397843e-07 -2.75718911579476e-06 -1.77474192575727e-06 -6.82908173919588e-06 3.43213774241899e-06 2.8003766800272e-05 -1.23670060077265e-05 9.82505111122968e-06 9.27734124094651e-06 -6.74778804425452e-06 4.45863423397843e-07 -1.23670060077265e-05 0.000127810221942828 -2.83541522213253e-05 1.34454228667066e-05 9.38219897648228e-06 -2.75718911579476e-06 9.82505111122968e-06 -2.83541522213253e-05 0.000241310859345178 0 0 0 0 192 0 0 0 0 188 0 0 0 0 0 0 0 0 522 0 0 0 0 0 1255 +1153 1063 0.990973929226622 -0.0950530736229429 0.0945282221771954 -0.00997341624744336 0.0918773481068487 0.995067413142913 0.0374085044598646 0.294766094450059 -0.0976177468394081 -0.0283858502761879 0.994819088581484 0.393725697708113 3.6899625263772e-05 2.0721660614781e-05 3.26024575040221e-07 3.22037681078157e-06 -3.76620963031053e-06 1.10213188576217e-07 2.0721660614781e-05 3.62462780439597e-05 1.78794395166474e-06 -1.74736904702794e-06 1.5546237226896e-07 -8.46217394051687e-06 3.26024575040221e-07 1.78794395166474e-06 1.34590615907748e-05 3.00803083925075e-06 5.26435692419952e-06 -1.82205636147937e-06 3.22037681078157e-06 -1.74736904702794e-06 3.00803083925075e-06 3.18373511658026e-05 -2.33771027380343e-05 1.89590549800038e-05 -3.76620963031053e-06 1.5546237226896e-07 5.26435692419952e-06 -2.33771027380343e-05 7.46462235669022e-05 -3.11176177595293e-05 1.10213188576217e-07 -8.46217394051687e-06 -1.82205636147937e-06 1.89590549800038e-05 -3.11176177595293e-05 0.000119432862252849 223 315 0 0 251 223 315 0 0 251 0 0 0 0 0 0 0 0 765 0 0 0 0 0 2229 +1153 1069 0.9606636603754 -0.277708247166106 0.00186040051249561 0.0768359884589226 0.277137656593299 0.959078357621673 0.057995027715226 0.286719023479755 -0.017889967359188 -0.0551981285701238 0.99831513845591 0.553154932505499 0.000142678069128542 8.79277125021667e-05 5.65920234123343e-06 6.66090003195003e-06 -3.60606630071209e-05 -2.8736437855595e-05 8.79277125021667e-05 0.000132816969837021 8.25797171116632e-06 -7.33149289724034e-06 -3.47858370640702e-05 4.87978356033476e-05 5.65920234123343e-06 8.25797171116632e-06 1.80128646767426e-05 3.9035642782592e-06 -5.50992318169712e-07 5.80847793145949e-06 6.66090003195003e-06 -7.33149289724034e-06 3.9035642782592e-06 3.3705606595307e-05 -2.31330866800234e-05 1.32642176030009e-05 -3.60606630071209e-05 -3.47858370640702e-05 -5.50992318169712e-07 -2.31330866800234e-05 0.000139281912845453 -8.36522334409777e-05 -2.8736437855595e-05 4.87978356033476e-05 5.80847793145949e-06 1.32642176030009e-05 -8.36522334409777e-05 0.000422293320616279 0 0 0 0 205 0 0 0 0 198 0 0 0 0 0 0 0 0 548 0 0 0 0 0 1300 +1153 1123 0.958462890389669 -0.273748213502606 0.0800674924673766 0.0837705934236705 0.276494565301417 0.960682763127078 -0.0252860433698659 0.26732723118589 -0.0699974507011657 0.046373960739342 0.996468671188755 0.622729956735495 4.6264905332027e-05 3.86715887144553e-05 -3.55360408590221e-06 5.36547079797781e-06 -2.44001964953288e-05 -2.1282626290595e-06 3.86715887144553e-05 6.70257939505115e-05 -1.3716521885991e-06 1.18518874255492e-05 -5.10191459213777e-05 1.79868115025093e-06 -3.55360408590221e-06 -1.3716521885991e-06 1.33274122164817e-05 4.67180055356221e-06 2.0156779926962e-06 3.03856512068031e-06 5.36547079797781e-06 1.18518874255492e-05 4.67180055356221e-06 6.75295352602621e-05 -0.000152714100180392 1.69907021034496e-05 -2.44001964953288e-05 -5.10191459213777e-05 2.0156779926962e-06 -0.000152714100180392 0.000544534667730385 -6.77620485574634e-05 -2.1282626290595e-06 1.79868115025093e-06 3.03856512068031e-06 1.69907021034496e-05 -6.77620485574634e-05 0.000129556082950467 0 0 0 0 251 0 0 0 0 242 0 0 0 0 0 0 0 0 315 0 0 0 0 0 1664 +1154 1061 0.999794753821322 0.0167917891179763 0.0113351687053802 -0.120253675728705 -0.0169398728016468 0.999770728348775 0.0130970014286895 0.360693046242822 -0.0111126477864658 -0.0132863296352484 0.999849979998998 0.347103609318199 3.41232020758272e-05 2.37780452018362e-05 -1.79190745471491e-06 -2.31775189728998e-06 2.1840723607521e-06 5.01295818647474e-06 2.37780452018362e-05 4.07700316946248e-05 -1.72160830534955e-06 5.41955693957783e-06 -5.47949594107635e-06 5.43281693881655e-07 -1.79190745471491e-06 -1.72160830534955e-06 1.22169634954433e-05 4.93344622878766e-06 3.42181686714485e-06 -5.15827398716709e-07 -2.31775189728998e-06 5.41955693957783e-06 4.93344622878766e-06 2.43095284242376e-05 -6.01581505808604e-06 9.35600425742383e-06 2.1840723607521e-06 -5.47949594107635e-06 3.42181686714485e-06 -6.01581505808604e-06 3.14902957858202e-05 -6.17315066329343e-06 5.01295818647474e-06 5.43281693881655e-07 -5.15827398716709e-07 9.35600425742383e-06 -6.17315066329343e-06 0.000114796855438682 800 778 0 0 93 800 778 0 0 82 0 0 0 0 0 0 0 0 1195 0 5 0 0 0 2280 +1154 1070 0.943747161077514 -0.328736197080291 -0.0356904565300171 0.0452483305427451 0.32985578952733 0.943489592093678 0.0319773001707024 0.363302547675761 0.0231614782221314 -0.0419511899723236 0.998851161878721 0.65134026892733 4.96412962857246e-05 2.83839232251658e-05 6.97818908107482e-07 3.4535244118941e-06 1.54603143694748e-06 2.76696062526356e-05 2.83839232251658e-05 5.50264314591019e-05 -7.96436431274335e-07 -3.87807364951944e-06 9.52240648954476e-06 1.08355602047561e-05 6.97818908107482e-07 -7.96436431274335e-07 1.80152428409075e-05 2.80962176171582e-06 4.46407476461254e-06 -1.51558659127258e-06 3.4535244118941e-06 -3.87807364951944e-06 2.80962176171582e-06 2.78606686355189e-05 -6.00708585331886e-06 5.85699754972538e-06 1.54603143694748e-06 9.52240648954476e-06 4.46407476461254e-06 -6.00708585331886e-06 6.97135921972868e-05 4.3902029036733e-06 2.76696062526356e-05 1.08355602047561e-05 -1.51558659127258e-06 5.85699754972538e-06 4.3902029036733e-06 0.000283933069486888 0 0 0 0 168 0 0 0 0 168 0 0 0 0 0 0 0 0 465 0 0 0 0 0 1179 +1154 1065 0.961502849991819 -0.268074953786424 0.060399409020419 0.010406937301181 0.265719936038709 0.963032802642233 0.0442802058106234 0.357251489170931 -0.0700370262732049 -0.0265262169834572 0.997191643949824 0.580528402373214 5.46702790640847e-05 4.79521088635802e-05 -1.80863710782785e-06 -1.13013443583573e-05 1.96666616255325e-05 2.71877048453931e-05 4.79521088635802e-05 7.15383856194918e-05 8.32148477576604e-07 -1.30555710140972e-05 1.8446141253349e-05 4.72352259440219e-07 -1.80863710782785e-06 8.32148477576604e-07 1.51597587677551e-05 3.12941456121774e-06 1.58429538704419e-06 -4.73364409628265e-06 -1.13013443583573e-05 -1.30555710140972e-05 3.12941456121774e-06 3.50193246225577e-05 -2.66959853335786e-05 -5.25713735329052e-06 1.96666616255325e-05 1.8446141253349e-05 1.58429538704419e-06 -2.66959853335786e-05 0.000107448233648544 7.18861480503825e-06 2.71877048453931e-05 4.72352259440219e-07 -4.73364409628265e-06 -5.25713735329052e-06 7.18861480503825e-06 0.00022533001988107 0 0 0 0 343 0 0 0 0 341 0 0 0 0 0 0 0 0 569 0 0 0 0 0 1686 +1154 1067 0.94680354613724 -0.320921738208357 0.0239224364827854 0.0282958300171948 0.317476986578804 0.94362528789541 0.0936999415002273 0.356935774355523 -0.0526441641095024 -0.0811206138390897 0.99531303517817 0.61524063001222 0.000101108595669039 6.44122319208741e-05 5.39633845452201e-06 7.10102864971724e-06 -3.52518228521447e-05 0.000129018089665794 6.44122319208741e-05 7.82296189219832e-05 3.01085119072786e-06 2.55090102416017e-06 -2.46492834451859e-05 5.59935273503714e-05 5.39633845452201e-06 3.01085119072786e-06 1.75170213223993e-05 -1.75468749297113e-06 6.85994821630879e-07 4.42802857685541e-06 7.10102864971724e-06 2.55090102416017e-06 -1.75468749297113e-06 2.96506816867533e-05 -1.81069103619103e-05 3.21633847489403e-05 -3.52518228521447e-05 -2.46492834451859e-05 6.85994821630879e-07 -1.81069103619103e-05 0.000138345438918059 -0.000154690126848265 0.000129018089665794 5.59935273503714e-05 4.42802857685541e-06 3.21633847489403e-05 -0.000154690126848265 0.000441702144178739 0 0 0 0 237 0 0 0 0 234 0 0 0 0 0 0 0 0 536 0 0 0 0 0 1275 +1155 1062 0.992862050828429 -0.113036105113722 0.0380497958665302 -0.103200584619349 0.112828014853919 0.993585623736073 0.00757940427230565 0.416833429559537 -0.0386624764971004 -0.00323221993664171 0.999247099403042 0.485805685005286 3.64197676478586e-05 1.79611294209186e-05 -2.30233005004933e-06 -9.27560643520335e-09 6.22331269779833e-07 4.05580168823046e-06 1.79611294209186e-05 4.64975356912916e-05 -1.71620883536571e-06 -2.26302548669378e-06 -4.66212370951096e-06 1.80771772771471e-05 -2.30233005004933e-06 -1.71620883536571e-06 1.32048780954331e-05 4.11618732104797e-06 2.2159940229587e-06 2.80192795095358e-06 -9.27560643520335e-09 -2.26302548669378e-06 4.11618732104797e-06 2.64385373790582e-05 -6.95602695659524e-06 2.80080287041085e-05 6.22331269779833e-07 -4.66212370951096e-06 2.2159940229587e-06 -6.95602695659524e-06 4.16378478798954e-05 -4.46008507989249e-05 4.05580168823046e-06 1.80771772771471e-05 2.80192795095358e-06 2.80080287041085e-05 -4.46008507989249e-05 0.000259379930790382 295 315 0 0 223 295 315 0 0 204 0 0 0 0 0 0 0 0 774 0 0 0 0 0 2027 +1155 1060 0.998151586382461 0.0605460009967454 -0.00525284356121263 -0.204441980787691 -0.0606401991950584 0.99795626297677 -0.0201510155333258 0.424131319110894 0.00402204472378317 0.0204323016016991 0.999783148591482 0.3423068128774 3.30308980239955e-05 2.73677924771565e-05 -2.27625683183946e-06 4.6382387302917e-06 -2.68581653624201e-06 5.91310720136694e-06 2.73677924771565e-05 4.5376583858536e-05 -1.67016672621496e-06 1.92629879845555e-06 -7.27406067263885e-07 5.77439776139462e-07 -2.27625683183946e-06 -1.67016672621496e-06 1.15529562407125e-05 3.89881156899773e-06 2.58742042490118e-06 8.9445501091081e-07 4.6382387302917e-06 1.92629879845555e-06 3.89881156899773e-06 2.21692498368674e-05 -1.2267911163831e-06 1.09855026312749e-05 -2.68581653624201e-06 -7.27406067263885e-07 2.58742042490118e-06 -1.2267911163831e-06 2.23255642100775e-05 -1.13704374835959e-05 5.91310720136694e-06 5.77439776139462e-07 8.9445501091081e-07 1.09855026312749e-05 -1.13704374835959e-05 0.000137423480221543 898 896 0 0 25 868 866 0 0 11 0 0 0 0 0 0 0 0 1146 0 122 81 0 0 2428 +1156 1065 0.935807809195472 -0.349438578619383 0.0464373128123882 -0.0649642807775904 0.346802852326519 0.936241890438365 0.0563817719355088 0.507084659532662 -0.0631785237795345 -0.0366579099358122 0.99732876814628 0.689695982874938 9.02522186414683e-05 6.85418126927462e-05 -1.17597754889226e-06 1.02537150330728e-05 -1.67501970183047e-05 -2.79041936863304e-05 6.85418126927462e-05 9.27339645963103e-05 2.21924902490454e-06 -7.44171833026884e-06 1.24589078755991e-05 -4.95321084165753e-05 -1.17597754889226e-06 2.21924902490454e-06 1.63575903358584e-05 2.16352084449887e-06 1.02993245542705e-05 -4.4355634326456e-06 1.02537150330728e-05 -7.44171833026884e-06 2.16352084449887e-06 3.57122295846927e-05 -2.03635844829904e-05 3.95867099375591e-06 -1.67501970183047e-05 1.24589078755991e-05 1.02993245542705e-05 -2.03635844829904e-05 9.3256548446418e-05 -4.25687160772033e-05 -2.79041936863304e-05 -4.95321084165753e-05 -4.4355634326456e-06 3.95867099375591e-06 -4.25687160772033e-05 0.000304317196921015 0 0 0 0 327 0 0 0 0 291 0 0 0 0 0 0 0 0 470 0 0 0 0 0 1496 +1156 1060 0.999807951385402 0.0181621597674411 -0.00736181357464922 -0.234167494748259 -0.0182194320392419 0.999803674969082 -0.00778869786845476 0.486120721415009 0.00721890869130436 0.00792133012192849 0.999942568294003 0.386282339241345 3.79806205710323e-05 2.73507146815986e-05 -1.80663195520649e-06 9.86504461133596e-06 -8.93642219437834e-06 2.47222165979008e-05 2.73507146815986e-05 3.72829354418514e-05 -1.64520567236022e-06 5.83052558849874e-06 -5.42254932806478e-06 -4.0228273094402e-08 -1.80663195520649e-06 -1.64520567236022e-06 1.03605455303268e-05 3.60255589459848e-06 4.23834332603565e-06 -1.28312144240007e-06 9.86504461133596e-06 5.83052558849874e-06 3.60255589459848e-06 3.61925726413413e-05 -1.91477648316593e-05 5.12234478855799e-05 -8.93642219437834e-06 -5.42254932806478e-06 4.23834332603565e-06 -1.91477648316593e-05 3.96655258361307e-05 -4.74686763762324e-05 2.47222165979008e-05 -4.0228273094402e-08 -1.28312144240007e-06 5.12234478855799e-05 -4.74686763762324e-05 0.000226326749097745 852 825 0 0 56 829 824 0 0 32 0 0 0 0 0 0 0 0 1121 0 46 18 0 0 2337 +1156 1061 0.997704098170757 -0.0663100549857202 -0.0137662304596093 -0.184673614425489 0.0665101968942257 0.997678505520619 0.0146285109028474 0.486104589340401 0.0127642548692684 -0.0155105199762663 0.999798228427965 0.468147437305339 3.11801685063347e-05 1.78525489861712e-05 -3.21327459096916e-06 -1.72549492426742e-06 3.96496073761591e-06 7.81598909073665e-06 1.78525489861712e-05 3.56537269271599e-05 -1.48803982816143e-06 -2.18565941306842e-06 -2.82547694062207e-06 -4.13412146722077e-06 -3.21327459096916e-06 -1.48803982816143e-06 1.18474673931689e-05 3.46972772897483e-06 3.3473707126216e-06 2.27715458914253e-06 -1.72549492426742e-06 -2.18565941306842e-06 3.46972772897483e-06 2.1921438811266e-05 -1.37572749875515e-06 3.84233677413102e-06 3.96496073761591e-06 -2.82547694062207e-06 3.3473707126216e-06 -1.37572749875515e-06 2.56954226047922e-05 5.21631825446646e-08 7.81598909073665e-06 -4.13412146722077e-06 2.27715458914253e-06 3.84233677413102e-06 5.21631825446646e-08 0.000106523141840624 578 546 0 0 189 578 546 0 0 156 0 0 0 0 0 0 0 0 975 0 0 0 0 0 2189 +1156 1071 0.905444929540544 -0.417122597918697 -0.0786016404083046 -0.010985314349559 0.419235289715223 0.907800454143003 0.0118366935902827 0.510693337462423 0.0664172524778976 -0.0436700556825138 0.996835831423597 0.784225851601707 6.35523776085164e-05 4.61714899942342e-05 -1.8350321176216e-06 -1.37136562495835e-06 1.35952529739049e-05 2.91027867204974e-05 4.61714899942342e-05 5.36452417944389e-05 -1.50140752143476e-06 -2.87148343120517e-07 5.73448126058259e-06 8.83235158061096e-06 -1.8350321176216e-06 -1.50140752143476e-06 1.76369871401889e-05 1.78551126817392e-06 4.85191791956506e-06 5.29263347227051e-07 -1.37136562495835e-06 -2.87148343120517e-07 1.78551126817392e-06 3.51423145769593e-05 -1.20503350893654e-05 1.62683662173587e-05 1.35952529739049e-05 5.73448126058259e-06 4.85191791956506e-06 -1.20503350893654e-05 0.000100504673206362 1.02778332706e-05 2.91027867204974e-05 8.83235158061096e-06 5.29263347227051e-07 1.62683662173587e-05 1.02778332706e-05 0.000242394293409408 0 0 0 0 170 0 0 0 0 145 0 0 0 0 0 0 0 0 350 0 0 0 0 0 1187 +1157 1059 0.999544445366347 0.0271752342382875 -0.0131304372119421 -0.345220307335318 -0.0271244754867347 0.999623946264438 0.00402850894012825 0.563184370491273 0.013234975136058 -0.00367051751192843 0.999905676918749 0.365728939905891 3.39301091813148e-05 2.56569696522382e-05 -9.07675723568259e-07 3.19166161877368e-06 -3.17490229252036e-06 5.33733800251443e-06 2.56569696522382e-05 3.86534290889021e-05 -5.96144995876571e-07 -3.05227549275623e-06 1.64217618849686e-06 2.1736153622468e-05 -9.07675723568259e-07 -5.96144995876571e-07 1.20099367249388e-05 4.175760404047e-06 2.63411401444223e-06 7.05776099166317e-06 3.19166161877368e-06 -3.05227549275623e-06 4.175760404047e-06 2.50610057138151e-05 -4.40858035540025e-06 7.21470109398226e-06 -3.17490229252036e-06 1.64217618849686e-06 2.63411401444223e-06 -4.40858035540025e-06 2.26835260841374e-05 -9.15657096544681e-06 5.33733800251443e-06 2.1736153622468e-05 7.05776099166317e-06 7.21470109398226e-06 -9.15657096544681e-06 0.000298901033012627 955 942 0 0 57 928 926 0 0 30 0 0 0 0 0 0 0 0 1301 0 102 53 0 0 2243 +1157 1058 0.99526469486143 0.0950294252016174 -0.020435153736507 -0.40632270788067 -0.0949993128086714 0.995474344015402 0.00244151039019519 0.564939814957753 0.0205746865897072 -0.00048862353139091 0.999788199329628 0.307733708779461 8.71113456058082e-05 5.07989492689183e-05 -2.67014613601133e-06 3.84496764159544e-05 -2.46648933984346e-05 0.000337386465161496 5.07989492689183e-05 4.74120468567742e-05 -6.03945623653065e-07 1.94198098446335e-05 -1.42161662092616e-05 0.00017236711006297 -2.67014613601133e-06 -6.03945623653065e-07 1.12126313037262e-05 4.23716834592581e-06 3.4833026802197e-06 -5.50177098149593e-07 3.84496764159544e-05 1.94198098446335e-05 4.23716834592581e-06 6.44323945985815e-05 -3.0951370359289e-05 0.000222775268311736 -2.46648933984346e-05 -1.42161662092616e-05 3.4833026802197e-06 -3.0951370359289e-05 3.97090563824293e-05 -0.000140946413585965 0.000337386465161496 0.00017236711006297 -5.50177098149593e-07 0.000222775268311736 -0.000140946413585965 0.0021246324337474 993 993 0 0 0 971 971 0 0 0 0 0 0 0 0 0 0 0 1328 0 197 157 0 0 2093 +1157 1057 0.986808285806385 0.160149584133384 -0.0236963660878156 -0.454345233968863 -0.160095210861527 0.987092699159465 0.00418649319668971 0.548133280284938 0.0240609751063198 -0.00033759144948469 0.999710435830769 0.27538555451566 3.56413180732464e-05 2.3400516991651e-05 -2.19079741731618e-06 -5.95661670567514e-06 6.05420872348211e-06 -9.80664514550503e-06 2.3400516991651e-05 3.83411042450876e-05 7.41209931114908e-07 1.05190850306508e-05 -9.46244973468052e-06 -1.0523279668414e-05 -2.19079741731618e-06 7.41209931114908e-07 1.0432918618295e-05 2.13540710718262e-06 4.88316916751757e-06 -2.42022727400781e-07 -5.95661670567514e-06 1.05190850306508e-05 2.13540710718262e-06 0.000163671567303717 -9.64680567422333e-05 4.5799230723749e-05 6.05420872348211e-06 -9.46244973468052e-06 4.88316916751757e-06 -9.64680567422333e-05 8.19418618194808e-05 -2.63955261762659e-05 -9.80664514550503e-06 -1.0523279668414e-05 -2.42022727400781e-07 4.5799230723749e-05 -2.63955261762659e-05 0.000156675276528333 1102 1102 0 0 0 1066 1066 0 0 0 0 0 0 0 0 0 0 0 1316 0 351 309 0 0 1988 +1157 1161 0.946895492736868 0.31947739850096 -0.0363746846263015 0.152387658727973 -0.317364398358964 0.94677031380487 0.0539055799716503 -0.366953244433903 0.051660086032225 -0.0394989208065992 0.997883295163446 -0.0760889460188627 2.77684564833372e-05 2.39384867615972e-05 6.63164377009163e-07 3.15159356185779e-06 -2.21375138589539e-06 -9.47926279524111e-06 2.39384867615972e-05 3.31137582056205e-05 -1.19610948261758e-07 -3.84641678243611e-06 6.7497831939198e-07 -1.01663364014694e-05 6.63164377009163e-07 -1.19610948261758e-07 9.92083197389628e-06 3.9027259992351e-06 5.70214560956577e-06 -4.134116093054e-07 3.15159356185779e-06 -3.84641678243611e-06 3.9027259992351e-06 5.83167275858151e-05 -1.55407842768964e-05 3.89850175254815e-05 -2.21375138589539e-06 6.7497831939198e-07 5.70214560956577e-06 -1.55407842768964e-05 1.97465156492125e-05 -1.84629310108863e-05 -9.47926279524111e-06 -1.01663364014694e-05 -4.134116093054e-07 3.89850175254815e-05 -1.84629310108863e-05 0.000100869631693841 3010 2857 0 300 0 2961 2808 0 300 0 0 0 0 0 0 0 0 0 1149 0 769 754 0 0 3652 +1158 1057 0.996010653542495 0.0889686777664396 0.0068813084760847 -0.506888724538926 -0.0889228075244127 0.996015934766887 -0.00670760705625663 0.583588964072364 -0.00745065982499879 0.00606894281867343 0.999953826734633 0.303220530681708 3.31416087212791e-05 2.36939368152818e-05 -1.90854602326254e-06 5.29760386006475e-06 -2.41215380360802e-06 -5.6724258307134e-06 2.36939368152818e-05 3.50417232042069e-05 -1.38092404254285e-07 1.72180058884221e-05 -1.36570030558097e-05 4.17343838608635e-06 -1.90854602326254e-06 -1.38092404254285e-07 1.2240132654578e-05 3.12908920163937e-06 3.24195526580218e-06 7.27034657176955e-07 5.29760386006475e-06 1.72180058884221e-05 3.12908920163937e-06 0.00010720004097515 -5.68188554480421e-05 7.83636872411804e-05 -2.41215380360802e-06 -1.36570030558097e-05 3.24195526580218e-06 -5.68188554480421e-05 5.48264033588552e-05 -4.86511813854643e-05 -5.6724258307134e-06 4.17343838608635e-06 7.27034657176955e-07 7.83636872411804e-05 -4.86511813854643e-05 0.000221347600428103 1192 1192 0 0 0 1152 1152 0 0 0 0 0 0 0 0 28 28 0 1316 0 239 190 0 0 1906 +1158 1162 0.943123368007752 0.332263211666437 -0.0109302740505008 0.181079388934391 -0.331955157699901 0.943010824297884 0.0231594156545444 -0.355502842360386 0.0180023885678614 -0.0182138252470683 0.999672031506194 -0.0559213523338944 3.21965422724097e-05 2.50467302189966e-05 -4.96567082911774e-07 1.52036949625246e-05 -6.98363014689493e-06 -7.9282603244374e-06 2.50467302189966e-05 3.55775188348443e-05 -5.31253160280624e-07 2.71428086196437e-05 -1.18092644999704e-05 5.07029342705729e-06 -4.96567082911774e-07 -5.31253160280624e-07 9.99892194159642e-06 4.86953961279417e-06 4.98823521079606e-06 3.23517438587399e-06 1.52036949625246e-05 2.71428086196437e-05 4.86953961279417e-06 0.000177148508973955 -5.83519295747325e-05 9.30901336241947e-05 -6.98363014689493e-06 -1.18092644999704e-05 4.98823521079606e-06 -5.83519295747325e-05 3.50583894276147e-05 -3.50794909385293e-05 -7.9282603244374e-06 5.07029342705729e-06 3.23517438587399e-06 9.30901336241947e-05 -3.50794909385293e-05 0.000193799111130395 2837 2705 0 1508 0 2802 2670 0 1508 0 0 0 0 0 0 0 0 0 1186 0 934 918 0 0 3596 +1159 1058 0.997935468838112 -0.0548423979362608 0.0334232168328926 -0.548352425129015 0.0557228893656333 0.998107506163 -0.0260070325454723 0.642927231673157 -0.0319336755730236 0.0278157784301768 0.999102858986361 0.41626225471238 2.8615177228423e-05 1.86547023290555e-05 -1.71380088047007e-08 1.02655530638925e-06 5.344611002514e-07 -2.75114713806674e-05 1.86547023290555e-05 3.35701645092898e-05 -1.82508183767234e-08 -3.30897594377656e-06 2.73151982415168e-06 -1.64738624445201e-05 -1.71380088047007e-08 -1.82508183767234e-08 1.09530191368713e-05 4.60125787258413e-06 4.81370706182536e-06 1.7799677439002e-07 1.02655530638925e-06 -3.30897594377656e-06 4.60125787258413e-06 2.91433229886362e-05 -6.72281228701287e-06 5.93279427755599e-06 5.344611002514e-07 2.73151982415168e-06 4.81370706182536e-06 -6.72281228701287e-06 2.11277932798074e-05 -3.11384211287466e-06 -2.75114713806674e-05 -1.64738624445201e-05 1.7799677439002e-07 5.93279427755599e-06 -3.11384211287466e-06 0.000111185002497328 987 954 0 0 145 987 954 0 0 113 0 0 0 0 0 113 113 0 1144 0 0 0 0 0 1902 +1160 1162 0.984830876961487 0.172793452678519 0.0158292922995602 0.14880179053956 -0.172508343022716 0.984845447821804 -0.017897359923379 -0.177154595176774 -0.0186819530784534 0.0148951876828173 0.999714518256621 -0.0195630567878698 0.000132460495265978 0.000175962733185101 -6.22230706559716e-07 0.000132995280429074 -4.53204916774912e-05 7.68275359845831e-05 0.000175962733185101 0.000294587790020445 -1.34278657230555e-06 0.000259156944237835 -8.95491834465956e-05 0.000165567125164582 -6.22230706559716e-07 -1.34278657230555e-06 9.91726493672583e-06 3.39754267707491e-07 7.1054521918628e-06 -4.10996524741105e-06 0.000132995280429074 0.000259156944237835 3.39754267707491e-07 0.000659057559251677 -0.000224189231787265 0.000633964238382758 -4.53204916774912e-05 -8.95491834465956e-05 7.1054521918628e-06 -0.000224189231787265 9.14253592067723e-05 -0.000225829176890547 7.68275359845831e-05 0.000165567125164582 -4.10996524741105e-06 0.000633964238382758 -0.000225829176890547 0.000826405055308772 2710 2578 0 1411 0 2668 2536 0 1124 0 0 0 0 0 0 0 0 0 2425 0 504 488 0 0 3674 +1163 1059 0.889022924680091 -0.455289858367587 0.0484704472939818 -1.00613110196673 0.456476396893225 0.889582364542634 -0.0165080517964505 0.69860266492564 -0.0356025065498887 0.0368016516254106 0.998688189559187 0.533617233417809 4.05890631052935e-05 2.05661993639375e-05 1.09688409054952e-06 -6.02711783466236e-06 6.90326201252682e-06 -1.50451100023365e-05 2.05661993639375e-05 3.52693182168986e-05 3.93504558591384e-07 -1.42547104399764e-06 1.22761721407461e-06 -3.89888774482081e-06 1.09688409054952e-06 3.93504558591384e-07 1.63202845046427e-05 4.03291573847916e-06 3.4070420900717e-06 -2.82092740948197e-07 -6.02711783466236e-06 -1.42547104399764e-06 4.03291573847916e-06 3.38924052559272e-05 -1.37306922671634e-05 -1.00489297172889e-05 6.90326201252682e-06 1.22761721407461e-06 3.4070420900717e-06 -1.37306922671634e-05 3.19141769882073e-05 1.08910948690713e-05 -1.50451100023365e-05 -3.89888774482081e-06 -2.82092740948197e-07 -1.00489297172889e-05 1.08910948690713e-05 0.000108892559598808 472 445 0 0 595 460 433 0 0 594 0 0 0 0 0 469 469 0 0 0 0 0 0 0 1264 +1163 1165 0.988086028690407 0.152147234965969 -0.0231779809092819 0.231934903838354 -0.152799197111799 0.987814620814097 -0.0295749939626499 -0.152678900224025 0.0183957948675863 0.0327642152067084 0.999293801108102 -0.0143214677499009 6.74041339575385e-05 2.75170651784763e-05 -1.84638642179428e-06 5.17395382470369e-06 4.02894024792359e-07 3.84071429249607e-07 2.75170651784763e-05 4.72908556054547e-05 -3.40943558989325e-07 1.83417260367092e-05 -2.01104006211459e-06 -1.94383441897197e-05 -1.84638642179428e-06 -3.40943558989325e-07 1.13826302800686e-05 5.03092121728438e-06 4.92865812642455e-06 -1.05158904406894e-08 5.17395382470369e-06 1.83417260367092e-05 5.03092121728438e-06 0.000236023544822442 -1.77087567721987e-05 5.47346193530558e-05 4.02894024792359e-07 -2.01104006211459e-06 4.92865812642455e-06 -1.77087567721987e-05 1.24937270991254e-05 -2.29311227727744e-06 3.84071429249607e-07 -1.94383441897197e-05 -1.05158904406894e-08 5.47346193530558e-05 -2.29311227727744e-06 0.000100344364794823 3086 3010 0 1066 0 3086 3010 0 930 0 0 0 0 0 0 0 0 0 2782 0 320 342 0 0 3750 +1163 1058 0.917811422204609 -0.394179718608758 0.0473766050733221 -1.04421496869764 0.39538289457031 0.918317894067301 -0.0190948191140889 0.667069592676563 -0.0359799937737147 0.0362573423366462 0.998694570514292 0.477251207628355 8.96328005394246e-05 3.94723445423572e-05 -8.03186671796733e-07 1.03380522683052e-05 -1.40742305682188e-06 7.66627270759235e-06 3.94723445423572e-05 9.45056109198954e-05 -2.99660219090452e-06 1.23403115683963e-05 -7.58805867079045e-06 -1.51319120855882e-05 -8.03186671796733e-07 -2.99660219090452e-06 1.46084567746733e-05 1.75699080122218e-06 5.65384579864019e-06 -5.69180478930672e-06 1.03380522683052e-05 1.23403115683963e-05 1.75699080122218e-06 3.94756183061929e-05 -1.24637424782054e-05 2.23335998291669e-05 -1.40742305682188e-06 -7.58805867079045e-06 5.65384579864019e-06 -1.24637424782054e-05 2.67070672265612e-05 -1.32072016939145e-05 7.66627270759235e-06 -1.51319120855882e-05 -5.69180478930672e-06 2.23335998291669e-05 -1.32072016939145e-05 0.000251835267362693 566 542 0 0 532 552 528 0 0 531 0 0 0 0 0 577 577 0 0 0 0 0 0 0 1241 +1164 1166 0.992367163237753 0.120780306877568 -0.0248903756101688 0.220719462235757 -0.121091827640158 0.992575753714435 -0.0114079979395413 -0.12604078858276 0.0233277218395022 0.0143349436267701 0.999625093114912 -0.0258473018151354 3.27654941199323e-05 9.46242935351018e-06 6.49953025082563e-06 -9.10035455846284e-06 1.65984690587822e-06 -7.47672994671498e-06 9.46242935351018e-06 3.35614484038801e-05 -1.25666157619331e-06 8.63496044416776e-06 1.70975396030973e-06 2.02971505448013e-05 6.49953025082563e-06 -1.25666157619331e-06 1.02620555097178e-05 -3.30890687294216e-07 3.53089560545131e-06 -2.03942322710159e-06 -9.10035455846284e-06 8.63496044416776e-06 -3.30890687294216e-07 0.000186916362506974 -4.84573172809643e-06 4.01381078505948e-05 1.65984690587822e-06 1.70975396030973e-06 3.53089560545131e-06 -4.84573172809643e-06 1.04856535811508e-05 2.33965044995766e-06 -7.47672994671498e-06 2.02971505448013e-05 -2.03942322710159e-06 4.01381078505948e-05 2.33965044995766e-06 0.000161091896325056 3366 3302 0 848 0 3382 3318 0 740 0 0 0 0 0 0 0 0 0 2996 0 184 219 0 0 3754 +1165 1169 0.99446196671638 0.0949870450557116 0.0449761939938652 0.507849525077488 -0.0940720322967092 0.995321257361416 -0.0220464823510723 -0.176814847383461 -0.0468598921697061 0.0176933862240514 0.998744759480504 -0.0859105815305516 5.5934657536053e-05 1.37000172567412e-05 -1.07465331320462e-07 -1.40607835508431e-05 7.24625029263256e-07 -2.76989547494149e-05 1.37000172567412e-05 5.21243294392901e-05 -1.19512523419571e-06 1.28245687189391e-05 -1.03267439019706e-06 -3.97941263711308e-05 -1.07465331320462e-07 -1.19512523419571e-06 1.34642188703953e-05 -2.62257218097783e-06 5.24750356375982e-06 1.74230475486297e-06 -1.40607835508431e-05 1.28245687189391e-05 -2.62257218097783e-06 0.000380031223472792 -4.75811346468639e-06 6.62020441368672e-06 7.24625029263256e-07 -1.03267439019706e-06 5.24750356375982e-06 -4.75811346468639e-06 1.07534040401509e-05 1.45799860099424e-06 -2.76989547494149e-05 -3.97941263711308e-05 1.74230475486297e-06 6.62020441368672e-06 1.45799860099424e-06 9.21784730639174e-05 3042 3042 0 1356 159 3042 3042 0 1252 189 0 0 0 0 0 0 0 0 2425 0 0 0 0 0 3578 +1166 1170 0.998488013508148 0.0390153792735445 0.0387232108778922 0.517853713219161 -0.0387947826520609 0.999226496692818 -0.00643219604629751 -0.123066625985012 -0.0389442129145215 0.00492021210316481 0.999229272886522 -0.123689443586308 3.34359650855907e-05 7.61517572546148e-06 5.64720651714796e-06 -1.75801567907385e-06 4.25268137398342e-06 -1.41956077711627e-05 7.61517572546148e-06 3.00181392420455e-05 1.75197974131427e-06 5.61746664864837e-07 1.75570006230524e-07 -1.59048545555089e-05 5.64720651714796e-06 1.75197974131427e-06 1.10647333764237e-05 2.91569053440497e-06 4.75958938319901e-06 -3.17767179770512e-06 -1.75801567907385e-06 5.61746664864837e-07 2.91569053440497e-06 0.00021313168705543 -1.89573291942367e-06 6.38005218000651e-05 4.25268137398342e-06 1.75570006230524e-07 4.75958938319901e-06 -1.89573291942367e-06 9.81049204201894e-06 2.35029480121334e-07 -1.41956077711627e-05 -1.59048545555089e-05 -3.17767179770512e-06 6.38005218000651e-05 2.35029480121334e-07 0.000101978878409968 3307 3310 0 1105 412 3307 3310 0 999 467 0 0 0 0 0 0 0 0 2682 0 0 0 0 0 3271 +1166 1169 0.997157284393507 0.0442100357344128 0.0610149401485277 0.37791697688323 -0.0429211387820238 0.998830086613611 -0.022276308516013 -0.100747251847951 -0.061928394348802 0.0195941525922476 0.997888241817475 -0.0924094642281506 3.48829108025911e-05 1.16709098607144e-05 9.02021546949413e-06 -4.53619850948456e-07 1.86836347731712e-06 -1.31199478219706e-05 1.16709098607144e-05 4.83025738105628e-05 3.37952787480607e-06 -6.21052946035237e-06 2.10278427916894e-06 2.09681042720504e-05 9.02021546949413e-06 3.37952787480607e-06 1.14539663052569e-05 -5.44432096263918e-06 3.8328625290929e-06 -6.71402608756767e-06 -4.53619850948456e-07 -6.21052946035237e-06 -5.44432096263918e-06 0.000195211264291588 2.34661828763366e-06 2.71705396067511e-05 1.86836347731712e-06 2.10278427916894e-06 3.8328625290929e-06 2.34661828763366e-06 1.07070351461094e-05 1.38707143734513e-05 -1.31199478219706e-05 2.09681042720504e-05 -6.71402608756767e-06 2.71705396067511e-05 1.38707143734513e-05 0.000256357503810174 3246 3246 0 815 211 3246 3246 0 723 251 0 0 0 0 0 0 0 0 2990 0 0 0 0 0 3506 +1166 1057 0.852154640933961 -0.517074885217572 0.080411634804584 -1.59526481195475 0.516392313644873 0.855802097845015 0.0306879085726941 0.568972530507712 -0.0846843925597034 0.0153731064299274 0.996289225704809 0.528719517308487 7.21660021654618e-05 2.87059019601425e-05 -2.92532076271635e-06 -4.36988801850832e-05 3.56832902722153e-05 0.00013262445555654 2.87059019601425e-05 0.000180318421874432 -4.38988936351074e-06 -0.000185239308547691 0.000134326121782792 0.000504770329649021 -2.92532076271635e-06 -4.38988936351074e-06 1.37232132070087e-05 1.16353752361444e-05 -4.38810216209608e-07 -1.69641897244057e-05 -4.36988801850832e-05 -0.000185239308547691 1.16353752361444e-05 0.000281805567030501 -0.000190431689244034 -0.00074595345789529 3.56832902722153e-05 0.000134326121782792 -4.38810216209608e-07 -0.000190431689244034 0.000153653267874001 0.000545524513692154 0.00013262445555654 0.000504770329649021 -1.69641897244057e-05 -0.00074595345789529 0.000545524513692154 0.00242696021962001 475 440 0 0 520 467 432 0 0 529 0 0 0 0 0 916 916 0 0 0 0 0 0 0 738 +1167 1059 0.750712701389659 -0.658460101546876 0.0534858359111905 -1.68082710849547 0.657638868286119 0.752555839862394 0.03421734660022 0.627402313605577 -0.0627818356819336 0.009486967897335 0.997982183482512 0.590282954129519 4.67746062933282e-05 -1.4050910865021e-06 6.1109093987763e-06 5.98016226123221e-06 -3.11265202014738e-06 2.0547311454769e-05 -1.4050910865021e-06 7.37733063141001e-05 -3.23299565334671e-06 -5.03824909497299e-07 -3.08440837609176e-06 -1.9249037394154e-05 6.1109093987763e-06 -3.23299565334671e-06 1.41151466611906e-05 4.41111821324147e-06 4.92163982917227e-06 -8.40260200808823e-07 5.98016226123221e-06 -5.03824909497299e-07 4.41111821324147e-06 1.81083374143462e-05 1.25991374111982e-06 1.69158995845152e-05 -3.11265202014738e-06 -3.08440837609176e-06 4.92163982917227e-06 1.25991374111982e-06 1.47729532900245e-05 -5.45787994007425e-06 2.0547311454769e-05 -1.9249037394154e-05 -8.40260200808823e-07 1.69158995845152e-05 -5.45787994007425e-06 0.000179063249545017 262 256 0 0 623 253 247 0 0 634 0 0 0 0 0 606 606 0 0 0 0 0 0 0 711 +1167 1169 0.999676428931949 0.00237258619188119 0.0253260394185023 0.283532268901809 -0.00182373010659723 0.999763454940765 -0.0216727518650271 -0.0454682504747381 -0.0253714691408229 0.0216195513289901 0.99944428736872 -0.0231437763428382 4.52958764357753e-05 6.21246408847862e-06 2.68493204154158e-06 1.06282429340497e-05 7.6311570684374e-07 -2.52556747791089e-06 6.21246408847862e-06 3.38218320476604e-05 -1.56955600081793e-06 -4.97765868464517e-06 -6.53853940470323e-07 -2.19757855945265e-05 2.68493204154158e-06 -1.56955600081793e-06 1.30614662354714e-05 -5.08318694313161e-08 4.96201406816371e-06 -1.45406598560879e-07 1.06282429340497e-05 -4.97765868464517e-06 -5.08318694313161e-08 9.81353981295801e-05 -1.25882575945875e-07 8.19906135209079e-06 7.6311570684374e-07 -6.53853940470323e-07 4.96201406816371e-06 -1.25882575945875e-07 1.0396451123576e-05 4.47232491199468e-06 -2.52556747791089e-06 -2.19757855945265e-05 -1.45406598560879e-07 8.19906135209079e-06 4.47232491199468e-06 9.66408601359326e-05 3314 3314 0 422 239 3314 3314 0 371 289 0 0 0 0 0 0 0 0 3410 0 0 0 0 0 3447 +1167 1171 0.999810940393939 -0.00219669737013026 0.0193198858498589 0.551850825907931 0.00236764708841181 0.999958212122677 -0.00882996351540005 -0.069197981017668 -0.0192996817552065 0.00887403679745716 0.999774361421149 -0.0982780376925351 3.92532242239368e-05 2.83198634555695e-06 -1.30683110518695e-06 2.68282397331737e-06 1.21478740898116e-06 -1.66585310342671e-06 2.83198634555695e-06 2.2991876271052e-05 6.09041195422899e-07 -1.61800400116027e-06 -2.28264314406743e-07 -1.50479826822044e-05 -1.30683110518695e-06 6.09041195422899e-07 1.06917688951153e-05 -9.44523961879093e-07 5.0246655480822e-06 -3.69004064555776e-07 2.68282397331737e-06 -1.61800400116027e-06 -9.44523961879093e-07 9.71231821269853e-05 1.11209523460722e-06 2.43482706873704e-05 1.21478740898116e-06 -2.28264314406743e-07 5.0246655480822e-06 1.11209523460722e-06 9.77175044022442e-06 2.60113812022413e-06 -1.66585310342671e-06 -1.50479826822044e-05 -3.69004064555776e-07 2.43482706873704e-05 2.60113812022413e-06 8.37028131268296e-05 3440 3444 0 906 675 3440 3444 0 843 765 0 0 0 0 0 0 0 0 2898 0 0 0 0 0 2985 +1167 1170 0.999994524679607 -0.00292538012074614 -0.00154685550581652 0.406787745380687 0.00291395489779801 0.999968834707253 -0.00733747102703844 -0.0620702544307406 0.00156827218949089 0.00733292338485634 0.999971883983231 -0.0727673641652421 4.86557056315718e-05 -3.67247277962661e-06 1.04816236420806e-06 7.22569255888615e-06 1.48594289890777e-06 1.8910080687955e-07 -3.67247277962661e-06 5.16569512486683e-05 1.33281396717415e-06 1.48596085716758e-05 -1.29417998629929e-06 -1.19289600828234e-05 1.04816236420806e-06 1.33281396717415e-06 1.20603689088259e-05 1.47726808627346e-06 4.74586706171441e-06 -5.31698462658767e-06 7.22569255888615e-06 1.48596085716758e-05 1.47726808627346e-06 0.000219945619359098 -2.46470953357984e-06 5.63734404153653e-06 1.48594289890777e-06 -1.29417998629929e-06 4.74586706171441e-06 -2.46470953357984e-06 1.11545260131004e-05 7.31411469670575e-06 1.8910080687955e-07 -1.19289600828234e-05 -5.31698462658767e-06 5.63734404153653e-06 7.31411469670575e-06 0.000148998708464151 3164 3167 0 633 418 3164 3167 0 571 490 0 0 0 0 0 0 0 0 3178 0 0 0 0 0 3243 +1168 1170 0.999750220690806 -0.0124073204098304 -0.0185890997343052 0.256314941125671 0.0121291920838547 0.999813913851477 -0.0150006789307963 -0.0283335274249122 0.0187717587901905 0.0147714613102322 0.999714671795249 -0.0375189758196444 5.27797001689638e-05 2.11057660931388e-06 -6.92095657126077e-06 8.14756322473173e-06 1.25276227871845e-06 2.60966368046465e-06 2.11057660931388e-06 9.92963669410092e-05 -2.54736305226449e-06 9.02997212084561e-05 1.32379902093441e-05 0.000307618617779204 -6.92095657126077e-06 -2.54736305226449e-06 1.43483574149726e-05 -3.74185308402408e-06 3.80822760700258e-06 -2.11243369914819e-05 8.14756322473173e-06 9.02997212084561e-05 -3.74185308402408e-06 0.000288000386219942 2.14976855690976e-05 0.000478483628880029 1.25276227871845e-06 1.32379902093441e-05 3.80822760700258e-06 2.14976855690976e-05 1.52842770859887e-05 7.49222349322931e-05 2.60966368046465e-06 0.000307618617779204 -2.11243369914819e-05 0.000478483628880029 7.49222349322931e-05 0.00168742471671668 3311 3314 0 325 253 3311 3314 0 253 320 0 0 0 0 0 0 0 0 3488 0 0 0 0 0 3411 +1168 1172 0.999401256226411 -0.015151359079802 0.0311057128371505 0.535571729881375 0.014845501444 0.999839388151927 0.0100403678645723 -0.0390161182502179 -0.0312528421099355 -0.00957257635198825 0.99946567006678 -0.0990811087984299 5.24665389668648e-05 1.17865705641529e-07 7.09858979554203e-07 1.60898077641468e-06 2.34515703924763e-06 -8.78839187342071e-06 1.17865705641529e-07 6.01199722427931e-05 3.23172292591499e-06 1.35752801776771e-05 -2.61555309007303e-06 -3.21412693399697e-05 7.09858979554203e-07 3.23172292591499e-06 1.22392682995829e-05 -1.81698423606174e-06 4.92078824975746e-06 -2.25948864611975e-06 1.60898077641468e-06 1.35752801776771e-05 -1.81698423606174e-06 0.000110656930986758 9.79924908622422e-07 -6.44842124496583e-06 2.34515703924763e-06 -2.61555309007303e-06 4.92078824975746e-06 9.79924908622422e-07 1.07109685390805e-05 1.07264280668009e-06 -8.78839187342071e-06 -3.21412693399697e-05 -2.25948864611975e-06 -6.44842124496583e-06 1.07264280668009e-06 0.000116562335936767 3166 3168 0 802 739 3166 3168 0 723 832 0 0 0 0 0 0 0 0 3004 0 0 0 0 0 2923 +1168 1057 0.827966562651981 -0.560444613362949 0.0193185528111792 -1.93314864024109 0.559989387018895 0.828137960509227 0.0244827447362569 0.545780498062551 -0.029719649332815 -0.00945270945674012 0.999513576059606 0.439572958388673 4.91183228776915e-05 3.00168295976471e-05 3.01698002994695e-06 1.76193220733748e-05 -1.23760643638766e-05 -2.14567949436127e-05 3.00168295976471e-05 0.000315825901322228 -9.82359346561999e-06 5.21155419333424e-05 -3.50044330683792e-05 -0.000154961816813558 3.01698002994695e-06 -9.82359346561999e-06 1.34964938722016e-05 3.11479379136276e-06 6.1604408023923e-06 -3.06364698669406e-07 1.76193220733748e-05 5.21155419333424e-05 3.11479379136276e-06 0.000220948133618541 -0.000134120108080705 0.000243931172606943 -1.23760643638766e-05 -3.50044330683792e-05 6.1604408023923e-06 -0.000134120108080705 0.0001037622483988 -0.000152709299741496 -2.14567949436127e-05 -0.000154961816813558 -3.06364698669406e-07 0.000243931172606943 -0.000152709299741496 0.00119616497384314 302 272 0 0 468 298 268 0 0 477 0 0 0 0 0 612 612 0 0 0 0 0 0 0 613 +1169 1173 0.998988686998126 0.0105010574724718 0.0437187721890738 0.529035183700673 -0.0123360136194216 0.999044986375117 0.0419158438627214 -0.0316895439207305 -0.0432368594805604 -0.0424127691939873 0.998164180378937 -0.0824950990206591 4.40055379162371e-05 6.2351152182176e-08 7.20740964967581e-06 7.14908871099738e-06 -1.63680484904822e-07 -4.27129331362082e-06 6.2351152182176e-08 4.44130259466534e-05 -1.54159296078578e-06 1.10852059368894e-05 -5.25322971098433e-07 -3.31300098934977e-05 7.20740964967581e-06 -1.54159296078578e-06 1.40521137800832e-05 -4.65690560727392e-06 3.14164127330778e-06 1.41922472371748e-06 7.14908871099738e-06 1.10852059368894e-05 -4.65690560727392e-06 0.00015000752958194 2.22122577358835e-07 1.86152894653083e-05 -1.63680484904822e-07 -5.25322971098433e-07 3.14164127330778e-06 2.22122577358835e-07 1.26727922073152e-05 1.04341168933858e-06 -4.27129331362082e-06 -3.31300098934977e-05 1.41922472371748e-06 1.86152894653083e-05 1.04341168933858e-06 0.000108759302716022 3245 3249 0 851 680 3245 3249 0 776 774 0 0 0 0 0 0 0 0 2969 0 0 0 0 0 2979 +1169 1172 0.999526315250764 -0.0064831216240285 0.0300851168393574 0.395220850997901 0.00554818814289293 0.999502235873392 0.0310563695950008 -0.0278991033557586 -0.0302714837687351 -0.0308747407778313 0.999064756485955 -0.0566725543110432 4.55211425696489e-05 4.15016798492049e-07 1.10666328314743e-07 -1.28098751241493e-05 9.48607117725567e-07 -5.03762360046462e-06 4.15016798492049e-07 6.4028905946053e-05 1.1559521081217e-06 9.02847964151964e-06 -2.78411694038032e-06 -4.48735998363321e-05 1.10666328314743e-07 1.1559521081217e-06 1.45665173317566e-05 -1.41076355474611e-06 4.89079140707885e-06 8.86201695095664e-07 -1.28098751241493e-05 9.02847964151964e-06 -1.41076355474611e-06 8.46370738579327e-05 -6.89944629880644e-07 -1.30783953527242e-06 9.48607117725567e-07 -2.78411694038032e-06 4.89079140707885e-06 -6.89944629880644e-07 1.1213072467175e-05 5.2520881150413e-06 -5.03762360046462e-06 -4.48735998363321e-05 8.86201695095664e-07 -1.30783953527242e-06 5.2520881150413e-06 0.000112416001574262 3411 3413 0 558 467 3411 3413 0 486 541 0 0 0 0 0 0 0 0 3259 0 0 0 0 0 3205 +1169 1058 0.794103451507549 -0.607368890612767 0.0224218424669776 -2.02102084454433 0.605768503970636 0.793933990662195 0.0520897117325396 0.638788013657913 -0.049439133295138 -0.0277821739073567 0.998390666478812 0.517204693176265 5.89903880694603e-05 -1.5869655647595e-05 -2.47997368978819e-06 7.9071950629158e-06 -1.73084615486803e-06 2.96196680205855e-05 -1.5869655647595e-05 0.000223315020656347 -2.72224367130143e-06 -8.10163295711543e-06 1.49206863627123e-06 -0.000236610138491678 -2.47997368978819e-06 -2.72224367130143e-06 1.34858644904731e-05 4.03572797954996e-06 5.1424494237298e-06 -3.05690681921206e-06 7.9071950629158e-06 -8.10163295711543e-06 4.03572797954996e-06 3.70564803394356e-05 -1.26644530673436e-05 4.25237819694673e-05 -1.73084615486803e-06 1.49206863627123e-06 5.1424494237298e-06 -1.26644530673436e-05 2.54801129793146e-05 -2.17093122087163e-05 2.96196680205855e-05 -0.000236610138491678 -3.05690681921206e-06 4.25237819694673e-05 -2.17093122087163e-05 0.000503477745159977 302 282 0 0 492 297 277 0 0 499 0 0 0 0 0 488 488 0 0 0 0 0 0 0 531 +1170 1172 0.999018531404159 -0.00215578315008695 0.0442416829481702 0.270963756670927 0.0011660742066312 0.999748763828738 0.022384134869495 -0.0138429170725578 -0.044278823177917 -0.0223105764587317 0.998770055616436 -0.0372744242652841 4.62034948618311e-05 -9.65433730332281e-07 -1.7716363664898e-06 1.30918417481903e-05 3.39602100636315e-07 4.44011569802287e-06 -9.65433730332281e-07 8.75339714154816e-05 1.51988060959306e-07 4.7137240706702e-05 -4.01711780691591e-06 -5.72077753557451e-05 -1.7716363664898e-06 1.51988060959306e-07 1.24537207388904e-05 -4.23179642478453e-07 5.86813643169792e-06 3.1951491195288e-06 1.30918417481903e-05 4.7137240706702e-05 -4.23179642478453e-07 0.000360629229131355 -7.64920227537121e-06 3.42127592848893e-05 3.39602100636315e-07 -4.01711780691591e-06 5.86813643169792e-06 -7.64920227537121e-06 1.04517255575467e-05 8.67642239282895e-07 4.44011569802287e-06 -5.72077753557451e-05 3.1951491195288e-06 3.42127592848893e-05 8.67642239282895e-07 0.000166881260909322 3146 3148 0 344 272 3146 3148 0 284 347 0 0 0 0 0 0 0 0 3471 0 0 0 0 0 3409 +1170 1173 0.996898793037301 0.012709029190145 0.0776612967817066 0.413485016816534 -0.0148197396699443 0.999534627535483 0.0266627769300025 -0.0152333870447124 -0.0772862973423319 -0.0277310103412775 0.996623208293167 -0.0325622145331051 3.40348604836268e-05 4.67372817114328e-06 8.745926054791e-06 -1.6558055367357e-07 1.03401422566583e-06 -7.34116204748346e-06 4.67372817114328e-06 4.00464653623771e-05 1.90470758685422e-06 2.7933301232395e-06 1.92991279944425e-07 9.39475083750117e-06 8.745926054791e-06 1.90470758685422e-06 1.1344506492137e-05 -5.05240053774731e-07 3.94908168880007e-06 -6.82981593299169e-07 -1.6558055367357e-07 2.7933301232395e-06 -5.05240053774731e-07 0.000103757852722904 -1.50787049755152e-06 3.06818483380379e-06 1.03401422566583e-06 1.92991279944425e-07 3.94908168880007e-06 -1.50787049755152e-06 1.05411508081787e-05 8.40962134317494e-06 -7.34116204748346e-06 9.39475083750117e-06 -6.82981593299169e-07 3.06818483380379e-06 8.40962134317494e-06 0.000290337151689727 3335 3339 0 621 485 3335 3339 0 549 564 0 0 0 0 0 0 0 0 3205 0 0 0 0 0 3192 +1171 1060 0.708090108056491 -0.70465921547987 0.0454289435474924 -2.16889237101186 0.702965605519518 0.709540802718646 0.0488999666048693 0.746183512464679 -0.0666915011761268 -0.00269059782822568 0.99777001576225 0.743334496470544 4.9579733762688e-05 1.50572292171904e-05 5.42048480972337e-06 5.30165227419652e-06 -4.35452419269916e-06 2.9529177478918e-06 1.50572292171904e-05 0.000377271570692393 -7.53138818176248e-06 7.83656552957379e-05 -7.96515918332858e-05 -0.000308789477401493 5.42048480972337e-06 -7.53138818176248e-06 1.46235707708501e-05 3.91914678557574e-06 5.13441883572158e-06 5.80901186179579e-06 5.30165227419652e-06 7.83656552957379e-05 3.91914678557574e-06 5.36167416722893e-05 -3.73385538977205e-05 -4.53227069768011e-05 -4.35452419269916e-06 -7.96515918332858e-05 5.13441883572158e-06 -3.73385538977205e-05 5.69882010048762e-05 4.6739261879584e-05 2.9529177478918e-06 -0.000308789477401493 5.80901186179579e-06 -4.53227069768011e-05 4.6739261879584e-05 0.000354773837713782 148 143 0 0 503 148 143 0 0 511 0 0 0 0 0 273 273 0 0 0 0 0 0 0 384 +1171 1174 0.998098804736424 0.0447551778728292 0.0423762909808492 0.409107543403589 -0.0456688653067364 0.998739146163284 0.0208440078350929 -0.0124904221444657 -0.041389983393538 -0.0227396564311263 0.998884266219104 -0.0210448323697688 4.04739535342922e-05 -2.8410726107929e-08 3.74404466438632e-06 -1.07616105371841e-05 -3.80856664880656e-07 4.3379033031599e-06 -2.8410726107929e-08 4.34939216603903e-05 -1.35466805051882e-06 5.94242379917567e-06 -7.47906507068616e-07 -6.88703144398635e-06 3.74404466438632e-06 -1.35466805051882e-06 1.28463129627347e-05 -2.38661332574838e-06 4.47790734692516e-06 -2.76784078762253e-06 -1.07616105371841e-05 5.94242379917567e-06 -2.38661332574838e-06 8.30186968304059e-05 -1.95400713345573e-06 -1.61946754216799e-05 -3.80856664880656e-07 -7.47906507068616e-07 4.47790734692516e-06 -1.95400713345573e-06 1.05731193974901e-05 3.28765364807158e-06 4.3379033031599e-06 -6.88703144398635e-06 -2.76784078762253e-06 -1.61946754216799e-05 3.28765364807158e-06 0.000151775258374256 3120 3131 0 698 399 3120 3131 0 626 481 0 0 0 0 0 0 0 0 3146 0 0 0 0 0 3289 +1171 1175 0.997072443235362 0.0754402283454178 0.0124625393823467 0.551958976375592 -0.075717290388682 0.996852402824109 0.0234984876108201 -0.0210917370404644 -0.0106505810574502 -0.0243733241678498 0.999646190505495 -0.0372153925457344 4.5984934781687e-05 1.3784354614847e-05 4.46561804822174e-06 1.49284065183465e-06 -6.09962291535437e-07 -7.15401491578735e-06 1.3784354614847e-05 4.316283166931e-05 4.22308603091778e-06 2.63388019324939e-06 1.3341761261265e-06 8.53942756821673e-06 4.46561804822174e-06 4.22308603091778e-06 1.29517994069654e-05 -2.28612257794798e-07 3.93561998889365e-06 -3.11206040835621e-06 1.49284065183465e-06 2.63388019324939e-06 -2.28612257794798e-07 9.77574594241013e-05 1.45559980840328e-06 2.88277367831328e-05 -6.09962291535437e-07 1.3341761261265e-06 3.93561998889365e-06 1.45559980840328e-06 1.10673888974675e-05 9.79298482739733e-06 -7.15401491578735e-06 8.53942756821673e-06 -3.11206040835621e-06 2.88277367831328e-05 9.79298482739733e-06 0.000279359441543986 3303 3325 0 1038 586 3303 3325 0 961 692 0 0 0 0 0 0 0 0 2797 0 0 0 0 0 3096 +1172 1174 0.998890034962356 0.0459631266338185 0.0102999535409645 0.284085900715128 -0.0460020610284814 0.998934946115665 0.00357544543019476 -0.00877177376279023 -0.0101246448843569 -0.00404529590215521 0.999940561807065 -0.00542765541024945 3.82389500522124e-05 3.58568635433337e-06 6.37939142988793e-06 -8.52906077734121e-06 6.1523196498542e-07 1.74840655205741e-05 3.58568635433337e-06 4.25036103177953e-05 -6.37274399088451e-07 1.30808089580302e-05 1.46078891651378e-06 3.54569617561102e-05 6.37939142988793e-06 -6.37274399088451e-07 1.27606197916102e-05 -6.10111930595804e-07 4.73452242309821e-06 1.40991169490673e-07 -8.52906077734121e-06 1.30808089580302e-05 -6.10111930595804e-07 7.62081305853438e-05 1.62615688724683e-06 4.60255478212151e-05 6.1523196498542e-07 1.46078891651378e-06 4.73452242309821e-06 1.62615688724683e-06 1.02539929472333e-05 1.20002282277888e-05 1.74840655205741e-05 3.54569617561102e-05 1.40991169490673e-07 4.60255478212151e-05 1.20002282277888e-05 0.000388087179729857 3419 3430 0 490 199 3419 3430 0 431 268 0 0 0 0 0 0 0 0 3361 0 0 0 0 0 3518 +1172 1175 0.996614498498299 0.0774531135233153 -0.0275781904505755 0.419192000314021 -0.0773361231723624 0.996991067660965 0.00528536251537504 -0.0174697803713474 0.027904577324392 -0.00313467857908562 0.999605676431738 -0.0491692031886733 3.51633550348107e-05 9.03515800160172e-06 5.07738775762693e-07 -3.98768461702591e-06 -2.46456482047117e-06 -5.33308667250895e-06 9.03515800160172e-06 3.720741951791e-05 4.26322467510291e-06 5.57553855437846e-06 4.50648707350712e-07 -1.40252925145443e-05 5.07738775762693e-07 4.26322467510291e-06 1.21089689047125e-05 -3.36968716227121e-06 4.49075651890293e-06 -2.49570948617817e-06 -3.98768461702591e-06 5.57553855437846e-06 -3.36968716227121e-06 7.94958826181476e-05 -3.10461390293093e-07 1.19317119707572e-06 -2.46456482047117e-06 4.50648707350712e-07 4.49075651890293e-06 -3.10461390293093e-07 1.06446768463202e-05 1.71992426442484e-06 -5.33308667250895e-06 -1.40252925145443e-05 -2.49570948617817e-06 1.19317119707572e-06 1.71992426442484e-06 0.000110748971405193 3353 3375 0 796 327 3353 3375 0 730 407 0 0 0 0 0 0 0 0 3047 0 0 0 0 0 3382 +1173 1177 0.994767031933436 0.0930368796190517 -0.0422219280598668 0.569554421181004 -0.0936053147906223 0.995540780079157 -0.0116876106340113 -0.0176716154369538 0.040946272373575 0.0155786466078999 0.999039893371919 -0.0470981580765754 3.81452836393943e-05 1.26196740541524e-06 -4.24256306944168e-06 -2.98175457333105e-06 -3.1345990425443e-06 -1.38258713535777e-05 1.26196740541524e-06 3.82738495607135e-05 -1.20942579807778e-06 7.12506687977364e-06 4.830729489338e-07 -1.75880002425052e-05 -4.24256306944168e-06 -1.20942579807778e-06 1.15649511856718e-05 -1.35268383257257e-07 4.06738906768177e-06 2.33857443919374e-06 -2.98175457333105e-06 7.12506687977364e-06 -1.35268383257257e-07 9.70112830306977e-05 1.59473297409707e-06 3.42420110443172e-05 -3.1345990425443e-06 4.830729489338e-07 4.06738906768177e-06 1.59473297409707e-06 1.13529210001353e-05 2.50795193510418e-06 -1.38258713535777e-05 -1.75880002425052e-05 2.33857443919374e-06 3.42420110443172e-05 2.50795193510418e-06 0.000136796646301676 3384 3415 0 1084 589 3384 3415 0 1009 665 0 0 0 0 0 0 0 0 2742 0 0 0 0 0 3135 +1174 1177 0.997670848725992 0.0626138869164091 -0.0270624974379344 0.431770198608467 -0.0630574220905963 0.997883900803624 -0.0158581851493674 0.000994206511636452 0.0260122878972121 0.0175277403609928 0.999507948540776 -0.0228457463097529 4.96049481855159e-05 -3.97420188124015e-06 -9.13435153728046e-07 -1.76042610861659e-05 -2.22161994159243e-06 -7.70871352610471e-06 -3.97420188124015e-06 3.0636248330352e-05 -3.29844236032508e-06 4.84464441317752e-06 1.34342661700357e-06 1.92974714791648e-05 -9.13435153728046e-07 -3.29844236032508e-06 1.19253573776242e-05 -2.73494963197447e-07 4.47446440717767e-06 4.35007800202438e-07 -1.76042610861659e-05 4.84464441317752e-06 -2.73494963197447e-07 7.03979177982939e-05 7.94364883260837e-07 3.51486711568321e-05 -2.22161994159243e-06 1.34342661700357e-06 4.47446440717767e-06 7.94364883260837e-07 1.08102286056834e-05 1.00396450005362e-05 -7.70871352610471e-06 1.92974714791648e-05 4.35007800202438e-07 3.51486711568321e-05 1.00396450005362e-05 0.000214321192994774 3372 3403 0 734 425 3372 3403 0 667 515 0 0 0 0 0 0 0 0 3109 0 0 0 0 0 3285 +1174 1176 0.998035468252259 0.0477459052159007 -0.0405651654206892 0.288581240610465 -0.0483356521975552 0.998737416279086 -0.01368349556261 -0.000408661389259284 0.0398606176210383 0.0156173576282679 0.999083194385523 -0.0615608357141592 3.87421648690048e-05 -7.06789902615783e-06 -2.20810694430214e-06 4.92875095881083e-08 -5.69539818037656e-07 7.10749484001828e-06 -7.06789902615783e-06 5.27150643965611e-05 3.46516970037689e-06 6.86674942764741e-07 -1.4628264557421e-06 -3.32713862340818e-05 -2.20810694430214e-06 3.46516970037689e-06 1.12516252108189e-05 -1.38463785881159e-06 4.58009396284211e-06 -3.89561876769155e-06 4.92875095881083e-08 6.86674942764741e-07 -1.38463785881159e-06 8.1058242286264e-05 -2.81096309216139e-07 -3.42427326188043e-06 -5.69539818037656e-07 -1.4628264557421e-06 4.58009396284211e-06 -2.81096309216139e-07 1.04457933606426e-05 6.186678491648e-06 7.10749484001828e-06 -3.32713862340818e-05 -3.89561876769155e-06 -3.42427326188043e-06 6.186678491648e-06 0.000128295922340638 3277 3303 0 477 210 3277 3303 0 424 280 0 0 0 0 0 0 0 0 3367 0 0 0 0 0 3522 +1174 1178 0.99813527600215 0.0602936498889775 -0.00952084991890425 0.58449391768805 -0.0603882008844924 0.998125106477882 -0.00997682376567446 0.00244055762637804 0.00890146021993463 0.0105331667404702 0.99990490368053 -0.0320151532380394 3.83274782531901e-05 -3.92866703284293e-06 -7.7926122064806e-07 4.88168574876085e-06 -9.41192230097442e-07 -5.70268865759087e-06 -3.92866703284293e-06 4.93936871441756e-05 -2.483837028768e-06 1.30167523155263e-05 1.86797891230236e-06 9.83649284005249e-06 -7.7926122064806e-07 -2.483837028768e-06 1.11732054777275e-05 -3.52182307558939e-06 3.03125920633272e-06 -3.13796476607131e-06 4.88168574876085e-06 1.30167523155263e-05 -3.52182307558939e-06 8.31927154637739e-05 8.75888183043924e-07 -1.03548068955076e-06 -9.41192230097442e-07 1.86797891230236e-06 3.03125920633272e-06 8.75888183043924e-07 1.13554382447706e-05 8.08437820398862e-06 -5.70268865759087e-06 9.83649284005249e-06 -3.13796476607131e-06 -1.03548068955076e-06 8.08437820398862e-06 0.000219640658675668 3354 3383 0 978 752 3354 3383 0 905 851 0 0 0 0 0 0 0 0 2843 0 0 0 0 0 2945 +1175 1177 0.999541319607092 0.0302221864276334 -0.00194160903517661 0.284040292486373 -0.0302487240726783 0.999421897986828 -0.0155204547736271 0.010381601062861 0.00147142450947437 0.0155720670412955 0.999877665336102 -0.0433766015313138 3.56010666496036e-05 -4.59645739043923e-06 2.15018263367884e-06 4.24483079565481e-06 4.33654503560347e-07 5.71923927120965e-06 -4.59645739043923e-06 3.37487624203481e-05 1.34237247182433e-06 7.53844138514932e-07 4.80827777317366e-07 -1.71718831252815e-06 2.15018263367884e-06 1.34237247182433e-06 1.24103213660888e-05 5.61362277248711e-07 4.33984502450249e-06 -1.55121001343146e-06 4.24483079565481e-06 7.53844138514932e-07 5.61362277248711e-07 0.000102085979678076 -2.61297116837808e-09 -1.54322761147367e-05 4.33654503560347e-07 4.80827777317366e-07 4.33984502450249e-06 -2.61297116837808e-09 1.10381618858333e-05 4.31302365032285e-06 5.71923927120965e-06 -1.71718831252815e-06 -1.55121001343146e-06 -1.54322761147367e-05 4.31302365032285e-06 0.000167666682081671 3426 3457 0 403 263 3426 3457 0 356 346 0 0 0 0 0 0 0 0 3446 0 0 0 0 0 3453 +1175 1179 0.999190618482011 0.0112396246165755 0.0386235520895691 0.590483527581515 -0.0108086184073172 0.999877169084878 -0.0113499123756983 0.0307265700367277 -0.0387463766778545 0.0109232587303193 0.999189371797483 -0.0375185955931633 5.07302049690999e-05 6.23097321604279e-07 4.50637836481153e-06 -1.1837123435973e-06 2.05455384535634e-08 7.24897231802529e-06 6.23097321604279e-07 2.43994774293519e-05 9.15967441822597e-07 6.83755208582224e-06 5.56731661696928e-07 -9.2692311284769e-06 4.50637836481153e-06 9.15967441822597e-07 1.08340717278113e-05 -2.8873871296028e-06 3.59191795963518e-06 -1.51506883170257e-06 -1.1837123435973e-06 6.83755208582224e-06 -2.8873871296028e-06 4.95175572868155e-05 -2.47150122675266e-06 -1.95177379262524e-06 2.05455384535634e-08 5.56731661696928e-07 3.59191795963518e-06 -2.47150122675266e-06 1.04872977072845e-05 2.72800912075189e-06 7.24897231802529e-06 -9.2692311284769e-06 -1.51506883170257e-06 -1.95177379262524e-06 2.72800912075189e-06 0.000100050576803923 3480 3504 0 806 949 3480 3504 0 744 1055 0 0 0 0 0 0 0 0 3008 0 0 0 0 0 2734 +1177 1151 0.36443947647788 -0.93094373254036 -0.0229703031836989 -2.89901731840785 0.931125595207099 0.36465303494756 -0.00576975335339552 0.472516954552924 0.0137475064922487 -0.0192855113324912 0.99971949821832 0.725124779153294 6.58196334300313e-05 -5.54771954034124e-05 6.595460864399e-06 1.03413410530589e-05 -1.07618472340175e-05 2.95089935533067e-05 -5.54771954034124e-05 0.000106888499747126 -8.44000577628412e-06 -2.02370690367292e-05 2.76564129550026e-05 -4.71504742231112e-05 6.595460864399e-06 -8.44000577628412e-06 1.56643526819141e-05 6.8239891690485e-06 1.0420264793065e-06 1.07887057336577e-05 1.03413410530589e-05 -2.02370690367292e-05 6.8239891690485e-06 4.2610508971356e-05 -5.60435987510166e-05 9.60403556075532e-06 -1.07618472340175e-05 2.76564129550026e-05 1.0420264793065e-06 -5.60435987510166e-05 0.000140492661383309 1.67434096187012e-05 2.95089935533067e-05 -4.71504742231112e-05 1.07887057336577e-05 9.60403556075532e-06 1.67434096187012e-05 0.000463372651554909 0 0 0 0 653 0 0 0 0 658 0 0 0 0 0 0 0 0 0 67 0 0 0 0 256 +1177 1150 0.294060614917954 -0.955563109954613 -0.0206760162493212 -2.96263460100451 0.955513109508339 0.294425253230562 -0.0175632519148325 0.505751184372142 0.0228703369406593 -0.0145915439205993 0.999631949536545 0.831229924529361 0.000156203867377796 -0.000142071196216773 -4.83988104134808e-07 5.90288387701644e-05 -6.88140975944259e-05 0.00017777649593397 -0.000142071196216773 0.000767504701816998 -3.8020590153685e-05 4.07185747246278e-06 -0.000128647744321084 -0.00059272601618727 -4.83988104134808e-07 -3.8020590153685e-05 1.93743439562155e-05 7.67131436104285e-07 1.79236380230595e-05 3.45036649826015e-05 5.90288387701644e-05 4.07185747246278e-06 7.67131436104285e-07 0.000104447653065691 -0.000166418852137064 0.000268044403063221 -6.88140975944259e-05 -0.000128647744321084 1.79236380230595e-05 -0.000166418852137064 0.000369219211442846 -0.00034468063093575 0.00017777649593397 -0.00059272601618727 3.45036649826015e-05 0.000268044403063221 -0.00034468063093575 0.00214150346528319 0 0 0 0 531 0 0 0 0 535 0 0 0 0 0 0 0 0 0 50 0 0 0 0 197 +1176 1179 0.999291710858633 -0.00617559024935018 0.0371205966317709 0.440050866913828 0.00596645197197166 0.999965713920135 0.0057421629252539 0.0317740481731045 -0.0371547851574015 -0.00551661755663159 0.999294295425848 -0.018246938776774 3.83153088476721e-05 -1.31004215756522e-05 4.66805723270623e-07 -8.98173320850247e-07 -1.0684530806917e-06 -3.72601803947968e-06 -1.31004215756522e-05 3.22523673374889e-05 -6.47216221734388e-07 8.53776548920343e-06 8.3875271389187e-07 2.11500017155615e-05 4.66805723270623e-07 -6.47216221734388e-07 1.13248789678189e-05 -4.04531064613869e-06 3.72551710588582e-06 -5.45639852723168e-06 -8.98173320850247e-07 8.53776548920343e-06 -4.04531064613869e-06 5.67258370579112e-05 -2.11675414261433e-06 1.35000231013388e-05 -1.0684530806917e-06 8.3875271389187e-07 3.72551710588582e-06 -2.11675414261433e-06 1.04159654499055e-05 8.38871262410305e-06 -3.72601803947968e-06 2.11500017155615e-05 -5.45639852723168e-06 1.35000231013388e-05 8.38871262410305e-06 0.000280147435392121 3172 3196 0 497 680 3172 3196 0 444 778 0 0 0 0 0 0 0 0 3321 0 0 0 0 0 3013 +1179 1181 0.997398551137006 -0.0630395963328595 -0.0349591116018553 0.305082713473591 0.0642319253846289 0.997352175431071 0.034101289188137 0.0413892620353349 0.0327168145023978 -0.0362580674760752 0.998806769396221 -0.017674785840752 3.91672185747091e-05 -1.86368491609671e-05 -1.86932102499096e-06 -5.58682256677761e-06 -2.07694322771164e-07 8.89656253502419e-06 -1.86368491609671e-05 6.37624401720794e-05 -4.54190154186459e-07 3.04268191571222e-05 -1.19523615058961e-06 0.000129362326353563 -1.86932102499096e-06 -4.54190154186459e-07 1.38255156282871e-05 1.21129989391478e-06 4.55179127463597e-06 4.08950500095267e-06 -5.58682256677761e-06 3.04268191571222e-05 1.21129989391478e-06 0.000103057596422581 6.66575522026058e-07 0.000145130836904846 -2.07694322771164e-07 -1.19523615058961e-06 4.55179127463597e-06 6.66575522026058e-07 1.04334348393346e-05 -2.35687897527807e-08 8.89656253502419e-06 0.000129362326353563 4.08950500095267e-06 0.000145130836904846 -2.35687897527807e-08 0.00101941355900885 3434 3438 0 136 567 3434 3438 0 84 646 0 0 0 0 0 0 0 0 3676 0 0 0 0 0 3125 +1179 1182 0.996089962642148 -0.0847695883762861 -0.02487776537552 0.444499217442405 0.0857003514989845 0.995553644400023 0.039094639975097 0.0663626562045414 0.0214531134457196 -0.0410738117094939 0.998925775978945 -0.037166127166881 4.55919296170158e-05 -1.10709149402222e-05 3.634675113797e-07 4.22183112106954e-06 3.00539157714926e-07 -4.67065005752635e-07 -1.10709149402222e-05 5.78568658050282e-05 1.77923984633395e-06 1.08312108720349e-05 -5.85943156632647e-07 -3.26865084884071e-05 3.634675113797e-07 1.77923984633395e-06 1.19059958486423e-05 7.85633524514845e-07 4.76720748763555e-06 -1.83561198873545e-06 4.22183112106954e-06 1.08312108720349e-05 7.85633524514845e-07 0.000104040476899281 2.84738670355911e-07 1.13233666145976e-05 3.00539157714926e-07 -5.85943156632647e-07 4.76720748763555e-06 2.84738670355911e-07 1.00278056418931e-05 2.0675436856456e-06 -4.67065005752635e-07 -3.26865084884071e-05 -1.83561198873545e-06 1.13233666145976e-05 2.0675436856456e-06 0.000100116459031343 3311 3307 0 268 922 3311 3307 0 208 1010 0 0 0 0 0 0 0 0 3543 0 0 0 0 0 2763 +1179 1151 0.382836753128479 -0.922709264317804 -0.0452065702762378 -3.20475100331259 0.923344916628668 0.383745677029987 -0.0131689140324963 0.500284584426531 0.0294989048956476 -0.0366997125723518 0.998890857755273 0.579689256138308 0.000101824025759021 -0.000110489706727272 5.68222196451187e-06 1.8391488825969e-05 -1.70530332929282e-05 7.95224638450651e-05 -0.000110489706727272 0.000624762695087149 -2.54868913145858e-05 4.44459529024667e-05 -0.000158017952559997 -0.000559899188281611 5.68222196451187e-06 -2.54868913145858e-05 1.7202120915062e-05 1.00960001482323e-06 1.53292884232686e-05 2.6214701149611e-05 1.8391488825969e-05 4.44459529024667e-05 1.00960001482323e-06 6.12306102325936e-05 -0.000101446831154432 -8.54941628802937e-05 -1.70530332929282e-05 -0.000158017952559997 1.53292884232686e-05 -0.000101446831154432 0.000248135618873948 0.000241835949299836 7.95224638450651e-05 -0.000559899188281611 2.6214701149611e-05 -8.54941628802937e-05 0.000241835949299836 0.000708842372538145 0 0 0 0 502 0 0 0 0 506 0 0 0 0 0 0 0 0 0 76 0 0 0 0 240 +1178 1180 0.998666496009225 -0.0508265293454626 0.00904951177424502 0.294527489206052 0.0506550320291369 0.998549146359359 0.018266637214385 0.0374631096230355 -0.0099648120295612 -0.0177838752719892 0.999792196559628 0.0178138853285176 3.69194582111482e-05 -1.61778064146481e-05 -7.96688157175593e-07 -8.06524165747346e-06 -1.98539760374093e-06 -1.20099275988538e-05 -1.61778064146481e-05 4.41059541043987e-05 -2.4086034206829e-06 1.63452458269542e-05 1.35292247806775e-06 6.79046102113034e-05 -7.96688157175593e-07 -2.4086034206829e-06 1.07061771606848e-05 -5.01486743824914e-06 4.79281830579797e-06 -2.87499176953548e-06 -8.06524165747346e-06 1.63452458269542e-05 -5.01486743824914e-06 9.01517443801958e-05 3.66201255867365e-06 3.82650613348587e-05 -1.98539760374093e-06 1.35292247806775e-06 4.79281830579797e-06 3.66201255867365e-06 9.59689011221825e-06 1.11706816838166e-05 -1.20099275988538e-05 6.79046102113034e-05 -2.87499176953548e-06 3.82650613348587e-05 1.11706816838166e-05 0.000514646920113299 3235 3250 0 159 518 3235 3250 0 112 610 0 0 0 0 0 0 0 0 3675 0 0 0 0 0 3167 +1180 1182 0.998535116034998 -0.0530359480693646 -0.0107149548462644 0.293595243030773 0.0532393654504165 0.998387711264899 0.0196862378750813 0.0408523053344619 0.00965360095564469 -0.0202278572177319 0.999748789337086 -0.0171614679647882 4.4282640572598e-05 -3.26254429813373e-06 -6.00601356540031e-07 -4.04657161117427e-06 3.46364408767457e-07 6.25397865251293e-06 -3.26254429813373e-06 3.79501788956643e-05 5.95606401669984e-07 -2.44111778393373e-06 -4.64585922136062e-07 -2.96666676733307e-05 -6.00601356540031e-07 5.95606401669984e-07 1.27637523483498e-05 -1.42047355751768e-06 5.47726618100011e-06 -1.24045487387961e-06 -4.04657161117427e-06 -2.44111778393373e-06 -1.42047355751768e-06 6.83901197591857e-05 6.94477010759247e-07 1.19391898802147e-05 3.46364408767457e-07 -4.64585922136062e-07 5.47726618100011e-06 6.94477010759247e-07 1.01842903386395e-05 1.6107830556768e-06 6.25397865251293e-06 -2.96666676733307e-05 -1.24045487387961e-06 1.19391898802147e-05 1.6107830556768e-06 0.000106338920161933 3691 3687 0 162 513 3691 3687 0 103 596 0 0 0 0 0 0 0 0 3657 0 0 0 0 0 3192 +1181 1185 0.997234517405027 0.0103207878277408 0.0735989037593449 0.593938992960566 -0.00794881673989751 0.999441791746916 -0.0324487476206616 0.0510456875809898 -0.0738927168833173 0.0317739869756476 0.996759890918206 -0.00734999988611192 4.50406714282155e-05 3.41514965235076e-07 -1.14804348164276e-07 -1.53030324716345e-05 6.19124254775971e-07 -6.43473302723652e-06 3.41514965235076e-07 2.94925179002267e-05 6.44621266105197e-07 1.05082492446915e-05 -2.87313847435472e-07 -2.26280291436882e-05 -1.14804348164276e-07 6.44621266105197e-07 1.15050305563672e-05 3.48470703469591e-07 4.45765247936195e-06 -3.0304159235012e-07 -1.53030324716345e-05 1.05082492446915e-05 3.48470703469591e-07 8.35906226556703e-05 -1.04543109174011e-06 -1.11103579992038e-05 6.19124254775971e-07 -2.87313847435472e-07 4.45765247936195e-06 -1.04543109174011e-06 9.99126040179269e-06 4.44839952760023e-07 -6.43473302723652e-06 -2.26280291436882e-05 -3.0304159235012e-07 -1.11103579992038e-05 4.44839952760023e-07 6.01342698911914e-05 3473 3466 0 883 914 3473 3466 0 794 1006 0 0 0 0 0 0 0 0 2954 0 0 0 0 0 2783 +1182 1184 0.998283650388914 0.00129012880034119 0.0585498841490191 0.298749457092962 -0.000299913429018187 0.999856835853047 -0.0169179741655849 0.0203160532244397 -0.0585633282705152 0.0168713771106817 0.998141118888641 0.0209290864509128 3.10601676395332e-05 1.93427264144475e-06 2.92699222260458e-06 -6.1196694309363e-06 1.79159440737776e-06 5.87991479056569e-06 1.93427264144475e-06 3.35149059046024e-05 -6.1884754433878e-07 1.31811356366415e-05 -1.95274453713428e-07 7.78626961457183e-07 2.92699222260458e-06 -6.1884754433878e-07 9.67396331060925e-06 1.61535718314729e-08 4.72700919379247e-06 6.96619771747602e-07 -6.1196694309363e-06 1.31811356366415e-05 1.61535718314729e-08 6.29872732405895e-05 4.10521150963417e-07 7.70558560985529e-06 1.79159440737776e-06 -1.95274453713428e-07 4.72700919379247e-06 4.10521150963417e-07 9.23675138774753e-06 2.69967498550811e-06 5.87991479056569e-06 7.78626961457183e-07 6.96619771747602e-07 7.70558560985529e-06 2.69967498550811e-06 0.000158418834785527 3453 3444 0 385 355 3453 3444 0 316 415 0 0 0 0 0 0 0 0 3443 0 0 0 0 0 3369 +1180 1184 0.997626211457165 -0.0515899403783484 0.045611624235306 0.593340233875581 0.0513800685221499 0.998662546540631 0.00576252510988788 0.0783888878022495 -0.0458479091375329 -0.00340531771518765 0.998942627501187 0.0135861259757142 4.02724435778793e-05 -9.98876045025258e-06 -2.44791055519855e-06 2.77331788144901e-06 -6.80517659572894e-07 6.33590655638918e-06 -9.98876045025258e-06 4.68410841690849e-05 -9.45956441213653e-07 -5.03188467086764e-06 -6.58409591299652e-07 -3.49812953270234e-05 -2.44791055519855e-06 -9.45956441213653e-07 1.0494109379129e-05 -3.16778213389587e-06 4.96986764779369e-06 2.22469120839549e-06 2.77331788144901e-06 -5.03188467086764e-06 -3.16778213389587e-06 9.39102999918253e-05 -1.00754954688273e-06 7.049284552001e-07 -6.80517659572894e-07 -6.58409591299652e-07 4.96986764779369e-06 -1.00754954688273e-06 9.3672933077252e-06 3.06848713606704e-07 6.33590655638918e-06 -3.49812953270234e-05 2.22469120839549e-06 7.049284552001e-07 3.06848713606704e-07 7.36641434927829e-05 3658 3649 0 655 1129 3658 3649 0 572 1232 0 0 0 0 0 0 0 0 3176 0 0 0 0 0 2537 +1182 1186 0.997481355231873 0.0595083310373976 0.0385966902976211 0.599004115370485 -0.0572261596344453 0.996689094521895 -0.0577582506194429 0.0249803302662348 -0.0419059974022808 0.0554040377433711 0.997584222000053 -0.02225195092434 4.39205499144552e-05 -1.64540050646891e-06 -1.57793027606836e-06 -8.86819252025439e-07 1.84168280212959e-06 7.43139403796328e-08 -1.64540050646891e-06 2.27694687751785e-05 2.56166815642955e-07 1.0229044023579e-07 2.35987957394152e-07 -6.19459063060598e-06 -1.57793027606836e-06 2.56166815642955e-07 1.04688287699772e-05 -8.53850959853915e-07 4.69993174738279e-06 1.29207482829867e-07 -8.86819252025439e-07 1.0229044023579e-07 -8.53850959853915e-07 7.40022310261173e-05 1.10144327602554e-06 6.67837322099804e-06 1.84168280212959e-06 2.35987957394152e-07 4.69993174738279e-06 1.10144327602554e-06 1.03982579485671e-05 4.33858081367789e-06 7.43139403796328e-08 -6.19459063060598e-06 1.29207482829867e-07 6.67837322099804e-06 4.33858081367789e-06 0.000111305797896177 3322 3321 0 1083 753 3322 3321 0 994 829 0 0 0 0 0 0 0 0 2729 0 0 0 0 0 2982 +1181 1184 0.997841398985055 -0.0205709769360295 0.0623648729610303 0.434895593703114 0.0213908767641174 0.999692946629483 -0.012507711642174 0.0448650095066308 -0.0620884277688721 0.0138147517950478 0.997975039652812 -0.0207501589355132 3.21916082159921e-05 -1.93613957366529e-06 2.94552797165289e-06 -4.47444185123699e-06 4.40897101705632e-07 6.56428878338361e-06 -1.93613957366529e-06 5.05055846853506e-05 -3.37292304387571e-06 -6.49915041391441e-07 5.75297564259632e-07 -1.98727426456907e-05 2.94552797165289e-06 -3.37292304387571e-06 1.11579564054097e-05 -7.84875864622554e-07 4.77481039396599e-06 4.03141328045849e-07 -4.47444185123699e-06 -6.49915041391441e-07 -7.84875864622554e-07 6.94194316315546e-05 -1.72428683774902e-06 -2.8008745590478e-05 4.40897101705632e-07 5.75297564259632e-07 4.77481039396599e-06 -1.72428683774902e-06 9.57880322671027e-06 8.87881094479841e-06 6.56428878338361e-06 -1.98727426456907e-05 4.03141328045849e-07 -2.8008745590478e-05 8.87881094479841e-06 0.000333143377974828 3473 3464 0 500 670 3473 3464 0 431 758 0 0 0 0 0 0 0 0 3326 0 0 0 0 0 3012 +1183 1185 0.998656940606305 0.0449143804533438 0.0258266027062622 0.303823346872373 -0.0441528603385841 0.998593951909133 -0.0293367369423021 0.00504906743266814 -0.0271079306251197 0.0281570175798617 0.999235879288885 0.00771011429393752 3.73864828917997e-05 7.0627919774383e-06 -1.70905444170889e-06 1.2228333708641e-05 -2.55186689553691e-06 -8.82899677776698e-06 7.0627919774383e-06 5.86565464283832e-05 1.0381342849496e-06 2.74409202480272e-05 -6.77948584700678e-07 -5.27733344893322e-05 -1.70905444170889e-06 1.0381342849496e-06 1.16848435187923e-05 -4.98640640779425e-07 5.11459659450215e-06 -1.21336595831678e-07 1.2228333708641e-05 2.74409202480272e-05 -4.98640640779425e-07 0.000152502335210405 7.53334036045945e-07 -3.04093492121517e-05 -2.55186689553691e-06 -6.77948584700678e-07 5.11459659450215e-06 7.53334036045945e-07 9.51523332977348e-06 -9.99449348454108e-08 -8.82899677776698e-06 -5.27733344893322e-05 -1.21336595831678e-07 -3.04093492121517e-05 -9.99449348454108e-08 7.59274857227237e-05 3133 3126 0 530 234 3133 3126 0 452 291 0 0 0 0 0 0 0 0 3319 0 0 0 0 0 3519 +1184 1187 0.996351708426347 0.0849600476769109 -0.0080661895983582 0.438156136261977 -0.0852385669871917 0.995342225127691 -0.0450360031066953 0.00283574052514144 0.00420235813200935 0.0455592490784612 0.99895279919 0.00950435399830837 5.91459074355505e-05 1.74924482697228e-05 -6.47959926534537e-07 -1.28315465866933e-05 -3.45806248791081e-06 -4.94728052249689e-06 1.74924482697228e-05 7.54999076422588e-05 -5.75305544085797e-06 1.63924471608217e-05 1.49752427831338e-06 -1.90666467104379e-05 -6.47959926534537e-07 -5.75305544085797e-06 1.4426241039647e-05 -4.92363089838119e-06 4.77342094015656e-06 3.87466607804814e-06 -1.28315465866933e-05 1.63924471608217e-05 -4.92363089838119e-06 0.000120428368229525 2.60477426809269e-07 -4.34237375922077e-05 -3.45806248791081e-06 1.49752427831338e-06 4.77342094015656e-06 2.60477426809269e-07 1.19047624491735e-05 1.1027474394107e-05 -4.94728052249689e-06 -1.90666467104379e-05 3.87466607804814e-06 -4.34237375922077e-05 1.1027474394107e-05 0.00028773910135702 3249 3256 0 861 340 3249 3256 0 781 405 0 0 0 0 0 0 0 0 2975 0 0 0 0 0 3425 +1184 1188 0.993074137500674 0.114366993903266 0.0269062842626669 0.597322749269379 -0.11390996351282 0.993328885601821 -0.0179511905330246 -0.00399439981067741 -0.0287798130605675 0.0147619691970677 0.999476766426125 0.0237433891853374 3.56220726533389e-05 -1.63720576592561e-06 -1.76612946381664e-06 -4.33709488983589e-06 -4.09213592333538e-06 -2.58594514024899e-06 -1.63720576592561e-06 4.34037826798021e-05 1.25093173892969e-07 1.24621215293302e-05 1.06518755390187e-06 -2.37165345419114e-05 -1.76612946381664e-06 1.25093173892969e-07 1.30765222259468e-05 1.68037345085714e-06 3.40726375531584e-06 -7.74009476543425e-07 -4.33709488983589e-06 1.24621215293302e-05 1.68037345085714e-06 6.72050926540189e-05 -2.93943450216228e-06 2.68132957889333e-06 -4.09213592333538e-06 1.06518755390187e-06 3.40726375531584e-06 -2.93943450216228e-06 1.16794757376912e-05 1.24144640031421e-06 -2.58594514024899e-06 -2.37165345419114e-05 -7.74009476543425e-07 2.68132957889333e-06 1.24144640031421e-06 0.000161081916787526 3243 3257 0 1274 559 3243 3257 0 1180 633 0 0 0 0 0 0 0 0 2536 0 0 0 0 0 3212 +1183 1187 0.995039461855284 0.0994802768576598 -0.000379298128820126 0.599457777369422 -0.0993641775055407 0.993679020831895 -0.052237570648093 -0.000662330685415614 -0.0048197073971945 0.0520161328329054 0.998634614033439 -0.0389784212316061 3.49230162319654e-05 6.51265603473032e-06 -3.99975977599463e-07 8.27661502261678e-07 -3.29823779291917e-06 -1.05706750911297e-05 6.51265603473032e-06 5.49163043439328e-05 -1.65891978934823e-06 7.34771560883242e-06 1.88935259513575e-06 2.61225954090865e-05 -3.99975977599463e-07 -1.65891978934823e-06 1.34285474362788e-05 -3.87455339597999e-06 3.1515661968164e-06 -2.24585643956804e-06 8.27661502261678e-07 7.34771560883242e-06 -3.87455339597999e-06 0.000101755872801547 1.08736976671986e-06 2.22503088892492e-07 -3.29823779291917e-06 1.88935259513575e-06 3.1515661968164e-06 1.08736976671986e-06 1.19369784393486e-05 1.59573780534577e-05 -1.05706750911297e-05 2.61225954090865e-05 -2.24585643956804e-06 2.22503088892492e-07 1.59573780534577e-05 0.000317756210086096 3301 3308 0 1249 598 3301 3308 0 1147 670 0 0 0 0 0 0 0 0 2576 0 0 0 0 0 3154 +1184 1186 0.99825957398458 0.0560650257243495 -0.0182903209007892 0.299923828431242 -0.0567978054154444 0.997486502018226 -0.0423637532736709 0.00484980030151078 0.0158692232990507 0.0433288723828716 0.998934820981786 -0.023495478814804 4.11712323451553e-05 -5.69937800333372e-06 -8.03975082518262e-06 2.11825014642398e-07 -1.10654255900661e-06 -5.0393270680361e-06 -5.69937800333372e-06 2.62663578248497e-05 2.78228472265203e-07 6.84901681719683e-07 5.45966467022856e-08 -1.00181130737546e-05 -8.03975082518262e-06 2.78228472265203e-07 1.04050896766771e-05 -1.29056597063932e-06 4.83736664965578e-06 -2.17550404313723e-06 2.11825014642398e-07 6.84901681719683e-07 -1.29056597063932e-06 7.17555722552028e-05 -8.16881399241026e-07 -6.5001548632038e-06 -1.10654255900661e-06 5.45966467022856e-08 4.83736664965578e-06 -8.16881399241026e-07 9.73555890275289e-06 1.93024689366156e-07 -5.0393270680361e-06 -1.00181130737546e-05 -2.17550404313723e-06 -6.5001548632038e-06 1.93024689366156e-07 7.02233645317061e-05 3497 3496 0 541 193 3497 3496 0 472 249 0 0 0 0 0 0 0 0 3290 0 0 0 0 0 3578 +1186 1189 0.997076513689657 0.0547896712489644 0.0532589689433583 0.426046254098358 -0.056809603415858 0.99769241668845 0.0371821279930674 0.0202527750382694 -0.0510988728663572 -0.0400990474548999 0.997888256061267 0.0128425198399999 4.75840570601265e-05 -1.72210516977853e-05 -2.24270031186443e-06 -1.61613508317101e-05 -6.1740794852756e-07 -1.79809789346987e-05 -1.72210516977853e-05 0.00013295670807894 3.9803895541617e-06 7.06128201304588e-05 3.1772149017516e-06 -6.64167541241759e-05 -2.24270031186443e-06 3.9803895541617e-06 1.09149762020697e-05 3.14810527316576e-06 3.19949338775079e-06 -7.46105738437423e-06 -1.61613508317101e-05 7.06128201304588e-05 3.14810527316576e-06 0.000139822567744931 1.8597794838459e-06 -7.25561853054463e-05 -6.1740794852756e-07 3.1772149017516e-06 3.19949338775079e-06 1.8597794838459e-06 1.10326767858564e-05 -1.64589476605055e-06 -1.79809789346987e-05 -6.64167541241759e-05 -7.46105738437423e-06 -7.25561853054463e-05 -1.64589476605055e-06 0.000380448447294514 3383 3398 0 714 443 3383 3398 0 640 509 0 0 0 0 0 0 0 0 3079 0 0 0 0 0 3329 +1187 1190 0.998809398629383 0.0156928282794832 0.0461900460077886 0.424150702195734 -0.0165691135787981 0.99968877346246 0.0186499514298478 0.0475415238959104 -0.0458829999544915 -0.0193930748906265 0.99875855889272 0.0115315695226997 3.8484119423512e-05 -1.13542752077626e-05 -2.55908556750517e-06 -1.05634399660219e-05 -2.23475471719443e-06 1.5377326418538e-05 -1.13542752077626e-05 5.7198413379706e-05 2.3037731842618e-06 4.61494990608398e-05 2.91383532792625e-06 -1.01243838187691e-05 -2.55908556750517e-06 2.3037731842618e-06 1.11405121903143e-05 -4.77854257671798e-07 3.41967881131243e-06 -3.16804816005242e-06 -1.05634399660219e-05 4.61494990608398e-05 -4.77854257671798e-07 0.000136438895436918 2.94433332252562e-06 -3.62135721079831e-06 -2.23475471719443e-06 2.91383532792625e-06 3.41967881131243e-06 2.94433332252562e-06 1.04466393648728e-05 6.18189931794256e-06 1.5377326418538e-05 -1.01243838187691e-05 -3.16804816005242e-06 -3.62135721079831e-06 6.18189931794256e-06 0.00020992939376198 3241 3245 0 557 577 3241 3245 0 493 652 0 0 0 0 0 0 0 0 3245 0 0 0 0 0 3189 +1187 1191 0.999799010906264 -0.00663852305030746 0.0189173941801327 0.583747609494272 0.00609629172302979 0.999572974630688 0.0285780267895858 0.0729556000360936 -0.0190990318624715 -0.028456956964319 0.999412541737519 0.0214573220043861 4.17441212439024e-05 -1.38767873686861e-05 -1.94730934703459e-06 -6.34584764800244e-06 -1.22408273962837e-06 1.15317713684998e-05 -1.38767873686861e-05 5.75645353971028e-05 -2.27251618722408e-06 1.22959655841068e-05 1.14696714513867e-06 -1.2342237167028e-05 -1.94730934703459e-06 -2.27251618722408e-06 1.03546342546057e-05 -1.48864178534253e-06 4.70086995226559e-06 2.49571385493741e-06 -6.34584764800244e-06 1.22959655841068e-05 -1.48864178534253e-06 6.16239832109023e-05 -1.65140069555772e-06 -1.87286586107673e-05 -1.22408273962837e-06 1.14696714513867e-06 4.70086995226559e-06 -1.65140069555772e-06 1.01674323760219e-05 4.11632922193198e-06 1.15317713684998e-05 -1.2342237167028e-05 2.49571385493741e-06 -1.87286586107673e-05 4.11632922193198e-06 0.000274988751262002 3363 3362 0 757 961 3363 3362 0 691 1042 0 0 0 0 0 0 0 0 3028 0 0 0 0 0 2780 +1188 1191 0.999314350839585 -0.0366409603234226 -0.00531678781191368 0.431741206479049 0.0366364435097018 0.999328213821477 -0.000944493163604821 0.0783359150462877 0.00534782320388089 0.00074905737633593 0.999985419743722 0.0492263117764972 3.29146101454849e-05 -5.88830438287414e-06 -6.75604143089606e-06 -4.40589388446916e-07 -2.24812044254709e-06 1.93238386931435e-06 -5.88830438287414e-06 3.04193835080694e-05 -5.87373363248068e-07 2.77036947750865e-06 -4.86181278671798e-07 -9.76666413475026e-06 -6.75604143089606e-06 -5.87373363248068e-07 1.07508726587374e-05 -1.47272573231333e-06 4.68782807907592e-06 -9.11684105107058e-07 -4.40589388446916e-07 2.77036947750865e-06 -1.47272573231333e-06 7.63028183605147e-05 -7.79416233345979e-07 -2.19734915432987e-06 -2.24812044254709e-06 -4.86181278671798e-07 4.68782807907592e-06 -7.79416233345979e-07 1.0114401111369e-05 2.14532141660052e-06 1.93238386931435e-06 -9.76666413475026e-06 -9.11684105107058e-07 -2.19734915432987e-06 2.14532141660052e-06 0.000110857416499664 3569 3568 0 386 764 3569 3568 0 319 846 0 0 0 0 0 0 0 0 3408 0 0 0 0 0 2979 +1186 1188 0.997881165230256 0.0589684789482696 0.0274936096072014 0.287041005568109 -0.0597682736748176 0.997784022735185 0.0292369190634659 0.00623386634859773 -0.0257086277470779 -0.0308182164461059 0.999194327443087 -0.0361094816742187 4.43336482681319e-05 -1.04338239467056e-05 -1.74991645770751e-07 1.78886262136752e-06 -1.53306204276005e-06 -1.35746257935643e-05 -1.04338239467056e-05 5.88875855308588e-05 -1.25624405238332e-06 1.02775489707209e-05 2.14784659984635e-06 0.000147886771582366 -1.74991645770751e-07 -1.25624405238332e-06 1.20108076087641e-05 -3.14720490783567e-06 3.72032031076247e-06 -1.89628312627871e-06 1.78886262136752e-06 1.02775489707209e-05 -3.14720490783567e-06 6.44683457476866e-05 1.2286296773756e-06 4.61512968918592e-05 -1.53306204276005e-06 2.14784659984635e-06 3.72032031076247e-06 1.2286296773756e-06 1.16335183631274e-05 2.26541201584394e-05 -1.35746257935643e-05 0.000147886771582366 -1.89628312627871e-06 4.61512968918592e-05 2.26541201584394e-05 0.00107919560596457 3440 3454 0 512 195 3440 3454 0 451 241 0 0 0 0 0 0 0 0 3312 0 0 0 0 0 3596 +1185 1189 0.996194689966467 0.0809662750578881 0.0322583630376021 0.573625781491267 -0.0813539598961635 0.996625773540581 0.0108903959455807 0.0134984477462694 -0.0312677612218839 -0.0134733001854968 0.999420230578851 0.00579457821041622 4.4587360485475e-05 -1.57077553892597e-05 -1.15547908797755e-06 -1.67248922879757e-05 -2.28073921225844e-06 -2.55473275585413e-06 -1.57077553892597e-05 5.62567179236065e-05 -3.44917646442169e-06 3.37704071644841e-05 1.46654557452424e-06 -2.52187280540977e-05 -1.15547908797755e-06 -3.44917646442169e-06 1.07783333755528e-05 -3.45114194791406e-06 3.0655672754603e-06 3.85261441245672e-06 -1.67248922879757e-05 3.37704071644841e-05 -3.45114194791406e-06 0.000131322733288809 5.23813746128123e-06 -9.00485420693771e-06 -2.28073921225844e-06 1.46654557452424e-06 3.0655672754603e-06 5.23813746128123e-06 1.15926344611298e-05 6.5761451250421e-07 -2.55473275585413e-06 -2.52187280540977e-05 3.85261441245672e-06 -9.00485420693771e-06 6.5761451250421e-07 0.000187237834046199 3456 3471 0 1083 626 3456 3471 0 992 707 0 0 0 0 0 0 0 0 2696 0 0 0 0 0 3139 +1190 1194 0.996456663332538 -0.0789890173385972 -0.02889382702356 0.570080417280907 0.0795171444520738 0.996677965246026 0.0176084448838796 0.126435350264573 0.027406966967774 -0.0198436068526712 0.999427380767959 0.0851937542646868 3.60962402734489e-05 -1.77784991846972e-05 -1.93937346018619e-06 -3.55301375293655e-06 -1.54220914230048e-06 6.3627988423131e-06 -1.77784991846972e-05 8.47086699667934e-05 1.13084557364551e-06 1.81141778804634e-05 -7.20541013791952e-07 1.80611368184914e-05 -1.93937346018619e-06 1.13084557364551e-06 1.12030372162511e-05 -2.67539373249512e-06 3.84911933148107e-06 2.01598285257989e-06 -3.55301375293655e-06 1.81141778804634e-05 -2.67539373249512e-06 7.57894733919325e-05 -2.07266260193276e-06 6.43430529170445e-06 -1.54220914230048e-06 -7.20541013791952e-07 3.84911933148107e-06 -2.07266260193276e-06 1.02709472446892e-05 3.35614347889179e-06 6.3627988423131e-06 1.80611368184914e-05 2.01598285257989e-06 6.43430529170445e-06 3.35614347889179e-06 0.000343579030825439 3411 3381 0 493 1157 3411 3381 0 409 1242 0 0 0 0 0 0 0 0 3281 0 0 0 0 0 2578 +1191 1195 0.999114188531949 -0.0408549524864342 0.0100851936756711 0.568023391901912 0.0408240716284903 0.999161067061586 0.00324919128780185 0.107679372384636 -0.0102094784301888 -0.00283459444789443 0.999943864236638 0.0278654047367771 5.12050482673162e-05 -1.6633739911034e-05 6.14371889261202e-07 -5.80290986453368e-06 1.77722461347759e-06 -1.38286640438377e-05 -1.6633739911034e-05 5.22253307695949e-05 2.50802478803629e-07 1.6901694101287e-05 1.88191679012689e-06 0.000123528143347668 6.14371889261202e-07 2.50802478803629e-07 1.23831940199993e-05 -1.45714117488744e-07 4.78544661743932e-06 -3.18546377328221e-06 -5.80290986453368e-06 1.6901694101287e-05 -1.45714117488744e-07 6.25011783214202e-05 -1.04183554818159e-06 -1.38723060236131e-05 1.77722461347759e-06 1.88191679012689e-06 4.78544661743932e-06 -1.04183554818159e-06 1.05256999631776e-05 1.0696598934579e-05 -1.38286640438377e-05 0.000123528143347668 -3.18546377328221e-06 -1.38723060236131e-05 1.0696598934579e-05 0.000816539289500955 3442 3413 0 639 1014 3442 3413 0 543 1094 0 0 0 0 0 0 0 0 3133 0 0 0 0 0 2717 +1192 1195 0.998309641526165 -0.0268302043927343 0.051555792770003 0.420714860494246 0.0268577190998841 0.999639253727642 0.000159159024744376 0.0724889394593864 -0.0515414644791075 0.00122578101125036 0.998670103137298 0.0430507819645432 4.31296418364865e-05 -1.31154148556055e-05 7.81495636680271e-07 -8.73611384003188e-06 1.78963114081648e-07 -2.10785246376304e-05 -1.31154148556055e-05 4.94165291770537e-05 -4.08757005538798e-06 3.99840809700031e-06 1.20110605982299e-06 0.000111712433747465 7.81495636680271e-07 -4.08757005538798e-06 1.16468657984072e-05 -1.21825653983979e-06 4.18870759077873e-06 -1.07773251662164e-06 -8.73611384003188e-06 3.99840809700031e-06 -1.21825653983979e-06 5.37534842041943e-05 -1.12192428586521e-06 -4.99103233904233e-05 1.78963114081648e-07 1.20110605982299e-06 4.18870759077873e-06 -1.12192428586521e-06 9.81129126401888e-06 6.01256921275893e-06 -2.10785246376304e-05 0.000111712433747465 -1.07773251662164e-06 -4.99103233904233e-05 6.01256921275893e-06 0.000728409751252995 3365 3336 0 455 666 3365 3336 0 369 729 0 0 0 0 0 0 0 0 3328 0 0 0 0 0 3087 +1193 1195 0.999509026130889 -0.00140612438200791 0.031300630937811 0.285687865306918 0.00132200974235641 0.999995459916401 0.00270784726786695 0.0357617396967343 -0.0313042964003959 -0.00266513804657519 0.999506347186484 0.0294123654622337 2.86312454000271e-05 -5.12895265891364e-06 -3.48652348745371e-06 -2.72122932181194e-06 -2.80566770394723e-06 -4.60454207578183e-07 -5.12895265891364e-06 2.78252639107196e-05 1.27463052773336e-06 1.26566840915335e-05 1.6604678038916e-07 -1.81728597828779e-05 -3.48652348745371e-06 1.27463052773336e-06 9.92896046424358e-06 -1.23581018660954e-06 3.67051108759389e-06 -1.24903293642674e-06 -2.72122932181194e-06 1.26566840915335e-05 -1.23581018660954e-06 4.25952362819384e-05 -3.93599826631315e-07 -1.25429232895417e-05 -2.80566770394723e-06 1.6604678038916e-07 3.67051108759389e-06 -3.93599826631315e-07 9.30938296508707e-06 -1.42626623522312e-06 -4.60454207578183e-07 -1.81728597828779e-05 -1.24903293642674e-06 -1.25429232895417e-05 -1.42626623522312e-06 6.22042428729784e-05 3420 3391 0 344 328 3420 3391 0 254 383 0 0 0 0 0 0 0 0 3437 0 0 0 0 0 3433 +1191 1193 0.999173899862152 -0.0392695428100855 -0.0104604417566707 0.283147515554857 0.0392865604519232 0.999226967138023 0.00142629309993015 0.0618531424466437 0.0103963456134946 -0.00183606961643095 0.999944270870256 0.0244110776239879 3.29864738242486e-05 -4.09355360935696e-06 -9.81226985068497e-07 -4.3651097696315e-06 -2.08685174874938e-06 1.95852989821185e-06 -4.09355360935696e-06 3.68504419286546e-05 -3.00556523138529e-06 2.4680120368799e-06 -7.98100245794509e-07 -1.37320132566668e-05 -9.81226985068497e-07 -3.00556523138529e-06 1.03529298080561e-05 4.23774884698501e-07 4.78631427642283e-06 1.4902730236012e-06 -4.3651097696315e-06 2.4680120368799e-06 4.23774884698501e-07 5.5931202804438e-05 2.7033839609781e-07 -9.44326500140751e-06 -2.08685174874938e-06 -7.98100245794509e-07 4.78631427642283e-06 2.7033839609781e-07 9.42475362496153e-06 5.80604926033321e-07 1.95852989821185e-06 -1.37320132566668e-05 1.4902730236012e-06 -9.44326500140751e-06 5.80604926033321e-07 0.000113085699271284 3536 3512 0 173 475 3536 3512 0 109 544 0 0 0 0 0 0 0 0 3598 0 0 0 0 0 3306 +1193 1197 0.999413174564503 0.0316145653281307 -0.0131842999819987 0.572453075139303 -0.031621749599733 0.999499850700819 -0.000336751084325908 0.048865073942478 0.0131670596244478 0.000753464102902721 0.999913026634163 0.0454445048209645 4.94964311021551e-05 1.11056064665248e-05 -8.20168064969694e-06 9.65464502022984e-06 -8.9817786930827e-07 -2.82107322722348e-05 1.11056064665248e-05 0.000640180087546312 -2.17751289892112e-06 0.000279887250964074 2.73062925871792e-06 -0.0013137508091951 -8.20168064969694e-06 -2.17751289892112e-06 1.26428491635733e-05 -6.45178075470804e-07 4.7335477608903e-06 -3.68483957861e-06 9.65464502022984e-06 0.000279887250964074 -6.45178075470804e-07 0.000202531995561207 -1.04778925197739e-06 -0.000759022922209137 -8.9817786930827e-07 2.73062925871792e-06 4.7335477608903e-06 -1.04778925197739e-06 1.04560720077967e-05 2.03065282846361e-07 -2.82107322722348e-05 -0.0013137508091951 -3.68483957861e-06 -0.000759022922209137 2.03065282846361e-07 0.004344756834313 3283 3260 0 1014 727 3283 3260 0 893 795 0 0 0 0 0 0 0 0 2778 0 0 0 0 0 3044 +1192 1194 0.998484520023439 -0.0452930877013157 0.0312601900193014 0.281035914096596 0.0453662867895177 0.998969080405126 -0.00163597599866147 0.0549570925200705 -0.0311538648724864 0.00305165545530381 0.99950994197281 -0.00654397877561515 3.41137312802534e-05 -7.34599688974175e-06 -3.47505333110341e-06 3.13408740488347e-06 -2.19369783286799e-07 5.93117183700156e-06 -7.34599688974175e-06 3.61880686650336e-05 4.79904588613442e-07 1.85436325377536e-05 1.51180343024379e-07 -5.61471521094359e-06 -3.47505333110341e-06 4.79904588613442e-07 1.0477656894271e-05 -1.61188072056466e-06 4.73862997388953e-06 -1.19015432440577e-06 3.13408740488347e-06 1.85436325377536e-05 -1.61188072056466e-06 7.66082404769947e-05 -2.99843936030479e-07 -5.29785581472844e-06 -2.19369783286799e-07 1.51180343024379e-07 4.73862997388953e-06 -2.99843936030479e-07 9.98414571796081e-06 8.7659488679156e-07 5.93117183700156e-06 -5.61471521094359e-06 -1.19015432440577e-06 -5.29785581472844e-06 8.7659488679156e-07 0.000230173876993208 3472 3442 0 184 478 3472 3442 0 113 533 0 0 0 0 0 0 0 0 3596 0 0 0 0 0 3304 +1196 1199 0.998364429537488 0.0398662848902638 0.0409773737974338 0.433082851916625 -0.0382487076081886 0.998486112841013 -0.0395287089334641 0.00635549380742354 -0.0424912014491187 0.0378967253557818 0.998377852321815 0.0231686570888071 5.36668096107676e-05 1.96361764115046e-06 4.62665645114916e-06 -1.95048302523266e-06 1.34725428213672e-06 6.56138815992051e-06 1.96361764115046e-06 4.69208476209467e-05 2.09066398489779e-06 9.61551399644528e-06 -1.01985061213503e-06 -3.21077308635831e-05 4.62665645114916e-06 2.09066398489779e-06 1.1243822529104e-05 -2.68154990524765e-06 4.79324131577075e-06 1.34375033428441e-07 -1.95048302523266e-06 9.61551399644528e-06 -2.68154990524765e-06 5.53856440229469e-05 -4.62775776484856e-07 -1.46942973155393e-05 1.34725428213672e-06 -1.01985061213503e-06 4.79324131577075e-06 -4.62775776484856e-07 1.00600706767989e-05 4.28309521226588e-06 6.56138815992051e-06 -3.21077308635831e-05 1.34375033428441e-07 -1.46942973155393e-05 4.28309521226588e-06 0.000166709899230499 3495 3481 0 787 417 3495 3481 0 682 477 0 0 0 0 0 0 0 0 2993 0 0 0 0 0 3367 +1194 1198 0.997342878168654 0.0727873512710608 -0.00303065359444465 0.578397588183177 -0.0728165816756911 0.997284432489588 -0.0110229826720212 0.0143222985061754 0.00222008993820504 0.0112143750991074 0.999934652360744 0.00345196591026234 6.05580693532427e-05 1.10692846310953e-05 -3.02094634796384e-06 3.33421312553027e-06 8.35319124246243e-08 -2.79555600545681e-06 1.10692846310953e-05 0.000196620890224718 -3.42509112736439e-06 8.93990403444106e-05 4.59262028846501e-06 -0.0001765527336439 -3.02094634796384e-06 -3.42509112736439e-06 1.21265083521656e-05 -5.32023343130721e-06 4.76071400249862e-06 1.9277334448463e-06 3.33421312553027e-06 8.93990403444106e-05 -5.32023343130721e-06 0.000117972412920488 3.62472770552908e-06 -0.000103353542112003 8.35319124246243e-08 4.59262028846501e-06 4.76071400249862e-06 3.62472770552908e-06 1.07690728704404e-05 -1.46975977679852e-06 -2.79555600545681e-06 -0.0001765527336439 1.9277334448463e-06 -0.000103353542112003 -1.46975977679852e-06 0.000369451916303964 3429 3410 0 1216 578 3429 3410 0 1094 636 0 0 0 0 0 0 0 0 2567 0 0 0 0 0 3213 +1197 1200 0.999088197786398 0.0131406162770387 0.0406213890430499 0.426714318067166 -0.0111683201347391 0.99876537708515 -0.0484044436113678 0.00686990313484968 -0.0412073011649048 0.0479066356553842 0.998001459212805 -0.0157996968775533 4.00780841237227e-05 -2.11354067805612e-05 -2.18379127943052e-06 -8.72978164622268e-06 -1.52622678379726e-07 1.109890519036e-05 -2.11354067805612e-05 4.77327871055934e-05 4.39004299699519e-07 8.71744556512674e-06 -1.91212844097192e-06 -2.5288217289873e-05 -2.18379127943052e-06 4.39004299699519e-07 9.40356070308097e-06 -2.53151911373091e-06 3.35264104694804e-06 3.49087616648468e-07 -8.72978164622268e-06 8.71744556512674e-06 -2.53151911373091e-06 6.49742356649078e-05 -1.45285289813023e-06 -1.45546536048057e-05 -1.52622678379726e-07 -1.91212844097192e-06 3.35264104694804e-06 -1.45285289813023e-06 9.70039310826937e-06 2.95913038682726e-06 1.109890519036e-05 -2.5288217289873e-05 3.49087616648468e-07 -1.45546536048057e-05 2.95913038682726e-06 0.000116364450723776 3160 3142 0 703 490 3160 3142 0 604 540 0 0 0 0 0 0 0 0 3072 0 0 0 0 0 3290 +1195 1197 0.998871572806013 0.0324444453032719 -0.0346834111500767 0.285053599354172 -0.0325960614914724 0.999461326890015 -0.00381481670523527 0.013077918316912 0.0345409585171926 0.00494105456490693 0.999391068683576 -0.00984108003276384 3.35518891623094e-05 -8.49073016587149e-06 -4.17502489027831e-06 -1.15491872266622e-05 1.40467727455602e-07 -2.15065227242781e-05 -8.49073016587149e-06 0.000109061144478806 -2.18129278984228e-06 -8.25198718132601e-06 1.56694742892247e-06 0.000299116511909232 -4.17502489027831e-06 -2.18129278984228e-06 1.01107647526019e-05 9.8987536682278e-07 2.5180694705685e-06 -9.06889073475395e-06 -1.15491872266622e-05 -8.25198718132601e-06 9.8987536682278e-07 8.4683353386292e-05 -1.40308987865828e-06 -8.49714755133579e-05 1.40467727455602e-07 1.56694742892247e-06 2.5180694705685e-06 -1.40308987865828e-06 1.03015818572847e-05 1.06596565952132e-05 -2.15065227242781e-05 0.000299116511909232 -9.06889073475395e-06 -8.49714755133579e-05 1.06596565952132e-05 0.00207358219929608 3638 3615 0 471 224 3638 3615 0 385 266 0 0 0 0 0 0 0 0 3333 0 0 0 0 0 3584 +1195 1199 0.998414214854155 0.0543199232081704 0.0147784139818555 0.579324515733729 -0.0538686413377214 0.998115425949009 -0.0293898955945158 0.00787445009590846 -0.0163470198381407 0.0285471964523151 0.999458769793494 0.0487430001855021 5.23593761368292e-05 -3.40819029779223e-06 -6.44953661779427e-06 8.99083094320004e-06 1.88738668095315e-07 -1.0823084007835e-05 -3.40819029779223e-06 5.43873519630622e-05 1.38178758328897e-06 1.18746208641156e-05 7.2081560301575e-07 -1.6660691590808e-05 -6.44953661779427e-06 1.38178758328897e-06 1.12982521437649e-05 -3.53188784328417e-06 4.52625450249319e-06 -2.80667337388707e-06 8.99083094320004e-06 1.18746208641156e-05 -3.53188784328417e-06 8.43482580627384e-05 -5.89542346368423e-07 -3.41405918506869e-05 1.88738668095315e-07 7.2081560301575e-07 4.52625450249319e-06 -5.89542346368423e-07 9.89393055123175e-06 5.21196926119666e-06 -1.0823084007835e-05 -1.6660691590808e-05 -2.80667337388707e-06 -3.41405918506869e-05 5.21196926119666e-06 0.000194128062436943 3580 3566 0 1172 621 3580 3566 0 1044 679 0 0 0 0 0 0 0 0 2605 0 0 0 0 0 3172 +1198 1202 0.999064887780198 -0.0347832970318456 0.0256801918282442 0.58479726175439 0.0345540215410292 0.999359385988658 0.00931864967224672 0.0207435988428591 -0.0259878740970306 -0.00842258178745523 0.999626775609753 0.0222125752928177 5.47341755608446e-05 -2.87843858907191e-05 3.62891837233972e-06 -4.77746708645623e-06 7.59978624664147e-08 3.81205673607192e-05 -2.87843858907191e-05 0.000153488593453254 -1.320557197708e-06 5.4989068420822e-05 -1.81188583642421e-06 -0.000104616252817972 3.62891837233972e-06 -1.320557197708e-06 1.17909632791978e-05 -1.77985373948025e-06 4.07245179730219e-06 -9.56488132135943e-07 -4.77746708645623e-06 5.4989068420822e-05 -1.77985373948025e-06 0.00011024496964575 8.21659835395286e-07 -9.91189779873186e-05 7.59978624664147e-08 -1.81188583642421e-06 4.07245179730219e-06 8.21659835395286e-07 1.04553741552126e-05 5.39277589501198e-06 3.81205673607192e-05 -0.000104616252817972 -9.56488132135943e-07 -9.91189779873186e-05 5.39277589501198e-06 0.000680525101125904 3405 3385 0 852 896 3405 3385 0 745 958 0 0 0 0 0 0 0 0 2907 0 0 0 0 0 2854 +1200 1202 0.99934558878091 -0.0223650676890103 -0.0284288221951274 0.289981935450191 0.0236487375213772 0.9986775409592 0.0456498236286915 0.00591489905418972 0.0273702648467491 -0.0462922556260939 0.998552900787568 -0.00304527540676314 5.82372391750239e-05 -1.07047452470959e-06 7.49073472032306e-06 3.3361977103865e-06 -1.05587349305738e-06 2.10881700125778e-05 -1.07047452470959e-06 5.23264517883889e-05 -1.5357612073063e-06 1.48780872408979e-05 1.3051512971068e-06 -3.30188282542507e-06 7.49073472032306e-06 -1.5357612073063e-06 1.17817775052617e-05 -1.56589273668021e-06 2.83417928023446e-06 3.19538445381797e-06 3.3361977103865e-06 1.48780872408979e-05 -1.56589273668021e-06 6.49726476044702e-05 5.59621385577996e-07 -2.6356655245292e-05 -1.05587349305738e-06 1.3051512971068e-06 2.83417928023446e-06 5.59621385577996e-07 1.01021671314234e-05 2.88066709318827e-07 2.10881700125778e-05 -3.30188282542507e-06 3.19538445381797e-06 -2.6356655245292e-05 2.88066709318827e-07 0.000221847181619123 3633 3613 0 325 359 3633 3613 0 238 416 0 0 0 0 0 0 0 0 3457 0 0 0 0 0 3407 +1200 1203 0.997472055348021 -0.0346821224746967 -0.0620213606787616 0.43077369757303 0.0386286423481188 0.99722709680806 0.0636077462429689 0.0146453860515666 0.0596433298042289 -0.0658427503406331 0.996045885206824 0.0010926693231223 4.17505633966137e-05 -1.27879681351397e-05 -1.81336933583505e-06 -7.80049112986603e-06 -1.13534300410821e-06 1.90293149938754e-05 -1.27879681351397e-05 7.04628782400549e-05 3.41915429840819e-06 2.70506313962925e-05 9.3091711312824e-07 -2.93512502567203e-05 -1.81336933583505e-06 3.41915429840819e-06 1.06151157760595e-05 -2.04091502588007e-07 4.25085978504397e-06 -2.41723216711194e-06 -7.80049112986603e-06 2.70506313962925e-05 -2.04091502588007e-07 7.15459065902067e-05 2.16266183345196e-07 -3.42306742756047e-05 -1.13534300410821e-06 9.3091711312824e-07 4.25085978504397e-06 2.16266183345196e-07 9.79726096434852e-06 -2.73723954561845e-07 1.90293149938754e-05 -2.93512502567203e-05 -2.41723216711194e-06 -3.42306742756047e-05 -2.73723954561845e-07 0.000240214141594303 3537 3511 0 529 629 3537 3511 0 436 688 0 0 0 0 0 0 0 0 3254 0 0 0 0 0 3137 +1199 1201 0.999620206703128 -0.0145708594506476 0.0233908615844825 0.283595602579551 0.0147268766370163 0.999870350349219 -0.00651165086960945 0.0106147377179266 -0.0232929486178338 0.0068536521212458 0.999705189542041 0.0518693276185818 3.36906508410888e-05 -1.28231432821004e-05 6.19855257230635e-07 -4.91632677063778e-06 -2.32600701305277e-06 1.61347099698064e-05 -1.28231432821004e-05 6.03831429658739e-05 -1.31445875270488e-06 5.60558648883723e-06 -1.06860579511059e-06 -1.86937833228547e-05 6.19855257230635e-07 -1.31445875270488e-06 1.09364280746476e-05 -1.93196823393883e-06 3.92376743628478e-06 1.36354767558796e-06 -4.91632677063778e-06 5.60558648883723e-06 -1.93196823393883e-06 5.64330288751217e-05 -1.40484105370326e-06 -3.1311247815115e-05 -2.32600701305277e-06 -1.06860579511059e-06 3.92376743628478e-06 -1.40484105370326e-06 9.73598709495761e-06 2.7903100738982e-06 1.61347099698064e-05 -1.86937833228547e-05 1.36354767558796e-06 -3.1311247815115e-05 2.7903100738982e-06 0.000109476944693929 3490 3471 0 339 350 3490 3471 0 256 397 0 0 0 0 0 0 0 0 3452 0 0 0 0 0 3428 +1199 1202 0.999466872876168 -0.0326128025408515 0.00154114683469443 0.428788985028095 0.0325544731779771 0.999049361912017 0.028992735974658 0.0158295454262264 -0.00248521613527475 -0.0289271079374224 0.999578434204709 0.053026545823833 3.20259602356419e-05 -9.46210079331146e-06 4.7246392272783e-07 5.85015159829148e-06 -2.19636097438673e-06 8.67233381783891e-06 -9.46210079331146e-06 6.09692687034841e-05 -8.69337922775222e-07 1.5388319208963e-05 8.54254788457486e-07 -5.36531255187571e-05 4.7246392272783e-07 -8.69337922775222e-07 1.02488538324689e-05 9.31532499976985e-08 3.15274749980197e-06 6.45588386813897e-07 5.85015159829148e-06 1.5388319208963e-05 9.31532499976985e-08 7.08252782973046e-05 -9.02674764555905e-07 -4.52902058324346e-05 -2.19636097438673e-06 8.54254788457486e-07 3.15274749980197e-06 -9.02674764555905e-07 9.23993260038468e-06 -1.08437774497156e-06 8.67233381783891e-06 -5.36531255187571e-05 6.45588386813897e-07 -4.52902058324346e-05 -1.08437774497156e-06 0.000165056829087742 3495 3475 0 544 620 3495 3475 0 452 676 0 0 0 0 0 0 0 0 3226 0 0 0 0 0 3137 +1196 1200 0.998514720416111 0.0305670288885172 0.0450999984175579 0.578293869970456 -0.0277882804529369 0.997750651427032 -0.0610036805971819 0.00657823274639921 -0.0468632540675964 0.0596598216713948 0.997118117926022 -0.0167187325686669 4.16610262201703e-05 -4.39017996871063e-06 -2.4098504626069e-07 -7.31129808508322e-06 -4.82002581414882e-07 5.48651683001583e-06 -4.39017996871063e-06 3.27448658399523e-05 8.22504398358907e-07 8.92579493988321e-06 -1.91141697737777e-07 -1.25119232656679e-05 -2.4098504626069e-07 8.22504398358907e-07 9.86350727504027e-06 -3.26690269521408e-06 3.61571806613552e-06 -2.17899290039383e-06 -7.31129808508322e-06 8.92579493988321e-06 -3.26690269521408e-06 5.51391817121114e-05 7.80028783629789e-07 -5.43357777190353e-06 -4.82002581414882e-07 -1.91141697737777e-07 3.61571806613552e-06 7.80028783629789e-07 9.9231840263616e-06 4.34053526225303e-06 5.48651683001583e-06 -1.25119232656679e-05 -2.17899290039383e-06 -5.43357777190353e-06 4.34053526225303e-06 0.000111226171997364 3494 3476 0 1103 683 3494 3476 0 981 756 0 0 0 0 0 0 0 0 2657 0 0 0 0 0 3078 +1200 1204 0.997437732528834 -0.050484061614426 -0.0506885514751574 0.568652583749375 0.0535700463550495 0.99666901049478 0.0614909233372974 0.030439667185683 0.0474153968796708 -0.0640487551968528 0.996819711430546 0.0186964559353997 4.07079604310225e-05 -1.0837905081128e-05 -2.55317850434132e-06 2.59307497098175e-07 1.15376708822003e-07 2.30921722346075e-05 -1.0837905081128e-05 4.98807075296559e-05 2.54256817870806e-06 1.56940244320378e-05 9.87284754110555e-08 -2.35206490776464e-06 -2.55317850434132e-06 2.54256817870806e-06 9.95574677128616e-06 -5.47849331745018e-07 3.74937589442588e-06 -1.72029136931819e-06 2.59307497098175e-07 1.56940244320378e-05 -5.47849331745018e-07 6.65949788103716e-05 1.28684586814626e-07 -2.06004348547344e-05 1.15376708822003e-07 9.87284754110555e-08 3.74937589442588e-06 1.28684586814626e-07 9.94504207924937e-06 2.77779505531688e-07 2.30921722346075e-05 -2.35206490776464e-06 -1.72029136931819e-06 -2.06004348547344e-05 2.77779505531688e-07 0.000190491791116346 3602 3575 0 762 920 3602 3575 0 651 983 0 0 0 0 0 0 0 0 2995 0 0 0 0 0 2837 +1199 1203 0.998503509871673 -0.0453879010270775 -0.0305070354886625 0.56824740460148 0.0466762768605964 0.997986816648883 0.0429376172308406 0.0257393204309428 0.0284967709115129 -0.0442973163451856 0.998611877464028 0.0467968079983667 4.10771517376207e-05 -1.87208302080424e-05 8.31190973803632e-07 -7.77262430921249e-06 1.01315887612444e-07 1.4641622359702e-05 -1.87208302080424e-05 6.51794261094863e-05 -8.78217845605051e-07 2.32959138662189e-05 5.09713893999387e-07 2.83153980400648e-05 8.31190973803632e-07 -8.78217845605051e-07 9.15123627522287e-06 -1.68795353403573e-06 4.21290246209618e-06 -1.93581616716539e-06 -7.77262430921249e-06 2.32959138662189e-05 -1.68795353403573e-06 7.90616272978768e-05 5.77062824224636e-07 -8.27129312680365e-06 1.01315887612444e-07 5.09713893999387e-07 4.21290246209618e-06 5.77062824224636e-07 8.92713783026411e-06 -2.45397835114852e-06 1.4641622359702e-05 2.83153980400648e-05 -1.93581616716539e-06 -8.27129312680365e-06 -2.45397835114852e-06 0.000437748725529703 3295 3269 0 775 908 3295 3269 0 676 974 0 0 0 0 0 0 0 0 2992 0 0 0 0 0 2846 +1201 1205 0.998921457598909 -0.0458679135467832 -0.0072149882422355 0.564656236791616 0.0460892981760609 0.998348509130453 0.0342933070822744 0.0412476083162746 0.00563011031054651 -0.0345888540409457 0.999385767876462 0.0757708326610243 4.50146912151092e-05 -2.06025730215303e-05 1.57709755337339e-06 3.72656532373046e-09 -1.87999493466993e-06 -1.1204179095514e-05 -2.06025730215303e-05 9.28146693959547e-05 -1.08660562694069e-06 1.40492775116648e-05 2.50649629612169e-06 0.000212221066742857 1.57709755337339e-06 -1.08660562694069e-06 9.8736908537894e-06 -1.83700576239394e-07 1.46621728663041e-06 -1.29166375278382e-05 3.72656532373046e-09 1.40492775116648e-05 -1.83700576239394e-07 7.56165722359754e-05 -1.08355471553663e-06 -2.34820365971069e-05 -1.87999493466993e-06 2.50649629612169e-06 1.46621728663041e-06 -1.08355471553663e-06 1.10322299334023e-05 2.42249064402193e-05 -1.1204179095514e-05 0.000212221066742857 -1.29166375278382e-05 -2.34820365971069e-05 2.42249064402193e-05 0.0014802585650165 3537 3508 0 756 907 3537 3508 0 653 979 0 0 0 0 0 0 0 0 3027 0 0 0 0 0 2839 +1203 1205 0.999668293115092 -0.016413110932298 0.0198472549709577 0.280096574779686 0.0168477143733783 0.999617494424043 -0.0219321536058785 0.0178306229718352 -0.0194796884151464 0.0222592594423729 0.999562437823834 0.0239461378754437 4.26801623815074e-05 -7.5467719595366e-06 -2.68156407926134e-06 -9.344334396676e-06 -4.76583178308281e-07 7.69404123340142e-06 -7.5467719595366e-06 9.05053211181203e-05 -8.69801300713175e-07 6.29388332959458e-05 3.13374107676327e-08 -1.87408019665344e-05 -2.68156407926134e-06 -8.69801300713175e-07 1.03485424300562e-05 -5.77139494656626e-07 3.67159170411778e-06 -9.75702515466192e-07 -9.344334396676e-06 6.29388332959458e-05 -5.77139494656626e-07 0.000103332847396833 -9.00121494329394e-07 -3.17709166213435e-05 -4.76583178308281e-07 3.13374107676327e-08 3.67159170411778e-06 -9.00121494329394e-07 1.00429505907482e-05 2.37369937477057e-06 7.69404123340142e-06 -1.87408019665344e-05 -9.75702515466192e-07 -3.17709166213435e-05 2.37369937477057e-06 0.000213285164530234 3338 3309 0 324 341 3338 3309 0 234 389 0 0 0 0 0 0 0 0 3469 0 0 0 0 0 3435 +1204 1208 0.996719630139742 0.0738152432739292 -0.0331856709214525 0.5851424623343 -0.0759833159020469 0.994671989501551 -0.0696718666719681 -0.00768038238560216 0.0278660115306448 0.0719648744974756 0.997017824434416 0.0408123387549748 5.2108000177633e-05 -4.51416772051124e-06 7.08114153164397e-06 3.49389451044854e-06 5.10520447463758e-07 1.25251461154943e-05 -4.51416772051124e-06 4.66650943314022e-05 1.96746038881024e-07 1.41331259217637e-05 -9.86817292887417e-07 -3.04589255542484e-05 7.08114153164397e-06 1.96746038881024e-07 1.21191196923659e-05 -4.16449567823682e-07 3.64931611327359e-06 1.59241985707752e-06 3.49389451044854e-06 1.41331259217637e-05 -4.16449567823682e-07 4.56000801091762e-05 -3.16696876166358e-06 -1.92864529767142e-05 5.10520447463758e-07 -9.86817292887417e-07 3.64931611327359e-06 -3.16696876166358e-06 9.93148984452199e-06 3.58525261634865e-06 1.25251461154943e-05 -3.04589255542484e-05 1.59241985707752e-06 -1.92864529767142e-05 3.58525261634865e-06 9.4642405205432e-05 3348 3344 0 1245 568 3348 3344 0 1126 625 0 0 0 0 0 0 0 0 2536 0 0 0 0 0 3211 +1202 1206 0.999999803410576 0.000142348392607507 0.000610668277520186 0.576818834707854 -0.000141650920813036 0.999999337843751 -0.00114203637283858 0.0278139912657847 -0.000610830440204343 0.00114194964660248 0.999999161418237 0.0499930189605212 4.45026371583433e-05 -1.78021737826901e-05 1.77416719050695e-06 -1.10680587319916e-06 -5.24787144786562e-07 1.82463354119852e-05 -1.78021737826901e-05 4.78488762666444e-05 1.47876748526474e-06 5.52391753943837e-06 5.57686942444229e-07 -2.50917690613894e-05 1.77416719050695e-06 1.47876748526474e-06 1.00036638508386e-05 1.28673452652013e-06 3.67660556296679e-06 -4.06770664729775e-06 -1.10680587319916e-06 5.52391753943837e-06 1.28673452652013e-06 4.91138498503126e-05 -1.22041245978612e-06 -2.52629462601477e-05 -5.24787144786562e-07 5.57686942444229e-07 3.67660556296679e-06 -1.22041245978612e-06 9.35415115528677e-06 8.992689194811e-07 1.82463354119852e-05 -2.50917690613894e-05 -4.06770664729775e-06 -2.52629462601477e-05 8.992689194811e-07 0.000155020783838831 3434 3414 0 950 809 3434 3414 0 836 868 0 0 0 0 0 0 0 0 2849 0 0 0 0 0 2943 +1206 1208 0.998246544216484 0.0444837077155563 -0.0390517183709654 0.302523650679141 -0.0463038324543713 0.997820558642754 -0.0470115714468225 0.000591323537670829 0.0368753584373867 0.0487373829594814 0.998130690562301 -0.00139515429310332 5.18480434188278e-05 -1.13367433831208e-05 3.2342267161765e-06 1.0784372635237e-05 -1.0582915027314e-07 7.36531815231228e-06 -1.13367433831208e-05 9.64245600703072e-05 -3.55483872785312e-06 4.34065989089239e-05 -1.36940061529168e-06 -0.000117183363647099 3.2342267161765e-06 -3.55483872785312e-06 1.17276273978e-05 3.15247569878222e-06 3.88677683809575e-06 5.56985216199141e-06 1.0784372635237e-05 4.34065989089239e-05 3.15247569878222e-06 7.51819222181151e-05 2.63740112725277e-06 -5.20902001415922e-05 -1.0582915027314e-07 -1.36940061529168e-06 3.88677683809575e-06 2.63740112725277e-06 9.75035070549596e-06 4.00713200093477e-06 7.36531815231228e-06 -0.000117183363647099 5.56985216199141e-06 -5.20902001415922e-05 4.00713200093477e-06 0.000200286356664446 3613 3609 0 544 208 3613 3609 0 463 257 0 0 0 0 0 0 0 0 3267 0 0 0 0 0 3577 +1203 1207 0.999083388504459 0.0417062037140857 0.00964237451087178 0.57848245190122 -0.0412104646459148 0.998049453692688 -0.0468933426767096 0.0139504962847223 -0.0115793099153852 0.0464529929658648 0.998853362123989 0.0307106143584592 5.43480915853849e-05 -1.50097123765399e-05 2.4722548251737e-06 -6.1621630208389e-06 9.80395880189933e-07 5.06848240932054e-06 -1.50097123765399e-05 0.000135441050297319 -3.8286238978241e-06 9.26707349459457e-06 1.10763602453019e-05 0.000244639602451242 2.4722548251737e-06 -3.8286238978241e-06 1.20107600466372e-05 -2.05331569178026e-06 3.97254962695201e-06 -1.10529165156445e-05 -6.1621630208389e-06 9.26707349459457e-06 -2.05331569178026e-06 6.51876823421385e-05 -4.34208064800026e-06 -0.000130248794998238 9.80395880189933e-07 1.10763602453019e-05 3.97254962695201e-06 -4.34208064800026e-06 1.15221313589028e-05 5.20648620867902e-05 5.06848240932054e-06 0.000244639602451242 -1.10529165156445e-05 -0.000130248794998238 5.20648620867902e-05 0.00162765908111147 3346 3339 0 1094 675 3346 3339 0 980 736 0 0 0 0 0 0 0 0 2691 0 0 0 0 0 3105 +1204 1207 0.998313255963163 0.0580139601714189 0.00224129280947612 0.442553216505984 -0.057870286872914 0.997452359193309 -0.0417111620186886 -0.00321125066454073 -0.00465541249251075 0.0415111017070334 0.999127196892164 0.0270047803869699 6.78692063698489e-05 -1.86838906206997e-06 1.18162899941103e-06 1.26618054227141e-05 2.50522061048114e-06 4.62259286463219e-06 -1.86838906206997e-06 6.07330432683451e-05 2.83418512848896e-07 3.03651599790663e-05 2.54290844270984e-06 -2.67571568255457e-05 1.18162899941103e-06 2.83418512848896e-07 1.17622370944879e-05 -3.05524404913205e-06 5.66453799586697e-06 -4.03321608735332e-06 1.26618054227141e-05 3.03651599790663e-05 -3.05524404913205e-06 7.06985970293051e-05 4.96802634251068e-07 -2.24385079178775e-05 2.50522061048114e-06 2.54290844270984e-06 5.66453799586697e-06 4.96802634251068e-07 1.04616925960305e-05 1.48431806018595e-06 4.62259286463219e-06 -2.67571568255457e-05 -4.03321608735332e-06 -2.24385079178775e-05 1.48431806018595e-06 0.000154245358547127 3378 3371 0 868 382 3378 3371 0 771 429 0 0 0 0 0 0 0 0 2918 0 0 0 0 0 3425 +1207 1210 0.99764124843962 0.0638272941682322 0.0252589772357789 0.430114892217619 -0.063668443566809 0.997946241540575 -0.00704473482960954 0.00434561583346581 -0.0256567477599112 0.00541991828364623 0.999656118762939 0.0118385295698117 4.59180705577962e-05 -1.61257230815832e-05 1.77522191165558e-06 -5.84218555018621e-06 -3.15987631131014e-07 1.86328205551434e-06 -1.61257230815832e-05 5.28394592771185e-05 -1.80879793053943e-06 1.43835668226086e-05 -2.16617570611227e-07 -2.67665301056227e-05 1.77522191165558e-06 -1.80879793053943e-06 1.09038697139281e-05 -4.68520688233732e-07 1.97693602093411e-06 2.60984832393152e-06 -5.84218555018621e-06 1.43835668226086e-05 -4.68520688233732e-07 4.09398595656082e-05 -3.36338318401451e-06 -3.36870189733394e-05 -3.15987631131014e-07 -2.16617570611227e-07 1.97693602093411e-06 -3.36338318401451e-06 1.07233739347555e-05 3.25864787667732e-06 1.86328205551434e-06 -2.67665301056227e-05 2.60984832393152e-06 -3.36870189733394e-05 3.25864787667732e-06 0.000285325160018623 3574 3584 0 796 380 3574 3584 0 710 447 0 0 0 0 0 0 0 0 2994 0 0 0 0 0 3418 +1205 1209 0.993905831199952 0.104141483695204 -0.0361351640440999 0.589195005205724 -0.105729391886112 0.993365647300086 -0.0452325817909365 -0.0215652015973507 0.0311848424418893 0.0487774757223281 0.998322725106482 0.00319943514433641 4.36484985654102e-05 -1.02409805214649e-05 2.48471861228114e-07 1.26221705881971e-07 3.96891270675854e-07 4.19552866435527e-06 -1.02409805214649e-05 0.000154958057991931 -1.39559081963659e-05 7.68703115397569e-05 3.30042068576708e-06 -0.000154454514891649 2.48471861228114e-07 -1.39559081963659e-05 1.19679039968566e-05 -7.53709597636417e-06 1.64212064553455e-06 1.6810667258585e-05 1.26221705881971e-07 7.68703115397569e-05 -7.53709597636417e-06 8.89632220102643e-05 1.20213849697436e-06 -8.78008102541083e-05 3.96891270675854e-07 3.30042068576708e-06 1.64212064553455e-06 1.20213849697436e-06 1.07268773409914e-05 -3.1003360501902e-06 4.19552866435527e-06 -0.000154454514891649 1.6810667258585e-05 -8.78008102541083e-05 -3.1003360501902e-06 0.000264073698445648 3367 3374 0 1344 488 3367 3374 0 1225 542 0 0 0 0 0 0 0 0 2452 0 0 0 0 0 3314 +1209 1213 0.99816201667675 -0.0595190859826963 -0.011404686211751 0.570371416117465 0.0599225486403811 0.997437157959985 0.0390948089284053 0.0685440112606365 0.00904857050838753 -0.0397063511858212 0.999170420422494 0.0386811947490186 4.6623484959818e-05 -2.14777472262836e-05 2.79961072385995e-06 1.21695128845843e-05 1.19516345980108e-06 -6.25701864937937e-06 -2.14777472262836e-05 6.69630909482049e-05 -2.52438074127889e-06 1.64195530483865e-05 -3.47205829595706e-07 -5.5082105456874e-05 2.79961072385995e-06 -2.52438074127889e-06 9.97140037541954e-06 1.76517640116543e-07 2.69478210451647e-06 -7.3040802648589e-07 1.21695128845843e-05 1.64195530483865e-05 1.76517640116543e-07 6.29853885088172e-05 9.85691524095566e-07 -4.36405455753638e-05 1.19516345980108e-06 -3.47205829595706e-07 2.69478210451647e-06 9.85691524095566e-07 9.52044197666473e-06 2.93912850637581e-06 -6.25701864937937e-06 -5.5082105456874e-05 -7.3040802648589e-07 -4.36405455753638e-05 2.93912850637581e-06 0.000465073730157128 3472 3462 0 603 1037 3472 3462 0 523 1117 0 0 0 0 0 0 0 0 3151 0 0 0 0 0 2712 +1209 1212 0.999566345233969 -0.0198787304634588 0.0217245840182732 0.431483726340941 0.0195240088184732 0.999674544612098 0.0164200467188603 0.0417001350268118 -0.0220439233182762 -0.0159887751173918 0.999629143490216 0.0251010589592671 3.87731619620601e-05 -7.46972102081039e-05 1.96210475375758e-06 -3.29493165204572e-05 -3.61729140531381e-06 2.44769740491565e-05 -7.46972102081039e-05 0.000878811435662039 -2.42494069010718e-05 0.000429148867665947 3.76551732406236e-05 -0.000267942056748725 1.96210475375758e-06 -2.42494069010718e-05 9.5398251566733e-06 -1.48385786612051e-05 1.51711203987327e-06 6.44896628680699e-06 -3.29493165204572e-05 0.000429148867665947 -1.48385786612051e-05 0.000258248295901792 2.03556783147699e-05 -0.000124018202506618 -3.61729140531381e-06 3.76551732406236e-05 1.51711203987327e-06 2.03556783147699e-05 1.1469730103549e-05 -3.01533445039924e-06 2.44769740491565e-05 -0.000267942056748725 6.44896628680699e-06 -0.000124018202506618 -3.01533445039924e-06 0.000274695036553661 3471 3471 0 486 655 3471 3471 0 427 729 0 0 0 0 0 0 0 0 3277 0 0 0 0 0 3114 +1210 1212 0.999318691660257 -0.0369006238671804 -0.000704596796072688 0.287865276447403 0.0369008755195128 0.999318870325972 0.000347557645122737 0.0390763926285144 0.000691291780351821 -0.000373321089863899 0.999999691373472 0.0246664954889427 4.3640096082118e-05 -2.7899849485194e-05 4.44832298598475e-06 -9.57428950988887e-06 -6.75664157595952e-07 2.41216971796622e-05 -2.7899849485194e-05 4.6958553315348e-05 -2.07130729044262e-06 2.6834872558191e-06 7.77680061420223e-08 -2.03234672817733e-05 4.44832298598475e-06 -2.07130729044262e-06 1.14524076010024e-05 -3.72707412316665e-06 3.66645056768811e-06 9.62914598470894e-07 -9.57428950988887e-06 2.6834872558191e-06 -3.72707412316665e-06 4.0361730753981e-05 2.96827591115548e-07 -2.39945217533198e-05 -6.75664157595952e-07 7.77680061420223e-08 3.66645056768811e-06 2.96827591115548e-07 9.4742805901242e-06 1.43106136953127e-06 2.41216971796622e-05 -2.03234672817733e-05 9.62914598470894e-07 -2.39945217533198e-05 1.43106136953127e-06 0.000171093827267411 3558 3558 0 203 459 3558 3558 0 147 523 0 0 0 0 0 0 0 0 3569 0 0 0 0 0 3312 +1211 1213 0.996728732120639 -0.0642650116577563 -0.0490085996720079 0.285758577662031 0.065306938791989 0.99766553406243 0.0199621113499072 0.0486372513068069 0.0476113254468104 -0.023097411555305 0.998598854029306 -0.00464520747315429 3.48909171379671e-05 -1.92348042722013e-05 -2.63836382876634e-07 4.00621965167068e-08 -1.68387942451479e-07 2.42844217621047e-05 -1.92348042722013e-05 6.96152001140029e-05 6.87816862937394e-07 2.48411339515372e-05 2.26080261038311e-07 -3.25435041919008e-05 -2.63836382876634e-07 6.87816862937394e-07 1.04056075529917e-05 -8.44195854445129e-07 2.27022310297783e-06 -2.01785064817001e-06 4.00621965167068e-08 2.48411339515372e-05 -8.44195854445129e-07 5.85169143686511e-05 1.57738029379524e-06 -1.73487026723701e-05 -1.68387942451479e-07 2.26080261038311e-07 2.27022310297783e-06 1.57738029379524e-06 9.70819068256933e-06 2.30328762722904e-06 2.42844217621047e-05 -3.25435041919008e-05 -2.01785064817001e-06 -1.73487026723701e-05 2.30328762722904e-06 0.000161775119954276 3638 3628 0 110 520 3638 3628 0 57 593 0 0 0 0 0 0 0 0 3663 0 0 0 0 0 3235 +1209 1211 0.998953863073716 0.00625384925262992 0.0452997662204255 0.287417696972096 -0.00698430914597748 0.99984784220286 0.0159847385977193 0.0208769535113535 -0.0451929073622536 -0.0162844039439392 0.998845543270999 0.0200752320863426 3.35486530329726e-05 -2.18289156648396e-05 1.73080435627325e-06 -3.86114053849272e-07 -2.42250274571287e-08 1.91666764041357e-05 -2.18289156648396e-05 3.93847932669268e-05 -1.004925796211e-06 1.00605949027125e-05 -4.80132905124491e-08 -3.08491827162014e-05 1.73080435627325e-06 -1.004925796211e-06 8.74749539980202e-06 -1.26191882479379e-06 3.52473370602355e-06 7.02766844799109e-07 -3.86114053849272e-07 1.00605949027125e-05 -1.26191882479379e-06 3.82779880896729e-05 4.99971709527237e-08 -2.3807408577174e-05 -2.42250274571287e-08 -4.80132905124491e-08 3.52473370602355e-06 4.99971709527237e-08 8.91725249221834e-06 1.47031509201633e-06 1.91666764041357e-05 -3.08491827162014e-05 7.02766844799109e-07 -2.3807408577174e-05 1.47031509201633e-06 0.000151766173128471 3563 3574 0 343 331 3563 3574 0 280 396 0 0 0 0 0 0 0 0 3432 0 0 0 0 0 3451 +1212 1216 0.993976514427163 -0.108268451616243 -0.016989148061313 0.567493776749486 0.108697194624934 0.993714884838471 0.0267515893197631 0.117043711689256 0.013986016155327 -0.0284371242407774 0.999497734523204 0.0427359897983785 4.82747733509784e-05 -1.60850926639265e-05 5.5507418119076e-06 6.12099048934701e-06 -3.2664827228996e-06 -1.30999549228321e-05 -1.60850926639265e-05 7.04788138220406e-05 7.79738251631424e-07 5.5619526288128e-06 -9.4840011574031e-07 -4.8893956349536e-05 5.5507418119076e-06 7.79738251631424e-07 1.10476913780185e-05 -2.39037673349557e-06 1.85985832509751e-06 -6.65060603036458e-06 6.12099048934701e-06 5.5619526288128e-06 -2.39037673349557e-06 3.78486066970352e-05 -1.75459112136269e-06 -3.82405760305543e-05 -3.2664827228996e-06 -9.4840011574031e-07 1.85985832509751e-06 -1.75459112136269e-06 1.0365314150747e-05 7.79574280526769e-06 -1.30999549228321e-05 -4.8893956349536e-05 -6.65060603036458e-06 -3.82405760305543e-05 7.79574280526769e-06 0.000683396855298637 3587 3546 0 438 1185 3587 3546 0 339 1262 0 0 0 0 0 0 0 0 3324 0 0 0 0 0 2538 +1210 1214 0.992618474513637 -0.0998609560734179 -0.0688211704806238 0.570435038091389 0.102714451869652 0.993936440830913 0.0392440182128799 0.102394822586695 0.0644849240624279 -0.0460232662951994 0.996856837027356 0.0268263217898604 3.76177126627299e-05 -1.88463818977436e-05 3.81184168797253e-07 -4.48496580366701e-06 -4.42448226599159e-07 1.97424004734142e-05 -1.88463818977436e-05 4.7559105630973e-05 -1.89719489820577e-06 2.37579542077422e-05 8.85002581954621e-07 -3.67009063245629e-05 3.81184168797253e-07 -1.89719489820577e-06 9.90233028630698e-06 -1.61630941919323e-06 3.06005295304595e-06 1.90476536943359e-06 -4.48496580366701e-06 2.37579542077422e-05 -1.61630941919323e-06 3.91858233302119e-05 2.4030849536784e-07 -2.22772209661337e-05 -4.42448226599159e-07 8.85002581954621e-07 3.06005295304595e-06 2.4030849536784e-07 9.62091656563964e-06 8.04001670256922e-08 1.97424004734142e-05 -3.67009063245629e-05 1.90476536943359e-06 -2.22772209661337e-05 8.04001670256922e-08 8.50950504984223e-05 3455 3434 0 430 1188 3455 3434 0 352 1266 0 0 0 0 0 0 0 0 3329 0 0 0 0 0 2548 +1214 1218 0.999790804384141 0.00948371411612929 0.0181219931429996 0.595129758031112 -0.00877970794364889 0.999218467177829 -0.0385405186682065 0.0629561164214535 -0.0184733374714918 0.0383733503535158 0.999092699295371 0.0211964562588777 4.32185067564573e-05 -5.71957572782927e-06 4.62870615157848e-06 4.55150449006875e-06 -8.45423313937241e-07 4.47334911277534e-06 -5.71957572782927e-06 2.8447227056494e-05 -2.56857752476915e-07 -1.04967053074787e-05 -1.66099242287496e-06 -1.23281399172281e-05 4.62870615157848e-06 -2.56857752476915e-07 9.5507585133328e-06 -1.70789766276047e-06 2.62873325089056e-06 -1.07762378946282e-06 4.55150449006875e-06 -1.04967053074787e-05 -1.70789766276047e-06 2.91980177593913e-05 -2.32627451356978e-07 -1.50213666406973e-06 -8.45423313937241e-07 -1.66099242287496e-06 2.62873325089056e-06 -2.32627451356978e-07 1.02538052643436e-05 3.50580407448521e-06 4.47334911277534e-06 -1.23281399172281e-05 -1.07762378946282e-06 -1.50213666406973e-06 3.50580407448521e-06 0.000118549007646652 3598 3572 0 979 845 3598 3572 0 862 902 0 0 0 0 0 0 0 0 2793 0 0 0 0 0 2935 +1211 1215 0.990884350007155 -0.119439043045881 -0.0623098700623078 0.570594660947973 0.122282106958679 0.991519863498981 0.043993710967681 0.120355288105431 0.0565269071208018 -0.0512120618921537 0.99708677329915 0.0348908227626257 5.05288588742116e-05 -4.06358733449257e-05 -2.67290660779082e-06 1.48877930076638e-05 -6.20484248606791e-08 4.26340123783246e-05 -4.06358733449257e-05 9.0030926288512e-05 9.58043071063686e-07 4.96046886743217e-06 1.54839363857849e-07 -8.35328510818598e-05 -2.67290660779082e-06 9.58043071063686e-07 9.92949144441824e-06 -2.64971451239173e-06 2.73353789233031e-06 -1.2028845450952e-06 1.48877930076638e-05 4.96046886743217e-06 -2.64971451239173e-06 7.58534657705021e-05 -2.35899145624955e-08 -6.57791079466747e-06 -6.20484248606791e-08 1.54839363857849e-07 2.73353789233031e-06 -2.35899145624955e-08 9.58008580266935e-06 -1.82392552556824e-07 4.26340123783246e-05 -8.35328510818598e-05 -1.2028845450952e-06 -6.57791079466747e-06 -1.82392552556824e-07 0.000188018079593252 3538 3503 0 371 1239 3538 3503 0 291 1328 0 0 0 0 0 0 0 0 3391 0 0 0 0 0 2489 +1215 1218 0.99920775656505 0.0394453517023445 -0.00528426431196467 0.445891831108361 -0.0396190746517407 0.998481761425001 -0.0382687996332141 0.0254028480078743 0.00376671527728707 0.0384478390901965 0.999253509138354 0.0198864976885809 5.02829808570637e-05 -2.27111274168694e-05 5.87680277743677e-06 -4.42610602827561e-06 2.0468403093558e-08 -2.88657518209422e-05 -2.27111274168694e-05 0.000482127516908193 -1.03751835615581e-05 0.000327543586018128 1.63672171354271e-05 7.91613759033292e-05 5.87680277743677e-06 -1.03751835615581e-05 1.15198641018221e-05 -7.39822276570424e-06 3.049639452951e-06 -8.03678086793248e-06 -4.42610602827561e-06 0.000327543586018128 -7.39822276570424e-06 0.00026431462328012 1.06350455594345e-05 2.25034759982394e-05 2.0468403093558e-08 1.63672171354271e-05 3.049639452951e-06 1.06350455594345e-05 1.08411607606905e-05 2.23473486668174e-05 -2.88657518209422e-05 7.91613759033292e-05 -8.03678086793248e-06 2.25034759982394e-05 2.23473486668174e-05 0.000933199564302282 3494 3468 0 802 450 3494 3468 0 689 501 0 0 0 0 0 0 0 0 2984 0 0 0 0 0 3345 +1216 1218 0.998382466374786 0.0521013807016996 -0.0227573496781856 0.303247717456584 -0.0526098040569509 0.998365126783489 -0.022344622164557 0.00522418762860937 0.0215559586306868 0.023505738694288 0.999491281050489 -0.0301394243373191 4.05660723236262e-05 4.51217514198128e-06 4.45127424510895e-06 5.05967329943555e-06 -9.36358618974244e-08 -1.55124997266881e-06 4.51217514198128e-06 4.50230134641972e-05 1.28992197663633e-07 -1.03436642607032e-06 1.80815652680586e-06 1.04554075501887e-05 4.45127424510895e-06 1.28992197663633e-07 1.11468185032478e-05 -2.29377743198805e-06 2.32189625986207e-06 -2.61857289661173e-06 5.05967329943555e-06 -1.03436642607032e-06 -2.29377743198805e-06 4.02125790879853e-05 2.12060764682574e-06 7.34319460075544e-06 -9.36358618974244e-08 1.80815652680586e-06 2.32189625986207e-06 2.12060764682574e-06 1.04526852893642e-05 8.18399064663032e-06 -1.55124997266881e-06 1.04554075501887e-05 -2.61857289661173e-06 7.34319460075544e-06 8.18399064663032e-06 0.000228742005656769 3728 3702 0 579 184 3728 3702 0 480 230 0 0 0 0 0 0 0 0 3213 0 0 0 0 0 3617 +1218 1244 0.984366336640824 0.148796030752059 0.0942478462393531 3.53525609378656 -0.147324580575202 0.988834022659289 -0.0224219443802368 0.373501419171149 -0.0965317732493563 0.0081863828326092 0.995296237252735 0.0894123497418515 5.55316191596683e-05 -7.84584456963067e-06 -3.73206903351431e-06 5.54444941471421e-06 -5.96676660686393e-07 6.86704396212655e-06 -7.84584456963067e-06 0.000144058070677243 -4.26086666834765e-06 5.50023367377692e-05 2.20850109206363e-05 8.6905866911463e-05 -3.73206903351431e-06 -4.26086666834765e-06 1.36636473845792e-05 -1.07132112398956e-05 -2.2831556576012e-06 -1.35965341984135e-05 5.54444941471421e-06 5.50023367377692e-05 -1.07132112398956e-05 6.50623263679028e-05 1.90298410231951e-05 3.18658835692907e-05 -5.96676660686393e-07 2.20850109206363e-05 -2.2831556576012e-06 1.90298410231951e-05 3.18950122843158e-05 3.44077869404921e-05 6.86704396212655e-06 8.6905866911463e-05 -1.35965341984135e-05 3.18658835692907e-05 3.44077869404921e-05 0.000346830877151956 3828 3859 0 962 3914 3828 3859 0 962 3914 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1216 1219 0.997862626911504 0.0639638030076178 -0.0133719751000085 0.453217533842151 -0.0643753270657823 0.997379266297485 -0.0330214540119612 -0.00221193961275614 0.0112247529347486 0.0338117001153916 0.999365185433663 -0.0162981540214382 4.2402185031655e-05 -3.40365057330106e-06 -2.18795672077027e-06 5.38901611349027e-09 3.96906867800247e-07 7.02502557909494e-06 -3.40365057330106e-06 4.63004660968959e-05 1.97780463278468e-06 -4.75435007568912e-07 -5.78584428769244e-07 -3.36337706835673e-08 -2.18795672077027e-06 1.97780463278468e-06 9.71041967790796e-06 -2.29006755403902e-06 2.27758756279694e-06 1.19349851835923e-06 5.38901611349027e-09 -4.75435007568912e-07 -2.29006755403902e-06 3.39261333695112e-05 -1.25889837042472e-06 -3.16290492423516e-05 3.96906867800247e-07 -5.78584428769244e-07 2.27758756279694e-06 -1.25889837042472e-06 9.99861040207722e-06 1.71595751125604e-05 7.02502557909494e-06 -3.36337706835673e-08 1.19349851835923e-06 -3.16290492423516e-05 1.71595751125604e-05 0.000719170508882069 3635 3615 0 949 361 3635 3615 0 821 411 0 0 0 0 0 0 0 0 2835 0 0 0 0 0 3433 +1220 1224 0.994436479948115 -0.104049164833495 -0.0164273748923418 0.57769670502287 0.103700955817603 0.99439117323187 -0.0207919782863591 0.0656998152373996 0.0184986245682474 0.0189727672203347 0.999648855845434 0.0311839410319813 4.1396599702722e-05 -1.39805881076277e-05 -1.00099966781518e-06 -2.76988664755465e-06 6.31071630882981e-07 1.25631441551341e-05 -1.39805881076277e-05 3.16613267519847e-05 1.94325733130688e-06 3.49008862469206e-06 -1.49975448984482e-07 -1.13775959894932e-05 -1.00099966781518e-06 1.94325733130688e-06 8.39459401400752e-06 -4.1003095555835e-06 1.50668213824295e-06 -4.17827760374997e-06 -2.76988664755465e-06 3.49008862469206e-06 -4.1003095555835e-06 2.05195256368429e-05 -1.75010477278515e-06 -3.22098198112659e-05 6.31071630882981e-07 -1.49975448984482e-07 1.50668213824295e-06 -1.75010477278515e-06 1.12356300229513e-05 2.97248882954623e-05 1.25631441551341e-05 -1.13775959894932e-05 -4.17827760374997e-06 -3.22098198112659e-05 2.97248882954623e-05 0.000690452594437692 3385 3339 0 627 1095 3385 3339 0 508 1155 0 0 0 0 0 0 0 0 3135 0 0 0 0 0 2651 +1221 1223 0.997927571243934 -0.0584282665250386 -0.0269573778780948 0.287378675994444 0.0572632873001801 0.997469640522242 -0.0421335040556255 0.0373966602667293 0.0293509536260814 0.0405025172959339 0.998748250368396 0.0428929397615229 3.71577070537079e-05 -1.39737026526334e-05 -2.43201001580289e-06 5.80348897587445e-06 3.30040230969797e-07 -2.41787748822182e-06 -1.39737026526334e-05 4.30492302368003e-05 3.17676072947562e-06 -6.34390450041705e-06 -7.81340715798177e-07 -8.82852376102471e-06 -2.43201001580289e-06 3.17676072947562e-06 1.13349026392231e-05 -7.98201533827643e-06 1.25415231367126e-06 -6.61203634101108e-07 5.80348897587445e-06 -6.34390450041705e-06 -7.98201533827643e-06 2.62814408438042e-05 6.49113389257595e-07 -7.5255292386266e-06 3.30040230969797e-07 -7.81340715798177e-07 1.25415231367126e-06 6.49113389257595e-07 1.08503896012876e-05 9.86407427301894e-06 -2.41787748822182e-06 -8.82852376102471e-06 -6.61203634101108e-07 -7.5255292386266e-06 9.86407427301894e-06 0.000279238350885744 3591 3560 0 189 485 3591 3560 0 105 543 0 0 0 0 0 0 0 0 3561 0 0 0 0 0 3295 +1220 1222 0.99924197607656 -0.0291171330123069 0.0258392300921566 0.292710111894479 0.0295138129510308 0.99945022760815 -0.0151055413378387 0.0201958698347063 -0.0253851943404686 0.0158567051798667 0.999551978042731 0.0394622842825938 5.04004733963519e-05 -3.41669261659973e-05 5.33923436943972e-06 8.84644590621554e-07 4.64101371798845e-06 4.95461022481737e-05 -3.41669261659973e-05 5.07207555500082e-05 -2.75504249014462e-06 -3.80764224560689e-06 -2.60228109400139e-06 -5.01983929573097e-05 5.33923436943972e-06 -2.75504249014462e-06 1.0741206657777e-05 -1.4334940211044e-06 2.71843265501582e-06 1.6597298195549e-06 8.84644590621554e-07 -3.80764224560689e-06 -1.4334940211044e-06 3.13771870675222e-05 7.88467014018519e-08 -1.99158130011842e-05 4.64101371798845e-06 -2.60228109400139e-06 2.71843265501582e-06 7.88467014018519e-08 1.05399248951344e-05 1.11438405437329e-05 4.95461022481737e-05 -5.01983929573097e-05 1.6597298195549e-06 -1.99158130011842e-05 1.11438405437329e-05 0.000254758328909815 3625 3608 0 309 405 3625 3608 0 221 457 0 0 0 0 0 0 0 0 3477 0 0 0 0 0 3366 +1220 1223 0.998118868396883 -0.0590749734096256 -0.0163973188899331 0.437724978955676 0.0582514423231183 0.997202979078069 -0.0468293496121939 0.0427279532163805 0.0191178978290648 0.0457860899671142 0.998768311445713 0.0442904638919582 4.59453577068419e-05 -8.36772830057812e-06 2.5987950739459e-06 5.18704397787837e-06 4.71977897498813e-06 1.79179189138635e-05 -8.36772830057812e-06 5.98175385782492e-05 3.65570840039933e-06 4.77346431697851e-06 -4.19184842840507e-07 -5.10150490827791e-05 2.5987950739459e-06 3.65570840039933e-06 1.12319009112399e-05 -2.03578624811074e-06 3.12623765437598e-06 -4.07280746058288e-06 5.18704397787837e-06 4.77346431697851e-06 -2.03578624811074e-06 2.46100248322314e-05 -2.1592403619117e-06 -2.57926095540351e-05 4.71977897498813e-06 -4.19184842840507e-07 3.12623765437598e-06 -2.1592403619117e-06 1.11040105209683e-05 1.6271154993253e-05 1.79179189138635e-05 -5.10150490827791e-05 -4.07280746058288e-06 -2.57926095540351e-05 1.6271154993253e-05 0.000327997524289858 3532 3501 0 469 720 3532 3501 0 373 784 0 0 0 0 0 0 0 0 3297 0 0 0 0 0 3048 +1223 1225 0.997447945882369 -0.0708415038041702 -0.00889250211170313 0.279012247699572 0.0710593033206262 0.997101424611373 0.0271905213182327 0.0388783199629694 0.00694050910453588 -0.0277530246411768 0.999590715721508 0.00136431121206505 4.27310501531314e-05 -1.06179773713723e-05 1.38074732019209e-06 -5.25178864659082e-06 2.9350224263328e-06 1.76168334445627e-05 -1.06179773713723e-05 3.5322155851376e-05 -9.80866036526338e-07 5.97478394139839e-06 -7.91661292289347e-07 -3.1787672954055e-06 1.38074732019209e-06 -9.80866036526338e-07 9.50132443789605e-06 -5.58606319980864e-06 1.99548417886324e-06 -6.52557803626918e-07 -5.25178864659082e-06 5.97478394139839e-06 -5.58606319980864e-06 1.73834850765995e-05 -2.04605359565119e-06 -3.15179760276464e-05 2.9350224263328e-06 -7.91661292289347e-07 1.99548417886324e-06 -2.04605359565119e-06 1.06329900719912e-05 1.70584925928552e-05 1.76168334445627e-05 -3.1787672954055e-06 -6.52557803626918e-07 -3.15179760276464e-05 1.70584925928552e-05 0.000659688090491293 3311 3300 0 152 505 3311 3300 0 65 544 0 0 0 0 0 0 0 0 3601 0 0 0 0 0 3288 +1222 1224 0.996109422856286 -0.0755048049497089 -0.0454427345834673 0.282741479037563 0.0752854266712165 0.997140694313627 -0.00652229060001996 0.0384329006289547 0.0458052641936483 0.00307573946306368 0.998945652975629 0.0260657039742565 4.84747291863242e-05 -1.61416176918947e-05 1.36852867520719e-07 -2.66693831480185e-06 2.22774682647409e-06 4.58615020541276e-05 -1.61416176918947e-05 3.91967370092e-05 3.25125570577719e-07 6.78774981690062e-06 -1.57345755191993e-06 -4.66201241994918e-05 1.36852867520719e-07 3.25125570577719e-07 9.26146104996966e-06 -4.47475258884202e-06 1.25041030830184e-06 -5.41170141857529e-06 -2.66693831480185e-06 6.78774981690062e-06 -4.47475258884202e-06 2.9177654212484e-05 -4.98295256101591e-06 -0.000135371070717622 2.22774682647409e-06 -1.57345755191993e-06 1.25041030830184e-06 -4.98295256101591e-06 1.29453275377714e-05 7.96866393678703e-05 4.58615020541276e-05 -4.66201241994918e-05 -5.41170141857529e-06 -0.000135371070717622 7.96866393678703e-05 0.00214045729440683 3477 3431 0 140 517 3477 3431 0 63 567 0 0 0 0 0 0 0 0 3625 0 0 0 0 0 3249 +1223 1249 0.925505124936514 0.365362217065016 0.0997532658993352 3.45651865971474 -0.364294865302994 0.930820393283702 -0.0293708454261713 0.309338953422754 -0.103583371397733 -0.00915673459869239 0.994578624031991 0.23592894781369 7.02797366475424e-05 -2.50680313987587e-05 -3.30136195358562e-06 -6.73799041736293e-06 2.60655427390873e-06 3.63755087278018e-05 -2.50680313987587e-05 7.93672436242192e-05 -7.18516763278655e-07 1.12281318961352e-05 6.29130962453639e-06 -2.11800242357754e-05 -3.30136195358562e-06 -7.18516763278655e-07 1.30702908996499e-05 -7.5652239416946e-06 2.40089458026501e-06 -5.31468050511183e-06 -6.73799041736293e-06 1.12281318961352e-05 -7.5652239416946e-06 3.12803290299789e-05 -9.627849288687e-07 -2.25124674982211e-05 2.60655427390873e-06 6.29130962453639e-06 2.40089458026501e-06 -9.627849288687e-07 1.96624524419472e-05 9.77649163233728e-07 3.63755087278018e-05 -2.11800242357754e-05 -5.31468050511183e-06 -2.25124674982211e-05 9.77649163233728e-07 0.000198529452827622 3838 3829 0 2335 3641 3838 3829 0 2335 3647 0 0 0 0 0 0 0 0 0 0 0 0 0 0 136 +1224 1226 0.998055904648301 -0.0547962423648022 0.0296948315260348 0.275670158113431 0.0541877883930389 0.998311548407278 0.0209221391290364 0.0349213018551341 -0.0307911478469539 -0.0192723672485084 0.999340022752469 0.0122302040601597 5.81092562222685e-05 -3.04255510893597e-05 -2.56452565791318e-06 -2.21888061866852e-08 8.1608370705701e-07 7.83052789593153e-06 -3.04255510893597e-05 4.32915232578552e-05 7.28028908530762e-07 2.42742632922561e-06 7.73077695362702e-07 3.04497721169827e-05 -2.56452565791318e-06 7.28028908530762e-07 9.2278066504474e-06 -5.52890661920144e-06 1.0503415778062e-06 -9.86913643911003e-06 -2.21888061866852e-08 2.42742632922561e-06 -5.52890661920144e-06 1.98445287660576e-05 -1.3658243856853e-06 -5.73612509097849e-05 8.1608370705701e-07 7.73077695362702e-07 1.0503415778062e-06 -1.3658243856853e-06 1.02254500339906e-05 1.56326903732354e-05 7.83052789593153e-06 3.04497721169827e-05 -9.86913643911003e-06 -5.73612509097849e-05 1.56326903732354e-05 0.000838421105165867 3717 3734 0 200 449 3717 3734 0 95 482 0 0 0 0 0 0 0 0 3523 0 0 0 0 0 3357 +1224 1227 0.997052365605575 -0.0525504480475904 0.055901973581661 0.423043923534983 0.0508831984087262 0.998228265722724 0.0308420108277827 0.0462761384024813 -0.0574236916265876 -0.0279066286426784 0.997959788627665 -0.0139470338293513 3.75791766529532e-05 -9.98608816689649e-07 1.11758247018498e-06 6.62089403309422e-07 -2.10404218454682e-06 1.2982135225276e-05 -9.98608816689649e-07 3.40835556024273e-05 4.87974266262572e-06 -2.32655830792413e-06 1.67849805484802e-06 -3.18113794695226e-06 1.11758247018498e-06 4.87974266262572e-06 1.04867785941657e-05 -4.84277933184324e-06 9.04993373751855e-07 -5.42177615666415e-06 6.62089403309422e-07 -2.32655830792413e-06 -4.84277933184324e-06 2.42805763884289e-05 -2.18221653531497e-06 -8.31155634753788e-05 -2.10404218454682e-06 1.67849805484802e-06 9.04993373751855e-07 -2.18221653531497e-06 1.05080267344131e-05 1.61444686531102e-05 1.2982135225276e-05 -3.18113794695226e-06 -5.42177615666415e-06 -8.31155634753788e-05 1.61444686531102e-05 0.000996625523581056 3705 3717 0 288 649 3705 3717 0 165 688 0 0 0 0 0 0 0 0 3218 0 0 0 0 0 3134 +1223 1227 0.993846296897246 -0.0974821584814921 0.0526000657929275 0.557144531765103 0.0947785681473821 0.994157128577202 0.0516587525891334 0.0798161583121299 -0.0573285370785188 -0.0463555010427295 0.997278600171243 -0.0215104420204029 4.06773468387318e-05 -7.70953899927843e-06 -1.25908518839637e-06 -2.20831222428438e-07 2.45070194906765e-08 9.34724449033394e-06 -7.70953899927843e-06 5.26153449943468e-05 -1.1376767810742e-06 -1.07808193455695e-06 1.6539199534989e-06 3.37857485248229e-06 -1.25908518839637e-06 -1.1376767810742e-06 1.08075728181073e-05 -6.13003664170278e-06 5.76178831640607e-07 -4.31641352221294e-06 -2.20831222428438e-07 -1.07808193455695e-06 -6.13003664170278e-06 2.10859201028608e-05 -6.12690501950346e-08 -1.92321253049403e-05 2.45070194906765e-08 1.6539199534989e-06 5.76178831640607e-07 -6.12690501950346e-08 1.01203447767783e-05 3.20091266260176e-06 9.34724449033394e-06 3.37857485248229e-06 -4.31641352221294e-06 -1.92321253049403e-05 3.20091266260176e-06 0.000390269545330996 3562 3579 0 327 1027 3562 3579 0 205 1084 0 0 0 0 0 0 0 0 3097 0 0 0 0 0 2729 +1222 1226 0.991575072001387 -0.129203046415302 -0.0092438835156134 0.562106061282564 0.129359458723113 0.991415580124961 0.0190073123915547 0.0907544999884581 0.00670872747308324 -0.020042960921288 0.999776611395366 -0.0424317304386279 4.89536709131417e-05 -3.1911026130133e-05 -1.31704887601638e-06 1.41993341576737e-06 1.56903393159078e-06 4.01175545715144e-05 -3.1911026130133e-05 8.44440874108167e-05 1.64911657786261e-06 -1.28967960845027e-05 -2.09013304270745e-06 -7.5794220222707e-05 -1.31704887601638e-06 1.64911657786261e-06 1.03553320631568e-05 -4.12372174599405e-06 1.51944339911282e-06 -6.89305823957003e-06 1.41993341576737e-06 -1.28967960845027e-05 -4.12372174599405e-06 2.90268012168013e-05 -6.42690474835755e-07 -2.55734994028208e-05 1.56903393159078e-06 -2.09013304270745e-06 1.51944339911282e-06 -6.42690474835755e-07 1.07851110470243e-05 1.46068756175661e-05 4.01175545715144e-05 -7.5794220222707e-05 -6.89305823957003e-06 -2.55734994028208e-05 1.46068756175661e-05 0.000615698018800636 3386 3404 0 485 1141 3386 3404 0 378 1209 0 0 0 0 0 0 0 0 3220 0 0 0 0 0 2623 +1226 1252 0.844018116922138 0.536006161251469 -0.0181882766548444 3.3607167722285 -0.536222169608776 0.844016955951896 -0.0100579762254688 -0.125672761325285 0.00996007666966063 0.0182420713231732 0.999783988522808 0.5309088035672 6.13711503503278e-05 -5.66998151593397e-05 -3.33280650737965e-06 -5.10317240076733e-06 -4.09867809767781e-07 4.54005993736837e-05 -5.66998151593397e-05 9.52307016263117e-05 -1.2155852679809e-06 9.43300936894356e-06 8.01288713575116e-07 -6.71096836911881e-05 -3.33280650737965e-06 -1.2155852679809e-06 1.35236552358132e-05 -7.40513098306214e-06 3.18319479458299e-07 -1.44334608027519e-06 -5.10317240076733e-06 9.43300936894356e-06 -7.40513098306214e-06 4.09774163676825e-05 1.9164148500982e-05 3.05401895750274e-06 -4.09867809767781e-07 8.01288713575116e-07 3.18319479458299e-07 1.9164148500982e-05 2.51136494960012e-05 1.25675456549351e-05 4.54005993736837e-05 -6.71096836911881e-05 -1.44334608027519e-06 3.05401895750274e-06 1.25675456549351e-05 0.000247225822189412 3811 3763 0 2758 3241 3811 3763 0 2847 3252 0 0 0 0 0 0 0 0 132 0 0 0 0 0 391 +1225 1229 0.998268581554524 0.0378468957074824 0.0450272313875313 0.559287878700943 -0.0379451080311873 0.99927894242508 0.00132815748910895 0.0061447125487179 -0.0449444975232882 -0.00303442105207895 0.998984876978254 0.00261256127548717 4.13417282773193e-05 -1.05355619694246e-05 -1.47814407178912e-06 -6.00331598530474e-07 -5.95712503330771e-07 7.65244364381385e-06 -1.05355619694246e-05 3.399669520882e-05 -2.89654598843873e-07 2.35612526932592e-06 -1.70732231333883e-07 1.01615206303843e-05 -1.47814407178912e-06 -2.89654598843873e-07 9.14642138782949e-06 -6.14856505865659e-06 8.25448650494409e-07 -9.17114366297166e-06 -6.00331598530474e-07 2.35612526932592e-06 -6.14856505865659e-06 2.13048266433605e-05 -1.65261238427572e-06 -6.2976107652458e-05 -5.95712503330771e-07 -1.70732231333883e-07 8.25448650494409e-07 -1.65261238427572e-06 9.86600242105747e-06 1.73385487455214e-05 7.65244364381385e-06 1.01615206303843e-05 -9.17114366297166e-06 -6.2976107652458e-05 1.73385487455214e-05 0.000873605900793372 3853 3921 0 389 572 3853 3921 0 318 611 0 0 0 0 0 0 0 0 2525 0 0 0 0 0 3233 +1228 1254 0.830480006472183 0.554140334280821 -0.0568458333838434 3.23529569253304 -0.556025516782597 0.830808896384563 -0.0243352085446226 -0.100316061365704 0.0337429034999811 0.051817638033829 0.998086343385173 0.642407449593176 4.67152881619545e-05 -1.00066035090772e-05 -7.07936811592319e-06 1.9142930372249e-06 -8.13159803408373e-07 1.03007670949272e-05 -1.00066035090772e-05 8.69773900622137e-05 -7.03154946960421e-06 -3.12043511830121e-06 -2.56509917425513e-06 -2.09531657663632e-05 -7.07936811592319e-06 -7.03154946960421e-06 1.58844191840971e-05 -1.21673333265745e-05 -2.70511886222672e-06 -2.63468587037621e-06 1.9142930372249e-06 -3.12043511830121e-06 -1.21673333265745e-05 3.17462186674457e-05 9.83675623564033e-06 -4.71999310523673e-05 -8.13159803408373e-07 -2.56509917425513e-06 -2.70511886222672e-06 9.83675623564033e-06 1.95117573115165e-05 -1.14386272080074e-07 1.03007670949272e-05 -2.09531657663632e-05 -2.63468587037621e-06 -4.71999310523673e-05 -1.14386272080074e-07 0.0009271715243238 3813 3727 0 2893 2972 3813 3727 0 2956 2982 0 0 0 0 0 0 0 0 333 0 0 0 0 0 416 +1227 1231 0.991080315061228 0.132419739353363 -0.0149940564132434 0.555818882753052 -0.132569866869554 0.991128126435358 -0.00950091505725487 -0.0695826682663099 0.0136029223450239 0.0114039299508524 0.999842443030576 -0.00854655232131641 0.000189493932824677 -0.000111177794869345 1.86242061883892e-05 -2.85683921542767e-05 1.94424722768226e-05 0.000253657009042657 -0.000111177794869345 9.56806493793693e-05 -1.27283171479008e-05 1.58946372735284e-05 -1.11960289934059e-05 -0.000126014103903024 1.86242061883892e-05 -1.27283171479008e-05 1.36793189074202e-05 -7.39295495378328e-06 3.77027048716637e-06 1.84458716576947e-05 -2.85683921542767e-05 1.58946372735284e-05 -7.39295495378328e-06 2.66617795154937e-05 -3.64989281609931e-06 -7.74071041649987e-05 1.94424722768226e-05 -1.11960289934059e-05 3.77027048716637e-06 -3.64989281609931e-06 1.40133167382061e-05 3.63513970502566e-05 0.000253657009042657 -0.000126014103903024 1.84458716576947e-05 -7.74071041649987e-05 3.63513970502566e-05 0.000847624512332859 3857 3932 0 585 225 3857 3932 0 582 248 0 0 0 0 0 0 0 0 2053 0 0 0 0 0 3633 +1225 1227 0.997737696216647 -0.026748349652451 0.061676700131967 0.280211330650198 0.025681015096303 0.999507514139999 0.0180337084733576 0.0224657527048446 -0.0621286971690362 -0.0164089904792712 0.997933249280496 -0.00369157790049974 3.53359176591122e-05 9.923303183538e-07 -8.01497867762536e-07 2.53530840573157e-06 -3.39372375533054e-06 -3.09969174744705e-06 9.923303183538e-07 3.56276723820122e-05 8.63311245342771e-07 -4.39731580918711e-06 1.98541854240156e-06 2.25999864437817e-05 -8.01497867762536e-07 8.63311245342771e-07 9.65673942122386e-06 -6.60406299578246e-06 9.05120251288615e-08 -8.82263619749074e-06 2.53530840573157e-06 -4.39731580918711e-06 -6.60406299578246e-06 2.58401652583473e-05 -1.7381005954984e-06 -9.25426875516611e-05 -3.39372375533054e-06 1.98541854240156e-06 9.05120251288615e-08 -1.7381005954984e-06 9.96967293487597e-06 1.59429318531371e-05 -3.09969174744705e-06 2.25999864437817e-05 -8.82263619749074e-06 -9.25426875516611e-05 1.59429318531371e-05 0.0011020689864014 3571 3583 0 130 371 3571 3583 0 107 404 0 0 0 0 0 0 0 0 3416 0 0 0 0 0 3423 +1227 1230 0.994551179671768 0.0975994608530541 -0.036637361459143 0.418709526492597 -0.0980201063748842 0.995135568558063 -0.00986199456890078 -0.0469298001871272 0.0354966161732511 0.0133994563999371 0.999279963177705 -0.00222759731358756 6.00455373111063e-05 -3.12966099583169e-05 1.59485746493657e-06 1.67294043735599e-06 4.69078301779804e-06 6.97654314720207e-06 -3.12966099583169e-05 4.23551150565376e-05 -4.74785214435636e-08 7.44558777397463e-06 -3.17854716204291e-06 -2.38620388615784e-05 1.59485746493657e-06 -4.74785214435636e-08 9.11504409752699e-06 -4.47740839198239e-06 1.57832251121779e-06 -4.73237247443976e-06 1.67294043735599e-06 7.44558777397463e-06 -4.47740839198239e-06 2.28594827374562e-05 7.10652062824135e-07 -4.7638237548241e-05 4.69078301779804e-06 -3.17854716204291e-06 1.57832251121779e-06 7.10652062824135e-07 1.18166836286546e-05 5.10776795401745e-06 6.97654314720207e-06 -2.38620388615784e-05 -4.73237247443976e-06 -4.7638237548241e-05 5.10776795401745e-06 0.000478341717317528 3852 3887 0 445 155 3852 3887 0 446 174 0 0 0 0 0 0 0 0 2567 0 0 0 0 0 3676 +1226 1230 0.994830106045264 0.100607043460381 -0.01383050657529 0.56130894479576 -0.100614031637429 0.994925514807601 0.000191370039215789 -0.0436366095382826 0.0137795770483227 0.00120116234972096 0.999904335656856 0.0131133101074261 5.5382302571362e-05 -2.54772454246367e-05 -1.82839765078422e-06 -5.23344339306698e-06 2.26501091794934e-06 5.64616170654072e-05 -2.54772454246367e-05 4.25393178345332e-05 -7.72783364112912e-07 6.93011020043576e-06 -4.06874237019215e-07 -6.39881151187975e-06 -1.82839765078422e-06 -7.72783364112912e-07 1.20393022512778e-05 -9.81662655917198e-06 6.77896705096266e-07 -1.52353873523303e-06 -5.23344339306698e-06 6.93011020043576e-06 -9.81662655917198e-06 1.79690996444561e-05 -7.08452750350101e-07 -1.65165281550215e-05 2.26501091794934e-06 -4.06874237019215e-07 6.77896705096266e-07 -7.08452750350101e-07 1.03674426444881e-05 7.9148329851909e-06 5.64616170654072e-05 -6.39881151187975e-06 -1.52353873523303e-06 -1.65165281550215e-05 7.9148329851909e-06 0.000349014101500076 3865 3902 0 402 335 3865 3902 0 402 359 0 0 0 0 0 0 0 0 2451 0 0 0 0 0 3491 +1226 1229 0.99770313203014 0.0670744208856493 0.0094595137350807 0.42272394765142 -0.0670563851245715 0.997746736787223 -0.00221143493533386 -0.0200265427208177 -0.0095865296783845 0.00157203476515272 0.99995281246438 0.0154273540364766 4.34489551830377e-05 -2.60160673617672e-05 -1.77214999066691e-06 3.57670692868908e-06 -4.46381430584645e-07 1.4731845216006e-06 -2.60160673617672e-05 4.3245751793521e-05 3.96752493921831e-06 -4.07509189477182e-06 -1.46507974551975e-06 1.62721400991645e-05 -1.77214999066691e-06 3.96752493921831e-06 1.1173512169216e-05 -7.7016877798184e-06 2.84172254661301e-07 -7.8247682580519e-06 3.57670692868908e-06 -4.07509189477182e-06 -7.7016877798184e-06 2.14824449013899e-05 9.28410028934048e-07 -3.86885203043269e-05 -4.46381430584645e-07 -1.46507974551975e-06 2.84172254661301e-07 9.28410028934048e-07 1.11390661992119e-05 1.09158716076042e-05 1.4731845216006e-06 1.62721400991645e-05 -7.8247682580519e-06 -3.86885203043269e-05 1.09158716076042e-05 0.000455996302886854 3880 3944 0 281 253 3880 3944 0 282 281 0 0 0 0 0 0 0 0 2968 0 0 0 0 0 3567 +1227 1229 0.997859549775115 0.0641697109430128 -0.0125923437093759 0.278017748910038 -0.0643239300920925 0.99785388543552 -0.0122497077003264 -0.0233109007526656 0.0117792588948739 0.013033476847182 0.999845676862765 0.0208745903230221 5.25102716305655e-05 -2.14843956535997e-05 1.63963132594613e-06 -1.54156213241625e-06 1.08209768862039e-06 4.18928725098561e-06 -2.14843956535997e-05 4.23073720866104e-05 9.86829333321811e-08 5.80514095786112e-06 -4.65612501431008e-07 -1.14238507452885e-05 1.63963132594613e-06 9.86829333321811e-08 9.86602042584732e-06 -4.84911476036905e-06 1.75069124893052e-06 -3.30412171608503e-06 -1.54156213241625e-06 5.80514095786112e-06 -4.84911476036905e-06 2.45684524911563e-05 8.2732167765104e-07 -6.7655814845728e-05 1.08209768862039e-06 -4.65612501431008e-07 1.75069124893052e-06 8.2732167765104e-07 1.07899312730633e-05 1.1201860183169e-05 4.18928725098561e-06 -1.14238507452885e-05 -3.30412171608503e-06 -6.7655814845728e-05 1.1201860183169e-05 0.000687601503289457 3866 3934 0 330 91 3866 3934 0 326 111 0 0 0 0 0 0 0 0 3134 0 0 0 0 0 3740 +1229 1233 0.997514356146886 0.0615302106436867 0.0343386438143262 0.548581412155082 -0.0615140618185437 0.998105047969552 -0.00152755238304696 -0.026913362854618 -0.0343675643514056 -0.000588554026503686 0.999409087473548 0.0717047147242044 4.7083807850104e-05 -1.99044270128535e-05 1.21225798045282e-06 -2.58575600340469e-06 1.43421274593441e-06 1.3451199521134e-05 -1.99044270128535e-05 2.72563166890654e-05 -1.35608989615679e-06 -2.71910702570322e-08 -7.29364430179162e-07 -8.5097891484648e-06 1.21225798045282e-06 -1.35608989615679e-06 1.03120718871936e-05 -7.53988965539729e-06 -4.83479787239014e-08 9.81250540887836e-07 -2.58575600340469e-06 -2.71910702570322e-08 -7.53988965539729e-06 1.83465551085639e-05 -3.24381523213987e-07 -2.55548573568825e-05 1.43421274593441e-06 -7.29364430179162e-07 -4.83479787239014e-08 -3.24381523213987e-07 1.32147803178866e-05 4.80314714758223e-06 1.3451199521134e-05 -8.5097891484648e-06 9.81250540887836e-07 -2.55548573568825e-05 4.80314714758223e-06 0.000225053907469942 3822 3873 0 480 468 3822 3873 0 492 506 0 0 0 0 0 0 0 0 1839 0 0 0 0 0 3363 +1228 1232 0.994020613588833 0.108336092318345 0.0136495736809048 0.553999565044596 -0.107910885480161 0.993744161619729 -0.0287712016014353 -0.0576120005501349 -0.0166811437068002 0.0271262298872136 0.999492824935096 -0.00799073371970649 5.54356570862586e-05 -2.78767737492155e-05 2.41631786777219e-06 1.38321697131295e-06 7.6660868053073e-06 3.65416791991987e-05 -2.78767737492155e-05 4.16980154535028e-05 3.25666557632162e-07 -3.5776905886392e-06 -5.54720871730197e-06 -3.30849306883996e-05 2.41631786777219e-06 3.25666557632162e-07 1.07109503761667e-05 -7.08863243648164e-06 6.32722120979146e-07 -9.15842010411217e-07 1.38321697131295e-06 -3.5776905886392e-06 -7.08863243648164e-06 1.87916110549948e-05 1.34459999855034e-06 -4.13163271323816e-06 7.6660868053073e-06 -5.54720871730197e-06 6.32722120979146e-07 1.34459999855034e-06 1.28590577444135e-05 4.67531905726008e-06 3.65416791991987e-05 -3.30849306883996e-05 -9.15842010411217e-07 -4.13163271323816e-06 4.67531905726008e-06 0.000145129966648544 3835 3899 0 495 307 3835 3899 0 548 330 0 0 0 0 0 0 0 0 1986 0 0 0 0 0 3541 +1229 1231 0.997661574711134 0.0683454596698253 0.000529610631930726 0.27763414007351 -0.0683474134121547 0.997643325111927 0.00603547342676836 -0.0266607242542887 -0.000115865306176499 -0.00605755743988497 0.999981646118114 0.0012823741639761 6.67513397030141e-05 -2.22267345500238e-05 6.37047400822982e-06 1.82879231415319e-06 7.49576059884483e-06 1.88135506367493e-05 -2.22267345500238e-05 3.34268948710173e-05 -3.62615898056036e-06 -5.70306400580469e-06 -5.45680866291425e-06 -6.22301463069894e-06 6.37047400822982e-06 -3.62615898056036e-06 1.05579370400002e-05 -4.78698401873369e-06 3.60146869719358e-06 -2.52244374046913e-06 1.82879231415319e-06 -5.70306400580469e-06 -4.78698401873369e-06 2.01233494664132e-05 1.24385921020151e-06 -3.36449844000483e-05 7.49576059884483e-06 -5.45680866291425e-06 3.60146869719358e-06 1.24385921020151e-06 1.24750649025331e-05 1.14690388580893e-05 1.88135506367493e-05 -6.22301463069894e-06 -2.52244374046913e-06 -3.36449844000483e-05 1.14690388580893e-05 0.000417597317906854 3859 3934 0 312 86 3859 3934 0 334 118 0 0 0 0 0 0 0 0 2731 0 0 0 0 0 3752 +1229 1232 0.99709697127222 0.0749180377813014 0.0135984372177528 0.415703847485477 -0.0751380146046858 0.997037312055012 0.0164583453415689 -0.0340721908422267 -0.0123251223536197 -0.017432325866499 0.999772076712414 0.006120809424346 5.1011109061665e-05 -2.94129098704014e-05 2.52228210169096e-06 3.09411710465421e-06 9.69726741071911e-06 2.33026414135928e-05 -2.94129098704014e-05 3.23757777686444e-05 -2.324936624052e-06 -5.03857406275807e-06 -8.29533060841971e-06 -3.02754428652248e-05 2.52228210169096e-06 -2.324936624052e-06 9.11709464665471e-06 -3.86855312209707e-06 8.09703517976466e-07 5.10051141609674e-07 3.09411710465421e-06 -5.03857406275807e-06 -3.86855312209707e-06 1.82145232224243e-05 4.14694161747884e-06 -1.67111357377928e-05 9.69726741071911e-06 -8.29533060841971e-06 8.09703517976466e-07 4.14694161747884e-06 1.40378344607826e-05 1.48921265545586e-06 2.33026414135928e-05 -3.02754428652248e-05 5.10051141609674e-07 -1.67111357377928e-05 1.48921265545586e-06 0.000250711372048177 3835 3899 0 419 236 3835 3899 0 422 260 0 0 0 0 0 0 0 0 2261 0 0 0 0 0 3607 +1230 1234 0.998250620036323 0.00285888323319446 0.0590552824373541 0.544363592936399 -0.00219574200648851 0.999933843813073 -0.0112910014725822 0.0156413423083088 -0.0590836552198461 0.0111415790564835 0.998190856951711 0.0539840020382465 6.76358982844614e-05 -3.12972861139404e-05 5.21906549377661e-06 -1.29284630267813e-05 -3.90256434787731e-08 5.90138376343408e-05 -3.12972861139404e-05 4.19834186523245e-05 -3.86841072827201e-06 8.90114151215333e-06 -2.81829871344446e-07 -4.57577236409306e-05 5.21906549377661e-06 -3.86841072827201e-06 1.19396657098708e-05 -9.13069574098496e-06 1.43940145899413e-06 4.99759452817021e-06 -1.29284630267813e-05 8.90114151215333e-06 -9.13069574098496e-06 3.23948455062157e-05 -3.95638820937209e-07 -4.66406187699824e-05 -3.90256434787731e-08 -2.81829871344446e-07 1.43940145899413e-06 -3.95638820937209e-07 1.40576880989881e-05 1.10034012377087e-05 5.90138376343408e-05 -4.57577236409306e-05 4.99759452817021e-06 -4.66406187699824e-05 1.10034012377087e-05 0.000313059148468432 3815 3867 0 241 669 3815 3867 0 260 710 0 0 0 0 0 0 0 0 2145 0 0 0 0 0 3154 +1230 1233 0.998087418631724 0.0284955520735116 0.0548589854179601 0.411879551260772 -0.0284079602014314 0.999593588688605 -0.00237597344887042 0.00060334526941976 -0.0549043947808922 0.000812997331876276 0.998491285124253 0.0504078754957498 4.4855774808622e-05 -1.98453956963303e-05 3.06853155120069e-06 -4.09841785585454e-06 -8.27790386600651e-07 1.64349149978106e-05 -1.98453956963303e-05 5.03278803175226e-05 -4.11663358061604e-06 4.78983660405297e-06 -3.20212372228065e-07 -2.11362059339102e-05 3.06853155120069e-06 -4.11663358061604e-06 1.11243827218794e-05 -8.65018485980829e-06 4.55335460802376e-07 1.30578067148594e-06 -4.09841785585454e-06 4.78983660405297e-06 -8.65018485980829e-06 2.25669159419179e-05 1.49526825969518e-06 -2.16194294701324e-05 -8.27790386600651e-07 -3.20212372228065e-07 4.55335460802376e-07 1.49526825969518e-06 1.36388854996901e-05 5.35951726671271e-06 1.64349149978106e-05 -2.11362059339102e-05 1.30578067148594e-06 -2.16194294701324e-05 5.35951726671271e-06 0.000229767518532507 3817 3868 0 259 395 3817 3868 0 288 436 0 0 0 0 0 0 0 0 2347 0 0 0 0 0 3425 +1231 1233 0.999366725655582 -0.00571358934978647 0.0351212549488469 0.276402841262635 0.00601648564055862 0.999945564440518 -0.00852467338201317 0.0165551626607711 -0.0350706366206382 0.00873058145114394 0.999346700297023 0.00920391009534161 6.11373497049656e-05 -3.17731000700196e-05 1.21726085631654e-06 -1.25799712219159e-05 -1.74325831275503e-06 4.3076476664165e-05 -3.17731000700196e-05 4.30884672340317e-05 -4.34242240586434e-06 1.12309693558728e-05 1.12267608644373e-06 -2.54362993189483e-05 1.21726085631654e-06 -4.34242240586434e-06 1.08712388237489e-05 -8.04229193933709e-06 2.44523548137605e-06 -2.56227135707735e-06 -1.25799712219159e-05 1.12309693558728e-05 -8.04229193933709e-06 2.2906326772019e-05 8.93577484734344e-07 -3.12872214250855e-05 -1.74325831275503e-06 1.12267608644373e-06 2.44523548137605e-06 8.93577484734344e-07 1.47498182578245e-05 2.75721558137292e-06 4.3076476664165e-05 -2.54362993189483e-05 -2.56227135707735e-06 -3.12872214250855e-05 2.75721558137292e-06 0.000220266670697414 3822 3873 0 101 317 3822 3873 0 136 358 0 0 0 0 0 0 0 0 3123 0 0 0 0 0 3503 +1231 1234 0.998765955864977 -0.0321542611665293 0.0378506128609994 0.409240578476946 0.032621505404058 0.99939821088968 -0.0117920929304015 0.0373737285017983 -0.0374486687385766 0.013012284939273 0.999213829793387 0.0239812955636628 5.48392061385989e-05 -2.29714201527326e-05 3.31022262968013e-06 -1.02559814601143e-05 -3.73674036016772e-06 4.74566690327644e-05 -2.29714201527326e-05 3.88328866956092e-05 -4.19785814459802e-06 8.52509303547891e-06 2.78891378426918e-06 -2.271094308116e-05 3.31022262968013e-06 -4.19785814459802e-06 1.05306447319196e-05 -7.45591200238138e-06 3.584529978825e-07 2.23627648093715e-06 -1.02559814601143e-05 8.52509303547891e-06 -7.45591200238138e-06 2.31220299133446e-05 1.04249492554254e-06 -2.31294865650189e-05 -3.73674036016772e-06 2.78891378426918e-06 3.584529978825e-07 1.04249492554254e-06 1.34447817803191e-05 1.72843587475342e-07 4.74566690327644e-05 -2.271094308116e-05 2.23627648093715e-06 -2.31294865650189e-05 1.72843587475342e-07 0.000148123577351294 3815 3867 0 90 589 3815 3867 0 116 638 0 0 0 0 0 0 3 0 2893 0 0 0 0 0 3225 +1230 1232 0.998491166454273 0.0407221024561228 0.0368388502038069 0.276808375239133 -0.0417112789513557 0.998778387335213 0.0264934369290428 -0.011140608758269 -0.0357149789448024 -0.0279900582997608 0.998969967974688 0.0376225853922368 4.96630928859047e-05 -2.18797751547466e-05 8.10793299140966e-07 -4.30824936687079e-06 1.83547629410781e-06 2.50520332520136e-05 -2.18797751547466e-05 4.20099862078031e-05 -3.77787272209751e-06 7.19446506523864e-06 -3.48837667694305e-07 -1.08203752326521e-05 8.10793299140966e-07 -3.77787272209751e-06 9.50659189695376e-06 -6.59251250872124e-06 1.49054594075817e-06 -1.52040917175383e-06 -4.30824936687079e-06 7.19446506523864e-06 -6.59251250872124e-06 1.6761876493986e-05 1.29682128810356e-06 -1.48819159590181e-05 1.83547629410781e-06 -3.48837667694305e-07 1.49054594075817e-06 1.29682128810356e-06 1.18755768626492e-05 1.75455892056983e-06 2.50520332520136e-05 -1.08203752326521e-05 -1.52040917175383e-06 -1.48819159590181e-05 1.75455892056983e-06 0.000195450172472305 3825 3889 0 249 168 3825 3889 0 272 205 0 0 0 0 0 0 0 0 2755 0 0 0 0 0 3656 +1232 1236 0.996749935230729 -0.0787316306453047 0.0170557014944604 0.539380512022221 0.0791781883302318 0.996486186889073 -0.0273147182306007 0.0978030517681085 -0.0148452386400209 0.0285763831722295 0.99948137011878 0.0205116911815751 0.000102246864091244 -3.91884611886599e-05 6.15442348608979e-06 -2.72159804143427e-05 9.67598274096859e-07 0.000108396040689718 -3.91884611886599e-05 4.78946417302011e-05 -2.02803624302804e-06 6.48676044027766e-06 -1.86913489961284e-06 -3.39628679249674e-05 6.15442348608979e-06 -2.02803624302804e-06 1.1976545920491e-05 -7.55087095943914e-06 3.07160494108142e-06 -9.09872462201958e-07 -2.72159804143427e-05 6.48676044027766e-06 -7.55087095943914e-06 4.47931785297677e-05 -6.50667992612657e-06 -0.000192877969716078 9.67598274096859e-07 -1.86913489961284e-06 3.07160494108142e-06 -6.50667992612657e-06 1.57564364351501e-05 4.92276513443993e-05 0.000108396040689718 -3.39628679249674e-05 -9.09872462201958e-07 -0.000192877969716078 4.92276513443993e-05 0.0014895622799722 3815 3848 0 90 969 3815 3848 0 105 1019 0 0 0 0 0 0 0 0 2756 0 0 0 0 0 2823 +1232 1235 0.997584602735883 -0.0689601487367835 0.00833416285489191 0.402808668117547 0.06916669600316 0.997219166612747 -0.0277471062308217 0.0669706646794511 -0.00639754236387743 0.0282565324549698 0.999580231809995 0.0437281318762029 5.97417684401325e-05 -2.12978990822617e-05 1.01372572862885e-06 -3.99319958016839e-06 -5.90046269539126e-07 2.85969225570384e-05 -2.12978990822617e-05 4.08437639935715e-05 2.15593125856072e-06 2.29101042543967e-06 1.70154850852867e-06 -1.76155840894501e-05 1.01372572862885e-06 2.15593125856072e-06 1.26613187575256e-05 -6.52885963940127e-06 3.73793440933469e-06 -4.12145178603294e-06 -3.99319958016839e-06 2.29101042543967e-06 -6.52885963940127e-06 2.46565651439213e-05 -2.44531474665726e-07 -3.11948052570459e-05 -5.90046269539126e-07 1.70154850852867e-06 3.73793440933469e-06 -2.44531474665726e-07 1.41108213997731e-05 6.62066845996782e-06 2.85969225570384e-05 -1.76155840894501e-05 -4.12145178603294e-06 -3.11948052570459e-05 6.62066845996782e-06 0.000297520461698097 3822 3858 0 34 702 3822 3858 0 51 755 0 0 0 0 0 2 10 0 3033 0 0 0 0 0 3099 +1234 1236 0.999247486973764 -0.0381056425961204 -0.0072401504787009 0.268716419801702 0.038129440508319 0.999267755628213 0.00317778669448694 0.0474015154736937 0.00711375731523515 -0.00345145825555364 0.999968740457806 0.0209192815488588 6.61607030774713e-05 -2.06513353083183e-05 3.2553613270915e-06 -1.30443711281868e-05 3.33801823194148e-06 5.05419150336378e-05 -2.06513353083183e-05 4.14637363707451e-05 -1.8982537876647e-06 5.12692514004646e-06 -2.35002299447699e-06 -1.7683070090445e-05 3.2553613270915e-06 -1.8982537876647e-06 1.28547310026982e-05 -7.79103003994967e-06 2.78205553430153e-06 6.61881821287405e-06 -1.30443711281868e-05 5.12692514004646e-06 -7.79103003994967e-06 2.40457163285079e-05 -2.20472866310172e-06 -5.69785527793247e-05 3.33801823194148e-06 -2.35002299447699e-06 2.78205553430153e-06 -2.20472866310172e-06 1.47358091728693e-05 1.29559813629045e-05 5.05419150336378e-05 -1.7683070090445e-05 6.61881821287405e-06 -5.69785527793247e-05 1.29559813629045e-05 0.000394363684604613 3822 3855 0 47 406 3822 3855 0 59 444 0 0 0 0 0 0 0 0 3219 0 0 0 0 0 3404 +1233 1235 0.998413187903997 -0.0557386221973322 -0.008019489692067 0.268080648246562 0.0556735412150966 0.99841599078011 -0.00812195562305137 0.045953621712129 0.00845949336243271 0.00766259421573018 0.999934858689273 0.0278993552299433 7.10921756431799e-05 -1.96146317551405e-05 8.24472096098352e-06 -7.76793488496726e-06 -2.18480747030153e-06 3.47702536287735e-05 -1.96146317551405e-05 4.20445630328675e-05 -1.30892303064302e-06 5.34861637169109e-06 1.74876656297151e-06 -2.62364264485432e-05 8.24472096098352e-06 -1.30892303064302e-06 1.6216218228451e-05 -5.53228469948079e-06 7.48411847162609e-06 2.29040483376039e-06 -7.76793488496726e-06 5.34861637169109e-06 -5.53228469948079e-06 2.45621369903323e-05 -1.53683611655878e-06 -1.84043860040959e-05 -2.18480747030153e-06 1.74876656297151e-06 7.48411847162609e-06 -1.53683611655878e-06 1.53517036884735e-05 4.65577232210057e-06 3.47702536287735e-05 -2.62364264485432e-05 2.29040483376039e-06 -1.84043860040959e-05 4.65577232210057e-06 0.000154716726622084 3818 3844 0 4 458 3825 3858 0 17 495 0 0 0 0 0 19 36 0 3356 0 0 0 0 0 3355 +1234 1237 0.99880446200595 -0.0374056901937299 0.0314715906514948 0.395249566385282 0.0374860773513873 0.999295212245703 -0.00196793994339949 0.0774473226230472 -0.0313757977079527 0.00314533367796028 0.999502709448175 0.049350385447064 5.78311214453195e-05 -1.06572416373385e-05 5.67533999482833e-06 -2.27758987345477e-06 1.20575226157724e-06 5.08199184909547e-06 -1.06572416373385e-05 5.18016737058961e-05 -7.59540595911388e-06 1.64386874696853e-05 -4.08724262893737e-06 -3.67691709755554e-05 5.67533999482833e-06 -7.59540595911388e-06 1.32387922107676e-05 -7.48361854044221e-06 6.36008882574172e-06 7.57821479642469e-06 -2.27758987345477e-06 1.64386874696853e-05 -7.48361854044221e-06 3.08023289767328e-05 -5.75440530527055e-07 -6.14976769901453e-05 1.20575226157724e-06 -4.08724262893737e-06 6.36008882574172e-06 -5.75440530527055e-07 1.70530151828946e-05 1.1330908320564e-05 5.08199184909547e-06 -3.67691709755554e-05 7.57821479642469e-06 -6.14976769901453e-05 1.1330908320564e-05 0.000351340653748453 3832 3857 0 110 609 3832 3857 0 127 648 0 0 0 0 0 0 0 0 2858 0 0 0 0 0 3218 +1234 1238 0.999408741828858 -0.0138163361478123 0.0314845297171585 0.525448353303697 0.0138241880946002 0.999904440843037 -3.17158954294378e-05 0.0985845435462049 -0.0314810828845688 0.000466945204027137 0.999504238801713 0.0737979483696826 8.12574316895362e-05 -1.71257810102384e-05 8.32392876336662e-06 -9.96013660580736e-06 3.86828493017673e-06 3.36660268141413e-05 -1.71257810102384e-05 5.27828363227581e-05 -3.56249627630236e-06 7.13479572848648e-06 -6.46676581543419e-07 -2.17859155181139e-05 8.32392876336662e-06 -3.56249627630236e-06 1.48406606713068e-05 -8.78498974399982e-06 4.07003331562615e-06 1.83475448209615e-06 -9.96013660580736e-06 7.13479572848648e-06 -8.78498974399982e-06 3.36765753807544e-05 -4.05879116291937e-06 -8.6122618805606e-05 3.86828493017673e-06 -6.46676581543419e-07 4.07003331562615e-06 -4.05879116291937e-06 1.92540243227162e-05 2.08494381060379e-05 3.36660268141413e-05 -2.17859155181139e-05 1.83475448209615e-06 -8.6122618805606e-05 2.08494381060379e-05 0.000511948871051924 3847 3864 0 257 761 3847 3864 0 271 809 0 0 0 0 0 0 0 0 2489 0 0 0 0 0 3057 +1235 1238 0.998493301796533 0.0144257488300195 0.052943592984898 0.392419383280891 -0.0146592953799541 0.999884443377662 0.00402553726929415 0.063988629071437 -0.0528794036125655 -0.00479558776756421 0.998589390596327 0.057237566092374 8.0771301495814e-05 -2.38103230836336e-05 4.41123666770235e-06 -8.6283124702781e-06 3.13304553502059e-06 4.86653119264295e-05 -2.38103230836336e-05 6.16425217673538e-05 3.23338261659444e-06 -1.58094345713142e-06 -3.276320729511e-06 -2.34943319939885e-05 4.41123666770235e-06 3.23338261659444e-06 1.64065849331818e-05 -9.04472745030077e-06 4.71563083153648e-06 2.88129971753124e-07 -8.6283124702781e-06 -1.58094345713142e-06 -9.04472745030077e-06 2.70823960930573e-05 2.16998403237819e-07 -3.10415341760023e-05 3.13304553502059e-06 -3.276320729511e-06 4.71563083153648e-06 2.16998403237819e-07 2.13276563732028e-05 7.75522910117077e-06 4.86653119264295e-05 -2.34943319939885e-05 2.88129971753124e-07 -3.10415341760023e-05 7.75522910117077e-06 0.000226774024175432 3847 3864 0 267 441 3847 3864 0 278 485 0 0 0 0 0 0 0 0 2912 0 0 0 0 0 3385 +1236 1240 0.994136348328582 0.107543787194426 -0.0112807254993414 0.519720305064787 -0.107782928078931 0.99390093070895 -0.0233190984091439 0.0599347464935714 0.00870409941598874 0.0243982329639549 0.999664426135887 0.0647953580595269 9.42379132418999e-05 -3.31664683001231e-05 4.02894449958036e-06 -1.2326284439858e-05 -3.90191195143396e-06 4.15722963532519e-05 -3.31664683001231e-05 6.3398503168346e-05 -4.19748071199435e-06 1.35476450854462e-05 4.17425785388554e-06 -4.8232894537078e-06 4.02894449958036e-06 -4.19748071199435e-06 1.53878146229393e-05 -1.03909028039478e-05 -6.55724712998425e-06 -1.15745245246914e-06 -1.2326284439858e-05 1.35476450854462e-05 -1.03909028039478e-05 2.7797912269266e-05 5.77192381554404e-06 -1.46345414000206e-05 -3.90191195143396e-06 4.17425785388554e-06 -6.55724712998425e-06 5.77192381554404e-06 2.66794268588544e-05 6.33417083354502e-06 4.15722963532519e-05 -4.8232894537078e-06 -1.15745245246914e-06 -1.46345414000206e-05 6.33417083354502e-06 0.00028998494835303 3872 3919 0 625 373 3872 3919 0 633 414 0 0 0 0 0 0 0 0 2368 0 0 0 0 0 3505 +1237 1241 0.988391228147576 0.140755175696838 -0.0571905642171663 0.511324311187541 -0.14120976873406 0.989971750974297 -0.00396654597317751 0.0517056434682599 0.0560587311219119 0.0119963655928092 0.998355400585165 0.12573434306202 0.000206328638713643 -5.20578914094008e-05 2.69324264143583e-05 -9.64393563604575e-06 -9.74124252406575e-06 0.000159771821589099 -5.20578914094008e-05 0.000111964520901823 -1.17291765874198e-05 8.54936422602486e-06 6.84087951440895e-07 -8.40721359656415e-05 2.69324264143583e-05 -1.17291765874198e-05 1.91812400001621e-05 -7.43516216612856e-06 -2.42833487217035e-06 1.36066364036152e-05 -9.64393563604575e-06 8.54936422602486e-06 -7.43516216612856e-06 2.33230335910892e-05 -5.88374461899211e-06 -5.30033261819701e-05 -9.74124252406575e-06 6.84087951440895e-07 -2.42833487217035e-06 -5.88374461899211e-06 2.2598453482952e-05 -1.02625730659123e-06 0.000159771821589099 -8.40721359656415e-05 1.36066364036152e-05 -5.30033261819701e-05 -1.02625730659123e-06 0.00073605947757032 3863 3906 0 666 263 3863 3906 0 668 292 0 0 0 0 0 0 0 0 2258 0 0 0 0 0 3634 +1237 1240 0.993107308402958 0.107667086783826 -0.0463214034773964 0.392203017486159 -0.10855744571167 0.993942263471159 -0.0171481155346015 0.0392918296132656 0.0441945129760412 0.0220584521060369 0.998779389912255 0.0582909402300508 0.000193069816798738 -2.55812893360633e-05 1.39541103952297e-05 -2.5057113540797e-05 1.56589065136447e-06 0.000213319255695059 -2.55812893360633e-05 5.77887539836603e-05 -1.72608108481741e-06 2.08750673554732e-05 -7.7062054700248e-07 -0.000121321583757782 1.39541103952297e-05 -1.72608108481741e-06 1.48704838144373e-05 -8.68910798519129e-06 -1.32452096168208e-06 5.13258274309364e-06 -2.5057113540797e-05 2.08750673554732e-05 -8.68910798519129e-06 4.933462650206e-05 -8.5200075315875e-06 -0.000194889217654019 1.56589065136447e-06 -7.7062054700248e-07 -1.32452096168208e-06 -8.5200075315875e-06 2.45282122637559e-05 5.89287274854282e-05 0.000213319255695059 -0.000121321583757782 5.13258274309364e-06 -0.000194889217654019 5.89287274854282e-05 0.00152057782600936 3872 3919 0 551 177 3872 3919 0 555 200 0 0 0 0 0 0 0 0 2546 0 0 0 0 0 3711 +1238 1241 0.991289941828033 0.117674441800554 -0.0591352431085162 0.385478036476683 -0.118137976900171 0.992987475181577 -0.00439232813571945 0.041531029572324 0.0582036909869986 0.0113401886864868 0.998240316995885 0.0603408130141334 8.10175123564803e-05 -1.68355243594307e-06 9.00428971231859e-06 -1.89460185953827e-06 -6.12832619882069e-06 5.89042201938033e-05 -1.68355243594307e-06 7.30064578706244e-05 -5.11836048782652e-06 1.02630841135572e-05 -5.05866558237154e-06 -1.19762764791113e-05 9.00428971231859e-06 -5.11836048782652e-06 1.47230345672423e-05 -7.90356803730373e-06 -1.60302288870451e-06 6.1038366969244e-06 -1.89460185953827e-06 1.02630841135572e-05 -7.90356803730373e-06 1.94715052909045e-05 -2.30388970987603e-06 -1.06669864510799e-05 -6.12832619882069e-06 -5.05866558237154e-06 -1.60302288870451e-06 -2.30388970987603e-06 1.90052039174997e-05 -2.50591897955714e-06 5.89042201938033e-05 -1.19762764791113e-05 6.1038366969244e-06 -1.06669864510799e-05 -2.50591897955714e-06 0.000200310774809222 3863 3906 0 556 150 3863 3906 0 554 173 0 0 0 0 0 0 0 0 2644 0 0 0 0 0 3739 +1238 1240 0.995231592949109 0.0841919115174076 -0.0492523951805718 0.259347330196481 -0.0850829091981577 0.996240882435388 -0.0162789043469482 0.0288288816990034 0.0476966975623707 0.0203918169716198 0.998653693150053 0.034155019416797 8.68854007314576e-05 1.72224278831851e-05 -1.59496053414255e-06 -2.58628880537996e-06 -4.79903922826222e-06 7.46672472817742e-05 1.72224278831851e-05 5.19031425476433e-05 -1.6115904790574e-06 6.78221142087884e-06 1.59329187108999e-06 1.1829313912744e-05 -1.59496053414255e-06 -1.6115904790574e-06 1.22745805779727e-05 -6.98614390766986e-06 -1.25715607022282e-07 -2.43207511168028e-06 -2.58628880537996e-06 6.78221142087884e-06 -6.98614390766986e-06 2.17797006733675e-05 -9.69633799968961e-07 -2.11935563818915e-05 -4.79903922826222e-06 1.59329187108999e-06 -1.25715607022282e-07 -9.69633799968961e-07 1.66053548681022e-05 1.94666828409061e-06 7.46672472817742e-05 1.1829313912744e-05 -2.43207511168028e-06 -2.11935563818915e-05 1.94666828409061e-06 0.00025110040449624 3872 3919 0 402 69 3872 3919 0 399 95 0 0 0 0 0 0 0 0 2947 0 0 0 0 0 3819 +1240 1244 0.993236124824251 0.104516889125872 0.050578851623524 0.495339919359524 -0.105147661789793 0.994406662317833 0.00996790640238146 0.0903600178583845 -0.0492541324585427 -0.0152187327119386 0.998670326289111 0.0853841872117013 5.73925502923123e-05 7.95654263623408e-06 6.10746645013876e-06 -9.54221348186292e-06 -3.57747178725249e-07 3.55058024770924e-05 7.95654263623408e-06 5.62688419107245e-05 2.58089435973009e-08 7.86007437673097e-06 5.47316437445035e-06 3.82667104626925e-05 6.10746645013876e-06 2.58089435973009e-08 1.70535825138699e-05 -9.79236516088045e-06 -7.51879433229649e-06 2.80636305353204e-06 -9.54221348186292e-06 7.86007437673097e-06 -9.79236516088045e-06 2.47655015009975e-05 3.54112470269393e-06 -1.49274903437014e-05 -3.57747178725249e-07 5.47316437445035e-06 -7.51879433229649e-06 3.54112470269393e-06 2.11565585177634e-05 2.08621950247437e-06 3.55058024770924e-05 3.82667104626925e-05 2.80636305353204e-06 -1.49274903437014e-05 2.08621950247437e-06 0.000146073540463864 3828 3859 0 516 409 3828 3859 0 537 447 0 0 0 0 0 0 0 0 2681 0 0 0 0 0 3467 +1241 1243 0.995991535942229 0.0625714135090636 0.0639193127537983 0.23893716166428 -0.0647157600109421 0.997389080604962 0.0320451602616349 0.0551425063072942 -0.061747313606717 -0.0360532952927398 0.997440438903942 0.0961039739686645 4.511431691167e-05 4.10791011464787e-07 4.07505420021207e-06 -4.44685046027453e-06 8.057981165655e-08 2.8071099541728e-05 4.10791011464787e-07 6.60258704770213e-05 -1.88151641983459e-07 -3.44666990007175e-06 -6.07348219351613e-06 2.39337577657878e-05 4.07505420021207e-06 -1.88151641983459e-07 1.43116516869495e-05 -9.50543992758819e-06 -7.97611424296354e-06 5.15242189022616e-06 -4.44685046027453e-06 -3.44666990007175e-06 -9.50543992758819e-06 2.09477912156536e-05 4.20916208716717e-06 -2.11966746782635e-05 8.057981165655e-08 -6.07348219351613e-06 -7.97611424296354e-06 4.20916208716717e-06 2.03878425416893e-05 -4.51188685661178e-06 2.8071099541728e-05 2.39337577657878e-05 5.15242189022616e-06 -2.11966746782635e-05 -4.51188685661178e-06 0.000136519165006893 3840 3873 0 282 150 3840 3873 0 298 181 0 0 0 0 0 0 0 0 3235 0 0 0 0 0 3599 +1241 1244 0.995725006640876 0.0725774854429851 0.0571333506526755 0.371224273198737 -0.0730334436679109 0.997311858552932 0.00593067413557743 0.0795295544135831 -0.0565493347090343 -0.0100779658894839 0.998348940675301 0.0468772810622471 4.75006824714944e-05 1.36616115951866e-05 4.91284186041273e-06 -1.59323412506994e-06 -1.68415147961974e-06 1.95282617826183e-05 1.36616115951866e-05 8.47044860790726e-05 -2.63863112245353e-06 -1.29500394270071e-06 -1.24845694989113e-06 5.96859833703835e-05 4.91284186041273e-06 -2.63863112245353e-06 1.7729203047242e-05 -9.39524892494585e-06 -5.91603358606033e-06 -1.57027967629816e-06 -1.59323412506994e-06 -1.29500394270071e-06 -9.39524892494585e-06 2.38430797239374e-05 2.12078196118635e-06 -2.26831570565058e-05 -1.68415147961974e-06 -1.24845694989113e-06 -5.91603358606033e-06 2.12078196118635e-06 1.95253751990347e-05 1.93167569225527e-06 1.95282617826183e-05 5.96859833703835e-05 -1.57027967629816e-06 -2.26831570565058e-05 1.93167569225527e-06 0.0001878556870303 3828 3859 0 369 306 3828 3859 0 385 351 0 0 0 0 0 0 0 0 3000 0 0 0 0 0 3563 +1242 1244 0.998735500438392 0.0316434857254727 0.039065201589352 0.241011568154759 -0.0325157577118763 0.999231288857801 0.0218987869070665 0.0663863608654742 -0.0383422177827191 -0.0231413305304677 0.998996673246104 0.0724018212024116 4.43463719190809e-05 5.93558300040098e-06 8.82451106251908e-08 3.32544149465979e-06 1.1327936936977e-06 -4.5231991034754e-06 5.93558300040098e-06 8.81700045509954e-05 -8.12168386204907e-06 9.64506759769532e-06 -5.28685405136362e-06 -4.10057972194864e-06 8.82451106251908e-08 -8.12168386204907e-06 1.81917017831293e-05 -9.06168007575879e-06 -5.17770477910082e-06 -5.97965768332195e-06 3.32544149465979e-06 9.64506759769532e-06 -9.06168007575879e-06 2.48993585812032e-05 -6.04749729198913e-07 -3.63382129865715e-05 1.1327936936977e-06 -5.28685405136362e-06 -5.17770477910082e-06 -6.04749729198913e-07 2.21962034692047e-05 2.88013472256774e-06 -4.5231991034754e-06 -4.10057972194864e-06 -5.97965768332195e-06 -3.63382129865715e-05 2.88013472256774e-06 0.000224840943930249 3828 3859 0 195 236 3828 3859 0 200 266 0 0 0 0 0 0 0 0 3325 0 0 0 0 0 3642 +1243 1245 0.99897101753425 0.0411185286234837 -0.0191356403191637 0.249617229708532 -0.0414336880454789 0.999007055305657 -0.0163753761627251 0.0679294315801668 0.0184433083131686 0.0171513863393183 0.999682786850461 0.0815752700550506 5.46008284008823e-05 1.92445868967266e-05 1.87110495317442e-06 2.44851537643913e-06 -4.7108571041498e-06 2.00203424211363e-05 1.92445868967266e-05 6.27160578045158e-05 -6.41169604003219e-06 7.42347114387873e-07 -1.52146643995836e-06 4.54458230528966e-05 1.87110495317442e-06 -6.41169604003219e-06 1.68379802501674e-05 -8.07049880612447e-06 -5.23746971300987e-06 -3.21334209345025e-06 2.44851537643913e-06 7.42347114387873e-07 -8.07049880612447e-06 1.62237600240078e-05 -1.78701727073688e-06 -1.23699288706978e-05 -4.7108571041498e-06 -1.52146643995836e-06 -5.23746971300987e-06 -1.78701727073688e-06 1.94217523013987e-05 2.08278584751716e-06 2.00203424211363e-05 4.54458230528966e-05 -3.21334209345025e-06 -1.23699288706978e-05 2.08278584751716e-06 0.000190347916326623 3840 3864 0 229 223 3840 3864 0 229 261 0 0 0 0 0 0 0 0 3166 0 0 0 0 0 3650 +1243 1246 0.997792028885758 0.0614656484513914 -0.0251603090699009 0.368435683677269 -0.0618025674143126 0.998005812203308 -0.0128390603010652 0.0945515021817489 0.0243209735216813 0.0143656837242439 0.999600979080199 0.123645543516156 6.60906247786793e-05 1.12086299574542e-05 7.68655616804714e-06 1.90335411152209e-07 -6.57771343193049e-06 1.88925694022323e-05 1.12086299574542e-05 4.33265357170574e-05 1.01399677671685e-06 4.48666232651543e-06 -6.4746370800184e-06 4.46719844583482e-06 7.68655616804714e-06 1.01399677671685e-06 2.05635127131113e-05 -5.93522384319854e-06 -8.00703565882357e-06 6.25203232127319e-06 1.90335411152209e-07 4.48666232651543e-06 -5.93522384319854e-06 1.86828340993595e-05 -1.03053479051036e-06 -1.36745923989768e-05 -6.57771343193049e-06 -6.4746370800184e-06 -8.00703565882357e-06 -1.03053479051036e-06 2.18554599945943e-05 -1.73780687549464e-06 1.88925694022323e-05 4.46719844583482e-06 6.25203232127319e-06 -1.36745923989768e-05 -1.73780687549464e-06 0.000156858689370468 3829 3849 0 362 356 3829 3849 0 361 399 0 0 0 0 0 0 0 0 2950 0 0 0 0 0 3507 +1244 1246 0.998398468652231 0.0511441562024323 -0.0241820817801318 0.243990498460527 -0.0513963975403674 0.998628996072921 -0.00992665715445983 0.0625727347918 0.0236412375469706 0.0111536311903737 0.999658285814966 0.095087212680433 0.00012110137425308 6.04723676849063e-05 1.01415075386327e-05 -8.14531018144987e-06 -1.05640520762663e-05 9.96490236701531e-05 6.04723676849063e-05 8.87178735735062e-05 7.61971265503493e-06 3.57879753270541e-06 -7.35429308881665e-06 7.37366157421755e-05 1.01415075386327e-05 7.61971265503493e-06 2.07731840404385e-05 -7.25384134981095e-06 -7.15358310709394e-06 1.05842128003637e-05 -8.14531018144987e-06 3.57879753270541e-06 -7.25384134981095e-06 2.26016453321705e-05 -1.30794091539658e-06 -2.2414238628451e-05 -1.05640520762663e-05 -7.35429308881665e-06 -7.15358310709394e-06 -1.30794091539658e-06 2.12755283658677e-05 -1.02376967664432e-05 9.96490236701531e-05 7.37366157421755e-05 1.05842128003637e-05 -2.2414238628451e-05 -1.02376967664432e-05 0.000271775166368519 3829 3849 0 261 185 3829 3849 0 250 226 0 0 0 0 0 0 0 0 3016 0 0 0 0 0 3671 +1244 1247 0.995958652943638 0.0897983780089986 -0.0016164571281665 0.36576238692619 -0.0898129141336968 0.995806343852097 -0.0174174050516394 0.096086490127465 4.56235400301838e-05 0.0174921939982573 0.999846998829131 0.0927393606519688 4.01277367715339e-05 2.19400433070074e-05 3.38287227507909e-06 2.38582021621408e-06 -7.28010765479338e-06 2.53136584475841e-06 2.19400433070074e-05 5.19764341585372e-05 3.29220460584358e-06 -2.07271698152748e-06 -3.72469927927375e-06 5.25040536172029e-05 3.38287227507909e-06 3.29220460584358e-06 2.09568063213265e-05 -6.93105108053676e-06 -6.80795571358066e-06 1.32146521914789e-06 2.38582021621408e-06 -2.07271698152748e-06 -6.93105108053676e-06 1.76114810591207e-05 -1.76376714143182e-06 -9.82293511926219e-06 -7.28010765479338e-06 -3.72469927927375e-06 -6.80795571358066e-06 -1.76376714143182e-06 1.9901580490573e-05 4.12466814607507e-06 2.53136584475841e-06 5.25040536172029e-05 1.32146521914789e-06 -9.82293511926219e-06 4.12466814607507e-06 0.000159206142942301 3838 3847 0 447 285 3838 3847 0 441 329 0 0 0 0 0 0 0 0 2971 0 0 0 0 0 3542 +1245 1247 0.997970740410221 0.0596144265670871 0.0223723362694412 0.236456055263617 -0.0595252242699433 0.998216051432344 -0.00463274631639339 0.0697962487083791 -0.0226086036872808 0.00329162693762276 0.999738974048434 0.0750933056299758 5.21151295298728e-05 4.04343295996229e-06 8.22900291915151e-06 -4.92227621612386e-06 7.96047698823486e-07 2.80967909995214e-05 4.04343295996229e-06 8.04366261103665e-05 3.36301069742862e-06 2.09047849525194e-06 3.73888384877818e-06 2.96395201691775e-05 8.22900291915151e-06 3.36301069742862e-06 1.95908464126021e-05 -1.0335158712158e-05 4.84685087195826e-07 8.0147493300513e-06 -4.92227621612386e-06 2.09047849525194e-06 -1.0335158712158e-05 1.7879083110733e-05 -2.09704170394879e-06 -1.57091436417382e-05 7.96047698823486e-07 3.73888384877818e-06 4.84685087195826e-07 -2.09704170394879e-06 1.9508208466688e-05 5.79968246563752e-06 2.80967909995214e-05 2.96395201691775e-05 8.0147493300513e-06 -1.57091436417382e-05 5.79968246563752e-06 0.000128553773932531 3838 3847 0 279 165 3838 3847 0 270 201 0 0 0 0 0 0 0 0 3268 0 0 0 0 0 3664 +1245 1249 0.986559576858666 0.160330600241569 0.0315325218564606 0.472085280456081 -0.159782201320422 0.986965165552792 -0.019220044915383 0.128593034857764 -0.034203061992312 0.0139233836235152 0.999317912347628 0.162456768617575 3.97440980274683e-05 1.32776948652535e-05 2.9151019015797e-06 -2.17596255199514e-06 3.07003343600407e-06 1.34676797851169e-05 1.32776948652535e-05 5.82578581823745e-05 5.99881876196847e-06 -4.1127120007269e-06 -4.79628681540946e-07 3.05511146017761e-05 2.9151019015797e-06 5.99881876196847e-06 1.63008129124873e-05 -7.6212367527144e-06 -7.68075553260461e-06 3.44505985209934e-06 -2.17596255199514e-06 -4.1127120007269e-06 -7.6212367527144e-06 2.08145687012574e-05 -1.39677826487938e-06 -1.13098995005433e-05 3.07003343600407e-06 -4.79628681540946e-07 -7.68075553260461e-06 -1.39677826487938e-06 1.77175996855843e-05 -4.98607897397428e-06 1.34676797851169e-05 3.05511146017761e-05 3.44505985209934e-06 -1.13098995005433e-05 -4.98607897397428e-06 0.000123202417830508 3838 3829 0 723 307 3838 3829 0 715 346 0 0 0 0 0 0 0 0 2656 0 0 0 0 0 3399 +1246 1249 0.989761674365676 0.138042814803191 0.0362768416219591 0.350135475876535 -0.137310420887861 0.990284358965172 -0.0219712699800861 0.0999503013313971 -0.0389573648037348 0.0167651325718369 0.99910022222868 0.11664708126068 4.2539071309977e-05 7.78852443616645e-06 1.37735426232607e-06 7.29582449933428e-07 1.09174193371464e-06 1.29684131233829e-05 7.78852443616645e-06 6.74466555095858e-05 4.10529002818177e-07 1.62768746093074e-06 -7.38007185426927e-06 1.87661337953761e-05 1.37735426232607e-06 4.10529002818177e-07 2.25067899791935e-05 -5.38799746506515e-06 -7.69010284905179e-06 -4.91075624367744e-07 7.29582449933428e-07 1.62768746093074e-06 -5.38799746506515e-06 2.11844271767793e-05 -1.10574958675748e-06 -6.60818938500811e-06 1.09174193371464e-06 -7.38007185426927e-06 -7.69010284905179e-06 -1.10574958675748e-06 1.91862787665359e-05 -7.55896549977017e-07 1.29684131233829e-05 1.87661337953761e-05 -4.91075624367744e-07 -6.60818938500811e-06 -7.55896549977017e-07 9.09859678965865e-05 3838 3829 0 581 159 3838 3829 0 564 205 0 0 0 0 0 0 0 0 2753 0 0 0 0 0 3546 +1246 1250 0.98345713088238 0.180815490136394 0.0108549639949984 0.464866953340112 -0.180603939866443 0.983390228996619 -0.0180519920977176 0.123320012452559 -0.0139387453278786 0.0157929110905277 0.999778123054296 0.147803373312553 5.88535015883284e-05 2.54744748420538e-05 1.58642539789817e-05 1.69266979381966e-06 7.06336298911904e-06 -1.72138283625429e-05 2.54744748420538e-05 5.17618407224486e-05 1.44764216174037e-05 -1.53753031889548e-06 5.71575255990425e-06 1.10083500976043e-05 1.58642539789817e-05 1.44764216174037e-05 2.0424784440064e-05 -2.84574400112369e-06 -3.1373543206331e-06 1.47885662711585e-06 1.69266979381966e-06 -1.53753031889548e-06 -2.84574400112369e-06 2.8133984879874e-05 -5.31124698014374e-06 -5.36084550936972e-05 7.06336298911904e-06 5.71575255990425e-06 -3.1373543206331e-06 -5.31124698014374e-06 2.07788076471619e-05 -1.68703719969937e-06 -1.72138283625429e-05 1.10083500976043e-05 1.47885662711585e-06 -5.36084550936972e-05 -1.68703719969937e-06 0.00033222920583577 3834 3810 0 801 245 3834 3810 0 785 299 0 0 0 0 0 0 0 0 2403 0 0 0 0 0 3397 +1247 1251 0.984524615193157 0.171114808072415 -0.0378286206080208 0.442896114619912 -0.171301729790593 0.985217090791083 -0.00173245026049813 0.117693193361346 0.0369729556502538 0.00818574807180426 0.999282739808403 0.200331443667278 5.45695986153798e-05 2.35936820367e-05 5.75555230213831e-06 4.48882421885559e-06 -9.01119189183093e-06 -4.70982383911672e-06 2.35936820367e-05 6.2115587365311e-05 2.33910374176449e-06 2.53319037404608e-06 -4.53892573147283e-06 1.08404529021796e-05 5.75555230213831e-06 2.33910374176449e-06 1.74442022266639e-05 -6.57529086434928e-06 -6.10499661989396e-06 -2.17783257770264e-06 4.48882421885559e-06 2.53319037404608e-06 -6.57529086434928e-06 2.02745548251319e-05 -6.35991386054572e-06 -2.4479832097551e-05 -9.01119189183093e-06 -4.53892573147283e-06 -6.10499661989396e-06 -6.35991386054572e-06 2.02932764521866e-05 4.41058948978891e-06 -4.70982383911672e-06 1.08404529021796e-05 -2.17783257770264e-06 -2.4479832097551e-05 4.41058948978891e-06 0.000226631516524634 3823 3789 0 794 246 3823 3789 0 763 294 0 0 0 0 0 0 0 0 2381 0 0 0 0 0 3250 +1248 1251 0.990513785706061 0.123944798885228 -0.0593306594902522 0.321116316324406 -0.124598384174377 0.992179424250079 -0.00743187432048564 0.091686921812228 0.0579455174054231 0.0147538782725615 0.998210719281523 0.167100791805447 5.49989028626616e-05 2.19308841516591e-05 4.72766828870029e-06 4.7701185518005e-06 -7.01209197579293e-06 -1.0932425586384e-05 2.19308841516591e-05 7.10652492849031e-05 5.16596941952061e-06 3.71526648403768e-06 -1.0702598267551e-06 2.20461194512318e-05 4.72766828870029e-06 5.16596941952061e-06 1.72397284546943e-05 -7.8058532303944e-06 -8.32815412612159e-06 1.02500341436312e-05 4.7701185518005e-06 3.71526648403768e-06 -7.8058532303944e-06 2.07531098861699e-05 -1.53660426179414e-06 -3.31560871150192e-05 -7.01209197579293e-06 -1.0702598267551e-06 -8.32815412612159e-06 -1.53660426179414e-06 1.82660683573373e-05 3.13977522040986e-06 -1.0932425586384e-05 2.20461194512318e-05 1.02500341436312e-05 -3.31560871150192e-05 3.13977522040986e-06 0.000360849642127842 3823 3789 0 575 158 3823 3789 0 524 209 0 0 0 0 0 0 0 0 2684 0 0 0 0 0 3529 +1248 1250 0.995055258540767 0.0958614300385831 -0.0259926659141415 0.219797564262378 -0.0960245018353342 0.995365920405604 -0.00509701308410529 0.0678570398772277 0.0253836068682571 0.00756774246796777 0.999649139336546 0.120789351882236 3.42301144747724e-05 1.3890612367374e-05 7.23493253077072e-06 -3.76951992634514e-07 -1.85805185748933e-06 7.99354071117117e-06 1.3890612367374e-05 3.71090312968531e-05 8.04526407527422e-06 1.24456523382174e-06 -7.80374950169559e-07 1.74476879118468e-06 7.23493253077072e-06 8.04526407527422e-06 1.67383609790882e-05 -4.14264219925282e-06 -9.79483722816097e-06 2.94394502631326e-06 -3.76951992634514e-07 1.24456523382174e-06 -4.14264219925282e-06 2.11112409896008e-05 2.49559008867555e-07 -2.36598954884866e-05 -1.85805185748933e-06 -7.80374950169559e-07 -9.79483722816097e-06 2.49559008867555e-07 1.96947596389785e-05 -1.18766112750722e-05 7.99354071117117e-06 1.74476879118468e-06 2.94394502631326e-06 -2.36598954884866e-05 -1.18766112750722e-05 0.000206029291273746 3834 3810 0 397 61 3834 3810 0 349 109 0 0 0 0 0 0 0 0 2973 0 0 0 0 0 3678 +1249 1251 0.995595127390889 0.0694185705782997 -0.0630190794473078 0.195844077814042 -0.0690275921102398 0.997579697779094 0.00836290059928752 0.0676208854660379 0.063447094834853 -0.00397600777625343 0.997977283067696 0.160629297236929 6.62663618754649e-05 3.10696447002931e-05 8.97747875813641e-06 2.93261232179282e-06 -2.66637717838038e-06 -2.85805224301382e-05 3.10696447002931e-05 9.02487628918701e-05 6.06843974001497e-06 3.43564454807252e-06 3.70220291544336e-08 3.20841622416041e-05 8.97747875813641e-06 6.06843974001497e-06 2.19391593268864e-05 -8.52503152092183e-06 -1.10794715484343e-05 -4.35477181845759e-06 2.93261232179282e-06 3.43564454807252e-06 -8.52503152092183e-06 1.99531711196847e-05 1.34222683762505e-06 -2.86282386565587e-05 -2.66637717838038e-06 3.70220291544336e-08 -1.10794715484343e-05 1.34222683762505e-06 2.1030040036109e-05 -6.89870688883354e-07 -2.85805224301382e-05 3.20841622416041e-05 -4.35477181845759e-06 -2.86282386565587e-05 -6.89870688883354e-07 0.000404764203450501 3823 3789 0 305 91 3823 3789 0 236 145 0 0 0 0 0 0 0 0 3149 0 0 0 0 0 3642 +1249 1253 0.986918285477663 0.113236092171185 -0.114760120336418 0.387320102406506 -0.114916048902514 0.993342110482443 -0.00810883758137556 0.103461903327037 0.113077847054431 0.0211905396836663 0.993360136875569 0.268213071773748 7.91033632294748e-05 5.07151202731037e-05 1.7705423280848e-06 -4.46611365281197e-07 -3.83523887014983e-06 6.94109217944859e-05 5.07151202731037e-05 0.000145704596415354 2.48320656303703e-07 6.81474452089192e-06 -2.64805442901494e-06 4.2308896773767e-05 1.7705423280848e-06 2.48320656303703e-07 1.91656553616638e-05 -5.61834003678977e-06 -4.38318859039408e-06 3.46737883440286e-06 -4.46611365281197e-07 6.81474452089192e-06 -5.61834003678977e-06 2.08914852770188e-05 -5.15235193845531e-06 -3.00573797604483e-06 -3.83523887014983e-06 -2.64805442901494e-06 -4.38318859039408e-06 -5.15235193845531e-06 2.03409858085516e-05 -3.91937321201868e-06 6.94109217944859e-05 4.2308896773767e-05 3.46737883440286e-06 -3.00573797604483e-06 -3.91937321201868e-06 0.000126277909605676 3336 3279 0 594 270 3336 3279 0 528 322 0 0 0 0 0 0 0 0 2390 0 0 0 0 0 3129 +1250 1253 0.993638503768872 0.0717273073247292 -0.0868200277119405 0.276927991018892 -0.0720917342235927 0.997397436815491 -0.00106531240670453 0.0795543909124673 0.0865176611137468 0.00731754178893847 0.99622344275648 0.249591886311465 7.33950919931954e-05 5.95829307107083e-05 -1.21102273077757e-06 1.36231511142408e-06 -8.78350512894106e-06 -1.5950092477385e-06 5.95829307107083e-05 0.000147249624939767 2.18971404624259e-06 4.65680581194142e-06 -1.04593460717355e-05 3.38509437384143e-05 -1.21102273077757e-06 2.18971404624259e-06 1.76726448957384e-05 -4.52605283279631e-06 -7.27634361870922e-06 -3.67418174290118e-06 1.36231511142408e-06 4.65680581194142e-06 -4.52605283279631e-06 1.85057972452787e-05 -2.21948832577935e-06 -1.52825814761962e-05 -8.78350512894106e-06 -1.04593460717355e-05 -7.27634361870922e-06 -2.21948832577935e-06 2.12282285885598e-05 -1.13528176066289e-05 -1.5950092477385e-06 3.38509437384143e-05 -3.67418174290118e-06 -1.52825814761962e-05 -1.13528176066289e-05 0.000400483861594673 3336 3279 0 392 199 3336 3279 0 314 255 0 0 0 0 0 0 0 0 2902 0 0 0 0 0 3206 +1249 1317 0.885969216103667 0.428925105104497 -0.176300318569619 0.742495231824346 -0.42976572546026 0.902247078813159 0.035378383127801 0.171443853035463 0.174241124124787 0.044423675942194 0.983700446111271 1.08267477209316 0.00210747492944967 0.000719465856911021 0.000351495253390536 -0.000379305980597429 0.000286933294771828 0.00120374585263337 0.000719465856911021 0.0008028818837174 0.000219394540945877 -0.000229196288572477 0.000204444028157308 0.000892524281373436 0.000351495253390536 0.000219394540945877 0.00014746397238745 -0.000119320423630899 9.97784885179992e-05 0.000302214436448236 -0.000379305980597429 -0.000229196288572477 -0.000119320423630899 0.00016631961817351 -6.9054375066248e-05 -0.00030709229893587 0.000286933294771828 0.000204444028157308 9.97784885179992e-05 -6.9054375066248e-05 0.000254375889238097 0.000268900899756049 0.00120374585263337 0.000892524281373436 0.000302214436448236 -0.00030709229893587 0.000268900899756049 0.00129787373223954 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 180 0 0 0 0 0 314 +1250 1314 0.907372378395174 0.391234575869958 -0.153658301335589 0.665669486289056 -0.388774493131786 0.920132530583453 0.0470161637334743 0.175275628609143 0.159780350530369 0.0170772599073755 0.987004866643751 0.978232168472136 0.000444005101306514 0.000171724954760694 1.61421567918753e-05 -0.000142536727442268 -7.20251681090099e-05 0.000270164862430524 0.000171724954760694 0.000288611017258293 1.62844692374599e-05 -0.000122706273884155 -3.22052889224266e-05 0.000228005648398659 1.61421567918753e-05 1.62844692374599e-05 4.31700896450823e-05 -2.15333551345059e-05 7.60470944714032e-06 4.77606264766636e-05 -0.000142536727442268 -0.000122706273884155 -2.15333551345059e-05 0.00013908310900447 2.08660423931221e-05 -0.000145830117633465 -7.20251681090099e-05 -3.22052889224266e-05 7.60470944714032e-06 2.08660423931221e-05 0.000140744943388412 -4.67313266993224e-06 0.000270164862430524 0.000228005648398659 4.77606264766636e-05 -0.000145830117633465 -4.67313266993224e-06 0.000458613571910309 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 248 0 0 0 0 0 253 +1250 1254 0.990217132650557 0.0987288990638217 -0.0986034213146485 0.360658938852281 -0.100340253969799 0.994886644299699 -0.0115064515537807 0.0959321331465213 0.0969632076541642 0.0212877778015702 0.995060283037006 0.29905279885422 9.8484311247593e-05 7.29385434794947e-05 1.6021107599373e-05 -1.30540878420615e-06 -1.79452248874498e-06 4.44050862704842e-05 7.29385434794947e-05 0.000132565938798177 1.44167409207659e-05 1.11304393098327e-08 2.30364856758769e-06 2.66280763296903e-05 1.6021107599373e-05 1.44167409207659e-05 1.77419977724944e-05 -7.11719643847041e-06 -6.96035280856909e-06 1.22582145833389e-05 -1.30540878420615e-06 1.11304393098327e-08 -7.11719643847041e-06 2.08860012083439e-05 -1.15384568753185e-06 -4.35076427883191e-06 -1.79452248874498e-06 2.30364856758769e-06 -6.96035280856909e-06 -1.15384568753185e-06 1.92707416556197e-05 -7.05101243697822e-06 4.44050862704842e-05 2.66280763296903e-05 1.22582145833389e-05 -4.35076427883191e-06 -7.05101243697822e-06 0.000160700775250208 2672 2607 0 540 232 2672 2607 0 453 281 0 0 0 0 0 0 0 0 2674 0 0 0 0 0 2709 +1250 1252 0.996956470574157 0.0475470928695214 -0.0617824387668284 0.190733706410222 -0.0474809655159344 0.998868916361566 0.00253886595662425 0.0632010608923059 0.0618332733566196 0.000402351001201116 0.99808641129898 0.177778508451804 5.04855651067591e-05 2.57903399486394e-05 -1.13008702903614e-06 1.69483148083242e-06 -5.37926267867492e-06 9.35430699923882e-06 2.57903399486394e-05 8.73193124695665e-05 3.67128604211963e-06 6.56203596336947e-06 -5.39660095451891e-06 3.66169440030223e-05 -1.13008702903614e-06 3.67128604211963e-06 1.79065383297859e-05 -5.1033419215554e-06 -1.07443325366253e-05 2.88711118893263e-06 1.69483148083242e-06 6.56203596336947e-06 -5.1033419215554e-06 1.88348587083763e-05 -3.17678834930613e-07 -7.31806950303732e-06 -5.37926267867492e-06 -5.39660095451891e-06 -1.07443325366253e-05 -3.17678834930613e-07 1.94355271307884e-05 -7.918030813171e-06 9.35430699923882e-06 3.66169440030223e-05 2.88711118893263e-06 -7.31806950303732e-06 -7.918030813171e-06 0.000208602214213369 3777 3729 0 260 142 3777 3729 0 172 203 0 0 0 0 0 0 0 0 3377 0 0 0 0 0 3622 +1251 1297 0.923857339599608 0.353825956563552 -0.145927408425633 0.586770074418958 -0.363248941957593 0.930695830902318 -0.0430752423989999 0.104988504839333 0.120572891790083 0.0928033555585731 0.988357078672706 0.892004148808758 0.000195686986279977 7.46676566240171e-05 3.09816852577762e-06 -2.69070095027945e-05 1.4228815650965e-05 0.00013076126671818 7.46676566240171e-05 0.000277114415728432 -1.00134317476027e-06 -4.63496724674979e-05 4.21561086057554e-06 0.000281687864965937 3.09816852577762e-06 -1.00134317476027e-06 3.07693879460164e-05 -5.30803680213858e-06 2.70587994044362e-06 2.18930429115051e-05 -2.69070095027945e-05 -4.63496724674979e-05 -5.30803680213858e-06 8.01241189857228e-05 3.21243651534781e-06 -3.77911418160769e-05 1.4228815650965e-05 4.21561086057554e-06 2.70587994044362e-06 3.21243651534781e-06 8.63686805046025e-05 5.31726344564087e-05 0.00013076126671818 0.000281687864965937 2.18930429115051e-05 -3.77911418160769e-05 5.31726344564087e-05 0.00047964679150728 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 211 0 0 0 0 0 685 +1251 1254 0.99603309368646 0.0721976004197347 -0.0520152167640496 0.271183632947586 -0.072958002119036 0.99725198345783 -0.0128690099162126 0.0702953713172475 0.0509431664522091 0.0166128860544206 0.998563370952873 0.203328275035844 5.24910753270873e-05 3.47882420665261e-05 3.13666743949145e-06 -1.34165007207364e-06 -4.66213746332869e-07 3.55566525126933e-05 3.47882420665261e-05 7.59100226673364e-05 3.43415440106761e-06 -2.04694926145641e-06 -2.84338534086126e-06 3.78595759689044e-05 3.13666743949145e-06 3.43415440106761e-06 1.22193496499209e-05 -4.82305308988066e-06 -5.48234844077771e-06 6.14606994168593e-06 -1.34165007207364e-06 -2.04694926145641e-06 -4.82305308988066e-06 1.76362451066386e-05 -6.62237563871205e-07 -6.89349653180838e-06 -4.66213746332869e-07 -2.84338534086126e-06 -5.48234844077771e-06 -6.62237563871205e-07 1.48019864248087e-05 1.55843363320293e-06 3.55566525126933e-05 3.78595759689044e-05 6.14606994168593e-06 -6.89349653180838e-06 1.55843363320293e-06 0.00013202215953158 3336 3261 0 433 181 3336 3261 0 331 234 0 0 0 0 0 0 0 0 3195 0 0 0 0 0 3155 +1251 1253 0.997963596002913 0.0436244948919837 -0.0465356261197269 0.185020507433493 -0.0438724169188008 0.999027805667571 -0.00431908980473916 0.0512724909326313 0.0463019663366324 0.00635192478369911 0.998907293478681 0.161795371713415 6.17051584373352e-05 2.53185151985701e-05 -4.68074142666395e-06 9.52288259229213e-07 -7.40617132833325e-06 3.62326356318732e-05 2.53185151985701e-05 0.000116252560069188 1.62903423931068e-06 7.19814627405624e-06 -2.71068657707412e-06 6.52798689483375e-06 -4.68074142666395e-06 1.62903423931068e-06 1.49372992338056e-05 -1.97139765247734e-06 -6.60896448437105e-06 -3.89355191896321e-06 9.52288259229213e-07 7.19814627405624e-06 -1.97139765247734e-06 1.9352314299333e-05 -3.18275444283364e-06 -7.46581130278212e-06 -7.40617132833325e-06 -2.71068657707412e-06 -6.60896448437105e-06 -3.18275444283364e-06 1.90378196750695e-05 -6.21267687267332e-06 3.62326356318732e-05 6.52798689483375e-06 -3.89355191896321e-06 -7.46581130278212e-06 -6.21267687267332e-06 0.000168397243664161 3814 3748 0 259 130 3814 3748 0 160 187 0 0 0 0 0 0 0 0 3405 0 0 0 0 0 3633 +1252 1255 0.994729987337629 0.0974905787906989 0.0317464854485532 0.263323539198295 -0.0977843268159958 0.995176810926189 0.00783201276314314 0.0603607386962885 -0.0308298186894309 -0.0108950466650701 0.999465267149261 0.246478535570485 0.000119418567036471 7.40545468790661e-06 3.77571018818035e-06 3.57861911092809e-06 -4.99044762763783e-06 -2.00088879479297e-05 7.40545468790661e-06 0.000162586929518826 6.46465074395255e-06 -1.29962219201916e-05 -1.10205086366394e-05 0.000147370414889135 3.77571018818035e-06 6.46465074395255e-06 1.55787420313231e-05 -7.96094821555501e-06 -6.17286351445576e-06 7.9295540704323e-09 3.57861911092809e-06 -1.29962219201916e-05 -7.96094821555501e-06 2.19875813854533e-05 1.09889040789889e-06 -2.02204008948638e-05 -4.99044762763783e-06 -1.10205086366394e-05 -6.17286351445576e-06 1.09889040789889e-06 1.73388132885986e-05 -7.67447985505025e-06 -2.00088879479297e-05 0.000147370414889135 7.9295540704323e-09 -2.02204008948638e-05 -7.67447985505025e-06 0.00037307477020392 3649 3548 0 513 113 3649 3548 0 373 167 0 0 0 0 0 0 0 0 2683 0 0 0 0 0 3093 +1252 1254 0.998509991829452 0.054084810247295 -0.00725462040778443 0.181038790651277 -0.0540587557603136 0.998530749197844 0.00374083306750813 0.045331282992893 0.00744628379755394 -0.00334308344291468 0.999966687770498 0.106450136423165 6.9320780554973e-05 3.00006415434942e-05 1.26939722656324e-06 4.22961718544095e-07 -2.79714355221379e-06 1.38402016040413e-05 3.00006415434942e-05 7.00664969623288e-05 7.90980724344882e-07 -6.63315246781985e-07 -3.79673148750204e-07 2.79761518953399e-05 1.26939722656324e-06 7.90980724344882e-07 1.23347985550071e-05 -3.0625460683424e-06 -5.09323235423973e-06 1.95221441736256e-06 4.22961718544095e-07 -6.63315246781985e-07 -3.0625460683424e-06 1.62989217486537e-05 -9.98391418572302e-07 -7.35854663770157e-06 -2.79714355221379e-06 -3.79673148750204e-07 -5.09323235423973e-06 -9.98391418572302e-07 1.42189697561818e-05 -5.24407676560455e-07 1.38402016040413e-05 2.79761518953399e-05 1.95221441736256e-06 -7.35854663770157e-06 -5.24407676560455e-07 0.00022348640933879 3813 3727 0 321 99 3813 3727 0 186 160 0 0 0 0 0 0 0 0 3397 0 0 0 0 0 3586 +1252 1296 0.933831333694483 0.341165749828908 -0.107540556787015 0.517380303181478 -0.345861598940711 0.937868602004536 -0.0279685493408789 0.0928109432930292 0.091317000545119 0.0633120566538241 0.993807219179709 0.834047419796877 0.000130746198415973 2.19512163325404e-05 1.26288731937493e-05 -1.44917195498108e-05 1.6960089268214e-05 1.88252355041325e-05 2.19512163325404e-05 0.000156820080553624 -8.62881085698993e-06 -2.33026424511411e-05 -5.29379109593511e-06 3.28627452061074e-05 1.26288731937493e-05 -8.62881085698993e-06 2.02091638545761e-05 -1.37340109272871e-06 -6.70053324299613e-06 -5.5108581353618e-06 -1.44917195498108e-05 -2.33026424511411e-05 -1.37340109272871e-06 4.1488352789901e-05 -1.98640240437287e-07 -1.397379617257e-05 1.6960089268214e-05 -5.29379109593511e-06 -6.70053324299613e-06 -1.98640240437287e-07 4.10547114210939e-05 -9.74172440886112e-06 1.88252355041325e-05 3.28627452061074e-05 -5.5108581353618e-06 -1.397379617257e-05 -9.74172440886112e-06 0.000329340832426933 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 250 0 0 0 0 0 765 +1253 1255 0.996714209335414 0.073484718967964 0.0340702360878249 0.167648118839569 -0.0736443763808938 0.997278586726265 0.00345344534246764 0.0391047162102764 -0.0337237414346338 -0.00595117933383839 0.999413474357929 0.158772400666609 5.09191337551858e-05 2.13035883150555e-05 4.28853699317775e-06 1.84921096167703e-07 -5.52249576600013e-06 8.47658481785344e-06 2.13035883150555e-05 7.76825746766444e-05 8.35851886989021e-06 -7.17267824784139e-06 -8.59042929747789e-06 7.8214569027024e-05 4.28853699317775e-06 8.35851886989021e-06 1.42487871168093e-05 -6.65705623433479e-06 -6.6195387799535e-06 9.7353008087853e-06 1.84921096167703e-07 -7.17267824784139e-06 -6.65705623433479e-06 1.81755677492386e-05 5.55844550670037e-09 -1.13573372235753e-05 -5.52249576600013e-06 -8.59042929747789e-06 -6.6195387799535e-06 5.55844550670037e-09 1.61320220312058e-05 -2.797450837531e-06 8.47658481785344e-06 7.8214569027024e-05 9.7353008087853e-06 -1.13573372235753e-05 -2.797450837531e-06 0.000186209731483758 3650 3555 0 314 20 3650 3555 0 184 77 0 0 0 0 0 0 0 0 3155 0 0 0 0 0 3589 +1254 1297 0.955015862701087 0.296152822012215 -0.0154339885804144 0.386493977808349 -0.296151084099643 0.955137964177723 0.00245046384188086 0.08080582387084 0.0154673002138512 0.00223056061009956 0.999877886155834 0.655248497986713 0.000248184615295025 0.000106476867331005 1.79505757389982e-06 -4.12632331168035e-05 1.95932208720145e-05 0.000129003091924623 0.000106476867331005 0.000336022768757272 -1.47310510744215e-05 -5.86590837120339e-05 -6.09525324630097e-06 0.000203573503055524 1.79505757389982e-06 -1.47310510744215e-05 1.7542416589569e-05 -5.31194572891281e-06 -7.78612460846645e-06 -6.48208221348535e-06 -4.12632331168035e-05 -5.86590837120339e-05 -5.31194572891281e-06 5.23205383519281e-05 -1.34824381140201e-06 -4.39051597174142e-05 1.95932208720145e-05 -6.09525324630097e-06 -7.78612460846645e-06 -1.34824381140201e-06 3.74533111960974e-05 1.6904329956986e-05 0.000129003091924623 0.000203573503055524 -6.48208221348535e-06 -4.39051597174142e-05 1.6904329956986e-05 0.000289227226112917 625 628 0 0 0 627 659 0 0 0 0 0 0 0 0 0 0 0 456 0 0 0 0 0 1358 +1254 1256 0.99465557573358 0.103193810582054 0.00336498434699238 0.14325138354078 -0.102974465396516 0.993860738385994 -0.0404609956766893 0.0271515906875511 -0.00751965015158076 0.0398982474853521 0.999175452415238 0.143829763321432 0.000110186814269159 -3.34901208504831e-07 4.35837771422328e-07 6.21906577139665e-08 -5.52407158448434e-06 5.96639166669833e-05 -3.34901208504831e-07 9.22338208719018e-05 -7.90323884503863e-06 -4.46404322593603e-06 -7.68264957239831e-06 6.88890762851387e-05 4.35837771422328e-07 -7.90323884503863e-06 1.51589308789365e-05 6.02138546033285e-07 6.88297709213672e-07 -1.91963848986848e-06 6.21906577139665e-08 -4.46404322593603e-06 6.02138546033285e-07 2.26489956183211e-05 7.27726168130499e-06 -1.67679241883181e-05 -5.52407158448434e-06 -7.68264957239831e-06 6.88297709213672e-07 7.27726168130499e-06 2.52559081704204e-05 1.85589740364211e-07 5.96639166669833e-05 6.88890762851387e-05 -1.91963848986848e-06 -1.67679241883181e-05 1.85589740364211e-07 0.000357285851023943 2435 2436 0 3 0 2448 2505 0 0 0 0 0 0 0 0 0 0 0 2778 0 0 3 0 0 3643 +1255 1292 0.966227828468613 0.254868256227639 -0.038025721036036 0.299612169442894 -0.255035874600838 0.966931483467508 0.000457106014884764 0.0782506619548219 0.0368847686642208 0.00925625446961089 0.999276656183752 0.610829989064557 0.00028057188929507 0.000221333494761533 2.38520972190668e-05 -5.77732187881163e-05 4.7875874399284e-05 0.000263362032140531 0.000221333494761533 0.000331786882478605 1.47594736234361e-05 -7.23876804902244e-05 2.00870889121409e-05 0.000175106294559036 2.38520972190668e-05 1.47594736234361e-05 2.03585539914989e-05 -1.527870787254e-05 2.28690413202521e-06 2.83231631198744e-05 -5.77732187881163e-05 -7.23876804902244e-05 -1.527870787254e-05 5.51586902743148e-05 -1.04695935249635e-05 -3.49312310897696e-05 4.7875874399284e-05 2.00870889121409e-05 2.28690413202521e-06 -1.04695935249635e-05 3.86706722422563e-05 7.31935164822385e-05 0.000263362032140531 0.000175106294559036 2.83231631198744e-05 -3.49312310897696e-05 7.31935164822385e-05 0.00066968831615915 354 354 0 0 0 358 366 0 0 0 0 0 0 0 0 0 0 0 567 0 0 0 0 0 1494 +1255 1290 0.964964355422698 0.249506628038799 -0.0811802644019148 0.305810742194313 -0.253884684259575 0.965999698399024 -0.0488584669367691 0.0837142425119418 0.0662295995916643 0.0677571048503696 0.995501187784436 0.597002185673441 0.000216559563216107 5.77936247970489e-05 1.46167818582871e-05 3.9476002376196e-06 3.94296396585292e-05 -1.71752948497663e-05 5.77936247970489e-05 0.000207320489204334 -5.37617139956828e-06 -1.93296885155757e-05 1.39340955831682e-05 0.000243505268265539 1.46167818582871e-05 -5.37617139956828e-06 1.77318698477295e-05 -8.29245097843555e-06 -1.85712882848113e-06 -7.90836761046562e-06 3.9476002376196e-06 -1.93296885155757e-05 -8.29245097843555e-06 3.83331698424032e-05 -1.7079052743757e-06 -3.08914378699828e-05 3.94296396585292e-05 1.39340955831682e-05 -1.85712882848113e-06 -1.7079052743757e-06 3.35962445621735e-05 3.31921091120519e-05 -1.71752948497663e-05 0.000243505268265539 -7.90836761046562e-06 -3.08914378699828e-05 3.31921091120519e-05 0.00066146343578806 510 521 0 0 0 510 540 0 0 0 0 0 0 0 0 0 0 0 500 0 0 0 0 0 1865 +1255 1295 0.966287092739333 0.255763760620434 -0.0295660812192167 0.297820644946948 -0.255603861650505 0.966738484243598 0.00913066217420896 0.0782834863442669 0.0309179610375191 -0.00126563647359711 0.999521124263814 0.61078221797299 0.000178087724320131 0.000140574197464478 3.48017141265347e-07 -3.24624533514859e-05 1.65649552397334e-05 0.000149308113844761 0.000140574197464478 0.000271205909430304 5.48669302703736e-06 -5.91756210012211e-05 9.36300443257177e-06 0.000183117474162974 3.48017141265347e-07 5.48669302703736e-06 2.04007524272183e-05 -1.23230758743118e-05 -8.07009294763685e-06 1.24316352746047e-06 -3.24624533514859e-05 -5.91756210012211e-05 -1.23230758743118e-05 5.12061620399148e-05 -2.08755751827949e-06 -4.76459617931072e-05 1.65649552397334e-05 9.36300443257177e-06 -8.07009294763685e-06 -2.08755751827949e-06 3.49478487535119e-05 1.5317396760512e-05 0.000149308113844761 0.000183117474162974 1.24316352746047e-06 -4.76459617931072e-05 1.5317396760512e-05 0.000249627518117375 369 369 0 0 0 373 380 0 0 0 0 0 0 0 0 0 0 0 566 0 0 0 0 0 1165 +1255 1288 0.960614385045515 0.238932966072946 -0.141883899605318 0.320888610082535 -0.255313543186954 0.960443360324338 -0.111191484719904 0.0978474800599234 0.109704138066671 0.143037020845924 0.983618530101264 0.608349770124148 0.000200699141473244 0.00013567283521253 1.31800922527772e-05 -3.08238778725989e-05 4.49935504640478e-05 0.000208308294508566 0.00013567283521253 0.000166965974869313 3.37260058209114e-06 -4.40905998705012e-05 -6.17108170472886e-07 7.44679010728197e-05 1.31800922527772e-05 3.37260058209114e-06 2.1737015717175e-05 -1.35861848964006e-05 1.23536280126234e-06 3.16007771639791e-05 -3.08238778725989e-05 -4.40905998705012e-05 -1.35861848964006e-05 6.24227905664557e-05 1.32190654404884e-05 1.13251672366675e-05 4.49935504640478e-05 -6.17108170472886e-07 1.23536280126234e-06 1.32190654404884e-05 5.88417132644553e-05 0.000128119063610345 0.000208308294508566 7.44679010728197e-05 3.16007771639791e-05 1.13251672366675e-05 0.000128119063610345 0.000634661627791567 431 463 0 0 1 431 463 0 0 17 0 0 0 0 0 0 0 0 328 0 0 0 0 0 2081 +1255 1287 0.958454337412526 0.235442784028557 -0.161034091247779 0.319930734339717 -0.256687015964913 0.95812399012044 -0.126925944513783 0.0975408082473829 0.124406828309962 0.162988082400431 0.978753199772693 0.594430424159889 0.000120683002702492 6.49099146681778e-05 1.89697801560223e-06 1.48050583329861e-06 2.5063604761601e-05 9.62806119966577e-05 6.49099146681778e-05 0.000151818562842803 -1.11469800622251e-05 -1.95431259559523e-05 -6.31047050296237e-06 6.14318964181468e-05 1.89697801560223e-06 -1.11469800622251e-05 1.71691328477147e-05 -4.95810173250989e-06 -2.94176002093757e-07 3.33522583695587e-06 1.48050583329861e-06 -1.95431259559523e-05 -4.95810173250989e-06 4.15159031934248e-05 4.77392341411523e-06 9.47913257758007e-06 2.5063604761601e-05 -6.31047050296237e-06 -2.94176002093757e-07 4.77392341411523e-06 4.12332237010807e-05 2.99847490977564e-05 9.62806119966577e-05 6.14318964181468e-05 3.33522583695587e-06 9.47913257758007e-06 2.99847490977564e-05 0.000169457375953573 370 402 0 0 1 370 402 0 0 16 0 0 0 0 0 0 0 0 352 0 0 0 0 0 2037 +1256 1260 0.987606519282068 0.137049975384444 -0.0764896549781817 0.169317271524729 -0.147632289989219 0.976607172470411 -0.156343012737658 0.0915293576365187 0.0532735396242535 0.165697721548825 0.984736612018377 0.278765149428701 0.00016696357047589 9.28819661278725e-05 -7.77813281126348e-06 4.07934574597673e-06 2.67642242341257e-05 0.000132424212147056 9.28819661278725e-05 0.000134861461290782 -1.79213089552891e-05 -7.89843279339039e-06 7.24311781537977e-06 0.000111348296150239 -7.77813281126348e-06 -1.79213089552891e-05 1.9406812179854e-05 -1.7881848377053e-06 -6.38696690401906e-06 -7.32452641751595e-06 4.07934574597673e-06 -7.89843279339039e-06 -1.7881848377053e-06 2.43510638659188e-05 -3.82177868026235e-06 -1.19667698472823e-05 2.67642242341257e-05 7.24311781537977e-06 -6.38696690401906e-06 -3.82177868026235e-06 2.50536258008143e-05 4.25623200518937e-05 0.000132424212147056 0.000111348296150239 -7.32452641751595e-06 -1.19667698472823e-05 4.25623200518937e-05 0.000256797515610996 1539 1566 0 0 3 1546 1605 0 0 23 0 0 0 0 0 0 0 0 1104 0 0 4 0 0 3293 +1256 1259 0.98863444560533 0.132889369357812 -0.0703018383424357 0.143331888609527 -0.140121339389898 0.983940829038166 -0.110573302380217 0.067561943437487 0.0544788326804457 0.119167363247531 0.991378432449691 0.237755586506154 0.000180893760290163 8.71673085965918e-05 2.01309914553547e-06 1.48855943508541e-06 2.31881142713338e-05 8.60599388137522e-05 8.71673085965918e-05 0.000180128755227378 -1.12942074711203e-05 -8.78670618532972e-06 2.33388963935401e-06 3.20550846583443e-05 2.01309914553547e-06 -1.12942074711203e-05 1.66942942852844e-05 -4.43093615434879e-08 -6.28169270176537e-06 2.57427620942282e-06 1.48855943508541e-06 -8.78670618532972e-06 -4.43093615434879e-08 1.83939464549254e-05 -4.26052399982898e-06 -5.2215406207011e-06 2.31881142713338e-05 2.33388963935401e-06 -6.28169270176537e-06 -4.26052399982898e-06 2.67442877666997e-05 6.97432551628717e-05 8.60599388137522e-05 3.20550846583443e-05 2.57427620942282e-06 -5.2215406207011e-06 6.97432551628717e-05 0.000430276600167198 1817 1827 0 0 0 1849 1895 0 0 2 0 0 0 0 0 0 0 0 1502 0 0 18 0 0 3390 +1256 1258 0.993088480059324 0.10437397072894 -0.053678161366942 0.106081897932523 -0.108536731653836 0.99073915573441 -0.0815824930764628 0.0407913433080327 0.0446659675297029 0.0868446862447098 0.995220051956196 0.145641964681943 7.27991573479819e-05 1.75720024896151e-05 -5.76084901283181e-06 6.18862215545602e-06 -1.68058802710034e-06 2.51969496844174e-05 1.75720024896151e-05 0.000113139740596464 -1.27561053485371e-05 -6.31347434393343e-06 -8.58290974316002e-06 2.50049397834997e-05 -5.76084901283181e-06 -1.27561053485371e-05 1.99444906639078e-05 -4.14071146534397e-06 -2.28853463892324e-06 1.63037361390371e-06 6.18862215545602e-06 -6.31347434393343e-06 -4.14071146534397e-06 1.97481304712151e-05 -3.23889911189589e-06 -7.74364089433961e-06 -1.68058802710034e-06 -8.58290974316002e-06 -2.28853463892324e-06 -3.23889911189589e-06 2.00341557471812e-05 1.91888514295304e-05 2.51969496844174e-05 2.50049397834997e-05 1.63037361390371e-06 -7.74364089433961e-06 1.91888514295304e-05 0.000213262010528163 1955 1956 0 0 0 1999 2025 0 0 0 0 0 0 0 0 0 0 0 2040 0 0 29 0 0 3484 +1257 1259 0.9960921381497 0.0808725001350016 -0.0354977610318359 0.0874052384658293 -0.0838388971504586 0.992217003006276 -0.0920676830915052 0.052518516495232 0.0277757383511941 0.0946839884413261 0.995119817254128 0.146274396610486 0.000286868220939595 2.12074594043199e-05 5.21425471293084e-06 1.93206032439129e-05 -4.36859113469206e-07 -9.29519638259882e-06 2.12074594043199e-05 9.08986482854658e-05 -3.68110911760799e-06 -2.54732526456156e-06 1.85187369252361e-06 4.76661178408626e-06 5.21425471293084e-06 -3.68110911760799e-06 1.8098292207427e-05 -2.55872209682581e-06 -6.27081606574506e-06 -7.55255114801294e-06 1.93206032439129e-05 -2.54732526456156e-06 -2.55872209682581e-06 2.42863622858484e-05 -4.12150318956051e-06 1.90551645608389e-06 -4.36859113469206e-07 1.85187369252361e-06 -6.27081606574506e-06 -4.12150318956051e-06 2.34971023124492e-05 4.75018560161798e-05 -9.29519638259882e-06 4.76661178408626e-06 -7.55255114801294e-06 1.90551645608389e-06 4.75018560161798e-05 0.000317328710071659 1839 1857 0 0 0 1852 1921 0 0 7 0 0 0 0 0 0 0 0 1701 0 0 1 0 0 3392 +1257 1261 0.992650996224586 0.110948621179285 -0.0483156615679858 0.136243480893422 -0.117828742059043 0.97713560968111 -0.176981320590364 0.0977428832277744 0.0275751199293901 0.181373657821474 0.983027572863212 0.242139363207243 0.000177574372720471 6.40501793809723e-06 6.86264019040974e-06 9.85836977682595e-06 1.11555215015255e-05 2.58917316507172e-05 6.40501793809723e-06 0.000221233300936105 -4.07738828122966e-05 -1.21269845651453e-05 9.00335669567211e-06 0.00010135994775258 6.86264019040974e-06 -4.07738828122966e-05 2.57903769782127e-05 9.36990053997003e-06 -1.0355858691079e-05 -1.44160957285629e-05 9.85836977682595e-06 -1.21269845651453e-05 9.36990053997003e-06 2.32812835688274e-05 -1.08326411993475e-05 -1.3741242616535e-05 1.11555215015255e-05 9.00335669567211e-06 -1.0355858691079e-05 -1.08326411993475e-05 2.4603536807218e-05 3.09747776516954e-05 2.58917316507172e-05 0.00010135994775258 -1.44160957285629e-05 -1.3741242616535e-05 3.09747776516954e-05 0.000141672070218117 1645 1693 0 0 10 1645 1722 0 0 44 0 0 0 0 0 0 0 0 992 0 0 0 0 0 3154 +1257 1290 0.988587494835553 0.138864943820493 -0.0584062704895442 0.1731662283694 -0.139549716613002 0.990184393878177 -0.00779376118045844 0.0914713001148966 0.0567506973348995 0.0158553933359742 0.998262472926917 0.452270884151095 0.000129535960324735 4.75439748936299e-05 6.57527039327204e-06 -4.24639563362035e-06 9.01418632856547e-06 9.01382967201675e-05 4.75439748936299e-05 0.000130404825553403 -8.87660997099378e-06 4.21389891441893e-06 7.5520076789463e-06 0.000113792385691643 6.57527039327204e-06 -8.87660997099378e-06 1.75215664567167e-05 -9.22932467138256e-06 -7.74785301574677e-06 -1.91724941742104e-06 -4.24639563362035e-06 4.21389891441893e-06 -9.22932467138256e-06 3.47195707859878e-05 1.61146357204976e-05 5.74603464490091e-06 9.01418632856547e-06 7.5520076789463e-06 -7.74785301574677e-06 1.61146357204976e-05 3.69194784002461e-05 2.56678349840911e-05 9.01382967201675e-05 0.000113792385691643 -1.91724941742104e-06 5.74603464490091e-06 2.56678349840911e-05 0.000217007365032246 923 974 0 0 0 923 977 0 0 21 0 0 0 0 0 0 0 0 795 0 0 0 0 0 2350 +1257 1298 0.989359829729062 0.145421527960424 -0.00443920309701329 0.166897093357255 -0.145058046845017 0.9883156165416 0.0468017643418027 0.0810588007053649 0.0111933178276067 -0.0456598434694245 0.998894332915328 0.453515566939665 0.000203993403763281 4.24408041893723e-05 -1.28982649405886e-05 -1.08009624331833e-05 4.08157096814959e-07 -2.17667082404146e-06 4.24408041893723e-05 0.000177486149304698 -6.51697726209315e-06 -2.22368835708409e-05 4.94469818072985e-07 5.93912007851387e-05 -1.28982649405886e-05 -6.51697726209315e-06 2.70693748490032e-05 -9.56029823139008e-06 -5.12266548724686e-06 3.99732049032734e-06 -1.08009624331833e-05 -2.22368835708409e-05 -9.56029823139008e-06 4.36013115638424e-05 1.36704039034775e-05 -1.74535189894761e-05 4.08157096814959e-07 4.94469818072985e-07 -5.12266548724686e-06 1.36704039034775e-05 3.92468388931475e-05 1.01625197186752e-05 -2.17667082404146e-06 5.93912007851387e-05 3.99732049032734e-06 -1.74535189894761e-05 1.01625197186752e-05 0.000403899723252587 793 809 0 0 0 793 837 0 0 0 0 0 0 0 0 0 0 0 856 0 0 0 0 0 1760 +1258 1261 0.997870566201663 0.0652251106544799 -0.000134344647363363 0.0855241987246558 -0.0649098934447923 0.992841590236864 -0.100261071353346 0.0903943776175483 -0.00640615652003064 0.100056292336094 0.994961154780726 0.15504594621058 0.00018991802646985 5.07413336977598e-05 -1.40853992353646e-06 9.28245912011457e-06 3.63595495147729e-06 3.53181125168758e-05 5.07413336977598e-05 0.000145517586180363 -2.08375730259039e-05 -3.81992841004228e-06 2.03275204688576e-06 6.24384041377023e-05 -1.40853992353646e-06 -2.08375730259039e-05 2.03859074377078e-05 4.33912659137986e-06 -9.50449461913247e-06 -5.96680954485343e-06 9.28245912011457e-06 -3.81992841004228e-06 4.33912659137986e-06 2.4215243203302e-05 -6.70056884366319e-06 -1.52967604165616e-05 3.63595495147729e-06 2.03275204688576e-06 -9.50449461913247e-06 -6.70056884366319e-06 3.24691518649831e-05 6.88080487539047e-05 3.53181125168758e-05 6.24384041377023e-05 -5.96680954485343e-06 -1.52967604165616e-05 6.88080487539047e-05 0.000333278656702185 1645 1718 0 0 7 1645 1725 0 0 64 0 0 0 0 0 0 0 0 1153 0 0 0 0 0 3217 +1258 1292 0.996145722104983 0.08764583990608 0.00345066357383826 0.12511439070529 -0.0874728994765277 0.989728233168219 0.11307747930903 0.0905790552006997 0.00649555148630946 -0.112943486828027 0.993580181260685 0.358375267990232 0.000129882235932282 1.63450298823845e-05 -3.5541291417659e-07 9.29419560462892e-06 6.84750073637769e-06 1.88348636703861e-05 1.63450298823845e-05 0.000130627307538008 -4.03407691757515e-06 4.23753002295055e-06 -6.18362099476928e-06 0.000106793802718841 -3.5541291417659e-07 -4.03407691757515e-06 1.77776314812657e-05 -2.85923888955102e-06 -7.41866968763978e-06 -6.51185644340984e-06 9.29419560462892e-06 4.23753002295055e-06 -2.85923888955102e-06 3.89132360579827e-05 1.5519848336581e-05 8.93508296716312e-06 6.84750073637769e-06 -6.18362099476928e-06 -7.41866968763978e-06 1.5519848336581e-05 2.75999501279982e-05 -2.84031271957755e-07 1.88348636703861e-05 0.000106793802718841 -6.51185644340984e-06 8.93508296716312e-06 -2.84031271957755e-07 0.000177556694901714 1003 1057 0 0 3 1003 1057 0 0 58 0 0 0 0 0 0 0 0 1028 0 0 0 0 0 2052 +1258 1262 0.997555203372439 0.0679203216666594 -0.0164452464034117 0.100468471232068 -0.0693785666053516 0.990764076910729 -0.116503898642998 0.112888826503555 0.00838037710119334 0.117360017927438 0.993054074797396 0.206347622317871 0.000243352092827716 6.20264161096966e-05 -1.87551155473828e-06 2.10904049333229e-05 2.54030885239425e-06 4.47379481901814e-05 6.20264161096966e-05 0.000159574014255021 -3.35090809973149e-05 6.66269218371455e-06 1.32806367979311e-05 0.000122092962493534 -1.87551155473828e-06 -3.35090809973149e-05 2.73733866412114e-05 1.59876947061886e-07 -1.291894706755e-05 -2.41780114835197e-05 2.10904049333229e-05 6.66269218371455e-06 1.59876947061886e-07 2.79977779973876e-05 -4.05872638163863e-06 -1.42440910955134e-06 2.54030885239425e-06 1.32806367979311e-05 -1.291894706755e-05 -4.05872638163863e-06 2.42545174729121e-05 2.77806185898196e-05 4.47379481901814e-05 0.000122092962493534 -2.41780114835197e-05 -1.42440910955134e-06 2.77806185898196e-05 0.00016752651782965 1571 1652 0 0 36 1571 1652 0 0 111 0 0 0 0 0 0 0 0 910 0 0 0 0 0 3142 +1258 1293 0.99584878373294 0.0892017950434964 0.0181173866394215 0.127211836706885 -0.0906954424051962 0.989282810013543 0.114428399178848 0.0829704965554123 -0.00771600055404176 -0.115596546543251 0.993266279384699 0.344332603045308 0.000116145203292001 1.38949251284219e-05 -2.38416764248658e-06 1.14080764034747e-06 9.09913481358741e-07 2.441511150792e-06 1.38949251284219e-05 8.29067853003265e-05 -1.03838906915869e-06 4.07701550996029e-06 1.46412770530523e-06 5.62999461211122e-05 -2.38416764248658e-06 -1.03838906915869e-06 1.59776216433888e-05 -4.94185748539465e-06 -6.37799096602333e-06 -3.19563307425475e-07 1.14080764034747e-06 4.07701550996029e-06 -4.94185748539465e-06 3.53829241346668e-05 1.1945491546308e-05 7.69349404971954e-06 9.09913481358741e-07 1.46412770530523e-06 -6.37799096602333e-06 1.1945491546308e-05 2.94331360625045e-05 1.37404009010309e-05 2.441511150792e-06 5.62999461211122e-05 -3.19563307425475e-07 7.69349404971954e-06 1.37404009010309e-05 0.000204129849139783 1014 1065 0 0 2 1014 1069 0 0 49 0 0 0 0 0 0 0 0 1105 0 0 0 0 0 2024 +1258 1285 0.994123465639588 0.0811500742695613 -0.0716463572750149 0.145232486255342 -0.0821265921532975 0.996563539473787 -0.0107858542898989 0.112861045956295 0.0705248745197064 0.0166065420097525 0.997371778644482 0.353429535711076 0.000102037049924047 2.19854385399123e-05 1.86297701085047e-06 1.33154261203904e-06 -1.90236858489677e-06 3.84510812287467e-05 2.19854385399123e-05 9.34373838507636e-05 -3.49827525595524e-06 1.20779829045225e-06 6.03054760398806e-07 3.68877272482211e-05 1.86297701085047e-06 -3.49827525595524e-06 1.72692323653539e-05 -8.25352189707295e-06 -7.65077406411456e-06 1.07176235382254e-06 1.33154261203904e-06 1.20779829045225e-06 -8.25352189707295e-06 4.80261035311662e-05 1.49283699951694e-05 6.75992711468587e-06 -1.90236858489677e-06 6.03054760398806e-07 -7.65077406411456e-06 1.49283699951694e-05 3.13017846922482e-05 1.5079238989574e-05 3.84510812287467e-05 3.68877272482211e-05 1.07176235382254e-06 6.75992711468587e-06 1.5079238989574e-05 0.000118604136890777 1055 1119 0 0 59 1055 1119 0 0 125 0 0 0 0 0 0 0 0 809 0 0 0 0 0 2639 +1258 1295 0.995978854513022 0.0881894137674001 0.0157717678873053 0.12578341864211 -0.0894247576662447 0.989273143624442 0.115506969572177 0.0869865726134979 -0.00541609446577028 -0.116452885764058 0.993181449342446 0.348877559593668 0.00018395126815611 7.40814017745986e-07 2.96338436662964e-06 9.45762915930834e-06 7.39603509991238e-06 1.61488077928397e-06 7.40814017745986e-07 0.000133572803915761 -9.58151688192513e-07 -1.88717854691505e-06 -1.52045972626073e-06 7.62455862909361e-05 2.96338436662964e-06 -9.58151688192513e-07 1.46033648920312e-05 -1.94164806851233e-06 -1.0558132972747e-05 -4.24554875169115e-06 9.45762915930834e-06 -1.88717854691505e-06 -1.94164806851233e-06 3.32869948710446e-05 1.21310009171467e-05 7.35350666706587e-06 7.39603509991238e-06 -1.52045972626073e-06 -1.0558132972747e-05 1.21310009171467e-05 2.30551261114208e-05 2.27218950418304e-06 1.61488077928397e-06 7.62455862909361e-05 -4.24554875169115e-06 7.35350666706587e-06 2.27218950418304e-06 0.000191808787396639 1008 1062 0 0 3 1008 1063 0 0 52 0 0 0 0 0 0 0 0 957 0 0 0 0 0 1799 +1258 1296 0.995856515979341 0.0883704535538989 0.0214583904374661 0.126209024342283 -0.0904033975609683 0.987600134845053 0.128347962054203 0.0895369469663197 -0.00985014167015077 -0.129756065726084 0.991497018712798 0.357135365092923 0.0001786319581689 3.95933527765429e-05 4.75021580382072e-06 -4.24302040690393e-06 -3.66309293319695e-07 7.29678686500708e-05 3.95933527765429e-05 0.000158383975818024 -1.46640328795354e-06 1.46466287287402e-05 3.91182598140983e-07 0.000100782380807068 4.75021580382072e-06 -1.46640328795354e-06 1.47790589066823e-05 -1.0974696213196e-06 -9.13383175614139e-06 -2.20848518587149e-06 -4.24302040690393e-06 1.46466287287402e-05 -1.0974696213196e-06 3.3708174723745e-05 1.18057207345963e-05 8.69965332864413e-06 -3.66309293319695e-07 3.91182598140983e-07 -9.13383175614139e-06 1.18057207345963e-05 2.30595902271168e-05 7.20222233825401e-07 7.29678686500708e-05 0.000100782380807068 -2.20848518587149e-06 8.69965332864413e-06 7.20222233825401e-07 0.000267616405728287 1010 1054 0 0 1 1010 1054 0 0 43 0 0 0 0 0 0 0 0 1063 0 0 0 0 0 1922 +1258 1260 0.999322557670044 0.0366656054678508 -0.00317160960357763 0.0623567506938821 -0.0367951654350914 0.99712888675824 -0.0661823163154363 0.0704629554836866 0.000735888854276814 0.0662541815129289 0.997802506460896 0.120825622933594 0.000150379926733537 4.30966178978568e-05 -5.23410230413399e-06 1.72256820506656e-05 -1.12232286196624e-05 -3.10564832066837e-05 4.30966178978568e-05 0.000107005768170954 -1.3963633536801e-05 -3.78210750586891e-06 -4.08075919997705e-06 4.26352612280268e-05 -5.23410230413399e-06 -1.3963633536801e-05 1.71772542932925e-05 3.98156851354854e-06 -7.10864930143479e-06 -4.55336979144193e-06 1.72256820506656e-05 -3.78210750586891e-06 3.98156851354854e-06 2.45066498696895e-05 -7.94769936922412e-06 -2.01688303885795e-05 -1.12232286196624e-05 -4.08075919997705e-06 -7.10864930143479e-06 -7.94769936922412e-06 2.04585677817368e-05 2.28322706835309e-05 -3.10564832066837e-05 4.26352612280268e-05 -4.55336979144193e-06 -2.01688303885795e-05 2.28322706835309e-05 0.000169594928849329 1707 1782 0 0 5 1707 1786 0 0 69 0 0 0 0 0 0 0 0 1507 0 0 0 0 0 3337 +1258 1286 0.993349775061937 0.0810552998895969 -0.0817695710164005 0.146264394791877 -0.0832255525866413 0.996253946484745 -0.0234857725063149 0.109113424551038 0.0795596114938154 0.0301349045689162 0.996374505768577 0.350723490727669 0.000236997015647624 -4.40452448741617e-06 9.5282399732396e-06 8.76370680196007e-06 6.30175926608482e-06 -8.01777653135956e-06 -4.40452448741617e-06 0.000131258868789841 -6.6042701868575e-06 2.11536502126102e-07 2.94601976727988e-06 8.37301609917876e-05 9.5282399732396e-06 -6.6042701868575e-06 1.54272047278912e-05 -3.84739036738565e-06 -5.99121371421442e-06 2.79542300796643e-06 8.76370680196007e-06 2.11536502126102e-07 -3.84739036738565e-06 3.94639231193037e-05 1.35382021235645e-05 5.34576020686578e-07 6.30175926608482e-06 2.94601976727988e-06 -5.99121371421442e-06 1.35382021235645e-05 3.17247484626382e-05 3.37314885094939e-05 -8.01777653135956e-06 8.37301609917876e-05 2.79542300796643e-06 5.34576020686578e-07 3.37314885094939e-05 0.000306662487659597 911 963 0 0 53 911 963 0 0 122 0 0 0 0 0 0 0 0 797 0 0 0 0 0 2581 +1258 1291 0.996061557802911 0.0874176942527454 -0.0148162005511599 0.127335291602452 -0.0858292239401831 0.992573208615662 0.0862077134381611 0.095232460071037 0.0222422432561234 -0.0845965263467935 0.996167009263503 0.355200862113581 0.00011193923782236 -1.14520628745669e-05 2.61016726671828e-06 9.0985705478108e-07 8.27149560105134e-06 -1.14258248665321e-05 -1.14520628745669e-05 0.000163790199008844 -7.74664465442225e-06 1.97438830605496e-05 1.51620733393061e-05 0.000171644106048709 2.61016726671828e-06 -7.74664465442225e-06 1.69827444946146e-05 -2.3030088241803e-06 -1.05965641629323e-05 -7.53342381199312e-06 9.0985705478108e-07 1.97438830605496e-05 -2.3030088241803e-06 3.76157452728953e-05 1.21838805922693e-05 2.0078325049719e-05 8.27149560105134e-06 1.51620733393061e-05 -1.05965641629323e-05 1.21838805922693e-05 2.76386190118776e-05 2.22465801178158e-05 -1.14258248665321e-05 0.000171644106048709 -7.53342381199312e-06 2.0078325049719e-05 2.22465801178158e-05 0.000293135445318761 971 1025 0 0 5 971 1025 0 0 62 0 0 0 0 0 0 0 0 945 0 0 0 0 0 2132 +1258 1288 0.993432729741099 0.0808181982811533 -0.0809927793432069 0.143970559428622 -0.0823681833502447 0.996473891601296 -0.015977037539847 0.110581720376779 0.0794159546358897 0.0225433401153734 0.996586626423269 0.349625910460471 0.000206359027299426 5.03952697003189e-05 8.04054017143085e-06 5.14839476055749e-07 1.35811220690015e-06 3.31761622513661e-05 5.03952697003189e-05 9.05627037004627e-05 -6.03023744232622e-06 1.65013429514016e-05 8.99526504776799e-06 6.89614712990689e-05 8.04054017143085e-06 -6.03023744232622e-06 1.83412311603794e-05 -9.44094048572524e-06 -9.03806812847254e-06 -4.90045498499145e-07 5.14839476055749e-07 1.65013429514016e-05 -9.44094048572524e-06 4.15407647167182e-05 1.38803865944944e-05 4.66189800785969e-06 1.35811220690015e-06 8.99526504776799e-06 -9.03806812847254e-06 1.38803865944944e-05 2.91313266460217e-05 1.12154626927079e-05 3.31761622513661e-05 6.89614712990689e-05 -4.90045498499145e-07 4.66189800785969e-06 1.12154626927079e-05 0.000112106476165008 918 971 0 0 47 918 971 0 0 116 0 0 0 0 0 0 0 0 780 0 0 0 0 0 2602 +1258 1297 0.995570713529303 0.0879625559314201 0.0331895031111757 0.130428197741323 -0.0912628558951465 0.988998766424494 0.116415338957932 0.0842577279008792 -0.0225841868708324 -0.118928670911771 0.992645921634972 0.345281071457867 9.2286939008983e-05 -1.44494783483508e-05 8.37940320083447e-07 -1.08784516879172e-06 -3.45823291225514e-06 -3.23868146867192e-06 -1.44494783483508e-05 0.000101176384978274 -1.43960992626672e-07 2.63654804207742e-06 2.35743010223728e-06 5.30435681803962e-05 8.37940320083447e-07 -1.43960992626672e-07 1.43140549130117e-05 -3.9535482116096e-06 -9.37997669095071e-06 -1.6944635676915e-06 -1.08784516879172e-06 2.63654804207742e-06 -3.9535482116096e-06 3.55043201666689e-05 1.91680129051618e-05 -8.12037395049129e-09 -3.45823291225514e-06 2.35743010223728e-06 -9.37997669095071e-06 1.91680129051618e-05 2.93331617920892e-05 4.4409080357476e-06 -3.23868146867192e-06 5.30435681803962e-05 -1.6944635676915e-06 -8.12037395049129e-09 4.4409080357476e-06 0.000116028743669886 1201 1251 0 0 2 1201 1255 0 0 46 0 0 0 0 0 0 0 0 1095 0 0 0 0 0 2042 +1258 1298 0.995535616324466 0.0899318352146019 0.0286548712158932 0.12848412495355 -0.0926390147289789 0.989136315763266 0.114137468818595 0.0851905738975555 -0.0180789817055538 -0.11628247440266 0.993051628349345 0.345281916517573 0.00012011927968905 4.40640907433033e-05 -9.72645824523178e-06 9.73500289933626e-06 2.0954674081293e-06 2.82327166912725e-05 4.40640907433033e-05 0.000147919565781158 -1.87822836050222e-05 1.88532668011858e-05 -7.30094704374405e-06 9.92947084788559e-05 -9.72645824523178e-06 -1.87822836050222e-05 2.24459189957222e-05 -1.0421391819922e-05 -6.10306167447941e-06 -1.09082452678802e-05 9.73500289933626e-06 1.88532668011858e-05 -1.0421391819922e-05 3.60581179002691e-05 1.02313248620911e-05 1.30277197264742e-05 2.0954674081293e-06 -7.30094704374405e-06 -6.10306167447941e-06 1.02313248620911e-05 3.56751594770746e-05 7.35229463657168e-06 2.82327166912725e-05 9.92947084788559e-05 -1.09082452678802e-05 1.30277197264742e-05 7.35229463657168e-06 0.000204830944086855 1006 1059 0 0 3 1006 1061 0 0 53 0 0 0 0 0 0 0 0 999 0 0 0 0 0 1832 +1258 1294 0.995784275619084 0.0879601736154584 0.026013156042951 0.12578014904508 -0.0905386195990707 0.988024433408807 0.124941895888855 0.0917287108435369 -0.0147117229062833 -0.126770370531703 0.991822987414782 0.372762645775996 0.000194291249070845 4.71079685039634e-05 2.79120124026205e-06 -2.84909642364254e-06 6.60739081211224e-06 3.1804921747993e-05 4.71079685039634e-05 0.000118414274257447 -3.18361973542506e-06 -3.43136356950035e-06 4.56500798117251e-07 9.36525387583077e-05 2.79120124026205e-06 -3.18361973542506e-06 1.68163674289872e-05 -4.4589454878132e-06 -9.30338884528276e-06 -4.15780400023848e-06 -2.84909642364254e-06 -3.43136356950035e-06 -4.4589454878132e-06 4.06016025554284e-05 1.55029253099153e-05 -1.70412366440519e-05 6.60739081211224e-06 4.56500798117251e-07 -9.30338884528276e-06 1.55029253099153e-05 2.73512301418926e-05 -5.93628429265894e-06 3.1804921747993e-05 9.36525387583077e-05 -4.15780400023848e-06 -1.70412366440519e-05 -5.93628429265894e-06 0.000242804963959076 1011 1063 0 0 5 1011 1065 0 0 52 0 0 0 0 0 0 0 0 1056 0 0 0 0 0 1721 +1258 1289 0.994616121917724 0.0842930826569161 -0.06027807426869 0.13623733175221 -0.0832497898830028 0.996335563970663 0.0196192877469032 0.102537244014561 0.0617109593652803 -0.0144955228761923 0.997988796184988 0.362934648759613 0.000223974647643639 -5.20416926141092e-05 1.70849088747347e-05 -7.47028443757745e-06 2.05968094171577e-06 -6.63122034720298e-05 -5.20416926141092e-05 0.000130387256550296 -7.19399071547926e-06 1.98759585566567e-05 1.3988267882776e-05 0.00013307645714017 1.70849088747347e-05 -7.19399071547926e-06 1.76357735558812e-05 -5.82418914033139e-06 -8.84146595980246e-06 -8.60703136580687e-06 -7.47028443757745e-06 1.98759585566567e-05 -5.82418914033139e-06 3.67853875958456e-05 1.47332743963073e-05 1.72916147501761e-05 2.05968094171577e-06 1.3988267882776e-05 -8.84146595980246e-06 1.47332743963073e-05 2.87989845843342e-05 2.13208266478294e-05 -6.63122034720298e-05 0.00013307645714017 -8.60703136580687e-06 1.72916147501761e-05 2.13208266478294e-05 0.000241943869730127 944 996 0 0 28 944 996 0 0 87 0 0 0 0 0 0 0 0 812 0 0 0 0 0 2499 +1258 1290 0.995716399368964 0.0862993357014972 -0.03318548907558 0.129136497912422 -0.084044834857853 0.994391664280377 0.0642003406799242 0.0973625065134602 0.0385398204643115 -0.0611362631110408 0.997385100937144 0.350318373743313 0.000100403337400052 2.87252147218839e-05 3.69956466945343e-06 3.76187489567585e-06 7.05012628899883e-06 2.39884212765216e-05 2.87252147218839e-05 0.000141771931158241 -4.69272053534288e-06 6.4687709197108e-06 6.01931221041323e-06 0.000121482950601442 3.69956466945343e-06 -4.69272053534288e-06 1.39237539687918e-05 -4.41262180950781e-06 -7.19148063438217e-06 -3.80007972990611e-06 3.76187489567585e-06 6.4687709197108e-06 -4.41262180950781e-06 3.63962758609706e-05 1.42065205326787e-05 5.60530030772423e-06 7.05012628899883e-06 6.01931221041323e-06 -7.19148063438217e-06 1.42065205326787e-05 2.59226295133107e-05 8.22101144356493e-06 2.39884212765216e-05 0.000121482950601442 -3.80007972990611e-06 5.60530030772423e-06 8.22101144356493e-06 0.000157929800745645 995 1049 0 0 8 995 1049 0 0 69 0 0 0 0 0 0 0 0 937 0 0 0 0 0 2397 +1258 1287 0.993413409820965 0.0810696445524446 -0.0809784534306756 0.144807334386656 -0.0827892671328102 0.99640263711159 -0.0181030937875799 0.111612250014984 0.0792195331688845 0.0246880029409025 0.99655143774684 0.345197720635959 0.00012909121026823 3.73328448450957e-05 7.7883784489494e-06 5.80026984312826e-06 8.96493624996293e-06 4.42369350565078e-05 3.73328448450957e-05 9.8119464976038e-05 -1.95912993513922e-06 4.50634559112899e-06 5.86413300974793e-06 5.42147243864e-05 7.7883784489494e-06 -1.95912993513922e-06 1.58513970988345e-05 -4.30463554935704e-06 -8.90275749450791e-06 2.37239722197354e-06 5.80026984312826e-06 4.50634559112899e-06 -4.30463554935704e-06 4.22230977769841e-05 1.68247985671483e-05 3.03019659452034e-06 8.96493624996293e-06 5.86413300974793e-06 -8.90275749450791e-06 1.68247985671483e-05 3.16535000662479e-05 1.02282189075737e-05 4.42369350565078e-05 5.42147243864e-05 2.37239722197354e-06 3.03019659452034e-06 1.02282189075737e-05 0.000101943930261967 903 957 0 0 45 903 957 0 0 109 0 0 0 0 0 0 0 0 784 0 0 0 0 0 2492 +1258 1284 0.994516526982323 0.0799092747415063 -0.0674639560751129 0.148690575857957 -0.0815005364269793 0.996448457381606 -0.0211691838277139 0.108224222424659 0.0655327408333645 0.0265514517889962 0.997497107908972 0.329879626612563 7.74055826897284e-05 2.3554506280462e-05 2.34266871345301e-06 -2.03315969477392e-06 6.08708610166311e-06 3.45538235317639e-05 2.3554506280462e-05 8.73535401376548e-05 -5.54869366779208e-06 -3.08438326133699e-06 9.13423559335595e-07 3.54323918818611e-05 2.34266871345301e-06 -5.54869366779208e-06 1.69118480912994e-05 -7.26044255935202e-06 -8.27661384232747e-06 -1.27849712418611e-06 -2.03315969477392e-06 -3.08438326133699e-06 -7.26044255935202e-06 4.24890887079207e-05 1.98598924463233e-05 9.2177188001349e-06 6.08708610166311e-06 9.13423559335595e-07 -8.27661384232747e-06 1.98598924463233e-05 3.68470874680442e-05 2.50341846511921e-05 3.45538235317639e-05 3.54323918818611e-05 -1.27849712418611e-06 9.2177188001349e-06 2.50341846511921e-05 0.000220328452076628 1068 1132 0 0 57 1068 1132 0 0 129 0 0 0 0 0 0 0 0 789 0 0 0 0 0 2654 +1258 1299 0.995551049465756 0.0891888474059592 0.0303884419809359 0.128436553027374 -0.0921037974088978 0.989179480420699 0.11419652366643 0.0810614639544098 -0.0198745669259205 -0.116487359885239 0.992993301375429 0.349572347938855 0.000451672916688165 -0.000111720563721707 -7.49634773389298e-06 2.41463696880497e-05 2.44774203853568e-05 -0.000134621707515837 -0.000111720563721707 0.000130782431369555 -8.13581099657049e-06 -5.54736903618598e-06 -1.16453026280376e-05 0.000117122551087592 -7.49634773389298e-06 -8.13581099657049e-06 2.23556461227986e-05 -7.93930163421326e-06 -4.87302212767249e-06 -6.89553571062359e-06 2.41463696880497e-05 -5.54736903618598e-06 -7.93930163421326e-06 3.93587224125508e-05 1.19098619260969e-05 -6.77083932076267e-06 2.44774203853568e-05 -1.16453026280376e-05 -4.87302212767249e-06 1.19098619260969e-05 3.09018390523703e-05 -7.42539274237306e-06 -0.000134621707515837 0.000117122551087592 -6.89553571062359e-06 -6.77083932076267e-06 -7.42539274237306e-06 0.000274240863033753 1124 1175 0 0 1 1124 1180 0 0 46 0 0 0 0 0 0 0 0 998 0 0 0 0 0 2026 +1258 1314 0.994522788539134 0.0876488796127784 0.0569394149861911 0.133272155121027 -0.09507323220974 0.984936734226058 0.144432372026842 0.0957286651782012 -0.0434223858572727 -0.149054699606325 0.987875089741477 0.36073214244388 0.00015206354614757 2.28109824731899e-05 -2.64445694227303e-06 3.0437248996986e-06 4.56834064834786e-06 -7.84208669187798e-06 2.28109824731899e-05 0.000142657055147339 -2.24930742617888e-05 1.47110559370579e-05 -6.39902377024643e-06 5.74353992529686e-05 -2.64445694227303e-06 -2.24930742617888e-05 2.37281586672424e-05 -3.74316159204353e-06 -6.60078854712679e-06 -1.26718242572953e-05 3.0437248996986e-06 1.47110559370579e-05 -3.74316159204353e-06 4.29216263101066e-05 5.46653207481657e-06 5.93372306567486e-06 4.56834064834786e-06 -6.39902377024643e-06 -6.60078854712679e-06 5.46653207481657e-06 3.42253000622855e-05 -7.41488876196948e-06 -7.84208669187798e-06 5.74353992529686e-05 -1.26718242572953e-05 5.93372306567486e-06 -7.41488876196948e-06 0.000164080078883527 1046 1100 0 0 8 1046 1101 0 0 51 0 0 0 0 0 0 0 0 1101 0 0 0 0 0 1682 +1258 1316 0.99518472290059 0.0884145631094661 0.042311137250594 0.132103019172539 -0.0929938562087901 0.988100864852133 0.122510503981842 0.0873289760461527 -0.0309759586243142 -0.125855257771093 0.991564896554268 0.340034086303043 0.000177883830724188 -1.37642224023346e-06 8.96945373755082e-06 5.62415593748231e-06 8.00966346820807e-06 3.8588272050927e-05 -1.37642224023346e-06 0.000119346346254416 -6.33261035754623e-06 3.42812847481008e-06 -2.92937584218584e-06 3.8132456891057e-07 8.96945373755082e-06 -6.33261035754623e-06 2.37818794841239e-05 -2.71617477764659e-06 -9.29379807458608e-06 -5.61397783161684e-06 5.62415593748231e-06 3.42812847481008e-06 -2.71617477764659e-06 3.80952101411553e-05 4.76036748192385e-06 1.14428293099804e-05 8.00966346820807e-06 -2.92937584218584e-06 -9.29379807458608e-06 4.76036748192385e-06 2.96559269928593e-05 1.34203793899587e-05 3.8588272050927e-05 3.8132456891057e-07 -5.61397783161684e-06 1.14428293099804e-05 1.34203793899587e-05 0.00016165481322393 1035 1087 0 0 7 1035 1089 0 0 58 0 0 0 0 0 0 0 0 1076 0 0 0 0 0 2025 +1258 1317 0.994939267184849 0.0875368557472501 0.0493270057834629 0.132724173428296 -0.093385538355395 0.986781059081554 0.132447282584277 0.0914052388369243 -0.0370809363386323 -0.136383431265574 0.989961900194386 0.354741534201768 0.000118191850321001 1.22974966596332e-05 2.48722003846657e-06 2.44172391974298e-06 2.4381153398001e-06 2.98465316462583e-05 1.22974966596332e-05 0.000121645688088092 2.69737170946929e-06 1.81461666810796e-05 9.76516662965729e-06 5.18864218729999e-05 2.48722003846657e-06 2.69737170946929e-06 2.0707612246849e-05 -2.86589129857817e-06 -8.77995926358547e-06 -1.28371838582612e-06 2.44172391974298e-06 1.81461666810796e-05 -2.86589129857817e-06 4.02571397203056e-05 7.36332453773012e-06 1.92870475546882e-05 2.4381153398001e-06 9.76516662965729e-06 -8.77995926358547e-06 7.36332453773012e-06 2.86468105026035e-05 1.09012544836636e-05 2.98465316462583e-05 5.18864218729999e-05 -1.28371838582612e-06 1.92870475546882e-05 1.09012544836636e-05 0.000144355362795533 1061 1113 0 0 8 1061 1115 0 0 57 0 0 0 0 0 0 0 0 1000 0 0 0 0 0 1997 +1258 1318 0.995134680075912 0.0882716326294757 0.0437617113826677 0.128939949749939 -0.0931778747965186 0.987528019221702 0.126910578363136 0.0878610672835178 -0.0320133122094127 -0.130370741061743 0.990948342607421 0.348985668291729 0.000166283466810489 -5.25989568278735e-05 9.44397301850964e-06 5.53527375481705e-06 1.67562119306118e-05 -4.16084375442383e-05 -5.25989568278735e-05 0.000112709026652631 2.76044993848126e-06 5.80998672411005e-06 8.93203612493698e-06 8.23319495676542e-05 9.44397301850964e-06 2.76044993848126e-06 1.96574422506953e-05 -2.51234831407991e-06 -6.45239433602732e-06 1.59661760056408e-06 5.53527375481705e-06 5.80998672411005e-06 -2.51234831407991e-06 4.4590470893588e-05 7.17797869652308e-06 8.29688861037424e-06 1.67562119306118e-05 8.93203612493698e-06 -6.45239433602732e-06 7.17797869652308e-06 2.97061685348421e-05 1.34960311883144e-05 -4.16084375442383e-05 8.23319495676542e-05 1.59661760056408e-06 8.29688861037424e-06 1.34960311883144e-05 0.000166675781953998 1192 1242 0 0 2 1192 1247 0 0 44 0 0 0 0 0 0 0 0 1106 0 0 0 0 0 2019 +1258 1313 0.994760916616598 0.0877943585728642 0.052372410436076 0.132779462771886 -0.0941599704867057 0.986363436322776 0.134985449006433 0.0892807266213937 -0.0398072698140449 -0.139209633604521 0.989462510245662 0.348231222087758 0.00011062637217412 1.25738382407341e-05 -5.80743057592009e-07 6.78052314399976e-06 6.02260167407538e-06 1.92362137661144e-05 1.25738382407341e-05 0.000116277370239164 5.82476111711263e-06 3.58744983441603e-06 1.49659020036613e-05 5.71462208637894e-05 -5.80743057592009e-07 5.82476111711263e-06 2.26224138800938e-05 -4.48919275229759e-06 -7.05864083584334e-06 -6.79469746259066e-06 6.78052314399976e-06 3.58744983441603e-06 -4.48919275229759e-06 3.80089115480461e-05 9.13244428245036e-06 8.88778969634753e-06 6.02260167407538e-06 1.49659020036613e-05 -7.05864083584334e-06 9.13244428245036e-06 2.83655297115772e-05 1.05589832095948e-05 1.92362137661144e-05 5.71462208637894e-05 -6.79469746259066e-06 8.88778969634753e-06 1.05589832095948e-05 0.000154787996878337 1152 1204 0 0 6 1152 1207 0 0 54 0 0 0 0 0 0 0 0 1103 0 0 0 0 0 2006 +1259 1290 0.99802134416946 0.0573632191414137 -0.0257460224485086 0.0904985028855556 -0.05428665254611 0.992725979507916 0.107462034995558 0.0772686116256311 0.0317231136164609 -0.105851739238346 0.99387577360689 0.280562887076775 0.00012028750091953 2.60317273532243e-05 2.66554554920766e-06 1.368873203203e-05 -3.83141212251416e-06 2.84332111077674e-05 2.60317273532243e-05 0.000101077463354462 -5.78109614767061e-06 5.83704604371724e-06 -9.28737041773088e-06 6.12651105696574e-05 2.66554554920766e-06 -5.78109614767061e-06 1.31844176384133e-05 -3.20174064154316e-06 -6.93672459838544e-06 -4.52121764912067e-06 1.368873203203e-05 5.83704604371724e-06 -3.20174064154316e-06 3.16728991134433e-05 6.71567623830373e-06 1.01780996175508e-05 -3.83141212251416e-06 -9.28737041773088e-06 -6.93672459838544e-06 6.71567623830373e-06 2.10175490864258e-05 1.05000501606506e-06 2.84332111077674e-05 6.12651105696574e-05 -4.52121764912067e-06 1.01780996175508e-05 1.05000501606506e-06 8.95392078812362e-05 1176 1239 0 0 8 1176 1239 0 0 54 0 0 0 0 0 0 0 0 942 0 0 0 0 0 2229 +1258 1315 0.995438130596934 0.0878827577572604 0.0371422810643052 0.128418185132047 -0.0917393124703216 0.988574914956187 0.119597391555335 0.0889028932850411 -0.0262073787539666 -0.122459211202531 0.992127469073657 0.346497747163397 0.000182992713535033 -3.66455578252608e-05 1.93697548631597e-06 2.2106659490371e-05 7.79807138293353e-06 -4.78585627567528e-05 -3.66455578252608e-05 7.93257454015453e-05 3.80320132775287e-06 -7.35868791563443e-06 1.64745582448459e-06 6.78003892491869e-05 1.93697548631597e-06 3.80320132775287e-06 2.19589402854632e-05 -2.63672551133064e-06 -1.07538027426243e-05 -3.55763008273532e-06 2.2106659490371e-05 -7.35868791563443e-06 -2.63672551133064e-06 3.5644408442478e-05 7.42300744284219e-06 -3.94144806135126e-06 7.79807138293353e-06 1.64745582448459e-06 -1.07538027426243e-05 7.42300744284219e-06 2.84121377272197e-05 5.9875510464187e-06 -4.78585627567528e-05 6.78003892491869e-05 -3.55763008273532e-06 -3.94144806135126e-06 5.9875510464187e-06 0.000191217838466936 1005 1059 0 0 5 1005 1060 0 0 55 0 0 0 0 0 0 0 0 1076 0 0 0 0 0 2013 +1259 1294 0.998060521234819 0.0576111323005602 0.0235829045609205 0.082181177578693 -0.0605832622051096 0.986026281861042 0.155183245938072 0.0593084691914529 -0.0143130811871196 -0.156311000618436 0.98760417515956 0.262805591617923 0.000213100394286651 -8.24329845942798e-06 4.93492003846971e-06 7.2991646666234e-06 1.23086417413135e-05 -2.57691015725277e-07 -8.24329845942798e-06 0.000115452574965833 2.85393458739677e-07 -5.86977312730792e-06 5.1162224953484e-06 9.20547423123621e-05 4.93492003846971e-06 2.85393458739677e-07 1.29823241681463e-05 -1.44157904413557e-06 -7.61871446051843e-06 -2.71008278808171e-06 7.2991646666234e-06 -5.86977312730792e-06 -1.44157904413557e-06 2.41560309923485e-05 6.05568075209453e-06 -3.56432836233095e-06 1.23086417413135e-05 5.1162224953484e-06 -7.61871446051843e-06 6.05568075209453e-06 2.15825778440907e-05 7.91384374387685e-06 -2.57691015725277e-07 9.20547423123621e-05 -2.71008278808171e-06 -3.56432836233095e-06 7.91384374387685e-06 0.000146840150816796 1253 1292 0 0 3 1253 1307 0 0 26 0 0 0 0 0 0 0 0 1092 0 0 0 0 0 1796 +1259 1292 0.9982088103574 0.0585126173478238 0.0124677398100978 0.0835391950055386 -0.0597290554305147 0.986576744403993 0.15198278632331 0.0585546571887122 -0.00340747153233042 -0.152455242652805 0.988304501722739 0.249728499279726 0.000192451674523151 5.74922840448098e-05 3.22254877380492e-06 1.27218074603323e-05 2.00577390136279e-06 7.61101582863965e-05 5.74922840448098e-05 0.000125139059620906 6.61704593569415e-07 7.93622535667849e-06 -4.98240003595244e-06 8.15435104954771e-05 3.22254877380492e-06 6.61704593569415e-07 1.41487985903924e-05 -1.48602936427519e-08 -5.9888125264777e-06 -1.75706933280301e-06 1.27218074603323e-05 7.93622535667849e-06 -1.48602936427519e-08 2.77226396922579e-05 7.47615565410051e-06 7.98878578256371e-06 2.00577390136279e-06 -4.98240003595244e-06 -5.9888125264777e-06 7.47615565410051e-06 2.53512063804543e-05 -3.35810055140258e-06 7.61101582863965e-05 8.15435104954771e-05 -1.75706933280301e-06 7.98878578256371e-06 -3.35810055140258e-06 0.000140496985134887 1181 1224 0 0 2 1181 1235 0 0 26 0 0 0 0 0 0 0 0 1058 0 0 0 0 0 2142 +1259 1261 0.999343427072447 0.0353839769643762 0.00779031073067787 0.0445087314511978 -0.034912914558923 0.997929968137239 -0.054008028020013 0.0649236117273815 -0.00968520335859608 0.053700585358017 0.998510112101079 0.0999757401471197 0.000161850127063208 2.12538140439518e-05 3.9424547874029e-06 1.37240067806263e-05 2.26487330359089e-07 3.28988910697899e-05 2.12538140439518e-05 0.000132891058418187 -1.30902242057582e-05 -5.67079015593259e-06 -2.9399437068725e-06 5.78898857385022e-05 3.9424547874029e-06 -1.30902242057582e-05 1.48028803816919e-05 6.58175588890969e-06 -5.93311774209107e-06 -1.07815563866483e-06 1.37240067806263e-05 -5.67079015593259e-06 6.58175588890969e-06 2.05590899109032e-05 -7.02960960010765e-06 -1.19477034666915e-05 2.26487330359089e-07 -2.9399437068725e-06 -5.93311774209107e-06 -7.02960960010765e-06 2.13995503444659e-05 3.08691606254578e-05 3.28988910697899e-05 5.78898857385022e-05 -1.07815563866483e-06 -1.19477034666915e-05 3.08691606254578e-05 0.000170112011788987 1645 1715 0 0 0 1645 1725 0 0 43 0 0 0 0 0 0 0 0 1210 0 0 0 0 0 3405 +1259 1289 0.9977687302883 0.0545077989657394 -0.0385546457743425 0.0993937911964835 -0.0521051535915266 0.996789398273687 0.0607943127141384 0.0761821646814548 0.0417446263377445 -0.0586497684657967 0.997405429517421 0.265366568235821 0.000125282760349378 -6.35798658996671e-06 6.40440210103138e-06 1.14734623484748e-05 5.61986469933948e-06 -2.55033952038091e-06 -6.35798658996671e-06 5.65628276688644e-05 -2.2870151034822e-07 -9.41073514826353e-07 3.7561032237223e-07 3.1519569112917e-05 6.40440210103138e-06 -2.2870151034822e-07 1.26143887466931e-05 -1.46518972328556e-06 -6.29729688060368e-06 -5.52964380024186e-07 1.14734623484748e-05 -9.41073514826353e-07 -1.46518972328556e-06 2.97513226332992e-05 5.78621071023123e-06 -2.36773838731869e-06 5.61986469933948e-06 3.7561032237223e-07 -6.29729688060368e-06 5.78621071023123e-06 1.91219720256783e-05 3.83096935290922e-06 -2.55033952038091e-06 3.1519569112917e-05 -5.52964380024186e-07 -2.36773838731869e-06 3.83096935290922e-06 8.69554991463583e-05 1157 1220 0 0 24 1157 1220 0 0 81 0 0 0 0 0 0 0 0 827 0 0 0 0 0 2628 +1259 1262 0.999235310816799 0.0389659407585696 -0.00323250331102661 0.0596894598975514 -0.0390976248517042 0.996629608987629 -0.0721165599576154 0.0860323312857717 0.000411518907899395 0.0721877964060725 0.997390972839751 0.138160963934134 0.000151965284824085 3.55315801581792e-05 -6.87930030159867e-07 1.26025937222951e-05 -1.24227265196279e-05 2.95835902563456e-05 3.55315801581792e-05 0.000191827207080572 -3.23429224442013e-05 1.85127011574053e-05 -2.09282865167697e-05 1.9096290471026e-05 -6.87930030159867e-07 -3.23429224442013e-05 2.22544907723406e-05 -5.66575813008402e-06 -7.25491933213698e-06 -4.99073730243824e-06 1.26025937222951e-05 1.85127011574053e-05 -5.66575813008402e-06 3.08146336312359e-05 4.41026135321909e-08 9.48239698901211e-06 -1.24227265196279e-05 -2.09282865167697e-05 -7.25491933213698e-06 4.41026135321909e-08 3.79038662489512e-05 5.53670481359503e-05 2.95835902563456e-05 1.9096290471026e-05 -4.99073730243824e-06 9.48239698901211e-06 5.53670481359503e-05 0.000223679225863718 1571 1652 0 0 17 1571 1652 0 0 91 0 0 0 0 0 0 0 0 968 0 0 0 0 0 3313 +1259 1288 0.996656161146029 0.0527716831473205 -0.0623830578559499 0.102494509588125 -0.0507995934845373 0.998170503792651 0.0327879041741166 0.0887701618237569 0.0639992011783408 -0.0295092327267943 0.99751356253056 0.277580649481837 0.000126542718890059 8.5255445941641e-06 9.41857014387793e-06 1.00123026957607e-05 7.28885080713279e-06 1.8648804843315e-05 8.5255445941641e-06 9.50950923922908e-05 -1.14472599837899e-06 -6.7093116846068e-06 -2.89651385110739e-06 7.21738201763653e-05 9.41857014387793e-06 -1.14472599837899e-06 1.35824056593894e-05 -1.01137830573851e-06 -6.64756924074341e-06 1.11412994731599e-06 1.00123026957607e-05 -6.7093116846068e-06 -1.01137830573851e-06 3.16791367207303e-05 6.24806274191415e-06 -3.90161989551263e-06 7.28885080713279e-06 -2.89651385110739e-06 -6.64756924074341e-06 6.24806274191415e-06 2.20334771750668e-05 7.2310821673125e-06 1.8648804843315e-05 7.21738201763653e-05 1.11412994731599e-06 -3.90161989551263e-06 7.2310821673125e-06 0.000132308526840901 1119 1183 0 0 44 1119 1183 0 0 103 0 0 0 0 0 0 0 0 791 0 0 0 0 0 2578 +1259 1285 0.995715465212657 0.0502928126642231 -0.0775973281154902 0.0999842651011714 -0.0487528986462147 0.998576971087546 0.0216145249129682 0.0905320018803046 0.0785739601263268 -0.0177388220562351 0.996750453715534 0.275029164625631 0.000118404898157246 3.63343380081822e-05 3.6486012952498e-06 9.36461495575927e-06 1.19239378691654e-05 4.08922751682735e-05 3.63343380081822e-05 6.80927840555383e-05 3.09017566651255e-06 2.40260116684272e-06 5.2275361187608e-06 4.58225467024757e-05 3.6486012952498e-06 3.09017566651255e-06 1.24918295701316e-05 4.02461035906965e-07 -6.55325826397077e-06 6.32886379129926e-07 9.36461495575927e-06 2.40260116684272e-06 4.02461035906965e-07 3.18174746132799e-05 1.06640438713931e-05 8.33923104804013e-06 1.19239378691654e-05 5.2275361187608e-06 -6.55325826397077e-06 1.06640438713931e-05 2.72844600578117e-05 1.15412223071683e-05 4.08922751682735e-05 4.58225467024757e-05 6.32886379129926e-07 8.33923104804013e-06 1.15412223071683e-05 8.71998451005822e-05 1133 1197 0 0 47 1133 1197 0 0 104 0 0 0 0 0 0 0 0 837 0 0 0 0 0 2600 +1259 1291 0.998298618369068 0.0573235444874526 -0.010671448346135 0.0872505336155584 -0.0554406670873017 0.989857638358235 0.130798272988493 0.0731155578109296 0.0180610352783049 -0.129984102994375 0.991351568301288 0.283815600703317 0.000118094933611276 1.6545928490091e-06 1.14885394407948e-06 7.60557116055306e-06 9.63539280577426e-06 2.19261120031087e-05 1.6545928490091e-06 7.24744083693494e-05 -4.23346503258871e-06 4.5713772158831e-06 3.23450879686029e-06 4.96546871099711e-05 1.14885394407948e-06 -4.23346503258871e-06 1.30556429600674e-05 1.60608645491219e-09 -6.69271314813437e-06 -5.5962397777435e-06 7.60557116055306e-06 4.5713772158831e-06 1.60608645491219e-09 3.15062526427093e-05 6.3013354075257e-06 4.5764485792125e-06 9.63539280577426e-06 3.23450879686029e-06 -6.69271314813437e-06 6.3013354075257e-06 2.20203262137122e-05 3.65389263329841e-06 2.19261120031087e-05 4.96546871099711e-05 -5.5962397777435e-06 4.5764485792125e-06 3.65389263329841e-06 8.43184326595469e-05 1046 1099 0 0 8 1046 1100 0 0 48 0 0 0 0 0 0 0 0 952 0 0 0 0 0 2055 +1259 1298 0.997719785599065 0.0589372983618173 0.0328880568894689 0.0866231424522253 -0.0632794666586737 0.986331833677324 0.152135541456038 0.0597710183776516 -0.0234720796596429 -0.153869778502921 0.987812306432712 0.26622136110664 0.000110078534131498 4.33873002455442e-05 -6.76402647048218e-06 3.2820220112306e-06 2.76221404231647e-06 -3.73926190398036e-05 4.33873002455442e-05 8.49506411802986e-05 -6.99862480543909e-06 2.15732046530793e-06 -4.27771853050657e-06 -3.90236914240829e-06 -6.76402647048218e-06 -6.99862480543909e-06 1.56675445058001e-05 -1.68958199079664e-06 -4.39073766315523e-06 -1.46250471916349e-06 3.2820220112306e-06 2.15732046530793e-06 -1.68958199079664e-06 2.38708647488468e-05 1.09660873467718e-06 -3.89074700067097e-07 2.76221404231647e-06 -4.27771853050657e-06 -4.39073766315523e-06 1.09660873467718e-06 2.49019195069134e-05 1.17546134748956e-06 -3.73926190398036e-05 -3.90236914240829e-06 -1.46250471916349e-06 -3.89074700067097e-07 1.17546134748956e-06 0.000224119523733964 1149 1196 0 0 5 1149 1204 0 0 35 0 0 0 0 0 0 0 0 1007 0 0 0 0 0 1779 +1259 1263 0.996142978316758 0.0624922636193235 -0.0615945106154055 0.0710524974773716 -0.0659542277590429 0.996257111312497 -0.0558731420271705 0.0965976744868942 0.0578723300976089 0.0597200564886961 0.996536155020007 0.198935448935746 0.000163158281441905 6.24720705883632e-05 -1.16219043824756e-05 2.10679665637845e-05 -1.93027293996058e-05 -3.21866900492477e-06 6.24720705883632e-05 0.000159933122393705 -2.71823106782426e-05 1.27636528222664e-05 -2.36197472135558e-05 -2.12993105014575e-06 -1.16219043824756e-05 -2.71823106782426e-05 1.80333527614647e-05 2.5820513893017e-07 -2.65940999815854e-06 4.2425756680553e-06 2.10679665637845e-05 1.27636528222664e-05 2.5820513893017e-07 2.50933658111374e-05 -4.4471823315464e-06 -3.08488693833861e-06 -1.93027293996058e-05 -2.36197472135558e-05 -2.65940999815854e-06 -4.4471823315464e-06 2.95115827476442e-05 3.09445027888488e-05 -3.21866900492477e-06 -2.12993105014575e-06 4.2425756680553e-06 -3.08488693833861e-06 3.09445027888488e-05 0.000133507397749013 1517 1589 0 0 8 1517 1597 0 0 55 0 0 0 0 0 0 0 0 828 0 0 0 0 0 3272 +1259 1297 0.997707358022226 0.058296824413451 0.0343730710239309 0.0873137702351271 -0.0627159750068409 0.987308535892919 0.145906002042143 0.0552673214589345 -0.0254309698448612 -0.147727232480297 0.988701133081409 0.259391130922618 9.48690176386286e-05 -7.5243127356967e-06 -3.72871989436059e-07 4.0351220940184e-06 -1.39523370915628e-06 -8.02138509994493e-06 -7.5243127356967e-06 5.89610703997864e-05 -1.71315929833487e-06 1.66852788920711e-06 -2.39165038661394e-06 3.50388330161855e-05 -3.72871989436059e-07 -1.71315929833487e-06 1.17751439005867e-05 -4.44881814631808e-07 -7.57790612146161e-06 3.42275006743928e-08 4.0351220940184e-06 1.66852788920711e-06 -4.44881814631808e-07 2.50655610366248e-05 7.02807480421374e-06 1.69849003594017e-06 -1.39523370915628e-06 -2.39165038661394e-06 -7.57790612146161e-06 7.02807480421374e-06 1.98671632060959e-05 -5.95517668106321e-07 -8.02138509994493e-06 3.50388330161855e-05 3.42275006743928e-08 1.69849003594017e-06 -5.95517668106321e-07 8.67929363199426e-05 1319 1365 0 0 5 1319 1384 0 0 34 0 0 0 0 0 0 0 0 1107 0 0 0 0 0 2067 +1259 1286 0.994638332180802 0.0496394525101842 -0.0907221743075097 0.103319198193665 -0.0493167394202223 0.998766367369768 0.00579677703174484 0.0863222535822864 0.0908980053111778 -0.00129157480891923 0.995859369823351 0.274850605647604 0.000136387179957192 -5.32119255523279e-06 1.05123956494164e-05 7.26783779836131e-06 7.78823000855554e-06 3.17907099205162e-05 -5.32119255523279e-06 6.2727408685798e-05 -4.06924660643457e-07 -9.23735099595661e-06 -3.80668869253626e-06 5.22429304863862e-05 1.05123956494164e-05 -4.06924660643457e-07 1.25259728328886e-05 -9.0225319471921e-07 -5.7289954110097e-06 3.19268765389158e-06 7.26783779836131e-06 -9.23735099595661e-06 -9.0225319471921e-07 2.86854751013181e-05 9.76818003784529e-06 -2.66559170115831e-06 7.78823000855554e-06 -3.80668869253626e-06 -5.7289954110097e-06 9.76818003784529e-06 2.59985924002728e-05 3.52826631233419e-06 3.17907099205162e-05 5.22429304863862e-05 3.19268765389158e-06 -2.66559170115831e-06 3.52826631233419e-06 9.55773835904748e-05 1074 1137 0 0 42 1074 1137 0 0 103 0 0 0 0 0 0 0 0 831 0 0 0 0 0 2643 +1259 1314 0.99785009571323 0.0574544291788897 0.0315305415878991 0.0837407373060054 -0.0615677888068939 0.986688947502828 0.15051354841738 0.06234027363518 -0.0224631668855486 -0.152131224419872 0.988105002866589 0.271178992133312 0.00024108422513153 2.11227033168049e-05 -7.47549849544305e-06 1.73202618883829e-05 -3.48447327021398e-06 7.49063981125827e-06 2.11227033168049e-05 0.000149808305165529 -1.12720051759816e-05 8.80420666010048e-06 -9.27263565686815e-06 5.1784101664318e-05 -7.47549849544305e-06 -1.12720051759816e-05 1.82446307696085e-05 2.41660373406066e-07 -7.01868653200045e-06 -2.16832356154044e-06 1.73202618883829e-05 8.80420666010048e-06 2.41660373406066e-07 2.83036530425925e-05 -3.72608448358059e-06 5.59145611345103e-06 -3.48447327021398e-06 -9.27263565686815e-06 -7.01868653200045e-06 -3.72608448358059e-06 2.45365598900579e-05 6.36485692488957e-06 7.49063981125827e-06 5.1784101664318e-05 -2.16832356154044e-06 5.59145611345103e-06 6.36485692488957e-06 0.000143556854630994 1170 1213 0 0 4 1170 1225 0 0 30 0 0 0 0 0 0 0 0 1109 0 0 0 0 0 1788 +1259 1316 0.997446727680564 0.0586532413687238 0.0407409218879172 0.0893671560744205 -0.0641708681459844 0.986464494620989 0.150896986495914 0.0580858042328742 -0.0313388755497996 -0.153126085723823 0.987709611550973 0.25374781681641 0.000164935897163306 -2.67166811447132e-05 3.62998685829822e-06 9.50170460526392e-06 2.41374966923938e-06 -7.4004836872412e-05 -2.67166811447132e-05 0.000125447128253257 -1.8680236339213e-06 -6.69422576329523e-06 -4.66737566153695e-06 6.05724778397743e-05 3.62998685829822e-06 -1.8680236339213e-06 1.32464644592867e-05 1.96137995754699e-06 -7.53442058495029e-06 -1.4642092320884e-06 9.50170460526392e-06 -6.69422576329523e-06 1.96137995754699e-06 2.60529040863798e-05 3.02459408172744e-07 -3.9449298109048e-06 2.41374966923938e-06 -4.66737566153695e-06 -7.53442058495029e-06 3.02459408172744e-07 2.11933304517113e-05 5.51001059165814e-06 -7.4004836872412e-05 6.05724778397743e-05 -1.4642092320884e-06 -3.9449298109048e-06 5.51001059165814e-06 0.000155341521158032 1185 1230 0 0 5 1185 1239 0 0 33 0 0 0 0 0 0 0 0 1093 0 0 0 0 0 2112 +1259 1317 0.997376526452327 0.0580929115553678 0.0431888655663785 0.0892820090214655 -0.0640353003198843 0.986279942027869 0.152155697449836 0.0586712876006414 -0.0337571443524586 -0.154522132979466 0.987412459727263 0.26533150068371 0.000111675860629413 1.38632266419496e-05 -1.48870120570328e-06 4.66449494776628e-06 1.78661232279756e-06 4.70230427932252e-06 1.38632266419496e-05 7.22650363505514e-05 -8.75528239583654e-07 -4.43682351517555e-06 2.02595070925759e-06 3.75016882120788e-05 -1.48870120570328e-06 -8.75528239583654e-07 1.3533875732501e-05 1.67607049598893e-06 -8.47274306546579e-06 -2.3548529549262e-06 4.66449494776628e-06 -4.43682351517555e-06 1.67607049598893e-06 2.73434624342288e-05 1.62010381050651e-06 -5.41668952391484e-07 1.78661232279756e-06 2.02595070925759e-06 -8.47274306546579e-06 1.62010381050651e-06 1.9904013451187e-05 1.47902696046935e-06 4.70230427932252e-06 3.75016882120788e-05 -2.3548529549262e-06 -5.41668952391484e-07 1.47902696046935e-06 0.000127909615152433 1238 1279 0 0 4 1238 1292 0 0 34 0 0 0 0 0 0 0 0 1005 0 0 0 0 0 2094 +1259 1296 0.997577954628298 0.058859884384465 0.0370639777933812 0.0884400942205217 -0.0642499689040934 0.983894384055365 0.166804623797236 0.0615240230246153 -0.026648938730161 -0.168781974850876 0.98529309295762 0.2665612723435 0.000144371231427511 3.89604925989957e-05 1.59560243359436e-06 6.68221395889084e-06 -1.56881858608035e-06 4.04612702747022e-05 3.89604925989957e-05 7.59468115893103e-05 -2.73934315389977e-06 4.72703620682073e-06 2.52437807042815e-06 4.02291097220332e-05 1.59560243359436e-06 -2.73934315389977e-06 1.3659297870293e-05 1.30047318042566e-06 -7.67953622895182e-06 -3.54455549056988e-06 6.68221395889084e-06 4.72703620682073e-06 1.30047318042566e-06 2.71628505762748e-05 5.70714958964726e-06 4.18383265700483e-06 -1.56881858608035e-06 2.52437807042815e-06 -7.67953622895182e-06 5.70714958964726e-06 1.88678262861668e-05 3.50157632701609e-06 4.04612702747022e-05 4.02291097220332e-05 -3.54455549056988e-06 4.18383265700483e-06 3.50157632701609e-06 8.71822975732257e-05 1169 1215 0 0 6 1169 1224 0 0 34 0 0 0 0 0 0 0 0 1076 0 0 0 0 0 1960 +1259 1287 0.995466014174201 0.0513593519408394 -0.0800601748208598 0.100884876692837 -0.0498714957777915 0.9985457337643 0.0204756316142065 0.0889805256832977 0.0809953611820786 -0.0163900747201456 0.996579709264468 0.267888359494891 0.000123951807284197 1.10826277379936e-05 2.53117810462241e-06 9.53069178611476e-06 -3.8358268400931e-07 3.8592497853576e-05 1.10826277379936e-05 6.88003058738539e-05 -1.80398255998815e-06 -3.77606534759511e-06 -2.06493793824504e-06 3.3379088547526e-05 2.53117810462241e-06 -1.80398255998815e-06 1.14337126830846e-05 1.20428860917707e-07 -7.13953418417148e-06 1.82411893686094e-06 9.53069178611476e-06 -3.77606534759511e-06 1.20428860917707e-07 2.64647479627603e-05 6.66795985181475e-06 8.95805940972654e-07 -3.8358268400931e-07 -2.06493793824504e-06 -7.13953418417148e-06 6.66795985181475e-06 2.24436184444791e-05 4.69189474048743e-06 3.8592497853576e-05 3.3379088547526e-05 1.82411893686094e-06 8.95805940972654e-07 4.69189474048743e-06 8.81879056726038e-05 951 1005 0 0 35 951 1005 0 0 92 0 0 0 0 0 0 0 0 789 0 0 0 0 0 2534 +1259 1312 0.997759721324099 0.0596366507780429 0.0303151511167858 0.0876204532162796 -0.0636248015913919 0.985939802832778 0.154514044062401 0.0616182522783337 -0.0206742140288771 -0.15609668501938 0.987525392990099 0.26549038603984 0.000183748984385903 2.49358604053354e-05 1.93117108478984e-06 8.38843407627752e-06 -6.83285241774289e-06 -6.31763441250038e-06 2.49358604053354e-05 0.000102797102561452 -8.97297571104025e-06 7.71832275134125e-07 -3.48760263044232e-06 1.67132199816866e-05 1.93117108478984e-06 -8.97297571104025e-06 1.7883510296996e-05 -1.54034509927958e-06 -9.15751135340925e-06 -3.08733340330958e-07 8.38843407627752e-06 7.71832275134125e-07 -1.54034509927958e-06 2.84561441486137e-05 1.82600892131227e-06 1.98390508190445e-06 -6.83285241774289e-06 -3.48760263044232e-06 -9.15751135340925e-06 1.82600892131227e-06 2.38653339779651e-05 6.01331849267125e-06 -6.31763441250038e-06 1.67132199816866e-05 -3.08733340330958e-07 1.98390508190445e-06 6.01331849267125e-06 0.000144257879429437 1265 1306 0 0 3 1265 1320 0 0 28 0 0 0 0 0 0 0 0 1101 0 0 0 0 0 1878 +1259 1313 0.997883861544334 0.0582184675328936 0.0289552915283146 0.0857604892348968 -0.0618509507947203 0.987271714429672 0.146523110030071 0.0582916108015906 -0.0200563893848659 -0.148003959153857 0.988783378359298 0.267585832754192 9.40364517836654e-05 -2.89605952106127e-06 1.74574012393236e-06 1.54158060448597e-06 4.46123509733834e-06 9.02554711735155e-06 -2.89605952106127e-06 8.36291340071003e-05 2.56178710547723e-06 -3.39248473042781e-06 -8.26987482204972e-07 3.71502661312823e-05 1.74574012393236e-06 2.56178710547723e-06 1.52647201413741e-05 -4.28467227233397e-06 -5.49020379935508e-06 -6.81701991513702e-07 1.54158060448597e-06 -3.39248473042781e-06 -4.28467227233397e-06 3.42986829597403e-05 5.87864747016385e-06 -7.5536005365639e-06 4.46123509733834e-06 -8.26987482204972e-07 -5.49020379935508e-06 5.87864747016385e-06 2.20265208553231e-05 -2.8416210496535e-06 9.02554711735155e-06 3.71502661312823e-05 -6.81701991513702e-07 -7.5536005365639e-06 -2.8416210496535e-06 0.000117678019664984 1266 1309 0 0 2 1266 1326 0 0 25 0 0 0 0 0 0 0 0 1111 0 0 0 0 0 2087 +1260 1263 0.995864441596148 0.0516882065858605 -0.0747150805683214 0.0432579930392299 -0.0547149676521137 0.997738249415356 -0.0390468688681935 0.0552160451919416 0.072527831066574 0.0429734214779223 0.996440163164482 0.129160964430073 0.000143588606418312 4.42765018922147e-05 -2.31573151681593e-06 8.73580450740298e-06 -2.18859851936914e-05 -5.12353336946991e-05 4.42765018922147e-05 8.34090083184089e-05 -8.27596845184792e-06 1.66205329320174e-05 -7.95657587950064e-06 -1.00780323743129e-05 -2.31573151681593e-06 -8.27596845184792e-06 1.56163609175019e-05 1.1756452861715e-06 -6.4435997951182e-06 4.4253802974738e-06 8.73580450740298e-06 1.66205329320174e-05 1.1756452861715e-06 2.36555626396116e-05 -3.58281530830324e-06 -5.91669531798822e-06 -2.18859851936914e-05 -7.95657587950064e-06 -6.4435997951182e-06 -3.58281530830324e-06 2.72424576602945e-05 3.4364748943957e-05 -5.12353336946991e-05 -1.00780323743129e-05 4.4253802974738e-06 -5.91669531798822e-06 3.4364748943957e-05 0.000131868392228325 1593 1608 0 0 0 1603 1674 0 0 4 0 0 0 0 0 0 0 0 840 0 0 0 0 0 3370 +1259 1299 0.997700008907667 0.0586412064665617 0.0339985459952034 0.0878824455906148 -0.0631615330112175 0.986316241544903 0.152285562061572 0.0560650979123018 -0.0246031090172515 -0.154082706910548 0.987751591473182 0.272119265748448 0.000117917131308095 2.74187509211783e-05 -2.46062667467125e-07 1.01062666440643e-06 -7.86524440990042e-07 -8.08895587829294e-06 2.74187509211783e-05 6.6537581557802e-05 -3.41696457649961e-06 1.97308062774172e-06 -1.82231408361968e-06 4.74481731781104e-06 -2.46062667467125e-07 -3.41696457649961e-06 1.58550018273379e-05 -5.13035650688882e-06 -5.08770186424082e-06 -2.68427813443314e-06 1.01062666440643e-06 1.97308062774172e-06 -5.13035650688882e-06 3.48562190881408e-05 8.11555442187547e-06 -1.20926393739429e-05 -7.86524440990042e-07 -1.82231408361968e-06 -5.08770186424082e-06 8.11555442187547e-06 2.67143596864899e-05 -3.82447721529179e-06 -8.08895587829294e-06 4.74481731781104e-06 -2.68427813443314e-06 -1.20926393739429e-05 -3.82447721529179e-06 0.000179595308420514 1263 1304 0 0 2 1263 1319 0 0 25 0 0 0 0 0 0 0 0 1005 0 0 0 0 0 2084 +1260 1291 0.998469117221278 0.0484931915048777 -0.0266051185495108 0.0582235765620031 -0.044504386328278 0.98995691051111 0.134181499950035 0.0309501387485114 0.0328448101365443 -0.132792039328302 0.990599562254156 0.187011435411846 0.000188790173533209 -3.58762566033385e-05 8.93371045912662e-06 1.01826634456812e-05 5.88521931644842e-06 -5.00953982953561e-05 -3.58762566033385e-05 8.95359825540346e-05 -4.94865703197175e-06 4.95398051263578e-06 4.99598362121259e-06 5.91980135063487e-05 8.93371045912662e-06 -4.94865703197175e-06 1.34671110892074e-05 3.2763224002334e-06 -6.98620243819685e-06 -2.92106218421066e-06 1.01826634456812e-05 4.95398051263578e-06 3.2763224002334e-06 2.76044093690576e-05 5.89316080470423e-06 -1.13792313978818e-06 5.88521931644842e-06 4.99598362121259e-06 -6.98620243819685e-06 5.89316080470423e-06 1.98088342267054e-05 4.75069975360491e-06 -5.00953982953561e-05 5.91980135063487e-05 -2.92106218421066e-06 -1.13792313978818e-06 4.75069975360491e-06 0.000111299270596569 1212 1230 0 0 0 1212 1276 0 0 3 0 0 0 0 0 0 0 0 933 0 0 0 0 0 2620 +1260 1290 0.997550581252695 0.0472640990073835 -0.0515649375780721 0.0595035933010481 -0.0411666607338877 0.992684963253579 0.113498324984391 0.0365326114623849 0.056552134234096 -0.111097563768346 0.992199167223147 0.186140011870984 0.000120181980981746 9.46364001617441e-06 7.1746995318482e-06 5.04613793211517e-06 -6.09991456634618e-06 -7.63904708800861e-07 9.46364001617441e-06 9.2073771560606e-05 -2.83990705298152e-06 1.72186777180774e-06 3.08932819251185e-06 4.88368658120821e-05 7.1746995318482e-06 -2.83990705298152e-06 1.34771720526848e-05 9.42148694355114e-07 -8.35602141943997e-06 -9.72146559832024e-07 5.04613793211517e-06 1.72186777180774e-06 9.42148694355114e-07 2.73340095162543e-05 3.22646409832928e-06 -1.05229868818709e-06 -6.09991456634618e-06 3.08932819251185e-06 -8.35602141943997e-06 3.22646409832928e-06 2.17030339406403e-05 6.14505119535819e-06 -7.63904708800861e-07 4.88368658120821e-05 -9.72146559832024e-07 -1.05229868818709e-06 6.14505119535819e-06 7.98306967756313e-05 1380 1413 0 0 0 1380 1456 0 0 8 0 0 0 0 0 0 0 0 930 0 0 0 0 0 2871 +1260 1292 0.998683446946763 0.0506126878544918 -0.00835036661918002 0.0547028995205808 -0.0485150089644121 0.984804279793407 0.166753783782474 0.0246101542762686 0.0166633339915503 -0.166129125467911 0.985963207716978 0.189187028258818 0.000145461192817417 -4.29040127180374e-05 6.13334322830333e-06 1.40979527542756e-06 3.97043552110261e-06 2.35354363809753e-06 -4.29040127180374e-05 0.000114236931508255 2.43477333628353e-06 -3.16221041368001e-06 -7.64432517544922e-06 4.92252829515331e-05 6.13334322830333e-06 2.43477333628353e-06 1.39647652415077e-05 3.60324171043188e-06 -7.79152730132683e-06 1.76399573344997e-06 1.40979527542756e-06 -3.16221041368001e-06 3.60324171043188e-06 2.54926684975122e-05 6.91337044004493e-06 2.46787315858476e-07 3.97043552110261e-06 -7.64432517544922e-06 -7.79152730132683e-06 6.91337044004493e-06 2.3805470549811e-05 -3.2698081656758e-06 2.35354363809753e-06 4.92252829515331e-05 1.76399573344997e-06 2.46787315858476e-07 -3.2698081656758e-06 7.95942799777928e-05 1272 1284 0 0 0 1279 1337 0 0 2 0 0 0 0 0 0 0 0 1042 0 0 3 0 0 2457 +1260 1294 0.998720014123033 0.0502082752602415 0.00612066054279459 0.0521729538158897 -0.050504600518857 0.983299874316374 0.174844623868834 0.0257425319199878 0.00276020226051669 -0.174929946735244 0.984577013249185 0.193753139727209 0.000167122090321265 -7.21919995828284e-05 8.08408216251613e-06 1.1481252206383e-05 1.74371216112246e-05 -3.4068337501556e-05 -7.21919995828284e-05 0.000178664511900654 -5.6558604386328e-06 -2.24959186925178e-06 -1.25689742696022e-05 7.79301669056889e-05 8.08408216251613e-06 -5.6558604386328e-06 1.37825933588975e-05 1.58342188357006e-06 -7.63830800178373e-06 -3.54810186592017e-06 1.1481252206383e-05 -2.24959186925178e-06 1.58342188357006e-06 2.81705592561393e-05 8.8368559958868e-06 -4.80807097004744e-07 1.74371216112246e-05 -1.25689742696022e-05 -7.63830800178373e-06 8.8368559958868e-06 2.48324457383848e-05 -7.40694275954502e-07 -3.4068337501556e-05 7.79301669056889e-05 -3.54810186592017e-06 -4.80807097004744e-07 -7.40694275954502e-07 0.000117840461732019 1313 1324 0 0 0 1324 1379 0 0 2 0 0 0 0 0 0 0 0 1069 0 0 3 0 0 2192 +1260 1288 0.995730106890934 0.0432088999597435 -0.0815753957712624 0.0713909663461179 -0.0384774120624492 0.997533335610948 0.0587088843862014 0.0565851892185875 0.0839109229596822 -0.0553193936080715 0.994936541543675 0.205882404669084 0.000138896943977149 -1.90065168085145e-05 9.94616669180422e-06 6.66464610651388e-06 5.7777963787501e-06 -1.41866793750344e-05 -1.90065168085145e-05 8.38094338001721e-05 9.9767049612111e-07 -1.07069560932225e-06 -1.43171614343231e-06 4.6110606431127e-05 9.94616669180422e-06 9.9767049612111e-07 1.53164520479625e-05 7.66642050673001e-07 -7.53679248100862e-06 1.14955547670661e-07 6.66464610651388e-06 -1.07069560932225e-06 7.66642050673001e-07 3.05035373411959e-05 4.07932620146831e-06 -7.97696085518827e-06 5.7777963787501e-06 -1.43171614343231e-06 -7.53679248100862e-06 4.07932620146831e-06 1.89945357277056e-05 -1.64938301461419e-06 -1.41866793750344e-05 4.6110606431127e-05 1.14955547670661e-07 -7.97696085518827e-06 -1.64938301461419e-06 7.5025758292536e-05 1219 1289 0 0 0 1219 1294 0 0 49 0 0 0 0 0 0 0 0 789 0 0 0 0 0 2935 +1260 1287 0.994798888737539 0.0411592282642096 -0.0931723612196937 0.0718600732900108 -0.0379605938954713 0.998636069082139 0.0358468246749441 0.0489840173683011 0.0945207081948792 -0.0321235031848608 0.995004480525324 0.179084239839592 9.9160030256565e-05 -1.66550052396766e-05 3.42212315878327e-06 1.30224638598649e-07 -9.73732914279889e-07 -6.31612425069241e-06 -1.66550052396766e-05 6.28613366371116e-05 -3.35353389631071e-06 3.40031271697083e-06 -2.80676235646901e-07 4.14201765091209e-05 3.42212315878327e-06 -3.35353389631071e-06 1.33336326919481e-05 5.34478935559655e-06 -4.7497997260718e-06 -1.5162750401486e-06 1.30224638598649e-07 3.40031271697083e-06 5.34478935559655e-06 2.60573349387159e-05 5.44074251569551e-06 2.87576454374971e-06 -9.73732914279889e-07 -2.80676235646901e-07 -4.7497997260718e-06 5.44074251569551e-06 2.24251436607433e-05 5.59869912308095e-06 -6.31612425069241e-06 4.14201765091209e-05 -1.5162750401486e-06 2.87576454374971e-06 5.59869912308095e-06 6.45784425987553e-05 1168 1235 0 0 0 1168 1246 0 0 39 0 0 0 0 0 0 0 0 784 0 0 0 0 0 2972 +1260 1262 0.999367883963874 0.0305945347690871 -0.0181054396199695 0.0319274047642242 -0.0312169655581565 0.998894134567654 -0.0351569194850516 0.0522751153460812 0.0170098078445969 0.0356998931174962 0.999217786104956 0.0954586907400317 9.50427856382526e-05 3.36172177776488e-05 3.54741369696381e-06 1.48883693608448e-06 -6.98660621033987e-06 -1.05045945805744e-07 3.36172177776488e-05 5.86149293006661e-05 -7.98209050046904e-07 -2.62897318898636e-07 -4.4918758224137e-06 1.97349591924415e-05 3.54741369696381e-06 -7.98209050046904e-07 1.44068661146241e-05 -1.93786917054596e-06 -7.52015966626096e-06 6.88446789030142e-07 1.48883693608448e-06 -2.62897318898636e-07 -1.93786917054596e-06 2.79215316873738e-05 4.58529546971059e-06 -5.37997290732731e-06 -6.98660621033987e-06 -4.4918758224137e-06 -7.52015966626096e-06 4.58529546971059e-06 2.54289356457124e-05 1.28373160851685e-05 -1.05045945805744e-07 1.97349591924415e-05 6.88446789030142e-07 -5.37997290732731e-06 1.28373160851685e-05 7.6371589206513e-05 1571 1619 0 0 0 1571 1652 0 0 16 0 0 0 0 0 0 0 0 997 0 0 0 0 0 3439 +1260 1264 0.994387956830255 0.0559922270510019 -0.0897633656945845 0.0524542058243497 -0.0591220977121741 0.997718474282206 -0.0325948406668935 0.0610513877469649 0.0877335105479246 0.0377189154915287 0.995429613052113 0.1604274058606 0.000117144076973264 1.61130473199597e-05 -1.15636381356496e-06 9.72603314632473e-06 -1.07340264680675e-05 -3.81330187362871e-06 1.61130473199597e-05 6.04519943016656e-05 -7.19893372850624e-06 3.23406771339154e-06 -1.57675057459097e-06 2.71230216036302e-05 -1.15636381356496e-06 -7.19893372850624e-06 1.35546238188964e-05 3.60794068859164e-06 -8.18776841741707e-06 -3.65395904164679e-06 9.72603314632473e-06 3.23406771339154e-06 3.60794068859164e-06 2.16744348719753e-05 -4.66166268666033e-06 -8.16125123541152e-06 -1.07340264680675e-05 -1.57675057459097e-06 -8.18776841741707e-06 -4.66166268666033e-06 1.93934645737689e-05 1.09861402212934e-05 -3.81330187362871e-06 2.71230216036302e-05 -3.65395904164679e-06 -8.16125123541152e-06 1.09861402212934e-05 8.77784821260803e-05 1588 1614 0 0 0 1598 1673 0 0 8 0 0 0 0 0 0 0 0 762 0 0 0 0 0 3292 +1260 1296 0.998672363967492 0.0515084776106096 0.00062143528852145 0.053931590356975 -0.0508121826191732 0.983046758389013 0.176173757745949 0.0265517444048857 0.00846354211050463 -0.17597143960055 0.984358888261722 0.196977179098446 0.000263164823155755 -0.000111057572950383 9.75872000592995e-06 1.19660984415207e-05 7.37843045262845e-06 -0.000128325630872599 -0.000111057572950383 0.000144232176926578 -5.51600916636986e-06 -4.35376578153467e-06 -7.48261160487546e-06 8.48958813796977e-05 9.75872000592995e-06 -5.51600916636986e-06 1.25394492592981e-05 4.17306434463199e-06 -8.34833008248999e-06 -3.68773508492228e-06 1.19660984415207e-05 -4.35376578153467e-06 4.17306434463199e-06 2.76762069744919e-05 5.81247882504324e-06 -4.58023895378137e-06 7.37843045262845e-06 -7.48261160487546e-06 -8.34833008248999e-06 5.81247882504324e-06 2.16941224358853e-05 -1.1204430323132e-07 -0.000128325630872599 8.48958813796977e-05 -3.68773508492228e-06 -4.58023895378137e-06 -1.1204430323132e-07 0.00013948908546328 1298 1313 0 0 0 1306 1363 0 0 4 0 0 0 0 0 0 0 0 1052 0 0 1 0 0 2374 +1260 1293 0.998624531462504 0.0513991327677755 -0.0103525026933562 0.0493117450850809 -0.0488047457518891 0.983408721210515 0.174715150571416 0.0247385904761566 0.019160948655764 -0.173969584116936 0.984564595061589 0.203436362492059 0.00017271742595089 -3.43628839054629e-05 4.69298516198014e-06 2.44051318705734e-06 -3.15715023196388e-06 -4.73981660130616e-05 -3.43628839054629e-05 8.96205386095992e-05 -3.96173771120669e-06 2.04089855199719e-06 1.27917678275243e-06 7.15467922593526e-05 4.69298516198014e-06 -3.96173771120669e-06 1.34499856884254e-05 1.09217735305819e-06 -8.34552356593552e-06 -2.49174365111373e-06 2.44051318705734e-06 2.04089855199719e-06 1.09217735305819e-06 2.83230009625647e-05 4.59357437110915e-06 -6.59848943513687e-06 -3.15715023196388e-06 1.27917678275243e-06 -8.34552356593552e-06 4.59357437110915e-06 2.49930082257651e-05 6.74937478458047e-06 -4.73981660130616e-05 7.15467922593526e-05 -2.49174365111373e-06 -6.59848943513687e-06 6.74937478458047e-06 0.000124373879659566 1284 1293 0 0 0 1294 1349 0 0 1 0 0 0 0 0 0 0 0 1086 0 0 2 0 0 2305 +1260 1289 0.996681895737209 0.0437217424014277 -0.0686557204540598 0.0641820728384759 -0.039008201371636 0.996884371915087 0.0685558841910195 0.0358460050101649 0.0714391974719251 -0.0656502724506592 0.99528211216304 0.180961736683057 9.8525429804049e-05 -1.2109071169989e-05 6.24967659515498e-06 -5.43352525820759e-06 -1.66974445121491e-06 -4.7132935285899e-06 -1.2109071169989e-05 8.47295021764417e-05 -8.98238185667006e-06 6.99195679697204e-06 4.81302766086415e-06 4.35162374493183e-05 6.24967659515498e-06 -8.98238185667006e-06 1.35283036874751e-05 -1.42696535124048e-06 -8.91698157338419e-06 -5.4157593089229e-06 -5.43352525820759e-06 6.99195679697204e-06 -1.42696535124048e-06 2.73664026786802e-05 8.021497457361e-06 2.19851914086471e-06 -1.66974445121491e-06 4.81302766086415e-06 -8.91698157338419e-06 8.021497457361e-06 2.01888347857967e-05 7.049504150598e-06 -4.7132935285899e-06 4.35162374493183e-05 -5.4157593089229e-06 2.19851914086471e-06 7.049504150598e-06 7.7576694834263e-05 1345 1384 0 0 0 1345 1419 0 0 11 0 0 0 0 0 0 0 0 821 0 0 0 0 0 3144 +1260 1298 0.998648378834621 0.0511630308315599 0.00915203404230643 0.0540405110493687 -0.0519745046170006 0.982159955860901 0.180722084906995 0.0288298887159674 0.000257528251011229 -0.18095348954757 0.983491620858946 0.199772952251225 0.00032145043159591 -9.55940012163332e-05 7.90111598726108e-06 2.39582389574917e-05 9.84005321060317e-06 -0.000145989831976981 -9.55940012163332e-05 0.000217678933898556 -1.17232776110424e-05 8.64924562976963e-06 -1.30876013651793e-05 5.40411391684348e-05 7.90111598726108e-06 -1.17232776110424e-05 1.63947185400903e-05 -3.99572501330824e-07 -6.6836337990574e-06 -5.29273951362424e-06 2.39582389574917e-05 8.64924562976963e-06 -3.99572501330824e-07 3.19319580824163e-05 2.84834720847188e-06 -1.40716154440687e-05 9.84005321060317e-06 -1.30876013651793e-05 -6.6836337990574e-06 2.84834720847188e-06 2.41874620508007e-05 -1.38916224659785e-06 -0.000145989831976981 5.40411391684348e-05 -5.29273951362424e-06 -1.40716154440687e-05 -1.38916224659785e-06 0.000209246615043833 1206 1226 0 0 0 1210 1270 0 0 7 0 0 0 0 0 0 0 0 981 0 0 1 0 0 2164 +1260 1286 0.993501462264147 0.0385342566230729 -0.107097878342708 0.0717341515392018 -0.0361740084070196 0.999059794734517 0.0238949296042631 0.0502500754380238 0.107917957702929 -0.0198654879509912 0.993961305481103 0.197963172964644 0.00014490461723941 -6.94684500073711e-05 1.64012061922277e-05 -1.0302185170069e-05 -8.5137396115322e-07 -1.42939998050693e-05 -6.94684500073711e-05 0.000110355960540239 -1.24071949724909e-05 -8.430693587047e-07 3.57432550867182e-06 5.61445987226018e-05 1.64012061922277e-05 -1.24071949724909e-05 1.39604618665419e-05 -4.38979586756213e-07 -8.50941074030445e-06 -2.49973750341389e-06 -1.0302185170069e-05 -8.430693587047e-07 -4.38979586756213e-07 2.89431793308644e-05 9.84320330140275e-06 -3.80186438202202e-06 -8.5137396115322e-07 3.57432550867182e-06 -8.50941074030445e-06 9.84320330140275e-06 2.42902846310025e-05 2.12103560896488e-06 -1.42939998050693e-05 5.61445987226018e-05 -2.49973750341389e-06 -3.80186438202202e-06 2.12103560896488e-06 6.30866365178862e-05 1203 1263 0 0 0 1203 1278 0 0 41 0 0 0 0 0 0 0 0 827 0 0 0 0 0 3071 +1260 1316 0.998552246819759 0.0535665737520745 -0.00490230024325751 0.0527217117125313 -0.0517454476895023 0.981482634409675 0.184429517690787 0.0355872433862487 0.0146907799188626 -0.183908837549224 0.982833516144351 0.212214996680682 0.000185632341893135 4.35036683080387e-05 3.30780726295968e-06 2.28986159318788e-05 -7.34244322476672e-06 -0.000117959400791048 4.35036683080387e-05 0.000149386898589883 -5.63590146224563e-07 5.75337779481138e-06 -1.74471394216492e-05 -5.47409040583447e-05 3.30780726295968e-06 -5.63590146224563e-07 1.67069115390442e-05 4.00848722245109e-06 -9.72943904490968e-06 -8.91840521869607e-06 2.28986159318788e-05 5.75337779481138e-06 4.00848722245109e-06 2.9283533624694e-05 -4.92367662386915e-06 -1.3137253197003e-05 -7.34244322476672e-06 -1.74471394216492e-05 -9.72943904490968e-06 -4.92367662386915e-06 2.42046352475388e-05 2.075553598574e-05 -0.000117959400791048 -5.47409040583447e-05 -8.91840521869607e-06 -1.3137253197003e-05 2.075553598574e-05 0.000310036943004945 1209 1230 0 0 0 1213 1274 0 0 7 0 0 0 0 0 0 0 0 1065 0 0 0 0 0 2353 +1260 1314 0.998651663333498 0.0510999379084223 -0.00914612852482821 0.0498205002848548 -0.0488026763253212 0.984209641632456 0.170146055203168 0.0314720818634805 0.0176961607339904 -0.16947028548825 0.985376409415107 0.204171323560123 0.000358740450423929 -0.0001812789545172 -2.81779155574514e-06 3.73144250468055e-05 7.81050327282098e-06 -0.000121068621984638 -0.0001812789545172 0.000252120883995768 -8.82262684471792e-07 -2.02229734476982e-05 -8.60747303731904e-06 0.000149833312577263 -2.81779155574514e-06 -8.82262684471792e-07 1.69484079989866e-05 4.02829656113718e-06 -1.04428963683149e-05 2.55800880869616e-07 3.73144250468055e-05 -2.02229734476982e-05 4.02829656113718e-06 3.37636337150938e-05 3.38035998033878e-07 -1.00846113150812e-05 7.81050327282098e-06 -8.60747303731904e-06 -1.04428963683149e-05 3.38035998033878e-07 2.31350923805182e-05 1.9553031770512e-06 -0.000121068621984638 0.000149833312577263 2.55800880869616e-07 -1.00846113150812e-05 1.9553031770512e-06 0.000163310401505569 1289 1304 0 0 0 1294 1354 0 0 3 0 0 0 0 0 0 0 0 1082 0 0 1 0 0 2168 +1260 1317 0.998606885384131 0.0523534890559455 -0.00658791674764437 0.0525879951121853 -0.0505354506729664 0.98482297112437 0.166041813321367 0.0264023364628482 0.0151808000014847 -0.165477574702546 0.986096707012998 0.197289866017879 0.000235787578200587 -0.00011249325717765 4.96634105369114e-06 2.23834912011397e-05 8.34202361491021e-06 -5.884759683724e-05 -0.00011249325717765 0.000149862850086226 -7.33195693076447e-06 -7.70699415319504e-06 7.98562495477571e-07 7.58742773810955e-05 4.96634105369114e-06 -7.33195693076447e-06 1.79375130842934e-05 3.38867229438868e-06 -9.09567412617089e-06 -2.93348976583231e-06 2.23834912011397e-05 -7.70699415319504e-06 3.38867229438868e-06 3.52807088199378e-05 1.43959480502323e-06 -6.62368468071681e-06 8.34202361491021e-06 7.98562495477571e-07 -9.09567412617089e-06 1.43959480502323e-06 2.1921060469101e-05 2.9313522666371e-06 -5.884759683724e-05 7.58742773810955e-05 -2.93348976583231e-06 -6.62368468071681e-06 2.9313522666371e-06 0.000111674602590874 1289 1300 0 0 0 1296 1350 0 0 1 0 0 0 0 0 0 0 0 977 0 0 3 0 0 2461 +1260 1295 0.998467818760137 0.0516746973699233 0.0197924367398318 0.0560734655994937 -0.0545039985632893 0.980175220758217 0.190488453067881 0.0268677745666836 -0.00955662288606009 -0.191275357177312 0.981489892304401 0.184840363993987 0.000242447148154929 -5.93015125677123e-05 7.89026938834479e-06 -3.20891790254831e-06 -4.87344825874234e-06 -3.59104673202729e-05 -5.93015125677123e-05 0.000115061032976713 -8.21460036760227e-07 8.01940069615205e-06 2.66892877742009e-06 7.93181349731361e-05 7.89026938834479e-06 -8.21460036760227e-07 1.39197529069928e-05 2.89986033175323e-06 -8.91673883324455e-06 -1.38127029510053e-06 -3.20891790254831e-06 8.01940069615205e-06 2.89986033175323e-06 2.98206027410286e-05 1.01701052350887e-05 8.85045770503681e-06 -4.87344825874234e-06 2.66892877742009e-06 -8.91673883324455e-06 1.01701052350887e-05 2.47997106143311e-05 8.01787758849385e-06 -3.59104673202729e-05 7.93181349731361e-05 -1.38127029510053e-06 8.85045770503681e-06 8.01787758849385e-06 0.000163054111738175 1303 1318 0 0 0 1312 1368 0 0 6 0 0 0 0 0 0 0 0 940 0 0 4 0 0 2174 +1260 1297 0.998627428812673 0.0513849120572127 0.0101414612291963 0.0548749154284617 -0.0523741544603162 0.981371062364491 0.184845302613175 0.028925014252299 -0.000454276961457827 -0.185122739733567 0.982715302041227 0.203016904506318 0.000184357954394959 -6.84489509460926e-05 3.72038636906952e-06 1.04316795406234e-05 9.012356255466e-07 -4.41359556168638e-05 -6.84489509460926e-05 0.000177804031485896 -1.22375543002684e-06 4.68209382911373e-07 -1.46411176225691e-05 4.02001482962082e-05 3.72038636906952e-06 -1.22375543002684e-06 1.27917307377709e-05 2.87782267263236e-06 -7.32396458761359e-06 -3.91333087489826e-07 1.04316795406234e-05 4.68209382911373e-07 2.87782267263236e-06 2.60793206590964e-05 3.71885563795828e-06 -1.88228883571017e-06 9.012356255466e-07 -1.46411176225691e-05 -7.32396458761359e-06 3.71885563795828e-06 2.02798752538449e-05 1.74862977213261e-06 -4.41359556168638e-05 4.02001482962082e-05 -3.91333087489826e-07 -1.88228883571017e-06 1.74862977213261e-06 0.000106051640533012 1405 1430 0 0 0 1418 1485 0 0 8 0 0 0 0 0 0 0 0 1087 0 0 3 0 0 2198 +1260 1312 0.998658188511381 0.0517264857162902 -0.00248861298894923 0.0524712280869735 -0.0504170302887586 0.982106912653046 0.181450090041211 0.0321565026587705 0.0118298595101015 -0.181081149749342 0.983397006111686 0.211143062137122 0.000182821257813059 -4.64995459153596e-05 3.84925950537683e-06 2.96387620328807e-06 3.80225397398828e-07 -1.66653630574209e-05 -4.64995459153596e-05 0.00013227156104365 -8.58609930302184e-06 4.40448103676167e-06 3.00189497259855e-06 2.27665854624203e-05 3.84925950537683e-06 -8.58609930302184e-06 1.54045347565863e-05 -1.34676349052927e-06 -8.30796127581759e-06 -3.63039187516648e-06 2.96387620328807e-06 4.40448103676167e-06 -1.34676349052927e-06 3.16991578758612e-05 1.05676859385518e-06 1.5523048389404e-06 3.80225397398828e-07 3.00189497259855e-06 -8.30796127581759e-06 1.05676859385518e-06 2.12670953214418e-05 8.03672222942055e-06 -1.66653630574209e-05 2.27665854624203e-05 -3.63039187516648e-06 1.5523048389404e-06 8.03672222942055e-06 7.68819538492997e-05 1301 1315 0 0 0 1308 1364 0 0 4 0 0 0 0 0 0 0 0 1079 0 0 1 0 0 2177 +1260 1315 0.998619448068066 0.0518327130376666 -0.00851867356960253 0.0499235411171039 -0.0496827348425555 0.984673624526239 0.167180976851209 0.0272663183556249 0.0170535567784219 -0.166526943830465 0.985889422389596 0.195113753150499 0.000237778385463175 -5.30784344491845e-05 9.30268685167423e-07 3.09430478011423e-05 2.7118377346259e-06 -0.000107660320453582 -5.30784344491845e-05 0.000129836940848109 -7.46075846766116e-07 -2.1893557759829e-06 -4.55606184219461e-06 4.26782918846176e-05 9.30268685167423e-07 -7.46075846766116e-07 1.84132705584113e-05 3.4643978024676e-06 -1.07382867248406e-05 -8.79043847318143e-06 3.09430478011423e-05 -2.1893557759829e-06 3.4643978024676e-06 3.39229108143801e-05 -5.15539132813807e-07 -1.77363946761894e-05 2.7118377346259e-06 -4.55606184219461e-06 -1.07382867248406e-05 -5.15539132813807e-07 2.40870148380531e-05 4.09198642655577e-06 -0.000107660320453582 4.26782918846176e-05 -8.79043847318143e-06 -1.77363946761894e-05 4.09198642655577e-06 0.000151084176975228 1202 1215 0 0 0 1209 1267 0 0 2 0 0 0 0 0 0 0 0 1082 0 0 1 0 0 2408 +1260 1318 0.998669531396486 0.0515284557684223 0.00199632323146945 0.0503541543410091 -0.0510867827642523 0.983354013514958 0.17437036655012 0.027452726083401 0.0070219432581628 -0.174240357983295 0.984678114899855 0.198135824315786 0.000125899504265044 -6.36347469715747e-05 -7.25592790939498e-06 1.37359576871762e-05 4.75608330107731e-07 2.18418990465017e-06 -6.36347469715747e-05 0.000131017069709726 8.3621263578527e-06 -1.04483763948506e-05 1.28411716046868e-06 4.24861284608817e-05 -7.25592790939498e-06 8.3621263578527e-06 1.84269971113649e-05 1.09343217193393e-07 -8.55843714019839e-06 -1.32074914527726e-06 1.37359576871762e-05 -1.04483763948506e-05 1.09343217193393e-07 3.44558377361106e-05 -2.63637930623109e-06 5.23494458558612e-08 4.75608330107731e-07 1.28411716046868e-06 -8.55843714019839e-06 -2.63637930623109e-06 2.071374783634e-05 4.8970681263757e-07 2.18418990465017e-06 4.24861284608817e-05 -1.32074914527726e-06 5.23494458558612e-08 4.8970681263757e-07 9.24850726798694e-05 1405 1426 0 0 0 1419 1484 0 0 7 0 0 0 0 0 0 0 0 1085 0 0 4 0 0 2401 +1260 1309 0.998681974736905 0.0505161697919833 0.00907909274896344 0.0567988180591319 -0.0513255269804915 0.983139554072336 0.175505861721551 0.0270746212323103 -6.01312863831062e-05 -0.175740529781826 0.984436520338529 0.200246877363508 0.000213465110454135 -7.53307045833211e-05 7.56011136553995e-06 1.80531847486461e-06 -8.59352737108119e-06 -4.30889204355999e-05 -7.53307045833211e-05 0.000135944922720212 -7.30067870342707e-06 1.27248831535457e-05 2.33839757034299e-06 6.04034921677246e-05 7.56011136553995e-06 -7.30067870342707e-06 1.56575658355825e-05 8.59914040768692e-07 -9.11473651478803e-06 -1.9783112150877e-06 1.80531847486461e-06 1.27248831535457e-05 8.59914040768692e-07 2.98146334152518e-05 4.42031973027469e-06 4.02863898311934e-06 -8.59352737108119e-06 2.33839757034299e-06 -9.11473651478803e-06 4.42031973027469e-06 2.4536615958666e-05 5.51992882256764e-06 -4.30889204355999e-05 6.04034921677246e-05 -1.9783112150877e-06 4.02863898311934e-06 5.51992882256764e-06 0.000123544013566168 1311 1325 0 0 0 1320 1375 0 0 3 0 0 0 0 0 0 0 0 984 0 0 2 0 0 2175 +1260 1313 0.998656976905894 0.0505520657566998 -0.0113459739516482 0.0511686151105475 -0.0480883702727702 0.985924945395634 0.160123423305664 0.0242782564323282 0.0192808485728748 -0.159362764453765 0.987031791881074 0.197016353354165 0.000223088510721961 -0.000109302202925207 7.94426297172245e-06 -2.98326896805165e-06 -6.69620567043472e-06 -4.89475991751338e-05 -0.000109302202925207 0.000125122279303251 -6.88731991262131e-06 3.19537977988749e-06 8.33644467032932e-06 7.68933914368435e-05 7.94426297172245e-06 -6.88731991262131e-06 1.36357790400758e-05 -7.31825537189715e-07 -8.59034312818713e-06 -7.77339187674708e-06 -2.98326896805165e-06 3.19537977988749e-06 -7.31825537189715e-07 2.94894952923642e-05 6.50272444836722e-06 1.29358958042478e-05 -6.69620567043472e-06 8.33644467032932e-06 -8.59034312818713e-06 6.50272444836722e-06 2.15485164021516e-05 8.89548276865604e-06 -4.89475991751338e-05 7.68933914368435e-05 -7.77339187674708e-06 1.29358958042478e-05 8.89548276865604e-06 9.86320635020953e-05 1302 1310 0 0 0 1312 1368 0 0 0 0 0 0 0 0 0 0 0 1089 0 0 2 0 0 2419 +1261 1263 0.9977004728319 0.0267746584226067 -0.0622646302274107 0.0247191722057568 -0.0277962851392223 0.999491877938645 -0.0155997585603241 0.0245705794501023 0.0618153139882222 0.0172946119075882 0.997937755251049 0.0687300580064159 6.70419554758913e-05 2.07466596533008e-05 -6.56565574567852e-06 6.92878632463973e-06 -8.40910516363523e-06 -3.05896085152314e-05 2.07466596533008e-05 5.60732540909885e-05 -5.90095484737625e-06 1.10190637850958e-05 -7.06253393265116e-06 -2.08813515676922e-06 -6.56565574567852e-06 -5.90095484737625e-06 1.29126091346806e-05 2.77393924025113e-06 -6.43407527129646e-06 -3.29638594978869e-07 6.92878632463973e-06 1.10190637850958e-05 2.77393924025113e-06 2.22981403146177e-05 -2.81122799434444e-06 -5.94713523386628e-06 -8.40910516363523e-06 -7.06253393265116e-06 -6.43407527129646e-06 -2.81122799434444e-06 2.2587339007807e-05 2.08783902435522e-05 -3.05896085152314e-05 -2.08813515676922e-06 -3.29638594978869e-07 -5.94713523386628e-06 2.08783902435522e-05 0.000100530974955003 1591 1600 0 0 0 1603 1674 0 0 1 0 0 0 0 0 0 0 0 843 0 0 0 0 0 3409 +1261 1264 0.997172724223 0.0318862134879427 -0.0680428354427042 0.0371011683824634 -0.0328006127515247 0.999385440949728 -0.0123636653482067 0.0267986541326664 0.0676067886295903 0.0145605565525246 0.997605790041374 0.0864782301501836 9.15789679497281e-05 2.93735350959862e-06 3.19579338565922e-06 5.2641781580264e-06 -9.74891878464507e-06 -2.50140920828881e-05 2.93735350959862e-06 8.98831214577044e-05 -1.10173593997551e-05 1.33350646622139e-05 -1.02562513198175e-06 1.17010831191822e-05 3.19579338565922e-06 -1.10173593997551e-05 1.35574462894109e-05 3.61174666264047e-06 -7.57893924189262e-06 -1.38106582391361e-06 5.2641781580264e-06 1.33350646622139e-05 3.61174666264047e-06 2.17723801570643e-05 -3.93465863392383e-06 -4.95857331932852e-06 -9.74891878464507e-06 -1.02562513198175e-06 -7.57893924189262e-06 -3.93465863392383e-06 1.99210217327586e-05 1.54420081168178e-05 -2.50140920828881e-05 1.17010831191822e-05 -1.38106582391361e-06 -4.95857331932852e-06 1.54420081168178e-05 8.36356260010907e-05 1587 1604 0 0 0 1598 1676 0 0 2 0 0 0 0 0 0 0 0 764 0 0 0 0 0 3325 +1261 1289 0.997695328788729 0.0175536065259564 -0.0655431293964645 0.0387205331884754 -0.00963181919265077 0.992814184258965 0.119277925842318 0.0127821808590252 0.067165906322999 -0.118371729868822 0.990695147154599 0.134690611752802 0.000101735318544626 -3.15076003949401e-07 4.00243738524358e-06 3.34077439145109e-06 1.70411328086337e-06 -1.72195711190514e-05 -3.15076003949401e-07 6.07437615951674e-05 -1.73044492968877e-06 3.23598850056792e-06 -1.46298481057187e-06 2.46837689153407e-05 4.00243738524358e-06 -1.73044492968877e-06 1.27963502367699e-05 -4.73867880705278e-08 -6.82547127881689e-06 -2.35269769375639e-07 3.34077439145109e-06 3.23598850056792e-06 -4.73867880705278e-08 2.77273649196061e-05 5.00890655785714e-06 8.41034623304827e-07 1.70411328086337e-06 -1.46298481057187e-06 -6.82547127881689e-06 5.00890655785714e-06 2.17664246101913e-05 3.56722028773812e-06 -1.72195711190514e-05 2.46837689153407e-05 -2.35269769375639e-07 8.41034623304827e-07 3.56722028773812e-06 8.46320425743476e-05 1345 1382 0 0 0 1345 1419 0 0 15 0 0 0 0 0 0 0 0 801 0 0 0 0 0 2967 +1261 1288 0.995659180476122 0.0141622542988322 -0.0919903630104423 0.0466660857575545 -0.00751837608562469 0.997363823145794 0.07217255919697 0.0262859046526196 0.0927699862814092 -0.0711676529975538 0.993140923943912 0.146064363029676 0.000145602967534221 -8.89352593416206e-06 1.41172843168947e-05 -9.26480718560802e-07 2.01664424018883e-06 -3.12113532550547e-06 -8.89352593416206e-06 4.50348384919722e-05 5.99632425488121e-07 -4.91284180068534e-06 -3.68448481220427e-06 2.83870622728145e-05 1.41172843168947e-05 5.99632425488121e-07 1.42616565698891e-05 9.0492504391093e-07 -7.94428039914699e-06 9.73060294284141e-07 -9.26480718560802e-07 -4.91284180068534e-06 9.0492504391093e-07 2.3265356716576e-05 1.22074342790281e-06 -6.70425368841576e-06 2.01664424018883e-06 -3.68448481220427e-06 -7.94428039914699e-06 1.22074342790281e-06 1.81080288261967e-05 2.69510152600339e-07 -3.12113532550547e-06 2.83870622728145e-05 9.73060294284141e-07 -6.70425368841576e-06 2.69510152600339e-07 6.83477130622801e-05 1235 1295 0 0 0 1235 1310 0 0 45 0 0 0 0 0 0 0 0 784 0 0 0 0 0 3029 +1261 1287 0.996348211322077 0.0143714152432222 -0.0841647445145802 0.048849727997105 -0.00831859725449978 0.99738218212282 0.0718302424027582 0.0212891801081759 0.084976718782353 -0.0708678009241746 0.993859503177968 0.117891814332967 8.62639915028504e-05 -1.15625082845499e-05 5.79601417521115e-07 4.91434815822317e-06 7.17165765731401e-07 -3.19836837629049e-06 -1.15625082845499e-05 4.81644799471012e-05 -1.99923222419052e-06 -2.63675022467981e-08 -2.67277571106409e-06 1.64599451603001e-05 5.79601417521115e-07 -1.99923222419052e-06 1.24501811987323e-05 2.28871355922581e-06 -7.11257192699303e-06 5.5000654615724e-07 4.91434815822317e-06 -2.63675022467981e-08 2.28871355922581e-06 2.43646470505595e-05 2.38770010149742e-06 1.64599021481504e-06 7.17165765731401e-07 -2.67277571106409e-06 -7.11257192699303e-06 2.38770010149742e-06 1.92998564995044e-05 5.06945122251103e-06 -3.19836837629049e-06 1.64599451603001e-05 5.5000654615724e-07 1.64599021481504e-06 5.06945122251103e-06 9.11845368023662e-05 1182 1248 0 0 0 1182 1260 0 0 38 0 0 0 0 0 0 0 0 777 0 0 0 0 0 2993 +1261 1293 0.999634899368632 0.0239040105697117 -0.0125962789325796 0.0278386783411446 -0.0209595354050922 0.980215570425587 0.196820053274163 -0.00833211332523626 0.0170518573729351 -0.196484181994187 0.980358710057807 0.134813288942313 0.000105762729494598 -1.78723522218847e-05 1.2445497193075e-06 -2.05100500363087e-06 -6.30972734050806e-07 -4.41340439106013e-07 -1.78723522218847e-05 9.74629555546348e-05 6.91359147540405e-07 -2.63614285593945e-06 3.61855272959497e-07 6.26191543906216e-05 1.2445497193075e-06 6.91359147540405e-07 1.21128843842801e-05 8.28523453344058e-07 -6.76703617470518e-06 -7.41759803949056e-07 -2.05100500363087e-06 -2.63614285593945e-06 8.28523453344058e-07 2.428838582398e-05 6.37551500135939e-06 -4.95824415274598e-06 -6.30972734050806e-07 3.61855272959497e-07 -6.76703617470518e-06 6.37551500135939e-06 2.11577460281215e-05 1.94117633809547e-06 -4.41340439106013e-07 6.26191543906216e-05 -7.41759803949056e-07 -4.95824415274598e-06 1.94117633809547e-06 9.8684802350891e-05 1289 1293 0 0 0 1304 1353 0 0 2 0 0 0 0 0 0 0 0 1062 0 0 5 0 0 2444 +1261 1297 0.99970283801393 0.0241596760820099 -0.0032474172055816 0.0297827430418275 -0.0229349259358984 0.977320749613851 0.210518743931593 -0.000929769642133229 0.0082598328802468 -0.210381706490448 0.977584427420444 0.13959025082482 0.000120503216963372 1.23559930185088e-06 4.19909713729048e-06 9.24414241201038e-06 -6.5328811334751e-07 2.59569328406775e-06 1.23559930185088e-06 6.16535145780047e-05 -7.9038012451569e-07 -2.37161910111729e-06 -6.87339755792779e-06 1.21711219759556e-05 4.19909713729048e-06 -7.9038012451569e-07 1.18234160872398e-05 1.46022886560971e-06 -8.70771621996344e-06 4.86503962860296e-07 9.24414241201038e-06 -2.37161910111729e-06 1.46022886560971e-06 2.72670695795406e-05 9.2042597842311e-06 -5.40931667034516e-06 -6.5328811334751e-07 -6.87339755792779e-06 -8.70771621996344e-06 9.2042597842311e-06 2.31647107859241e-05 -5.41720891440414e-06 2.59569328406775e-06 1.21711219759556e-05 4.86503962860296e-07 -5.40931667034516e-06 -5.41720891440414e-06 8.74105048416464e-05 1401 1420 0 0 0 1418 1479 0 0 13 0 0 0 0 0 0 0 0 1063 0 0 5 0 0 2247 +1261 1265 0.997741949305512 0.0201163628306863 -0.0640806877499043 0.0368435138249941 -0.0216915415038932 0.999477058051813 -0.0239809811158113 0.0282222281429497 0.0635647671530497 0.0253168397426734 0.997656543106004 0.100506438701489 0.000109216857047306 -4.78085743301958e-05 1.3049162207264e-05 1.28727210013795e-06 -3.61752356237788e-06 -9.24992303069659e-06 -4.78085743301958e-05 0.000112841730799373 -2.22752312443685e-05 1.34318085305802e-06 -1.04332903807459e-05 -5.68982868404466e-08 1.3049162207264e-05 -2.22752312443685e-05 1.95881993537939e-05 1.17077275931166e-06 -6.0540908838042e-06 3.5315173069838e-06 1.28727210013795e-06 1.34318085305802e-06 1.17077275931166e-06 2.70956797594802e-05 -8.91578531380347e-07 -1.42049361225806e-05 -3.61752356237788e-06 -1.04332903807459e-05 -6.0540908838042e-06 -8.91578531380347e-07 2.31139078599643e-05 1.25408256808065e-05 -9.24992303069659e-06 -5.68982868404466e-08 3.5315173069838e-06 -1.42049361225806e-05 1.25408256808065e-05 7.53934506054986e-05 1557 1591 0 0 0 1562 1646 0 0 12 0 0 0 0 0 0 0 0 749 0 0 0 0 0 3317 +1261 1291 0.999201513726119 0.0209005229864695 -0.0340514773001802 0.0323093886580134 -0.015148741343424 0.986809817764932 0.161173506502932 0.00249686968503977 0.036970942686692 -0.160528974648294 0.98633848028718 0.133722372025953 0.000134538644663243 -1.71813359844086e-05 9.06640272812227e-06 7.69891907658054e-06 1.1318872242679e-05 -3.91019050993885e-05 -1.71813359844086e-05 6.1905883155835e-05 -3.61663812076568e-06 -1.77474708943699e-06 -3.36653925290215e-06 3.57365190780551e-05 9.06640272812227e-06 -3.61663812076568e-06 1.22941923040629e-05 3.52565433776778e-06 -6.24822971214229e-06 -4.5911982634469e-06 7.69891907658054e-06 -1.77474708943699e-06 3.52565433776778e-06 2.59940770057459e-05 7.82975897276887e-06 -4.60648662733929e-06 1.1318872242679e-05 -3.36653925290215e-06 -6.24822971214229e-06 7.82975897276887e-06 2.07868753745811e-05 -1.80238261320725e-06 -3.91019050993885e-05 3.57365190780551e-05 -4.5911982634469e-06 -4.60648662733929e-06 -1.80238261320725e-06 9.96405246610066e-05 1212 1225 0 0 0 1215 1277 0 0 4 0 0 0 0 0 0 0 0 915 0 0 0 0 0 2639 +1261 1316 0.999657351593036 0.0261696020552542 -0.000575616422813949 0.0328640009156479 -0.0254613779243782 0.977236475857016 0.210619534917235 0.00282722203938079 0.00607434277832287 -0.210532710481839 0.977567941463396 0.139037468056334 0.000153832351913547 -2.86601683623454e-05 -1.70666723404732e-07 1.31413833204619e-05 -6.58514729671518e-06 -3.37782799823747e-05 -2.86601683623454e-05 0.000156304456618951 -1.78206616685814e-06 4.16212325004254e-06 -7.89454983616485e-06 -3.03206644295451e-05 -1.70666723404732e-07 -1.78206616685814e-06 1.52787851846568e-05 5.47158644177101e-06 -9.62402038317018e-06 -1.06848196920531e-06 1.31413833204619e-05 4.16212325004254e-06 5.47158644177101e-06 2.88261446925864e-05 -2.71476314946282e-06 -1.52566047937527e-05 -6.58514729671518e-06 -7.89454983616485e-06 -9.62402038317018e-06 -2.71476314946282e-06 2.29335374755169e-05 2.97108408440262e-06 -3.37782799823747e-05 -3.03206644295451e-05 -1.06848196920531e-06 -1.52566047937527e-05 2.97108408440262e-06 0.000169385478407316 1214 1231 0 0 0 1221 1276 0 0 10 0 0 0 0 0 0 0 0 1042 0 0 1 0 0 2455 +1261 1314 0.999551904555498 0.0253031978295725 -0.0159918191296055 0.025238179929677 -0.0213796665638094 0.977420582408858 0.21021873118528 0.00673791973062835 0.020949939310099 -0.209782633368747 0.977523578631112 0.15431669047952 0.000250949740110259 -5.53118214113702e-05 9.66211860854108e-06 1.65130877258099e-05 -1.31556395107278e-05 -8.91437378744363e-05 -5.53118214113702e-05 0.000124378795971065 -3.98227875985303e-06 -3.44340290656439e-06 -3.28111299122957e-07 1.30520357129108e-05 9.66211860854108e-06 -3.98227875985303e-06 1.65366308247741e-05 4.04422274967051e-06 -1.00896018780013e-05 -7.83558186404066e-06 1.65130877258099e-05 -3.44340290656439e-06 4.04422274967051e-06 3.37832917506644e-05 -2.25547899300083e-07 -7.06586288684042e-06 -1.31556395107278e-05 -3.28111299122957e-07 -1.00896018780013e-05 -2.25547899300083e-07 2.52332021746805e-05 6.17236120516294e-06 -8.91437378744363e-05 1.30520357129108e-05 -7.83558186404066e-06 -7.06586288684042e-06 6.17236120516294e-06 0.000143809879709341 1286 1301 0 0 0 1295 1352 0 0 8 0 0 0 0 0 0 0 0 1053 0 0 2 0 0 2160 +1261 1292 0.999652472429934 0.0231229648590781 -0.0126594968638724 0.0302552291637146 -0.0202281429533105 0.980772457552538 0.194103603106732 -0.00317082462375206 0.0169043366442162 -0.193780068640924 0.98089934672225 0.133929448423983 0.000152965610306437 -2.41474281710839e-05 1.18658036153784e-05 3.54910995732164e-06 -8.3600284152114e-06 -3.26355943664441e-05 -2.41474281710839e-05 5.9425351076458e-05 4.97608260403554e-07 1.91387326878822e-08 2.00097830411709e-06 4.48847586745661e-05 1.18658036153784e-05 4.97608260403554e-07 1.26352161830062e-05 7.29106125846365e-07 -8.84542575360409e-06 -2.05162529382699e-06 3.54910995732164e-06 1.91387326878822e-08 7.29106125846365e-07 2.76764776402717e-05 1.0029007139884e-05 -1.81629459022853e-06 -8.3600284152114e-06 2.00097830411709e-06 -8.84542575360409e-06 1.0029007139884e-05 2.28963503490555e-05 2.61036589244075e-06 -3.26355943664441e-05 4.48847586745661e-05 -2.05162529382699e-06 -1.81629459022853e-06 2.61036589244075e-06 8.31622290002441e-05 1271 1281 0 0 0 1282 1336 0 0 5 0 0 0 0 0 0 0 0 1013 0 0 4 0 0 2501 +1261 1313 0.999666478213236 0.0242033281576826 -0.00900728831766275 0.0288465127903799 -0.02192932284325 0.979770866571388 0.198917454783607 -0.00178419052398298 0.0136395431148734 -0.198653587745209 0.9799748542384 0.143847017020762 0.000262266655985927 -0.000122270715309561 8.88890116006104e-06 4.31679018645812e-06 -7.57396085928573e-06 -3.25335785794747e-05 -0.000122270715309561 0.000129362953433434 -1.55389972252277e-06 -5.23187208246149e-06 2.89386433649063e-06 4.01714246717187e-05 8.88890116006104e-06 -1.55389972252277e-06 1.56009801449133e-05 -2.15820451029408e-08 -9.07954349817706e-06 1.25765105590412e-06 4.31679018645812e-06 -5.23187208246149e-06 -2.15820451029408e-08 2.93094990287522e-05 5.73959356942652e-06 -8.40954344661553e-06 -7.57396085928573e-06 2.89386433649063e-06 -9.07954349817706e-06 5.73959356942652e-06 2.297730380229e-05 1.10582795715144e-07 -3.25335785794747e-05 4.01714246717187e-05 1.25765105590412e-06 -8.40954344661553e-06 1.10582795715144e-07 7.37590484467848e-05 1300 1305 0 0 0 1315 1366 0 0 3 0 0 0 0 0 0 0 0 1060 0 0 4 0 0 2417 +1261 1317 0.999595746980876 0.0260881368004777 -0.0113027313523737 0.0313293658137577 -0.0232515213353736 0.978888120480495 0.203069973993585 0.000870656595927163 0.0163618267114351 -0.202725076644316 0.979098990871822 0.144868700457821 0.000316278961700607 -0.000181163293714337 1.3577655016139e-05 -2.52232582894274e-06 -1.68468861735206e-05 -8.33679850250428e-05 -0.000181163293714337 0.000160674416525631 -1.31806477501224e-05 -8.2553865040972e-07 8.59432379789241e-06 8.23638852162894e-05 1.3577655016139e-05 -1.31806477501224e-05 1.79279410777192e-05 3.07271053266098e-07 -9.7304548879122e-06 -2.6689624271694e-06 -2.52232582894274e-06 -8.2553865040972e-07 3.07271053266098e-07 2.82776231454714e-05 4.97149641036226e-07 -7.41366947537179e-06 -1.68468861735206e-05 8.59432379789241e-06 -9.7304548879122e-06 4.97149641036226e-07 2.71976267697071e-05 2.47953317061196e-06 -8.33679850250428e-05 8.23638852162894e-05 -2.6689624271694e-06 -7.41366947537179e-06 2.47953317061196e-06 0.000105278225766816 1291 1302 0 0 0 1300 1354 0 0 5 0 0 0 0 0 0 0 0 953 0 0 2 0 0 2457 +1261 1296 0.999597051470687 0.024350152404658 -0.0145878294814001 0.0279610909284606 -0.0209027763555059 0.979144976668737 0.202084607541024 -0.00187761695708749 0.0192043909494725 -0.201698251708457 0.979259417430342 0.140122515770879 0.000134088992083611 -3.64555128561162e-05 4.91353304291503e-06 1.14622969017948e-05 -9.62493504701717e-07 -3.26568380010243e-05 -3.64555128561162e-05 6.6012522877694e-05 -3.21068425075379e-06 -5.03592100015243e-06 -3.00928740962813e-06 4.61192434929242e-05 4.91353304291503e-06 -3.21068425075379e-06 1.21416584890754e-05 4.55721430448842e-06 -7.56201325680966e-06 -1.77366105018808e-06 1.14622969017948e-05 -5.03592100015243e-06 4.55721430448842e-06 2.40214339301263e-05 4.98037619775076e-06 -9.55150615275667e-06 -9.62493504701717e-07 -3.00928740962813e-06 -7.56201325680966e-06 4.98037619775076e-06 1.99513912579642e-05 -4.58943200361129e-06 -3.26568380010243e-05 4.61192434929242e-05 -1.77366105018808e-06 -9.55150615275667e-06 -4.58943200361129e-06 6.73884351630216e-05 1293 1302 0 0 0 1306 1360 0 0 5 0 0 0 0 0 0 0 0 1021 0 0 1 0 0 2404 +1261 1315 0.999534788549454 0.0253822349417238 -0.0169100156345576 0.0260275442197606 -0.0213949143769459 0.978662569995826 0.204357118124055 0.00320615111489793 0.0217362397438241 -0.203900260516089 0.978750335705317 0.15031570902969 0.000209953044543959 -6.70963434350472e-05 2.88105488737665e-06 1.74754884980369e-05 -6.38912148799146e-06 -4.0872614904978e-05 -6.70963434350472e-05 9.23448239693688e-05 -4.5796950748792e-06 -4.26035165765182e-06 -2.6954187691885e-06 2.04314467599463e-05 2.88105488737665e-06 -4.5796950748792e-06 1.5703484003436e-05 2.50942373017197e-06 -9.35241722754178e-06 -2.54942947598528e-06 1.74754884980369e-05 -4.26035165765182e-06 2.50942373017197e-06 2.79340025603544e-05 -1.79699084719249e-06 -6.28370477352935e-06 -6.38912148799146e-06 -2.6954187691885e-06 -9.35241722754178e-06 -1.79699084719249e-06 2.38933828888839e-05 5.35719844396397e-06 -4.0872614904978e-05 2.04314467599463e-05 -2.54942947598528e-06 -6.28370477352935e-06 5.35719844396397e-06 8.23898510285572e-05 1203 1218 0 0 0 1212 1269 0 0 7 0 0 0 0 0 0 0 0 1055 0 0 1 0 0 2309 +1261 1298 0.999668655992871 0.0242776105962032 -0.00855428834835857 0.0272859645880594 -0.0219328445272807 0.977325687891325 0.210602588110142 0.00276413065687209 0.0134732533691709 -0.2103451863283 0.977534333940329 0.148277422801321 0.00018270424614039 -5.18512952597077e-05 4.18100944205609e-06 1.36448399466076e-05 -4.71495831608831e-06 -6.70106259029802e-05 -5.18512952597077e-05 8.43983464026688e-05 -8.2870059271108e-06 -5.49305352032291e-06 -4.74058881605024e-06 4.00753848212341e-05 4.18100944205609e-06 -8.2870059271108e-06 1.4027908569106e-05 -1.551513918684e-06 -5.56502777595058e-06 -6.82462495749331e-06 1.36448399466076e-05 -5.49305352032291e-06 -1.551513918684e-06 3.30071330564671e-05 4.60311959331179e-06 -1.25944257115477e-05 -4.71495831608831e-06 -4.74058881605024e-06 -5.56502777595058e-06 4.60311959331179e-06 2.44138055697737e-05 2.64465977353041e-06 -6.70106259029802e-05 4.00753848212341e-05 -6.82462495749331e-06 -1.25944257115477e-05 2.64465977353041e-06 0.000110353215962771 1205 1222 0 0 0 1212 1269 0 0 10 0 0 0 0 0 0 0 0 959 0 0 2 0 0 2157 +1261 1318 0.999621270744574 0.0257343129339757 -0.00974988270800327 0.0279757707349326 -0.0231515286769368 0.977942970152482 0.207585052085315 0.000929701104428863 0.0148768879448822 -0.20728070886399 0.978168383223419 0.14619141941875 0.000196619982123657 -0.000107403129595512 -1.18328327069454e-06 2.16767556678021e-05 1.54482033948179e-06 -2.56715112665924e-05 -0.000107403129595512 0.000134232603561872 -1.21905438519987e-07 -1.72269804628844e-05 -3.23261774266419e-06 3.61508944900472e-05 -1.18328327069454e-06 -1.21905438519987e-07 1.44425046811155e-05 4.37455410424862e-06 -8.80959575463923e-06 8.34899135627405e-07 2.16767556678021e-05 -1.72269804628844e-05 4.37455410424862e-06 3.26566365722291e-05 -1.99547058683848e-07 -4.61118316656795e-06 1.54482033948179e-06 -3.23261774266419e-06 -8.80959575463923e-06 -1.99547058683848e-07 2.38869187694524e-05 -2.26659147017827e-06 -2.56715112665924e-05 3.61508944900472e-05 8.34899135627405e-07 -4.61118316656795e-06 -2.26659147017827e-06 8.05045769543349e-05 1403 1423 0 0 0 1419 1483 0 0 9 0 0 0 0 0 0 0 0 1061 0 0 4 0 0 2336 +1261 1312 0.999677148056377 0.0252517204359984 0.00281962211832302 0.030323397374847 -0.0252288473153041 0.973293724389503 0.228172810227579 0.00762240231351816 0.00301743550204932 -0.228170280008225 0.973616566418197 0.157893207039844 0.000248164076686931 -0.000117074291520087 7.9819435855639e-06 -1.46210577381782e-06 -8.28760661767656e-06 -4.54469490548907e-05 -0.000117074291520087 0.000181589959642463 -7.16369219477075e-06 8.23798917318001e-06 2.1169058616876e-06 2.1975783870882e-05 7.9819435855639e-06 -7.16369219477075e-06 1.64906732299275e-05 -1.42998015762276e-06 -7.58368094142836e-06 -4.11026533171931e-06 -1.46210577381782e-06 8.23798917318001e-06 -1.42998015762276e-06 3.31392503543426e-05 1.57323339275602e-06 -6.74522587066565e-06 -8.28760661767656e-06 2.1169058616876e-06 -7.58368094142836e-06 1.57323339275602e-06 2.27563376057152e-05 3.42130216287838e-06 -4.54469490548907e-05 2.1975783870882e-05 -4.11026533171931e-06 -6.74522587066565e-06 3.42130216287838e-06 9.59693303246663e-05 1303 1323 0 0 0 1313 1367 0 0 11 0 0 0 0 0 0 0 0 1048 0 0 2 0 0 2174 +1262 1264 0.997968874596233 0.0285605854004818 -0.0569422365095541 0.0247695750670573 -0.0289631091114027 0.999560903299717 -0.00625610943434516 0.00195048622949171 0.0567385552136217 0.00789262670061783 0.998357873107652 0.0394991556003971 7.43941984600678e-05 2.85027483971055e-05 -5.32053854698611e-06 1.300597624806e-05 -7.91024196529582e-06 -1.92166829788173e-05 2.85027483971055e-05 5.68041282742441e-05 -7.18492092412808e-06 1.29324382956902e-05 -6.56649917360287e-06 -2.75302649426937e-06 -5.32053854698611e-06 -7.18492092412808e-06 1.24364807554274e-05 2.11366095279811e-06 -5.85432958201622e-06 2.02980981428661e-06 1.300597624806e-05 1.29324382956902e-05 2.11366095279811e-06 2.44793893217034e-05 -4.15784629600113e-06 -6.6986686759778e-06 -7.91024196529582e-06 -6.56649917360287e-06 -5.85432958201622e-06 -4.15784629600113e-06 2.00758244498813e-05 1.64606970162054e-05 -1.92166829788173e-05 -2.75302649426937e-06 2.02980981428661e-06 -6.6986686759778e-06 1.64606970162054e-05 9.51032714577555e-05 1564 1564 0 0 0 1598 1640 0 0 0 0 0 0 0 0 0 0 0 764 0 0 13 0 0 3332 +1262 1266 0.998979486689977 0.000655260913860341 -0.0451614415819931 0.0246793113212123 -3.22606988623131e-05 0.999904853499797 0.0137943070430313 0.00633919227243126 0.0451661834991216 -0.0137787728294243 0.998884458427219 0.0597373126996091 8.94297914527771e-05 1.48873631557082e-05 2.03630948289925e-06 6.29958601938382e-06 -1.06135654512411e-05 -2.77363833193342e-05 1.48873631557082e-05 4.98547734175036e-05 -3.39711422909825e-06 3.81368922220517e-06 -8.2039903990563e-06 5.67400500168068e-06 2.03630948289925e-06 -3.39711422909825e-06 1.22100640089716e-05 3.55072261111533e-06 -7.09064150769275e-06 -3.82823868882117e-07 6.29958601938382e-06 3.81368922220517e-06 3.55072261111533e-06 2.6527687863037e-05 1.48840910319468e-06 -1.0340181540043e-06 -1.06135654512411e-05 -8.2039903990563e-06 -7.09064150769275e-06 1.48840910319468e-06 2.44203049402575e-05 1.39945368353113e-05 -2.77363833193342e-05 5.67400500168068e-06 -3.82823868882117e-07 -1.0340181540043e-06 1.39945368353113e-05 7.27661539315892e-05 1476 1521 0 0 0 1476 1560 0 0 8 0 0 0 0 0 0 0 0 678 0 0 0 0 0 3385 +1262 1265 0.998837014329288 0.0192059303647576 -0.0442238741470902 0.0227635607821605 -0.0194195833365331 0.999801711203234 -0.00440659257482989 0.0046468921023299 0.0441304723381592 0.00526027698027247 0.999011927304825 0.0556846413360506 9.61198837596233e-05 -2.75955272066817e-05 6.65713031898487e-06 8.51085393477956e-06 -3.06495646373146e-06 -8.81733861920855e-06 -2.75955272066817e-05 7.99331411135655e-05 -1.4744383519667e-05 1.41231566659671e-06 -2.60989047243592e-06 2.20060987987149e-05 6.65713031898487e-06 -1.4744383519667e-05 1.36373189221198e-05 8.92636973137528e-07 -7.94869057911389e-06 -2.64348869662464e-06 8.51085393477956e-06 1.41231566659671e-06 8.92636973137528e-07 3.20796867560918e-05 7.20662484560639e-06 -4.44703275310183e-06 -3.06495646373146e-06 -2.60989047243592e-06 -7.94869057911389e-06 7.20662484560639e-06 2.3825689312078e-05 1.11158714794904e-05 -8.81733861920855e-06 2.20060987987149e-05 -2.64348869662464e-06 -4.44703275310183e-06 1.11158714794904e-05 6.32279945764009e-05 1551 1553 0 0 0 1562 1629 0 0 0 0 0 0 0 0 0 0 0 749 0 0 0 0 0 3365 +1262 1288 0.995998813092973 0.00813596150518502 -0.088995339472215 0.0330811250778232 -0.00186081727912387 0.997519377344382 0.070367813533819 2.77259047699232e-05 0.089347085438991 -0.06992065469418 0.993543255409997 0.0989686346034332 0.000144199578858465 -5.26978172940912e-05 1.42986219357205e-05 9.07203187255982e-07 2.7719349875933e-07 -2.9583289084711e-05 -5.26978172940912e-05 9.20168747706013e-05 -7.98470939210285e-06 -4.86097740672768e-06 -3.73833959780274e-06 5.68941426643132e-05 1.42986219357205e-05 -7.98470939210285e-06 1.327670924579e-05 -3.27258586134021e-07 -7.84011639137165e-06 -3.21861316293126e-06 9.07203187255982e-07 -4.86097740672768e-06 -3.27258586134021e-07 2.45049404904962e-05 4.17972425076081e-06 -5.92021085060111e-06 2.7719349875933e-07 -3.73833959780274e-06 -7.84011639137165e-06 4.17972425076081e-06 1.98535688912218e-05 4.3264845672676e-06 -2.9583289084711e-05 5.68941426643132e-05 -3.21861316293126e-06 -5.92021085060111e-06 4.3264845672676e-06 7.82807160511491e-05 1272 1307 0 0 0 1272 1347 0 0 2 0 0 0 0 0 0 0 0 768 0 0 0 0 0 3237 +1261 1308 0.999672538802522 0.0235389685011615 -0.0100365395441568 0.0324217284235189 -0.0210054171561239 0.978847708651122 0.203509055618036 0.00276053867017546 0.0146146369854784 -0.203231592599057 0.979021619861091 0.152219461195201 0.000294103870547841 -0.000112800742193779 9.49410788599535e-06 2.29747598324952e-05 -2.20831322249656e-06 -6.87242224551601e-05 -0.000112800742193779 0.000110558867046828 -3.28903402012897e-06 -2.46799270177168e-06 7.2434518315667e-08 3.43904812420855e-05 9.49410788599535e-06 -3.28903402012897e-06 1.47021955257461e-05 2.39996413228923e-06 -6.81203565081275e-06 -7.78479789047189e-06 2.29747598324952e-05 -2.46799270177168e-06 2.39996413228923e-06 3.56038760559033e-05 7.0263790064826e-06 -1.13423122922215e-05 -2.20831322249656e-06 7.2434518315667e-08 -6.81203565081275e-06 7.0263790064826e-06 2.61261525597546e-05 -9.19561886961508e-06 -6.87242224551601e-05 3.43904812420855e-05 -7.78479789047189e-06 -1.13423122922215e-05 -9.19561886961508e-06 9.7957216301209e-05 1213 1231 0 0 0 1218 1276 0 0 10 0 0 0 0 0 0 0 0 1059 0 0 0 0 0 2418 +1262 1289 0.997948339553939 0.0118012850212848 -0.0629272695528849 0.0255937502277546 -0.0044270385330698 0.993232114267544 0.116061916740379 -0.0105671550320144 0.0638710647426654 -0.115545215649417 0.991246583968473 0.0902092138769933 0.000137042940545283 -1.35237226590971e-06 8.83088526480777e-06 3.09929751183768e-06 -2.64590002187026e-06 -4.83549486727235e-09 -1.35237226590971e-06 5.27126157379026e-05 -1.06840412924587e-06 -4.95847596424662e-06 -2.42927778227592e-06 2.86928132942379e-05 8.83088526480777e-06 -1.06840412924587e-06 1.33423389566952e-05 1.26749088799258e-06 -7.99074491788168e-06 -9.73334767961717e-07 3.09929751183768e-06 -4.95847596424662e-06 1.26749088799258e-06 2.89233072325661e-05 5.33243596847843e-06 3.91188975437489e-06 -2.64590002187026e-06 -2.42927778227592e-06 -7.99074491788168e-06 5.33243596847843e-06 2.2813518078102e-05 2.32789093687187e-06 -4.83549486727235e-09 2.86928132942379e-05 -9.73334767961717e-07 3.91188975437489e-06 2.32789093687187e-06 5.71551660164705e-05 1344 1355 0 0 0 1345 1417 0 0 0 0 0 0 0 0 0 0 0 786 0 0 0 0 0 3243 +1262 1293 0.999799389117919 0.0191410200085633 -0.00589939594092034 0.0160375954359221 -0.0174065041673753 0.976043362334692 0.216878695253963 -0.0235778494936434 0.00990934569520672 -0.216732499167573 0.976180735659371 0.109799052998633 0.00011217703931403 -2.00904391791309e-05 4.85676079740183e-06 -5.85438497359623e-06 -6.40149544319403e-06 -1.84233080068466e-05 -2.00904391791309e-05 8.53023024827125e-05 1.90650908422705e-09 4.03098847456946e-06 4.22662242323789e-06 4.89355917188577e-05 4.85676079740183e-06 1.90650908422705e-09 1.07725483911534e-05 2.10428994376593e-06 -6.7931458682398e-06 2.50522953668235e-08 -5.85438497359623e-06 4.03098847456946e-06 2.10428994376593e-06 2.75092211810055e-05 7.55217697826073e-06 -2.80210277322832e-06 -6.40149544319403e-06 4.22662242323789e-06 -6.7931458682398e-06 7.55217697826073e-06 2.29237360155613e-05 2.8767792526623e-06 -1.84233080068466e-05 4.89355917188577e-05 2.50522953668235e-08 -2.80210277322832e-06 2.8767792526623e-06 8.65908226068263e-05 1281 1289 0 0 0 1310 1345 0 0 0 0 0 0 0 0 0 0 0 1007 0 0 14 0 0 2498 +1262 1296 0.999674408380858 0.0181086311018613 -0.0179765043319973 0.0133082577592487 -0.0140967370463791 0.97918808466999 0.202464754574622 -0.025546883497389 0.021268738397631 -0.20214542369278 0.97912454184697 0.10232580777177 0.000236484647502216 -0.000112601877054593 1.52365694365469e-05 1.26161281775524e-05 1.12428092370877e-05 -8.06822748312018e-05 -0.000112601877054593 0.000118701803796026 -7.80588273007322e-06 -1.16675406035915e-05 -6.01151902474137e-06 7.56564009767788e-05 1.52365694365469e-05 -7.80588273007322e-06 1.29452530250918e-05 2.32815898431081e-06 -7.35952762167191e-06 -4.38565199204494e-06 1.26161281775524e-05 -1.16675406035915e-05 2.32815898431081e-06 2.7724325231504e-05 6.82452162695058e-06 -1.12863600356316e-05 1.12428092370877e-05 -6.01151902474137e-06 -7.35952762167191e-06 6.82452162695058e-06 2.08714014570829e-05 -4.54509735142433e-06 -8.06822748312018e-05 7.56564009767788e-05 -4.38565199204494e-06 -1.12863600356316e-05 -4.54509735142433e-06 0.000100259066369009 1279 1283 0 0 0 1311 1346 0 0 0 0 0 0 0 0 0 0 0 997 0 0 14 0 0 2518 +1262 1315 0.999673578086251 0.0201305000461788 -0.0157321404813011 0.0157742366667423 -0.0165362798443576 0.979205067646291 0.202197890554602 -0.0224791491733266 0.01947533632936 -0.201871737654662 0.979218317236328 0.106324027593889 0.000258586596607792 -8.61914368048809e-05 6.15176857443942e-07 2.54773106034516e-05 -6.9633288146442e-06 -6.47493914949909e-05 -8.61914368048809e-05 0.000122727259112513 -9.21825707103191e-07 -1.20331222536471e-05 -3.89450071672251e-06 4.05571222633412e-05 6.15176857443942e-07 -9.21825707103191e-07 1.65308705674822e-05 3.2048200720656e-06 -9.71608803296921e-06 -6.4822598602819e-06 2.54773106034516e-05 -1.20331222536471e-05 3.2048200720656e-06 3.74590854668065e-05 -1.55610245531697e-06 -8.20536648513415e-06 -6.9633288146442e-06 -3.89450071672251e-06 -9.71608803296921e-06 -1.55610245531697e-06 2.30509520707045e-05 -1.73167640578806e-06 -6.47493914949909e-05 4.05571222633412e-05 -6.4822598602819e-06 -8.20536648513415e-06 -1.73167640578806e-06 0.000123214274186973 1190 1196 0 0 0 1216 1253 0 0 0 0 0 0 0 0 0 0 0 1022 0 0 13 0 0 2512 +1262 1292 0.999776548012148 0.0165435989101529 -0.0131591557485254 0.016530734754169 -0.0137357456821775 0.98159638527125 0.190472742703437 -0.0280716222045541 0.0160680843745764 -0.190249430373694 0.98160428427499 0.0941386537199741 0.000219703276439193 -0.000102609046866337 1.46228985347899e-05 1.28155928665304e-05 3.4621753895022e-06 -5.97898663430125e-05 -0.000102609046866337 0.000104888931277726 -7.52023478330493e-06 -9.44121568872262e-06 -6.58767946694916e-06 6.09222851433333e-05 1.46228985347899e-05 -7.52023478330493e-06 1.15965198605158e-05 1.0639717156833e-06 -6.84488032821039e-06 -5.56787693883629e-06 1.28155928665304e-05 -9.44121568872262e-06 1.0639717156833e-06 2.77351234215822e-05 8.81574188145406e-06 -3.45028505677286e-06 3.4621753895022e-06 -6.58767946694916e-06 -6.84488032821039e-06 8.81574188145406e-06 2.15003890850577e-05 -2.4412706060839e-08 -5.97898663430125e-05 6.09222851433333e-05 -5.56787693883629e-06 -3.45028505677286e-06 -2.4412706060839e-08 8.55958061308933e-05 1263 1266 0 0 0 1290 1323 0 0 0 0 0 0 0 0 0 0 0 988 0 0 16 0 0 2683 +1262 1316 0.999753854843482 0.0213301299653713 -0.006103710450019 0.0212604593249345 -0.0195514989966191 0.977065097089906 0.212041351947391 -0.0197812475926945 0.0104865920385274 -0.211869822306888 0.977241633263271 0.10220707589291 0.000221012319030511 -8.21223635988752e-05 1.19761522693164e-06 1.68851727023614e-05 7.34602091352769e-07 -5.04452637919097e-05 -8.21223635988752e-05 0.000121059906956699 -9.19416156837954e-07 -5.74975008623872e-06 -9.35616357661078e-06 4.7484378368203e-05 1.19761522693164e-06 -9.19416156837954e-07 1.79685812043036e-05 2.68598140036649e-06 -1.07067500997128e-05 1.65285729226296e-07 1.68851727023614e-05 -5.74975008623872e-06 2.68598140036649e-06 3.16507475668241e-05 -3.5918000843682e-06 -1.07570026870542e-05 7.34602091352769e-07 -9.35616357661078e-06 -1.07067500997128e-05 -3.5918000843682e-06 2.44498521313351e-05 -6.76085215645634e-06 -5.04452637919097e-05 4.7484378368203e-05 1.65285729226296e-07 -1.07570026870542e-05 -6.76085215645634e-06 0.000104032824052992 1204 1215 0 0 0 1227 1267 0 0 0 0 0 0 0 0 0 0 0 1014 0 0 10 0 0 2555 +1262 1314 0.999667263393272 0.0195674274938418 -0.0168070902026303 0.0165176915783467 -0.0157599461037002 0.979141403418281 0.202567855818458 -0.0195270239401862 0.0204202497196917 -0.202235575241727 0.979123988832892 0.10723737995682 0.000332720459356023 -0.000216285470874686 6.3773404742062e-06 1.41146239972726e-05 -7.43421462147356e-06 -9.01603670662056e-05 -0.000216285470874686 0.000230312516104255 -1.1925619851282e-05 -2.8939064036359e-06 -1.12256965762451e-06 8.14395153716469e-05 6.3773404742062e-06 -1.1925619851282e-05 1.77914563075278e-05 2.3973511005909e-06 -7.93742625216996e-06 -4.45405676539531e-06 1.41146239972726e-05 -2.8939064036359e-06 2.3973511005909e-06 3.29566857736909e-05 -1.94563985293507e-06 -7.25784638505238e-06 -7.43421462147356e-06 -1.12256965762451e-06 -7.93742625216996e-06 -1.94563985293507e-06 2.66150800337871e-05 8.13192342458552e-07 -9.01603670662056e-05 8.14395153716469e-05 -4.45405676539531e-06 -7.25784638505238e-06 8.13192342458552e-07 0.000145832209061316 1285 1291 0 0 0 1311 1351 0 0 0 0 0 0 0 0 0 0 0 1026 0 0 11 0 0 2297 +1262 1294 0.999848779295207 0.0172027994841641 -0.00254602273995448 0.0176868199687183 -0.0163576823937684 0.980047087492538 0.198091222733613 -0.0263333835131546 0.00590294575524138 -0.19801962020795 0.980180282011483 0.0891070426272364 0.000193639722570112 -4.5711414290798e-05 8.37227457687626e-06 9.89713780043634e-06 -1.66353855492066e-06 -3.68879002400052e-05 -4.5711414290798e-05 9.92868916986177e-05 -1.01422158222257e-06 -1.75022549739271e-06 -2.43362218813967e-06 4.9565591404247e-05 8.37227457687626e-06 -1.01422158222257e-06 1.1996952275989e-05 5.4083490484619e-08 -7.29034812331025e-06 -3.22101435797911e-06 9.89713780043634e-06 -1.75022549739271e-06 5.4083490484619e-08 2.7322428090229e-05 6.46936486200496e-06 -1.59195637016347e-06 -1.66353855492066e-06 -2.43362218813967e-06 -7.29034812331025e-06 6.46936486200496e-06 2.10582272014829e-05 -1.65944576025457e-06 -3.68879002400052e-05 4.9565591404247e-05 -3.22101435797911e-06 -1.59195637016347e-06 -1.65944576025457e-06 9.49473710127046e-05 1378 1396 0 0 0 1407 1455 0 0 3 0 0 0 0 0 0 0 0 1023 0 0 16 0 0 2381 +1262 1297 0.99969574474753 0.0187741576687306 -0.0159984042176381 0.0139642975812212 -0.0148758852936651 0.976260042061078 0.216090347567011 -0.0193576388067173 0.0196755170303354 -0.215786610517732 0.97624229203147 0.111823485224739 0.000114105130164374 -2.32604439484238e-05 6.20275319830125e-06 -1.67772376661669e-06 -8.78774754292427e-07 -2.68596359257705e-05 -2.32604439484238e-05 4.83028878095956e-05 -2.4226468675015e-06 -4.39113719909172e-06 -5.16143419742551e-06 3.63489316605391e-05 6.20275319830125e-06 -2.4226468675015e-06 1.22113757660395e-05 -1.21678898237239e-06 -8.92142093980547e-06 -1.42299553614439e-06 -1.67772376661669e-06 -4.39113719909172e-06 -1.21678898237239e-06 2.96107141728548e-05 1.09910224218359e-05 -6.66972036584224e-06 -8.78774754292427e-07 -5.16143419742551e-06 -8.92142093980547e-06 1.09910224218359e-05 2.48332810818024e-05 -2.67005384390336e-06 -2.68596359257705e-05 3.63489316605391e-05 -1.42299553614439e-06 -6.66972036584224e-06 -2.67005384390336e-06 6.54342072658723e-05 1386 1401 0 0 0 1415 1461 0 0 3 0 0 0 0 0 0 0 0 1016 0 0 17 0 0 2356 +1262 1318 0.999676119197194 0.0206387164458298 -0.0148895967140008 0.0150221870516852 -0.0170257931529929 0.977237094219133 0.211465798770529 -0.0205715712667275 0.0189150488857007 -0.211143801864073 0.977271976401675 0.115433069762207 0.000134940392769451 -5.2281378611709e-05 8.52788408619759e-06 -1.56097655146183e-06 -1.91078546368876e-06 -2.85631654314069e-05 -5.2281378611709e-05 7.70548219231319e-05 -1.68870427348131e-06 -5.1715944897819e-06 -3.64559656854225e-06 4.25040615179425e-05 8.52788408619759e-06 -1.68870427348131e-06 1.53512007578939e-05 2.65668601026976e-06 -1.10837403160886e-05 -2.52539665773686e-08 -1.56097655146183e-06 -5.1715944897819e-06 2.65668601026976e-06 3.16451746580204e-05 1.98202504493034e-06 -4.5612506630954e-06 -1.91078546368876e-06 -3.64559656854225e-06 -1.10837403160886e-05 1.98202504493034e-06 2.22454027932789e-05 -3.76337250310807e-06 -2.85631654314069e-05 4.25040615179425e-05 -2.52539665773686e-08 -4.5612506630954e-06 -3.76337250310807e-06 5.99592498085133e-05 1384 1397 0 0 0 1417 1459 0 0 2 0 0 0 0 0 0 0 0 1029 0 0 21 0 0 2487 +1262 1312 0.999749861083491 0.0206031517405583 0.0087020343538402 0.0204137695215968 -0.022054521484747 0.972823656347163 0.230494537317952 -0.0177034435346786 -0.0037166309500299 -0.230628800867744 0.973034707944525 0.105551207411205 0.00014415502586926 -5.71232672473076e-05 1.68957791001976e-07 -7.88131863940081e-07 -1.21991006520058e-05 -4.26080993273226e-05 -5.71232672473076e-05 0.000103222797336039 -7.48119864924933e-06 9.94133737398887e-06 6.02111483503537e-06 3.11059736232746e-05 1.68957791001976e-07 -7.48119864924933e-06 1.85995398128335e-05 -2.57575702430007e-06 -7.94849418617289e-06 -7.02194288287244e-06 -7.88131863940081e-07 9.94133737398887e-06 -2.57575702430007e-06 3.08708058642644e-05 3.44278384501251e-06 -4.99543943866181e-07 -1.21991006520058e-05 6.02111483503537e-06 -7.94849418617289e-06 3.44278384501251e-06 2.53697574745037e-05 4.85323822920529e-06 -4.26080993273226e-05 3.11059736232746e-05 -7.02194288287244e-06 -4.99543943866181e-07 4.85323822920529e-06 7.84434941819859e-05 1362 1373 0 0 0 1389 1427 0 0 1 0 0 0 0 0 0 0 0 1005 0 0 16 0 0 2359 +1263 1265 0.999917310801276 -0.00357930897621888 0.0123515224647574 0.00970049791891847 0.0033992261188235 0.999888071994825 0.0145701319233566 0.00395643314747608 -0.0124022909874651 -0.0145269415130532 0.999817558931898 0.033203522135639 0.000128740509529395 4.40972730462619e-06 -2.35110365073101e-06 1.41929005635507e-05 -2.03042679034017e-05 -1.94845252072967e-05 4.40972730462619e-06 8.16031173691803e-05 -1.15791477953274e-05 1.47886733926454e-05 -2.86881517763635e-06 8.75235694247721e-06 -2.35110365073101e-06 -1.15791477953274e-05 1.20564024914948e-05 -5.8425250486737e-07 -6.93051592738856e-06 -2.9702086526376e-07 1.41929005635507e-05 1.47886733926454e-05 -5.8425250486737e-07 3.07514250791781e-05 1.23918944194827e-07 -9.6064798112523e-06 -2.03042679034017e-05 -2.86881517763635e-06 -6.93051592738856e-06 1.23918944194827e-07 2.56651056634143e-05 2.09982328778565e-05 -1.94845252072967e-05 8.75235694247721e-06 -2.9702086526376e-07 -9.6064798112523e-06 2.09982328778565e-05 9.25774590191413e-05 1562 1597 0 0 0 1562 1646 0 0 4 0 0 0 0 0 0 0 0 743 0 0 0 0 0 3398 +1262 1308 0.999683048390594 0.0174202271592368 -0.0181752151626909 0.0190123688632824 -0.0134262586435083 0.979613461225037 0.200442515863127 -0.0194992605680328 0.021296439592738 -0.200134960145455 0.979536859637375 0.108914938861807 0.000351242431307574 -0.000176406716444493 1.60639865488262e-05 2.59205445182317e-06 -1.10705553897582e-05 -8.88839081254744e-05 -0.000176406716444493 0.000168607301690375 -1.26255561543085e-05 6.38604377111608e-06 2.48539934931937e-06 8.90203955889543e-05 1.60639865488262e-05 -1.26255561543085e-05 1.48528290856236e-05 -4.56230288946871e-07 -8.54794154982158e-06 -6.73054553926664e-06 2.59205445182317e-06 6.38604377111608e-06 -4.56230288946871e-07 3.23794108200868e-05 5.56869829760309e-06 -3.51832895596224e-06 -1.10705553897582e-05 2.48539934931937e-06 -8.54794154982158e-06 5.56869829760309e-06 2.42397010295503e-05 4.30135115992178e-07 -8.88839081254744e-05 8.90203955889543e-05 -6.73054553926664e-06 -3.51832895596224e-06 4.30135115992178e-07 0.000117615498999322 1208 1218 0 0 0 1227 1271 0 0 0 0 0 0 0 0 0 0 0 1027 0 0 8 0 0 2524 +1262 1317 0.999725807641525 0.0205744284128811 -0.0111804486039013 0.0217822601635702 -0.017861702004909 0.978797179400296 0.204051565050385 -0.0221973791830245 0.0151416358755941 -0.20379591382927 0.97889629500244 0.102723157043584 0.000280811559701341 -0.00011014672282041 4.97255028751552e-06 7.32280708025198e-06 -4.29287189095626e-06 -6.76235734859849e-05 -0.00011014672282041 0.000125642289000427 -5.29000341887852e-06 -2.56702644281641e-06 8.6756443301234e-07 6.18277385510866e-05 4.97255028751552e-06 -5.29000341887852e-06 1.41315943925962e-05 2.97173945251227e-06 -8.55917510167043e-06 -3.06675779953401e-06 7.32280708025198e-06 -2.56702644281641e-06 2.97173945251227e-06 3.17739414160536e-05 -3.08186223334374e-06 -8.35804281662407e-06 -4.29287189095626e-06 8.6756443301234e-07 -8.55917510167043e-06 -3.08186223334374e-06 2.2729174544288e-05 1.89842242013524e-06 -6.76235734859849e-05 6.18277385510866e-05 -3.06675779953401e-06 -8.35804281662407e-06 1.89842242013524e-06 0.000115255946276976 1283 1290 0 0 0 1311 1348 0 0 0 0 0 0 0 0 0 0 0 923 0 0 11 0 0 2563 +1263 1292 0.999385590915159 -0.0164124625651262 0.0309688834752987 0.00835681007383671 0.0100105056532513 0.980441588110578 0.196555544515475 -0.0293775934027355 -0.0335891418128615 -0.196124764820144 0.980003492940979 0.0726840331789592 0.000261274437075982 8.02378294023623e-05 5.4231718865137e-06 9.39986547826586e-06 -7.07487401048988e-06 -0.000328600134976086 8.02378294023623e-05 0.000549573950779391 8.72110187605288e-06 5.58298924212565e-05 -1.46541723125767e-06 -0.000915074198518991 5.4231718865137e-06 8.72110187605288e-06 1.00117457501718e-05 2.49201261766633e-06 -5.51982472450754e-06 -1.86142758907283e-05 9.39986547826586e-06 5.58298924212565e-05 2.49201261766633e-06 2.89229257697194e-05 3.99556353123429e-06 -0.000107180380614692 -7.07487401048988e-06 -1.46541723125767e-06 -5.51982472450754e-06 3.99556353123429e-06 1.90549307321158e-05 9.71495331617821e-08 -0.000328600134976086 -0.000915074198518991 -1.86142758907283e-05 -0.000107180380614692 9.71495331617821e-08 0.00212629447985724 1286 1309 0 0 0 1295 1349 0 0 14 0 0 0 0 0 0 0 0 966 0 0 3 0 0 2667 +1263 1266 0.999686106251629 -0.0220683686025786 0.0118606945276018 0.0142004964563275 0.0220628042859088 0.999756406787525 0.000599795247075246 -0.00498070183148204 -0.0118710418455182 -0.000337926793039458 0.999929479598929 0.0126532592517668 8.36485519847205e-05 1.80880168674555e-05 -3.69499161358874e-06 1.19551586771448e-05 -9.60578237180096e-06 -1.58491240829727e-05 1.80880168674555e-05 6.7083303336404e-05 -1.22689909199235e-05 1.01568550428892e-05 -9.06632438571434e-06 -1.22260737085001e-05 -3.69499161358874e-06 -1.22689909199235e-05 1.25724016642122e-05 1.63059763120771e-06 -5.60907639476865e-06 4.05688657648455e-06 1.19551586771448e-05 1.01568550428892e-05 1.63059763120771e-06 2.43763623180275e-05 -5.41240107420014e-06 -7.10350633854938e-06 -9.60578237180096e-06 -9.06632438571434e-06 -5.60907639476865e-06 -5.41240107420014e-06 2.19488631919277e-05 2.38823237714959e-05 -1.58491240829727e-05 -1.22260737085001e-05 4.05688657648455e-06 -7.10350633854938e-06 2.38823237714959e-05 0.000125377127134939 1476 1547 0 0 0 1476 1560 0 0 39 0 0 0 0 0 0 0 0 649 0 0 0 0 0 3367 +1263 1294 0.998891635143768 -0.0166775646519511 0.0440154527079908 0.00686501241860835 0.00743444765899096 0.979287855436086 0.202336415860805 -0.0308192901813453 -0.0464782769454195 -0.201784922708985 0.978326435674471 0.0579333359815641 0.00018389666011914 -5.30723849167308e-05 2.46689646785207e-06 -1.43888185740692e-06 -5.01001361693934e-06 -2.56187672828097e-05 -5.30723849167308e-05 8.27460374184838e-05 1.35545142263236e-06 1.6256321952175e-06 4.07360403082299e-06 4.81229584831377e-05 2.46689646785207e-06 1.35545142263236e-06 1.21082600449879e-05 -3.59472902287358e-07 -7.28903228734059e-06 -2.59502538033051e-07 -1.43888185740692e-06 1.6256321952175e-06 -3.59472902287358e-07 2.72444981500423e-05 4.75519796943123e-06 -2.49143033904507e-06 -5.01001361693934e-06 4.07360403082299e-06 -7.28903228734059e-06 4.75519796943123e-06 2.05134361784575e-05 3.34633621681753e-07 -2.56187672828097e-05 4.81229584831377e-05 -2.59502538033051e-07 -2.49143033904507e-06 3.34633621681753e-07 9.01004920346545e-05 1397 1431 0 0 5 1411 1478 0 0 20 0 0 0 0 0 0 0 0 1004 0 0 6 0 0 2373 +1263 1267 0.999900689316728 -0.0133264300034792 0.0045845138558552 0.0132907679781802 0.0131271309320717 0.999070645950011 0.0410551194678581 -0.00521242948829705 -0.00512737139520892 -0.0409908607422463 0.999146365353037 0.0438098571677448 8.95566108386533e-05 -4.90900420765045e-06 1.76879055537032e-07 9.09604149775012e-07 -1.36440387220254e-05 -2.50586672360085e-05 -4.90900420765045e-06 6.66075543634331e-05 -9.82883982528111e-06 8.67962316030839e-06 -2.58555892153609e-06 2.21657906584544e-05 1.76879055537032e-07 -9.82883982528111e-06 1.12528426650161e-05 -2.00232801969239e-06 -7.12277453587941e-06 -4.23284447567244e-06 9.09604149775012e-07 8.67962316030839e-06 -2.00232801969239e-06 2.86689639899834e-05 3.32016039538678e-06 -4.88436543008761e-06 -1.36440387220254e-05 -2.58555892153609e-06 -7.12277453587941e-06 3.32016039538678e-06 2.11806564865529e-05 1.22205130414972e-05 -2.50586672360085e-05 2.21657906584544e-05 -4.23284447567244e-06 -4.88436543008761e-06 1.22205130414972e-05 9.20519188084026e-05 1555 1604 0 0 0 1555 1640 0 0 18 0 0 0 0 0 0 0 0 762 0 0 0 0 0 3345 +1263 1289 0.999688134030613 -0.018074533973778 -0.017232118268594 0.016654611821201 0.0198800059849142 0.993608364954568 0.111117966388653 -0.0143997968437795 0.0151135713989726 -0.111425887090661 0.993657814162213 0.0537873991123178 0.000123602095120773 -4.06169511054127e-05 4.35421691236793e-06 -1.3351748145096e-06 -5.03363639173209e-06 -2.85808684901168e-05 -4.06169511054127e-05 6.27949455474804e-05 -1.81778890205501e-06 -1.18953187912272e-06 2.78559064585216e-06 4.18477883731602e-05 4.35421691236793e-06 -1.81778890205501e-06 1.28272598715516e-05 -2.35832103303576e-06 -6.98049024694675e-06 -1.63488939290581e-06 -1.3351748145096e-06 -1.18953187912272e-06 -2.35832103303576e-06 2.84735657915207e-05 3.7652818847952e-06 -7.91665846437954e-07 -5.03363639173209e-06 2.78559064585216e-06 -6.98049024694675e-06 3.7652818847952e-06 2.00879168496981e-05 2.79571353025172e-06 -2.85808684901168e-05 4.18477883731602e-05 -1.63488939290581e-06 -7.91665846437954e-07 2.79571353025172e-06 6.85858637391561e-05 1345 1395 0 0 1 1345 1419 0 0 27 0 0 0 0 0 0 0 0 767 0 0 0 0 0 3254 +1263 1291 0.999698203230638 -0.0168249348218634 0.0179003917743453 0.0103412419170165 0.0135987902703247 0.985838358064441 0.167146057901439 -0.0273620672547851 -0.0204591143654539 -0.166852190087657 0.985769633992818 0.0442674229529231 0.000124219776744572 -2.92983596825381e-05 7.39285709251396e-07 8.30778217034676e-06 6.31035554857073e-06 1.56363770507855e-05 -2.92983596825381e-05 7.01413291958051e-05 -1.59552087424727e-06 1.60644362772192e-06 3.29091118001707e-06 2.98445234486284e-05 7.39285709251396e-07 -1.59552087424727e-06 9.66832167035058e-06 1.34560622266208e-06 -6.92374449761508e-06 -1.05974027998874e-06 8.30778217034676e-06 1.60644362772192e-06 1.34560622266208e-06 2.17827486326824e-05 4.71019412447948e-06 1.20642400610156e-06 6.31035554857073e-06 3.29091118001707e-06 -6.92374449761508e-06 4.71019412447948e-06 1.82626889749461e-05 9.59201612864194e-07 1.56363770507855e-05 2.98445234486284e-05 -1.05974027998874e-06 1.20642400610156e-06 9.59201612864194e-07 8.18961548779853e-05 1265 1305 0 0 4 1270 1347 0 0 19 0 0 0 0 0 0 0 0 874 0 0 0 0 0 2754 +1263 1290 0.999834729325341 -0.0163226884720911 0.00800524053133553 0.01478555698913 0.0150023659139096 0.989490992089883 0.143814135570758 -0.0219635395975836 -0.0102685467280739 -0.143670269763866 0.989572337191209 0.0478255317874156 7.94372757676417e-05 -1.31816973793785e-05 2.38406362625374e-06 3.71033893134631e-07 -5.72335459758263e-06 -4.85100134675825e-06 -1.31816973793785e-05 5.92044111215337e-05 -7.30906486550286e-07 -3.29269432306062e-07 7.91642438600158e-08 3.39663507624797e-05 2.38406362625374e-06 -7.30906486550286e-07 1.01988804127787e-05 1.44821918886605e-06 -5.71961565928621e-06 -6.21728774830905e-07 3.71033893134631e-07 -3.29269432306062e-07 1.44821918886605e-06 2.16818498203555e-05 4.65089906557061e-06 1.98278091139904e-06 -5.72335459758263e-06 7.91642438600158e-08 -5.71961565928621e-06 4.65089906557061e-06 2.24005880133392e-05 5.98665804664954e-06 -4.85100134675825e-06 3.39663507624797e-05 -6.21728774830905e-07 1.98278091139904e-06 5.98665804664954e-06 6.50347506913222e-05 1377 1413 0 0 0 1380 1453 0 0 19 0 0 0 0 0 0 0 0 874 0 0 1 0 0 3005 +1263 1314 0.998955434414075 -0.0147008167348098 0.0432657606187295 0.0101204490876251 0.0054776398118515 0.978533829527246 0.206013446000097 -0.0267728482783758 -0.0453655763402085 -0.205561257191312 0.977592212543271 0.0682467573465509 0.000262441254861206 -8.90116856848985e-05 -6.46719713016172e-06 8.63618192340171e-07 -2.15285514783258e-05 -5.13425489173463e-05 -8.90116856848985e-05 0.000113492832618056 -3.85331058725748e-06 2.60254915039926e-06 2.86447492695381e-06 3.37491962847263e-05 -6.46719713016172e-06 -3.85331058725748e-06 1.70966911686348e-05 -1.10488781717614e-06 -7.45619395609368e-06 -3.8839551379983e-06 8.63618192340171e-07 2.60254915039926e-06 -1.10488781717614e-06 3.64902929519045e-05 1.0694993640122e-07 3.21698866377453e-06 -2.15285514783258e-05 2.86447492695381e-06 -7.45619395609368e-06 1.0694993640122e-07 2.43558382159337e-05 4.54410977155909e-06 -5.13425489173463e-05 3.37491962847263e-05 -3.8839551379983e-06 3.21698866377453e-06 4.54410977155909e-06 9.20548912861221e-05 1311 1337 0 0 0 1320 1375 0 0 15 0 0 0 0 0 0 0 0 1022 0 0 3 0 0 2348 +1263 1315 0.998711539343962 -0.0145827666497216 0.0486066260714826 0.00997228180923425 0.00395495333972518 0.97727541994042 0.211936575239754 -0.0307981553760438 -0.0505926825271576 -0.211471266362868 0.976073913173378 0.0613525675284342 0.000164239409347908 -2.91461308403661e-06 -1.07270957793212e-05 1.99826893844011e-05 -1.43321599060159e-05 -3.64891233244268e-05 -2.91461308403661e-06 0.000101268360818169 -5.35639429407915e-06 1.39263205255466e-05 -4.87928177102721e-06 -1.83627474613591e-06 -1.07270957793212e-05 -5.35639429407915e-06 1.50757916321546e-05 -1.93134225308847e-06 -6.64778476679364e-06 -1.16680572267545e-06 1.99826893844011e-05 1.39263205255466e-05 -1.93134225308847e-06 3.654341539189e-05 -5.36021988264008e-06 -2.84031581175412e-06 -1.43321599060159e-05 -4.87928177102721e-06 -6.64778476679364e-06 -5.36021988264008e-06 2.25418315925433e-05 1.24261439026334e-05 -3.64891233244268e-05 -1.83627474613591e-06 -1.16680572267545e-06 -2.84031581175412e-06 1.24261439026334e-05 0.000122722420376481 1217 1245 0 0 0 1228 1281 0 0 16 0 0 0 0 0 0 0 0 1008 0 0 3 0 0 2532 +1263 1293 0.999253627035849 -0.0158466981919934 0.0352288377911154 0.00896807351545999 0.00798786601463046 0.977037085294192 0.21291953399433 -0.0271448082968403 -0.0377939525881213 -0.212479213374491 0.976434432530687 0.0764055812748935 0.000128987032814667 -4.38083220168068e-05 -6.2516529261696e-07 -6.55884569886916e-06 -5.47989499367273e-06 4.29160906808822e-06 -4.38083220168068e-05 8.55212696814741e-05 8.65323005811037e-07 7.64701180323814e-06 4.3365846594043e-06 1.9170506285054e-05 -6.2516529261696e-07 8.65323005811037e-07 1.10401747695607e-05 6.40082970316603e-07 -6.51656272636173e-06 3.88803699520251e-07 -6.55884569886916e-06 7.64701180323814e-06 6.40082970316603e-07 2.27139804607916e-05 2.98447016114318e-06 -7.20981850607796e-07 -5.47989499367273e-06 4.3365846594043e-06 -6.51656272636173e-06 2.98447016114318e-06 1.8917921547053e-05 4.37910710935076e-06 4.29160906808822e-06 1.9170506285054e-05 3.88803699520251e-07 -7.20981850607796e-07 4.37910710935076e-06 7.59892985837052e-05 1311 1339 0 0 0 1320 1375 0 0 18 0 0 0 0 0 0 0 0 1021 0 0 2 0 0 2509 +1263 1312 0.999102558920496 -0.0147281074140593 0.0397134688804318 0.00874466528872542 0.00619788108125452 0.978341983072402 0.206902272650791 -0.0294215096182245 -0.0419006327949796 -0.206470450694426 0.977555261845294 0.0649908627463812 0.000379416886794007 -0.000170359239871893 -2.59962539012937e-06 1.21984898673141e-05 -1.77242925065437e-05 -3.40848751183555e-05 -0.000170359239871893 0.000176192321005551 -1.10484249144985e-06 2.80993679093941e-06 5.59736562162756e-07 5.27142923330194e-05 -2.59962539012937e-06 -1.10484249144985e-06 1.71024555498392e-05 -3.55272637191655e-06 -6.02082342192056e-06 -3.78645559197345e-06 1.21984898673141e-05 2.80993679093941e-06 -3.55272637191655e-06 2.97549206043703e-05 1.44113337303886e-06 4.14303849196577e-06 -1.77242925065437e-05 5.59736562162756e-07 -6.02082342192056e-06 1.44113337303886e-06 2.30531114007366e-05 -9.07646808798265e-07 -3.40848751183555e-05 5.27142923330194e-05 -3.78645559197345e-06 4.14303849196577e-06 -9.07646808798265e-07 8.69482285531785e-05 1390 1425 0 0 5 1404 1472 0 0 20 0 0 0 0 0 0 0 0 1007 0 0 6 0 0 2442 +1263 1308 0.99928560519126 -0.0157646788552119 0.0343475495214626 0.0111223131739334 0.0086936068559924 0.980358112737917 0.197033986887501 -0.0295652059227015 -0.0367790763528767 -0.196594622738117 0.979794801911649 0.0673376779074984 0.000238273770067059 -8.46954711884486e-05 -6.40008696316099e-06 1.03022933122009e-05 -1.39190288995839e-05 5.10708137886189e-06 -8.46954711884486e-05 0.000126420866043719 6.85295652921076e-07 9.91326806590742e-06 2.8238901850818e-06 3.05836965249881e-05 -6.40008696316099e-06 6.85295652921076e-07 1.42360971941079e-05 -2.70479434414969e-06 -7.93704073991639e-06 -2.71388133032172e-06 1.03022933122009e-05 9.91326806590742e-06 -2.70479434414969e-06 3.85534096912861e-05 7.03226319493498e-06 -5.62493875546094e-07 -1.39190288995839e-05 2.8238901850818e-06 -7.93704073991639e-06 7.03226319493498e-06 2.53368596163359e-05 4.45598415005918e-07 5.10708137886189e-06 3.05836965249881e-05 -2.71388133032172e-06 -5.62493875546094e-07 4.45598415005918e-07 9.23301661909279e-05 1229 1257 0 0 0 1235 1292 0 0 17 0 0 0 0 0 0 0 0 1011 0 0 1 0 0 2592 +1263 1309 0.998924257553536 -0.0166160226648361 0.0432924411637663 0.00939079103712254 0.0071748598300873 0.977736820303661 0.209712259081118 -0.0296681160876995 -0.04581319741663 -0.209176045505428 0.976804244938143 0.0638810709258698 0.000203949621917359 -3.59537247435455e-05 -1.03642827776161e-05 1.53645746015807e-05 -1.22117563577401e-05 -1.39504196213177e-05 -3.59537247435455e-05 8.76387444297239e-05 -5.84265164567242e-07 5.64895278016723e-06 1.94194172727335e-06 2.32532576270784e-05 -1.03642827776161e-05 -5.84265164567242e-07 1.69180648756551e-05 -1.16665118218643e-06 -9.30609075673002e-06 1.11227669032024e-06 1.53645746015807e-05 5.64895278016723e-06 -1.16665118218643e-06 2.96768862305185e-05 -3.37162123818387e-06 -4.9115567511166e-06 -1.22117563577401e-05 1.94194172727335e-06 -9.30609075673002e-06 -3.37162123818387e-06 2.1933696914718e-05 -2.33889196510662e-06 -1.39504196213177e-05 2.32532576270784e-05 1.11227669032024e-06 -4.9115567511166e-06 -2.33889196510662e-06 0.000130675216852581 1397 1435 0 0 7 1409 1476 0 0 23 0 0 0 0 0 0 0 0 912 0 0 5 0 0 2349 +1263 1316 0.99869400263896 -0.0143501544089771 0.049034295767468 0.0124736010417498 0.00304408698450449 0.974752580787697 0.223266969751807 -0.0253817723905715 -0.0510002218368096 -0.222826119016964 0.973523239607784 0.070784720846391 0.000209386140116101 -6.30939960288399e-05 -2.18060263352806e-06 5.18059524951271e-06 -4.88965652209075e-06 -5.46006999386862e-05 -6.30939960288399e-05 0.000145985362250143 -2.86992600694196e-06 1.19594261301145e-05 -1.80583049614407e-06 2.56964715641833e-05 -2.18060263352806e-06 -2.86992600694196e-06 1.55070896308824e-05 9.95364683852383e-07 -7.06007734172913e-06 -3.55143513259762e-06 5.18059524951271e-06 1.19594261301145e-05 9.95364683852383e-07 3.71262234437628e-05 -4.35821196710945e-06 -2.58942437756886e-06 -4.88965652209075e-06 -1.80583049614407e-06 -7.06007734172913e-06 -4.35821196710945e-06 2.07458227895481e-05 -2.33635742054463e-06 -5.46006999386862e-05 2.56964715641833e-05 -3.55143513259762e-06 -2.58942437756886e-06 -2.33635742054463e-06 0.000121018754531136 1229 1261 0 0 0 1236 1292 0 0 26 0 0 0 0 0 0 0 0 1000 0 0 3 0 0 2559 +1263 1318 0.999065666550125 -0.014215464758157 0.04081316555309 0.00959996928884128 0.00534072269321426 0.977727056140377 0.209812488599192 -0.0275239838019737 -0.0428867182454956 -0.209398481973441 0.976889453902206 0.0807413098400364 0.000184676731376822 -8.25939337097092e-05 -4.04433937613458e-06 -6.78993291816435e-07 -1.70117201783806e-05 -9.44534782830947e-06 -8.25939337097092e-05 8.69439886986356e-05 2.7161899505743e-06 -4.42699201380805e-06 9.28370276699167e-06 2.08308275569075e-05 -4.04433937613458e-06 2.7161899505743e-06 1.6272323891849e-05 -3.51957066663618e-06 -8.62656709937904e-06 -3.97337268891717e-09 -6.78993291816435e-07 -4.42699201380805e-06 -3.51957066663618e-06 3.7980982371451e-05 -1.52702942601094e-06 5.73889910329636e-06 -1.70117201783806e-05 9.28370276699167e-06 -8.62656709937904e-06 -1.52702942601094e-06 2.33603938075263e-05 -3.12378553954858e-06 -9.44534782830947e-06 2.08308275569075e-05 -3.97337268891717e-09 5.73889910329636e-06 -3.12378553954858e-06 7.34919489553473e-05 1403 1434 0 0 3 1419 1482 0 0 23 0 0 0 0 0 0 0 0 1022 0 0 7 0 0 2525 +1263 1296 0.999273318462303 -0.0161466932429763 0.0345270807722568 0.00542753631342599 0.00860597212367956 0.97802602799317 0.208305126705295 -0.0312177076477736 -0.0371318226477394 -0.207856616120872 0.977454272527179 0.0633353574961333 0.00015769496882046 -6.90692914280529e-05 3.98505619951063e-07 1.96753726316801e-06 -2.16704518548485e-07 -3.38362557615525e-05 -6.90692914280529e-05 9.08321714907142e-05 -1.71741725747081e-06 6.45041671112665e-06 4.37993448585056e-06 4.75731131653619e-05 3.98505619951063e-07 -1.71741725747081e-06 1.0497662395437e-05 1.7302470410762e-06 -7.20521045225533e-06 -2.00718343451607e-06 1.96753726316801e-06 6.45041671112665e-06 1.7302470410762e-06 2.77038687046917e-05 6.29077412068498e-06 2.55001239747854e-06 -2.16704518548485e-07 4.37993448585056e-06 -7.20521045225533e-06 6.29077412068498e-06 1.88416453099093e-05 2.44313290415659e-06 -3.38362557615525e-05 4.75731131653619e-05 -2.00718343451607e-06 2.55001239747854e-06 2.44313290415659e-06 6.8421375584641e-05 1309 1332 0 0 0 1321 1375 0 0 12 0 0 0 0 0 0 0 0 985 0 0 4 0 0 2527 +1263 1307 0.999171958425888 -0.0160873594423103 0.0373710363991924 0.00909716612229495 0.00806604957033874 0.978601424659081 0.205606883395345 -0.0268979007963955 -0.0398790212982301 -0.205135195715879 0.977920863433695 0.0667017113015023 0.000190110341831122 -4.60009454013022e-05 -8.66170680740122e-06 1.56502749096008e-05 -9.63633994223015e-06 -4.68922485112602e-05 -4.60009454013022e-05 7.2752263368326e-05 -3.48264801760425e-06 2.75684734370815e-06 -2.53305834160413e-06 5.23203377902529e-05 -8.66170680740122e-06 -3.48264801760425e-06 1.46059936884873e-05 -3.15969918319589e-06 -6.74944296500386e-06 1.18729938299693e-07 1.56502749096008e-05 2.75684734370815e-06 -3.15969918319589e-06 3.39382401656038e-05 2.65033482798482e-06 -2.47254609671232e-06 -9.63633994223015e-06 -2.53305834160413e-06 -6.74944296500386e-06 2.65033482798482e-06 2.54386351939441e-05 1.5513248201259e-06 -4.68922485112602e-05 5.23203377902529e-05 1.18729938299693e-07 -2.47254609671232e-06 1.5513248201259e-06 7.31020276745659e-05 1405 1438 0 0 3 1418 1482 0 0 23 0 0 0 0 0 0 0 0 1014 0 0 5 0 0 2400 +1263 1297 0.999312467390823 -0.0157080796014169 0.0335834595076329 0.006363518617994 0.0081376706200325 0.976653319079865 0.214667353473143 -0.0262533952095228 -0.0361714090704956 -0.21424647153575 0.976109665253006 0.0732049592148331 0.000158202690441311 -4.583981255322e-05 3.04220739431213e-06 -5.55640278521546e-06 -8.65235493852887e-06 -2.0163728756288e-05 -4.583981255322e-05 8.52134884536334e-05 -8.89528189586058e-07 -1.99098382843245e-06 -4.46939815964352e-06 5.10006594470949e-05 3.04220739431213e-06 -8.89528189586058e-07 1.2274108379502e-05 -1.76097005208347e-06 -8.54340068912437e-06 9.9846099803346e-07 -5.55640278521546e-06 -1.99098382843245e-06 -1.76097005208347e-06 3.12628063338737e-05 9.45599721302528e-06 -6.59514830265293e-06 -8.65235493852887e-06 -4.46939815964352e-06 -8.54340068912437e-06 9.45599721302528e-06 2.44750875005481e-05 -3.12424605214069e-06 -2.0163728756288e-05 5.10006594470949e-05 9.9846099803346e-07 -6.59514830265293e-06 -3.12424605214069e-06 8.41061118059813e-05 1404 1437 0 0 4 1418 1482 0 0 23 0 0 0 0 0 0 0 0 1012 0 0 6 0 0 2404 +1263 1306 0.999145552188352 -0.0150558887917236 0.0384900734595941 0.00972252663667656 0.00668580353333742 0.977900323777705 0.208964726177824 -0.0279107785856675 -0.040785604977091 -0.208528839655695 0.977165419700524 0.0688501257225881 0.000225023801147555 -0.000105500720942046 6.83953720129143e-07 -1.13581381155573e-05 -1.77205579224e-05 -4.18862190072241e-05 -0.000105500720942046 0.000107772301244963 3.70763041848566e-06 7.23260258629242e-07 2.95823398579834e-06 6.6271890317399e-05 6.83953720129143e-07 3.70763041848566e-06 1.64091788974134e-05 -4.13553247943659e-06 -7.99197226699273e-06 4.48549764844193e-06 -1.13581381155573e-05 7.23260258629242e-07 -4.13553247943659e-06 3.19437188620702e-05 4.28894434737936e-06 1.50041945678616e-07 -1.77205579224e-05 2.95823398579834e-06 -7.99197226699273e-06 4.28894434737936e-06 2.44914119857569e-05 3.28747788642898e-06 -4.18862190072241e-05 6.6271890317399e-05 4.48549764844193e-06 1.50041945678616e-07 3.28747788642898e-06 8.1634275872877e-05 1397 1435 0 0 6 1408 1475 0 0 23 0 0 0 0 0 0 0 0 1008 0 0 5 0 0 2591 +1263 1313 0.999237066534262 -0.015611722610051 0.0357988684339314 0.00840013071511536 0.00809611702021549 0.979520563812188 0.201181306184865 -0.0281351853065044 -0.0382065145387286 -0.200737986405664 0.978899649126815 0.0722678886364948 0.000233079382286468 -0.000104611049913445 1.80792933882721e-06 -1.17435867298448e-05 -2.28126587764884e-05 -3.58846225957876e-05 -0.000104611049913445 8.86115586617411e-05 1.15191167417494e-06 -2.37157487355856e-07 9.32294853570442e-06 4.49310385586147e-05 1.80792933882721e-06 1.15191167417494e-06 1.54959132078785e-05 -5.04344919866036e-06 -5.29991349470563e-06 1.36731150036008e-06 -1.17435867298448e-05 -2.37157487355856e-07 -5.04344919866036e-06 3.76383784509332e-05 8.21605925886554e-06 -2.6851510351718e-06 -2.28126587764884e-05 9.32294853570442e-06 -5.29991349470563e-06 8.21605925886554e-06 2.71050522995985e-05 1.07996759525994e-06 -3.58846225957876e-05 4.49310385586147e-05 1.36731150036008e-06 -2.6851510351718e-06 1.07996759525994e-06 7.35422058131806e-05 1396 1431 0 0 5 1407 1475 0 0 21 0 0 0 0 0 0 0 0 1019 0 0 5 0 0 2533 +1263 1317 0.998693581438095 -0.0140677559686866 0.0491246235238225 0.0119049760968029 0.00335876521785049 0.97735065649853 0.211599652499959 -0.0323398930369509 -0.0509887153256794 -0.211158216709408 0.976121077748831 0.0628976521261821 0.000241974610040561 -8.85726232950289e-05 -6.98720569270364e-06 1.17323637383366e-05 -2.94970781164511e-06 6.88718808259831e-06 -8.85726232950289e-05 9.44368466208187e-05 2.09082818224524e-06 -3.53922831778158e-06 -7.24321111478147e-07 2.69504318212502e-05 -6.98720569270364e-06 2.09082818224524e-06 1.64126141667088e-05 7.1723108829349e-07 -7.02158671540036e-06 -3.14102602462987e-06 1.17323637383366e-05 -3.53922831778158e-06 7.1723108829349e-07 3.26996178237152e-05 -3.05239018901233e-06 3.98082204830442e-06 -2.94970781164511e-06 -7.24321111478147e-07 -7.02158671540036e-06 -3.05239018901233e-06 2.42268888332168e-05 -3.66479544476751e-06 6.88718808259831e-06 2.69504318212502e-05 -3.14102602462987e-06 3.98082204830442e-06 -3.66479544476751e-06 8.17395388908246e-05 1303 1325 0 0 0 1316 1365 0 0 12 0 0 0 0 0 0 0 0 917 0 0 6 0 0 2609 +1263 1304 0.999449636539474 -0.0153658846867927 0.0293992110252248 0.00747552191539798 0.00906200216521105 0.979007783968833 0.203621312846156 -0.0278790717297946 -0.0319108780492048 -0.203242831401815 0.978608219537268 0.0700637272594676 0.000105457570265214 -5.69138378512835e-05 -6.49072444260437e-06 3.01723627356538e-06 4.15251122765994e-06 -2.34118038698567e-05 -5.69138378512835e-05 7.72748405515319e-05 5.76255335395279e-06 -1.80704718364877e-06 -1.51005399700693e-06 4.19067053808352e-05 -6.49072444260437e-06 5.76255335395279e-06 1.77229335227792e-05 -6.67074461721186e-06 -6.08902932544945e-06 3.3385832064787e-06 3.01723627356538e-06 -1.80704718364877e-06 -6.67074461721186e-06 3.26277342808255e-05 2.47283534118206e-06 -2.57335637066551e-06 4.15251122765994e-06 -1.51005399700693e-06 -6.08902932544945e-06 2.47283534118206e-06 2.27059781409202e-05 -2.16274906281254e-06 -2.34118038698567e-05 4.19067053808352e-05 3.3385832064787e-06 -2.57335637066551e-06 -2.16274906281254e-06 7.52397544775561e-05 1397 1432 0 0 6 1409 1475 0 0 21 0 0 0 0 0 0 0 0 1010 0 0 4 0 0 2434 +1264 1290 0.999699428089114 -0.0225975141372659 0.00950819820550043 0.00787308691453399 0.0211821652088463 0.991405435059337 0.129099106162169 -0.0228675862588319 -0.0123437982551626 -0.128858898371909 0.991586110711023 0.0352993927773429 0.000165174933829218 -4.93786007502226e-05 4.27577264908439e-07 5.60035831546446e-06 -4.30804365229389e-06 -1.42645354721099e-05 -4.93786007502226e-05 8.41763466029204e-05 -9.4981683554211e-07 3.18544446400529e-06 -2.84537531347129e-07 4.57900946300774e-05 4.27577264908439e-07 -9.4981683554211e-07 9.89644976512349e-06 5.94501543062059e-07 -6.26064997037744e-06 -1.35387457829792e-06 5.60035831546446e-06 3.18544446400529e-06 5.94501543062059e-07 2.76933073025779e-05 3.39752540133426e-06 3.12805594984573e-06 -4.30804365229389e-06 -2.84537531347129e-07 -6.26064997037744e-06 3.39752540133426e-06 1.8586677512848e-05 1.74806277093204e-06 -1.42645354721099e-05 4.57900946300774e-05 -1.35387457829792e-06 3.12805594984573e-06 1.74806277093204e-06 6.39741900893246e-05 1379 1412 0 0 0 1380 1455 0 0 16 0 0 0 0 0 0 0 0 871 0 0 0 0 0 2986 +1264 1268 0.999746054898607 -0.0129319628441201 0.0184550820011709 0.00478219242498191 0.0124249516177944 0.999549302490037 0.027327869821402 -0.0118641004708339 -0.0188001673388061 -0.0270916265417624 0.99945615085373 0.00617359341279012 8.35619862904563e-05 -1.09181169860245e-05 -2.80687754640883e-06 4.8055637410616e-06 -9.44616702026565e-06 -1.64117885622392e-05 -1.09181169860245e-05 9.44150081598907e-05 -1.15330628024192e-05 1.77135664475444e-05 2.74374083249526e-06 2.58184283056488e-05 -2.80687754640883e-06 -1.15330628024192e-05 1.22632077347888e-05 -8.98927363026607e-07 -6.44203944963656e-06 -4.32243058375037e-06 4.8055637410616e-06 1.77135664475444e-05 -8.98927363026607e-07 2.41193468647556e-05 -6.52183301672239e-06 -1.59025490597658e-06 -9.44616702026565e-06 2.74374083249526e-06 -6.44203944963656e-06 -6.52183301672239e-06 1.8564413416308e-05 1.95720377252347e-05 -1.64117885622392e-05 2.58184283056488e-05 -4.32243058375037e-06 -1.59025490597658e-06 1.95720377252347e-05 0.000115544044021323 1500 1529 0 0 0 1500 1587 0 0 2 0 0 0 0 0 0 0 0 751 0 0 0 0 0 3339 +1264 1266 0.999467451600312 -0.0277117732860307 0.017229939434655 0.003107829093853 0.0276603872142409 0.999612212658032 0.00321360919704327 -0.00710859903682352 -0.0173123126917377 -0.00273531099816769 0.999846389153357 -0.000476866782983026 9.37401529693764e-05 3.26122084408152e-05 -6.94058201240754e-06 1.32199008945997e-05 -7.74145469554517e-06 9.67370707312517e-06 3.26122084408152e-05 7.66510836682315e-05 -1.13506960732726e-05 1.78175019928269e-05 -8.33882493783405e-06 9.40053223949257e-06 -6.94058201240754e-06 -1.13506960732726e-05 1.19055373274125e-05 -1.16234769109612e-07 -7.11118505236675e-06 -2.69800448685511e-06 1.32199008945997e-05 1.78175019928269e-05 -1.16234769109612e-07 3.05937123516427e-05 3.06877228044307e-07 9.29170874714845e-06 -7.74145469554517e-06 -8.33882493783405e-06 -7.11118505236675e-06 3.06877228044307e-07 2.26687929481761e-05 1.84121637414022e-05 9.67370707312517e-06 9.40053223949257e-06 -2.69800448685511e-06 9.29170874714845e-06 1.84121637414022e-05 9.56412343313318e-05 1476 1542 0 0 0 1476 1560 0 0 30 0 0 0 0 0 0 0 0 641 0 0 0 0 0 3355 +1264 1292 0.998829001265781 -0.0230476144677044 0.042537438777517 0.00056209853268786 0.0148394240037729 0.982803879579665 0.184055224806023 -0.0340417789524661 -0.0460479937200221 -0.183208465280695 0.981995030804053 0.0463249935372535 0.000216957472431655 -7.0303342735294e-05 3.41674623921006e-06 -1.10136218534593e-05 -2.27247002229508e-05 -2.34588174986477e-05 -7.0303342735294e-05 0.000151222546374392 9.21436635440286e-06 4.38833285766381e-06 1.01902186897241e-08 1.61342860893625e-06 3.41674623921006e-06 9.21436635440286e-06 1.20068069846254e-05 -1.85575441604074e-06 -8.04518810506782e-06 1.87681638130644e-06 -1.10136218534593e-05 4.38833285766381e-06 -1.85575441604074e-06 2.87544536897791e-05 7.58137680338963e-06 -6.23872586617535e-06 -2.27247002229508e-05 1.01902186897241e-08 -8.04518810506782e-06 7.58137680338963e-06 2.29305141520225e-05 1.99916342746772e-06 -2.34588174986477e-05 1.61342860893625e-06 1.87681638130644e-06 -6.23872586617535e-06 1.99916342746772e-06 0.000121016717760684 1291 1310 0 0 0 1304 1356 0 0 19 0 0 0 0 0 0 0 0 970 0 0 5 0 0 2694 +1263 1305 0.998833128045587 -0.0160024264126325 0.0455664862324917 0.00739988288499928 0.00625842160764094 0.978441238746381 0.206430556070144 -0.0314430685213606 -0.0478875190174704 -0.20590450376171 0.977399673037082 0.0606573687783931 0.000241325513739861 -0.000111413029461904 -8.35206963512287e-06 -1.76855844108778e-06 -1.28775742054016e-05 -4.76333676329779e-05 -0.000111413029461904 0.000133849280867469 3.74222009773225e-06 5.69921830091405e-06 2.03838835002189e-06 3.71325074625372e-05 -8.35206963512287e-06 3.74222009773225e-06 1.77831634874409e-05 -5.92777891680075e-06 -8.36263948727932e-06 -1.99590051322617e-06 -1.76855844108778e-06 5.69921830091405e-06 -5.92777891680075e-06 3.86262702521927e-05 9.62635830098022e-06 -9.24678923941827e-07 -1.28775742054016e-05 2.03838835002189e-06 -8.36263948727932e-06 9.62635830098022e-06 2.88401467677162e-05 2.01094377031754e-06 -4.76333676329779e-05 3.71325074625372e-05 -1.99590051322617e-06 -9.24678923941827e-07 2.01094377031754e-06 0.000125132440760496 1219 1244 0 0 0 1229 1284 0 0 15 0 0 0 0 0 0 0 0 920 0 0 3 0 0 2438 +1264 1294 0.998256763056334 -0.0229827703824006 0.0543620021507732 -0.000537026174105625 0.011608496276572 0.97953246793926 0.200951205686902 -0.0319527530991964 -0.0578677615472348 -0.19996983902172 0.978091706158037 0.0409380758306005 0.00014156965542232 -1.67194437828274e-05 5.03020392442769e-06 -5.8145190365021e-06 -1.14721242529211e-05 -1.59358770978758e-05 -1.67194437828274e-05 6.35525724570953e-05 5.86420116406096e-06 -3.53979984950337e-06 -5.26218633581644e-06 3.29995691554194e-05 5.03020392442769e-06 5.86420116406096e-06 1.31105077175078e-05 -2.17666292505697e-06 -8.65917499963909e-06 1.61147485744638e-06 -5.8145190365021e-06 -3.53979984950337e-06 -2.17666292505697e-06 2.82357699236654e-05 5.3083968941812e-06 2.29259573527493e-06 -1.14721242529211e-05 -5.26218633581644e-06 -8.65917499963909e-06 5.3083968941812e-06 2.17228475397165e-05 -4.00363173732657e-07 -1.59358770978758e-05 3.29995691554194e-05 1.61147485744638e-06 2.29259573527493e-06 -4.00363173732657e-07 7.07284885410682e-05 1394 1420 0 0 0 1411 1478 0 0 19 0 0 0 0 0 0 0 0 1005 0 0 6 0 0 2367 +1264 1291 0.999359634658452 -0.022983703387828 0.0274238945794625 0.0020092567396667 0.0185351515971293 0.988102462054049 0.152676038191975 -0.0310106269264006 -0.0306066785293106 -0.152069963705217 0.987895721910009 0.0308138375215012 0.000218699464307067 -5.87070340551645e-05 -1.29434427011407e-06 8.7245292181789e-06 -7.94969649263618e-06 -3.29673556825657e-05 -5.87070340551645e-05 9.08068936760871e-05 -2.07452585759044e-06 3.3965533056366e-06 6.20463439691294e-06 5.33966065198632e-05 -1.29434427011407e-06 -2.07452585759044e-06 1.0350900985862e-05 -2.389221243314e-08 -7.44028010389999e-06 -2.7681230731353e-06 8.7245292181789e-06 3.3965533056366e-06 -2.389221243314e-08 2.72444511653271e-05 4.99872508638141e-06 4.26737503764377e-06 -7.94969649263618e-06 6.20463439691294e-06 -7.44028010389999e-06 4.99872508638141e-06 1.97689179402869e-05 9.36906585099903e-06 -3.29673556825657e-05 5.33966065198632e-05 -2.7681230731353e-06 4.26737503764377e-06 9.36906585099903e-06 9.06792450848531e-05 1274 1297 0 0 0 1281 1356 0 0 16 0 0 0 0 0 0 0 0 877 0 0 1 0 0 2753 +1264 1293 0.998482607095427 -0.0225265350144466 0.0502497616726791 0.00110493556102158 0.0117814604301378 0.978760614128352 0.20466767556511 -0.033950243008713 -0.0537929411544975 -0.203765098707641 0.977540845198099 0.0484148093607088 0.000204934013789632 -8.57749789673714e-05 6.99657559439871e-07 -4.85199395260328e-06 -6.63202847362049e-06 -5.79984628312255e-05 -8.57749789673714e-05 0.00010605394779644 1.0397976147963e-06 2.87760128352991e-06 5.06525876355944e-07 7.75578487119524e-05 6.99657559439871e-07 1.0397976147963e-06 1.2035281972293e-05 -1.89955272569474e-06 -6.54726081489569e-06 -2.34139422209194e-06 -4.85199395260328e-06 2.87760128352991e-06 -1.89955272569474e-06 2.91369630875609e-05 4.58809377033999e-06 5.89943094909786e-06 -6.63202847362049e-06 5.06525876355944e-07 -6.54726081489569e-06 4.58809377033999e-06 1.96014549261944e-05 -4.4828685856453e-07 -5.79984628312255e-05 7.75578487119524e-05 -2.34139422209194e-06 5.89943094909786e-06 -4.4828685856453e-07 0.000115578052764867 1310 1331 0 0 0 1323 1374 0 0 12 0 0 0 0 0 0 0 0 1020 0 0 6 0 0 2539 +1264 1267 0.999778935373452 -0.0186465814618325 0.00971521401281645 0.00513071221498328 0.0183234287277256 0.99930854900414 0.0323523700352779 -0.00676722593706694 -0.0103117575217585 -0.0321672020391396 0.99942930653938 0.0280772828836166 0.000145541976844958 1.47071490651231e-05 -5.45798601048046e-06 1.26915025396749e-05 -1.6507395693132e-05 -6.56176718982362e-06 1.47071490651231e-05 9.22546495626061e-05 -1.48750873303643e-05 2.23684162655631e-05 1.8304833559424e-07 4.21366849212375e-05 -5.45798601048046e-06 -1.48750873303643e-05 1.26087422868232e-05 -1.18150709935426e-06 -7.42577768964763e-06 -6.9021817654085e-06 1.26915025396749e-05 2.23684162655631e-05 -1.18150709935426e-06 2.93496643139651e-05 -5.19334681391645e-07 5.89319325831452e-06 -1.6507395693132e-05 1.8304833559424e-07 -7.42577768964763e-06 -5.19334681391645e-07 2.16702756892197e-05 1.11227837962795e-05 -6.56176718982362e-06 4.21366849212375e-05 -6.9021817654085e-06 5.89319325831452e-06 1.11227837962795e-05 8.13866952754568e-05 1555 1599 0 0 0 1555 1640 0 0 13 0 0 0 0 0 0 0 0 754 0 0 0 0 0 3336 +1264 1308 0.998216804895719 -0.0226394069898023 0.0552328495999594 0.00174392656432048 0.0107437591487301 0.978317460919192 0.206832099297905 -0.0324436655211627 -0.0587178172545244 -0.205869868877829 0.976816162348418 0.0457085659944702 0.000228010623377477 -8.50540956353436e-05 9.63714113523209e-07 -4.36113549359477e-06 -1.44151381838313e-05 -2.97239759828653e-05 -8.50540956353436e-05 0.000100764203684597 -5.27422264774023e-06 1.2298239326289e-05 1.92625223639587e-06 5.48045140227623e-05 9.63714113523209e-07 -5.27422264774023e-06 1.59220968786491e-05 -4.07769804210257e-06 -4.98108894341221e-06 -2.73732414428127e-06 -4.36113549359477e-06 1.2298239326289e-05 -4.07769804210257e-06 3.79368518663174e-05 3.65281118887751e-06 6.42750658175219e-06 -1.44151381838313e-05 1.92625223639587e-06 -4.98108894341221e-06 3.65281118887751e-06 2.5314661682234e-05 -1.16837033920767e-06 -2.97239759828653e-05 5.48045140227623e-05 -2.73732414428127e-06 6.42750658175219e-06 -1.16837033920767e-06 8.64149141592989e-05 1226 1253 0 0 0 1237 1288 0 0 15 0 0 0 0 0 0 0 0 1007 0 0 5 0 0 2590 +1264 1315 0.997945063249654 -0.0216282295794997 0.060314761218954 0.00274722355453996 0.00864529736287403 0.978151622110182 0.207712934110342 -0.0332934621423962 -0.0634894445490781 -0.206764658122408 0.976328564870645 0.0442076681399119 0.00026202276329275 -9.56180797862116e-05 -5.29981107321073e-06 8.31876491599548e-08 -6.42941400500216e-06 -9.2624969602199e-05 -9.56180797862116e-05 8.87837547536104e-05 -8.63074405242097e-07 5.19755699270656e-06 -8.42166768815326e-08 5.03250469020945e-05 -5.29981107321073e-06 -8.63074405242097e-07 1.42096653385715e-05 -3.9923241489494e-07 -8.09018194865794e-06 2.88913585372193e-06 8.31876491599548e-08 5.19755699270656e-06 -3.9923241489494e-07 3.70759557465712e-05 9.14580649127889e-07 -1.4991576378274e-06 -6.42941400500216e-06 -8.42166768815326e-08 -8.09018194865794e-06 9.14580649127889e-07 2.32568652264675e-05 -2.37399703123505e-06 -9.2624969602199e-05 5.03250469020945e-05 2.88913585372193e-06 -1.4991576378274e-06 -2.37399703123505e-06 0.000112083668153145 1216 1241 0 0 0 1228 1280 0 0 15 0 0 0 0 0 0 0 0 1011 0 0 6 0 0 2540 +1264 1309 0.998609698792275 -0.0232357146478323 0.0473156532535189 -0.000679757129008114 0.0134443332918763 0.98018971205617 0.197604094799625 -0.0325264753720039 -0.0509697888983236 -0.19669323817571 0.979139341807699 0.0553295961885199 0.000208548350316242 -5.27581259787772e-05 -3.37837237920928e-06 7.78490275900918e-06 -1.90906789510742e-05 -1.63406070009627e-05 -5.27581259787772e-05 8.59733811031401e-05 5.96257860250254e-07 6.37075547347697e-06 4.6486410982071e-06 3.36335541085838e-05 -3.37837237920928e-06 5.96257860250254e-07 1.74505591247983e-05 -3.58968548182723e-06 -8.69736855981189e-06 -2.16849046975527e-07 7.78490275900918e-06 6.37075547347697e-06 -3.58968548182723e-06 3.40799953635272e-05 2.78652807058666e-06 -8.34075108103348e-07 -1.90906789510742e-05 4.6486410982071e-06 -8.69736855981189e-06 2.78652807058666e-06 2.78445926330917e-05 -6.4461270273305e-06 -1.63406070009627e-05 3.36335541085838e-05 -2.16849046975527e-07 -8.34075108103348e-07 -6.4461270273305e-06 8.61300366532011e-05 1393 1419 0 0 0 1409 1473 0 0 17 0 0 0 0 0 0 0 0 908 0 0 6 0 0 2356 +1264 1314 0.997818932277328 -0.0220125756092263 0.0622320247459548 0.00219076472339548 0.00851230257815455 0.977797429486463 0.20937938674684 -0.0308514221452912 -0.0654592934101108 -0.208392978299925 0.975852164777809 0.0464864136194503 0.000311153672271996 -0.000107897326627464 -3.75089559344019e-06 1.75939219796632e-05 -5.42942798906325e-06 -7.401508100186e-05 -0.000107897326627464 0.000102784499306893 -4.36010409102582e-06 2.81411491231124e-06 5.53126195740798e-07 3.54497504687768e-05 -3.75089559344019e-06 -4.36010409102582e-06 1.47475028867417e-05 3.03501835182662e-07 -6.45341917726743e-06 -6.54996691110619e-07 1.75939219796632e-05 2.81411491231124e-06 3.03501835182662e-07 3.52186770162848e-05 -3.16533617770367e-06 2.01679912817554e-06 -5.42942798906325e-06 5.53126195740798e-07 -6.45341917726743e-06 -3.16533617770367e-06 2.20865521227936e-05 3.61177111767128e-06 -7.401508100186e-05 3.54497504687768e-05 -6.54996691110619e-07 2.01679912817554e-06 3.61177111767128e-06 9.91236951532957e-05 1308 1331 0 0 0 1323 1374 0 0 13 0 0 0 0 0 0 0 0 1013 0 0 7 0 0 2342 +1264 1316 0.997753239456048 -0.0210665557389507 0.0635977466916918 0.00496462545734215 0.00668159518784005 0.975832586979254 0.218417303515821 -0.0301417723155665 -0.0666620539790723 -0.217501637737912 0.973780883022776 0.050538314398326 0.000340035816905587 -0.000163645212128977 -3.15871906930295e-06 -6.80066384702191e-06 -6.18601340929496e-06 -2.66880913707759e-05 -0.000163645212128977 0.000180718565493168 1.18327789472738e-06 6.54156280325128e-06 -3.32936710275438e-06 1.89930959223508e-05 -3.15871906930295e-06 1.18327789472738e-06 1.33625610560659e-05 3.75645072958149e-07 -6.42998304953776e-06 -1.06469785633784e-07 -6.80066384702191e-06 6.54156280325128e-06 3.75645072958149e-07 2.98925816258758e-05 -3.77005956720844e-06 3.64099744308603e-07 -6.18601340929496e-06 -3.32936710275438e-06 -6.42998304953776e-06 -3.77005956720844e-06 2.14876278104251e-05 -2.28977802904774e-06 -2.66880913707759e-05 1.89930959223508e-05 -1.06469785633784e-07 3.64099744308603e-07 -2.28977802904774e-06 6.70985268063581e-05 1227 1255 0 0 0 1237 1289 0 0 19 0 0 0 0 0 0 0 0 1001 0 0 5 0 0 2568 +1264 1307 0.998333294185195 -0.0223919863556032 0.0531905317550767 0.00122963700745368 0.0113856842453767 0.979964882881843 0.198844649192884 -0.0325670821230609 -0.0565773798933984 -0.197907623060424 0.97858651779951 0.0432867242195051 0.000275521629488691 -0.000114350477278377 -9.33948252398799e-06 1.58061048801837e-05 -2.95515233188807e-06 -5.06878782809333e-05 -0.000114350477278377 0.000121288336674218 2.18073946693881e-06 3.55635055275092e-07 -5.84715159612979e-06 5.4329127305761e-05 -9.33948252398799e-06 2.18073946693881e-06 1.44304935612933e-05 -8.02933489885015e-07 -5.46606686843321e-06 1.23412046178943e-06 1.58061048801837e-05 3.55635055275092e-07 -8.02933489885015e-07 3.11601623193618e-05 8.51887021419189e-07 -2.7813592089809e-06 -2.95515233188807e-06 -5.84715159612979e-06 -5.46606686843321e-06 8.51887021419189e-07 2.43549144302571e-05 -5.96146946582678e-06 -5.06878782809333e-05 5.4329127305761e-05 1.23412046178943e-06 -2.7813592089809e-06 -5.96146946582678e-06 8.72166584320243e-05 1399 1423 0 0 0 1418 1476 0 0 15 0 0 0 0 0 0 0 0 1008 0 0 9 0 0 2415 +1264 1306 0.998560525164627 -0.0219806209018201 0.0489257589385678 0.000189124929468656 0.0118087898577975 0.979884895775391 0.199213813560572 -0.0332837253570432 -0.0523204555125312 -0.198349296283154 0.978733940659533 0.0500334986470753 0.00021845530932058 -9.21269887174175e-05 -1.03899444426461e-06 2.77731285429022e-06 -1.14232670791677e-05 6.27184604956849e-06 -9.21269887174175e-05 0.000105451218105228 3.05622074373328e-06 6.13906874444569e-06 5.92283891316618e-06 2.94562776111853e-05 -1.03899444426461e-06 3.05622074373328e-06 1.36504572321592e-05 -1.75768675997153e-06 -6.93401842124395e-06 1.73137269612074e-06 2.77731285429022e-06 6.13906874444569e-06 -1.75768675997153e-06 3.50312340959082e-05 8.18769182895119e-06 7.55679911600819e-06 -1.14232670791677e-05 5.92283891316618e-06 -6.93401842124395e-06 8.18769182895119e-06 2.60570117272425e-05 2.05464904525388e-06 6.27184604956849e-06 2.94562776111853e-05 1.73137269612074e-06 7.55679911600819e-06 2.05464904525388e-06 8.02922560277136e-05 1391 1415 0 0 0 1408 1472 0 0 18 0 0 0 0 0 0 0 0 1005 0 0 7 0 0 2605 +1264 1318 0.998520821250122 -0.0216524169040125 0.0498732630995434 0.00180450325769922 0.0113056061647064 0.979918245501915 0.199078917521916 -0.0331441360538353 -0.053182260192944 -0.198220596746817 0.978713564954582 0.0586729569983929 0.000274506835649414 -0.000114075067568047 3.75189681369022e-06 -2.32920206207787e-05 -2.04838321689432e-05 -2.95615110268602e-05 -0.000114075067568047 0.000103135371154162 4.06100547148939e-07 6.66665604805136e-06 4.31889933707957e-06 4.70898355268959e-05 3.75189681369022e-06 4.06100547148939e-07 1.44466081360705e-05 -1.38946250963665e-06 -8.52041879225024e-06 4.06711493929249e-07 -2.32920206207787e-05 6.66665604805136e-06 -1.38946250963665e-06 3.30762564660133e-05 2.5870909170017e-07 5.23677748712209e-06 -2.04838321689432e-05 4.31889933707957e-06 -8.52041879225024e-06 2.5870909170017e-07 2.38483419360781e-05 -4.17669514994093e-06 -2.95615110268602e-05 4.70898355268959e-05 4.06711493929249e-07 5.23677748712209e-06 -4.17669514994093e-06 8.29424336012841e-05 1400 1424 0 0 0 1418 1478 0 0 16 0 0 0 0 0 0 0 0 1020 0 0 7 0 0 2547 +1264 1312 0.998448705794287 -0.0223148337323411 0.0510120583118391 0.000548204309850586 0.011024749309275 0.977269509883026 0.211713863399775 -0.02806896557346 -0.0545768888851329 -0.210823037755575 0.975999492802702 0.0518585415006849 0.000859007829296491 -0.000504719897111762 1.97595914877155e-07 -9.16319047752637e-06 -1.4052312847808e-05 -0.000134090154960136 -0.000504719897111762 0.000382438115650238 -2.45061599018665e-06 6.15629168539357e-06 2.09680073703377e-06 0.000128797430373683 1.97595914877155e-07 -2.45061599018665e-06 1.62034782076058e-05 -1.5714378203513e-06 -5.26587970846656e-06 1.42675577244114e-06 -9.16319047752637e-06 6.15629168539357e-06 -1.5714378203513e-06 3.14964025896267e-05 3.88288372957853e-06 -2.81210668800718e-06 -1.4052312847808e-05 2.09680073703377e-06 -5.26587970846656e-06 3.88288372957853e-06 2.48619447016778e-05 -7.95648903421041e-07 -0.000134090154960136 0.000128797430373683 1.42675577244114e-06 -2.81210668800718e-06 -7.95648903421041e-07 0.000112244199607693 1388 1418 0 0 0 1404 1469 0 0 22 0 0 0 0 0 0 0 0 1002 0 0 8 0 0 2411 +1264 1295 0.998102302731176 -0.0231805160329203 0.0570478479801875 -0.00339017545661508 0.0113822793539847 0.979926281847981 0.199034986523223 -0.0376883518420144 -0.0605164192548677 -0.198007943830643 0.978330525528326 0.0370697284709664 0.00018431343580883 -4.19156493657984e-05 3.90800167215162e-06 -5.44904089424251e-06 -4.01848424143955e-06 -8.50566473896007e-06 -4.19156493657984e-05 9.72555907733118e-05 1.87586486481692e-06 2.11961554039997e-06 1.05905124026574e-06 4.9052196905838e-05 3.90800167215162e-06 1.87586486481692e-06 1.07792035333336e-05 -1.82083168683895e-07 -6.90978036095897e-06 2.38667581929595e-08 -5.44904089424251e-06 2.11961554039997e-06 -1.82083168683895e-07 2.51829375304766e-05 8.07923356067112e-06 3.09879599623231e-06 -4.01848424143955e-06 1.05905124026574e-06 -6.90978036095897e-06 8.07923356067112e-06 1.98221178349367e-05 3.41606319847375e-06 -8.50566473896007e-06 4.9052196905838e-05 2.38667581929595e-08 3.09879599623231e-06 3.41606319847375e-06 8.78877560314388e-05 1301 1316 0 0 0 1320 1369 0 0 10 0 0 0 0 0 0 0 0 880 0 0 8 0 0 2356 +1264 1313 0.998642471538516 -0.0221195982124794 0.0471586409299767 0.0014303967474233 0.0124365200223101 0.980423800516885 0.196505736175212 -0.0323653132321587 -0.050582081898422 -0.195652484663359 0.979367938129422 0.057318559008956 0.000343788457261696 -0.000157361870917605 -4.26919389869831e-07 -5.65524836174174e-06 -9.6005026470516e-06 -5.20736369962859e-05 -0.000157361870917605 0.000121172796222475 3.77654504753082e-06 -2.76841585595333e-06 3.14919264422998e-06 5.10265121588365e-05 -4.26919389869831e-07 3.77654504753082e-06 1.6389006874044e-05 -4.74765215594448e-06 -8.06234819598485e-06 -6.08556519163508e-07 -5.65524836174174e-06 -2.76841585595333e-06 -4.74765215594448e-06 3.90317816005209e-05 8.86022935028121e-06 8.40026079374491e-06 -9.6005026470516e-06 3.14919264422998e-06 -8.06234819598485e-06 8.86022935028121e-06 2.67528280414596e-05 3.54761289182747e-06 -5.20736369962859e-05 5.10265121588365e-05 -6.08556519163508e-07 8.40026079374491e-06 3.54761289182747e-06 9.30055823894838e-05 1392 1417 0 0 0 1407 1469 0 0 18 0 0 0 0 0 0 0 0 1018 0 0 8 0 0 2542 +1264 1317 0.998535203403597 -0.021181775129798 0.0497873474498138 0.00210227930157814 0.0108849705691971 0.980013535493752 0.198632796045225 -0.0338845987754825 -0.0529996696163809 -0.197799905589935 0.978808578001423 0.0614489396994403 0.00025530453004207 -0.000125354997486304 -5.48434755231702e-06 5.71538226263015e-06 -7.29530654151282e-06 -2.64642761585778e-05 -0.000125354997486304 0.000130054641666909 4.51318374791301e-06 -5.40276159698594e-06 6.8604239462488e-07 5.82492170715631e-05 -5.48434755231702e-06 4.51318374791301e-06 1.56388369752703e-05 -1.12654193906877e-06 -7.46048466186522e-06 2.28712195130386e-07 5.71538226263015e-06 -5.40276159698594e-06 -1.12654193906877e-06 3.1967597903101e-05 1.41534634945953e-07 2.62436248570426e-06 -7.29530654151282e-06 6.8604239462488e-07 -7.46048466186522e-06 1.41534634945953e-07 2.39514999667366e-05 -2.91303015739974e-06 -2.64642761585778e-05 5.82492170715631e-05 2.28712195130386e-07 2.62436248570426e-06 -2.91303015739974e-06 0.00012043158892494 1302 1321 0 0 0 1318 1367 0 0 10 0 0 0 0 0 0 0 0 913 0 0 6 0 0 2602 +1265 1267 0.999925402781981 -0.00984336992964354 -0.0072316623068712 0.00262342261437396 0.0100349350778089 0.99958643509749 0.0269491901005479 -0.0113362407751555 0.0069634006976903 -0.0270197490276926 0.999610646308453 0.00929914890516123 0.00013257476921216 2.18728972191171e-06 -1.02371676654058e-08 8.97988934094253e-06 -1.01778062453011e-05 -2.50043637973478e-05 2.18728972191171e-06 6.29416060087032e-05 -1.03181920478045e-05 1.19753769036188e-05 -2.6732382751564e-06 1.71522871408714e-05 -1.02371676654058e-08 -1.03181920478045e-05 1.26430561345886e-05 2.94134825312314e-06 -5.82711932326305e-06 -4.82534479170284e-06 8.97988934094253e-06 1.19753769036188e-05 2.94134825312314e-06 1.86442564847387e-05 -8.91908973034869e-06 -1.69687865168977e-06 -1.01778062453011e-05 -2.6732382751564e-06 -5.82711932326305e-06 -8.91908973034869e-06 1.83790408147408e-05 1.04316027044435e-05 -2.50043637973478e-05 1.71522871408714e-05 -4.82534479170284e-06 -1.69687865168977e-06 1.04316027044435e-05 8.15481509549031e-05 1555 1569 0 0 0 1555 1640 0 0 0 0 0 0 0 0 0 0 0 765 0 0 0 0 0 3384 +1264 1297 0.9985949373275 -0.0229277018415934 0.0477752198545282 -0.00229091975221525 0.0121179828595724 0.97646727726055 0.215324896216819 -0.0306860158207406 -0.0515878438714065 -0.214443411947375 0.975373117036279 0.0514654169696585 0.000119866096348903 -5.206830645194e-05 1.28392228353856e-06 -1.27917192402568e-06 2.40059472993138e-07 1.9230275355333e-06 -5.206830645194e-05 8.52323773960746e-05 -1.57316415244429e-06 1.52018526472749e-06 2.41235174304606e-07 3.63629807177527e-05 1.28392228353856e-06 -1.57316415244429e-06 1.21858781182618e-05 4.99611189505105e-07 -7.78337434527013e-06 7.31762491702016e-07 -1.27917192402568e-06 1.52018526472749e-06 4.99611189505105e-07 2.64277292037786e-05 6.22573722559674e-06 -2.6457184769145e-06 2.40059472993138e-07 2.41235174304606e-07 -7.78337434527013e-06 6.22573722559674e-06 2.04225479668516e-05 -1.55600212355625e-06 1.9230275355333e-06 3.63629807177527e-05 7.31762491702016e-07 -2.6457184769145e-06 -1.55600212355625e-06 6.56226284871059e-05 1398 1427 0 0 0 1417 1478 0 0 18 0 0 0 0 0 0 0 0 1012 0 0 7 0 0 2403 +1264 1305 0.998412103978982 -0.022412295652286 0.0516813276905495 -0.00129602623189269 0.0115229137075681 0.979301193838894 0.202080167768646 -0.0325598375681266 -0.0551406663720287 -0.201163765995049 0.978004420318609 0.0536765931776144 0.000342421774712329 -9.48919883422253e-05 1.83340560430469e-06 -9.66957185690304e-06 -2.61629097751062e-05 -7.54203145973598e-05 -9.48919883422253e-05 8.56996784530582e-05 2.05003381590412e-06 1.06970513894187e-06 2.3953224691406e-06 5.33268780472302e-05 1.83340560430469e-06 2.05003381590412e-06 1.52006146568557e-05 -9.26729017495574e-07 -7.71177225826732e-06 2.03580368674297e-06 -9.66957185690304e-06 1.06970513894187e-06 -9.26729017495574e-07 3.14573093723816e-05 7.91543735995441e-06 4.34965896964429e-07 -2.61629097751062e-05 2.3953224691406e-06 -7.71177225826732e-06 7.91543735995441e-06 2.79763376741425e-05 4.81545496517335e-06 -7.54203145973598e-05 5.33268780472302e-05 2.03580368674297e-06 4.34965896964429e-07 4.81545496517335e-06 0.000100049671748321 1216 1239 0 0 0 1229 1281 0 0 12 0 0 0 0 0 0 0 0 917 0 0 5 0 0 2417 +1264 1296 0.998357811936158 -0.0230360027748767 0.0524501851493592 -0.00231016783431289 0.0119966454002259 0.979356905051666 0.201782390279143 -0.0377241121859542 -0.0560157106996549 -0.20082179937392 0.978024971588678 0.0358169227263884 0.000240315561850401 -9.00512767390128e-05 4.82254151014591e-06 -3.18290318772716e-07 5.65858505733168e-06 -5.39498721511025e-05 -9.00512767390128e-05 8.48568923715798e-05 -3.39309774233378e-06 1.83707779433851e-06 -8.29033985349574e-07 6.68820381756907e-05 4.82254151014591e-06 -3.39309774233378e-06 1.04996086380749e-05 1.23454426691591e-06 -7.25382031338587e-06 -2.00719390161646e-06 -3.18290318772716e-07 1.83707779433851e-06 1.23454426691591e-06 2.72591206595173e-05 9.15053769189493e-06 6.58620570825585e-06 5.65858505733168e-06 -8.29033985349574e-07 -7.25382031338587e-06 9.15053769189493e-06 2.26645752766485e-05 2.8806663385073e-06 -5.39498721511025e-05 6.68820381756907e-05 -2.00719390161646e-06 6.58620570825585e-06 2.8806663385073e-06 9.04246403497722e-05 1307 1325 0 0 0 1323 1371 0 0 10 0 0 0 0 0 0 0 0 992 0 0 9 0 0 2541 +1264 1304 0.999041830944718 -0.0217709591986834 0.037966371412014 0.000498082859973476 0.0141651732234269 0.981650015370557 0.190164652842044 -0.0315004584431128 -0.0414097559782238 -0.189444642728566 0.981017818111001 0.0471767003493689 0.000450279073242087 -0.000244984646529146 5.82098880446558e-06 -1.15997774850993e-05 -1.11752908160413e-05 8.90273071288462e-05 -0.000244984646529146 0.000229260822319173 -4.33027835324858e-06 1.13904215176161e-05 5.52097628535544e-07 -7.07294097670689e-05 5.82098880446558e-06 -4.33027835324858e-06 1.40823981765303e-05 -2.67429603949107e-06 -8.14184396425513e-06 8.21427928422519e-06 -1.15997774850993e-05 1.13904215176161e-05 -2.67429603949107e-06 3.20056338689915e-05 5.50141468630781e-06 -1.27415624309751e-05 -1.11752908160413e-05 5.52097628535544e-07 -8.14184396425513e-06 5.50141468630781e-06 2.2334396038527e-05 -5.07011815754626e-06 8.90273071288462e-05 -7.07294097670689e-05 8.21427928422519e-06 -1.27415624309751e-05 -5.07011815754626e-06 0.000205176438206848 1395 1420 0 0 0 1409 1475 0 0 18 0 0 0 0 0 0 0 0 1005 0 0 5 0 0 2440 +1265 1293 0.999609877338623 -0.0101649887968347 0.0260147290937776 -0.00497697803585077 0.004626057566286 0.978812611180427 0.204705817664148 -0.0325798419144704 -0.0275443772566348 -0.204505611651402 0.978477778022899 0.0356590466471933 0.000266433697795582 -0.000156372172363707 -5.26363991423339e-06 -1.57571637662045e-06 -9.03000292072162e-06 -6.41640414653068e-05 -0.000156372172363707 0.000188568147001298 7.72040903527437e-06 2.63041553276153e-06 1.54792112922952e-06 8.19024474381099e-05 -5.26363991423339e-06 7.72040903527437e-06 1.05712628206222e-05 6.52287090763762e-07 -5.81048791391973e-06 4.00075897338694e-06 -1.57571637662045e-06 2.63041553276153e-06 6.52287090763762e-07 2.84953625281507e-05 8.59258900013196e-07 -4.61047574390177e-06 -9.03000292072162e-06 1.54792112922952e-06 -5.81048791391973e-06 8.59258900013196e-07 1.95569315041084e-05 -2.64089923109458e-06 -6.41640414653068e-05 8.19024474381099e-05 4.00075897338694e-06 -4.61047574390177e-06 -2.64089923109458e-06 9.44826817504404e-05 1345 1355 0 0 0 1371 1412 0 0 2 0 0 0 0 0 0 0 0 1001 0 0 9 0 0 2582 +1265 1311 0.999668881906227 -0.0104271572749822 0.0235244753292675 -0.00820693264992419 0.0055544146559647 0.980106330579179 0.19839538612691 -0.035085423074716 -0.0251251870875449 -0.1981990291343 0.979839716394491 0.0350378399544349 0.000575552091998676 -0.000390878491061989 3.27836236422468e-06 -3.0141277342632e-05 -2.80923531735894e-05 4.32118231304908e-05 -0.000390878491061989 0.000385503861073582 -4.30659375024073e-06 3.12952696215537e-05 2.18698262330254e-05 -3.22770150451858e-08 3.27836236422468e-06 -4.30659375024073e-06 1.47062750111437e-05 3.20238281319636e-06 -5.05931448273966e-06 7.88632988499699e-07 -3.0141277342632e-05 3.12952696215537e-05 3.20238281319636e-06 2.98389764405352e-05 2.86144775960396e-07 -9.83861155145908e-06 -2.80923531735894e-05 2.18698262330254e-05 -5.05931448273966e-06 2.86144775960396e-07 2.52141461958247e-05 -7.60897418873483e-06 4.32118231304908e-05 -3.22770150451858e-08 7.88632988499699e-07 -9.83861155145908e-06 -7.60897418873483e-06 0.00013689141562913 1337 1343 0 0 0 1366 1404 0 0 0 0 0 0 0 0 0 0 0 898 0 0 14 0 0 2593 +1264 1303 0.998594687857251 -0.0225049528764414 0.0479810012328596 -0.00186568670680909 0.0126942069647702 0.980575203130235 0.195732286850262 -0.033682980051712 -0.0514539259222666 -0.194848141130796 0.979482871419944 0.0463769859372645 0.000198103256101351 -2.50966776756907e-05 -3.67758520253318e-06 1.35528168656043e-05 -1.14493248560772e-05 -5.91112076349825e-05 -2.50966776756907e-05 8.67540047343893e-05 -2.29882089665502e-06 6.16096845447299e-06 -4.24144638202784e-06 5.06966430098672e-05 -3.67758520253318e-06 -2.29882089665502e-06 1.34683422481596e-05 -2.72763917600291e-06 -8.02803085214333e-06 -1.03207266203902e-06 1.35528168656043e-05 6.16096845447299e-06 -2.72763917600291e-06 3.41052036635632e-05 5.27080930091577e-06 1.53248817124076e-06 -1.14493248560772e-05 -4.24144638202784e-06 -8.02803085214333e-06 5.27080930091577e-06 2.52965450241518e-05 4.38878281399425e-06 -5.91112076349825e-05 5.06966430098672e-05 -1.03207266203902e-06 1.53248817124076e-06 4.38878281399425e-06 0.000126774158924703 1388 1411 0 0 0 1406 1471 0 0 17 0 0 0 0 0 0 0 0 904 0 0 8 0 0 2496 +1265 1268 0.999983373278122 -0.00443084093005169 -0.00369063896374202 -0.00187656300512569 0.00450618156043102 0.999776359446799 0.02066217362839 -0.0148595375370847 0.003598262782586 -0.0206784607734204 0.999779702617026 -0.00196808711836393 0.000143871401554772 -4.98860787571022e-06 1.41029979902889e-06 9.1169376738308e-06 -8.41406853961164e-06 1.00166788369265e-05 -4.98860787571022e-06 0.000104792239294256 -1.08065366550014e-05 1.71141687388299e-05 -1.22308264526579e-06 3.17107434104978e-05 1.41029979902889e-06 -1.08065366550014e-05 1.32839138404519e-05 -2.01825798444782e-07 -4.20701002583249e-06 -1.94853683610106e-06 9.1169376738308e-06 1.71141687388299e-05 -2.01825798444782e-07 2.51831220707503e-05 -4.69000663311394e-06 4.43127582197619e-06 -8.41406853961164e-06 -1.22308264526579e-06 -4.20701002583249e-06 -4.69000663311394e-06 2.12817240881756e-05 6.48340171995604e-06 1.00166788369265e-05 3.17107434104978e-05 -1.94853683610106e-06 4.43127582197619e-06 6.48340171995604e-06 7.1198178243868e-05 1502 1506 0 0 0 1513 1589 0 0 0 0 0 0 0 0 0 0 0 760 0 0 0 0 0 3370 +1265 1309 0.999588555139492 -0.011030073822098 0.0264774980997586 -0.0075527343529103 0.00580969992360928 0.981828218774635 0.189682883267375 -0.0360204648279597 -0.0280885710021223 -0.18945101290124 0.98148833201916 0.0374864604277822 0.00024414448471749 -0.000127306458632083 -1.56474090633368e-06 1.02234503505851e-06 5.71213454571125e-07 -5.64620226698782e-05 -0.000127306458632083 0.000152562347443037 6.19152925075984e-07 2.14857485338521e-06 -4.62327642811287e-06 7.13611508951947e-05 -1.56474090633368e-06 6.19152925075984e-07 1.4411745059789e-05 -1.82471604128329e-06 -9.35187665566095e-06 3.05240217483478e-06 1.02234503505851e-06 2.14857485338521e-06 -1.82471604128329e-06 3.51314143184975e-05 6.82755025823876e-06 -1.3807951301691e-05 5.71213454571125e-07 -4.62327642811287e-06 -9.35187665566095e-06 6.82755025823876e-06 2.49766102434354e-05 -1.09483302073917e-05 -5.64620226698782e-05 7.13611508951947e-05 3.05240217483478e-06 -1.3807951301691e-05 -1.09483302073917e-05 0.000123670566986442 1376 1394 0 0 0 1406 1455 0 0 0 0 0 0 0 0 0 0 0 906 0 0 20 0 0 2415 +1265 1294 0.999853946546614 -0.0110398214289858 0.0130463756644221 -0.00710156395724975 0.00863935509884629 0.985142844304181 0.171519497025104 -0.0347052652837719 -0.0147460882486563 -0.171381733738122 0.985094337727244 0.0277992261902478 0.000196274551510323 -8.54525421359829e-05 3.01588553640417e-06 3.76396004450112e-06 2.31891089659876e-06 -1.79433875831799e-05 -8.54525421359829e-05 0.000118898599722084 -2.35883553763741e-06 3.1953557325484e-06 -2.95078134815982e-06 5.77161232781002e-05 3.01588553640417e-06 -2.35883553763741e-06 1.14317924963859e-05 6.32852499260767e-08 -5.89333509182627e-06 -1.4146938718401e-06 3.76396004450112e-06 3.1953557325484e-06 6.32852499260767e-08 2.50195470366809e-05 9.63376102120543e-07 5.84676882886965e-07 2.31891089659876e-06 -2.95078134815982e-06 -5.89333509182627e-06 9.63376102120543e-07 1.73507869124244e-05 -2.19990681187324e-06 -1.79433875831799e-05 5.77161232781002e-05 -1.4146938718401e-06 5.84676882886965e-07 -2.19990681187324e-06 8.71397977292803e-05 1385 1400 0 0 0 1409 1461 0 0 0 0 0 0 0 0 0 0 0 997 0 0 13 0 0 2432 +1265 1291 0.999802663086895 -0.0118092524373733 -0.0159742430563524 -0.00726366433466985 0.0139687747428028 0.989674871013814 0.14264824925661 -0.0302445878544624 0.0141247377511182 -0.142843240094383 0.989644532416969 0.0428891300842403 0.000147481554843274 -4.866930618697e-05 1.84922750763072e-06 -4.17651737711291e-06 -3.3423644262818e-06 6.40889614963084e-07 -4.866930618697e-05 8.98744723164994e-05 -3.06391591083802e-06 8.31359354867662e-06 1.23239505345582e-05 4.91513439353473e-05 1.84922750763072e-06 -3.06391591083802e-06 1.04751975913928e-05 1.94273470672818e-06 -4.00737270253607e-06 -1.40983463881348e-06 -4.17651737711291e-06 8.31359354867662e-06 1.94273470672818e-06 2.51062851286597e-05 4.65264861299735e-06 5.64500047690494e-06 -3.3423644262818e-06 1.23239505345582e-05 -4.00737270253607e-06 4.65264861299735e-06 2.54386446781696e-05 6.18467369120365e-06 6.40889614963084e-07 4.91513439353473e-05 -1.40983463881348e-06 5.64500047690494e-06 6.18467369120365e-06 7.74464692191798e-05 1305 1318 0 0 0 1321 1381 0 0 0 0 0 0 0 0 0 0 0 874 0 0 4 0 0 2776 +1265 1315 0.999441955880707 -0.00928606651181826 0.0320865360250154 -0.00920060941810249 0.00244569131350436 0.978346141580704 0.206960976631218 -0.0357728388555833 -0.0333135921111124 -0.206767009512849 0.977822892121967 0.0380066736736063 0.00033148277641081 -0.000197147498560842 3.0136857537987e-06 9.14560968770284e-06 6.10801642043248e-06 -0.000123851231704405 -0.000197147498560842 0.00017332413216795 -4.00592587976886e-06 -3.02227236011095e-06 -1.56213050840825e-06 0.000104943814339598 3.0136857537987e-06 -4.00592587976886e-06 1.4785721734779e-05 3.96571094900613e-06 -4.912730272072e-06 -5.62092739136955e-06 9.14560968770284e-06 -3.02227236011095e-06 3.96571094900613e-06 2.48011027354154e-05 -2.11793083287633e-06 1.8119386759427e-06 6.10801642043248e-06 -1.56213050840825e-06 -4.912730272072e-06 -2.11793083287633e-06 2.54143182401843e-05 -5.15482544961004e-06 -0.000123851231704405 0.000104943814339598 -5.62092739136955e-06 1.8119386759427e-06 -5.15482544961004e-06 0.000148531009179099 1237 1246 0 0 0 1261 1302 0 0 1 0 0 0 0 0 0 0 0 990 0 0 16 0 0 2580 +1265 1292 0.999809002088062 -0.0116223383639849 0.0157124343953215 -0.00641195488721588 0.00873287904239009 0.984910972500328 0.172841294464283 -0.0358651280016524 -0.0174841690481767 -0.172671067348908 0.984824353036258 0.0364627261121412 0.000226174879027799 -7.0884627061523e-05 7.07869715936071e-06 -1.47859714637416e-05 -2.67581738685392e-05 -2.47501756261953e-05 -7.0884627061523e-05 8.96422569317859e-05 2.37851275061792e-06 4.96764479938605e-06 7.93662314972862e-06 4.6672860397051e-05 7.07869715936071e-06 2.37851275061792e-06 1.10948943043454e-05 1.37972620586189e-06 -4.99223947409996e-06 2.57268823999882e-08 -1.47859714637416e-05 4.96764479938605e-06 1.37972620586189e-06 2.06643406567166e-05 3.5616058634885e-06 7.41492636319707e-07 -2.67581738685392e-05 7.93662314972862e-06 -4.99223947409996e-06 3.5616058634885e-06 2.26885893628379e-05 1.99049209249504e-06 -2.47501756261953e-05 4.6672860397051e-05 2.57268823999882e-08 7.41492636319707e-07 1.99049209249504e-06 7.3250943167882e-05 1334 1342 0 0 0 1359 1404 0 0 0 0 0 0 0 0 0 0 0 967 0 0 14 0 0 2741 +1265 1269 0.999069856563696 -0.0140540735539332 -0.0407664656591249 -0.00123819002798649 0.0150441392701201 0.999596783505008 0.0240820323075768 -0.00508692181529209 0.0404115772943498 -0.0246729289502195 0.998878446557738 0.018689935375292 0.000144994099153865 -1.67476586912315e-05 -1.12489026682162e-06 1.31523594332157e-05 -1.16769027041714e-05 -6.87971728340847e-06 -1.67476586912315e-05 0.00011318520484423 -1.83624580804408e-05 1.93376160898395e-05 7.35133247187319e-08 5.2487452253033e-05 -1.12489026682162e-06 -1.83624580804408e-05 1.3434832202995e-05 -9.79325742905035e-07 -6.2597403802983e-06 -8.19086100261618e-06 1.31523594332157e-05 1.93376160898395e-05 -9.79325742905035e-07 2.4819265374253e-05 -7.77365440902956e-06 -5.54190408850573e-07 -1.16769027041714e-05 7.35133247187319e-08 -6.2597403802983e-06 -7.77365440902956e-06 1.64281485892979e-05 4.18550617917772e-06 -6.87971728340847e-06 5.2487452253033e-05 -8.19086100261618e-06 -5.54190408850573e-07 4.18550617917772e-06 8.97865271338169e-05 1527 1554 0 0 0 1527 1613 0 0 4 0 0 0 0 0 0 0 0 745 0 0 0 0 0 3391 +1265 1312 0.999566617302749 -0.0103035315281993 0.0275756198839958 -0.00774831150423096 0.00455493813980891 0.979598088566381 0.200915000474419 -0.0323827239522505 -0.0290831585712717 -0.200702322146857 0.979220479653269 0.039216878026884 0.000441143629799401 -0.000290492229725853 4.45014548568208e-06 1.07439768651719e-05 1.23861555586585e-05 -4.49960195011993e-05 -0.000290492229725853 0.000271813659020906 -3.98549329051757e-06 -1.18604819233602e-05 -2.02800801096493e-05 6.033560989108e-05 4.45014548568208e-06 -3.98549329051757e-06 1.45640765772353e-05 -1.43362798678778e-06 -7.44234806642854e-06 -2.70021872379904e-06 1.07439768651719e-05 -1.18604819233602e-05 -1.43362798678778e-06 3.19179113546824e-05 5.46671177005872e-06 -6.74569892015485e-06 1.23861555586585e-05 -2.02800801096493e-05 -7.44234806642854e-06 5.46671177005872e-06 2.50499455357029e-05 -6.39092023591437e-06 -4.49960195011993e-05 6.033560989108e-05 -2.70021872379904e-06 -6.74569892015485e-06 -6.39092023591437e-06 0.000101903429501795 1374 1397 0 0 0 1401 1455 0 0 0 0 0 0 0 0 0 0 0 990 0 0 14 0 0 2464 +1265 1313 0.999584443282955 -0.0107406186675917 0.02675032443432 -0.00737622237076611 0.00537463547237756 0.981161479463542 0.193114640849552 -0.035564675458019 -0.0283205586146011 -0.192890617520785 0.980811478130332 0.0426147892625213 0.000520913228290622 -0.000320932778847296 5.21783993130727e-06 -3.97522480827231e-06 -6.55796716131338e-06 -6.13296320893184e-05 -0.000320932778847296 0.000279524064301517 -5.00037710020054e-07 4.39367783466442e-09 2.98568667098353e-06 7.79192000791088e-05 5.21783993130727e-06 -5.00037710020054e-07 1.53184986081823e-05 -2.89606489566802e-06 -5.88162418170125e-06 -1.2798464929174e-06 -3.97522480827231e-06 4.39367783466442e-09 -2.89606489566802e-06 3.25849536234554e-05 2.28704838207322e-07 3.38734873509038e-06 -6.55796716131338e-06 2.98568667098353e-06 -5.88162418170125e-06 2.28704838207322e-07 2.15873510968261e-05 7.69865923725624e-07 -6.13296320893184e-05 7.79192000791088e-05 -1.2798464929174e-06 3.38734873509038e-06 7.69865923725624e-07 7.5954957791929e-05 1373 1391 0 0 0 1404 1454 0 0 0 0 0 0 0 0 0 0 0 1014 0 0 18 0 0 2589 +1265 1314 0.998788822094003 -0.0108806973333617 0.0479843650120903 -0.00797271383923324 -2.39814483538586e-05 0.975134071930021 0.221615751213821 -0.0302741886972809 -0.0492025231564792 -0.221348485846901 0.973952750151834 0.0452105915475672 0.000368298252570397 -0.000167578775044582 3.27295009865525e-06 4.26692112516748e-06 -6.82078005123384e-06 -8.07452092508767e-05 -0.000167578775044582 0.000138251538030359 -9.07942276747815e-06 5.5843124646508e-06 -2.16479879139795e-06 5.87478930399929e-05 3.27295009865525e-06 -9.07942276747815e-06 1.53166997065762e-05 1.20193168930154e-06 -7.95968805856441e-06 -5.267398528567e-06 4.26692112516748e-06 5.5843124646508e-06 1.20193168930154e-06 3.58110941474949e-05 6.62588230267968e-07 -8.76196331788692e-07 -6.82078005123384e-06 -2.16479879139795e-06 -7.95968805856441e-06 6.62588230267968e-07 2.57604823698639e-05 7.93494359359302e-07 -8.07452092508767e-05 5.87478930399929e-05 -5.267398528567e-06 -8.76196331788692e-07 7.93494359359302e-07 9.56682835527012e-05 1343 1354 0 0 0 1370 1412 0 0 3 0 0 0 0 0 0 0 0 1008 0 0 16 0 0 2386 +1265 1305 0.999793619578687 -0.00978403391229821 0.0178042391062225 -0.0104738587083643 0.00623048956429741 0.981827088288028 0.189675379803605 -0.0355272790991216 -0.0193364745891727 -0.189525305392856 0.981685417721078 0.0428983830367484 0.000340578092156623 -0.000200652410353959 4.99165603694099e-06 -9.94714798767775e-07 -4.81018947158719e-06 -5.71713347852153e-05 -0.000200652410353959 0.000200089645420595 -9.05686621149277e-07 -8.26313276630302e-06 -9.72609567950821e-06 9.75995839936892e-05 4.99165603694099e-06 -9.05686621149277e-07 1.60990587088833e-05 -2.99150543442189e-06 -7.97999221907648e-06 9.71535393544934e-09 -9.94714798767775e-07 -8.26313276630302e-06 -2.99150543442189e-06 3.8519695537248e-05 1.4293706229881e-05 -5.0962750810277e-06 -4.81018947158719e-06 -9.72609567950821e-06 -7.97999221907648e-06 1.4293706229881e-05 3.68439693092229e-05 -1.44006814588653e-05 -5.71713347852153e-05 9.75995839936892e-05 9.71535393544934e-09 -5.0962750810277e-06 -1.44006814588653e-05 0.000114077932734832 1239 1245 0 0 0 1263 1303 0 0 0 0 0 0 0 0 0 0 0 902 0 0 15 0 0 2478 +1265 1316 0.998920985410792 -0.00960811962196221 0.045437307834663 -0.00656743069858762 -0.000751140066008659 0.974895033459332 0.222663669072727 -0.0326976564858693 -0.0464359849096915 -0.222457541507717 0.973835890451676 0.0430778295037267 0.00034490161335102 -0.00011587787673478 4.5931527346891e-06 7.20181167620162e-06 -1.17921100460447e-05 -7.25686371076974e-05 -0.00011587787673478 0.000124088316009104 -3.67348929750444e-06 4.64930256659678e-07 -4.66275035946892e-06 4.46026859641165e-05 4.5931527346891e-06 -3.67348929750444e-06 1.70460945919325e-05 -1.55270406407128e-06 -8.12764858602463e-06 -2.92045439096709e-06 7.20181167620162e-06 4.64930256659678e-07 -1.55270406407128e-06 4.30775772739797e-05 2.95171850111331e-07 2.13752958129901e-06 -1.17921100460447e-05 -4.66275035946892e-06 -8.12764858602463e-06 2.95171850111331e-07 2.79954951825356e-05 4.34470234396829e-06 -7.25686371076974e-05 4.46026859641165e-05 -2.92045439096709e-06 2.13752958129901e-06 4.34470234396829e-06 9.42916588716516e-05 1249 1263 0 0 0 1272 1315 0 0 3 0 0 0 0 0 0 0 0 997 0 0 14 0 0 2623 +1265 1317 0.999091211843726 -0.00961854004521246 0.0415238979869918 -0.00557501684182043 0.000561713108206324 0.977091895935434 0.212817084313461 -0.0317740636680325 -0.0426196538585138 -0.212600354149981 0.976209329252842 0.0516022710345589 0.00037793933197019 -0.000235089040848543 5.41585865342083e-06 -2.88764686570395e-05 -2.64688530318654e-05 -5.9378617435918e-05 -0.000235089040848543 0.000213978858664529 -1.59328559829086e-06 1.79314542192521e-05 1.63432533781888e-05 7.73413927268739e-05 5.41585865342083e-06 -1.59328559829086e-06 1.52369616341661e-05 1.85748495461769e-06 -8.53853966334737e-06 -1.31449086915219e-06 -2.88764686570395e-05 1.79314542192521e-05 1.85748495461769e-06 3.0807587685205e-05 1.89561072367559e-06 4.73217605863888e-06 -2.64688530318654e-05 1.63432533781888e-05 -8.53853966334737e-06 1.89561072367559e-06 2.83347594332734e-05 3.92557343739002e-06 -5.9378617435918e-05 7.73413927268739e-05 -1.31449086915219e-06 4.73217605863888e-06 3.92557343739002e-06 0.000106039747553065 1339 1349 0 0 0 1365 1405 0 0 2 0 0 0 0 0 0 0 0 902 0 0 14 0 0 2642 +1265 1303 0.999877228554109 -0.00984268763500164 0.0121921827034297 -0.00802356182227498 0.00738934463726522 0.982326537071587 0.187029335000624 -0.0345112171810862 -0.0138175759373975 -0.186916280898865 0.982278666433386 0.0317817885019071 0.000288018257788185 -8.88657916926137e-05 5.73223656578525e-06 4.42528993355226e-07 -2.80548397064093e-05 -2.54091017566429e-05 -8.88657916926137e-05 0.000150681779719257 -4.40553256005912e-06 8.99965010738771e-06 -1.18108063852141e-05 7.76337395726033e-05 5.73223656578525e-06 -4.40553256005912e-06 1.42675389319887e-05 -2.00445800001376e-06 -8.19691024761318e-06 -2.36389791220977e-07 4.42528993355226e-07 8.99965010738771e-06 -2.00445800001376e-06 3.37207398864917e-05 6.9051461372837e-06 -5.33003463819109e-07 -2.80548397064093e-05 -1.18108063852141e-05 -8.19691024761318e-06 6.9051461372837e-06 3.26086285912094e-05 -8.58519355078781e-06 -2.54091017566429e-05 7.76337395726033e-05 -2.36389791220977e-07 -5.33003463819109e-07 -8.58519355078781e-06 0.00011370227115742 1375 1393 0 0 0 1404 1454 0 0 0 0 0 0 0 0 0 0 0 893 0 0 15 0 0 2538 +1265 1307 0.999794472397152 -0.0099922708425294 0.0176399401220636 -0.00716420934236016 0.00655532908251086 0.982695431982149 0.185112710590165 -0.0350608319069968 -0.0191843849190023 -0.184959029206005 0.982558963569338 0.0369970128515107 0.000262910210389661 -0.000117217534877229 -1.39955092764738e-06 8.19523490479337e-06 1.06154632122083e-06 -3.67471936455622e-05 -0.000117217534877229 0.000120866476330496 2.68502391810638e-06 1.06653154042692e-07 -5.29563943245356e-06 5.94143227537626e-05 -1.39955092764738e-06 2.68502391810638e-06 1.32950540770763e-05 5.39641230229421e-07 -6.3766124162496e-06 3.78905766920247e-06 8.19523490479337e-06 1.06653154042692e-07 5.39641230229421e-07 2.91714080503232e-05 4.78374269667782e-06 -2.41603850367501e-06 1.06154632122083e-06 -5.29563943245356e-06 -6.3766124162496e-06 4.78374269667782e-06 2.71308068839639e-05 -4.24832276492425e-06 -3.67471936455622e-05 5.94143227537626e-05 3.78905766920247e-06 -2.41603850367501e-06 -4.24832276492425e-06 7.21475210576962e-05 1384 1399 0 0 0 1415 1462 0 0 0 0 0 0 0 0 0 0 0 1003 0 0 21 0 0 2463 +1265 1318 0.998890689552038 -0.00961720229801304 0.0460966348686486 -0.0085920506302033 -0.000918707683043642 0.974755635456812 0.223272495219137 -0.0341230979255747 -0.0470802113679148 -0.223067166040064 0.973665493448549 0.0500271176413329 0.000333432482260727 -0.000176561980834491 3.76247199349142e-06 -4.47826576371075e-06 1.73452358095854e-07 -2.94074264393347e-05 -0.000176561980834491 0.000139595331753929 -1.87359063726531e-06 -3.37659916320466e-06 2.67110082318281e-07 3.12538773151243e-05 3.76247199349142e-06 -1.87359063726531e-06 1.5275244886041e-05 1.71738710506945e-06 -6.01752203854562e-06 -2.89991494889005e-06 -4.47826576371075e-06 -3.37659916320466e-06 1.71738710506945e-06 2.69527789248851e-05 6.40872113470558e-08 3.66575286356664e-06 1.73452358095854e-07 2.67110082318281e-07 -6.01752203854562e-06 6.40872113470558e-08 2.37197527953378e-05 -1.44867153796956e-06 -2.94074264393347e-05 3.12538773151243e-05 -2.89991494889005e-06 3.66575286356664e-06 -1.44867153796956e-06 5.75235452446394e-05 1378 1396 0 0 0 1413 1459 0 0 0 0 0 0 0 0 0 0 0 1011 0 2 26 0 0 2553 +1266 1270 0.999101574407036 0.00962190477580515 -0.0412730295213099 -4.97395948408567e-05 -0.00788588792580199 0.999085636836798 0.0420202693712286 -0.0070822776284228 0.0416396060140255 -0.0416570428006389 0.998263909993796 0.00817571224080395 6.20247734421715e-05 1.64241681823727e-06 -6.51802175732261e-07 1.4623211329495e-07 -3.46316500290426e-06 9.18381483863405e-06 1.64241681823727e-06 5.39323652476384e-05 -1.43914276226567e-06 5.94833581653084e-06 6.0661527603215e-06 3.86624539042997e-05 -6.51802175732261e-07 -1.43914276226567e-06 9.82626186177855e-06 2.19890288948019e-06 -6.16244852523831e-06 -1.35674399405125e-06 1.4623211329495e-07 5.94833581653084e-06 2.19890288948019e-06 2.30018414516636e-05 1.0577583356544e-06 5.85098722701327e-06 -3.46316500290426e-06 6.0661527603215e-06 -6.16244852523831e-06 1.0577583356544e-06 1.72935993759476e-05 6.57887484296232e-06 9.18381483863405e-06 3.86624539042997e-05 -1.35674399405125e-06 5.85098722701327e-06 6.57887484296232e-06 5.84267453410576e-05 1419 1419 0 0 0 1446 1501 0 0 0 0 0 0 0 0 0 0 0 791 0 0 2 0 0 3396 +1265 1295 0.999823224682334 -0.0106449593202891 0.015498523377695 -0.00980352093371965 0.00759974401575178 0.982759961549897 0.184729807733727 -0.0340511422961841 -0.0171977695273141 -0.18457936725299 0.982667132811397 0.0362188410839415 0.000391767808541415 -0.00021733573674955 3.65135277482051e-06 -2.40586682667368e-05 -2.98063334881237e-05 -1.26425939905605e-05 -0.00021733573674955 0.000213112391387253 -1.27297333743171e-06 1.59846457458037e-05 1.85854927498579e-05 6.73345120347093e-05 3.65135277482051e-06 -1.27297333743171e-06 1.23901684837773e-05 -2.28229341700488e-07 -6.41621660028112e-06 -1.40555272655342e-06 -2.40586682667368e-05 1.59846457458037e-05 -2.28229341700488e-07 3.30200624302835e-05 1.26198264556749e-05 -1.20862795850859e-08 -2.98063334881237e-05 1.85854927498579e-05 -6.41621660028112e-06 1.26198264556749e-05 3.07675833005026e-05 -7.87790488069145e-06 -1.26425939905605e-05 6.73345120347093e-05 -1.40555272655342e-06 -1.20862795850859e-08 -7.87790488069145e-06 0.000116808717058594 1341 1345 0 0 0 1367 1407 0 0 0 0 0 0 0 0 0 0 0 876 0 0 13 0 0 2385 +1266 1268 0.999892363331681 0.0146445786619051 -0.000893345846814512 0.00230559897413376 -0.0146163681853166 0.999554242502833 0.0260322506837133 -0.00522326474503913 0.0012741789740898 -0.026016391187167 0.999660704368006 0.00848350203118231 7.97932650304871e-05 5.53217215062257e-06 -2.2951815960755e-06 -5.31474417840861e-07 8.67951390654746e-07 3.28642668315898e-06 5.53217215062257e-06 3.95751192801718e-05 -3.53023557485235e-06 3.64261375127081e-06 2.33238884815583e-06 2.413244317719e-05 -2.2951815960755e-06 -3.53023557485235e-06 1.1221759754194e-05 4.34732589340505e-06 -6.75536288547054e-06 -1.3273913794051e-06 -5.31474417840861e-07 3.64261375127081e-06 4.34732589340505e-06 2.13071910975214e-05 -1.06750493918364e-05 -3.80788743758758e-07 8.67951390654746e-07 2.33238884815583e-06 -6.75536288547054e-06 -1.06750493918364e-05 1.52780092512512e-05 4.70455694801763e-06 3.28642668315898e-06 2.413244317719e-05 -1.3273913794051e-06 -3.80788743758758e-07 4.70455694801763e-06 4.43337775885143e-05 1477 1477 0 0 0 1513 1563 0 0 0 0 0 0 0 0 0 0 0 777 0 0 2 0 0 3376 +1265 1306 0.999894561496693 -0.00976552115096635 0.0107471152401863 -0.00636990212410532 0.00770638461496015 0.984134251633717 0.177257965681407 -0.0363470140395931 -0.0123076206271611 -0.177156454463264 0.984105742853126 0.0269602146531986 0.000411482203907499 -0.000261830221653532 1.56206444416663e-05 -1.53625539982328e-05 -1.12165656982184e-05 -5.16420991689728e-05 -0.000261830221653532 0.000290593233095199 -9.954313143643e-06 1.91368690581499e-05 1.91850478894374e-06 0.000110024174753728 1.56206444416663e-05 -9.954313143643e-06 1.54183784019332e-05 -1.06675019074868e-06 -7.30755999734883e-06 -1.16602046436293e-06 -1.53625539982328e-05 1.91368690581499e-05 -1.06675019074868e-06 3.06245789683125e-05 4.68050661314306e-06 1.07572348412418e-05 -1.12165656982184e-05 1.91850478894374e-06 -7.30755999734883e-06 4.68050661314306e-06 2.55074901313091e-05 -4.59492191979442e-07 -5.16420991689728e-05 0.000110024174753728 -1.16602046436293e-06 1.07572348412418e-05 -4.59492191979442e-07 0.00010888084151655 1377 1393 0 0 0 1407 1456 0 0 0 0 0 0 0 0 0 0 0 996 0 0 17 0 0 2648 +1266 1269 0.999793314664517 0.00773942420771101 -0.0187997144944233 -0.00112637195749005 -0.0070884971087327 0.99938136798558 0.034447562061931 -0.00378013875271048 0.0190546886848938 -0.0343071805341709 0.999229671398382 0.00929148766801076 9.38287158134542e-05 -1.74582830205321e-05 1.3098224661108e-06 -1.01433068052942e-06 -4.55957538450326e-06 -1.37372600729157e-05 -1.74582830205321e-05 4.737590952639e-05 -5.36110608714445e-07 -8.49802993685797e-06 2.35457381765045e-06 3.06804313914542e-05 1.3098224661108e-06 -5.36110608714445e-07 9.839475458417e-06 5.89395083799585e-07 -5.22533308627213e-06 6.73867553536534e-07 -1.01433068052942e-06 -8.49802993685797e-06 5.89395083799585e-07 2.49810984789878e-05 -1.24721635457958e-06 -6.68477430066601e-06 -4.55957538450326e-06 2.35457381765045e-06 -5.22533308627213e-06 -1.24721635457958e-06 1.65454902959857e-05 5.45741993357369e-06 -1.37372600729157e-05 3.06804313914542e-05 6.73867553536534e-07 -6.68477430066601e-06 5.45741993357369e-06 5.80849542296486e-05 1504 1504 0 0 0 1527 1585 0 0 0 0 0 0 0 0 0 0 0 766 0 0 0 0 0 3453 +1265 1296 0.99992482032864 -0.0106678246136027 0.00604575956767902 -0.0105440964834499 0.00938416709013912 0.983129206666048 0.182671564312048 -0.0377817535786524 -0.00789247101743932 -0.182601096705906 0.983155403984049 0.0275535885609434 0.000424865820127609 -0.000249886255522659 1.06536229644115e-05 -7.19454028668826e-06 -1.64266529938308e-05 -0.000104502227068572 -0.000249886255522659 0.000228732363206835 -8.27615208849968e-06 8.01504371115853e-06 1.31081580199464e-05 0.000124393437531149 1.06536229644115e-05 -8.27615208849968e-06 1.09232645227871e-05 3.21580897923079e-06 -5.66431021632126e-06 -7.31920819216723e-06 -7.19454028668826e-06 8.01504371115853e-06 3.21580897923079e-06 2.46704130834281e-05 4.33224515317391e-06 -1.63736984331066e-06 -1.64266529938308e-05 1.31081580199464e-05 -5.66431021632126e-06 4.33224515317391e-06 2.38474925667053e-05 -4.49122464920039e-06 -0.000104502227068572 0.000124393437531149 -7.31920819216723e-06 -1.63736984331066e-06 -4.49122464920039e-06 0.000162420709897208 1339 1343 0 0 0 1368 1406 0 0 0 0 0 0 0 0 0 0 0 981 0 0 12 0 0 2586 +1265 1297 0.999766399117178 -0.0101153548541048 0.0191004395877854 -0.011451759611492 0.00604056994174725 0.979277278750911 0.202433996248132 -0.0365955880157391 -0.020752318209057 -0.202271329946647 0.97910962122255 0.039835950819351 0.000296613596161164 -0.000200855569380818 8.47725976789595e-06 -1.01781024348123e-05 7.35178054150446e-06 -6.07150905829391e-05 -0.000200855569380818 0.000212715012387771 -3.97594906156988e-06 8.48467418661695e-06 -7.67815955677948e-06 9.01682720622079e-05 8.47725976789595e-06 -3.97594906156988e-06 1.27391484933005e-05 -2.25626864678705e-06 -8.78059151164595e-06 1.17303461250069e-06 -1.01781024348123e-05 8.48467418661695e-06 -2.25626864678705e-06 3.51531593485057e-05 1.26846527920059e-05 -6.85193264110782e-07 7.35178054150446e-06 -7.67815955677948e-06 -8.78059151164595e-06 1.26846527920059e-05 2.52566056872806e-05 -4.29453846400057e-06 -6.07150905829391e-05 9.01682720622079e-05 1.17303461250069e-06 -6.85193264110782e-07 -4.29453846400057e-06 8.43605225503598e-05 1379 1395 0 0 0 1411 1455 0 0 0 0 0 0 0 0 0 0 0 1000 0 2 22 0 0 2455 +1266 1311 0.99919390936849 0.00741842473821769 0.039452483512676 -0.00635346501468087 -0.0149375806559683 0.980913219382782 0.193871412859792 -0.0303320292272185 -0.0372612421298729 -0.194304459584717 0.98023332774418 0.0307014189520207 0.000150521345922435 -7.74920811936017e-05 1.57069202286033e-06 -7.26218720937311e-06 -8.23486580186882e-06 -2.87455382768695e-06 -7.74920811936017e-05 0.000108694886766908 -1.40178259574642e-06 9.35919796303029e-06 7.12165623824348e-06 4.67154402515946e-05 1.57069202286033e-06 -1.40178259574642e-06 1.4125398379572e-05 2.52903937820283e-06 -6.61810856284707e-06 2.19002445829313e-06 -7.26218720937311e-06 9.35919796303029e-06 2.52903937820283e-06 2.65822549396063e-05 -3.38349891125033e-06 1.59865731002686e-06 -8.23486580186882e-06 7.12165623824348e-06 -6.61810856284707e-06 -3.38349891125033e-06 2.17975925303601e-05 4.07317551013743e-06 -2.87455382768695e-06 4.67154402515946e-05 2.19002445829313e-06 1.59865731002686e-06 4.07317551013743e-06 6.23616211776942e-05 1353 1357 0 0 0 1396 1424 0 0 0 0 0 0 0 0 0 0 0 921 0 2 29 0 0 2610 +1265 1304 0.99994299122882 -0.0095606639790452 0.0047547867080565 -0.00438142656123089 0.00855461661302674 0.983793413019755 0.179101476916147 -0.0328314027377509 -0.00639005688264588 -0.179050591183668 0.983819115981091 0.0277950284498501 0.000207464018981576 -0.000148061089123667 -5.19183498364766e-06 1.3808394263732e-05 2.78321157560734e-06 -1.02393176781754e-05 -0.000148061089123667 0.000209847613391454 1.1682384793921e-05 -2.24668649413522e-05 -6.73012548950767e-06 2.14595243255163e-06 -5.19183498364766e-06 1.1682384793921e-05 1.56096011056007e-05 -4.80275492517201e-06 -8.40032839810822e-06 -4.24949023002484e-07 1.3808394263732e-05 -2.24668649413522e-05 -4.80275492517201e-06 3.39192836627914e-05 4.92740617864114e-06 -6.41437743892468e-06 2.78321157560734e-06 -6.73012548950767e-06 -8.40032839810822e-06 4.92740617864114e-06 2.22964502469346e-05 -1.73485505361684e-06 -1.02393176781754e-05 2.14595243255163e-06 -4.24949023002484e-07 -6.41437743892468e-06 -1.73485505361684e-06 0.000126254873953457 1384 1402 0 0 0 1409 1463 0 0 0 0 0 0 0 0 0 0 0 996 0 0 11 0 0 2488 +1266 1312 0.99876415985885 0.00889541946221819 0.0488981031742158 -0.00719117463472437 -0.0186875212869451 0.978870212992483 0.203626822064776 -0.03099829240252 -0.0460535506730484 -0.204288956208213 0.977826719230848 0.0319925643948763 0.000171903178047591 -8.85798350623698e-05 5.55497256855002e-06 -1.64474870683413e-05 -1.7524441043375e-05 7.10905274948718e-06 -8.85798350623698e-05 0.000102673790105324 -5.78680773918855e-06 1.17501167721519e-05 4.39105451203311e-06 1.77772316765785e-05 5.55497256855002e-06 -5.78680773918855e-06 1.67570755549414e-05 -2.52477502533238e-06 -8.73303447867231e-06 1.681799553308e-06 -1.64474870683413e-05 1.17501167721519e-05 -2.52477502533238e-06 3.84932088378383e-05 1.20261187516514e-05 -4.60018797859334e-06 -1.7524441043375e-05 4.39105451203311e-06 -8.73303447867231e-06 1.20261187516514e-05 3.25718077629604e-05 -6.33506814205271e-06 7.10905274948718e-06 1.77772316765785e-05 1.681799553308e-06 -4.60018797859334e-06 -6.33506814205271e-06 8.85997307929808e-05 1342 1350 0 0 0 1386 1421 0 0 6 0 0 0 0 0 0 0 0 1014 0 7 42 0 0 2539 +1266 1292 0.99957972194913 0.00760585960272982 0.027973744257863 -0.00614387464829665 -0.0125103124120705 0.983664367196114 0.179577016324528 -0.0315476323250998 -0.0261509378694752 -0.179851504326128 0.983346106332951 0.0341214207328442 0.000159779288178285 -2.74625271904666e-05 4.25036080431743e-06 -2.39438333300039e-06 -1.16424128358785e-05 3.33020555070584e-06 -2.74625271904666e-05 0.000130438568229619 7.42639310340609e-06 -9.74764854383708e-06 -1.18873333439728e-05 4.49519574555559e-05 4.25036080431743e-06 7.42639310340609e-06 1.17010938512466e-05 -1.80354026292801e-07 -6.65544945896121e-06 4.11458156248859e-06 -2.39438333300039e-06 -9.74764854383708e-06 -1.80354026292801e-07 2.52915005708613e-05 3.68625778945854e-06 -4.28497667382538e-06 -1.16424128358785e-05 -1.18873333439728e-05 -6.65544945896121e-06 3.68625778945854e-06 2.30483160781222e-05 -5.47354014504281e-06 3.33020555070584e-06 4.49519574555559e-05 4.11458156248859e-06 -4.28497667382538e-06 -5.47354014504281e-06 0.00010233348362944 1333 1341 0 0 0 1376 1406 0 0 6 0 0 0 0 0 0 0 0 991 0 2 29 0 0 2758 +1266 1314 0.998699138931478 0.00771142483128638 0.0504040060371826 -0.00901240211499691 -0.0179532812287761 0.978378905214514 0.206039795972452 -0.0281505874858691 -0.0477253558461893 -0.206676684118748 0.977244615565128 0.0423457980476112 0.000302059549400365 -8.20813462183814e-05 -2.28131214749928e-06 -6.73275583949335e-07 -3.195274500064e-05 -1.4826417460667e-05 -8.20813462183814e-05 9.17177847094616e-05 -7.02705238470457e-06 1.04283177457461e-05 1.21327295922629e-06 3.1038045185999e-05 -2.28131214749928e-06 -7.02705238470457e-06 1.69525881772089e-05 -1.50385628107363e-06 -4.51150981298873e-06 -5.8350400173927e-06 -6.73275583949335e-07 1.04283177457461e-05 -1.50385628107363e-06 3.2346453823242e-05 -3.13975770527088e-06 3.84397939772068e-06 -3.195274500064e-05 1.21327295922629e-06 -4.51150981298873e-06 -3.13975770527088e-06 3.37886611817391e-05 -9.03042302910963e-07 -1.4826417460667e-05 3.1038045185999e-05 -5.8350400173927e-06 3.84397939772068e-06 -9.03042302910963e-07 5.82832975910108e-05 1351 1353 0 0 0 1392 1417 0 0 0 0 0 0 0 0 0 0 0 1006 0 4 34 0 0 2406 +1266 1310 0.998985972526388 0.00754602930437067 0.0443856298507192 -0.0138215673045024 -0.0159916079649683 0.981041852038184 0.193135064201675 -0.0381396052892255 -0.0420867576584635 -0.193649017532307 0.980167721789781 0.0333706949536934 0.000227000360456291 -0.000105138860287252 -5.98840390164938e-07 2.5404319343435e-06 -1.35808117105199e-05 -2.35657696608551e-05 -0.000105138860287252 8.2828382088248e-05 1.94092337948307e-07 4.50921945875167e-07 7.80496479636042e-06 3.33666792958364e-05 -5.98840390164938e-07 1.94092337948307e-07 1.49968050751989e-05 4.31794704664699e-06 -4.47147867998087e-06 2.98014112304158e-06 2.5404319343435e-06 4.50921945875167e-07 4.31794704664699e-06 2.81625317204689e-05 8.38298753408638e-06 4.25959450465898e-06 -1.35808117105199e-05 7.80496479636042e-06 -4.47147867998087e-06 8.38298753408638e-06 3.5637295149922e-05 5.86809977491145e-06 -2.35657696608551e-05 3.33666792958364e-05 2.98014112304158e-06 4.25959450465898e-06 5.86809977491145e-06 8.18114172002288e-05 1334 1335 0 0 0 1387 1409 0 0 0 0 0 0 0 0 0 0 0 1019 0 12 56 0 0 2432 +1266 1308 0.999169878953488 0.00741543937499427 0.0400570125065314 -0.00683606333835233 -0.0149698726135669 0.981332041409227 0.191737652581679 -0.0314100813126639 -0.0378874109171663 -0.192178135495365 0.980628425210854 0.0330247007031728 0.000202283716044005 -8.89246779700143e-05 8.04264248904229e-06 2.18233790968482e-06 -7.12274210266766e-06 -1.98963938984606e-05 -8.89246779700143e-05 9.31125842387319e-05 -3.62430788854452e-06 5.95055384274967e-06 1.70796952204975e-06 5.3617546674472e-05 8.04264248904229e-06 -3.62430788854452e-06 1.32966497120953e-05 1.07837136299679e-06 -5.03835959267849e-06 2.64321731817415e-06 2.18233790968482e-06 5.95055384274967e-06 1.07837136299679e-06 2.97284257898186e-05 1.37061508802113e-06 1.3924058299256e-06 -7.12274210266766e-06 1.70796952204975e-06 -5.03835959267849e-06 1.37061508802113e-06 2.21677318812982e-05 1.92080627184623e-06 -1.98963938984606e-05 5.3617546674472e-05 2.64321731817415e-06 1.3924058299256e-06 1.92080627184623e-06 8.5177628554281e-05 1254 1255 0 0 0 1295 1320 0 0 0 0 0 0 0 0 0 0 0 1032 0 2 29 0 0 2641 +1266 1293 0.999178510099672 0.0077326615388545 0.0397807855694916 -0.00579393193268968 -0.015357759604897 0.980659068633842 0.195120297063438 -0.0314149110307389 -0.0375025889095479 -0.195570951451721 0.979972223470313 0.0322734001569215 0.000124836674946329 -4.19350199043778e-05 -1.27085369061286e-06 -5.11417042662125e-06 -1.19733252708102e-05 -1.14170935456968e-05 -4.19350199043778e-05 7.51374505916645e-05 1.2513449602894e-06 3.445130928603e-06 3.25136517998303e-06 5.11196454504224e-05 -1.27085369061286e-06 1.2513449602894e-06 1.03175428512699e-05 1.78346083043864e-06 -6.05828451141129e-06 -4.32642687171642e-07 -5.11417042662125e-06 3.445130928603e-06 1.78346083043864e-06 2.44047209205983e-05 4.12088856120514e-06 4.31570715101273e-06 -1.19733252708102e-05 3.25136517998303e-06 -6.05828451141129e-06 4.12088856120514e-06 2.25734518937786e-05 1.27695532572146e-06 -1.14170935456968e-05 5.11196454504224e-05 -4.32642687171642e-07 4.31570715101273e-06 1.27695532572146e-06 7.47452261223881e-05 1354 1357 0 0 0 1396 1423 0 0 0 0 0 0 0 0 0 0 0 1001 0 2 30 0 0 2598 +1266 1316 0.998519750718933 0.00787817838819311 0.0538167420928013 -0.00752479421575852 -0.0185606991667713 0.979415188894907 0.201000965690203 -0.0319010518940325 -0.051125413158623 -0.201702310515367 0.978111634764725 0.0342109598052414 0.000159083244038623 -5.14328004288193e-05 8.5794610460965e-06 -1.83886102720229e-06 -7.93632910620806e-06 -3.65680783562666e-05 -5.14328004288193e-05 7.12163074743213e-05 -6.6501772460247e-06 -3.26453613107816e-06 -7.85946005975773e-06 3.67757385326185e-05 8.5794610460965e-06 -6.6501772460247e-06 1.49038701830347e-05 8.93404761666513e-07 -6.34841224297587e-06 -3.26124058682254e-06 -1.83886102720229e-06 -3.26453613107816e-06 8.93404761666513e-07 3.55281395454967e-05 2.96436038251926e-06 1.38740417010764e-06 -7.93632910620806e-06 -7.85946005975773e-06 -6.34841224297587e-06 2.96436038251926e-06 3.16213194454785e-05 -2.76646136971137e-06 -3.65680783562666e-05 3.67757385326185e-05 -3.26124058682254e-06 1.38740417010764e-06 -2.76646136971137e-06 6.91061650416774e-05 1253 1255 0 0 0 1294 1316 0 0 0 0 0 0 0 0 0 0 0 1017 0 3 30 0 0 2672 +1266 1315 0.998884852373765 0.00797018999942205 0.0465352314877072 -0.00868394598264109 -0.0171290426373967 0.979669205020005 0.199887079707014 -0.0309968670759973 -0.0439959952332895 -0.200461280068858 0.97871325095586 0.03199180246288 0.000148634226170668 -7.21834635445833e-05 1.47231277558518e-06 1.34038396384447e-05 5.01683164822183e-06 -4.90315608820339e-06 -7.21834635445833e-05 9.59001434738246e-05 -4.14696299961159e-06 1.50127094516512e-06 -5.94684652858846e-06 2.46253229765583e-05 1.47231277558518e-06 -4.14696299961159e-06 1.51148794008367e-05 9.65527776025743e-07 -5.70070666038903e-06 -4.16705189054462e-07 1.34038396384447e-05 1.50127094516512e-06 9.65527776025743e-07 2.81877900300045e-05 -6.47301241610795e-06 5.35234985038359e-06 5.01683164822183e-06 -5.94684652858846e-06 -5.70070666038903e-06 -6.47301241610795e-06 2.23587620531109e-05 1.95143354008774e-06 -4.90315608820339e-06 2.46253229765583e-05 -4.16705189054462e-07 5.35234985038359e-06 1.95143354008774e-06 7.47244917681566e-05 1241 1243 0 0 0 1281 1306 0 0 0 0 0 0 0 0 0 0 0 1020 0 2 30 0 0 2593 +1266 1313 0.999146230585953 0.00752052303389161 0.0406232893692452 -0.00972690797417094 -0.0149447851435534 0.982495623001123 0.185685228762677 -0.0350397759589666 -0.0385157539572283 -0.186133802725167 0.981769190889679 0.0380751275661392 0.000285915431102321 -0.000155728814921772 9.27031244803421e-06 -6.16256417187092e-06 -1.11095494251915e-05 1.58249872171449e-05 -0.000155728814921772 0.00012902418788994 -4.92455360116157e-06 4.89609200411415e-06 6.45207811114209e-06 2.47566622515987e-05 9.27031244803421e-06 -4.92455360116157e-06 1.2911593454111e-05 -7.68357723079083e-07 -6.3148282366316e-06 3.39616346601501e-07 -6.16256417187092e-06 4.89609200411415e-06 -7.68357723079083e-07 3.11032207905656e-05 3.89127257516188e-06 6.3175460431119e-06 -1.11095494251915e-05 6.45207811114209e-06 -6.3148282366316e-06 3.89127257516188e-06 2.24605680807536e-05 1.1186642675882e-06 1.58249872171449e-05 2.47566622515987e-05 3.39616346601501e-07 6.3175460431119e-06 1.1186642675882e-06 7.36384702043735e-05 1339 1343 0 0 0 1389 1421 0 0 3 0 0 0 0 0 0 0 0 1028 0 6 41 0 0 2600 +1266 1318 0.999277443118577 0.00842577027455176 0.0370620839899798 -0.0118540217999101 -0.0154466210776357 0.980987329281212 0.193456097569964 -0.0332272344464692 -0.0347274181545905 -0.193888798503152 0.980408659816569 0.0528117954004392 0.000176068181230612 -7.5456636158378e-05 3.16524636331009e-06 1.70260637949535e-07 -6.12364565854937e-06 -5.42412454421821e-06 -7.5456636158378e-05 8.56172974025578e-05 5.58129112203442e-08 -8.65975062075746e-07 3.96326314527017e-06 3.23922644933839e-05 3.16524636331009e-06 5.58129112203442e-08 1.4368541397471e-05 2.31524956366422e-06 -5.61310662227316e-06 -2.3978066690255e-06 1.70260637949535e-07 -8.65975062075746e-07 2.31524956366422e-06 2.89437464452486e-05 -1.6443428989706e-06 2.30770322043853e-06 -6.12364565854937e-06 3.96326314527017e-06 -5.61310662227316e-06 -1.6443428989706e-06 2.83727917877649e-05 -1.61688788187008e-06 -5.42412454421821e-06 3.23922644933839e-05 -2.3978066690255e-06 2.30770322043853e-06 -1.61688788187008e-06 6.35353897706291e-05 1346 1348 0 0 0 1398 1424 0 0 1 0 0 0 0 0 0 0 0 1034 0 7 47 0 0 2608 +1266 1309 0.998863623509129 0.00694309208647718 0.0471514061560443 -0.00757796992908578 -0.0162846614542048 0.979508476853253 0.200743501946992 -0.0315475413636495 -0.0447914214056162 -0.201283226437025 0.978508452351622 0.0343260054884659 0.000130497876761463 -5.1011610878209e-05 1.8218184436831e-06 -8.37528236214472e-07 -7.3459251108187e-06 1.1183267143282e-05 -5.1011610878209e-05 7.87567436792191e-05 -5.71752923520614e-06 3.7661293829181e-06 2.76978748056486e-07 2.56764214476795e-05 1.8218184436831e-06 -5.71752923520614e-06 1.34506050799186e-05 7.26069297699574e-07 -6.46098808399072e-06 -2.31299217572667e-06 -8.37528236214472e-07 3.7661293829181e-06 7.26069297699574e-07 2.98994268098802e-05 6.62922577483034e-06 3.47181445311435e-06 -7.3459251108187e-06 2.76978748056486e-07 -6.46098808399072e-06 6.62922577483034e-06 2.69985494235473e-05 -9.32458065541092e-07 1.1183267143282e-05 2.56764214476795e-05 -2.31299217572667e-06 3.47181445311435e-06 -9.32458065541092e-07 7.48799348370962e-05 1349 1356 0 0 0 1394 1429 0 0 6 0 0 0 0 0 0 0 0 927 0 5 37 0 0 2468 +1266 1305 0.99881601002965 0.00731489277926365 0.0480943910667119 -0.00809866135591865 -0.017023058467385 0.978680915895704 0.20467994611579 -0.0304592229667521 -0.0455718508387133 -0.205256320743539 0.977646689354574 0.0303664578007999 0.000126552276104062 -7.60769219807147e-05 8.0330947805982e-06 -6.11138694438525e-06 -7.31363095216955e-07 -5.55209197763915e-06 -7.60769219807147e-05 8.64777756787186e-05 -2.49757591618398e-06 1.63521806644006e-06 -4.20978947632976e-06 2.94065877274163e-05 8.0330947805982e-06 -2.49757591618398e-06 1.58085475250356e-05 -3.02886138553782e-06 -7.61985011292929e-06 1.54065153930649e-06 -6.11138694438525e-06 1.63521806644006e-06 -3.02886138553782e-06 3.70903248040626e-05 1.043273724465e-05 4.63676892672883e-06 -7.31363095216955e-07 -4.20978947632976e-06 -7.61985011292929e-06 1.043273724465e-05 2.83615486285528e-05 2.6328553242458e-06 -5.55209197763915e-06 2.94065877274163e-05 1.54065153930649e-06 4.63676892672883e-06 2.6328553242458e-06 7.33353963502757e-05 1248 1250 0 0 0 1286 1314 0 0 0 0 0 0 0 0 0 0 0 921 0 2 28 0 0 2529 +1266 1296 0.999206011115483 0.00787440846741761 0.0390556147304384 -0.0087201025349508 -0.0154336749905485 0.980237334413239 0.19722213338952 -0.033321233417051 -0.0367307640401108 -0.197668312872134 0.979580567926556 0.0309062692944592 0.000190969313681812 -9.3157456586485e-05 8.93824247628722e-06 -4.58986260778591e-06 -6.7586494475618e-06 -1.51328863609822e-05 -9.3157456586485e-05 9.93865947969489e-05 -5.53246325347406e-06 1.71167974498321e-06 3.62280207541674e-06 4.80910399403479e-05 8.93824247628722e-06 -5.53246325347406e-06 1.13494619489151e-05 3.43627557530772e-06 -6.48024117257408e-06 -3.28469326670111e-07 -4.58986260778591e-06 1.71167974498321e-06 3.43627557530772e-06 2.38551475522752e-05 3.62399629284139e-06 -2.58793826580107e-06 -6.7586494475618e-06 3.62280207541674e-06 -6.48024117257408e-06 3.62399629284139e-06 2.32271885592203e-05 2.45243721888667e-06 -1.51328863609822e-05 4.80910399403479e-05 -3.28469326670111e-07 -2.58793826580107e-06 2.45243721888667e-06 7.12049129811371e-05 1350 1351 0 0 0 1394 1415 0 0 0 0 0 0 0 0 0 0 0 975 0 4 35 0 0 2593 +1266 1295 0.998820401772399 0.00736542999419601 0.047995368987274 -0.0082563586282959 -0.0166547941321094 0.980434388626953 0.19614032586419 -0.0317884774706978 -0.0456116524107715 -0.196708312073217 0.979400539680097 0.0309702683811002 0.000138779344718399 -3.56246469938081e-06 8.81371160664381e-06 3.09771698599162e-06 -7.34494863532729e-07 2.48899765984718e-05 -3.56246469938081e-06 6.36414546786936e-05 -5.92221082499689e-07 9.19847204069987e-07 1.15279767453953e-06 4.6395671666339e-05 8.81371160664381e-06 -5.92221082499689e-07 1.20195999712494e-05 2.00765264772383e-06 -5.25780259390986e-06 2.30145101272485e-06 3.09771698599162e-06 9.19847204069987e-07 2.00765264772383e-06 2.28417103983825e-05 1.03205530795587e-06 2.64871422764538e-06 -7.34494863532729e-07 1.15279767453953e-06 -5.25780259390986e-06 1.03205530795587e-06 1.94581021717901e-05 3.34192874154976e-06 2.48899765984718e-05 4.6395671666339e-05 2.30145101272485e-06 2.64871422764538e-06 3.34192874154976e-06 6.56367158915838e-05 1346 1347 0 0 0 1392 1413 0 0 0 0 0 0 0 0 0 0 0 895 0 3 34 0 0 2417 +1266 1303 0.99920451555086 0.00759930799571393 0.0391482645944634 -0.00667567912772721 -0.014736427913104 0.982553149004658 0.185397268246846 -0.0315490141103421 -0.0370563597123858 -0.185826693182162 0.981883529908639 0.02856971290103 0.000215500196475965 -0.000103246663578984 3.62301396588053e-07 -5.63193010479511e-06 -2.07926476168289e-05 -7.97733785639777e-06 -0.000103246663578984 0.000104548903570371 -9.17162777486478e-07 4.33280761679541e-06 5.08253133770417e-06 4.90943605509687e-05 3.62301396588053e-07 -9.17162777486478e-07 1.24273464766393e-05 7.16196264845752e-07 -6.26775352914136e-06 -6.34400562494824e-07 -5.63193010479511e-06 4.33280761679541e-06 7.16196264845752e-07 2.97752793481107e-05 7.71895507916522e-06 6.16243930078643e-06 -2.07926476168289e-05 5.08253133770417e-06 -6.26775352914136e-06 7.71895507916522e-06 2.8365778441629e-05 -4.97806070159172e-06 -7.97733785639777e-06 4.90943605509687e-05 -6.34400562494824e-07 6.16243930078643e-06 -4.97806070159172e-06 8.82035551185065e-05 1346 1354 0 0 0 1392 1429 0 0 6 0 0 0 0 0 0 0 0 925 0 3 34 0 0 2553 +1266 1317 0.998830092745497 0.0084913484167365 0.0476061217501298 -0.00679522555488927 -0.01762784849388 0.980657655818632 0.194935427877494 -0.032912769819349 -0.0450300431212253 -0.195546565007853 0.979660061516305 0.0377841093208831 0.000237609489766747 -0.000126181799086364 8.88316056888186e-07 2.84425120345298e-06 -1.08372668526857e-05 -2.39931603933271e-05 -0.000126181799086364 0.000107861629304941 -5.87558888751751e-07 -5.48322559576112e-06 2.29429265930177e-06 4.05743423601916e-05 8.88316056888186e-07 -5.87558888751751e-07 1.47430097117183e-05 1.99784485704345e-06 -5.67569540499785e-06 -1.83953874465074e-06 2.84425120345298e-06 -5.48322559576112e-06 1.99784485704345e-06 2.6189667804765e-05 -6.72190917340495e-06 9.20789246601536e-07 -1.08372668526857e-05 2.29429265930177e-06 -5.67569540499785e-06 -6.72190917340495e-06 2.33377038620044e-05 -3.71851784610195e-06 -2.39931603933271e-05 4.05743423601916e-05 -1.83953874465074e-06 9.20789246601536e-07 -3.71851784610195e-06 7.7219602651009e-05 1344 1347 0 0 0 1387 1411 0 0 0 0 0 0 0 0 0 0 0 931 0 3 34 0 0 2665 +1266 1307 0.999343086030615 0.00856072750064755 0.0352152005172026 -0.00978850321406566 -0.0154161716414795 0.979819037229681 0.199291233962314 -0.0315760093354966 -0.0327984459193965 -0.19970320034231 0.979307354061181 0.0484640625895275 0.000222835398509675 -7.96472070806311e-05 7.07863754851496e-06 -1.7023482353972e-05 -3.83749774938739e-05 -3.36534746389691e-05 -7.96472070806311e-05 7.42489184962397e-05 -4.67261839954594e-06 8.80205342855649e-06 1.04754373736523e-05 3.73880734261951e-05 7.07863754851496e-06 -4.67261839954594e-06 1.34924577998504e-05 3.67194553336001e-06 -5.14706952128222e-06 -2.23328743146394e-06 -1.7023482353972e-05 8.80205342855649e-06 3.67194553336001e-06 2.90368120621702e-05 8.46600002735798e-06 3.58743216657579e-06 -3.83749774938739e-05 1.04754373736523e-05 -5.14706952128222e-06 8.46600002735798e-06 3.54928965142956e-05 2.37079900284607e-06 -3.36534746389691e-05 3.73880734261951e-05 -2.23328743146394e-06 3.58743216657579e-06 2.37079900284607e-06 5.32965106771595e-05 1349 1352 0 0 0 1399 1427 0 0 2 0 0 0 0 0 0 0 0 1007 0 8 43 0 0 2477 +1266 1294 0.998968009740142 0.00713359931729541 0.0448556270338575 -0.00799669169160896 -0.0155621868173047 0.981568093834552 0.190478070935915 -0.0323482045383176 -0.0426700580885889 -0.1909795510697 0.980666139527583 0.030293623734002 0.00015566094464829 -4.96137618358322e-05 4.60671733522747e-07 -4.78671391217893e-06 -1.15504107586018e-05 -8.14808068957372e-06 -4.96137618358322e-05 7.84917633199227e-05 -7.80783975818503e-07 3.61303487757886e-06 6.17311226148623e-06 5.50753679400036e-05 4.60671733522747e-07 -7.80783975818503e-07 1.210016673229e-05 1.18514883334114e-06 -3.74643646955912e-06 -1.91667630056992e-06 -4.78671391217893e-06 3.61303487757886e-06 1.18514883334114e-06 2.413823912932e-05 3.75402991133672e-06 1.64180993860232e-06 -1.15504107586018e-05 6.17311226148623e-06 -3.74643646955912e-06 3.75402991133672e-06 2.42021378438147e-05 -1.7889140041548e-06 -8.14808068957372e-06 5.50753679400036e-05 -1.91667630056992e-06 1.64180993860232e-06 -1.7889140041548e-06 7.55287415693249e-05 1348 1355 0 0 0 1397 1433 0 0 5 0 0 0 0 0 0 0 0 1024 0 6 38 0 0 2449 +1266 1306 0.999336281336495 0.00886515532033682 0.0353327868373275 -0.00747461938204588 -0.0155546437166397 0.98091281199935 0.193824942446466 -0.0323310452341354 -0.0329400950726333 -0.194245886125482 0.980399656191256 0.0328114982677049 0.000316440714541671 -0.000190663857210201 1.04897852777156e-05 -2.81726024993797e-05 -2.1796542600056e-05 -1.37794704201652e-05 -0.000190663857210201 0.000165518031459004 -5.72657459775214e-06 2.05123499916993e-05 1.07578927295987e-05 4.62853092176656e-05 1.04897852777156e-05 -5.72657459775214e-06 1.43806098157551e-05 -1.24150399599901e-06 -7.47632844459425e-06 -1.04857627597959e-06 -2.81726024993797e-05 2.05123499916993e-05 -1.24150399599901e-06 3.35320442840497e-05 7.04932828794373e-06 6.77341391386141e-06 -2.1796542600056e-05 1.07578927295987e-05 -7.47632844459425e-06 7.04932828794373e-06 2.56470873698061e-05 -2.32512147717782e-06 -1.37794704201652e-05 4.62853092176656e-05 -1.04857627597959e-06 6.77341391386141e-06 -2.32512147717782e-06 7.27061665417784e-05 1345 1351 0 0 0 1393 1428 0 0 5 0 0 0 0 0 0 0 0 990 0 3 36 0 0 2644 +1266 1304 0.999192662509906 0.00846573478939776 0.0392728216562159 -0.00698272439150601 -0.0162839902057732 0.978987246172953 0.203270272036214 -0.0320298497532234 -0.0367267593090329 -0.20374568256818 0.978334729009189 0.0296275282613779 0.000113673962198032 -5.2004738236446e-05 3.63300415073157e-06 -1.13662146438845e-05 -9.91947548494357e-06 4.54497862494695e-06 -5.2004738236446e-05 6.79501235224394e-05 -2.00436257027101e-06 5.59847538150175e-06 9.36183633564425e-07 3.29528649471484e-05 3.63300415073157e-06 -2.00436257027101e-06 1.37364480894565e-05 6.63555602977151e-07 -5.65391076230798e-06 3.60490900647517e-08 -1.13662146438845e-05 5.59847538150175e-06 6.63555602977151e-07 2.94928229714314e-05 8.35560399417386e-06 -1.82208135933871e-06 -9.91947548494357e-06 9.36183633564425e-07 -5.65391076230798e-06 8.35560399417386e-06 2.9984450185371e-05 -7.88505919825575e-06 4.54497862494695e-06 3.29528649471484e-05 3.60490900647517e-08 -1.82208135933871e-06 -7.88505919825575e-06 8.35380674712103e-05 1349 1356 0 0 0 1394 1429 0 0 6 0 0 0 0 0 0 0 0 1012 0 5 38 0 0 2551 +1267 1269 0.999678660231339 -0.003231930880489 -0.0251422135234602 -0.00297481012529999 0.00348530112537954 0.999943521951115 0.0100401984076667 0.0031816395684161 0.0251083443130158 -0.010124600277721 0.999633464583432 0.0103757389124072 7.78075439846321e-05 1.29472371267848e-05 -6.37675705609435e-06 4.18050111810555e-06 -7.69126333794009e-06 2.80690107170205e-07 1.29472371267848e-05 0.000113224981854321 -1.89855951537628e-05 3.32013452725401e-05 6.44027528474928e-06 1.04752630083191e-05 -6.37675705609435e-06 -1.89855951537628e-05 1.48923613234164e-05 -3.45836554520636e-06 -7.597421085159e-06 -1.46636560538029e-06 4.18050111810555e-06 3.32013452725401e-05 -3.45836554520636e-06 3.57496302433293e-05 -7.66540819946473e-06 -6.12564591490682e-06 -7.69126333794009e-06 6.44027528474928e-06 -7.597421085159e-06 -7.66540819946473e-06 1.85318080964457e-05 8.06068158348861e-06 2.80690107170205e-07 1.04752630083191e-05 -1.46636560538029e-06 -6.12564591490682e-06 8.06068158348861e-06 8.07757848976584e-05 1526 1539 0 0 0 1527 1613 0 0 0 0 0 0 0 0 0 0 0 763 0 0 0 0 0 3466 +1267 1271 0.999037377684454 0.00548450986047346 -0.0435228461955276 -0.00340065991566218 -0.00498741527808301 0.999921183329672 0.0115218408873261 -0.00374320786899784 0.0435826075196646 -0.0112936831981105 0.998985990413083 0.0154436856692645 0.000107266624992839 -7.02934110539881e-06 -1.06780494383652e-07 6.74545785462154e-06 -6.32742766238652e-06 -1.38430377675377e-05 -7.02934110539881e-06 4.90214780966826e-05 -3.05535438478039e-06 7.78853911485019e-06 4.04457149417152e-06 3.80242252107676e-05 -1.06780494383652e-07 -3.05535438478039e-06 1.13746841141833e-05 2.36365215960243e-06 -6.45014360113485e-06 -2.1794160067282e-06 6.74545785462154e-06 7.78853911485019e-06 2.36365215960243e-06 2.38238610576796e-05 -1.60493531845896e-06 2.41372724013129e-06 -6.32742766238652e-06 4.04457149417152e-06 -6.45014360113485e-06 -1.60493531845896e-06 1.72638796766672e-05 4.99465805967429e-06 -1.38430377675377e-05 3.80242252107676e-05 -2.1794160067282e-06 2.41372724013129e-06 4.99465805967429e-06 6.21942682726338e-05 1334 1334 0 0 0 1358 1412 0 0 0 0 0 0 0 0 0 0 0 801 0 0 2 0 0 3304 +1266 1297 0.999184902548715 0.00800049136855821 0.0395666861965407 -0.0118696948218862 -0.0159834644733006 0.978466736397033 0.205784777444712 -0.0341894167710139 -0.0370683069770476 -0.206249455520252 0.977797066223588 0.0455754660176128 8.63349618117022e-05 -3.16000732808307e-05 6.5805931081729e-06 -5.97871507174186e-06 -3.57348708242136e-06 -3.03324116922055e-06 -3.16000732808307e-05 5.65687679704375e-05 -2.30277196993184e-06 -1.33327941382536e-06 -1.27480387102064e-06 3.64415646647238e-05 6.5805931081729e-06 -2.30277196993184e-06 1.14894580055354e-05 1.61714141701555e-06 -4.6090261774621e-06 9.87132440748451e-07 -5.97871507174186e-06 -1.33327941382536e-06 1.61714141701555e-06 2.57496006124651e-05 1.20305061099759e-05 -2.89169568091684e-06 -3.57348708242136e-06 -1.27480387102064e-06 -4.6090261774621e-06 1.20305061099759e-05 2.87041622693589e-05 -3.26355532046021e-06 -3.03324116922055e-06 3.64415646647238e-05 9.87132440748451e-07 -2.89169568091684e-06 -3.26355532046021e-06 6.28662821552627e-05 1343 1346 0 0 0 1397 1424 0 0 2 0 0 0 0 0 0 0 0 1006 0 9 46 0 0 2542 +1267 1309 0.999105925039125 -0.00263050851168225 0.0421951534738747 -0.00671635435417544 -0.00452033112007677 0.985694192495337 0.168483012459804 -0.0262686672365013 -0.0420347137289971 -0.168523112082395 0.98480101722926 0.0305216850575068 0.000100310250036086 -2.29844865999441e-05 3.94749017747001e-06 8.26359400594564e-06 -3.15004224640572e-06 1.08466858524714e-05 -2.29844865999441e-05 5.96912213030315e-05 -2.66589438396286e-06 2.40962254920234e-06 -2.7463227500523e-06 1.12792719797556e-05 3.94749017747001e-06 -2.66589438396286e-06 1.40918699997002e-05 1.32257076726493e-06 -8.33544726813231e-06 -3.5119693917214e-06 8.26359400594564e-06 2.40962254920234e-06 1.32257076726493e-06 3.30268068658488e-05 7.95835865444613e-06 -2.59579989895612e-07 -3.15004224640572e-06 -2.7463227500523e-06 -8.33544726813231e-06 7.95835865444613e-06 3.3531925613913e-05 -4.52621735714218e-06 1.08466858524714e-05 1.12792719797556e-05 -3.5119693917214e-06 -2.59579989895612e-07 -4.52621735714218e-06 7.29950410530607e-05 1368 1386 0 0 0 1404 1451 0 0 0 0 0 0 0 0 0 0 0 938 0 0 19 0 0 2518 +1267 1308 0.999001128742142 -0.00162990205061249 0.0446552146029121 -0.00542499062596601 -0.00558393226048994 0.986947765643813 0.160943864720576 -0.03014336964135 -0.0443346870118307 -0.161032454213398 0.985952830625062 0.0163441752156853 0.000167809351060462 -6.4631353122441e-05 8.91484161715511e-06 1.06658216047132e-06 -3.73666286569511e-06 -2.94720789384126e-05 -6.4631353122441e-05 7.85372120017937e-05 -5.0024894655588e-06 2.93500228367897e-06 -2.02314627678243e-07 2.11814540113634e-05 8.91484161715511e-06 -5.0024894655588e-06 1.4100861938666e-05 6.86100960917661e-07 -6.25908542412242e-06 -4.19410198459922e-06 1.06658216047132e-06 2.93500228367897e-06 6.86100960917661e-07 3.26672877211135e-05 9.29655596834517e-06 -5.95139243217748e-06 -3.73666286569511e-06 -2.02314627678243e-07 -6.25908542412242e-06 9.29655596834517e-06 2.83857346101002e-05 -5.08068032027937e-06 -2.94720789384126e-05 2.11814540113634e-05 -4.19410198459922e-06 -5.95139243217748e-06 -5.08068032027937e-06 8.2485029289823e-05 1232 1235 0 0 0 1266 1299 0 0 0 0 0 0 0 0 0 0 0 1046 0 0 17 0 0 2658 +1267 1312 0.999182479465823 -0.00148372163303668 0.0404001398344947 -0.00528812796076064 -0.00530040005788967 0.98589215250259 0.167297846349069 -0.0221328079641862 -0.0400784042566242 -0.167375213827872 0.985078301105205 0.0264630966518396 0.00015268730958001 -9.15936599397201e-05 7.73044525137125e-06 1.41985100309643e-06 6.68485752674781e-07 -1.40434146609336e-05 -9.15936599397201e-05 9.40413228688173e-05 -6.31015200406768e-06 -3.74143312133204e-06 -1.18942970485383e-06 3.38914344078007e-05 7.73044525137125e-06 -6.31015200406768e-06 1.71478415961503e-05 9.45129489307293e-07 -9.41191001985049e-06 1.09867573844164e-07 1.41985100309643e-06 -3.74143312133204e-06 9.45129489307293e-07 2.70220220858053e-05 1.99166368595292e-06 -4.25869532796674e-06 6.68485752674781e-07 -1.18942970485383e-06 -9.41191001985049e-06 1.99166368595292e-06 2.26692465208483e-05 -2.47045887284587e-06 -1.40434146609336e-05 3.38914344078007e-05 1.09867573844164e-07 -4.25869532796674e-06 -2.47045887284587e-06 7.85010867109521e-05 1368 1386 0 0 0 1403 1453 0 0 0 0 0 0 0 0 0 0 0 1038 0 0 17 0 0 2548 +1266 1302 0.999055247398218 0.00763189778413425 0.0427827860511459 -0.0078109022023359 -0.0161488373288025 0.979162648799199 0.202434488784555 -0.0271423162978255 -0.0403463467864622 -0.202934130526998 0.978360828615004 0.0360146521773851 0.00018516934432071 -5.92403966727202e-05 7.07269590613107e-06 -2.23241103008897e-06 -1.3049813722741e-05 -5.37457720890897e-07 -5.92403966727202e-05 6.84174451055279e-05 -5.22424315021111e-06 4.71255811343019e-06 -2.21939018080193e-06 3.37149530693413e-05 7.07269590613107e-06 -5.22424315021111e-06 1.52171688051491e-05 -3.07669167859688e-06 -7.3577637450642e-06 -1.69516880684006e-06 -2.23241103008897e-06 4.71255811343019e-06 -3.07669167859688e-06 4.03085896967029e-05 8.02686552350159e-06 -4.54838958323768e-06 -1.3049813722741e-05 -2.21939018080193e-06 -7.3577637450642e-06 8.02686552350159e-06 2.87080351971891e-05 -8.54853517438181e-06 -5.37457720890897e-07 3.37149530693413e-05 -1.69516880684006e-06 -4.54838958323768e-06 -8.54853517438181e-06 6.61745933111118e-05 1352 1354 0 0 0 1394 1421 0 0 0 0 0 0 0 0 0 0 0 922 0 2 29 0 0 2415 +1267 1311 0.999114801243976 -0.00272613596958901 0.0419783529677607 -0.0102029674507667 -0.0043814359209346 0.985726792116322 0.168295853553602 -0.0294829032909927 -0.0418379845891426 -0.168330803736987 0.984842283596099 0.0232844772676553 0.000192057809423812 -7.01658758457617e-05 1.00775565996207e-05 -2.52262262302523e-06 3.64098002056313e-06 2.35549659683996e-05 -7.01658758457617e-05 0.000104025958340195 -4.05021668207585e-06 -1.40593252303909e-06 -2.94906385258503e-06 1.33127127188593e-05 1.00775565996207e-05 -4.05021668207585e-06 1.67561071190791e-05 3.31830182057268e-06 -4.97132224767381e-06 -1.97967774025295e-06 -2.52262262302523e-06 -1.40593252303909e-06 3.31830182057268e-06 2.45759495374602e-05 -3.0189647117436e-06 -3.69991952002279e-06 3.64098002056313e-06 -2.94906385258503e-06 -4.97132224767381e-06 -3.0189647117436e-06 2.58766174486805e-05 3.00695481230611e-07 2.35549659683996e-05 1.33127127188593e-05 -1.97967774025295e-06 -3.69991952002279e-06 3.00695481230611e-07 9.37842113213858e-05 1317 1317 0 0 0 1355 1385 0 0 0 0 0 0 0 0 0 0 0 938 0 0 20 0 0 2595 +1267 1315 0.999002560643421 -0.00097408114627749 0.04464230049861 -0.00920419201109754 -0.00643834350397322 0.986172855523531 0.16559482709762 -0.0299803518610239 -0.0441863277588506 -0.165717078765244 0.985182936436021 0.0177080154134743 0.000135713231865852 -5.63314641262459e-05 7.02546041132629e-07 8.53605662829483e-06 -3.42923131432554e-06 -1.7455184830639e-05 -5.63314641262459e-05 9.08467957195942e-05 -1.3448708880017e-06 3.09969100333963e-06 -1.54593567364682e-06 2.19881583224085e-05 7.02546041132629e-07 -1.3448708880017e-06 1.43192740004098e-05 5.31905499309186e-06 -7.26827271954343e-06 -4.58014964449325e-06 8.53605662829483e-06 3.09969100333963e-06 5.31905499309186e-06 2.65482873356971e-05 -6.78723717027022e-06 1.41546304064205e-06 -3.42923131432554e-06 -1.54593567364682e-06 -7.26827271954343e-06 -6.78723717027022e-06 2.45399361136454e-05 -2.2407526455001e-07 -1.7455184830639e-05 2.19881583224085e-05 -4.58014964449325e-06 1.41546304064205e-06 -2.2407526455001e-07 8.83482593432846e-05 1217 1220 0 0 0 1252 1285 0 0 0 0 0 0 0 0 0 0 0 1044 0 0 17 0 0 2581 +1267 1313 0.999172160305699 -0.00250270691487829 0.0406045628980288 -0.0067646901203138 -0.0042820784932018 0.986091264080399 0.166149579319658 -0.0263420233744735 -0.0404556284566167 -0.166185906028218 0.985264221802335 0.0271600782335241 0.000149543825042838 -5.75964805377703e-05 1.08216796968644e-05 -3.72333761762584e-06 -3.11090900493062e-06 -5.33223365420375e-06 -5.75964805377703e-05 5.64190267873195e-05 -5.41985294467706e-06 2.91685468655872e-06 8.73872103911312e-07 1.83585735143231e-05 1.08216796968644e-05 -5.41985294467706e-06 1.42166098839713e-05 5.12997745716804e-07 -6.26287057312087e-06 -2.63197170610867e-06 -3.72333761762584e-06 2.91685468655872e-06 5.12997745716804e-07 2.97953404538026e-05 7.37212737839504e-07 4.00747503058713e-06 -3.11090900493062e-06 8.73872103911312e-07 -6.26287057312087e-06 7.37212737839504e-07 2.37875043741568e-05 3.06133306078283e-06 -5.33223365420375e-06 1.83585735143231e-05 -2.63197170610867e-06 4.00747503058713e-06 3.06133306078283e-06 5.02664050822937e-05 1366 1382 0 0 0 1403 1450 0 0 0 0 0 0 0 0 0 0 0 1049 0 0 19 0 0 2607 +1267 1316 0.998854938204034 -0.000466392478523845 0.0478392611091719 -0.00760450544466909 -0.00775928213281002 0.985133822700681 0.171613358780507 -0.028987900312385 -0.0472081133514039 -0.171788049203661 0.984002164725567 0.0254527229518543 8.19687083042207e-05 -2.63489421331891e-05 6.93155140495037e-06 -1.9865451007005e-06 -4.3589791764586e-06 -1.53216674552666e-05 -2.63489421331891e-05 6.44422775505829e-05 -4.33382149581449e-07 -1.70252298829625e-06 -5.46513900479927e-06 9.29013051711687e-06 6.93155140495037e-06 -4.33382149581449e-07 1.5348818160117e-05 3.24668337178791e-06 -8.54584106074554e-06 -2.18063098378725e-06 -1.9865451007005e-06 -1.70252298829625e-06 3.24668337178791e-06 2.96540343871196e-05 -1.78788202862026e-06 -4.2773250868099e-06 -4.3589791764586e-06 -5.46513900479927e-06 -8.54584106074554e-06 -1.78788202862026e-06 2.89023194400605e-05 -2.85037195906879e-06 -1.53216674552666e-05 9.29013051711687e-06 -2.18063098378725e-06 -4.2773250868099e-06 -2.85037195906879e-06 8.01195721810556e-05 1229 1232 0 0 0 1263 1296 0 0 0 0 0 0 0 0 0 0 0 1036 0 0 19 0 0 2652 +1267 1270 0.998932050348868 -0.0006871909756289 -0.0461983393031604 0.000940404561523701 0.00130235931718719 0.999910875371728 0.0132870302759587 -0.00112495148515883 0.0461850911660447 -0.013333007234241 0.998843915870781 0.00696660002742772 7.94182986482136e-05 6.03728043967896e-06 -2.08617026659301e-06 9.72192564493006e-06 -7.5613198303355e-06 1.01861719590889e-06 6.03728043967896e-06 5.35253617012216e-05 -3.79621000911607e-06 2.64642654842991e-06 9.92270921187258e-07 3.20003498616073e-05 -2.08617026659301e-06 -3.79621000911607e-06 1.07754610430994e-05 2.54575218315309e-06 -6.14957144943137e-06 -2.42018711282647e-06 9.72192564493006e-06 2.64642654842991e-06 2.54575218315309e-06 1.98527077244089e-05 -5.49812935257931e-06 -3.24658645018981e-06 -7.5613198303355e-06 9.92270921187258e-07 -6.14957144943137e-06 -5.49812935257931e-06 1.69293711867862e-05 4.03287972470718e-06 1.01861719590889e-06 3.20003498616073e-05 -2.42018711282647e-06 -3.24658645018981e-06 4.03287972470718e-06 6.3649167738751e-05 1416 1428 0 0 0 1419 1505 0 0 0 0 0 0 0 0 0 0 0 793 0 0 0 0 0 3438 +1267 1310 0.998774874348736 -0.00175334211585963 0.0494537780264802 -0.0117757715730927 -0.00668322195303053 0.985436399023475 0.169913030765665 -0.0343964687140659 -0.0490314686093957 -0.170035376528157 0.984217397638822 0.00972601473677939 0.000102593332655702 -5.10286762241685e-05 4.68188085965498e-06 2.19692962217815e-06 3.68403896906887e-06 7.88107928964969e-06 -5.10286762241685e-05 7.59964796726743e-05 -4.28433054327248e-06 5.42194538750334e-06 3.01960371578917e-06 -2.14141849377094e-06 4.68188085965498e-06 -4.28433054327248e-06 1.57428249045175e-05 2.4866939581476e-06 -3.06656957695671e-06 -3.05877304778965e-06 2.19692962217815e-06 5.42194538750334e-06 2.4866939581476e-06 2.59295117936025e-05 1.95559802903878e-06 5.3161599420971e-06 3.68403896906887e-06 3.01960371578917e-06 -3.06656957695671e-06 1.95559802903878e-06 3.012671520769e-05 -4.88626134516883e-06 7.88107928964969e-06 -2.14141849377094e-06 -3.05877304778965e-06 5.3161599420971e-06 -4.88626134516883e-06 7.85131983781473e-05 1357 1368 0 0 0 1402 1434 0 0 0 0 0 0 0 0 0 0 0 1031 0 4 38 0 0 2517 +1267 1317 0.999257402322033 -0.000568600785225884 0.038526881495513 -0.00826783323070651 -0.00588506831571344 0.985907234379544 0.167189387130276 -0.0270295077632976 -0.0380789952013134 -0.167291966009205 0.985171755702138 0.0430742140066748 0.000227731535394556 -0.000106373950838384 -4.92210598097899e-07 -2.9475631317399e-06 -2.67178656108373e-05 3.37869009307832e-05 -0.000106373950838384 9.9765402474813e-05 1.92153707095214e-07 -2.22073985898432e-06 1.18693400869403e-05 5.97523303520922e-06 -4.92210598097899e-07 1.92153707095214e-07 1.45123961641365e-05 3.6197090995154e-06 -7.01963770354596e-06 -3.08134877786939e-06 -2.9475631317399e-06 -2.22073985898432e-06 3.6197090995154e-06 2.71068408351083e-05 -3.78017101725251e-06 1.42796429512268e-06 -2.67178656108373e-05 1.18693400869403e-05 -7.01963770354596e-06 -3.78017101725251e-06 2.90423071951516e-05 -1.43396228355255e-05 3.37869009307832e-05 5.97523303520922e-06 -3.08134877786939e-06 1.42796429512268e-06 -1.43396228355255e-05 9.27832209185907e-05 1314 1315 0 0 0 1352 1382 0 0 0 0 0 0 0 0 0 0 0 942 0 0 19 0 0 2639 +1267 1293 0.999146057678844 -0.00208716483751932 0.0412649871896879 -0.00635960547883601 -0.00499284125869269 0.98530561382458 0.170727616108038 -0.0261893210762901 -0.0410149602095331 -0.170787854101833 0.984453798778948 0.0261996738835199 0.000135621175461049 -1.98914134168575e-06 2.63043417194716e-06 6.17682948782403e-06 -1.31722188706087e-05 -1.54328355854539e-05 -1.98914134168575e-06 8.93627328116156e-05 1.16790644125323e-05 -4.41691095716679e-06 -2.39572071106119e-06 6.61382961301921e-06 2.63043417194716e-06 1.16790644125323e-05 1.51548305149985e-05 5.44614116558228e-07 -5.51759558461526e-06 1.2493223885565e-06 6.17682948782403e-06 -4.41691095716679e-06 5.44614116558228e-07 3.14501103761494e-05 6.5582897108467e-06 -7.35661684605098e-07 -1.31722188706087e-05 -2.39572071106119e-06 -5.51759558461526e-06 6.5582897108467e-06 3.04164919709413e-05 5.86691904866676e-06 -1.54328355854539e-05 6.61382961301921e-06 1.2493223885565e-06 -7.35661684605098e-07 5.86691904866676e-06 9.17144074513229e-05 1327 1329 0 0 0 1360 1393 0 0 0 0 0 0 0 0 0 0 0 1051 0 0 15 0 0 2588 +1267 1295 0.999367526026118 -0.00202521006619251 0.0355027667742185 -0.0104460392235767 -0.00388070302201046 0.98620305744287 0.165494621164526 -0.0276731110176495 -0.0353480985130985 -0.165527725818132 0.98557145043725 0.0419434287074739 9.12095081903797e-05 -2.67073046707151e-06 5.23373918125589e-06 3.4536652733047e-06 4.21988391742287e-06 -5.19437025632852e-06 -2.67073046707151e-06 5.96740155453818e-05 -2.70981714736906e-06 2.47746351888772e-06 5.68265851334896e-07 2.69601883828427e-05 5.23373918125589e-06 -2.70981714736906e-06 1.25944227189866e-05 1.48883807182153e-06 -4.40471951034891e-06 3.95195414244595e-07 3.4536652733047e-06 2.47746351888772e-06 1.48883807182153e-06 3.26989407462097e-05 1.52069344911085e-05 -3.4531984926672e-06 4.21988391742287e-06 5.68265851334896e-07 -4.40471951034891e-06 1.52069344911085e-05 3.47672882159327e-05 -1.78427097555983e-06 -5.19437025632852e-06 2.69601883828427e-05 3.95195414244595e-07 -3.4531984926672e-06 -1.78427097555983e-06 6.57717417279524e-05 1316 1316 0 0 0 1356 1386 0 0 0 0 0 0 0 0 0 0 0 907 0 0 20 0 0 2490 +1267 1305 0.999222951015512 -0.00156612740851662 0.0393832630541431 -0.00953089579649366 -0.00494126841641725 0.986349326955067 0.16459219022093 -0.0269276443606796 -0.0391034273470812 -0.164658897300529 0.985575146556307 0.0322523658637771 9.7991792707281e-05 -3.4547627053186e-05 7.21092831502288e-06 -1.2502041164856e-06 -2.95967066322718e-06 -2.15349838764287e-05 -3.4547627053186e-05 5.13764845422843e-05 -2.5818706058968e-06 -1.23795046421892e-06 -8.46448166625419e-07 2.6210115675535e-05 7.21092831502288e-06 -2.5818706058968e-06 1.75889617231415e-05 -2.7880009384144e-06 -7.74144351220777e-06 -1.25865270369605e-06 -1.2502041164856e-06 -1.23795046421892e-06 -2.7880009384144e-06 3.38782048734814e-05 5.54901896357423e-06 4.65985996338383e-06 -2.95967066322718e-06 -8.46448166625419e-07 -7.74144351220777e-06 5.54901896357423e-06 2.69093380843227e-05 2.30665891419129e-06 -2.15349838764287e-05 2.6210115675535e-05 -1.25865270369605e-06 4.65985996338383e-06 2.30665891419129e-06 7.48063331548865e-05 1222 1224 0 0 0 1256 1290 0 0 0 0 0 0 0 0 0 0 0 945 0 0 19 0 0 2542 +1267 1318 0.999139495607985 -0.00133904280578298 0.0414544965062323 -0.00968065495713867 -0.00573575701520538 0.985414593983117 0.170074039925415 -0.028198248933641 -0.041077602263076 -0.170165463386239 0.984558959972872 0.0290269460359729 0.000129404035257367 -5.77130732184411e-05 8.29051973821954e-06 6.17286137958866e-07 6.25276121016243e-06 -2.52816968988105e-05 -5.77130732184411e-05 6.59758937088174e-05 -4.36078611327849e-06 2.65409529341803e-06 -1.82364177414286e-06 2.88124173014199e-05 8.29051973821954e-06 -4.36078611327849e-06 1.47256611653939e-05 4.16089831658465e-06 -4.79654453933058e-06 -4.14901475120246e-06 6.17286137958866e-07 2.65409529341803e-06 4.16089831658465e-06 2.70434881340425e-05 -9.58453596485363e-06 5.1119630871471e-06 6.25276121016243e-06 -1.82364177414286e-06 -4.79654453933058e-06 -9.58453596485363e-06 2.53278185120768e-05 7.88282487824817e-08 -2.52816968988105e-05 2.88124173014199e-05 -4.14901475120246e-06 5.1119630871471e-06 7.88282487824817e-08 6.67969686253789e-05 1369 1381 0 0 0 1411 1450 0 0 0 0 0 0 0 0 0 0 0 1050 0 2 30 0 0 2609 +1267 1314 0.999317775465204 -0.00171540475354851 0.0368922895170174 -0.0115827997869976 -0.00464913827795352 0.985131416822752 0.171739561843127 -0.0263583464385142 -0.0366383563024926 -0.171793914255798 0.984451360846296 0.0395151360537903 0.000117046260422865 -5.41339393114011e-05 3.87989412908862e-06 -2.86996251000176e-06 -9.94046341511552e-06 4.97689468420178e-06 -5.41339393114011e-05 6.29688232404404e-05 -3.72444083974521e-06 3.69459572755442e-06 9.48464298904965e-06 2.45960243850814e-06 3.87989412908862e-06 -3.72444083974521e-06 1.39207641591152e-05 2.22374890548405e-06 -5.7070153269767e-06 -2.84194612984491e-06 -2.86996251000176e-06 3.69459572755442e-06 2.22374890548405e-06 3.24695122088955e-05 2.67426721119873e-07 4.67812860782894e-06 -9.94046341511552e-06 9.48464298904965e-06 -5.7070153269767e-06 2.67426721119873e-07 3.16859824453057e-05 -1.14115960265455e-05 4.97689468420178e-06 2.45960243850814e-06 -2.84194612984491e-06 4.67812860782894e-06 -1.14115960265455e-05 8.69441550361313e-05 1316 1317 0 0 0 1353 1386 0 0 0 0 0 0 0 0 0 0 0 1042 0 0 21 0 0 2506 +1267 1294 0.99861762297036 -0.0033020639436378 0.0524589312390215 -0.00734691891425525 -0.0056430908528706 0.985521388075602 0.169457219294915 -0.0278183637740939 -0.0522589573054659 -0.169518996042481 0.984140392099671 0.0181214656744452 8.9768399939165e-05 -2.45625413740727e-06 -1.10941704795435e-06 9.8581913077696e-06 -6.57483416768594e-06 1.69961269290213e-05 -2.45625413740727e-06 7.19724216897138e-05 4.04671101272857e-06 -1.88346757465812e-06 -2.70242680882408e-06 2.83221402271842e-05 -1.10941704795435e-06 4.04671101272857e-06 1.19601554201637e-05 2.86621786262781e-07 -6.26402284236675e-06 3.39749922544936e-07 9.8581913077696e-06 -1.88346757465812e-06 2.86621786262781e-07 2.82744269658313e-05 6.60590705995139e-06 -3.32376280209741e-06 -6.57483416768594e-06 -2.70242680882408e-06 -6.26402284236675e-06 6.60590705995139e-06 2.92430554760763e-05 -9.10879323310296e-06 1.69961269290213e-05 2.83221402271842e-05 3.39749922544936e-07 -3.32376280209741e-06 -9.10879323310296e-06 7.80858262642821e-05 1368 1385 0 0 0 1404 1451 0 0 0 0 0 0 0 0 0 0 0 1033 0 1 22 0 0 2530 +1267 1303 0.999293954829994 -0.00150841237077263 0.0375408648322045 -0.00745010726982036 -0.00445878044141957 0.987371271091368 0.158360639997419 -0.0275497329991807 -0.0373056445756585 -0.158416216706298 0.986667416694834 0.0186235415994487 0.000213569667951766 -9.37040356211139e-05 3.35729687633589e-06 1.2158743260592e-05 -1.02615405086501e-05 -6.3200764337662e-06 -9.37040356211139e-05 0.000161515231825826 6.39563637659004e-06 -8.31680962744774e-06 -8.64386110671773e-06 2.85978177565724e-05 3.35729687633589e-06 6.39563637659004e-06 1.52447153389361e-05 -4.7947057089692e-07 -9.09136230877625e-06 3.60502000833835e-06 1.2158743260592e-05 -8.31680962744774e-06 -4.7947057089692e-07 3.12247901992096e-05 5.92887918870873e-06 -1.04071392935555e-05 -1.02615405086501e-05 -8.64386110671773e-06 -9.09136230877625e-06 5.92887918870873e-06 2.71150601449252e-05 -3.84872304549297e-06 -6.3200764337662e-06 2.85978177565724e-05 3.60502000833835e-06 -1.04071392935555e-05 -3.84872304549297e-06 0.000105007401125063 1363 1380 0 0 0 1400 1444 0 0 0 0 0 0 0 0 0 0 0 935 0 0 20 0 0 2562 +1267 1307 0.999424691742211 -0.000783752934328013 0.0339068026703121 -0.00883600736299821 -0.00512417945834106 0.984767412451234 0.173801283536632 -0.0262398942269008 -0.0335265315960997 -0.17387503876474 0.984196851536163 0.0341809597088379 0.000147141675708786 -6.03771732907328e-05 9.98236077079689e-06 6.02372246949754e-06 4.49763426761445e-06 -3.68596921909207e-06 -6.03771732907328e-05 6.39936884221104e-05 -2.84638728113468e-06 -3.74252923910371e-07 -4.13544916644599e-07 1.68345431707649e-05 9.98236077079689e-06 -2.84638728113468e-06 1.43420796749376e-05 3.08028856613852e-06 -5.35643909574742e-06 -2.80229873074931e-06 6.02372246949754e-06 -3.74252923910371e-07 3.08028856613852e-06 2.52374500120102e-05 2.82039257341308e-06 4.29395141281306e-07 4.49763426761445e-06 -4.13544916644599e-07 -5.35643909574742e-06 2.82039257341308e-06 2.54969144606564e-05 -4.26900678460768e-06 -3.68596921909207e-06 1.68345431707649e-05 -2.80229873074931e-06 4.29395141281306e-07 -4.26900678460768e-06 6.63899405890148e-05 1372 1385 0 0 0 1410 1450 0 0 0 0 0 0 0 0 0 0 0 1035 0 2 25 0 0 2499 +1267 1306 0.999263370209049 -0.00132243570431695 0.0383532022425987 -0.00624400508222229 -0.00515163860893198 0.985737605340812 0.168210683479396 -0.0266583426454792 -0.0380286415494518 -0.168284356316238 0.985004668943824 0.0187739408080362 0.000213635665075545 -0.000103109230502816 1.93758363506211e-06 -1.73318260260182e-06 -1.06150238372887e-05 -1.34133125187848e-05 -0.000103109230502816 8.81153300462234e-05 -8.01116425209104e-07 6.58496072492331e-07 1.74810211964458e-06 3.8779311192965e-05 1.93758363506211e-06 -8.01116425209104e-07 1.43361281945429e-05 6.92154738341006e-07 -6.69829631699244e-06 -3.35863686400041e-07 -1.73318260260182e-06 6.58496072492331e-07 6.92154738341006e-07 2.75200899844758e-05 3.5182474680609e-06 2.20237090219614e-08 -1.06150238372887e-05 1.74810211964458e-06 -6.69829631699244e-06 3.5182474680609e-06 2.48631766194135e-05 -3.17527552167483e-06 -1.34133125187848e-05 3.8779311192965e-05 -3.35863686400041e-07 2.20237090219614e-08 -3.17527552167483e-06 8.06175817939486e-05 1367 1385 0 0 0 1404 1451 0 0 0 0 0 0 0 0 0 0 0 1034 0 0 21 0 0 2666 +1268 1270 0.998974302034178 -0.00598284360247943 -0.0448837326628942 0.00342678002360281 0.0066541787614578 0.999867995480788 0.0148227365301505 -0.000381463397690799 0.0447891256929229 -0.015106197260064 0.998882243822566 0.00951995895911192 4.62221459062717e-05 1.74284970126181e-05 -3.69950092318135e-06 4.7016298125996e-06 5.11660780174186e-07 9.20069926788222e-06 1.74284970126181e-05 4.6452361056995e-05 9.08384793839154e-07 7.98752403279353e-07 6.32696534185003e-08 2.33702802689158e-05 -3.69950092318135e-06 9.08384793839154e-07 1.12252066933751e-05 2.13788739038488e-06 -3.9246512382253e-06 -9.5879498735135e-07 4.7016298125996e-06 7.98752403279353e-07 2.13788739038488e-06 1.78201986692059e-05 -5.13174389664441e-06 5.35553875440504e-07 5.11660780174186e-07 6.32696534185003e-08 -3.9246512382253e-06 -5.13174389664441e-06 1.71913923466374e-05 -1.94807458674809e-06 9.20069926788222e-06 2.33702802689158e-05 -9.5879498735135e-07 5.35553875440504e-07 -1.94807458674809e-06 4.32359662960235e-05 1446 1474 0 0 0 1446 1535 0 0 4 0 0 0 0 0 0 0 0 792 0 0 0 0 0 3457 +1268 1271 0.998959741532305 0.000150565021083969 -0.0456005715740932 -0.0027862762636069 0.000595570656292096 0.999866178746992 0.0163483911587963 -0.00434831566914642 0.0455969307443268 -0.0163585429687999 0.998825969815881 0.0126360637073701 5.38632506122197e-05 7.43849769487567e-06 -4.85453624327946e-06 5.18976204461714e-06 -2.22775378616574e-06 1.04650772430944e-05 7.43849769487567e-06 4.02838194482091e-05 -2.44235737456258e-06 5.55282878969746e-06 -1.99733215659374e-06 1.75119957148723e-05 -4.85453624327946e-06 -2.44235737456258e-06 1.28394935659586e-05 -2.91476309261601e-07 -3.98782406333844e-06 -4.42324488770385e-06 5.18976204461714e-06 5.55282878969746e-06 -2.91476309261601e-07 2.34978562313241e-05 -5.05995527350363e-06 6.6642024694643e-06 -2.22775378616574e-06 -1.99733215659374e-06 -3.98782406333844e-06 -5.05995527350363e-06 1.79885700702257e-05 -2.27864263884473e-06 1.04650772430944e-05 1.75119957148723e-05 -4.42324488770385e-06 6.6642024694643e-06 -2.27864263884473e-06 4.81770434644526e-05 1409 1426 0 0 0 1426 1507 0 0 7 0 0 0 0 0 0 0 0 803 0 0 0 0 0 3377 +1268 1272 0.999073726926736 0.0012203189480086 -0.0430139394427857 0.00565400979392361 -0.000349925007543114 0.999795152065478 0.0202368836251214 -0.00262228021547974 0.0430298235786716 -0.0202030870916487 0.998869495757457 0.0149806147321733 6.00844235319559e-05 3.52091455363371e-05 -6.01493052679914e-06 1.35535495501606e-05 -4.99365271424519e-06 3.13050572712257e-05 3.52091455363371e-05 7.71205885177353e-05 -7.17205957629349e-06 2.13166350811252e-05 -5.3995463813968e-06 3.78105738558159e-05 -6.01493052679914e-06 -7.17205957629349e-06 1.58293394492336e-05 -4.3397409012214e-06 -1.20671680423309e-06 -1.91893278483392e-06 1.35535495501606e-05 2.13166350811252e-05 -4.3397409012214e-06 3.47207533992478e-05 -7.87734423492764e-06 1.01050055982972e-05 -4.99365271424519e-06 -5.3995463813968e-06 -1.20671680423309e-06 -7.87734423492764e-06 2.2562279939852e-05 -1.78298897753514e-06 3.13050572712257e-05 3.78105738558159e-05 -1.91893278483392e-06 1.01050055982972e-05 -1.78298897753514e-06 6.01158577704322e-05 1466 1483 0 0 0 1469 1555 0 0 2 0 0 0 0 0 0 0 0 803 0 0 0 0 0 3440 +1268 1311 0.999443132304676 -0.006971889770567 0.0326315497953252 -0.00383660776072016 0.00148525559717681 0.986254368300807 0.165227464494818 -0.0239361355124598 -0.0333349561995929 -0.165086988465482 0.985715510142033 0.0285408168353915 0.000124938778318322 -4.93383990554093e-05 6.13833545208478e-06 1.52857389302248e-06 2.05080773623752e-06 2.21046911624381e-05 -4.93383990554093e-05 7.67281270397965e-05 -6.4569566989831e-06 3.59347424494126e-06 -1.26700084864043e-06 2.06275268722235e-05 6.13833545208478e-06 -6.4569566989831e-06 1.58053311804064e-05 4.0945996685659e-07 -6.91334188722894e-06 -1.79164288671595e-07 1.52857389302248e-06 3.59347424494126e-06 4.0945996685659e-07 3.30697620278821e-05 9.63790878195732e-07 1.30656561620399e-06 2.05080773623752e-06 -1.26700084864043e-06 -6.91334188722894e-06 9.63790878195732e-07 2.63953359833495e-05 3.68592313124198e-06 2.21046911624381e-05 2.06275268722235e-05 -1.79164288671595e-07 1.30656561620399e-06 3.68592313124198e-06 7.77134304512563e-05 1382 1402 0 0 9 1404 1464 0 0 10 0 0 0 0 0 0 0 0 940 0 0 9 0 0 2664 +1267 1304 0.999331322729371 -0.00116561845738374 0.0365451603578152 -0.00587491904613804 -0.0050713287926227 0.985412711826998 0.170106052196974 -0.024397324409869 -0.0362103443265006 -0.170177638670227 0.984747877509965 0.0166876892223274 0.00013488268783035 -6.55248133565526e-05 4.23221122017507e-06 9.35303134388882e-06 -4.37602356312405e-08 -4.16019240602237e-05 -6.55248133565526e-05 7.98903555141879e-05 8.12830388310167e-07 -5.98995016675644e-06 -2.97645163054852e-06 4.18835882538717e-05 4.23221122017507e-06 8.12830388310167e-07 1.59227993755208e-05 -8.28057987926094e-07 -7.9528840083111e-06 1.65045267833822e-07 9.35303134388882e-06 -5.98995016675644e-06 -8.28057987926094e-07 3.05042143467163e-05 4.87207914813732e-06 -4.08433560517444e-06 -4.37602356312405e-08 -2.97645163054852e-06 -7.9528840083111e-06 4.87207914813732e-06 2.53927866739382e-05 -6.97129300179723e-07 -4.16019240602237e-05 4.18835882538717e-05 1.65045267833822e-07 -4.08433560517444e-06 -6.97129300179723e-07 8.02648565031758e-05 1370 1388 0 0 0 1406 1453 0 0 0 0 0 0 0 0 0 0 0 1038 0 0 19 0 0 2557 +1267 1296 0.999351987786809 -0.00188861639048903 0.035944925019844 -0.0115775141659685 -0.00423958658230307 0.985495233034209 0.169650144628471 -0.0312483953166018 -0.0357439563026225 -0.169692600884598 0.984848613134454 0.019413788476227 0.000170728694665884 -6.49329701575106e-05 4.39702701451902e-06 1.38102150673681e-05 -1.74505841902049e-06 -2.87972904056231e-05 -6.49329701575106e-05 7.35533308478723e-05 -2.77367312338217e-06 -2.34662855192525e-06 1.59320583796654e-06 3.31107063058146e-05 4.39702701451902e-06 -2.77367312338217e-06 1.25874572956174e-05 2.16951544014062e-06 -5.53878813701967e-06 -1.77485334565425e-06 1.38102150673681e-05 -2.34662855192525e-06 2.16951544014062e-06 2.94754551511884e-05 3.96250048991615e-06 -3.32038422137765e-06 -1.74505841902049e-06 1.59320583796654e-06 -5.53878813701967e-06 3.96250048991615e-06 2.45361374247596e-05 6.28159265312595e-07 -2.87972904056231e-05 3.31107063058146e-05 -1.77485334565425e-06 -3.32038422137765e-06 6.28159265312595e-07 8.09445825933409e-05 1316 1316 0 0 0 1354 1382 0 0 0 0 0 0 0 0 0 0 0 1023 0 0 19 0 0 2586 +1267 1302 0.999236373083961 -0.00158714498714728 0.0390403852030229 -0.0104883381428632 -0.00521261224033733 0.984828240427505 0.173453640867227 -0.0269729829443525 -0.0387233699417099 -0.173524689388152 0.984067925904052 0.0314644880564166 0.000157625667927407 -7.18904503945103e-05 2.90059634703988e-06 6.29999823408962e-06 -6.99869275166944e-06 5.5809677836349e-06 -7.18904503945103e-05 8.67301017846096e-05 -3.56515484965956e-06 3.47799072160233e-06 1.47055278462175e-07 3.08629003431239e-06 2.90059634703988e-06 -3.56515484965956e-06 1.61148602864066e-05 -6.9215718729763e-07 -4.41940000099965e-06 -4.74712957933513e-06 6.29999823408962e-06 3.47799072160233e-06 -6.9215718729763e-07 3.79212151892697e-05 9.26945217298933e-06 -9.41850740740049e-06 -6.99869275166944e-06 1.47055278462175e-07 -4.41940000099965e-06 9.26945217298933e-06 3.37375028094496e-05 -1.11776443039407e-05 5.5809677836349e-06 3.08629003431239e-06 -4.74712957933513e-06 -9.41850740740049e-06 -1.11776443039407e-05 8.20170893051869e-05 1314 1316 0 0 0 1353 1383 0 0 0 0 0 0 0 0 0 0 0 944 0 0 17 0 0 2498 +1267 1297 0.999106014340165 -0.00206417548498559 0.0422245342055761 -0.0094448005159904 -0.00557311409400982 0.983658795445461 0.179956424008928 -0.0281478820640311 -0.0419059960937076 -0.180030867693162 0.982767914702673 0.0239349769390703 0.000125420743930713 -5.49175920378549e-05 8.69812934129904e-06 1.99737647292906e-06 1.23044054676099e-06 -1.24464766031111e-05 -5.49175920378549e-05 6.40775707153209e-05 -3.54286433711171e-06 -1.26955047328916e-06 -1.70430749094687e-06 2.66899675361275e-05 8.69812934129904e-06 -3.54286433711171e-06 1.38186896007584e-05 2.64768880036496e-06 -6.74688282108684e-06 -1.9576946374599e-07 1.99737647292906e-06 -1.26955047328916e-06 2.64768880036496e-06 2.35773958690411e-05 2.70284359902768e-06 -9.48122325341591e-07 1.23044054676099e-06 -1.70430749094687e-06 -6.74688282108684e-06 2.70284359902768e-06 2.23460515501279e-05 2.61697288391518e-06 -1.24464766031111e-05 2.66899675361275e-05 -1.9576946374599e-07 -9.48122325341591e-07 2.61697288391518e-06 6.14021487573207e-05 1370 1385 0 0 0 1410 1449 0 0 0 0 0 0 0 0 0 0 0 1040 0 3 28 0 0 2543 +1268 1314 0.999301249498984 -0.00670319409665171 0.0367706396282767 -0.00694507594463451 0.00039796210296779 0.98563923484772 0.168864266068836 -0.0236606356031196 -0.0373745150595239 -0.168731638757242 0.984953186555768 0.0353590524523918 9.66009782471036e-05 -4.60802116990159e-05 3.93664420623672e-06 -1.61039464025097e-07 -4.93904634787478e-06 1.54355183079545e-05 -4.60802116990159e-05 6.2349446993403e-05 -4.13555726632966e-06 1.05864255914261e-06 3.09571060946588e-06 -5.95522609708662e-07 3.93664420623672e-06 -4.13555726632966e-06 1.4551388840171e-05 8.61722520305315e-07 -6.23390595786371e-06 -3.89881573445036e-06 -1.61039464025097e-07 1.05864255914261e-06 8.61722520305315e-07 2.80806240266641e-05 -5.14344533069708e-06 6.79363091069091e-06 -4.93904634787478e-06 3.09571060946588e-06 -6.23390595786371e-06 -5.14344533069708e-06 2.57246115176074e-05 5.45348575130969e-06 1.54355183079545e-05 -5.95522609708662e-07 -3.89881573445036e-06 6.79363091069091e-06 5.45348575130969e-06 7.59880453791767e-05 1379 1398 0 0 9 1403 1463 0 0 10 0 0 0 0 0 0 0 0 1043 0 0 14 0 0 2532 +1268 1315 0.999260580633938 -0.00636953493786893 0.0379172917783063 -0.00846556391021882 -4.89754455014757e-05 0.985970623409839 0.166918924553865 -0.0265582187434018 -0.0384485317344068 -0.166797358484744 0.98524126568571 0.026323170714821 0.00014310587831171 -8.2050586039855e-05 7.50522790124962e-06 -6.07039694273693e-06 -2.17383922606601e-07 9.76154940069432e-06 -8.2050586039855e-05 8.52980135156145e-05 -9.60065520683696e-06 1.08178853005427e-05 -6.27797100735375e-06 1.52781467067664e-05 7.50522790124962e-06 -9.60065520683696e-06 1.62999231936719e-05 1.35859542354083e-06 -6.34971064967687e-06 -2.15767136537654e-06 -6.07039694273693e-06 1.08178853005427e-05 1.35859542354083e-06 2.95539013658425e-05 -9.77903287542562e-06 7.96766147200789e-06 -2.17383922606601e-07 -6.27797100735375e-06 -6.34971064967687e-06 -9.77903287542562e-06 2.58785276266338e-05 9.95316822555998e-07 9.76154940069432e-06 1.52781467067664e-05 -2.15767136537654e-06 7.96766147200789e-06 9.95316822555998e-07 7.52306641975794e-05 1267 1269 0 0 0 1291 1331 0 0 1 0 0 0 0 0 0 0 0 1036 0 0 12 0 0 2666 +1268 1309 0.999287998639575 -0.00712636102923646 0.0370501113816743 -0.00149367533510334 0.000907648899286817 0.986256334641215 0.165219909676622 -0.0236467254161335 -0.0377183237749123 -0.165068644383349 0.985560587022967 0.0294875098973339 6.92637994772289e-05 -2.61139857839397e-05 7.56702239739747e-06 2.04278362166462e-07 5.12208463214915e-06 1.69303029144556e-05 -2.61139857839397e-05 5.3384426761568e-05 -8.51974165439626e-06 3.69278465406193e-06 -6.47595654912397e-06 1.10445365898003e-05 7.56702239739747e-06 -8.51974165439626e-06 1.71874943153512e-05 -3.94257304700551e-06 -5.5373676591898e-06 1.2700444292701e-06 2.04278362166462e-07 3.69278465406193e-06 -3.94257304700551e-06 3.67375367607751e-05 7.4256299843716e-06 -1.07714600124957e-06 5.12208463214915e-06 -6.47595654912397e-06 -5.5373676591898e-06 7.4256299843716e-06 3.13629957646409e-05 -8.20740553859967e-08 1.69303029144556e-05 1.10445365898003e-05 1.2700444292701e-06 -1.07714600124957e-06 -8.20740553859967e-08 6.70220870710185e-05 1387 1411 0 0 7 1409 1466 0 0 11 0 0 0 0 0 0 0 0 933 0 0 11 0 0 2492 +1268 1312 0.999359308738014 -0.00552520033800363 0.0353616204366117 -0.00347423573703156 -0.000513427898603597 0.985697450266192 0.168523805233921 -0.0221341172002273 -0.0357869868872891 -0.168433989146943 0.985063085730846 0.0264624227480311 9.2781345113627e-05 -4.17208142107509e-05 8.59624278894195e-07 -1.40012340516415e-06 -3.95311180977689e-06 -1.54776939412695e-06 -4.17208142107509e-05 7.80345072643936e-05 -2.71517307017606e-06 1.56764116038625e-06 -3.53697764604076e-06 3.3013537694215e-05 8.59624278894195e-07 -2.71517307017606e-06 1.67978663921397e-05 -3.13155876853483e-06 -8.00140758882445e-06 -3.81267249811169e-07 -1.40012340516415e-06 1.56764116038625e-06 -3.13155876853483e-06 3.55304251129826e-05 6.80179252782205e-06 5.30124872313548e-06 -3.95311180977689e-06 -3.53697764604076e-06 -8.00140758882445e-06 6.80179252782205e-06 2.87843438582549e-05 -2.69665005090126e-06 -1.54776939412695e-06 3.3013537694215e-05 -3.81267249811169e-07 5.30124872313548e-06 -2.69665005090126e-06 5.54822604944832e-05 1379 1403 0 0 7 1402 1460 0 0 11 0 0 0 0 0 0 0 0 1033 0 0 12 0 0 2519 +1268 1313 0.999381654176768 -0.00630351604946143 0.0345915449253131 -0.00542247862577488 0.000424795320604805 0.985891779767621 0.167383446420391 -0.0263866449394531 -0.0351586240322537 -0.167265251239003 0.985284835407565 0.0298086585339854 0.000137091784830747 -7.0552337015108e-05 5.75502396958051e-06 -8.50365980517569e-07 -1.04089231120837e-05 3.46174442368128e-05 -7.0552337015108e-05 7.10110253457546e-05 -5.85913031469609e-06 -1.41337497416807e-06 1.55908023497054e-06 -7.46489067114363e-07 5.75502396958051e-06 -5.85913031469609e-06 1.59932756579246e-05 -2.75665674151664e-06 -2.13273453103177e-06 -5.74996677976596e-06 -8.50365980517569e-07 -1.41337497416807e-06 -2.75665674151664e-06 3.37164424837975e-05 -4.04768928339558e-06 8.49891853494536e-06 -1.04089231120837e-05 1.55908023497054e-06 -2.13273453103177e-06 -4.04768928339558e-06 2.62419196307458e-05 -9.0212714037801e-06 3.46174442368128e-05 -7.46489067114363e-07 -5.74996677976596e-06 8.49891853494536e-06 -9.0212714037801e-06 7.58893749620098e-05 1377 1396 0 0 7 1405 1461 0 0 11 0 0 0 0 0 0 0 0 1045 0 0 15 0 0 2682 +1268 1308 0.99956797773142 -0.00656406013425186 0.0286491013554327 -0.00248567594804609 0.00176753274909515 0.986403061900696 0.164334644250419 -0.0214137617505554 -0.0293382637847028 -0.164213009799726 0.985988516003414 0.0314668034644122 0.000123690945155943 -5.60312591679369e-05 6.31314853180699e-06 -1.29666578168689e-06 -6.50778528237964e-06 3.21229426762699e-05 -5.60312591679369e-05 8.63911726624912e-05 -5.75239858119863e-06 1.15994890867291e-05 -3.89074004572426e-06 1.08021512343072e-05 6.31314853180699e-06 -5.75239858119863e-06 1.50985655958294e-05 -5.7549632584381e-06 -9.61131991233931e-06 1.62025446405912e-06 -1.29666578168689e-06 1.15994890867291e-05 -5.7549632584381e-06 4.8524144581767e-05 1.08268636917733e-05 -3.69412681515136e-06 -6.50778528237964e-06 -3.89074004572426e-06 -9.61131991233931e-06 1.08268636917733e-05 2.90198739605712e-05 -9.24060974131433e-06 3.21229426762699e-05 1.08021512343072e-05 1.62025446405912e-06 -3.69412681515136e-06 -9.24060974131433e-06 0.000113965208717097 1289 1297 0 0 2 1305 1353 0 0 5 0 0 0 0 0 0 0 0 1037 0 0 6 0 0 2721 +1268 1310 0.999318899120063 -0.00624124035508585 0.036370108334933 -0.00882024948599331 0.000120715966965559 0.986141143418755 0.16590850094075 -0.0312931980970072 -0.036901535050998 -0.165791110061974 0.985470235235595 0.026418482996433 7.60856602896744e-05 -4.64052609755678e-05 7.29181712599004e-06 -4.19118454529008e-06 1.16492479207531e-06 1.64499081139672e-05 -4.64052609755678e-05 6.07899604419045e-05 -6.76215902389725e-06 9.40371854720124e-06 3.80339374082904e-06 -1.74166114970878e-06 7.29181712599004e-06 -6.76215902389725e-06 1.58799025314334e-05 8.58490870991675e-07 -3.22530480529421e-06 -1.00186819230946e-06 -4.19118454529008e-06 9.40371854720124e-06 8.58490870991675e-07 3.2284853904861e-05 9.48959510831694e-06 2.32927708590581e-06 1.16492479207531e-06 3.80339374082904e-06 -3.22530480529421e-06 9.48959510831694e-06 3.21343313402148e-05 8.17996387262882e-07 1.64499081139672e-05 -1.74166114970878e-06 -1.00186819230946e-06 2.32927708590581e-06 8.17996387262882e-07 8.38970356637607e-05 1373 1383 0 0 1 1410 1450 0 0 7 0 0 0 0 0 0 0 0 1032 0 0 24 0 0 2547 +1268 1306 0.999589601782859 -0.00434020057139165 0.0283159083658965 -0.00112429941603179 -0.000462514692185128 0.985881952049217 0.167441221638474 -0.0228589519629542 -0.0286428714996466 -0.167385600583279 0.985475340447253 0.0294119123081582 9.98366226980849e-05 -5.49847039933994e-05 4.95654132720923e-06 -1.08783675151809e-05 -8.15764109535675e-06 -1.65824455175543e-07 -5.49847039933994e-05 7.79684019145648e-05 -7.70203984896051e-07 8.19747383055777e-06 4.68347423193229e-06 2.27080294142458e-05 4.95654132720923e-06 -7.70203984896051e-07 1.49828179624274e-05 -1.65606726641852e-06 -8.01627561627035e-06 -4.91566768689179e-07 -1.08783675151809e-05 8.19747383055777e-06 -1.65606726641852e-06 3.60206860299199e-05 9.93095263409664e-06 2.47388805808747e-06 -8.15764109535675e-06 4.68347423193229e-06 -8.01627561627035e-06 9.93095263409664e-06 2.83649744373158e-05 -2.68959852817137e-06 -1.65824455175543e-07 2.27080294142458e-05 -4.91566768689179e-07 2.47388805808747e-06 -2.68959852817137e-06 5.78858296377725e-05 1382 1405 0 0 8 1407 1464 0 0 12 0 0 0 0 0 0 0 0 1033 0 0 11 0 0 2736 +1268 1295 0.999192125019099 -0.00687529279346963 0.0395958034243574 -0.00419711364868855 0.00013900389901369 0.985842999109113 0.16767099267752 -0.0250566213100603 -0.0401880327676331 -0.167530031506452 0.985047516907542 0.0299202775346305 7.94593641947771e-05 -6.16996622283299e-06 1.87276425596895e-06 1.39015611183633e-06 2.59000264184496e-06 2.38321275229664e-05 -6.16996622283299e-06 4.88541425223644e-05 -2.74197563882758e-06 8.12806112758906e-07 2.12807875895706e-06 2.74958347364023e-05 1.87276425596895e-06 -2.74197563882758e-06 1.28326008274086e-05 -8.54647583986385e-07 -7.61995979941055e-06 -9.85076168740434e-07 1.39015611183633e-06 8.12806112758906e-07 -8.54647583986385e-07 3.11300044971488e-05 8.32057106474186e-06 5.79737223461134e-07 2.59000264184496e-06 2.12807875895706e-06 -7.61995979941055e-06 8.32057106474186e-06 2.42785654735728e-05 3.26446518628137e-06 2.38321275229664e-05 2.74958347364023e-05 -9.85076168740434e-07 5.79737223461134e-07 3.26446518628137e-06 5.53222242097209e-05 1380 1402 0 0 9 1403 1463 0 0 9 0 0 0 0 0 0 0 0 905 0 0 10 0 0 2527 +1268 1305 0.999323723691354 -0.00626534953327053 0.0362331431547401 -0.0044555251862025 2.66360044271904e-05 0.98549995353448 0.169675693232887 -0.0229814829962302 -0.0367708384208085 -0.169559980475239 0.984833650147611 0.0235940182343602 0.000123634960548966 -5.46044702071968e-05 7.08331098118633e-06 1.33018999004557e-06 3.43460770501899e-06 -6.44375814938618e-07 -5.46044702071968e-05 5.66132674902289e-05 -1.55599229598507e-06 -2.5610877172841e-06 -4.81355172245754e-06 2.09700026501137e-05 7.08331098118633e-06 -1.55599229598507e-06 1.62437546536947e-05 -3.80421050362437e-06 -8.77548954200155e-06 -1.99493224293101e-06 1.33018999004557e-06 -2.5610877172841e-06 -3.80421050362437e-06 4.14198586356463e-05 1.50078749576618e-05 6.31271674784651e-07 3.43460770501899e-06 -4.81355172245754e-06 -8.77548954200155e-06 1.50078749576618e-05 3.47743787149437e-05 -1.51152946945593e-06 -6.44375814938618e-07 2.09700026501137e-05 -1.99493224293101e-06 6.31271674784651e-07 -1.51152946945593e-06 5.5448729046637e-05 1277 1282 0 0 1 1297 1344 0 0 3 0 0 0 0 0 0 0 0 946 0 0 9 0 0 2503 +1268 1318 0.999462745546072 -0.00507312025507221 0.0323802982751226 -0.00890023377143186 -0.000490145279193594 0.98552419994716 0.16953410003924 -0.0282656699836243 -0.0327716344284751 -0.169458888139239 0.984992236115341 0.0426284090862337 0.000160619262458716 -8.41856843651938e-05 2.68886053989858e-06 -1.44763069695237e-05 -1.81507037597189e-05 2.24607520537274e-05 -8.41856843651938e-05 8.68755621945211e-05 -9.87914238555765e-07 9.60655366459968e-06 1.16626497443187e-05 4.23430742898994e-06 2.68886053989858e-06 -9.87914238555765e-07 1.4307996144789e-05 4.08851146343789e-06 -3.76408359153044e-06 -2.82652397820388e-06 -1.44763069695237e-05 9.60655366459968e-06 4.08851146343789e-06 2.91965037898162e-05 -1.73419942002432e-06 1.78502027865234e-06 -1.81507037597189e-05 1.16626497443187e-05 -3.76408359153044e-06 -1.73419942002432e-06 2.95341756950994e-05 -9.09696458108341e-06 2.24607520537274e-05 4.23430742898994e-06 -2.82652397820388e-06 1.78502027865234e-06 -9.09696458108341e-06 7.41350327557349e-05 1380 1391 0 0 0 1415 1460 0 0 8 0 0 0 0 0 0 0 0 1050 0 0 21 0 0 2678 +1268 1294 0.999165962626836 -0.00728550365964893 0.0401783594042145 -0.00353038551076941 0.000405707126668443 0.985677170589789 0.168642671882997 -0.0249813172622485 -0.0408315384196624 -0.168485716945188 0.984858034772398 0.0257766709447489 6.58321376791242e-05 -1.31746491809786e-05 1.31059276108075e-06 -2.64468730492537e-06 -6.57059078424759e-06 1.03886731600065e-05 -1.31746491809786e-05 5.60133667223266e-05 8.77537350870126e-07 3.66929743141494e-06 4.0842702908678e-06 2.13333699913356e-05 1.31059276108075e-06 8.77537350870126e-07 1.30059862258771e-05 -3.06434224000426e-06 -7.24294025258323e-06 -1.12914362792973e-06 -2.64468730492537e-06 3.66929743141494e-06 -3.06434224000426e-06 3.26634900617233e-05 1.07577330305684e-05 5.55917876851047e-06 -6.57059078424759e-06 4.0842702908678e-06 -7.24294025258323e-06 1.07577330305684e-05 2.48161369024871e-05 2.35226973682484e-06 1.03886731600065e-05 2.13333699913356e-05 -1.12914362792973e-06 5.55917876851047e-06 2.35226973682484e-06 5.82013106341395e-05 1383 1404 0 0 9 1408 1467 0 0 12 0 0 0 0 0 0 0 0 1031 0 0 12 0 0 2547 +1268 1304 0.999519649674155 -0.0057379555115967 0.0304556362895387 -0.00293910184601425 0.000642810563042917 0.986337916377916 0.164733425599822 -0.0244820302689344 -0.030984781907152 -0.164634718640446 0.985867817056804 0.0211725304873527 0.000147439508059871 -5.39385121103035e-05 1.01410640251166e-05 -4.97367189736682e-06 -9.68308016969185e-06 6.28941235906791e-06 -5.39385121103035e-05 5.71413590811379e-05 -1.98221380763245e-06 -1.42860447009118e-07 8.98207703164656e-07 2.50676441979902e-05 1.01410640251166e-05 -1.98221380763245e-06 1.68015505786622e-05 -4.52699560028113e-06 -7.99189815440729e-06 8.86130842079382e-07 -4.97367189736682e-06 -1.42860447009118e-07 -4.52699560028113e-06 3.52355920744688e-05 8.40190562921615e-06 1.35100194878052e-06 -9.68308016969185e-06 8.98207703164656e-07 -7.99189815440729e-06 8.40190562921615e-06 3.14337259840878e-05 -5.90626470327216e-07 6.28941235906791e-06 2.50676441979902e-05 8.86130842079382e-07 1.35100194878052e-06 -5.90626470327216e-07 6.82601905674287e-05 1381 1402 0 0 10 1408 1463 0 0 12 0 0 0 0 0 0 0 0 1037 0 0 12 0 0 2527 +1268 1316 0.999257632053336 -0.00634871175072541 0.0379984031541558 -0.00700148154689273 -2.61655310256478e-05 0.986215923294915 0.165463445978029 -0.0257909714162681 -0.0385251099742044 -0.165341605467787 0.985483622087557 0.0317984008629539 0.000173056156462242 -8.65321837617555e-05 8.70364884960484e-06 -1.25279324978081e-05 -7.65254419191283e-06 3.63548457346234e-05 -8.65321837617555e-05 9.06982385337874e-05 -3.91568498330652e-06 3.10363992481791e-06 4.42753472674416e-06 5.23141601614781e-06 8.70364884960484e-06 -3.91568498330652e-06 1.62507328293705e-05 1.41984130281554e-07 -5.91950528329655e-06 1.64655012447336e-06 -1.25279324978081e-05 3.10363992481791e-06 1.41984130281554e-07 3.34458810904429e-05 -5.76473735075255e-06 -5.59988400293709e-06 -7.65254419191283e-06 4.42753472674416e-06 -5.91950528329655e-06 -5.76473735075255e-06 2.73996627354967e-05 -3.53007250525156e-06 3.63548457346234e-05 5.23141601614781e-06 1.64655012447336e-06 -5.59988400293709e-06 -3.53007250525156e-06 7.3070615883871e-05 1282 1286 0 0 1 1306 1348 0 0 2 0 0 0 0 0 0 0 0 1034 0 0 11 0 0 2746 +1268 1307 0.999668420807208 -0.00540761719026206 0.0251755062937313 -0.00379116972585716 0.00106976121070366 0.985577582070646 0.169220818254527 -0.0233295325497192 -0.0257274960261234 -0.169137776372114 0.985256569910662 0.0395753439544241 8.55447348202955e-05 -3.85654867367936e-05 1.59837745916775e-06 -6.61750012294828e-06 -1.11307919181577e-05 2.18438858895438e-05 -3.85654867367936e-05 7.364548581791e-05 -2.89109681533096e-06 1.52527962530879e-05 6.41003130341377e-06 3.08392491501242e-06 1.59837745916775e-06 -2.89109681533096e-06 1.56720906428525e-05 -5.64412930804006e-08 -1.80767299686265e-06 -2.04806069612979e-06 -6.61750012294828e-06 1.52527962530879e-05 -5.64412930804006e-08 3.90721911646155e-05 1.30025062526816e-05 -5.99889753500257e-06 -1.11307919181577e-05 6.41003130341377e-06 -1.80767299686265e-06 1.30025062526816e-05 3.90661749112982e-05 -6.45785811369009e-06 2.18438858895438e-05 3.08392491501242e-06 -2.04806069612979e-06 -5.99889753500257e-06 -6.45785811369009e-06 8.52702012724832e-05 1390 1404 0 0 1 1417 1469 0 0 9 0 0 0 0 0 0 0 0 1035 0 0 14 0 0 2577 +1269 1271 0.999719064778049 0.00785173515889489 -0.0223638497199832 0.000780975595012671 -0.00772366272813452 0.999953308518646 0.0058073932772564 -0.00459882720881791 0.0224084036326876 -0.00563303094339726 0.999733030568174 0.00966868896933155 8.30504459141418e-05 2.91361701090469e-05 -4.13146169301301e-06 1.26262206281724e-05 -4.37549212717678e-06 9.4286001588427e-06 2.91361701090469e-05 8.38202457559197e-05 -7.29682826846798e-06 2.01011845026086e-05 -2.91107466169707e-06 2.53700991113191e-05 -4.13146169301301e-06 -7.29682826846798e-06 1.16351053696862e-05 1.18106719913481e-07 -3.60354342796594e-06 -2.68081760672067e-06 1.26262206281724e-05 2.01011845026086e-05 1.18106719913481e-07 2.61019850094429e-05 -3.03614227679289e-06 1.63556467614095e-06 -4.37549212717678e-06 -2.91107466169707e-06 -3.60354342796594e-06 -3.03614227679289e-06 1.88143295265967e-05 -7.63256555270619e-07 9.4286001588427e-06 2.53700991113191e-05 -2.68081760672067e-06 1.63556467614095e-06 -7.63256555270619e-07 5.6605826799195e-05 1348 1348 0 0 0 1371 1436 0 0 2 0 0 0 0 0 0 0 0 804 0 0 1 0 0 3367 +1268 1317 0.999250563660555 -0.00556115309383681 0.0383064563791921 -0.00593557509890397 -0.00102009657667654 0.985498677326725 0.169680041225388 -0.0263629811792616 -0.0386945787809907 -0.169591953121432 0.984754435892228 0.0333131703467325 0.000106898185129766 -4.6776618742052e-05 3.79634211389154e-06 -1.49077455571217e-06 3.15074378046449e-06 -2.42504859532055e-06 -4.6776618742052e-05 6.65017027793139e-05 -8.42443281076357e-08 3.11543524123672e-07 1.68896138801905e-06 1.95272834957254e-05 3.79634211389154e-06 -8.42443281076357e-08 1.74000255478553e-05 1.29144968790673e-06 -2.78025004985651e-06 -2.66067912781304e-06 -1.49077455571217e-06 3.11543524123672e-07 1.29144968790673e-06 3.01167872453653e-05 -8.14628684428443e-06 5.84143781031418e-07 3.15074378046449e-06 1.68896138801905e-06 -2.78025004985651e-06 -8.14628684428443e-06 2.61909262021499e-05 -3.35042679163175e-06 -2.42504859532055e-06 1.95272834957254e-05 -2.66067912781304e-06 5.84143781031418e-07 -3.35042679163175e-06 5.74510601854412e-05 1370 1389 0 0 11 1400 1457 0 0 11 0 0 0 0 0 0 0 0 941 0 0 15 0 0 2747 +1268 1296 0.999516453177263 -0.00679759199585647 0.0303422571837079 -0.00761260013497011 0.0014729768014597 0.98506733250827 0.172163238713678 -0.0268151236708385 -0.0310594617996959 -0.17203529628567 0.98460101902477 0.0255753948803167 6.54451809294232e-05 -2.50636965442908e-05 5.08294088480843e-06 -5.79791307654672e-06 -4.61063204164945e-06 -6.96588117557733e-06 -2.50636965442908e-05 6.50997057931357e-05 -2.73678058675454e-06 4.80846142536581e-06 2.07046745697353e-06 3.51703725598901e-05 5.08294088480843e-06 -2.73678058675454e-06 1.30442919918468e-05 5.41556454745255e-07 -6.25675791222644e-06 -2.99961283955077e-07 -5.79791307654672e-06 4.80846142536581e-06 5.41556454745255e-07 3.008357961839e-05 6.82860368669789e-06 2.18137980635261e-06 -4.61063204164945e-06 2.07046745697353e-06 -6.25675791222644e-06 6.82860368669789e-06 2.84599266104162e-05 5.4131475208433e-06 -6.96588117557733e-06 3.51703725598901e-05 -2.99961283955077e-07 2.18137980635261e-06 5.4131475208433e-06 5.40223079171833e-05 1381 1401 0 0 9 1405 1464 0 0 9 0 0 0 0 0 0 0 0 1017 0 0 14 0 0 2663 +1268 1297 0.999619130921894 -0.00559652022263623 0.0270235463319609 -0.00579453496359824 0.000962215026115908 0.985693970852031 0.168542190469327 -0.0257359384157154 -0.0275801964677834 -0.168451995498281 0.98532393555391 0.0393144115751475 9.03189138932654e-05 -2.6430099185929e-05 2.41169196181681e-06 -6.3588324062957e-07 -6.14495359278298e-06 3.68514349124713e-06 -2.6430099185929e-05 6.12280596925423e-05 -4.15837259328986e-07 3.39480948271451e-06 -2.99629326182978e-06 3.21821198770276e-05 2.41169196181681e-06 -4.15837259328986e-07 1.23003896348403e-05 2.94399802091503e-06 -5.54062197309393e-06 -1.13926022359371e-06 -6.3588324062957e-07 3.39480948271451e-06 2.94399802091503e-06 2.73203956262309e-05 9.27119765342314e-06 2.9834013454869e-06 -6.14495359278298e-06 -2.99629326182978e-06 -5.54062197309393e-06 9.27119765342314e-06 2.93620479200153e-05 -4.41468013588821e-06 3.68514349124713e-06 3.21821198770276e-05 -1.13926022359371e-06 2.9834013454869e-06 -4.41468013588821e-06 5.8626258629423e-05 1387 1401 0 0 1 1414 1464 0 0 8 0 0 0 0 0 0 0 0 1041 0 0 15 0 0 2510 +1268 1302 0.999407789048728 -0.00632624623784416 0.0338238051861713 -0.00451830643802706 0.000490085096583477 0.985471994766869 0.169837296689525 -0.023113280023572 -0.0344068453266499 -0.169720140639659 0.984891487858395 0.0279533644717694 8.88531790470883e-05 -2.09786530863886e-05 2.36846925054287e-06 1.39440534116111e-05 2.44841103552463e-06 1.47851252152179e-05 -2.09786530863886e-05 6.32332588807573e-05 -1.12332936107217e-05 1.10785897012558e-05 -9.41446650969746e-06 1.82820436998757e-05 2.36846925054287e-06 -1.12332936107217e-05 1.80754810711621e-05 -8.37490608857926e-06 -2.82947042529073e-06 -2.24999226499926e-06 1.39440534116111e-05 1.10785897012558e-05 -8.37490608857926e-06 4.49960357761519e-05 3.79324788516817e-06 -4.01960356887955e-07 2.44841103552463e-06 -9.41446650969746e-06 -2.82947042529073e-06 3.79324788516817e-06 2.97109748740517e-05 2.09101559660645e-06 1.47851252152179e-05 1.82820436998757e-05 -2.24999226499926e-06 -4.01960356887955e-07 2.09101559660645e-06 6.94754384069738e-05 1381 1401 0 0 10 1403 1463 0 0 10 0 0 0 0 0 0 0 0 938 0 0 10 0 0 2536 +1268 1303 0.999427921389255 -0.00583850257498672 0.0333127878634538 -0.00291748532275178 6.97381324364643e-05 0.985340100735117 0.170601527015154 -0.0223700105888045 -0.0338204832039178 -0.170501606358976 0.984776815905443 0.0231061687802604 0.00012453507305445 -1.58782806797533e-05 3.26698589104787e-06 5.08315325197627e-07 -1.32366996311005e-05 -1.5726120412004e-05 -1.58782806797533e-05 7.80084561778263e-05 -4.84730445418867e-06 6.25212208087371e-06 -8.50000592265261e-06 2.78552526901604e-05 3.26698589104787e-06 -4.84730445418867e-06 1.57269342657385e-05 -4.14222984609418e-06 -7.93747483403155e-06 -1.44862460215107e-06 5.08315325197627e-07 6.25212208087371e-06 -4.14222984609418e-06 3.48186008462644e-05 6.23329100667854e-06 6.07063522867565e-06 -1.32366996311005e-05 -8.50000592265261e-06 -7.93747483403155e-06 6.23329100667854e-06 2.88544505825288e-05 3.29031378459141e-06 -1.5726120412004e-05 2.78552526901604e-05 -1.44862460215107e-06 6.07063522867565e-06 3.29031378459141e-06 6.80872987758999e-05 1382 1405 0 0 10 1405 1463 0 0 13 0 0 0 0 0 0 0 0 931 0 0 12 0 0 2613 +1269 1308 0.998818214132065 -0.00183534385673409 0.0485675470963823 -0.00462023979661187 -0.00572068786614619 0.987900829473742 0.154981369381715 -0.0277100530195688 -0.048264364166224 -0.155076054366949 0.986722842805217 0.0234324456254802 0.000156964837632043 -7.47083992724106e-05 1.5386744153288e-06 -7.49748863673376e-06 -1.21387347377868e-05 -9.48890430141631e-06 -7.47083992724106e-05 0.000102750951808685 -3.50718344982043e-06 9.86806701665766e-06 2.67669228867069e-06 4.177811882913e-05 1.5386744153288e-06 -3.50718344982043e-06 1.52997890272345e-05 -8.65834724577314e-07 -3.23792421707568e-06 -4.9193449549077e-06 -7.49748863673376e-06 9.86806701665766e-06 -8.65834724577314e-07 3.75921289117202e-05 1.52680111719496e-05 5.4662946917241e-06 -1.21387347377868e-05 2.67669228867069e-06 -3.23792421707568e-06 1.52680111719496e-05 4.09940128664941e-05 -4.95991252238308e-06 -9.48890430141631e-06 4.177811882913e-05 -4.9193449549077e-06 5.4662946917241e-06 -4.95991252238308e-06 7.9891816933562e-05 1253 1256 0 0 0 1285 1321 0 0 1 0 0 0 0 0 0 0 0 1048 0 0 15 0 0 2723 +1269 1273 0.99918343564999 -0.00181524134884652 -0.0403629387127388 0.00247522683977091 0.00260007096030385 0.999808415095546 0.019400328222308 -0.00559583766410069 0.0403199895050117 -0.0194894331107227 0.998996726943256 0.00926213196748533 6.30521937641273e-05 4.37612189837622e-06 1.39730649874613e-06 -2.3326845529212e-06 -5.53437713380459e-06 3.50731159924036e-07 4.37612189837622e-06 6.74097395442151e-05 -8.76031618082292e-07 8.95600066630966e-06 -2.02506497352837e-06 7.91704617514205e-06 1.39730649874613e-06 -8.76031618082292e-07 1.12181846138741e-05 2.17562362202417e-06 -5.38300071062612e-06 -1.41799005974442e-06 -2.3326845529212e-06 8.95600066630966e-06 2.17562362202417e-06 2.52017282653475e-05 3.32628481469513e-06 1.65528910222907e-06 -5.53437713380459e-06 -2.02506497352837e-06 -5.38300071062612e-06 3.32628481469513e-06 2.16725716935211e-05 7.40023019822447e-07 3.50731159924036e-07 7.91704617514205e-06 -1.41799005974442e-06 1.65528910222907e-06 7.40023019822447e-07 7.45991137802067e-05 1248 1252 0 0 0 1252 1329 0 0 0 0 0 0 0 0 0 0 0 794 0 0 0 0 0 3406 +1269 1312 0.998003225412943 -0.00112693376148358 0.0631529261844637 -0.00310946541171297 -0.00967755267530006 0.985307326643407 0.170516324840287 -0.0257089146639411 -0.062417201471869 -0.170787007945917 0.983328984052286 0.0162690296015453 8.55833844897588e-05 -4.36627096588711e-05 5.31356201562446e-06 6.85327479614255e-07 3.52896930973955e-07 -1.26165844590942e-06 -4.36627096588711e-05 8.03761407809485e-05 -5.07522614571269e-06 -6.08185274674126e-07 2.09117468944803e-07 2.94352850733668e-05 5.31356201562446e-06 -5.07522614571269e-06 1.65749186810215e-05 -2.74049495468753e-06 -6.24933449152807e-06 -2.72848123373084e-06 6.85327479614255e-07 -6.08185274674126e-07 -2.74049495468753e-06 3.21054424634095e-05 8.5957260059994e-06 -5.52608959454977e-06 3.52896930973955e-07 2.09117468944803e-07 -6.24933449152807e-06 8.5957260059994e-06 3.02530721966725e-05 1.29779799187685e-06 -1.26165844590942e-06 2.94352850733668e-05 -2.72848123373084e-06 -5.52608959454977e-06 1.29779799187685e-06 8.52810313998247e-05 1361 1371 0 0 0 1398 1447 0 0 10 0 0 0 0 0 0 0 0 1045 0 1 25 0 0 2565 +1269 1307 0.998779093061965 -0.000912881946431991 0.0493911926244942 -0.0037233404576416 -0.00696977466001005 0.987223688491405 0.159187974177115 -0.0268939496135636 -0.048905475189458 -0.159337865957773 0.986012017659276 0.0276854224418552 0.000248704283289512 -6.00823778451753e-05 6.93680668046536e-06 1.261089893781e-05 -1.21492565732899e-05 2.33949585846616e-05 -6.00823778451753e-05 7.71672279929066e-05 -7.4796360713341e-06 6.88143076609275e-06 -6.03517031900396e-07 1.96820308626544e-05 6.93680668046536e-06 -7.4796360713341e-06 1.52746546713037e-05 -1.96274526833521e-06 -6.89775314025609e-06 -8.22612054499797e-07 1.261089893781e-05 6.88143076609275e-06 -1.96274526833521e-06 3.84732483327735e-05 9.33851486219211e-06 5.46234166500002e-06 -1.21492565732899e-05 -6.03517031900396e-07 -6.89775314025609e-06 9.33851486219211e-06 3.19219792888783e-05 -2.61575278074287e-06 2.33949585846616e-05 1.96820308626544e-05 -8.22612054499797e-07 5.46234166500002e-06 -2.61575278074287e-06 6.76358246436173e-05 1373 1381 0 0 0 1411 1454 0 0 9 0 0 0 0 0 0 0 0 1043 0 2 27 0 0 2545 +1269 1314 0.998181650315107 -0.00281393241419588 0.0602119154202631 -0.00905981083277677 -0.00708527798579591 0.986507670865341 0.16356165247302 -0.0269374213128584 -0.0598597678751979 -0.163690858352595 0.984693917459491 0.0176034325565763 0.000130311187109243 -9.71170524713399e-06 1.94281956661749e-07 1.19934705524539e-05 -1.21988430855803e-05 -7.00569008763445e-06 -9.71170524713399e-06 7.05868482445758e-05 -5.78503477524063e-06 2.88054329238139e-06 -2.64808009545157e-06 2.94682579389222e-05 1.94281956661749e-07 -5.78503477524063e-06 1.69451350461236e-05 2.76799007430507e-06 -8.77325671011504e-06 -2.3579171578835e-06 1.19934705524539e-05 2.88054329238139e-06 2.76799007430507e-06 3.08436047320555e-05 -5.92987003669684e-06 -2.95062057279245e-06 -1.21988430855803e-05 -2.64808009545157e-06 -8.77325671011504e-06 -5.92987003669684e-06 2.40667627381318e-05 1.51701731404809e-06 -7.00569008763445e-06 2.94682579389222e-05 -2.3579171578835e-06 -2.95062057279245e-06 1.51701731404809e-06 7.2390989858932e-05 1342 1345 0 0 0 1381 1415 0 0 0 0 0 0 0 0 0 0 0 1046 0 0 23 0 0 2470 +1269 1306 0.998919289522093 -0.00060878112463946 0.04647453502962 -0.00246932422330672 -0.0065573119419297 0.988066978934878 0.153885174070147 -0.0275087865361666 -0.0460136358134556 -0.154023616773681 0.98699517263013 0.0191283728035481 0.000139366653599589 -6.50214546602724e-05 -4.59624520564152e-07 1.63631879143474e-06 -1.21233017969387e-05 5.87164402608019e-06 -6.50214546602724e-05 6.71811325169903e-05 1.04266447608315e-06 2.94914186001418e-06 6.31561243527258e-06 2.50315432292117e-05 -4.59624520564152e-07 1.04266447608315e-06 1.60820021832653e-05 -3.2088582855548e-06 -4.54840594447067e-06 -1.88535282004064e-06 1.63631879143474e-06 2.94914186001418e-06 -3.2088582855548e-06 3.41602238290508e-05 8.13414487574592e-06 9.49687137883411e-06 -1.21233017969387e-05 6.31561243527258e-06 -4.54840594447067e-06 8.13414487574592e-06 3.2843147929838e-05 -2.89857379568513e-06 5.87164402608019e-06 2.50315432292117e-05 -1.88535282004064e-06 9.49687137883411e-06 -2.89857379568513e-06 5.9132991856688e-05 1367 1377 0 0 0 1404 1452 0 0 10 0 0 0 0 0 0 0 0 1040 0 0 20 0 0 2728 +1269 1315 0.998335783746748 -0.000989758214636494 0.0576600665057086 -0.00959857120862988 -0.00866906892970462 0.985915174850873 0.167021301763174 -0.0291800490028469 -0.0570132452563281 -0.16724320128917 0.984265818510372 0.0198906981815677 0.000174335076947448 -8.13733238248727e-05 4.07335423872927e-06 4.63288198770178e-07 -1.41558273955087e-08 -3.58646816587096e-06 -8.13733238248727e-05 9.38151846810993e-05 -6.60833948176583e-06 2.13134122646994e-06 -2.45578236797009e-06 2.1581979655946e-05 4.07335423872927e-06 -6.60833948176583e-06 1.59228116305956e-05 4.95705709299493e-06 -7.48130346266312e-06 -5.76449874866415e-06 4.63288198770178e-07 2.13134122646994e-06 4.95705709299493e-06 2.66940518266686e-05 -7.16329871099007e-06 5.42767443308896e-06 -1.41558273955087e-08 -2.45578236797009e-06 -7.48130346266312e-06 -7.16329871099007e-06 2.70554743594713e-05 2.04662392395679e-06 -3.58646816587096e-06 2.1581979655946e-05 -5.76449874866415e-06 5.42767443308896e-06 2.04662392395679e-06 7.21160914930562e-05 1230 1234 0 0 0 1271 1305 0 0 0 0 0 0 0 0 0 0 0 1049 0 0 22 0 0 2648 +1269 1309 0.998315001857033 -0.00267656432771381 0.0579654472129043 -0.000894380553398177 -0.00650850800951453 0.987467245429211 0.157689817451659 -0.0250829153990016 -0.0576610474296337 -0.157801378979548 0.985785944514057 0.0214407414835974 9.70114935753042e-05 -3.14424350665763e-05 2.23849380533386e-06 1.08503632163711e-05 1.8470798791935e-06 3.36052394252161e-06 -3.14424350665763e-05 8.39261868458709e-05 -9.33531698748112e-06 6.41758772570135e-06 -6.82557888948478e-06 1.96763014063758e-05 2.23849380533386e-06 -9.33531698748112e-06 1.53230599269855e-05 -1.41403559128885e-06 -7.23896811577592e-06 -4.67799316212755e-06 1.08503632163711e-05 6.41758772570135e-06 -1.41403559128885e-06 3.85516982098265e-05 4.96870195086418e-06 7.0190330855796e-07 1.8470798791935e-06 -6.82557888948478e-06 -7.23896811577592e-06 4.96870195086418e-06 2.71745609633201e-05 -1.72153048207211e-06 3.36052394252161e-06 1.96763014063758e-05 -4.67799316212755e-06 7.0190330855796e-07 -1.72153048207211e-06 7.37246904353968e-05 1374 1386 0 0 0 1405 1453 0 0 11 0 0 0 0 0 0 0 0 944 0 0 17 0 0 2494 +1269 1311 0.9985671629896 -0.00318521446285437 0.0534179315186047 -0.0063358021117029 -0.00504159232889152 0.988187190156601 0.153168729044776 -0.030454198421589 -0.0532747909023581 -0.153218574654734 0.98675522042454 0.0183451264083311 0.00023544761069029 -0.000103160373753652 6.404468884053e-06 -5.07634798180165e-06 -8.83888852994404e-06 5.45220255173112e-06 -0.000103160373753652 0.000117214837905113 -5.55566730550851e-06 1.36061324283611e-05 3.427395051108e-06 1.41541723501129e-05 6.404468884053e-06 -5.55566730550851e-06 1.41455663097321e-05 1.43638677992033e-06 -7.32415227597889e-06 -1.05679403242249e-06 -5.07634798180165e-06 1.36061324283611e-05 1.43638677992033e-06 3.3676079557901e-05 7.29007389893721e-06 -3.36488608022467e-07 -8.83888852994404e-06 3.427395051108e-06 -7.32415227597889e-06 7.29007389893721e-06 3.07889592888773e-05 2.62162640536293e-06 5.45220255173112e-06 1.41541723501129e-05 -1.05679403242249e-06 -3.36488608022467e-07 2.62162640536293e-06 7.94336330446549e-05 1342 1344 0 0 0 1379 1411 0 0 1 0 0 0 0 0 0 0 0 944 0 0 20 0 0 2693 +1269 1313 0.998799079687274 -0.00196107861465221 0.0489545971949616 -0.00698512018518884 -0.00499952882303964 0.989903056389209 0.141657840103717 -0.0324896843724564 -0.0487381075484203 -0.141732470245776 0.988704457232104 0.0246192960733562 0.000134483919529576 -4.85860949062736e-05 5.87630569114954e-06 -3.5525657435494e-06 -5.51458069847042e-06 3.27549532826031e-06 -4.85860949062736e-05 7.89854552529198e-05 -2.78921028659182e-06 5.91863219010487e-06 6.04790514292684e-06 2.98866733948088e-05 5.87630569114954e-06 -2.78921028659182e-06 1.53107057229281e-05 -2.09843387633253e-08 -4.20022234446648e-06 -4.81592451008705e-06 -3.5525657435494e-06 5.91863219010487e-06 -2.09843387633253e-08 3.22912380451703e-05 2.63064878849272e-06 6.56615093936501e-06 -5.51458069847042e-06 6.04790514292684e-06 -4.20022234446648e-06 2.63064878849272e-06 2.49185647963871e-05 -1.75041497368906e-06 3.27549532826031e-06 2.98866733948088e-05 -4.81592451008705e-06 6.56615093936501e-06 -1.75041497368906e-06 7.44158769617973e-05 1358 1361 0 0 0 1401 1440 0 0 8 0 0 0 0 0 0 0 0 1054 0 0 27 0 0 2673 +1269 1310 0.998392901967489 -0.00151216054409359 0.0566509194225925 -0.00706484768498315 -0.00705097747730869 0.988561884712835 0.150650867271389 -0.0328218717393954 -0.0562307479725343 -0.150808200915919 0.986962506642959 0.0141102919518053 0.000169214342389201 -4.2594670410417e-05 5.80710407951112e-06 1.57562321957626e-06 -5.6102348156556e-06 1.24529014351782e-05 -4.2594670410417e-05 6.6814272880163e-05 -5.58766872951413e-06 5.61077403673182e-06 -7.74020289952332e-07 2.73353928664802e-05 5.80710407951112e-06 -5.58766872951413e-06 1.71404636409166e-05 -2.43816823185533e-06 -6.36865894870349e-06 3.05636578817404e-07 1.57562321957626e-06 5.61077403673182e-06 -2.43816823185533e-06 3.33107700408094e-05 4.40766345202154e-06 8.44904168440423e-06 -5.6102348156556e-06 -7.74020289952332e-07 -6.36865894870349e-06 4.40766345202154e-06 2.75070882016777e-05 3.22207678966341e-06 1.24529014351782e-05 2.73353928664802e-05 3.05636578817404e-07 8.44904168440423e-06 3.22207678966341e-06 7.37911097007685e-05 1359 1364 0 0 0 1404 1438 0 0 6 0 0 0 0 0 0 0 0 1043 0 3 34 0 0 2483 +1269 1318 0.998561457644389 -0.000636808866122672 0.0536153875448258 -0.00999269917261982 -0.00767060881662292 0.987948040719684 0.154595700452894 -0.0327926591327944 -0.05306766499005 -0.154784570654205 0.986521950906262 0.0243849761679514 0.000149849491249952 -7.70359285738924e-05 7.26363017458034e-06 -4.64571425305635e-06 -1.09113843936699e-05 2.90572565879014e-06 -7.70359285738924e-05 8.94557131737358e-05 -4.54585834498953e-06 5.11518743227044e-06 7.29029793241829e-06 3.4009736235982e-05 7.26363017458034e-06 -4.54585834498953e-06 1.59916141026189e-05 1.76394294641643e-06 -7.60558313400506e-06 -1.02883758341141e-07 -4.64571425305635e-06 5.11518743227044e-06 1.76394294641643e-06 2.96891132229525e-05 -2.99484712534492e-06 3.06030804059063e-06 -1.09113843936699e-05 7.29029793241829e-06 -7.60558313400506e-06 -2.99484712534492e-06 2.8059276753901e-05 -3.39981049172421e-06 2.90572565879014e-06 3.4009736235982e-05 -1.02883758341141e-07 3.06030804059063e-06 -3.39981049172421e-06 7.12314654519709e-05 1356 1360 0 0 0 1406 1439 0 0 5 0 0 0 0 0 0 0 0 1056 0 4 37 0 0 2676 +1269 1305 0.998793883553938 -0.00159530924056328 0.0490737522884699 -0.0064405957554952 -0.00662451653056406 0.985954952698102 0.166880037844016 -0.0256596760031625 -0.0486507343827348 -0.167003850969105 0.98475520806214 0.0316177455054006 0.000156209037433555 -5.05613952921787e-05 8.62659787034526e-06 -1.96123269192807e-06 -1.48719682216709e-05 3.29196945221408e-06 -5.05613952921787e-05 6.23303191184801e-05 -2.99786718266419e-06 -9.12100593005536e-07 3.67120810511771e-06 2.67011667303598e-05 8.62659787034526e-06 -2.99786718266419e-06 1.5102475769571e-05 4.73124061075959e-07 -5.81257369511708e-06 3.08443012920059e-06 -1.96123269192807e-06 -9.12100593005536e-07 4.73124061075959e-07 3.59796448667905e-05 1.34203166134958e-05 -5.0360688415272e-06 -1.48719682216709e-05 3.67120810511771e-06 -5.81257369511708e-06 1.34203166134958e-05 3.60505923676987e-05 -5.21515036163767e-06 3.29196945221408e-06 2.67011667303598e-05 3.08443012920059e-06 -5.0360688415272e-06 -5.21515036163767e-06 7.57903716108e-05 1241 1245 0 0 0 1273 1311 0 0 0 0 0 0 0 0 0 0 0 943 0 0 18 0 0 2561 +1269 1296 0.998739889254654 -0.00293521610188995 0.0501000810182623 -0.00823709518653578 -0.00492454426285632 0.987738623473628 0.156038971293151 -0.0323498105986103 -0.0499437931619577 -0.156089064975279 0.986479508818981 0.0105572547330733 9.77855729211521e-05 -4.47375420234685e-05 4.77123315993115e-06 -4.48127750775212e-06 -6.30290273289918e-06 -7.35811870991364e-06 -4.47375420234685e-05 0.000104791677516913 -5.33391149943744e-06 1.31883247123536e-05 3.02215094754988e-06 5.49340084390466e-05 4.77123315993115e-06 -5.33391149943744e-06 1.39821065307416e-05 -1.40009675531612e-06 -6.88487403935041e-06 -1.18690416763719e-06 -4.48127750775212e-06 1.31883247123536e-05 -1.40009675531612e-06 3.91995016993546e-05 1.35550395738701e-05 5.62591500839842e-06 -6.30290273289918e-06 3.02215094754988e-06 -6.88487403935041e-06 1.35550395738701e-05 3.00124671592072e-05 3.2683576701128e-06 -7.35811870991364e-06 5.49340084390466e-05 -1.18690416763719e-06 5.62591500839842e-06 3.2683576701128e-06 8.0438091507214e-05 1343 1344 0 0 0 1382 1414 0 0 1 0 0 0 0 0 0 0 0 1029 0 0 22 0 0 2665 +1269 1302 0.998465619400383 -0.00261361091830829 0.0553134333898887 -0.0054214883919957 -0.00618635094605882 0.987367805312955 0.158324180381427 -0.0258733201267584 -0.0550285011369759 -0.158423439141581 0.985836638593419 0.0166046187429187 0.000120162398021356 -2.32066474611108e-05 4.24339816834571e-06 6.5406675949555e-06 -8.0546480787358e-06 -1.41911487032337e-05 -2.32066474611108e-05 9.02231997601692e-05 -6.8944317833245e-06 8.59436593229862e-06 -4.4867840085159e-06 1.45223235147452e-05 4.24339816834571e-06 -6.8944317833245e-06 1.50450686942252e-05 -3.44101499032044e-06 -5.85215872234957e-06 4.97458661974638e-07 6.5406675949555e-06 8.59436593229862e-06 -3.44101499032044e-06 3.60306130831699e-05 7.34577209463609e-06 -6.28517488518986e-06 -8.0546480787358e-06 -4.4867840085159e-06 -5.85215872234957e-06 7.34577209463609e-06 2.85153615022656e-05 3.89504845737544e-06 -1.41911487032337e-05 1.45223235147452e-05 4.97458661974638e-07 -6.28517488518986e-06 3.89504845737544e-06 7.82917914047023e-05 1346 1349 0 0 0 1382 1418 0 0 2 0 0 0 0 0 0 0 0 945 0 0 18 0 0 2483 +1269 1316 0.998104514863089 -0.00108114746299685 0.061532174755003 -0.00820697027451965 -0.00913267154971876 0.986173000396306 0.165467240261366 -0.0293989560627839 -0.0608602638860688 -0.165715552708582 0.984293850366956 0.0183015686210386 0.000120815388882541 -5.54651284582767e-05 8.50066609031893e-06 -2.23848566034703e-06 8.76520689582815e-06 -1.7371322909678e-05 -5.54651284582767e-05 6.9401346714778e-05 -9.24689680894337e-06 -4.36304220723108e-07 -6.03163152056556e-06 3.38800042780177e-05 8.50066609031893e-06 -9.24689680894337e-06 1.74954070498589e-05 3.3896146840202e-06 -3.26228987698816e-06 -3.38693870233345e-06 -2.23848566034703e-06 -4.36304220723108e-07 3.3896146840202e-06 2.54439868678833e-05 -4.84183755242794e-06 -8.48288604364352e-07 8.76520689582815e-06 -6.03163152056556e-06 -3.26228987698816e-06 -4.84183755242794e-06 2.95525434581456e-05 -5.15751585074806e-06 -1.7371322909678e-05 3.38800042780177e-05 -3.38693870233345e-06 -8.48288604364352e-07 -5.15751585074806e-06 6.78905166163033e-05 1243 1246 0 0 0 1283 1315 0 0 0 0 0 0 0 0 0 0 0 1035 0 0 23 0 0 2727 +1270 1273 0.999931955351556 -0.00403610473353503 -0.0109450685421832 0.0026131755747378 0.00415308194261723 0.999934277644207 0.0106860798488379 0.000628912057582279 0.0109012190690335 -0.0107308084848146 0.999882999741505 0.00804381924296669 6.23056631337096e-05 1.02588262292895e-05 -2.82621094876561e-07 3.04630610393751e-06 -3.49774007343359e-06 1.60413686091444e-05 1.02588262292895e-05 4.0636018967012e-05 -4.08035801649253e-07 1.27018290498944e-06 -1.38220291192222e-06 2.10008581975483e-05 -2.82621094876561e-07 -4.08035801649253e-07 1.02348659163432e-05 1.51512389686657e-06 -6.01790688350543e-06 -1.01592795954782e-06 3.04630610393751e-06 1.27018290498944e-06 1.51512389686657e-06 2.11991096301015e-05 -2.31789918529387e-06 -2.99390102273629e-06 -3.49774007343359e-06 -1.38220291192222e-06 -6.01790688350543e-06 -2.31789918529387e-06 1.54917704922326e-05 -1.03187223182783e-06 1.60413686091444e-05 2.10008581975483e-05 -1.01592795954782e-06 -2.99390102273629e-06 -1.03187223182783e-06 4.82557962713265e-05 1252 1264 0 0 8 1252 1329 0 0 10 0 0 0 0 0 0 0 0 796 0 0 0 0 0 3387 +1269 1317 0.998256748597282 -0.00100726250110159 0.0590122809442027 -0.00506160721151978 -0.00827583195488213 0.987587523475149 0.156851503281534 -0.0275625168156651 -0.0584377830298017 -0.157066447398789 0.98585757420435 0.0218502933535372 0.000157160345681643 -8.04049075485442e-05 -1.36206164526802e-06 -4.00004463817913e-06 -7.74495024668766e-06 6.91639674613979e-06 -8.04049075485442e-05 9.94256850514682e-05 1.72292676407431e-06 -2.01373654194019e-06 8.21082898991281e-06 2.86190856881928e-05 -1.36206164526802e-06 1.72292676407431e-06 1.58237197844347e-05 3.86881411753978e-06 -8.4935272762083e-06 -9.97375748371711e-08 -4.00004463817913e-06 -2.01373654194019e-06 3.86881411753978e-06 2.64648967857994e-05 -6.18212502016761e-06 1.8201694837928e-06 -7.74495024668766e-06 8.21082898991281e-06 -8.4935272762083e-06 -6.18212502016761e-06 2.31763639360963e-05 -6.27344622253638e-07 6.91639674613979e-06 2.86190856881928e-05 -9.97375748371711e-08 1.8201694837928e-06 -6.27344622253638e-07 7.6449819567193e-05 1340 1342 0 0 0 1379 1410 0 0 1 0 0 0 0 0 0 0 0 946 0 0 22 0 0 2709 +1269 1301 0.99873024150674 -0.00178915756444165 0.0503458400972538 -0.00567509212673733 -0.00606265487412285 0.987837367622234 0.155372389262223 -0.029513772711298 -0.050011487837955 -0.155480333304197 0.986572205689908 0.0251796315426893 0.000185580515212264 -7.37537991933083e-05 1.9437441317942e-06 -5.1214299705861e-06 -1.9301545278096e-05 1.82892209247822e-05 -7.37537991933083e-05 0.000109722627703597 -8.63606022440744e-06 1.68547462282135e-05 -1.28321656757419e-06 1.86772666975478e-05 1.9437441317942e-06 -8.63606022440744e-06 1.61676928037759e-05 -3.93274084746177e-06 -5.02950842053133e-06 -1.89708024227401e-07 -5.1214299705861e-06 1.68547462282135e-05 -3.93274084746177e-06 3.67326128887959e-05 7.3089029152474e-06 -1.79489540919806e-06 -1.9301545278096e-05 -1.28321656757419e-06 -5.02950842053133e-06 7.3089029152474e-06 3.10509741789353e-05 -4.07866034881386e-06 1.82892209247822e-05 1.86772666975478e-05 -1.89708024227401e-07 -1.79489540919806e-06 -4.07866034881386e-06 8.33217511839709e-05 1364 1370 0 0 0 1410 1450 0 0 8 0 0 0 0 0 0 0 0 1036 0 2 29 0 0 2685 +1269 1304 0.998568040824826 -0.00150540227225079 0.0534752429379018 -0.00199225113071403 -0.00751353529407225 0.985749166941873 0.168053939735989 -0.0258676724991863 -0.0529661649607903 -0.168215081480233 0.984326303484746 0.0157293351804612 8.8136442061448e-05 -4.69802233341339e-05 7.84409372619614e-06 -8.95889572862088e-07 3.68288657986301e-06 -1.6184474694791e-05 -4.69802233341339e-05 7.12121751080114e-05 -2.90960188604483e-06 2.34555168520828e-06 -4.46663171284283e-06 2.62969570834032e-05 7.84409372619614e-06 -2.90960188604483e-06 1.6356270627953e-05 -2.01526388786237e-06 -5.49996348340359e-06 -1.05954232848653e-07 -8.95889572862088e-07 2.34555168520828e-06 -2.01526388786237e-06 3.68274273526682e-05 1.14855692585115e-05 5.80912036356138e-07 3.68288657986301e-06 -4.46663171284283e-06 -5.49996348340359e-06 1.14855692585115e-05 3.12423616086517e-05 -5.69079977611993e-07 -1.6184474694791e-05 2.62969570834032e-05 -1.05954232848653e-07 5.80912036356138e-07 -5.69079977611993e-07 7.04557345723444e-05 1370 1382 0 0 0 1405 1453 0 0 11 0 0 0 0 0 0 0 0 1042 0 0 20 0 0 2573 +1269 1295 0.998134202479404 -0.00246284497111285 0.0610085914888411 -0.0029613352461176 -0.00715421544078779 0.987586261657753 0.156914604120495 -0.0263120879640688 -0.0606377031411219 -0.157058301848432 0.985726005935856 0.0194441663956451 0.000143526435655453 -8.60552441889699e-06 2.56608912290416e-06 6.76439231208864e-06 -3.42492430134438e-06 1.97595880332505e-05 -8.60552441889699e-06 9.27105491326356e-05 -5.69043139301479e-06 3.95625233785145e-06 -9.91548302113045e-06 3.36087720792986e-05 2.56608912290416e-06 -5.69043139301479e-06 1.44455488941134e-05 -8.40578687529083e-07 -2.55623949973919e-06 8.80490843616066e-07 6.76439231208864e-06 3.95625233785145e-06 -8.40578687529083e-07 3.0783110644614e-05 3.4326957353443e-06 1.76921358848717e-06 -3.42492430134438e-06 -9.91548302113045e-06 -2.55623949973919e-06 3.4326957353443e-06 2.88581780218584e-05 3.68051055253699e-06 1.97595880332505e-05 3.36087720792986e-05 8.80490843616066e-07 1.76921358848717e-06 3.68051055253699e-06 5.89556080266997e-05 1350 1353 0 0 0 1384 1420 0 0 1 0 0 0 0 0 0 0 0 917 0 0 17 0 0 2476 +1269 1303 0.998858709785224 -0.00168377629464768 0.0477330366055652 -0.00481399006052504 -0.00524139163819333 0.989478535220669 0.144584771505349 -0.0295942968886019 -0.0474742635529369 -0.144669945859355 0.988340427719699 0.0239349174932429 0.000234211646697132 -8.75865284934387e-05 -3.61117937029178e-06 -3.01316582373002e-06 -2.6057778707493e-05 2.74429381855425e-05 -8.75865284934387e-05 9.67615127107477e-05 -2.08368647660032e-06 1.06628638598657e-05 8.08060149982933e-06 3.26172286816796e-05 -3.61117937029178e-06 -2.08368647660032e-06 1.46924259470832e-05 -3.94641111219855e-06 -7.36059058962443e-06 -1.22791750787734e-06 -3.01316582373002e-06 1.06628638598657e-05 -3.94641111219855e-06 3.99015791954871e-05 1.31721892412664e-05 1.56831908514411e-06 -2.6057778707493e-05 8.08060149982933e-06 -7.36059058962443e-06 1.31721892412664e-05 3.0546189146259e-05 -6.10973436368377e-06 2.74429381855425e-05 3.26172286816796e-05 -1.22791750787734e-06 1.56831908514411e-06 -6.10973436368377e-06 0.000106724339562338 1363 1369 0 0 0 1401 1445 0 0 9 0 0 0 0 0 0 0 0 941 0 0 23 0 0 2615 +1270 1309 0.996855480839559 -0.0086753803500399 0.0787647643043067 -0.00555261704973886 -0.0038216295756656 0.987568835915598 0.157140667797034 -0.0226985222520649 -0.0791488816567691 -0.156947545709048 0.984430252698681 0.0175749808293424 4.56856685084657e-05 -1.90230062978581e-05 5.01896593117763e-06 1.58060012199893e-06 3.8261159938495e-06 8.19927142984746e-06 -1.90230062978581e-05 5.59378307499289e-05 -3.28997375084756e-06 6.60016126815923e-06 1.04945906161782e-06 2.11776933627452e-05 5.01896593117763e-06 -3.28997375084756e-06 1.51890727190818e-05 -1.1525688330726e-07 -8.46478153283784e-06 -8.40513139405243e-07 1.58060012199893e-06 6.60016126815923e-06 -1.1525688330726e-07 3.07667108781797e-05 7.22426368972577e-06 1.12244923507515e-06 3.8261159938495e-06 1.04945906161782e-06 -8.46478153283784e-06 7.22426368972577e-06 2.65195286703272e-05 2.84550824859233e-06 8.19927142984746e-06 2.11776933627452e-05 -8.40513139405243e-07 1.12244923507515e-06 2.84550824859233e-06 5.72887836817832e-05 1374 1392 0 0 0 1405 1456 0 0 9 0 0 0 0 0 0 0 0 931 0 0 20 0 0 2509 +1269 1297 0.998623449793735 -0.00211204210428645 0.05240939610613 -0.00637134395379863 -0.00679784571201133 0.985550618036139 0.169244700307751 -0.0301847843163806 -0.0520095646562745 -0.169367997469222 0.984179600793235 0.025979183720804 8.01599779120366e-05 -2.96978406130294e-05 4.76641729286363e-06 4.38481026059169e-06 2.45639150716539e-06 -1.38403378739998e-05 -2.96978406130294e-05 7.03820868283653e-05 1.04694511080946e-08 9.49202347306556e-07 -1.59299621090782e-06 2.49683586592667e-05 4.76641729286363e-06 1.04694511080946e-08 1.24305278714171e-05 8.4542542214836e-07 -5.48960153085039e-06 4.05078229786254e-07 4.38481026059169e-06 9.49202347306556e-07 8.4542542214836e-07 2.63419260485955e-05 9.31277820080485e-06 -1.74797491496501e-06 2.45639150716539e-06 -1.59299621090782e-06 -5.48960153085039e-06 9.31277820080485e-06 2.45962927787539e-05 -5.99279885242786e-07 -1.38403378739998e-05 2.49683586592667e-05 4.05078229786254e-07 -1.74797491496501e-06 -5.99279885242786e-07 6.27084223048591e-05 1366 1375 0 0 0 1407 1446 0 0 8 0 0 0 0 0 0 0 0 1052 0 3 29 0 0 2570 +1270 1272 0.999979135305995 0.00617123293345933 0.00190914555652378 0.00307567582011094 -0.00619090975420715 0.999925935539818 0.0104783620492957 -0.00215029563249363 -0.0018443397437214 -0.0104899627693259 0.999943277937308 0.00393207792889461 6.55968457324991e-05 4.51770988657128e-05 -7.70062947804301e-06 1.61989149754887e-05 -6.21441582307906e-06 4.35831551142647e-05 4.51770988657128e-05 6.60661847704325e-05 -8.16478549623725e-06 2.1330717252241e-05 -4.75615951306886e-06 4.02863089709862e-05 -7.70062947804301e-06 -8.16478549623725e-06 1.31278530775223e-05 -3.63330875382058e-07 -3.62367016634478e-06 -6.05277108052663e-06 1.61989149754887e-05 2.1330717252241e-05 -3.63330875382058e-07 2.53813964070408e-05 -9.0267434134766e-06 1.16241962618999e-05 -6.21441582307906e-06 -4.75615951306886e-06 -3.62367016634478e-06 -9.0267434134766e-06 1.9638968995195e-05 -7.2259673811523e-06 4.35831551142647e-05 4.02863089709862e-05 -6.05277108052663e-06 1.16241962618999e-05 -7.2259673811523e-06 5.98928297173532e-05 1454 1455 0 0 0 1469 1543 0 0 0 0 0 0 0 0 0 0 0 806 0 0 0 0 0 3443 +1270 1308 0.997402472229458 -0.00687879007307721 0.0717007017936133 -0.0085733754051955 -0.00407107403641164 0.988454823872966 0.151461174954024 -0.0269819883901843 -0.0719147741897045 -0.151359649211386 0.985859280954361 0.017929372817105 0.000191540248683728 -0.000107214175461927 2.57673722945279e-06 -2.1822610665499e-05 -1.30211383709736e-05 1.95150261719328e-05 -0.000107214175461927 0.000102583811715326 -1.50170722786419e-06 1.27303270232488e-05 5.19426940407258e-06 1.35346135473566e-05 2.57673722945279e-06 -1.50170722786419e-06 1.41461179282042e-05 -3.65358201543361e-07 -7.55304146250182e-06 -2.37005229121554e-06 -2.1822610665499e-05 1.27303270232488e-05 -3.65358201543361e-07 3.80594571265394e-05 1.31232359044397e-05 -5.00336801839639e-06 -1.30211383709736e-05 5.19426940407258e-06 -7.55304146250182e-06 1.31232359044397e-05 3.32581737843521e-05 -8.90134099760223e-06 1.95150261719328e-05 1.35346135473566e-05 -2.37005229121554e-06 -5.00336801839639e-06 -8.90134099760223e-06 6.88547832658374e-05 1272 1276 0 0 6 1304 1340 0 0 8 0 0 0 0 0 0 0 0 1036 0 0 18 0 0 2725 +1270 1312 0.997089336329286 -0.00650067802084464 0.0759644427590558 -0.00785326567439034 -0.00556990350988758 0.98748518476147 0.157613406953522 -0.0232450840840561 -0.0760383558036015 -0.157577761952235 0.984574739359491 0.0180723968988688 8.47277573597912e-05 -3.64131459406711e-05 3.7879781634883e-06 -1.21194476007363e-06 6.7607186536158e-07 9.2441805624719e-07 -3.64131459406711e-05 6.7744986813855e-05 -3.11947318108402e-07 1.24053831242424e-07 -5.90490886713867e-06 3.37546969389782e-05 3.7879781634883e-06 -3.11947318108402e-07 1.62871025840859e-05 6.2791499501369e-07 -7.59065151750327e-06 5.12631730775701e-07 -1.21194476007363e-06 1.24053831242424e-07 6.2791499501369e-07 2.86740810748625e-05 3.3408060714686e-06 -2.68935563456838e-07 6.7607186536158e-07 -5.90490886713867e-06 -7.59065151750327e-06 3.3408060714686e-06 2.90255178014211e-05 -1.49110816580812e-07 9.2441805624719e-07 3.37546969389782e-05 5.12631730775701e-07 -2.68935563456838e-07 -1.49110816580812e-07 5.49057661264127e-05 1364 1383 0 0 1 1399 1450 0 0 9 0 0 0 0 0 0 0 0 1035 0 2 27 0 0 2540 +1270 1310 0.996687944702352 -0.00816147494792397 0.0809106371973114 -0.0109923236151758 -0.00421514905339637 0.988428818872745 0.151626852965723 -0.0292562005506276 -0.081211904321092 -0.151465706839884 0.985120686133448 0.00321192210481483 9.14806797358537e-05 -4.86333168257911e-05 2.08028505098247e-06 -1.87075578724541e-06 -4.6435500489791e-06 1.25199267657318e-06 -4.86333168257911e-05 7.12613130538358e-05 -1.35438376009538e-06 4.53868500115146e-06 1.05480386364504e-06 1.95875202048785e-05 2.08028505098247e-06 -1.35438376009538e-06 1.41033990041546e-05 7.15791828006846e-07 -7.44264602547293e-06 1.85318864246104e-06 -1.87075578724541e-06 4.53868500115146e-06 7.15791828006846e-07 3.26299561352787e-05 6.8682999804745e-06 1.69870901555544e-06 -4.6435500489791e-06 1.05480386364504e-06 -7.44264602547293e-06 6.8682999804745e-06 2.73299295895001e-05 2.55348866633956e-07 1.25199267657318e-06 1.95875202048785e-05 1.85318864246104e-06 1.69870901555544e-06 2.55348866633956e-07 8.06227856014633e-05 1366 1369 0 0 0 1406 1446 0 0 1 0 0 0 0 0 0 0 0 1031 0 3 34 0 0 2548 +1270 1306 0.997677242684064 -0.00593326641240889 0.0678595297655616 -0.00541887768723308 -0.00469642535033011 0.987837568477139 0.155418409122285 -0.0224418254125639 -0.0679563317083297 -0.155376107091318 0.985515196395213 0.017908758459676 7.66610419800802e-05 -4.09348000526067e-05 3.95351554861624e-06 -3.44075952528576e-06 2.88979676755524e-06 6.12714157559337e-06 -4.09348000526067e-05 6.06894307500158e-05 -2.38885525444856e-06 5.50581123189773e-06 -2.49793270331861e-06 2.36070310421293e-05 3.95351554861624e-06 -2.38885525444856e-06 1.56713655624286e-05 -9.40258779515956e-08 -5.9258268177387e-06 -4.35350221449219e-06 -3.44075952528576e-06 5.50581123189773e-06 -9.40258779515956e-08 3.34375370120637e-05 6.55186564075117e-06 1.94158405679567e-06 2.88979676755524e-06 -2.49793270331861e-06 -5.9258268177387e-06 6.55186564075117e-06 2.9330438439519e-05 -6.16176011806573e-06 6.12714157559337e-06 2.36070310421293e-05 -4.35350221449219e-06 1.94158405679567e-06 -6.16176011806573e-06 6.64183154724499e-05 1373 1391 0 0 0 1405 1457 0 0 9 0 0 0 0 0 0 0 0 1036 0 2 23 0 0 2735 +1270 1313 0.997271802579007 -0.00794527602583967 0.0733881759528766 -0.0101144606046575 -0.00360293615676441 0.987766344933115 0.155899540308897 -0.0257950873501629 -0.0737290352023369 -0.155738628497712 0.985042897016056 0.0211746295861285 0.000145156706171533 -6.11843946317932e-05 4.23472416995364e-06 -4.16881259127605e-06 -1.10463554608866e-05 2.28211279877283e-05 -6.11843946317932e-05 6.24661357064569e-05 -3.24717561149206e-06 7.73345776773889e-06 4.65084478646965e-06 1.74645144209323e-05 4.23472416995364e-06 -3.24717561149206e-06 1.24723881177979e-05 2.68198984774805e-06 -5.78404075786739e-06 -2.66671482823415e-06 -4.16881259127605e-06 7.73345776773889e-06 2.68198984774805e-06 2.87484854706249e-05 -2.96523222409433e-07 8.14311752294592e-06 -1.10463554608866e-05 4.65084478646965e-06 -5.78404075786739e-06 -2.96523222409433e-07 2.29065811877975e-05 -1.17913774029972e-06 2.28211279877283e-05 1.74645144209323e-05 -2.66671482823415e-06 8.14311752294592e-06 -1.17913774029972e-06 6.17003113779063e-05 1368 1382 0 0 0 1401 1450 0 0 9 0 0 0 0 0 0 0 0 1045 0 2 29 0 0 2665 +1270 1274 0.999900926922271 -0.00695761769849789 -0.0122363350700155 0.00363515057727757 0.0070267094335949 0.999959561551229 0.00561254102972938 0.00358301408595649 0.0121967903368046 -0.00569796614908479 0.999909381637778 0.00620688054840925 5.29293489230562e-05 -1.76527619849231e-07 1.17994052514478e-06 -7.46691656127157e-07 -1.60243049539841e-06 1.36877230815305e-05 -1.76527619849231e-07 4.30677071476261e-05 -5.49597974481025e-07 5.79512654578471e-06 -3.78383862889471e-07 1.74155506115659e-05 1.17994052514478e-06 -5.49597974481025e-07 1.20738429489282e-05 2.41670331384825e-07 -3.61367833947115e-06 -2.19404911589483e-06 -7.46691656127157e-07 5.79512654578471e-06 2.41670331384825e-07 2.35108614974288e-05 -4.29754820478184e-06 -8.0213301983903e-07 -1.60243049539841e-06 -3.78383862889471e-07 -3.61367833947115e-06 -4.29754820478184e-06 1.90971431073013e-05 -6.51368781337181e-06 1.36877230815305e-05 1.74155506115659e-05 -2.19404911589483e-06 -8.0213301983903e-07 -6.51368781337181e-06 4.14442127968366e-05 1229 1255 0 0 4 1229 1309 0 0 6 0 0 0 0 0 0 0 0 778 0 0 0 0 0 3411 +1270 1314 0.996846287833832 -0.00760705508610129 0.0789912092882856 -0.0102174739885333 -0.00476816957929955 0.987854923258375 0.155305876106002 -0.0244203079242451 -0.0792132753442992 -0.15519272955621 0.984703241439837 0.020404691783034 0.000116627849517019 -3.7005827172023e-05 -2.40174021550672e-06 -5.27074669394999e-06 -1.43211207081869e-05 4.14973276407401e-05 -3.7005827172023e-05 5.30064020951312e-05 -1.58666700040115e-06 7.06767229308964e-06 5.02109835099511e-06 2.23083545211515e-05 -2.40174021550672e-06 -1.58666700040115e-06 1.65025062480314e-05 3.64666485465768e-06 -4.11039636889214e-06 -4.57410936198461e-06 -5.27074669394999e-06 7.06767229308964e-06 3.64666485465768e-06 2.82865915941439e-05 -3.54963780820475e-06 7.75378548755408e-06 -1.43211207081869e-05 5.02109835099511e-06 -4.11039636889214e-06 -3.54963780820475e-06 3.0412853947178e-05 -5.22953491905399e-06 4.14973276407401e-05 2.23083545211515e-05 -4.57410936198461e-06 7.75378548755408e-06 -5.22953491905399e-06 8.96760107329783e-05 1368 1391 0 0 5 1400 1455 0 0 9 0 0 0 0 0 0 0 0 1047 0 3 25 0 0 2533 +1270 1311 0.997390575633014 -0.0084982347384008 0.0716925354885389 -0.0101112896649858 -0.00275088581675222 0.987852859781467 0.155367821793321 -0.0260342942503828 -0.0721420284277311 -0.15515961919233 0.985251754784747 0.0178970610048947 0.000207315327029437 -0.000109227507298711 6.8740612594306e-06 -9.33175757666332e-06 -9.12847488182565e-06 4.9913779221758e-05 -0.000109227507298711 0.000111663428206087 -3.4351459376492e-06 9.27285769556197e-06 5.50523118574181e-06 -2.08694049475728e-06 6.8740612594306e-06 -3.4351459376492e-06 1.67671827659426e-05 2.79032398618548e-06 -3.40340818612864e-06 -9.40016480027018e-07 -9.33175757666332e-06 9.27285769556197e-06 2.79032398618548e-06 2.73166900249553e-05 9.44822541744013e-07 -2.90006824203358e-06 -9.12847488182565e-06 5.50523118574181e-06 -3.40340818612864e-06 9.44822541744013e-07 2.96218564749797e-05 -2.59160106421038e-06 4.9913779221758e-05 -2.08694049475728e-06 -9.40016480027018e-07 -2.90006824203358e-06 -2.59160106421038e-06 7.97913002432745e-05 1367 1390 0 0 5 1402 1456 0 0 9 0 0 0 0 0 0 0 0 935 0 1 22 0 0 2673 +1270 1317 0.996979047770015 -0.00601119701624048 0.077437999832297 -0.0112859405244762 -0.00613019299058598 0.98780074553808 0.155602403092983 -0.0284574849001986 -0.0774286706685131 -0.155607045550145 0.984779796875252 0.0217438513844757 0.000118060827150834 -4.4003738671988e-05 5.61722524128677e-06 2.33366504200052e-06 -2.93423192452362e-06 2.28520309685924e-05 -4.4003738671988e-05 7.69769150892806e-05 -1.54252236785348e-06 3.3396622043585e-06 -1.68775416509998e-07 2.78263190542147e-05 5.61722524128677e-06 -1.54252236785348e-06 1.58225333099993e-05 4.65942406434459e-06 -5.72674560740219e-06 -1.51033903971951e-06 2.33366504200052e-06 3.3396622043585e-06 4.65942406434459e-06 2.75704414088879e-05 -6.80816129748059e-06 2.86281782846558e-06 -2.93423192452362e-06 -1.68775416509998e-07 -5.72674560740219e-06 -6.80816129748059e-06 2.91668379871635e-05 -2.28107301172529e-06 2.28520309685924e-05 2.78263190542147e-05 -1.51033903971951e-06 2.86281782846558e-06 -2.28107301172529e-06 9.32707470226182e-05 1359 1379 0 0 6 1396 1446 0 0 11 0 0 0 0 0 0 0 0 938 0 4 29 0 0 2721 +1270 1307 0.997389114705735 -0.0069181785786877 0.0718824921080501 -0.00661566555162378 -0.00428579726954253 0.987975328343136 0.154552200007108 -0.0232620144896391 -0.0720873484619519 -0.154456755729318 0.985366188176405 0.0169964191482212 9.01066079296463e-05 -5.09157501364894e-05 -1.45602753981988e-07 -5.17631523895488e-06 -4.43391322722198e-06 1.47256198595359e-05 -5.09157501364894e-05 8.31364575902893e-05 -1.24272046669528e-06 8.31735225254659e-06 -3.44441309978001e-06 2.53741762507277e-05 -1.45602753981988e-07 -1.24272046669528e-06 1.42544003995729e-05 -7.94950679980863e-07 -4.56921740104364e-06 -2.08797976660986e-06 -5.17631523895488e-06 8.31735225254659e-06 -7.94950679980863e-07 3.14885155250205e-05 8.60558713994916e-06 -1.8464417488984e-06 -4.43391322722198e-06 -3.44441309978001e-06 -4.56921740104364e-06 8.60558713994916e-06 3.16281528838167e-05 -9.37577832044534e-06 1.47256198595359e-05 2.53741762507277e-05 -2.08797976660986e-06 -1.8464417488984e-06 -9.37577832044534e-06 7.79600446041894e-05 1380 1387 0 0 2 1412 1458 0 0 3 0 0 0 0 0 0 0 0 1035 0 0 27 0 0 2582 +1270 1315 0.997392477933642 -0.00621893150417861 0.0718997208084647 -0.0145148575630465 -0.00454918887039597 0.988881044898521 0.148639106297874 -0.029022825638893 -0.0720246474618953 -0.148578611957965 0.986274224658961 0.0204123183552531 0.000139016806852101 -6.95357923403629e-05 3.67862750855921e-06 -2.64648386002506e-06 -8.90001281162687e-06 -1.63005513429118e-06 -6.95357923403629e-05 7.82433774313156e-05 -4.47916415247882e-06 6.46024428271574e-06 3.85767507888417e-06 2.8260902869181e-05 3.67862750855921e-06 -4.47916415247882e-06 1.5981821272181e-05 6.04803247531155e-06 -7.15999043992618e-06 -4.01915962458639e-06 -2.64648386002506e-06 6.46024428271574e-06 6.04803247531155e-06 2.47770410509794e-05 -8.91831127646973e-06 8.90142949672508e-06 -8.90001281162687e-06 3.85767507888417e-06 -7.15999043992618e-06 -8.91831127646973e-06 2.40044658033595e-05 -3.30138935996899e-06 -1.63005513429118e-06 2.8260902869181e-05 -4.01915962458639e-06 8.90142949672508e-06 -3.30138935996899e-06 8.05913371197263e-05 1251 1253 0 0 8 1288 1321 0 0 8 0 0 0 0 0 0 0 0 1039 0 0 22 0 0 2674 +1270 1303 0.997561160756521 -0.00711495672630814 0.0694341986407617 -0.00735494427691069 -0.00386237794269588 0.987639536298761 0.156694697983677 -0.0220812661368719 -0.0696908357442337 -0.156580725922288 0.985203361587302 0.0154152158261549 0.000102277960989341 -4.30578620922107e-05 1.75100164324033e-06 1.96251234250679e-07 -2.11608157547062e-06 9.17178674458651e-06 -4.30578620922107e-05 6.14366116859542e-05 1.32513440631449e-06 2.58535519130426e-06 -9.6506223077032e-07 3.14465470728069e-05 1.75100164324033e-06 1.32513440631449e-06 1.42623813694446e-05 9.5798784241365e-07 -8.60988552553964e-06 1.00067537395014e-06 1.96251234250679e-07 2.58535519130426e-06 9.5798784241365e-07 3.22076134685704e-05 6.55185643819095e-06 3.16705024590789e-06 -2.11608157547062e-06 -9.6506223077032e-07 -8.60988552553964e-06 6.55185643819095e-06 2.57878428469268e-05 3.12535566145921e-07 9.17178674458651e-06 3.14465470728069e-05 1.00067537395014e-06 3.16705024590789e-06 3.12535566145921e-07 6.44511956460307e-05 1372 1391 0 0 0 1403 1455 0 0 11 0 0 0 0 0 0 0 0 934 0 1 22 0 0 2619 +1270 1316 0.996798311814662 -0.00634455591617036 0.0797049068355662 -0.0126568679945456 -0.00631321154854674 0.987489484008463 0.157558441007278 -0.028836985857095 -0.0797073956630312 -0.157557181946515 0.984287796070687 0.0200598035090826 0.000128657341469619 -6.6129395590774e-05 7.40011909064996e-07 -5.81794929203641e-06 -9.2154535491546e-06 3.00008758928783e-05 -6.6129395590774e-05 8.8744903632854e-05 -3.78635865358979e-06 8.75275279160182e-06 6.88493375182805e-06 -1.84990359879622e-06 7.40011909064996e-07 -3.78635865358979e-06 1.68711537577572e-05 4.26916418825536e-06 -8.23002169763962e-06 -5.71244829890968e-06 -5.81794929203641e-06 8.75275279160182e-06 4.26916418825536e-06 3.02874798695445e-05 -2.70014666909006e-06 -7.62265789765375e-07 -9.2154535491546e-06 6.88493375182805e-06 -8.23002169763962e-06 -2.70014666909006e-06 2.89825101020255e-05 -6.67539886354337e-06 3.00008758928783e-05 -1.84990359879622e-06 -5.71244829890968e-06 -7.62265789765375e-07 -6.67539886354337e-06 6.63955947735289e-05 1264 1268 0 0 7 1300 1335 0 0 8 0 0 0 0 0 0 0 0 1030 0 0 23 0 0 2737 +1271 1275 0.999760836786015 -0.0171510941943076 -0.0135686844191072 0.00557321945837335 0.0172079918049467 0.999843575559474 0.00408771702645016 0.0130885429275861 0.0134964531254779 -0.00432022920519616 0.999899585644802 0.00447740441661481 5.73987819263091e-05 1.40240882836574e-06 1.39861644960833e-06 1.12091703832451e-05 -2.27234323148009e-06 9.97251984163134e-06 1.40240882836574e-06 3.56586342431311e-05 1.90237724300521e-06 9.67665508943919e-07 -6.34212833406873e-06 1.08042556868106e-05 1.39861644960833e-06 1.90237724300521e-06 1.2000263364683e-05 1.59039300199633e-06 -1.75435374048596e-06 -2.97403697849756e-07 1.12091703832451e-05 9.67665508943919e-07 1.59039300199633e-06 2.62549445292501e-05 -1.01594906930216e-05 9.93963901140763e-07 -2.27234323148009e-06 -6.34212833406873e-06 -1.75435374048596e-06 -1.01594906930216e-05 2.6098569441963e-05 -4.37371724277045e-06 9.97251984163134e-06 1.08042556868106e-05 -2.97403697849756e-07 9.93963901140763e-07 -4.37371724277045e-06 3.2456526128661e-05 1254 1329 0 0 0 1254 1350 0 0 38 0 0 0 0 0 0 0 0 769 0 0 0 0 0 3431 +1271 1273 0.999766367114794 -0.0103924408447658 -0.0189527929175192 -0.00114140080151564 0.0105075814720358 0.99992687842499 0.00598569418399803 0.00499531020871138 0.0188892010867281 -0.00618344374469932 0.999802462042258 -0.000399809138113336 6.62347699391138e-05 2.26574915512293e-05 -1.47195521175735e-06 1.37113469802203e-05 -5.60511310318652e-06 2.44884711784665e-05 2.26574915512293e-05 4.38682300352384e-05 -1.53021764649016e-06 1.10566552931345e-05 -8.81967264851714e-06 1.48515324056544e-05 -1.47195521175735e-06 -1.53021764649016e-06 1.38740686521592e-05 1.64838490030291e-06 -1.99647814961941e-06 -1.11781381391173e-06 1.37113469802203e-05 1.10566552931345e-05 1.64838490030291e-06 2.93711652273172e-05 -9.86117869744917e-06 7.51115098845494e-06 -5.60511310318652e-06 -8.81967264851714e-06 -1.99647814961941e-06 -9.86117869744917e-06 2.51899856395619e-05 -2.331036073482e-06 2.44884711784665e-05 1.48515324056544e-05 -1.11781381391173e-06 7.51115098845494e-06 -2.331036073482e-06 5.94920867500354e-05 1239 1261 0 0 0 1252 1326 0 0 9 0 0 0 0 0 0 0 0 788 0 0 3 0 0 3453 +1271 1274 0.999721898879203 -0.0135083739883263 -0.0193299956945863 0.00277889352706167 0.0134823371069852 0.999908018801448 -0.00147665930311525 0.00578490124884402 0.0193481649645342 0.00121563512427703 0.999812067712603 0.000369622202765021 6.68204518778052e-05 3.35208929330003e-05 -4.62303639578992e-06 7.0517917218113e-06 -3.53625220718582e-06 2.01410707040077e-05 3.35208929330003e-05 5.55466360703526e-05 -2.06279975645941e-06 1.11646590150223e-05 -3.07794109414685e-06 2.18233074110359e-05 -4.62303639578992e-06 -2.06279975645941e-06 1.36616642476241e-05 -2.54062670681736e-07 -2.73119578509012e-06 -9.49817511220958e-07 7.0517917218113e-06 1.11646590150223e-05 -2.54062670681736e-07 2.23961602317571e-05 -5.62989350885335e-06 4.70350284128071e-06 -3.53625220718582e-06 -3.07794109414685e-06 -2.73119578509012e-06 -5.62989350885335e-06 2.01385582249232e-05 -2.73273780767569e-06 2.01410707040077e-05 2.18233074110359e-05 -9.49817511220958e-07 4.70350284128071e-06 -2.73273780767569e-06 4.43515892394141e-05 1228 1266 0 0 0 1229 1308 0 0 10 0 0 0 0 0 0 0 0 772 0 0 1 0 0 3436 +1270 1305 0.997334699354421 -0.00657293798968226 0.072665631145756 -0.00981261800465704 -0.00462285865020912 0.988240211392177 0.152839503288402 -0.0266196326103182 -0.0728157032619164 -0.152768063003132 0.985575868355523 0.0175040611212062 0.000209684980142064 -0.000130183868761013 -1.48236535796763e-06 -1.79431918662705e-06 -3.49201683960434e-06 2.33197162420383e-05 -0.000130183868761013 0.000114907324720461 2.11773051398885e-06 4.63541614280279e-06 4.51458178339497e-06 2.21134620137398e-05 -1.48236535796763e-06 2.11773051398885e-06 1.65712756924737e-05 -1.46556169316489e-06 -5.89096278056293e-06 -3.50339932291656e-06 -1.79431918662705e-06 4.63541614280279e-06 -1.46556169316489e-06 3.42721569000303e-05 7.47173035586949e-06 8.2075836033589e-06 -3.49201683960434e-06 4.51458178339497e-06 -5.89096278056293e-06 7.47173035586949e-06 2.85363731765483e-05 8.30809132150975e-07 2.33197162420383e-05 2.21134620137398e-05 -3.50339932291656e-06 8.2075836033589e-06 8.30809132150975e-07 0.000112097350139937 1261 1265 0 0 7 1295 1332 0 0 8 0 0 0 0 0 0 0 0 945 0 0 19 0 0 2535 +1271 1308 0.997895769662049 -0.0130490440271926 0.0635118519692389 -0.0100554811680816 0.00315550435496277 0.988152150775673 0.153445005489518 -0.0178233586056928 -0.0647616837555351 -0.152921709928279 0.986114027356755 0.0159010776250374 9.91634642643845e-05 -4.42619440844281e-05 6.59820714794913e-06 4.36075056561116e-06 -5.55340843268097e-07 2.71018830564247e-05 -4.42619440844281e-05 7.20698169494948e-05 -4.34356776913467e-06 8.72861035410611e-06 2.27998866019468e-06 1.39688377979452e-05 6.59820714794913e-06 -4.34356776913467e-06 1.4494141651512e-05 2.3436225594244e-07 -3.06000198524677e-06 -1.25689251300656e-06 4.36075056561116e-06 8.72861035410611e-06 2.3436225594244e-07 3.64654895073773e-05 9.53664393528375e-07 7.29210792331794e-07 -5.55340843268097e-07 2.27998866019468e-06 -3.06000198524677e-06 9.53664393528375e-07 4.01162324716568e-05 3.97872965342569e-06 2.71018830564247e-05 1.39688377979452e-05 -1.25689251300656e-06 7.29210792331794e-07 3.97872965342569e-06 8.90208359797565e-05 1284 1299 0 0 0 1305 1351 0 0 9 0 0 0 0 0 0 0 0 1031 0 0 9 0 0 2853 +1270 1318 0.997136595709294 -0.00619723993478355 0.0753671262187273 -0.0126195511629594 -0.00534400732965762 0.988369988218771 0.151974366174322 -0.0284370407633368 -0.0754324272640051 -0.15194196459707 0.985506767258066 0.0190062497065886 0.000115244880513131 -5.27053928521408e-05 -1.35049009242065e-06 1.91548922519822e-06 1.25192464860022e-06 -3.64944690040597e-06 -5.27053928521408e-05 8.25158223847353e-05 9.20947060513138e-08 -1.81007772916381e-06 -2.21887241109283e-07 3.58321037064523e-05 -1.35049009242065e-06 9.20947060513138e-08 1.65121323582105e-05 3.58415708819226e-06 -6.67036084133673e-06 -2.08165730794668e-06 1.91548922519822e-06 -1.81007772916381e-06 3.58415708819226e-06 2.55940843272173e-05 -7.10618109674689e-06 -3.42503597876812e-06 1.25192464860022e-06 -2.21887241109283e-07 -6.67036084133673e-06 -7.10618109674689e-06 2.22659744199814e-05 -3.3634442505216e-06 -3.64944690040597e-06 3.58321037064523e-05 -2.08165730794668e-06 -3.42503597876812e-06 -3.3634442505216e-06 8.90218627838801e-05 1363 1364 0 0 1 1408 1446 0 0 1 0 0 0 0 0 0 0 0 1049 0 4 37 0 0 2688 +1270 1296 0.997338114956475 -0.00818209296540216 0.0724550744238839 -0.0130385020704248 -0.00370349060025079 0.986717282944797 0.162404703427613 -0.0284934329908562 -0.0728214845525611 -0.16224073746363 0.984060452662751 0.0111374797941341 0.000123029043932358 -4.54709648415462e-05 4.34206803794664e-06 4.92509069047715e-06 -1.82321994283103e-06 8.91744830914974e-06 -4.54709648415462e-05 7.14052975294931e-05 -7.81022458700733e-07 3.49596455546615e-07 5.44692656665492e-06 4.05852329492139e-05 4.34206803794664e-06 -7.81022458700733e-07 1.32943251091158e-05 2.30539221459661e-07 -6.77878261645073e-06 -1.44817024763808e-06 4.92509069047715e-06 3.49596455546615e-07 2.30539221459661e-07 4.08910538121903e-05 1.43118050905664e-05 5.31274477823228e-06 -1.82321994283103e-06 5.44692656665492e-06 -6.77878261645073e-06 1.43118050905664e-05 3.54804359128904e-05 6.9391269067264e-06 8.91744830914974e-06 4.05852329492139e-05 -1.44817024763808e-06 5.31274477823228e-06 6.9391269067264e-06 7.55578724360684e-05 1367 1389 0 0 7 1402 1457 0 0 10 0 0 0 0 0 0 0 0 1022 0 4 27 0 0 2673 +1270 1304 0.997829572993241 -0.00621604264147955 0.0655553512232581 -0.00620035590657562 -0.00358111027200386 0.9889387617503 0.148281155771742 -0.0236594982039816 -0.0657519498520398 -0.148194083288312 0.986770082019612 0.0186615102174433 0.000108584623678204 -7.14934887746237e-05 1.08411796833531e-06 -7.61552673529722e-07 1.25474993175254e-07 2.93537267007587e-06 -7.14934887746237e-05 9.07201472675996e-05 1.99464502103098e-06 5.69066746134522e-07 -3.65943888306664e-06 2.08698648165735e-05 1.08411796833531e-06 1.99464502103098e-06 1.4141753969081e-05 -3.54298402253693e-07 -8.45673079413646e-06 -3.42918322615146e-07 -7.61552673529722e-07 5.69066746134522e-07 -3.54298402253693e-07 3.18238798767805e-05 6.47769365538271e-06 -2.12583082474133e-06 1.25474993175254e-07 -3.65943888306664e-06 -8.45673079413646e-06 6.47769365538271e-06 2.68924661431807e-05 -6.32877049711982e-06 2.93537267007587e-06 2.08698648165735e-05 -3.42918322615146e-07 -2.12583082474133e-06 -6.32877049711982e-06 6.78259060192287e-05 1374 1390 0 0 1 1407 1457 0 0 12 0 0 0 0 0 0 0 0 1036 0 1 22 0 0 2545 +1270 1297 0.996984533313225 -0.00811890741869069 0.0771746310424483 -0.00893322398700696 -0.00463836483208924 0.986498867476065 0.163702382512065 -0.0254640624951727 -0.077461770609093 -0.163566707525611 0.983486454550003 0.0138726784536532 7.39378750110152e-05 -2.49515325469885e-05 4.27953054670293e-06 -6.7089100546618e-07 -2.1664975724831e-06 -1.37690638906176e-06 -2.49515325469885e-05 6.97746877708533e-05 -1.71485432859717e-06 5.80972214027042e-06 -1.18420678437386e-06 2.70580523019016e-05 4.27953054670293e-06 -1.71485432859717e-06 1.29176964729782e-05 6.16342626111446e-07 -7.2526832616267e-06 -1.43416568054428e-06 -6.7089100546618e-07 5.80972214027042e-06 6.16342626111446e-07 3.28818516866e-05 6.7318318344074e-06 6.77111316180776e-06 -2.1664975724831e-06 -1.18420678437386e-06 -7.2526832616267e-06 6.7318318344074e-06 2.47406113308917e-05 3.01985551900309e-06 -1.37690638906176e-06 2.70580523019016e-05 -1.43416568054428e-06 6.77111316180776e-06 3.01985551900309e-06 6.3293950961325e-05 1375 1382 0 0 1 1410 1455 0 0 2 0 0 0 0 0 0 0 0 1041 0 2 25 0 0 2537 +1270 1302 0.997068632840352 -0.00766138342196195 0.0761278175828859 -0.00884629761733096 -0.00436312489703018 0.987661688255575 0.156541856042657 -0.0250082325453326 -0.076387856017854 -0.156415129562996 0.984733061645026 0.014347611745997 0.000105056485760496 -5.67162762782279e-05 6.50136713349581e-06 -2.26908891713444e-06 -1.86954925435334e-06 1.11083987351654e-05 -5.67162762782279e-05 7.42856528786642e-05 -5.68266737741916e-06 4.50119691210091e-06 -1.82621824892855e-06 2.42502503197092e-05 6.50136713349581e-06 -5.68266737741916e-06 1.36947831826957e-05 -1.57948900759574e-06 -8.04987608227383e-06 -5.28593047331617e-06 -2.26908891713444e-06 4.50119691210091e-06 -1.57948900759574e-06 3.48858865564473e-05 1.10891928638192e-05 6.19556648946605e-07 -1.86954925435334e-06 -1.82621824892855e-06 -8.04987608227383e-06 1.10891928638192e-05 2.86059194656772e-05 -2.37058346035814e-06 1.11083987351654e-05 2.42502503197092e-05 -5.28593047331617e-06 6.19556648946605e-07 -2.37058346035814e-06 7.22196681297282e-05 1369 1392 0 0 9 1401 1455 0 0 11 0 0 0 0 0 0 0 0 943 0 1 22 0 0 2544 +1270 1301 0.996893737325227 -0.00736292162966801 0.0784134163700137 -0.00897280246478045 -0.00495065917677518 0.987793275798182 0.155691795742782 -0.0253359774126777 -0.078602591913099 -0.155596374228232 0.984688479099644 0.0124937658099619 0.000135967886965425 -4.27004401967344e-05 8.09868815011879e-06 -3.04430394251725e-06 -6.50842915977847e-06 1.55085081727373e-05 -4.27004401967344e-05 7.41959026504748e-05 -3.97240305329331e-06 2.5771557235418e-06 -3.1334491832629e-06 2.75607175576693e-05 8.09868815011879e-06 -3.97240305329331e-06 1.39531917175462e-05 -1.09494333976449e-06 -8.1002881422143e-06 -2.85821657342155e-06 -3.04430394251725e-06 2.5771557235418e-06 -1.09494333976449e-06 3.30820352683472e-05 1.05607791922817e-05 -1.15550114848237e-07 -6.50842915977847e-06 -3.1334491832629e-06 -8.1002881422143e-06 1.05607791922817e-05 3.0221116275551e-05 -3.1219190559819e-06 1.55085081727373e-05 2.75607175576693e-05 -2.85821657342155e-06 -1.15550114848237e-07 -3.1219190559819e-06 8.21572014979848e-05 1373 1376 0 0 1 1408 1454 0 0 1 0 0 0 0 0 0 0 0 1026 0 2 30 0 0 2684 +1270 1300 0.997136916242707 -0.00734758926127648 0.0752594392620129 -0.0100745515654317 -0.00471571217511707 0.98728839117338 0.158869111890764 -0.028907626432659 -0.0754700756900805 -0.158769158170994 0.98442705270071 0.0132002949376592 0.000107961345005754 -4.28639090144445e-05 4.71593182396178e-06 1.63435168942687e-06 -1.778235403088e-06 9.85004561122039e-06 -4.28639090144445e-05 7.0140309222068e-05 1.16780227792739e-06 3.12407516926766e-06 4.7971730564413e-06 1.81277661918341e-05 4.71593182396178e-06 1.16780227792739e-06 1.42232898262019e-05 8.84229602018445e-07 -4.71099099805126e-06 -1.82956252485105e-06 1.63435168942687e-06 3.12407516926766e-06 8.84229602018445e-07 2.97208345251724e-05 5.70574835800665e-06 -8.81040762038893e-07 -1.778235403088e-06 4.7971730564413e-06 -4.71099099805126e-06 5.70574835800665e-06 2.69470619468217e-05 -2.16157818210776e-06 9.85004561122039e-06 1.81277661918341e-05 -1.82956252485105e-06 -8.81040762038893e-07 -2.16157818210776e-06 5.99961991814588e-05 1369 1373 0 0 1 1408 1449 0 0 2 0 0 0 0 0 0 0 0 924 0 3 34 0 0 2728 +1271 1312 0.997262962290676 -0.0131104626728211 0.0727646879449818 -0.00883006713106428 0.00216574632520738 0.988910652260127 0.148495896876999 -0.0215661097438083 -0.0739046249302495 -0.147931868152045 0.986232360450094 0.00754774703033091 8.66090687861693e-05 -3.9903096597326e-05 4.47874387909448e-06 6.0520631375958e-06 2.48117724873976e-06 2.56094019968369e-05 -3.9903096597326e-05 8.15043736792588e-05 -4.16295458074556e-06 -8.55132916412722e-07 -2.37887913923713e-06 2.58601564884053e-05 4.47874387909448e-06 -4.16295458074556e-06 1.57634230258142e-05 -5.89937083601959e-07 -6.18332472832922e-06 -3.16039447887897e-06 6.0520631375958e-06 -8.55132916412722e-07 -5.89937083601959e-07 3.37493616078148e-05 2.33114815259005e-06 7.77649506153357e-06 2.48117724873976e-06 -2.37887913923713e-06 -6.18332472832922e-06 2.33114815259005e-06 2.80761043084208e-05 2.51878638229614e-06 2.56094019968369e-05 2.58601564884053e-05 -3.16039447887897e-06 7.77649506153357e-06 2.51878638229614e-06 7.61401775757068e-05 1372 1385 0 0 0 1403 1457 0 0 1 0 0 0 0 0 0 0 0 1030 0 0 15 0 0 2619 +1271 1309 0.997604388199489 -0.0141119112223475 0.0677225118167891 -0.009232953990396 0.0036258707720003 0.988292648208381 0.152527028943761 -0.0191311349909915 -0.0690821084382006 -0.151916080317124 0.985976250644413 0.0114869444419619 7.79358092819501e-05 -3.47721186991125e-05 4.27510152027025e-06 1.11337181922369e-06 -7.76324787861974e-07 2.42121315416656e-06 -3.47721186991125e-05 5.96631032747196e-05 -1.32788760740695e-06 4.2991919894821e-06 5.47951520776281e-06 2.36997989674153e-05 4.27510152027025e-06 -1.32788760740695e-06 1.63770510165177e-05 1.20098599599501e-06 -4.89667017524904e-06 -3.00543251540464e-06 1.11337181922369e-06 4.2991919894821e-06 1.20098599599501e-06 2.86198710001133e-05 -4.34288985504089e-06 -3.73464848990345e-06 -7.76324787861974e-07 5.47951520776281e-06 -4.89667017524904e-06 -4.34288985504089e-06 2.96463188300538e-05 1.55876721462684e-06 2.42121315416656e-06 2.36997989674153e-05 -3.00543251540464e-06 -3.73464848990345e-06 1.55876721462684e-06 5.83280301509653e-05 1382 1397 0 0 0 1408 1465 0 0 2 0 0 0 0 0 0 0 0 924 0 0 12 0 0 2501 +1271 1310 0.997653267826394 -0.0126605167816596 0.0672879521916031 -0.0135969172427503 0.00298790680871926 0.989869657187476 0.141947645956004 -0.0256976638138951 -0.0684034327224925 -0.141413482717773 0.987584526659571 0.0103255363349596 0.000105123969501207 -4.37207078146986e-05 1.450458796447e-06 8.16448267897561e-07 -1.22602940095114e-06 3.63399156321764e-05 -4.37207078146986e-05 7.17759696056998e-05 -2.85464662760491e-06 4.6455984984318e-06 -2.4839856219038e-06 6.72495386115984e-06 1.450458796447e-06 -2.85464662760491e-06 1.38043086110949e-05 2.75822612184665e-06 -4.94649162884448e-06 -2.49593659165773e-06 8.16448267897561e-07 4.6455984984318e-06 2.75822612184665e-06 2.85952001232469e-05 -2.37397690479841e-06 3.19427536135134e-06 -1.22602940095114e-06 -2.4839856219038e-06 -4.94649162884448e-06 -2.37397690479841e-06 2.91317900449551e-05 -2.46259663394938e-06 3.63399156321764e-05 6.72495386115984e-06 -2.49593659165773e-06 3.19427536135134e-06 -2.46259663394938e-06 9.14839218133448e-05 1367 1373 0 0 0 1409 1446 0 0 0 0 0 0 0 0 0 0 0 1025 0 0 27 0 0 2538 +1271 1313 0.997687953305098 -0.0138282759042865 0.0665396619723891 -0.0117099578700252 0.0037254304240728 0.988736466254835 0.149620591718042 -0.0205861710201 -0.0678591850676109 -0.149026773042351 0.986501977655668 0.0159041868749831 9.8864148843096e-05 -5.7775682423915e-05 8.92700137154978e-06 -4.65357861013012e-06 3.42296385754255e-06 2.36000951970788e-05 -5.7775682423915e-05 9.66323002630915e-05 -9.61215414893137e-06 1.55401272570578e-05 -2.90611531851435e-06 1.20556291103109e-05 8.92700137154978e-06 -9.61215414893137e-06 1.40469846733321e-05 1.15881042842858e-06 -2.83691018726356e-06 -3.32925919699907e-06 -4.65357861013012e-06 1.55401272570578e-05 1.15881042842858e-06 3.32833612668438e-05 -4.87432935887716e-06 1.77537645848371e-06 3.42296385754255e-06 -2.90611531851435e-06 -2.83691018726356e-06 -4.87432935887716e-06 2.72745873732237e-05 1.02235594838237e-06 2.36000951970788e-05 1.20556291103109e-05 -3.32925919699907e-06 1.77537645848371e-06 1.02235594838237e-06 8.84423572035964e-05 1373 1386 0 0 0 1406 1461 0 0 1 0 0 0 0 0 0 0 0 1036 0 0 13 0 0 2851 +1271 1314 0.997307315985684 -0.0135284992588916 0.072077022616317 -0.0126338447550511 0.00220938152141106 0.987933989233536 0.154859780286568 -0.0188363896782072 -0.0733023609082528 -0.154283546189843 0.985303684789803 0.0119307955800959 0.000132944516945923 -6.75442203779348e-05 -2.3100167499793e-06 -3.94233273366166e-06 -8.89695254425e-06 2.51922226614823e-05 -6.75442203779348e-05 8.29088327210046e-05 2.4049254725572e-06 3.58988537455353e-06 2.90622766354019e-06 1.03228808003993e-05 -2.3100167499793e-06 2.4049254725572e-06 1.89958169804399e-05 2.73891412875468e-06 -5.34578333855602e-06 -3.4159053429096e-06 -3.94233273366166e-06 3.58988537455353e-06 2.73891412875468e-06 2.89758254613141e-05 -1.11069735274706e-05 -5.50202019103135e-07 -8.89695254425e-06 2.90622766354019e-06 -5.34578333855602e-06 -1.11069735274706e-05 2.6923124397189e-05 -2.9106211419436e-06 2.51922226614823e-05 1.03228808003993e-05 -3.4159053429096e-06 -5.50202019103135e-07 -2.9106211419436e-06 5.311244061211e-05 1373 1398 0 0 0 1405 1463 0 0 7 0 0 0 0 0 0 0 0 1036 0 0 10 0 0 2522 +1271 1311 0.997388844392037 -0.0147175080057857 0.0707028149398333 -0.0086882881975638 0.00397124677592792 0.988710080381034 0.149788538119491 -0.0177987327116902 -0.0721090998512765 -0.149116638612293 0.986186851366215 0.010112353748174 7.20493154456592e-05 -2.34937975395922e-05 2.18008202276896e-06 7.34248135165926e-06 -8.81692353440506e-07 1.85067973617779e-05 -2.34937975395922e-05 6.66457487043018e-05 -7.93613398158031e-06 6.00094954479632e-07 -4.39847458244123e-06 1.55461362242227e-05 2.18008202276896e-06 -7.93613398158031e-06 1.6612111278678e-05 9.97721007377807e-07 -3.43590123423913e-06 -5.41200712087449e-06 7.34248135165926e-06 6.00094954479632e-07 9.97721007377807e-07 2.81976320751754e-05 -8.25919167408323e-06 -1.23051687438458e-06 -8.81692353440506e-07 -4.39847458244123e-06 -3.43590123423913e-06 -8.25919167408323e-06 2.89677231585814e-05 -3.82997682277221e-07 1.85067973617779e-05 1.55461362242227e-05 -5.41200712087449e-06 -1.23051687438458e-06 -3.82997682277221e-07 5.11390414897682e-05 1379 1406 0 0 0 1405 1468 0 0 8 0 0 0 0 0 0 0 0 929 0 0 5 0 0 2849 +1271 1315 0.997574889362584 -0.0131859583467676 0.0683408414910611 -0.0149240977345001 0.00300431539345247 0.98913294610811 0.146993159747343 -0.021116328850546 -0.0695364235652489 -0.146431367629919 0.986773804056323 0.0126878507368681 9.64449824692269e-05 -4.54002135032097e-05 6.53663355140185e-06 -3.59630078966695e-06 8.46526033422436e-07 4.14620947884117e-05 -4.54002135032097e-05 6.63658333966132e-05 -3.32991411800359e-06 1.0367519046254e-06 4.03002721276217e-06 -1.89546594606854e-06 6.53663355140185e-06 -3.32991411800359e-06 1.53471337248795e-05 2.20273176589784e-06 -5.1567960891644e-06 -1.11678190911529e-06 -3.59630078966695e-06 1.0367519046254e-06 2.20273176589784e-06 3.06749321678499e-05 -9.35822157873044e-06 -1.50245376365283e-06 8.46526033422436e-07 4.03002721276217e-06 -5.1567960891644e-06 -9.35822157873044e-06 2.98823570032515e-05 3.32220855852329e-06 4.14620947884117e-05 -1.89546594606854e-06 -1.11678190911529e-06 -1.50245376365283e-06 3.32220855852329e-06 8.44626687490292e-05 1264 1273 0 0 0 1293 1336 0 0 8 0 0 0 0 0 0 0 0 1032 0 0 10 0 0 2826 +1271 1307 0.99793297099169 -0.0124490015177296 0.0630460765544606 -0.00983591669970864 0.00290273930866174 0.988787914535098 0.149298473447781 -0.021417904660034 -0.0641978154784514 -0.148806862847597 0.986780197438746 0.0130000053898416 0.000492905584527721 -0.000235621153506537 -1.04310074038338e-05 -3.97190034415951e-05 -9.01134201653779e-05 0.000365348476053861 -0.000235621153506537 0.000168077024086491 3.44652660875146e-06 2.79789937615808e-05 3.85328422707728e-05 -0.000155163820458691 -1.04310074038338e-05 3.44652660875146e-06 1.57193082189101e-05 3.34692497331864e-06 -1.00553061019278e-06 -1.74804716630334e-05 -3.97190034415951e-05 2.79789937615808e-05 3.34692497331864e-06 3.48057632766681e-05 1.04575907346186e-05 -4.14168143505976e-05 -9.01134201653779e-05 3.85328422707728e-05 -1.00553061019278e-06 1.04575907346186e-05 5.06789842597107e-05 -8.68363995228457e-05 0.000365348476053861 -0.000155163820458691 -1.74804716630334e-05 -4.14168143505976e-05 -8.68363995228457e-05 0.000380158306687133 1381 1386 0 0 0 1416 1462 0 0 2 0 0 0 0 0 0 0 0 1023 0 0 21 0 0 2610 +1271 1306 0.998218455176399 -0.0118172165681346 0.0584830671034464 -0.00903277282942942 0.00270487004427606 0.988145149580946 0.153498687413585 -0.0168271594263739 -0.0596036863229782 -0.153067033525288 0.986416688739845 0.0181414131862878 0.000103869087225716 -5.59463221422202e-05 5.24674425336983e-06 2.14414677237878e-06 -9.40419375242401e-06 1.38619378106467e-05 -5.59463221422202e-05 8.06936542814426e-05 -3.15701559637305e-07 1.38922059565452e-06 4.09816193802764e-07 1.15122375739433e-05 5.24674425336983e-06 -3.15701559637305e-07 1.49332724957895e-05 7.93329315304672e-07 -8.39776549264378e-06 -8.27141304088869e-07 2.14414677237878e-06 1.38922059565452e-06 7.93329315304672e-07 3.0751925787029e-05 -2.39623378199311e-06 -4.43961936093486e-06 -9.40419375242401e-06 4.09816193802764e-07 -8.39776549264378e-06 -2.39623378199311e-06 2.79662259896469e-05 7.44894193418919e-07 1.38619378106467e-05 1.15122375739433e-05 -8.27141304088869e-07 -4.43961936093486e-06 7.44894193418919e-07 7.00649227452706e-05 1378 1394 0 0 0 1408 1466 0 0 1 0 0 0 0 0 0 0 0 1025 0 0 9 0 0 2867 +1271 1297 0.997470950457282 -0.0131776531996611 0.0698430558466361 -0.00962677595791762 0.00279039987766085 0.989165288980821 0.146779578770383 -0.0269133899462587 -0.0710205369056699 -0.146213475889323 0.986700411880928 0.00917275592208326 5.64721491261997e-05 -4.44106110492213e-06 5.24777818362646e-06 1.2961903647013e-06 8.24573293421118e-07 1.52215194912823e-05 -4.44106110492213e-06 5.10998962086788e-05 -4.36230707032798e-06 -1.66090272060384e-06 -7.8204542764827e-06 2.97322990486824e-05 5.24777818362646e-06 -4.36230707032798e-06 1.35930097941563e-05 3.19714468814661e-07 -3.89319004180305e-06 -2.4014294318111e-06 1.2961903647013e-06 -1.66090272060384e-06 3.19714468814661e-07 2.74839931852796e-05 5.79752996569073e-06 4.26466013403201e-06 8.24573293421118e-07 -7.8204542764827e-06 -3.89319004180305e-06 5.79752996569073e-06 2.94943786772527e-05 -4.79098506275313e-06 1.52215194912823e-05 2.97322990486824e-05 -2.4014294318111e-06 4.26466013403201e-06 -4.79098506275313e-06 5.67145738202717e-05 1380 1389 0 0 0 1413 1454 0 0 1 0 0 0 0 0 0 0 0 1033 0 0 24 0 0 2625 +1271 1303 0.997566497966094 -0.0134173454607747 0.0684182503170732 -0.00678512931594162 0.00313547120949993 0.988948842216161 0.148224007163515 -0.0198561392527135 -0.0696509221472183 -0.147648780286535 0.986584302897599 0.00884776993711788 8.32029376295191e-05 -2.60705226524133e-05 2.24286860705423e-06 6.17509655626483e-06 7.39079832895297e-07 2.37488163379394e-05 -2.60705226524133e-05 6.2498245824994e-05 1.33996530694895e-06 5.05559488098397e-07 6.30806829257736e-07 2.10394147537786e-05 2.24286860705423e-06 1.33996530694895e-06 1.58622388824151e-05 -1.18861804151291e-06 -2.56989700949438e-06 -2.25176397177867e-06 6.17509655626483e-06 5.05559488098397e-07 -1.18861804151291e-06 3.05723086384542e-05 8.24038765839386e-06 6.76526234677331e-06 7.39079832895297e-07 6.30806829257736e-07 -2.56989700949438e-06 8.24038765839386e-06 3.36407586683158e-05 -2.82695084262431e-06 2.37488163379394e-05 2.10394147537786e-05 -2.25176397177867e-06 6.76526234677331e-06 -2.82695084262431e-06 6.60315852673518e-05 1379 1396 0 0 0 1406 1462 0 0 4 0 0 0 0 0 0 0 0 928 0 0 12 0 0 2712 +1272 1275 0.999817663128611 -0.0166801204846998 -0.00929591720380415 -0.000998337325576762 0.0167101993534544 0.999855357692432 0.00316748027721259 0.0101114105649877 0.00924173866823202 -0.00332223935841743 0.999951775333208 0.00682174698498477 6.07948316473008e-05 2.87478141466317e-06 2.54704592907307e-06 5.11560192191777e-06 -2.85770204247536e-06 3.66154623614432e-06 2.87478141466317e-06 3.79948748081786e-05 3.81322794022136e-06 4.66447872518598e-06 -3.50038466251907e-06 1.47339963553381e-05 2.54704592907307e-06 3.81322794022136e-06 1.38109016022592e-05 1.80444903177532e-06 -2.83774268425742e-06 -8.38526709520856e-07 5.11560192191777e-06 4.66447872518598e-06 1.80444903177532e-06 2.17811079766204e-05 -7.11330195092728e-06 2.02353679102989e-06 -2.85770204247536e-06 -3.50038466251907e-06 -2.83774268425742e-06 -7.11330195092728e-06 2.38712416429761e-05 5.27504098004949e-07 3.66154623614432e-06 1.47339963553381e-05 -8.38526709520856e-07 2.02353679102989e-06 5.27504098004949e-07 5.43475083461831e-05 1254 1328 0 0 3 1254 1350 0 0 24 0 0 0 0 0 0 0 0 764 0 0 0 0 0 3375 +1271 1318 0.997810536092309 -0.0119390900835735 0.0650506893980084 -0.0130127955965821 0.0022420609044567 0.989112243562213 0.147145991444639 -0.022849653170513 -0.0660992225830271 -0.146677972999702 0.986973386171389 0.0184173304577052 9.37119995066567e-05 -5.68041535150222e-05 -8.49945029005272e-07 1.70226056549247e-06 2.40957991347582e-06 2.80324859375723e-05 -5.68041535150222e-05 9.51095430588471e-05 -1.65208620301308e-07 5.00441583479676e-06 -5.25020606509881e-06 5.82029371696486e-06 -8.49945029005272e-07 -1.65208620301308e-07 1.53466058553255e-05 4.72368954606043e-06 -4.82384952135944e-06 -5.63774303528676e-06 1.70226056549247e-06 5.00441583479676e-06 4.72368954606043e-06 2.51287196474719e-05 -1.12030439693764e-05 6.77424850367348e-06 2.40957991347582e-06 -5.25020606509881e-06 -4.82384952135944e-06 -1.12030439693764e-05 2.92051221155463e-05 -1.29738669327164e-06 2.80324859375723e-05 5.82029371696486e-06 -5.63774303528676e-06 6.77424850367348e-06 -1.29738669327164e-06 7.33975080473264e-05 1377 1382 0 0 0 1415 1456 0 0 1 0 0 0 0 0 0 0 0 1042 0 0 27 0 0 2850 +1271 1305 0.997271044367516 -0.0127650662774262 0.0727153157804933 -0.00768341930571235 0.0019319285409747 0.989113559720425 0.147141542839881 -0.0215696376178499 -0.0738019763843524 -0.146599519303854 0.986438973896329 0.00542124630379105 5.55417481124685e-05 -3.74758349447741e-05 3.70256295979486e-06 -5.42855368713174e-06 -1.39292916060847e-07 5.73080797734875e-06 -3.74758349447741e-05 6.95628824798571e-05 -9.43571355207329e-08 5.83802883833153e-06 4.45158055400993e-06 1.37410900042328e-05 3.70256295979486e-06 -9.43571355207329e-08 1.56163866802924e-05 4.65151998835416e-08 -2.88400253290464e-06 -1.47519150153628e-06 -5.42855368713174e-06 5.83802883833153e-06 4.65151998835416e-08 3.18081658606866e-05 7.87765785588849e-06 2.63068645936233e-06 -1.39292916060847e-07 4.45158055400993e-06 -2.88400253290464e-06 7.87765785588849e-06 3.20358590343702e-05 -2.93626069257553e-06 5.73080797734875e-06 1.37410900042328e-05 -1.47519150153628e-06 2.63068645936233e-06 -2.93626069257553e-06 5.94465888998082e-05 1275 1287 0 0 0 1297 1341 0 0 9 0 0 0 0 0 0 0 0 937 0 0 8 0 0 2609 +1271 1316 0.997540667698598 -0.0119009781132921 0.0690723027514139 -0.0143034531023076 0.000979319032029665 0.987749713922318 0.156043402874368 -0.0210759422851232 -0.0700832164049963 -0.155591996472588 0.985332163999534 0.0139460350372157 9.5673428705088e-05 -4.46343967851417e-05 3.73911448015279e-06 -1.6524771391342e-06 -8.31635410894615e-06 2.5193718549811e-05 -4.46343967851417e-05 7.99521389087368e-05 -3.97390927469274e-06 6.96610016185484e-06 -2.65375638478572e-07 4.90211935869295e-06 3.73911448015279e-06 -3.97390927469274e-06 1.80724168747347e-05 3.71898535304003e-06 -5.86374870065938e-06 -2.14041605325846e-07 -1.6524771391342e-06 6.96610016185484e-06 3.71898535304003e-06 3.56252155126223e-05 -1.54151832312892e-05 -4.68949974106324e-06 -8.31635410894615e-06 -2.65375638478572e-07 -5.86374870065938e-06 -1.54151832312892e-05 3.11718354832267e-05 -2.12086174344402e-06 2.5193718549811e-05 4.90211935869295e-06 -2.14041605325846e-07 -4.68949974106324e-06 -2.12086174344402e-06 7.18995897925057e-05 1274 1285 0 0 0 1305 1346 0 0 9 0 0 0 0 0 0 0 0 1018 0 0 15 0 0 2865 +1272 1276 0.999812709825665 -0.0176706613997934 -0.00789259125726404 0.00364342298009445 0.0176087313598328 0.999814150638955 -0.0078483604658252 0.00565787438808005 0.00802981014455701 0.00770791202584319 0.999938053201919 -0.000684104844768403 6.43336957891196e-05 1.5302308576214e-05 -5.19209903910469e-08 3.40249885880655e-06 -1.21135122717841e-06 2.12490138064105e-05 1.5302308576214e-05 5.62778551232027e-05 -1.27431506151567e-06 7.86943970006417e-06 2.73672715790599e-06 2.65629701063496e-05 -5.19209903910469e-08 -1.27431506151567e-06 1.22107863621912e-05 2.01649332325619e-06 -4.00058703181461e-06 3.09690233789928e-07 3.40249885880655e-06 7.86943970006417e-06 2.01649332325619e-06 2.193417938437e-05 -6.97301869031032e-08 6.31231736995166e-06 -1.21135122717841e-06 2.73672715790599e-06 -4.00058703181461e-06 -6.97301869031032e-08 2.4040081668237e-05 8.35508627070502e-06 2.12490138064105e-05 2.65629701063496e-05 3.09690233789928e-07 6.31231736995166e-06 8.35508627070502e-06 6.72801021702388e-05 1221 1277 0 0 5 1229 1304 0 0 27 0 0 0 0 0 0 0 0 763 0 0 0 0 0 3391 +1271 1317 0.997489900855005 -0.0121468406209935 0.0697592427940583 -0.0109168369713302 0.00123487174643156 0.988010762781127 0.154380075529277 -0.0192193769444079 -0.0707981128565024 -0.153906422515708 0.985545757600516 0.0132965084157906 0.000102163220975325 -5.11311618774693e-05 -4.37518996523863e-06 8.04853556164142e-06 -6.23197005287469e-06 1.53320682233435e-05 -5.11311618774693e-05 8.64474354075914e-05 2.49695931942084e-06 2.01643088171299e-06 -2.81552227575441e-06 1.97026188762895e-05 -4.37518996523863e-06 2.49695931942084e-06 1.6236877909111e-05 4.86747571358313e-06 -6.95516302788014e-06 -5.61250100151284e-06 8.04853556164142e-06 2.01643088171299e-06 4.86747571358313e-06 2.84220792721577e-05 -1.54525494081416e-05 6.59024768324118e-06 -6.23197005287469e-06 -2.81552227575441e-06 -6.95516302788014e-06 -1.54525494081416e-05 2.54058363844861e-05 -2.41960923186823e-06 1.53320682233435e-05 1.97026188762895e-05 -5.61250100151284e-06 6.59024768324118e-06 -2.41960923186823e-06 7.14049962915822e-05 1370 1392 0 0 0 1402 1462 0 0 8 0 0 0 0 0 0 0 0 928 0 0 10 0 0 2845 +1271 1302 0.997477620708709 -0.0135017167662091 0.0696857218493003 -0.00990567437127627 0.00253381114897241 0.987889817950691 0.155136350963959 -0.0189002450061138 -0.0709364221423263 -0.154568467786015 0.985432195932287 0.00771495622275771 6.51093509843856e-05 -4.19143812730332e-05 2.01135751295665e-06 1.31259752571693e-06 -2.31551174279126e-06 2.90596740006864e-06 -4.19143812730332e-05 6.84084052045333e-05 -3.02788340296315e-07 4.04900745280334e-06 -2.48088102266189e-06 1.5716131955507e-05 2.01135751295665e-06 -3.02788340296315e-07 1.60980554607105e-05 -5.27400391494082e-07 -5.84512833709004e-06 -4.9546684054798e-06 1.31259752571693e-06 4.04900745280334e-06 -5.27400391494082e-07 2.90099078572502e-05 -3.33585851114213e-06 3.45211420291235e-06 -2.31551174279126e-06 -2.48088102266189e-06 -5.84512833709004e-06 -3.33585851114213e-06 3.04803503398813e-05 2.76969359857119e-06 2.90596740006864e-06 1.5716131955507e-05 -4.9546684054798e-06 3.45211420291235e-06 2.76969359857119e-06 5.40589411004142e-05 1376 1400 0 0 0 1404 1464 0 0 10 0 0 0 0 0 0 0 0 932 0 0 10 0 0 2528 +1271 1304 0.99783768300131 -0.0125541489780461 0.0645162903925403 -0.00677929748793747 0.00292230478764571 0.989092216640503 0.147268622305991 -0.0214362593903757 -0.0656613928980011 -0.14676164459631 0.986990172776852 0.00630169508565105 7.23632025808816e-05 -4.91900103864458e-05 3.90103805957139e-06 -8.12150858893415e-06 -1.85255201565377e-06 1.35994080861365e-05 -4.91900103864458e-05 7.63991071256052e-05 5.31373708131067e-07 5.05147692495923e-06 3.56399266617332e-06 1.13328215931649e-05 3.90103805957139e-06 5.31373708131067e-07 1.54603146840324e-05 -1.76034068257318e-06 -6.05435843913925e-06 -1.38549129343562e-06 -8.12150858893415e-06 5.05147692495923e-06 -1.76034068257318e-06 3.08703473356465e-05 6.1169389905662e-06 -3.12142942431179e-06 -1.85255201565377e-06 3.56399266617332e-06 -6.05435843913925e-06 6.1169389905662e-06 2.83761482190077e-05 -5.78990982210902e-06 1.35994080861365e-05 1.13328215931649e-05 -1.38549129343562e-06 -3.12142942431179e-06 -5.78990982210902e-06 6.01722958203339e-05 1381 1393 0 0 0 1407 1462 0 0 2 0 0 0 0 0 0 0 0 1030 0 0 12 0 0 2616 +1272 1308 0.997269046570237 -0.0139172656583391 0.0725310862284988 -0.0125660878551406 0.00280967514650356 0.988522739816807 0.15104601481219 -0.0170008263455613 -0.0738007755952594 -0.150429726389661 0.985862233245533 0.00945707675296148 9.72032499873286e-05 -4.95110343940307e-05 5.55012841812951e-06 -5.29993211010256e-06 -1.04840409401694e-06 -1.60302197606553e-05 -4.95110343940307e-05 8.96167260353991e-05 -4.21895364161089e-06 1.47605174456763e-05 -1.08572410563027e-06 3.6681520757271e-05 5.55012841812951e-06 -4.21895364161089e-06 1.63852013418695e-05 1.9928531423282e-06 -2.91279640567614e-06 -2.42681697015437e-06 -5.29993211010256e-06 1.47605174456763e-05 1.9928531423282e-06 3.0509858780251e-05 -1.0910497738559e-06 9.95483112004653e-06 -1.04840409401694e-06 -1.08572410563027e-06 -2.91279640567614e-06 -1.0910497738559e-06 3.36520052982043e-05 1.17639639725465e-06 -1.60302197606553e-05 3.6681520757271e-05 -2.42681697015437e-06 9.95483112004653e-06 1.17639639725465e-06 5.59741755167106e-05 1286 1306 0 0 6 1305 1348 0 0 8 0 0 0 0 0 0 0 0 1027 0 0 7 0 0 2812 +1271 1300 0.997759218858828 -0.0137598895520753 0.0654767639833834 -0.0129112801839384 0.00345852185145164 0.987922701049509 0.154908926074792 -0.0215746585925219 -0.066817511243865 -0.154335356255646 0.985756571370751 0.0171945018319023 9.13582591299542e-05 -2.36903648204613e-05 9.87680063879341e-06 4.17853626704983e-06 -1.51178396918372e-07 9.02928751730555e-06 -2.36903648204613e-05 5.94960498035568e-05 -6.39162198617113e-06 4.4384526598585e-06 -6.31639694695499e-06 1.78967221070257e-05 9.87680063879341e-06 -6.39162198617113e-06 1.56029287626461e-05 -8.79361256887649e-07 -1.48608192804733e-06 -2.17036404207622e-06 4.17853626704983e-06 4.4384526598585e-06 -8.79361256887649e-07 3.06633417398379e-05 -3.919110287282e-06 -4.18140449079863e-06 -1.51178396918372e-07 -6.31639694695499e-06 -1.48608192804733e-06 -3.919110287282e-06 3.15511729799426e-05 5.64603004330044e-06 9.02928751730555e-06 1.78967221070257e-05 -2.17036404207622e-06 -4.18140449079863e-06 5.64603004330044e-06 6.00365453108811e-05 1377 1384 0 0 0 1413 1459 0 0 1 0 0 0 0 0 0 0 0 917 0 0 21 0 0 2868 +1272 1309 0.996776447919962 -0.0150865931560544 0.078797890701504 -0.0117232354788413 0.00309820329573235 0.988666299192966 0.150097801371052 -0.0163361700019586 -0.080169283446971 -0.149369821406565 0.985526023220377 0.012158850725984 9.29077311841831e-05 -2.46212454074559e-05 2.47097474917035e-06 8.6437016950078e-06 1.11885747934766e-06 2.74480488609348e-05 -2.46212454074559e-05 7.56074227172224e-05 -3.1161356776165e-06 8.68847092144604e-06 -1.83794293010919e-06 2.07931536815895e-05 2.47097474917035e-06 -3.1161356776165e-06 1.37319682887958e-05 2.90236564912703e-06 -7.58408410182316e-06 -3.52799450090184e-06 8.6437016950078e-06 8.68847092144604e-06 2.90236564912703e-06 3.08622468518269e-05 -2.18922872658449e-06 3.48616662100739e-06 1.11885747934766e-06 -1.83794293010919e-06 -7.58408410182316e-06 -2.18922872658449e-06 2.55740551055755e-05 -2.41298579640085e-07 2.74480488609348e-05 2.07931536815895e-05 -3.52799450090184e-06 3.48616662100739e-06 -2.41298579640085e-07 7.10633470374544e-05 1385 1413 0 0 0 1408 1463 0 0 8 0 0 0 0 0 0 0 0 928 0 0 15 0 0 2592 +1271 1301 0.997596287412994 -0.0137188791803422 0.0679223063054154 -0.0120702577169527 0.00341719656446428 0.988753111139076 0.149517918593185 -0.0204907622622028 -0.0692096099356968 -0.148926416618522 0.986423312947193 0.0155558409795577 8.59699082598574e-05 -3.54093213441645e-05 1.18540959738919e-05 9.75166542624879e-07 3.01517390520468e-06 1.92940452034693e-05 -3.54093213441645e-05 7.44057614581725e-05 -2.71155413042487e-06 4.53710615256167e-06 -5.33105883400238e-06 6.23596800769404e-06 1.18540959738919e-05 -2.71155413042487e-06 1.86132129462346e-05 -1.93726057628567e-06 -7.65132225646649e-07 1.12825580115516e-07 9.75166542624879e-07 4.53710615256167e-06 -1.93726057628567e-06 3.02740051854172e-05 -1.13702373406641e-06 -6.04281704265874e-07 3.01517390520468e-06 -5.33105883400238e-06 -7.65132225646649e-07 -1.13702373406641e-06 3.61745488680771e-05 2.01959768437952e-06 1.92940452034693e-05 6.23596800769404e-06 1.12825580115516e-07 -6.04281704265874e-07 2.01959768437952e-06 5.78889206875391e-05 1378 1386 0 0 0 1414 1458 0 0 1 0 0 0 0 0 0 0 0 1019 0 0 20 0 0 2858 +1272 1274 0.999819914206853 -0.0122729022439493 -0.0144746338783461 -0.000221926838862988 0.012368262166255 0.999902272270904 0.00651705443206163 0.00854662714912959 0.0143932361332845 -0.00669490686971319 0.999873998549626 -0.000241016780452432 5.83086673980114e-05 4.05619081277854e-05 -6.61469179461796e-06 8.44452360831209e-06 -4.51901746179736e-06 2.87676670875618e-05 4.05619081277854e-05 9.99041305230603e-05 -1.17948008315232e-05 2.26394126139158e-05 -6.99822809362103e-06 2.69747637742394e-05 -6.61469179461796e-06 -1.17948008315232e-05 1.52049202193715e-05 -3.41692156369075e-07 -2.06839625681548e-06 -3.53094394383043e-06 8.44452360831209e-06 2.26394126139158e-05 -3.41692156369075e-07 2.59310342360994e-05 -6.19151246468567e-06 2.54215359947243e-06 -4.51901746179736e-06 -6.99822809362103e-06 -2.06839625681548e-06 -6.19151246468567e-06 2.18552290944774e-05 -4.97429681662335e-06 2.87676670875618e-05 2.69747637742394e-05 -3.53094394383043e-06 2.54215359947243e-06 -4.97429681662335e-06 5.13854241731013e-05 1229 1267 0 0 3 1229 1309 0 0 11 0 0 0 0 0 0 0 0 773 0 0 0 0 0 3392 +1272 1310 0.996539860355527 -0.014365656774392 0.0818653444873219 -0.0172243604100617 0.00245669783782482 0.989610862121391 0.14375084767434 -0.0215344795227782 -0.0830799094746807 -0.143052331252581 0.9862219624227 0.00349441060310164 0.000137882760021801 -4.41190460932222e-05 5.18874694645996e-06 4.23893620850921e-06 -4.67376172444962e-06 5.43809803334101e-06 -4.41190460932222e-05 7.27455368706313e-05 -3.35430705688507e-06 5.3467747267274e-06 -3.51411233124716e-06 1.65104119836362e-05 5.18874694645996e-06 -3.35430705688507e-06 1.55195894995563e-05 2.43282058266489e-06 -6.00689482510545e-06 1.84291077749993e-06 4.23893620850921e-06 5.3467747267274e-06 2.43282058266489e-06 3.2702152668557e-05 -3.00216103276413e-06 -3.64811913670042e-06 -4.67376172444962e-06 -3.51411233124716e-06 -6.00689482510545e-06 -3.00216103276413e-06 2.67359049784238e-05 2.52628472958412e-06 5.43809803334101e-06 1.65104119836362e-05 1.84291077749993e-06 -3.64811913670042e-06 2.52628472958412e-06 7.6896082503254e-05 1370 1377 0 0 0 1410 1453 0 0 1 0 0 0 0 0 0 0 0 1025 0 0 23 0 0 2525 +1272 1315 0.997185361888223 -0.0128737564568567 0.0738621718509727 -0.0183456949707272 0.00182035424880174 0.989015030041784 0.147803777562883 -0.0225785322339605 -0.0749535879478891 -0.147253308099135 0.986254745442373 0.0089642797095797 0.000105168782219878 -4.86841818792799e-05 8.37946417654601e-06 -5.35284729061146e-06 -3.04099328252459e-07 1.48813772288466e-05 -4.86841818792799e-05 7.04120660552146e-05 -2.66169415500071e-06 4.39196113693612e-06 2.09451395689998e-06 2.53527129093801e-05 8.37946417654601e-06 -2.66169415500071e-06 1.69485281221032e-05 5.9367045929265e-06 -8.65703197112387e-06 5.84083907585277e-08 -5.35284729061146e-06 4.39196113693612e-06 5.9367045929265e-06 2.94029225401326e-05 -6.39518741788768e-06 4.32545362640104e-06 -3.04099328252459e-07 2.09451395689998e-06 -8.65703197112387e-06 -6.39518741788768e-06 2.67888485248365e-05 4.69462256898618e-06 1.48813772288466e-05 2.53527129093801e-05 5.84083907585277e-08 4.32545362640104e-06 4.69462256898618e-06 8.55237389570834e-05 1266 1278 0 0 8 1291 1328 0 0 8 0 0 0 0 0 0 0 0 1032 0 0 15 0 0 2758 +1272 1311 0.997072127727093 -0.0150263850013325 0.0749758618727383 -0.0144235848536573 0.00371670257353958 0.988866624307468 0.148758144155987 -0.0211710054364357 -0.0763764245808093 -0.148043936331568 0.98602719774036 0.0131980853898239 0.000131661306801839 -5.41880851061942e-05 -1.94426665595744e-06 3.69642504204098e-06 -1.10068868588466e-05 2.7360542645492e-05 -5.41880851061942e-05 9.85541287009238e-05 -6.2191202954851e-07 9.165431901278e-06 1.42384733374719e-05 1.03006022334207e-05 -1.94426665595744e-06 -6.2191202954851e-07 1.62265352856196e-05 3.84830570916717e-06 -4.27957435942665e-06 -3.10584192440157e-06 3.69642504204098e-06 9.165431901278e-06 3.84830570916717e-06 2.85601833728675e-05 -3.14699997776e-06 -4.3017036864275e-06 -1.10068868588466e-05 1.42384733374719e-05 -4.27957435942665e-06 -3.14699997776e-06 2.54021592185552e-05 -2.96719647086394e-06 2.7360542645492e-05 1.03006022334207e-05 -3.10584192440157e-06 -4.3017036864275e-06 -2.96719647086394e-06 7.58701123728072e-05 1378 1407 0 0 5 1404 1461 0 0 10 0 0 0 0 0 0 0 0 929 0 0 10 0 0 2750 +1272 1312 0.997107344430781 -0.0136018826459115 0.0747792248601403 -0.0139733786049687 0.00197935258236326 0.988170054488612 0.153349357922778 -0.0170446426671558 -0.0759804306749525 -0.152757756596713 0.9853385417987 0.010007159261481 9.13104869985377e-05 -4.88294204274091e-05 2.1447651058105e-06 3.93941175263921e-06 -4.67629293593681e-06 8.19952668790381e-06 -4.88294204274091e-05 0.000100498947751044 -3.2017531959306e-06 -1.48362787904776e-06 -4.93487069467443e-06 3.14252393515e-05 2.1447651058105e-06 -3.2017531959306e-06 1.64349682874872e-05 1.62822784934176e-06 -4.98936513616293e-06 -3.97094781978453e-06 3.93941175263921e-06 -1.48362787904776e-06 1.62822784934176e-06 2.70271173835014e-05 -4.82035036042942e-06 -8.57577471730366e-07 -4.67629293593681e-06 -4.93487069467443e-06 -4.98936513616293e-06 -4.82035036042942e-06 2.39860064768992e-05 -3.58524437738558e-06 8.19952668790381e-06 3.14252393515e-05 -3.97094781978453e-06 -8.57577471730366e-07 -3.58524437738558e-06 7.01467713367437e-05 1374 1402 0 0 1 1402 1455 0 0 7 0 0 0 0 0 0 0 0 1026 0 0 18 0 0 2680 +1272 1304 0.997221206131244 -0.0134564664513592 0.0732720243530226 -0.0100756021403523 0.00200075488675081 0.988033997496098 0.154223269229271 -0.0158390473439665 -0.074470551374551 -0.153648115193531 0.985315377772744 0.00682641502382466 8.00786373527966e-05 -4.36627199966447e-05 7.08047432799533e-06 -5.2869480016294e-06 -8.11859747348485e-06 1.72119989826417e-05 -4.36627199966447e-05 9.39171349253669e-05 -2.52335746467916e-06 1.31978389784141e-05 6.11197533501351e-06 2.11528276671469e-05 7.08047432799533e-06 -2.52335746467916e-06 1.5088441302315e-05 4.70359231347767e-07 -7.00812293165843e-06 -9.51446350068973e-07 -5.2869480016294e-06 1.31978389784141e-05 4.70359231347767e-07 3.41311583693772e-05 6.42343002214601e-06 -2.621437766677e-06 -8.11859747348485e-06 6.11197533501351e-06 -7.00812293165843e-06 6.42343002214601e-06 2.90522268213136e-05 -7.27703893713409e-06 1.72119989826417e-05 2.11528276671469e-05 -9.51446350068973e-07 -2.621437766677e-06 -7.27703893713409e-06 8.57444683063719e-05 1385 1413 0 0 1 1408 1463 0 0 12 0 0 0 0 0 0 0 0 1031 0 0 15 0 0 2670 +1272 1318 0.996595099507659 -0.0134059117785494 0.0813540974180526 -0.0156921021740253 0.000743086128192237 0.988113676893055 0.153723158176945 -0.0210182052869423 -0.0824478954269078 -0.153139293018721 0.984759209895191 0.00715590739246117 0.000111379597130262 -5.15412094035819e-05 3.39538741644132e-06 -5.67789318983015e-07 -3.34116223920991e-07 1.55758629900811e-05 -5.15412094035819e-05 7.82399780326658e-05 -1.4540262916079e-07 4.30830392587634e-06 1.82603529685496e-06 1.41880630815721e-05 3.39538741644132e-06 -1.4540262916079e-07 1.59135475372434e-05 4.78930148710007e-06 -7.10574181139748e-06 -2.04813970290155e-06 -5.67789318983015e-07 4.30830392587634e-06 4.78930148710007e-06 2.57955092466248e-05 -9.38329657275455e-06 4.92557539665588e-06 -3.34116223920991e-07 1.82603529685496e-06 -7.10574181139748e-06 -9.38329657275455e-06 2.14649822746661e-05 2.30671168991602e-06 1.55758629900811e-05 1.41880630815721e-05 -2.04813970290155e-06 4.92557539665588e-06 2.30671168991602e-06 7.7831679823319e-05 1372 1379 0 0 1 1413 1456 0 0 1 0 0 0 0 0 0 0 0 1040 0 2 26 0 0 2767 +1272 1306 0.997107479764923 -0.0129737488947135 0.0748889553703424 -0.00986958272046663 0.00108826082653635 0.987659553087218 0.156612333115661 -0.0144143648399784 -0.0759966412758988 -0.156077830056592 0.984816846667241 0.00766608711842733 0.000101459745982057 -5.28149370027796e-05 6.24165554686541e-06 -6.29375770103818e-06 -7.16961757940745e-06 -5.59081900247145e-06 -5.28149370027796e-05 7.56835460201678e-05 -2.32071080919495e-06 7.69783831468387e-06 3.91054029781635e-06 2.2300852027985e-05 6.24165554686541e-06 -2.32071080919495e-06 1.69442552735534e-05 2.25115461394261e-06 -5.6028043201536e-06 -4.18446733368573e-06 -6.29375770103818e-06 7.69783831468387e-06 2.25115461394261e-06 3.25363825283382e-05 2.15132249226905e-06 -2.16976953513937e-06 -7.16961757940745e-06 3.91054029781635e-06 -5.6028043201536e-06 2.15132249226905e-06 3.01574831796631e-05 -6.31829554045649e-06 -5.59081900247145e-06 2.2300852027985e-05 -4.18446733368573e-06 -2.16976953513937e-06 -6.31829554045649e-06 6.36450114080328e-05 1384 1414 0 0 0 1407 1463 0 0 10 0 0 0 0 0 0 0 0 1022 0 0 15 0 0 2813 +1272 1313 0.997081956042655 -0.0143731148866969 0.0749732385762146 -0.0144860350155221 0.00327954044089972 0.989273487904282 0.146038387912882 -0.0213524068611016 -0.0762680637531115 -0.145366363709597 0.986433881592274 0.0138036045138804 9.21378046796372e-05 -6.03053284019126e-05 8.57909862430926e-06 -1.18429148744789e-05 3.43992660227656e-06 -7.02823868042009e-07 -6.03053284019126e-05 9.87889058579265e-05 -6.35495470390389e-06 1.57437921649992e-05 -1.13884005248817e-06 3.06699871906358e-05 8.57909862430926e-06 -6.35495470390389e-06 1.46167773826011e-05 3.35586015087453e-07 -4.45191680842101e-06 -2.20970608542949e-06 -1.18429148744789e-05 1.57437921649992e-05 3.35586015087453e-07 3.27827546065887e-05 -4.1404411414693e-06 4.43204394477648e-06 3.43992660227656e-06 -1.13884005248817e-06 -4.45191680842101e-06 -4.1404411414693e-06 2.34100610996108e-05 -1.38704530427081e-06 -7.02823868042009e-07 3.06699871906358e-05 -2.20970608542949e-06 4.43204394477648e-06 -1.38704530427081e-06 6.58904554509943e-05 1376 1398 0 0 0 1405 1454 0 0 6 0 0 0 0 0 0 0 0 1038 0 0 19 0 0 2777 +1272 1302 0.997115052998567 -0.0138673792052857 0.0746275209131388 -0.0154247967261845 0.00207775345398514 0.987787909988575 0.15579065383067 -0.0175751879399085 -0.0758765709837274 -0.15518614846171 0.984967007214643 0.00845426533122311 0.000105037279161393 -4.12298135225744e-05 8.35408378717146e-06 -5.56053617645605e-07 -7.6803865393535e-06 1.9568927858652e-05 -4.12298135225744e-05 8.0048275123083e-05 -5.49498985793107e-06 9.69896352527255e-06 -1.09039533548125e-06 2.41428202575043e-05 8.35408378717146e-06 -5.49498985793107e-06 1.74023687353662e-05 2.40744649350239e-06 -4.65802966644144e-06 -1.96170800925462e-06 -5.56053617645605e-07 9.69896352527255e-06 2.40744649350239e-06 2.922541978775e-05 4.69144876578612e-07 1.31511145126961e-06 -7.6803865393535e-06 -1.09039533548125e-06 -4.65802966644144e-06 4.69144876578612e-07 3.59437399333514e-05 1.27697812451089e-06 1.9568927858652e-05 2.41428202575043e-05 -1.96170800925462e-06 1.31511145126961e-06 1.27697812451089e-06 7.16798579384473e-05 1378 1408 0 0 8 1403 1459 0 0 12 0 0 0 0 0 0 0 0 925 0 0 13 0 0 2523 +1272 1314 0.997286435451591 -0.0142610050134948 0.0722245761515102 -0.0187220049567033 0.0028052192994619 0.987706990188341 0.156291497778259 -0.0164776133985267 -0.0735655925616191 -0.155664784935754 0.985066788762043 0.0141859234098096 0.000114726082570701 -3.62520449293219e-05 3.22141513609575e-06 -1.75711379521193e-06 -6.76752068436472e-06 1.48985969260276e-05 -3.62520449293219e-05 8.03721632339607e-05 -4.68874353395406e-06 1.68263980760423e-05 5.60599132957063e-06 3.65862544657696e-05 3.22141513609575e-06 -4.68874353395406e-06 1.89596583077724e-05 3.0779472354523e-06 -8.20007321220737e-06 -4.62082133932381e-06 -1.75711379521193e-06 1.68263980760423e-05 3.0779472354523e-06 3.88429164084563e-05 -8.80641961739556e-06 5.08670606316987e-06 -6.76752068436472e-06 5.60599132957063e-06 -8.20007321220737e-06 -8.80641961739556e-06 2.44739327932732e-05 -1.21178332627333e-06 1.48985969260276e-05 3.65862544657696e-05 -4.62082133932381e-06 5.08670606316987e-06 -1.21178332627333e-06 8.12375085213101e-05 1378 1413 0 0 5 1403 1460 0 0 10 0 0 0 0 0 0 0 0 1030 0 0 13 0 0 2513 +1272 1316 0.99642414139483 -0.0128596410817851 0.0835078444029249 -0.0163173443736718 -0.00046150611352835 0.987506743509564 0.157576072216702 -0.0205894522350315 -0.0844909312156199 -0.157051141843617 0.983969624220145 0.00709581315507076 0.000138824779598347 -5.48789573133005e-05 5.58665441692998e-06 4.13039403454542e-06 -9.51834907472438e-07 1.59885490079984e-05 -5.48789573133005e-05 9.04335031974246e-05 -3.01048309679109e-06 2.74821962795352e-06 -3.26071490635854e-06 2.72635759227661e-05 5.58665441692998e-06 -3.01048309679109e-06 1.74130634032842e-05 5.06877683989029e-06 -6.61933604745908e-06 -2.29909125559976e-07 4.13039403454542e-06 2.74821962795352e-06 5.06877683989029e-06 2.59598617832244e-05 -8.52004177370696e-06 9.29894630042034e-07 -9.51834907472438e-07 -3.26071490635854e-06 -6.61933604745908e-06 -8.52004177370696e-06 2.67401963378397e-05 -6.30086609886158e-06 1.59885490079984e-05 2.72635759227661e-05 -2.29909125559976e-07 9.29894630042034e-07 -6.30086609886158e-06 7.11439142389023e-05 1278 1294 0 0 7 1304 1342 0 0 8 0 0 0 0 0 0 0 0 1018 0 0 15 0 0 2814 +1272 1305 0.996876970855999 -0.013802920382718 0.0777546420857011 -0.0131053022072251 0.00193718955317292 0.988584334562066 0.150656100955492 -0.0191526780794767 -0.0789465152720638 -0.150034972081127 0.985523695747095 0.00888013894179775 6.84762962771977e-05 -3.43335513863527e-05 3.76726712926142e-06 7.05987231849976e-09 -5.05627717613045e-06 4.6379659113951e-06 -3.43335513863527e-05 5.16194766601408e-05 -1.26339353575157e-06 6.30194294650375e-06 5.72208290896103e-06 2.40541027255007e-05 3.76726712926142e-06 -1.26339353575157e-06 1.55067615555044e-05 3.33629926252414e-06 -4.96331242740748e-06 -2.45508823498518e-07 7.05987231849976e-09 6.30194294650375e-06 3.33629926252414e-06 3.2216872300574e-05 3.86576264545421e-06 9.62996245597702e-06 -5.05627717613045e-06 5.72208290896103e-06 -4.96331242740748e-06 3.86576264545421e-06 3.17116787547977e-05 2.24037684170781e-06 4.6379659113951e-06 2.40541027255007e-05 -2.45508823498518e-07 9.62996245597702e-06 2.24037684170781e-06 6.68586468817383e-05 1274 1293 0 0 7 1296 1339 0 0 9 0 0 0 0 0 0 0 0 935 0 0 10 0 0 2674 +1273 1275 0.999971304251901 -0.00632049966273334 0.00417635687718429 0.00113741473023784 0.00632259347655455 0.999979892967302 -0.000488336802826456 0.00342110716398339 -0.00417318637044244 0.000514728196384024 0.999991159746126 -0.00203956001954622 5.15061477459184e-05 -1.06263776078971e-06 1.37318044903988e-06 -7.76091220820656e-07 -1.76358999789693e-06 1.22948662751178e-05 -1.06263776078971e-06 3.94546217010974e-05 -6.96524033533386e-07 2.28060823758028e-06 -7.59175115090577e-06 1.08285233587869e-05 1.37318044903988e-06 -6.96524033533386e-07 1.09032131681233e-05 2.85609954623663e-06 -2.47585788814559e-06 -6.07134088071351e-07 -7.76091220820656e-07 2.28060823758028e-06 2.85609954623663e-06 1.76388493570854e-05 -3.88050119822698e-06 1.03828357196839e-07 -1.76358999789693e-06 -7.59175115090577e-06 -2.47585788814559e-06 -3.88050119822698e-06 2.00705931897034e-05 -6.32029560114687e-06 1.22948662751178e-05 1.08285233587869e-05 -6.07134088071351e-07 1.03828357196839e-07 -6.32029560114687e-06 4.95747697355882e-05 1249 1267 0 0 0 1249 1325 0 0 0 0 0 0 0 0 0 0 0 778 0 0 0 0 0 3455 +1272 1303 0.997271708831388 -0.0136798207437136 0.0725396530798336 -0.0121028125228134 0.00257217038723499 0.988521657315772 0.151057330034591 -0.016256352579182 -0.0737734552804854 -0.150458617307551 0.985859869237955 0.00630753382143257 0.000158484552679752 -2.69226278604385e-05 4.002262705035e-07 2.21328161457385e-06 -2.30865476099377e-05 2.21304249496534e-05 -2.69226278604385e-05 7.90977288739458e-05 -2.11372706803357e-06 7.90024351702822e-06 -3.13280050752475e-06 3.12266270279801e-05 4.002262705035e-07 -2.11372706803357e-06 1.51805490532196e-05 2.52235246527408e-06 -6.73514228926332e-06 2.15035165084522e-06 2.21328161457385e-06 7.90024351702822e-06 2.52235246527408e-06 2.77412956477174e-05 -3.13564562620084e-06 2.98457558255237e-07 -2.30865476099377e-05 -3.13280050752475e-06 -6.73514228926332e-06 -3.13564562620084e-06 3.05641753499655e-05 -6.78716610377895e-06 2.21304249496534e-05 3.12266270279801e-05 2.15035165084522e-06 2.98457558255237e-07 -6.78716610377895e-06 6.40417324083504e-05 1382 1409 0 0 0 1405 1459 0 0 9 0 0 0 0 0 0 0 0 921 0 0 16 0 0 2658 +1272 1317 0.996806114389539 -0.0124940281192226 0.0788762928704535 -0.0150527690405932 0.000713063621547109 0.989039018937171 0.147652668652041 -0.0210453246029337 -0.0798565079120112 -0.147124839103239 0.985889050483342 0.0107915560342208 0.000146640854613314 -7.07103965166611e-05 4.36955103902961e-06 -3.52404177408327e-06 -4.44485247713988e-07 1.80596479819451e-05 -7.07103965166611e-05 9.4122607901971e-05 -2.66596346953357e-06 1.03910966187648e-05 1.35086484160503e-06 2.3909586828745e-05 4.36955103902961e-06 -2.66596346953357e-06 1.59152681019092e-05 4.30807136653711e-06 -8.18402492674149e-06 -3.37299628667041e-06 -3.52404177408327e-06 1.03910966187648e-05 4.30807136653711e-06 3.28096245069746e-05 -7.33085551674054e-06 -1.29636223099877e-06 -4.44485247713988e-07 1.35086484160503e-06 -8.18402492674149e-06 -7.33085551674054e-06 2.74095538813743e-05 -4.36172976670776e-06 1.80596479819451e-05 2.3909586828745e-05 -3.37299628667041e-06 -1.29636223099877e-06 -4.36172976670776e-06 8.75188619646804e-05 1372 1400 0 0 6 1400 1453 0 0 11 0 0 0 0 0 0 0 0 929 0 0 19 0 0 2805 +1272 1300 0.997113683367541 -0.0143135191956244 0.0745615558411434 -0.0143319918956384 0.00300120584154135 0.988731343055414 0.149670718657104 -0.0197464044650396 -0.0758636619516364 -0.149014946995507 0.985920509152342 0.00772977330778485 9.91442701266475e-05 -4.49421641939556e-05 9.39786325839784e-06 -2.98243862764882e-06 -4.434112169263e-06 5.79120381427887e-06 -4.49421641939556e-05 6.20211161027485e-05 -5.77405672331724e-06 5.90136265835346e-06 1.77466060943468e-06 1.74973255053352e-05 9.39786325839784e-06 -5.77405672331724e-06 1.63890697666565e-05 1.40807777761965e-06 -4.619194693972e-06 -3.05192836738919e-06 -2.98243862764882e-06 5.90136265835346e-06 1.40807777761965e-06 2.77394812564717e-05 1.14907639533348e-06 1.60317526767341e-06 -4.434112169263e-06 1.77466060943468e-06 -4.619194693972e-06 1.14907639533348e-06 2.84399559823678e-05 -6.21351555426083e-07 5.79120381427887e-06 1.74973255053352e-05 -3.05192836738919e-06 1.60317526767341e-06 -6.21351555426083e-07 6.99303349885629e-05 1379 1386 0 0 1 1414 1460 0 0 2 0 0 0 0 0 0 0 0 922 0 0 21 0 0 2822 +1272 1301 0.996275512512116 -0.0147624137988719 0.0849539540430665 -0.0132663221164125 0.00184996573840604 0.988668256517196 0.150105483517474 -0.0206433974522269 -0.0862071968891652 -0.149389255617929 0.985013283925874 0.0041898512069511 8.27389372533297e-05 -2.67016302499335e-05 2.63024696963239e-06 -1.72817245258992e-06 -1.11086231137248e-05 4.50936367472991e-06 -2.67016302499335e-05 9.02310279089307e-05 -3.99177090747945e-06 8.43674750149366e-06 -2.89359405723002e-06 1.86418956601948e-05 2.63024696963239e-06 -3.99177090747945e-06 1.48819951025499e-05 -7.46712990869646e-08 -6.06284102892879e-06 -1.70903093746454e-06 -1.72817245258992e-06 8.43674750149366e-06 -7.46712990869646e-08 3.70189392332256e-05 9.3073885467307e-06 -4.08547138404792e-06 -1.11086231137248e-05 -2.89359405723002e-06 -6.06284102892879e-06 9.3073885467307e-06 3.12880835867914e-05 -4.81768215060014e-06 4.50936367472991e-06 1.86418956601948e-05 -1.70903093746454e-06 -4.08547138404792e-06 -4.81768215060014e-06 6.11672846992296e-05 1378 1385 0 0 1 1413 1458 0 0 2 0 0 0 0 0 0 0 0 1020 0 1 22 0 0 2762 +1273 1311 0.99568897863823 -0.00701868567682193 0.092488895926634 -0.0140376188201396 -0.00738101545840146 0.987975443838983 0.154434591273999 -0.0257322547193963 -0.0924606858570744 -0.154451482422586 0.983664455568211 0.000274488296427874 0.000358991786985454 -0.000248477632587767 -3.40486678208294e-05 -9.02275924770799e-05 -0.000109410643186684 0.000480325503618584 -0.000248477632587767 0.000250589270616002 2.67529499586741e-05 7.43792284727569e-05 9.4295451870321e-05 -0.000363593643863378 -3.40486678208294e-05 2.67529499586741e-05 1.83929605527501e-05 1.57527467651094e-05 1.09073316280203e-05 -6.64621537177788e-05 -9.02275924770799e-05 7.43792284727569e-05 1.57527467651094e-05 5.20573654464411e-05 3.27340363177152e-05 -0.000145460368981867 -0.000109410643186684 9.4295451870321e-05 1.09073316280203e-05 3.27340363177152e-05 7.14111615626066e-05 -0.000187814438151029 0.000480325503618584 -0.000363593643863378 -6.64621537177788e-05 -0.000145460368981867 -0.000187814438151029 0.000838813601225458 1357 1361 0 0 0 1397 1425 0 0 0 0 0 0 0 0 0 0 0 943 0 3 29 0 0 2824 +1273 1277 0.999946439484971 -0.00780834594424066 0.00679322419359532 0.00348929684073161 0.00784581822277331 0.999954056575692 -0.00550707492532762 0.00329397909437407 -0.00674991094345596 0.00556007836572781 0.999961761384315 0.00419085490808445 6.25624736190954e-05 2.8305164457489e-05 -5.04342225665099e-06 1.12939978831535e-05 7.42093117084568e-06 3.83947121603701e-05 2.8305164457489e-05 6.26958462670699e-05 -7.85719007743903e-06 1.57826950416653e-05 5.48212487697879e-06 5.53433494297836e-05 -5.04342225665099e-06 -7.85719007743903e-06 1.19917811860162e-05 -3.34365323860185e-07 -5.16622847927484e-06 -9.03193358768796e-06 1.12939978831535e-05 1.57826950416653e-05 -3.34365323860185e-07 2.60961640966635e-05 2.50684295101989e-07 1.62983115164252e-05 7.42093117084568e-06 5.48212487697879e-06 -5.16622847927484e-06 2.50684295101989e-07 1.82495595714227e-05 6.67625694951328e-06 3.83947121603701e-05 5.53433494297836e-05 -9.03193358768796e-06 1.62983115164252e-05 6.67625694951328e-06 7.54894337259851e-05 1222 1246 0 0 0 1225 1300 0 0 0 0 0 0 0 0 0 0 0 766 0 0 0 0 0 3485 +1273 1276 0.999961653381635 -0.00874825908567692 0.000399661403548384 0.00289438325961957 0.00874962556219668 0.99995539896716 -0.00355585839823045 0.00424155430141514 -0.000368536007697299 0.00355921893071821 0.999993598050415 -0.00338829561323381 4.81285867670016e-05 1.41951137751271e-05 -2.59644541828764e-06 4.50527350003359e-06 6.78829673786014e-06 2.70514742075849e-05 1.41951137751271e-05 3.56443428312446e-05 -2.60905130763674e-06 4.24364551304397e-06 2.24586537142873e-06 2.42808096923818e-05 -2.59644541828764e-06 -2.60905130763674e-06 9.50754569085394e-06 2.60850309551574e-06 -5.54079766819576e-06 -1.21401876056441e-06 4.50527350003359e-06 4.24364551304397e-06 2.60850309551574e-06 1.70985369359851e-05 -1.37151089516254e-06 6.8925091834949e-06 6.78829673786014e-06 2.24586537142873e-06 -5.54079766819576e-06 -1.37151089516254e-06 1.48392098674752e-05 5.38901537323944e-06 2.70514742075849e-05 2.42808096923818e-05 -1.21401876056441e-06 6.8925091834949e-06 5.38901537323944e-06 4.37950443757376e-05 1226 1252 0 0 0 1229 1304 0 0 4 0 0 0 0 0 0 0 0 781 0 0 0 0 0 3480 +1273 1308 0.996314938407706 -0.00618648826974048 0.0855468928046907 -0.0130275175684291 -0.00654420485403806 0.989004831429109 0.147738338939859 -0.0247639513190828 -0.0855202717984295 -0.147753750452463 0.985319802063652 0.00187314078974336 9.14058665541297e-05 -4.18144707593951e-05 2.5194868484378e-06 -5.10072783772783e-06 -3.22561175319904e-07 1.58401633648747e-05 -4.18144707593951e-05 6.50653440773671e-05 -1.25569251454978e-06 5.38012436183004e-06 -9.09801864908091e-08 2.67978047389876e-05 2.5194868484378e-06 -1.25569251454978e-06 1.3220023113733e-05 1.92145317311103e-06 -3.0908412689332e-06 -3.1968573421412e-06 -5.10072783772783e-06 5.38012436183004e-06 1.92145317311103e-06 2.7131989432641e-05 1.06199730597809e-06 4.16475465215986e-06 -3.22561175319904e-07 -9.09801864908091e-08 -3.0908412689332e-06 1.06199730597809e-06 2.38342187546324e-05 -1.78309098024747e-06 1.58401633648747e-05 2.67978047389876e-05 -3.1968573421412e-06 4.16475465215986e-06 -1.78309098024747e-06 7.55676966373217e-05 1263 1266 0 0 0 1300 1325 0 0 0 0 0 0 0 0 0 0 0 1050 0 1 24 0 0 2780 +1273 1313 0.996465887348827 -0.00586232697783908 0.0837936063940409 -0.0155682975858299 -0.00627717651040341 0.989575264777399 0.14387978452791 -0.0274756416623788 -0.0837635505764398 -0.143897284418941 0.98604119545366 0.0146951639145117 8.93252157948528e-05 -4.0845618181306e-05 4.24446432009508e-06 -3.86113740397269e-06 8.74021014543686e-07 2.96772164659563e-05 -4.0845618181306e-05 7.37969539241072e-05 -4.71028416040344e-06 7.38633895997389e-06 1.97806625581592e-06 2.13040319776642e-05 4.24446432009508e-06 -4.71028416040344e-06 1.51189221373075e-05 -8.1673026668427e-07 1.09248277944291e-06 -2.23740417408411e-06 -3.86113740397269e-06 7.38633895997389e-06 -8.1673026668427e-07 3.07262223051376e-05 -2.48053665582264e-06 5.68826468419327e-06 8.74021014543686e-07 1.97806625581592e-06 1.09248277944291e-06 -2.48053665582264e-06 2.76930268367546e-05 4.14398734786532e-06 2.96772164659563e-05 2.13040319776642e-05 -2.23740417408411e-06 5.68826468419327e-06 4.14398734786532e-06 9.23127200047003e-05 1353 1368 0 0 0 1395 1433 0 0 0 0 0 0 0 0 0 0 0 1048 0 4 37 0 0 2796 +1273 1310 0.995398246726614 -0.00562091347508716 0.0956594780734714 -0.0176497961005617 -0.00830526458297618 0.989460897449142 0.144561941738985 -0.0316211388238643 -0.095463883190399 -0.14469118062565 0.984860959351809 -0.00601291297745474 6.89519565561741e-05 -1.88742062270752e-05 5.04253048106581e-06 -7.65431109583413e-06 -1.73952451679292e-06 -3.00174133579231e-06 -1.88742062270752e-05 5.13559865468769e-05 -5.67998594882998e-06 -5.41301189758817e-07 -7.37246501480145e-06 2.02029356646185e-05 5.04253048106581e-06 -5.67998594882998e-06 1.42660046275007e-05 1.75430257452952e-06 -3.67520628636665e-06 -4.07116005293759e-06 -7.65431109583413e-06 -5.41301189758817e-07 1.75430257452952e-06 2.76707356776807e-05 2.4777747663325e-06 1.03409763037329e-06 -1.73952451679292e-06 -7.37246501480145e-06 -3.67520628636665e-06 2.4777747663325e-06 3.12666368531039e-05 -1.28685246183763e-06 -3.00174133579231e-06 2.02029356646185e-05 -4.07116005293759e-06 1.03409763037329e-06 -1.28685246183763e-06 6.5379850055919e-05 1344 1345 0 0 0 1392 1422 0 0 5 0 0 0 0 0 0 0 0 1041 0 10 49 0 0 2528 +1273 1306 0.996600261312178 -0.00510624791207834 0.0822304407428243 -0.0126483118169884 -0.0070636063486385 0.989107035721172 0.147028491634198 -0.0231466762690625 -0.0820854714176036 -0.147109476646259 0.985708261740264 0.0108390030602925 0.000105610518111742 -5.46024197103507e-05 1.06536120488141e-06 -5.86592740193786e-06 -4.4877909896397e-06 1.7044552678916e-05 -5.46024197103507e-05 8.21656647161687e-05 7.22886567986783e-07 7.19703320265714e-06 3.53319961166805e-06 2.51430410130519e-05 1.06536120488141e-06 7.22886567986783e-07 1.2714462903689e-05 1.65735970671938e-06 -5.70559883310227e-06 -1.33815789203564e-06 -5.86592740193786e-06 7.19703320265714e-06 1.65735970671938e-06 2.83185856800997e-05 5.73705856979857e-06 1.30697691972569e-06 -4.4877909896397e-06 3.53319961166805e-06 -5.70559883310227e-06 5.73705856979857e-06 2.70653933331965e-05 -1.77795881342249e-06 1.7044552678916e-05 2.51430410130519e-05 -1.33815789203564e-06 1.30697691972569e-06 -1.77795881342249e-06 7.61615783280177e-05 1358 1375 0 0 0 1400 1443 0 0 0 0 0 0 0 0 0 0 0 1041 0 2 29 0 0 2796 +1273 1309 0.995993700703889 -0.00687391819151416 0.0891588324669404 -0.0132388473630781 -0.00651013203266413 0.988821740488287 0.148960342771601 -0.0236184288028207 -0.0891861331098554 -0.148943998826445 0.984815474530381 0.008407610169719 5.54164039430851e-05 -6.75946106291116e-06 2.79711293069264e-06 5.33531053260271e-06 5.46283191531268e-06 9.94642957602382e-06 -6.75946106291116e-06 5.18929905139204e-05 -4.1617839990791e-06 -2.99918544916244e-07 -6.70699490992165e-07 2.49677003021765e-05 2.79711293069264e-06 -4.1617839990791e-06 1.38943667320217e-05 -5.6938748761843e-07 -6.32805857090238e-06 -4.77171708346933e-06 5.33531053260271e-06 -2.99918544916244e-07 -5.6938748761843e-07 2.76833126114938e-05 -7.63454855701403e-07 5.15155717040343e-07 5.46283191531268e-06 -6.70699490992165e-07 -6.32805857090238e-06 -7.63454855701403e-07 2.27364236630108e-05 1.44929065032257e-06 9.94642957602382e-06 2.49677003021765e-05 -4.77171708346933e-06 5.15155717040343e-07 1.44929065032257e-06 5.32252877020971e-05 1360 1376 0 0 0 1400 1443 0 0 0 0 0 0 0 0 0 0 0 940 0 3 30 0 0 2562 +1273 1315 0.995877487185837 -0.0062549598780614 0.0904925742442318 -0.0201829617646202 -0.00757167094289305 0.988405769704255 0.15164664260864 -0.0280394536114678 -0.0903919261635491 -0.151706657376214 0.984283693755098 -0.000872463867398628 7.74421557463165e-05 -4.46028049676187e-05 1.42999526448006e-06 -1.73811332897655e-06 -2.11356448410089e-07 1.18353034309794e-05 -4.46028049676187e-05 8.2237962831518e-05 3.77833904007775e-06 6.56545847384462e-07 5.43190295807367e-06 2.65767740720124e-05 1.42999526448006e-06 3.77833904007775e-06 1.63875102361827e-05 1.41933503714275e-06 -5.89549587340306e-06 -1.51377091877702e-06 -1.73811332897655e-06 6.56545847384462e-07 1.41933503714275e-06 3.29417546921692e-05 -7.65089396815047e-06 5.09510869096411e-06 -2.11356448410089e-07 5.43190295807367e-06 -5.89549587340306e-06 -7.65089396815047e-06 2.46892782640148e-05 -1.63964018993076e-06 1.18353034309794e-05 2.65767740720124e-05 -1.51377091877702e-06 5.09510869096411e-06 -1.63964018993076e-06 8.86093858392367e-05 1243 1243 0 0 0 1281 1300 0 0 0 0 0 0 0 0 0 0 0 1041 0 4 33 0 0 2839 +1273 1314 0.996274421986539 -0.00568360116270937 0.0860521514734576 -0.0183700548720809 -0.00738624114029501 0.988535808228162 0.15080583308517 -0.0260178166977567 -0.0859227533148529 -0.150879596130551 0.984810960506775 0.00877861123363803 0.000116145073367917 -5.20887314733245e-05 7.85261001442423e-06 -2.70494000952635e-06 -3.88360295658755e-07 1.24714428966042e-05 -5.20887314733245e-05 6.66607042641916e-05 -1.8782291949181e-06 1.72442501060173e-06 3.62642561365786e-06 2.55064486056513e-05 7.85261001442423e-06 -1.8782291949181e-06 1.74646718869478e-05 5.34510844588959e-07 -6.10500588095779e-06 -5.88352151966234e-06 -2.70494000952635e-06 1.72442501060173e-06 5.34510844588959e-07 3.01133738472499e-05 -3.97223969871347e-06 6.09517717654597e-06 -3.88360295658755e-07 3.62642561365786e-06 -6.10500588095779e-06 -3.97223969871347e-06 2.35520347343373e-05 1.98061981648147e-06 1.24714428966042e-05 2.55064486056513e-05 -5.88352151966234e-06 6.09517717654597e-06 1.98061981648147e-06 7.3102330156243e-05 1347 1348 0 0 0 1389 1413 0 0 0 0 0 0 0 0 0 0 0 1047 0 3 31 0 0 2530 +1273 1305 0.995940992908965 -0.00558821455429134 0.0898349069215285 -0.0142087507323006 -0.00787757442898779 0.988829307015415 0.148844030476636 -0.025532489496124 -0.0896631611344382 -0.148947552667069 0.98477162027034 -0.000549243639029991 8.40390099628449e-05 -4.10524557594338e-05 2.9804715749756e-06 -4.32571017699643e-06 1.50697445039963e-06 2.24781676160896e-05 -4.10524557594338e-05 6.91625196296144e-05 -1.34805515200126e-06 6.46173430276903e-06 1.7503578210805e-06 1.32952862605218e-05 2.9804715749756e-06 -1.34805515200126e-06 1.44484060310692e-05 4.78371259052676e-07 -5.28713615829254e-06 -3.59635358843898e-06 -4.32571017699643e-06 6.46173430276903e-06 4.78371259052676e-07 2.69577247269717e-05 1.19408534152677e-06 2.32739761902329e-06 1.50697445039963e-06 1.7503578210805e-06 -5.28713615829254e-06 1.19408534152677e-06 2.49199201277842e-05 2.40722028830379e-06 2.24781676160896e-05 1.32952862605218e-05 -3.59635358843898e-06 2.32739761902329e-06 2.40722028830379e-06 7.52345356699815e-05 1253 1255 0 0 0 1290 1316 0 0 0 0 0 0 0 0 0 0 0 948 0 2 26 0 0 2749 +1273 1312 0.995971160769112 -0.00534177086227356 0.0895148725088892 -0.0142550018726139 -0.00786399153420613 0.989175557357497 0.14652601940828 -0.0259723975972955 -0.0893286323268058 -0.146639633832538 0.985148320424941 0.00645931014241322 7.60845478340011e-05 -2.6200775538105e-05 6.82447527567667e-06 -2.36633531757954e-06 3.19085064006266e-06 9.73174195688427e-06 -2.6200775538105e-05 7.97219584680036e-05 -4.45676359435812e-06 4.71412076857092e-06 -3.64817131585002e-06 3.43955265083679e-05 6.82447527567667e-06 -4.45676359435812e-06 1.43510583193088e-05 2.83842558076236e-07 -4.49915333588531e-06 -2.7965776029209e-06 -2.36633531757954e-06 4.71412076857092e-06 2.83842558076236e-07 2.57744926518069e-05 -1.42126437192853e-06 5.08010485151743e-07 3.19085064006266e-06 -3.64817131585002e-06 -4.49915333588531e-06 -1.42126437192853e-06 2.33212604273897e-05 2.12205651042389e-06 9.73174195688427e-06 3.43955265083679e-05 -2.7965776029209e-06 5.08010485151743e-07 2.12205651042389e-06 6.37304544921142e-05 1351 1367 0 0 0 1391 1431 0 0 0 0 0 0 0 0 0 0 0 1044 0 4 37 0 0 2759 +1273 1318 0.996093264207166 -0.00549641940976808 0.0881362489262253 -0.0165903323185959 -0.0075497991303623 0.989106298662225 0.147009287052907 -0.0284700376163771 -0.087984143652165 -0.147100371584795 0.985200624819844 0.0110154330083151 0.000107593113747983 -5.8664407441061e-05 -1.73194061306559e-07 -1.9210021657125e-06 -4.02300424532729e-06 4.00683540321219e-05 -5.8664407441061e-05 7.93007136604306e-05 -5.92168126730011e-07 3.73146390593665e-06 1.19603605963122e-05 -2.88581796034945e-06 -1.73194061306559e-07 -5.92168126730011e-07 1.52294676645602e-05 2.51375615558884e-06 -4.62565529345212e-06 -7.79396408163018e-06 -1.9210021657125e-06 3.73146390593665e-06 2.51375615558884e-06 2.42486372091759e-05 -5.37840477665945e-06 4.21605946595375e-06 -4.02300424532729e-06 1.19603605963122e-05 -4.62565529345212e-06 -5.37840477665945e-06 2.75441604944899e-05 2.7874522280326e-06 4.00683540321219e-05 -2.88581796034945e-06 -7.79396408163018e-06 4.21605946595375e-06 2.7874522280326e-06 0.000102668509569503 1354 1356 0 0 0 1401 1435 0 0 7 0 0 0 0 0 0 0 0 1051 0 8 43 0 0 2824 +1273 1307 0.996413111419864 -0.00572017100344738 0.0844286150204796 -0.0141648311485578 -0.00696639231273316 0.988781330407548 0.149207741138399 -0.0257798668988629 -0.0843349320787663 -0.149260712450295 0.985194832989952 0.00484141525313667 0.000103267872670864 -4.02890162198373e-05 3.46450540805621e-06 -2.86655437602821e-06 2.67714326634112e-07 3.07386344035367e-05 -4.02890162198373e-05 6.0982569308323e-05 -3.20662092191451e-06 7.35934187772573e-06 2.87871663213009e-06 2.85818283987579e-05 3.46450540805621e-06 -3.20662092191451e-06 1.37798322145161e-05 1.54149141017852e-06 -2.93708932031615e-06 -2.46552586985521e-06 -2.86655437602821e-06 7.35934187772573e-06 1.54149141017852e-06 2.5200046729846e-05 2.80811540720466e-07 2.61375802994868e-06 2.67714326634112e-07 2.87871663213009e-06 -2.93708932031615e-06 2.80811540720466e-07 2.36360139155598e-05 1.31680762910628e-06 3.07386344035367e-05 2.85818283987579e-05 -2.46552586985521e-06 2.61375802994868e-06 1.31680762910628e-06 8.83113934791998e-05 1360 1363 0 0 0 1404 1441 0 0 6 0 0 0 0 0 0 0 0 1038 0 5 38 0 0 2588 +1273 1300 0.996416708025257 -0.00568185794873271 0.0843887460409319 -0.0147823254345504 -0.00675069475822319 0.989215459262354 0.146312006604558 -0.0287148158944334 -0.0843099762091757 -0.146357410631035 0.985632454957215 0.00700519703401352 6.99735453459851e-05 -1.29834042426377e-05 7.49310817938203e-06 -1.73698258105409e-06 5.40222350012874e-06 9.2590835278191e-06 -1.29834042426377e-05 6.69972181924106e-05 -9.82233034951744e-07 5.21140155478082e-06 5.08288691496998e-06 2.75120536416245e-05 7.49310817938203e-06 -9.82233034951744e-07 1.23645054222656e-05 1.24563286446141e-06 -4.92795552407572e-06 -2.1299337852263e-06 -1.73698258105409e-06 5.21140155478082e-06 1.24563286446141e-06 2.47930637484401e-05 2.6349956944377e-06 -1.21885258403835e-06 5.40222350012874e-06 5.08288691496998e-06 -4.92795552407572e-06 2.6349956944377e-06 2.21434457068894e-05 1.53221155889319e-06 9.2590835278191e-06 2.75120536416245e-05 -2.1299337852263e-06 -1.21885258403835e-06 1.53221155889319e-06 6.13663947992091e-05 1356 1359 0 0 0 1403 1437 0 0 6 0 0 0 0 0 0 0 0 938 0 6 40 0 0 2797 +1273 1304 0.996606730706516 -0.00568031844290453 0.0821143001727326 -0.0129401403342903 -0.00664305347260403 0.988810768482205 0.149027292715771 -0.0252442470271494 -0.0820420267364876 -0.149067092666421 0.98541773260529 0.00159548608151731 6.76226829580712e-05 -3.52545707932674e-05 4.48317310990458e-06 -1.73497275378975e-06 6.52506808317049e-07 -1.02157688196502e-05 -3.52545707932674e-05 7.26116800739477e-05 1.28342091636921e-06 2.22026174700227e-06 -1.74404424914072e-06 2.76332916753921e-05 4.48317310990458e-06 1.28342091636921e-06 1.62328111522068e-05 -1.32986817392567e-06 -4.63983341872709e-06 1.26895678770301e-07 -1.73497275378975e-06 2.22026174700227e-06 -1.32986817392567e-06 3.07413067662645e-05 2.86202803576386e-06 -5.26842009950535e-06 6.52506808317049e-07 -1.74404424914072e-06 -4.63983341872709e-06 2.86202803576386e-06 2.58089362327982e-05 -6.3172808057217e-06 -1.02157688196502e-05 2.76332916753921e-05 1.26895678770301e-07 -5.26842009950535e-06 -6.3172808057217e-06 6.02893831455392e-05 1359 1374 0 0 0 1400 1439 0 0 0 0 0 0 0 0 0 0 0 1037 0 3 33 0 0 2766 +1273 1317 0.99613820382879 -0.00509240827713421 0.0876512763779936 -0.0156847599848126 -0.00792295832107113 0.989029740480954 0.147503895459135 -0.0279154127244072 -0.087440869187097 -0.147628722889943 0.985169962277418 0.00881669248369103 7.4004700111761e-05 -3.16824898511681e-05 1.90879098178238e-06 2.55917899070727e-06 5.72077706631563e-07 -4.47201732609818e-06 -3.16824898511681e-05 7.54474165221539e-05 -1.92293908196996e-06 4.55172307238182e-06 -1.62536303835531e-06 3.95358172461487e-05 1.90879098178238e-06 -1.92293908196996e-06 1.43098249447087e-05 4.68996991132393e-06 -6.10255291409292e-06 -2.08000956069616e-06 2.55917899070727e-06 4.55172307238182e-06 4.68996991132393e-06 2.64649672815029e-05 -7.06591518450519e-06 1.35112595008294e-06 5.72077706631563e-07 -1.62536303835531e-06 -6.10255291409292e-06 -7.06591518450519e-06 2.31824265801912e-05 -2.21939047895552e-06 -4.47201732609818e-06 3.95358172461487e-05 -2.08000956069616e-06 1.35112595008294e-06 -2.21939047895552e-06 5.87240833732443e-05 1343 1345 0 0 0 1388 1411 0 0 0 0 0 0 0 0 0 0 0 944 0 4 34 0 0 2789 +1273 1316 0.995569236041498 -0.00557645855992431 0.0938658583174834 -0.0173235796448395 -0.00875264479138276 0.988410313706325 0.151553432716387 -0.0277326859462121 -0.0936231139030544 -0.151703509744811 0.983982092151174 0.00175732737095786 0.000121070921371515 -5.33980945661193e-05 1.41269609614276e-06 -1.44820320981729e-06 -6.13075067261561e-07 2.98123104596319e-05 -5.33980945661193e-05 8.17292392521088e-05 -7.65853479815753e-07 -5.20894122239631e-06 -2.40781374486038e-06 1.8215097537148e-05 1.41269609614276e-06 -7.65853479815753e-07 1.53354656221182e-05 2.34130585508113e-06 -6.68152609300202e-06 -6.04164577706168e-06 -1.44820320981729e-06 -5.20894122239631e-06 2.34130585508113e-06 2.8838561313893e-05 -6.47756846625309e-06 3.92439156521679e-06 -6.13075067261561e-07 -2.40781374486038e-06 -6.68152609300202e-06 -6.47756846625309e-06 2.08239776974267e-05 -6.65354300764879e-06 2.98123104596319e-05 1.8215097537148e-05 -6.04164577706168e-06 3.92439156521679e-06 -6.65354300764879e-06 8.39515318989012e-05 1250 1250 0 0 0 1292 1313 0 0 0 0 0 0 0 0 0 0 0 1034 0 4 32 0 0 2777 +1273 1303 0.996250434439923 -0.00595387454828556 0.0863112000619103 -0.0140696348225807 -0.00685822237252541 0.989055006623624 0.147387783274709 -0.0251574484754392 -0.0862440529204931 -0.14742708452183 0.985305647038136 0.00927294247898248 9.63071948347962e-05 -4.90268904867776e-05 4.13486860255027e-06 -8.47838517538691e-06 -5.68291138106757e-06 1.55345892785587e-05 -4.90268904867776e-05 8.77605368578859e-05 2.40637823068363e-06 2.82818948731353e-06 -1.29316662587053e-06 2.91697619697152e-05 4.13486860255027e-06 2.40637823068363e-06 1.57612143540362e-05 -1.34207542694837e-06 -6.01298321948652e-06 2.03767524889288e-06 -8.47838517538691e-06 2.82818948731353e-06 -1.34207542694837e-06 3.29581198689342e-05 7.60565724560295e-06 -3.8147078470377e-06 -5.68291138106757e-06 -1.29316662587053e-06 -6.01298321948652e-06 7.60565724560295e-06 2.90462803130204e-05 -5.16115839870524e-06 1.55345892785587e-05 2.91697619697152e-05 2.03767524889288e-06 -3.8147078470377e-06 -5.16115839870524e-06 7.04938057044815e-05 1356 1372 0 0 0 1394 1437 0 0 0 0 0 0 0 0 0 0 0 940 0 3 33 0 0 2792 +1273 1301 0.995601363761203 -0.00646270789438022 0.0934674161593477 -0.0153842145192796 -0.00714792175893965 0.989471010999996 0.144554576562535 -0.028442503872865 -0.0934175127658666 -0.1445868313413 0.985072493023393 0.00814698041424817 6.43393704501735e-05 -2.95486262997329e-05 5.28170304847861e-06 -5.50760990341867e-06 -5.71374827796475e-06 7.51365772174883e-06 -2.95486262997329e-05 7.0632544577767e-05 9.50493768471988e-09 2.33427659328381e-06 5.72612790408873e-08 2.23925603891308e-05 5.28170304847861e-06 9.50493768471988e-09 1.43917650207605e-05 2.51833230313572e-07 -4.4666060405033e-06 -1.84026346352789e-06 -5.50760990341867e-06 2.33427659328381e-06 2.51833230313572e-07 3.36829008119311e-05 1.46312666322205e-05 -1.15056253617276e-05 -5.71374827796475e-06 5.72612790408873e-08 -4.4666060405033e-06 1.46312666322205e-05 3.48095136858285e-05 -1.62813527833613e-05 7.51365772174883e-06 2.23925603891308e-05 -1.84026346352789e-06 -1.15056253617276e-05 -1.62813527833613e-05 7.75281195989922e-05 1356 1358 0 0 0 1401 1435 0 0 6 0 0 0 0 0 0 0 0 1039 0 7 41 0 0 2835 +1273 1302 0.996374532705697 -0.00616407470465325 0.0848516043368621 -0.0157514025278859 -0.00651120850492436 0.988921173195804 0.148298743652264 -0.0253516287940753 -0.0848256726428346 -0.148313577895181 0.985295736250097 0.00435074397791208 6.67019395774133e-05 -3.65286906328415e-05 7.89293141815514e-06 -5.358572639419e-06 -1.02802059697254e-06 5.63294073231623e-06 -3.65286906328415e-05 6.04201368688032e-05 -3.33081772337814e-06 1.4527391048494e-06 1.66830491953984e-06 1.94914369131884e-05 7.89293141815514e-06 -3.33081772337814e-06 1.51187986384372e-05 -1.20992692424922e-06 -4.24567079604535e-06 -3.21048840931705e-06 -5.358572639419e-06 1.4527391048494e-06 -1.20992692424922e-06 2.87775611354918e-05 2.49974399240157e-06 -1.81889489548199e-06 -1.02802059697254e-06 1.66830491953984e-06 -4.24567079604535e-06 2.49974399240157e-06 2.7899215240933e-05 3.05978114337907e-06 5.63294073231623e-06 1.94914369131884e-05 -3.21048840931705e-06 -1.81889489548199e-06 3.05978114337907e-06 5.52186917160328e-05 1351 1354 0 0 0 1393 1417 0 0 0 0 0 0 0 0 0 0 0 942 0 3 29 0 0 2532 +1274 1276 0.99998054106495 -0.00563182211719306 -0.00268329481982818 -1.85657142174036e-05 0.00562035648613542 0.999975125222903 -0.00426151714867147 -0.00317563686823408 0.00270722817999834 0.00424635315064123 0.999987319619855 -0.00532257660075063 4.21947272887534e-05 2.91977070581499e-06 -1.27402864227421e-06 6.46125672346802e-07 4.34744878846836e-06 8.21242924461942e-06 2.91977070581499e-06 3.06978638351313e-05 -9.4726922980613e-07 1.7968063118348e-06 6.95380121909102e-07 1.37705380791157e-05 -1.27402864227421e-06 -9.4726922980613e-07 1.38455042144116e-05 7.89793292583857e-07 -1.72023066390668e-06 -4.13572775373874e-06 6.46125672346802e-07 1.7968063118348e-06 7.89793292583857e-07 2.19563059649904e-05 -7.91430785726588e-07 5.55021433541511e-06 4.34744878846836e-06 6.95380121909102e-07 -1.72023066390668e-06 -7.91430785726588e-07 2.28285936439208e-05 -4.06622882947388e-06 8.21242924461942e-06 1.37705380791157e-05 -4.13572775373874e-06 5.55021433541511e-06 -4.06622882947388e-06 5.03240499121653e-05 1214 1222 0 0 0 1229 1301 0 0 0 0 0 0 0 0 0 0 0 788 0 0 0 0 0 3494 +1274 1277 0.999981078300651 -0.00613983339243721 -0.000381427031244682 -0.00296619666021132 0.00614200936309368 0.99996318028779 0.00599281150309561 0.00447637823281524 0.000344618123029874 -0.00599504083731534 0.999981970199317 0.0044002659751618 5.47947314886628e-05 1.2557654124997e-05 5.07118392310062e-07 5.63731270065845e-06 2.22260594681928e-06 1.282448188801e-05 1.2557654124997e-05 5.35972763897148e-05 -3.44772187775146e-06 1.1902691704222e-05 -5.52447054673088e-07 2.64867671635242e-05 5.07118392310062e-07 -3.44772187775146e-06 1.42667256356064e-05 -1.97629142521822e-06 7.85649930102999e-07 -4.30833992111585e-06 5.63731270065845e-06 1.1902691704222e-05 -1.97629142521822e-06 2.64707857367119e-05 -8.55107120174854e-06 8.24772978005791e-06 2.22260594681928e-06 -5.52447054673088e-07 7.85649930102999e-07 -8.55107120174854e-06 2.84970145957712e-05 3.16864979099789e-06 1.282448188801e-05 2.64867671635242e-05 -4.30833992111585e-06 8.24772978005791e-06 3.16864979099789e-06 5.03839817070164e-05 1212 1224 0 0 0 1225 1296 0 0 0 0 0 0 0 0 0 0 0 769 0 0 1 0 0 3473 +1274 1307 0.996809416247679 -0.00300796200709602 0.0797617693166612 -0.0174797435249104 -0.00910421744922524 0.988483289242427 0.15105595027376 -0.024052056693191 -0.0792975466492983 -0.151300162105119 0.985302065380139 0.00686354565126284 7.26014472743294e-05 -3.23528069546118e-05 3.96000831013288e-06 -6.93478102372626e-07 2.38481047096844e-06 2.25268268475938e-06 -3.23528069546118e-05 5.85719343437116e-05 -1.12566393737999e-06 3.05354119661162e-06 -5.95368563224766e-06 1.40620057117205e-05 3.96000831013288e-06 -1.12566393737999e-06 1.32482307628498e-05 4.04391890590203e-06 -5.51906590824246e-06 -2.91651351586783e-06 -6.93478102372626e-07 3.05354119661162e-06 4.04391890590203e-06 2.49724617882108e-05 -3.15451753624271e-06 -1.83218765825123e-06 2.38481047096844e-06 -5.95368563224766e-06 -5.51906590824246e-06 -3.15451753624271e-06 2.18188851333737e-05 -6.04029659555229e-07 2.25268268475938e-06 1.40620057117205e-05 -2.91651351586783e-06 -1.83218765825123e-06 -6.04029659555229e-07 4.67516737718241e-05 1343 1343 0 0 0 1405 1440 0 0 0 0 0 0 0 0 0 0 0 1051 0 5 40 0 0 2633 +1273 1299 0.99588255789488 -0.00604194164101597 0.0904512344965863 -0.0137711309446591 -0.00650997375823614 0.990433861289902 0.137834635168534 -0.0283779693312865 -0.0904187542626914 -0.13785594420112 0.986316474325559 0.0161550533655737 9.22971513137123e-05 5.47559517099597e-06 4.55340864216202e-06 -9.54507240883688e-06 -1.53750996924872e-05 3.69035946520344e-05 5.47559517099597e-06 8.03762301121913e-05 -1.0465281216073e-06 -1.38930900826728e-06 -5.26831189857371e-06 5.69075204758601e-05 4.55340864216202e-06 -1.0465281216073e-06 1.33456210625608e-05 -9.09368257381887e-07 -4.88239419832081e-06 -1.97259512326899e-06 -9.54507240883688e-06 -1.38930900826728e-06 -9.09368257381887e-07 2.73202379838578e-05 2.24143329397265e-06 -7.07205409196233e-06 -1.53750996924872e-05 -5.26831189857371e-06 -4.88239419832081e-06 2.24143329397265e-06 2.43888540462438e-05 -1.40721899899296e-05 3.69035946520344e-05 5.69075204758601e-05 -1.97259512326899e-06 -7.07205409196233e-06 -1.40721899899296e-05 8.81776228977037e-05 1355 1371 0 0 0 1398 1437 0 0 0 0 0 0 0 0 0 0 0 956 0 4 36 0 0 2806 +1274 1278 0.999964929529695 -0.00520221322195787 -0.00656328334492061 -0.00121926849246661 0.00518456034298354 0.999982904767938 -0.00270379472727619 -0.00303773080557983 0.00657723686074843 0.00266967216537365 0.999974806085537 -0.000383721607744727 4.4897335904133e-05 1.02378891048496e-05 2.81336119947815e-06 -7.43533157405104e-06 -2.09373992553217e-06 9.47531807685219e-06 1.02378891048496e-05 5.21515530054478e-05 3.91728528953808e-06 -1.93789699096139e-06 1.6104776122899e-06 2.33217069768061e-05 2.81336119947815e-06 3.91728528953808e-06 1.43643096895079e-05 -6.31424405500695e-07 -2.08066854481063e-06 -9.86425172117994e-07 -7.43533157405104e-06 -1.93789699096139e-06 -6.31424405500695e-07 2.44511525649708e-05 1.60372123817215e-06 1.00548901742597e-06 -2.09373992553217e-06 1.6104776122899e-06 -2.08066854481063e-06 1.60372123817215e-06 2.46498051184388e-05 -5.60020698464787e-06 9.47531807685219e-06 2.33217069768061e-05 -9.86425172117994e-07 1.00548901742597e-06 -5.60020698464787e-06 4.95740952973598e-05 1202 1206 0 0 0 1203 1280 0 0 0 0 0 0 0 0 0 0 0 813 0 0 0 0 0 3483 +1274 1305 0.996350644410596 -0.0027006404007508 0.0853117806871664 -0.0200243604565024 -0.00994857818866621 0.989012454233024 0.147497088662775 -0.0296552681115231 -0.0847727501890397 -0.147807550258423 0.985376328572993 0.00735985968695511 9.46129620895056e-05 -5.70609193593915e-05 2.76902922235274e-06 -1.35131459479579e-06 -9.11460177009393e-06 1.24441632689896e-05 -5.70609193593915e-05 9.53182276571693e-05 6.16514268765101e-07 1.46905422961889e-06 -2.71413266445594e-06 6.88323625483263e-06 2.76902922235274e-06 6.16514268765101e-07 1.5006013315647e-05 4.76394514490871e-07 -5.17245162774838e-06 -3.1738615552079e-06 -1.35131459479579e-06 1.46905422961889e-06 4.76394514490871e-07 2.66933860475869e-05 4.69340207208948e-07 8.73802986169613e-07 -9.11460177009393e-06 -2.71413266445594e-06 -5.17245162774838e-06 4.69340207208948e-07 2.77323863047408e-05 4.37551584217403e-06 1.24441632689896e-05 6.88323625483263e-06 -3.1738615552079e-06 8.73802986169613e-07 4.37551584217403e-06 8.07045181336391e-05 1239 1239 0 0 0 1284 1308 0 0 0 0 0 0 0 0 0 0 0 958 0 5 36 0 0 2754 +1274 1315 0.996393444976475 -0.00296045583163563 0.0848017600594542 -0.02259595776471 -0.00992945494181192 0.988457105397129 0.151175251660075 -0.0304553626768681 -0.0842704499363261 -0.151472065052264 0.984862784745333 0.00699306849944023 9.24961120676591e-05 -5.21793679500061e-05 5.09956208931347e-06 1.64733320954022e-06 5.5573511033938e-06 1.32359169390184e-05 -5.21793679500061e-05 9.7106675770267e-05 -3.82296223284552e-06 1.05850749491251e-05 -3.09131293175609e-07 2.01693072707611e-05 5.09956208931347e-06 -3.82296223284552e-06 1.53576244998287e-05 2.74504211654612e-06 -4.91877636508618e-06 -3.05242436719876e-06 1.64733320954022e-06 1.05850749491251e-05 2.74504211654612e-06 2.85182462126038e-05 -6.39707061671177e-06 7.33176392965029e-06 5.5573511033938e-06 -3.09131293175609e-07 -4.91877636508618e-06 -6.39707061671177e-06 2.60147717768059e-05 5.08397202423037e-06 1.32359169390184e-05 2.01693072707611e-05 -3.05242436719876e-06 7.33176392965029e-06 5.08397202423037e-06 7.56184176413805e-05 1233 1233 0 0 0 1279 1302 0 0 0 0 0 0 0 0 0 0 0 1056 0 5 36 0 0 2839 +1274 1308 0.996554617800451 -0.00319035609430321 0.082877713340727 -0.0175061310763769 -0.009426310989481 0.988428396684575 0.151395010778725 -0.0260348842071391 -0.0824016893135436 -0.151654628203534 0.984992809792397 0.00683501600234284 0.000120500946234538 -6.04435458318612e-05 5.74193906054179e-06 -2.33748145511514e-06 -2.15471820646206e-06 3.61045796287509e-05 -6.04435458318612e-05 8.31303411364535e-05 -6.62460217084327e-06 1.45498178457035e-05 9.88550639923421e-07 3.90859270822612e-06 5.74193906054179e-06 -6.62460217084327e-06 1.43241225980732e-05 1.18353479587743e-06 -4.77279665528264e-06 -3.47102203946844e-06 -2.33748145511514e-06 1.45498178457035e-05 1.18353479587743e-06 3.16208024036658e-05 -3.00343089373353e-06 -6.1201552322417e-08 -2.15471820646206e-06 9.88550639923421e-07 -4.77279665528264e-06 -3.00343089373353e-06 2.52614197816321e-05 -2.40011071292192e-06 3.61045796287509e-05 3.90859270822612e-06 -3.47102203946844e-06 -6.1201552322417e-08 -2.40011071292192e-06 7.47051465867835e-05 1254 1256 0 0 0 1297 1324 0 0 0 0 0 0 0 0 0 0 0 1058 0 3 30 0 0 2877 +1274 1313 0.996586377058252 -0.00433172514873309 0.0824428845877217 -0.0203833060699841 -0.00848680282939311 0.987956409188263 0.154499539551318 -0.0277489545810091 -0.08211922576135 -0.154671812884798 0.984547136027162 0.0107327748465461 7.49715755497924e-05 -9.1744104128726e-06 5.82540114849404e-06 5.27302610986563e-06 -1.83937642936636e-06 2.59133246054645e-05 -9.1744104128726e-06 5.90870158114238e-05 -3.22074696329095e-06 2.98252788696123e-06 1.69720536720494e-06 2.5568326559488e-05 5.82540114849404e-06 -3.22074696329095e-06 1.34097758146244e-05 2.2036670696016e-06 -4.05355929422979e-06 -2.86238132080462e-06 5.27302610986563e-06 2.98252788696123e-06 2.2036670696016e-06 2.98480323750417e-05 -1.2768567781937e-06 4.14351677894805e-06 -1.83937642936636e-06 1.69720536720494e-06 -4.05355929422979e-06 -1.2768567781937e-06 2.51483388978887e-05 2.99835813122179e-07 2.59133246054645e-05 2.5568326559488e-05 -2.86238132080462e-06 4.14351677894805e-06 2.99835813122179e-07 7.02530843168017e-05 1345 1358 0 0 0 1394 1431 0 0 0 0 0 0 0 0 0 0 0 1055 0 5 42 0 0 2859 +1274 1309 0.996365779926154 -0.0042920222188043 0.0850694489074703 -0.0181810162918634 -0.00881327555090591 0.988174350781918 0.153080954500546 -0.0261335377690051 -0.0847204743035071 -0.153274365116962 0.984545280945362 0.00884195458266695 9.92693184567855e-05 -4.85937149811411e-05 2.89459037889107e-06 -3.52795694595785e-06 -7.44271424272565e-06 2.8406425006418e-05 -4.85937149811411e-05 8.46491216223012e-05 -3.77740378234494e-06 6.45882720505495e-06 1.13938322528901e-06 2.2718290274108e-05 2.89459037889107e-06 -3.77740378234494e-06 1.53723289700647e-05 2.48579220055029e-06 -4.03880732916945e-06 -3.87765138505943e-06 -3.52795694595785e-06 6.45882720505495e-06 2.48579220055029e-06 2.27921831469396e-05 -5.31617768888116e-06 -4.32401204078932e-06 -7.44271424272565e-06 1.13938322528901e-06 -4.03880732916945e-06 -5.31617768888116e-06 2.75225834044259e-05 -2.7234859142761e-06 2.8406425006418e-05 2.2718290274108e-05 -3.87765138505943e-06 -4.32401204078932e-06 -2.7234859142761e-06 7.56553025293444e-05 1349 1362 0 0 0 1397 1436 0 0 4 0 0 0 0 0 0 0 0 955 0 4 38 0 0 2594 +1274 1310 0.996352715713774 -0.00382972244017558 0.0852443494656339 -0.0237599733786507 -0.00868079453013748 0.989260262023016 0.145906743464721 -0.0310036867049489 -0.0848876298179743 -0.146114568774594 0.985618903580741 -0.00214759512014626 0.00011344941213531 -7.26931696640313e-05 1.31674967564057e-06 -5.78909823756854e-06 -7.81182038983018e-06 4.23812988386568e-05 -7.26931696640313e-05 0.000111300481926583 2.69403535445166e-07 9.0558415361421e-06 8.39122393564915e-06 -1.03052946943224e-06 1.31674967564057e-06 2.69403535445166e-07 1.66404451663894e-05 6.84670227786029e-07 -5.93915101857482e-06 -1.77031232093e-06 -5.78909823756854e-06 9.0558415361421e-06 6.84670227786029e-07 2.88628938232432e-05 1.79548107370995e-06 5.67795538950899e-07 -7.81182038983018e-06 8.39122393564915e-06 -5.93915101857482e-06 1.79548107370995e-06 3.42457154533744e-05 -6.83914756956448e-06 4.23812988386568e-05 -1.03052946943224e-06 -1.77031232093e-06 5.67795538950899e-07 -6.83914756956448e-06 0.000117104735271387 1318 1318 0 0 0 1395 1422 0 0 0 0 0 0 0 0 0 0 0 1049 0 11 52 0 0 2563 +1274 1312 0.996121240866663 -0.00353978583417787 0.0879200967385086 -0.0174332451847666 -0.00973305493454931 0.988626325749034 0.150077498905084 -0.0248273823902991 -0.0874513644027445 -0.150351115566904 0.984757229428597 0.00938107982001927 0.000119990255794042 -4.49907282811489e-05 5.81388111032972e-06 2.23651065545543e-06 -4.38519236067352e-06 2.39489675784121e-05 -4.49907282811489e-05 9.37578568072184e-05 -3.22802837528067e-06 8.28622552440942e-06 2.64832591516743e-06 3.69063221495994e-05 5.81388111032972e-06 -3.22802837528067e-06 1.59044209925836e-05 1.83281616999255e-06 -5.42734897343715e-06 -4.08496902617391e-06 2.23651065545543e-06 8.28622552440942e-06 1.83281616999255e-06 3.07444834838996e-05 -3.09428038001802e-06 -2.05673153061002e-07 -4.38519236067352e-06 2.64832591516743e-06 -5.42734897343715e-06 -3.09428038001802e-06 2.50763093957381e-05 -2.98272708633292e-06 2.39489675784121e-05 3.69063221495994e-05 -4.08496902617391e-06 -2.05673153061002e-07 -2.98272708633292e-06 8.10824044150611e-05 1345 1360 0 0 0 1392 1432 0 0 3 0 0 0 0 0 0 0 0 1054 0 3 38 0 0 2749 +1274 1317 0.996207816472993 -0.00254961599751226 0.0869683037455373 -0.020958133414564 -0.0108450588588008 0.988136126511954 0.153197193774236 -0.0311324508223295 -0.086327116808451 -0.153559418272592 0.984361282234995 0.00913539683227615 0.000100813972146662 -3.44711864085384e-05 3.8474202550958e-06 -1.32726227841151e-06 -5.16241899755679e-06 1.66833840978828e-05 -3.44711864085384e-05 7.4826094936924e-05 -2.8966527981634e-06 6.70251351934026e-06 -2.4310032179229e-06 1.91807580680104e-05 3.8474202550958e-06 -2.8966527981634e-06 1.57928955328788e-05 3.01045844731367e-06 -1.60664391104845e-06 -2.60615142440808e-06 -1.32726227841151e-06 6.70251351934026e-06 3.01045844731367e-06 2.83341410667405e-05 -4.84878082669367e-06 2.95519973743607e-06 -5.16241899755679e-06 -2.4310032179229e-06 -1.60664391104845e-06 -4.84878082669367e-06 3.3052208054087e-05 -5.54234900708857e-06 1.66833840978828e-05 1.91807580680104e-05 -2.60615142440808e-06 2.95519973743607e-06 -5.54234900708857e-06 6.41260505994504e-05 1334 1339 0 0 0 1388 1413 0 0 0 0 0 0 0 0 0 0 0 951 0 6 55 0 0 2887 +1274 1306 0.996921358408564 -0.00298913839440715 0.0783509425628228 -0.0170420707566868 -0.00893734095027581 0.988428182312701 0.151426062310117 -0.0229402408837057 -0.0778969131966228 -0.151660124824121 0.985358451251508 0.00772977323527737 9.08570219329333e-05 -5.85819939942121e-05 8.62119565183257e-06 -4.54297636951375e-06 8.12199655555828e-06 1.38727859762389e-05 -5.85819939942121e-05 0.000108691144408928 -3.16439626363104e-06 1.08618123163879e-05 -5.83730780818223e-06 9.43153295733776e-06 8.62119565183257e-06 -3.16439626363104e-06 1.72451864621673e-05 2.35918089529633e-06 -2.75767335283387e-06 -5.68872574662361e-06 -4.54297636951375e-06 1.08618123163879e-05 2.35918089529633e-06 2.82843477034685e-05 -1.75789036656638e-06 -4.61287511963236e-06 8.12199655555828e-06 -5.83730780818223e-06 -2.75767335283387e-06 -1.75789036656638e-06 3.7114717531677e-05 5.10145311453726e-07 1.38727859762389e-05 9.43153295733776e-06 -5.68872574662361e-06 -4.61287511963236e-06 5.10145311453726e-07 7.14793755897711e-05 1352 1369 0 0 0 1398 1440 0 0 3 0 0 0 0 0 0 0 0 1047 0 3 34 0 0 2877 +1274 1311 0.996673103438527 -0.00418319131887169 0.0813954900016242 -0.0197353520675499 -0.00821325290991308 0.9884431644983 0.151369260529423 -0.0277527921132359 -0.0810880222896859 -0.151534192402165 0.985120358724847 0.0106220725586259 9.03710226494008e-05 -3.49555851813531e-05 3.5211994650435e-06 1.54801178827471e-08 -1.08739867446812e-06 3.21671837322527e-05 -3.49555851813531e-05 7.34587013421885e-05 -4.63428382807527e-06 5.41768891181119e-06 -2.44508460606532e-06 8.13938689873129e-06 3.5211994650435e-06 -4.63428382807527e-06 1.39113319287664e-05 5.22759790038576e-06 -4.5152323612142e-06 -5.0372555727305e-06 1.54801178827471e-08 5.41768891181119e-06 5.22759790038576e-06 2.54049118767467e-05 -3.538032550948e-06 -5.63203345116397e-06 -1.08739867446812e-06 -2.44508460606532e-06 -4.5152323612142e-06 -3.538032550948e-06 2.82230528455998e-05 -3.97632297767594e-06 3.21671837322527e-05 8.13938689873129e-06 -5.0372555727305e-06 -5.63203345116397e-06 -3.97632297767594e-06 8.82717053684362e-05 1347 1354 0 0 0 1395 1424 0 0 0 0 0 0 0 0 0 0 0 953 0 3 42 0 0 2863 +1274 1314 0.996275102007525 -0.0031110381966446 0.0861756494680156 -0.0218684689197179 -0.0102149622991416 0.988054662563646 0.15376488003269 -0.0266827539439542 -0.0856246206714074 -0.154072402550163 0.984342480596717 0.0119303378031417 0.000132003150198235 -6.14838263494409e-05 -3.585007206088e-06 -3.49583613544307e-06 -1.59608439426254e-05 3.40935702723297e-05 -6.14838263494409e-05 0.000101600313190981 -2.7172201344807e-07 1.13651572680733e-05 2.8451043112074e-06 2.30901794725824e-05 -3.585007206088e-06 -2.7172201344807e-07 1.63336398493473e-05 3.30195245848017e-06 -3.37711844391341e-06 -4.7903300693481e-06 -3.49583613544307e-06 1.13651572680733e-05 3.30195245848017e-06 3.09520030381804e-05 -6.39743420322732e-06 1.98418297268417e-06 -1.59608439426254e-05 2.8451043112074e-06 -3.37711844391341e-06 -6.39743420322732e-06 2.75999338895096e-05 -6.81198941008422e-06 3.40935702723297e-05 2.30901794725824e-05 -4.7903300693481e-06 1.98418297268417e-06 -6.81198941008422e-06 9.99934496648418e-05 1344 1348 0 0 0 1393 1421 0 0 0 0 0 0 0 0 0 0 0 1059 0 7 51 0 0 2556 +1274 1302 0.996512939175434 -0.00359860665603904 0.0833607346781016 -0.0210648126695968 -0.00933431752623348 0.987990074551921 0.154235155211801 -0.0276066294769849 -0.0829146101254609 -0.154475443410996 0.984511302530712 0.00638165785195082 0.000120829516973162 -4.89861700265164e-05 -1.25747155089905e-06 -4.61684948222506e-06 -1.30741112440995e-05 2.9820729335193e-05 -4.89861700265164e-05 8.06649668848639e-05 -5.77051494894851e-06 8.50858957587508e-06 3.95449943451274e-06 1.92633698189944e-05 -1.25747155089905e-06 -5.77051494894851e-06 1.71199645027905e-05 7.79896778466803e-07 -2.08305895990068e-06 -5.53746514542924e-06 -4.61684948222506e-06 8.50858957587508e-06 7.79896778466803e-07 3.1977007485467e-05 1.98272420597944e-06 -3.64639086251366e-06 -1.30741112440995e-05 3.95449943451274e-06 -2.08305895990068e-06 1.98272420597944e-06 3.10721347899193e-05 -6.56538306060662e-07 2.9820729335193e-05 1.92633698189944e-05 -5.53746514542924e-06 -3.64639086251366e-06 -6.56538306060662e-07 7.26726983167285e-05 1343 1346 0 0 0 1392 1418 0 0 0 0 0 0 0 0 0 0 0 947 0 4 49 0 0 2565 +1274 1301 0.99602638310581 -0.0038200480685763 0.0889766901492249 -0.0193823458874187 -0.009855624015223 0.988215193373167 0.152753390344388 -0.0280958690682199 -0.0885116423552742 -0.153023327696101 0.9842507558282 0.00381161180861255 6.54473953502617e-05 -4.08503953418181e-05 6.32082136800507e-06 -5.47173885961391e-06 2.0818029818132e-06 7.7457783568339e-06 -4.08503953418181e-05 6.58180177814332e-05 -4.56376371750098e-06 8.32968969211957e-06 -5.22581550078979e-06 1.13174270846097e-05 6.32082136800507e-06 -4.56376371750098e-06 1.20976271925652e-05 1.65212356008508e-06 -4.90857946535897e-06 -2.85686410417349e-06 -5.47173885961391e-06 8.32968969211957e-06 1.65212356008508e-06 2.73480161245517e-05 -3.77264966640483e-07 -4.21134114775903e-06 2.0818029818132e-06 -5.22581550078979e-06 -4.90857946535897e-06 -3.77264966640483e-07 2.32337260883645e-05 -5.73800803725037e-06 7.7457783568339e-06 1.13174270846097e-05 -2.85686410417349e-06 -4.21134114775903e-06 -5.73800803725037e-06 7.309050340648e-05 1331 1331 0 0 0 1400 1432 0 0 0 0 0 0 0 0 0 0 0 1046 0 9 47 0 0 2863 +1274 1300 0.996512584484018 -0.00435535630350999 0.0833288655656089 -0.0199650133752145 -0.00849982226814168 0.988143914181145 0.153295002815406 -0.0272206521324485 -0.0830085657410839 -0.153468679991178 0.984660826008313 0.00510894451875482 7.13403438242712e-05 -2.1126132547134e-05 8.20582467145873e-06 -3.2947969642296e-06 1.51833126503816e-06 5.35639766283398e-06 -2.1126132547134e-05 5.67685699556887e-05 -9.40041261433729e-06 1.06882607629868e-05 1.23923741414434e-06 1.91804748776461e-05 8.20582467145873e-06 -9.40041261433729e-06 1.52922805815757e-05 -3.70602833290841e-07 -2.08625140170636e-06 -3.83470180653271e-06 -3.2947969642296e-06 1.06882607629868e-05 -3.70602833290841e-07 2.69884245516297e-05 -1.54102496009639e-06 -3.79423290109102e-06 1.51833126503816e-06 1.23923741414434e-06 -2.08625140170636e-06 -1.54102496009639e-06 2.85558978185642e-05 4.95906610476607e-07 5.35639766283398e-06 1.91804748776461e-05 -3.83470180653271e-06 -3.79423290109102e-06 4.95906610476607e-07 6.28786075581094e-05 1333 1333 0 0 0 1403 1436 0 0 0 0 0 0 0 0 0 0 0 943 0 6 43 0 0 2902 +1274 1316 0.996117923824089 -0.00301404965733607 0.0879772546801182 -0.0220491830767433 -0.0106852825649226 0.987883673291984 0.154827881144333 -0.0281805752095874 -0.0873779524416487 -0.155166889341119 0.984016427647072 0.00781527844818308 7.01522406499923e-05 -3.19572736007434e-05 7.18546204956845e-06 -4.64363929350042e-06 8.92025938272339e-07 7.06610508496825e-06 -3.19572736007434e-05 7.51259452863676e-05 -4.14987042475357e-06 6.30980431384563e-06 -2.35211514498747e-06 1.9765463568814e-05 7.18546204956845e-06 -4.14987042475357e-06 1.47712027132953e-05 3.01219291642634e-06 -5.1553500916083e-06 -2.78141421183932e-06 -4.64363929350042e-06 6.30980431384563e-06 3.01219291642634e-06 2.94880635807045e-05 -4.42823841427741e-06 4.23987817066345e-06 8.92025938272339e-07 -2.35211514498747e-06 -5.1553500916083e-06 -4.42823841427741e-06 3.07581347396801e-05 -8.07064156717923e-07 7.06610508496825e-06 1.9765463568814e-05 -2.78141421183932e-06 4.23987817066345e-06 -8.07064156717923e-07 7.5888588836501e-05 1250 1251 0 0 0 1294 1318 0 0 0 0 0 0 0 0 0 0 0 1045 0 6 37 0 0 2899 +1274 1303 0.996568856996638 -0.00356566746631201 0.082690986691013 -0.0171977047683408 -0.00920042439557656 0.988107594168962 0.153488548551897 -0.0252930775591487 -0.0822548810427374 -0.153722699563683 0.984684450056717 0.00483909550853385 9.05529563136911e-05 -3.35878550524754e-05 3.73191025659002e-06 -3.58983955358221e-06 -5.02362160151912e-06 4.76282677614075e-06 -3.35878550524754e-05 7.64808816930355e-05 -2.76497209177428e-06 9.17220774138791e-06 -2.62700050735953e-06 3.38982685980773e-05 3.73191025659002e-06 -2.76497209177428e-06 1.6681028611454e-05 1.78257081110822e-07 -5.39682919341225e-07 -7.36345264559543e-07 -3.58983955358221e-06 9.17220774138791e-06 1.78257081110822e-07 2.93166712766849e-05 -3.72017920926616e-06 7.91900399906751e-07 -5.02362160151912e-06 -2.62700050735953e-06 -5.39682919341225e-07 -3.72017920926616e-06 3.23509148859996e-05 -1.04985973001135e-06 4.76282677614075e-06 3.38982685980773e-05 -7.36345264559543e-07 7.91900399906751e-07 -1.04985973001135e-06 6.9492118959033e-05 1348 1365 0 0 0 1395 1437 0 0 6 0 0 0 0 0 0 0 0 944 0 3 35 0 0 2785 +1275 1279 0.999995246889266 -0.000833398871966061 -0.00296844154347297 -0.00415789182408244 0.000832122933899126 0.999999560886387 -0.000431043449519394 -0.00668171697823934 0.00296879947111448 0.000428571292435884 0.999995501268054 -0.00151505258875544 6.25578873426525e-05 1.07210108902573e-05 -2.27508717672593e-06 7.64317177037179e-06 1.59564972730372e-06 2.16084525586656e-05 1.07210108902573e-05 5.06349436822897e-05 -1.75364672484283e-06 7.05156674629506e-06 2.35124587521858e-06 3.06898825984012e-05 -2.27508717672593e-06 -1.75364672484283e-06 1.07262225142205e-05 1.75280155639324e-06 -4.56219822177182e-06 -1.79444639207643e-06 7.64317177037179e-06 7.05156674629506e-06 1.75280155639324e-06 2.71704778734387e-05 5.87932780059241e-06 7.31390510178942e-06 1.59564972730372e-06 2.35124587521858e-06 -4.56219822177182e-06 5.87932780059241e-06 2.04807033135106e-05 2.46248023057047e-06 2.16084525586656e-05 3.06898825984012e-05 -1.79444639207643e-06 7.31390510178942e-06 2.46248023057047e-06 5.43639933695034e-05 1220 1220 0 0 0 1231 1297 0 0 0 0 0 0 0 0 0 0 0 788 0 0 0 0 0 3452 +1274 1304 0.997086021014891 -0.00283098405649322 0.0762328815273555 -0.0170780953583091 -0.00817510690423991 0.989591078783252 0.143675552616661 -0.0254797846806114 -0.0758461226681772 -0.143880097031767 0.986684287578521 0.00932210174787484 8.1245426608691e-05 -3.45111258601212e-05 2.88378589263456e-06 4.88682580448092e-06 5.03086584390527e-06 1.39001710949537e-06 -3.45111258601212e-05 6.58616793949638e-05 -1.27868970538994e-06 2.8403374716487e-06 -5.31371985636757e-06 3.46186749873095e-05 2.88378589263456e-06 -1.27868970538994e-06 1.41976862597725e-05 2.03489258374078e-06 -3.82493398738844e-06 -1.71649338519478e-06 4.88682580448092e-06 2.8403374716487e-06 2.03489258374078e-06 2.97531475627464e-05 4.51160078534957e-06 8.99774073341098e-07 5.03086584390527e-06 -5.31371985636757e-06 -3.82493398738844e-06 4.51160078534957e-06 3.29052988235793e-05 -3.72034793170317e-06 1.39001710949537e-06 3.46186749873095e-05 -1.71649338519478e-06 8.99774073341098e-07 -3.72034793170317e-06 5.92684383388925e-05 1352 1367 0 0 0 1398 1436 0 0 5 0 0 0 0 0 0 0 0 1051 0 3 37 0 0 2750 +1274 1318 0.996342793524528 -0.00285164215767818 0.0853985124504128 -0.0208392023653716 -0.0102932981402276 0.988158875703307 0.153088485465667 -0.0308255595660167 -0.0848238516287438 -0.153407641614686 0.984515621861373 0.00959968076317236 7.94026062818586e-05 -3.50725489861421e-05 2.54687587175378e-06 -2.83148019852832e-06 -3.75149124780738e-06 2.2597438720775e-05 -3.50725489861421e-05 7.88326361206721e-05 -9.48948352569423e-07 3.57431189920101e-06 -5.31866201127004e-06 1.24934901031943e-05 2.54687587175378e-06 -9.48948352569423e-07 1.6316100940156e-05 1.8095236346443e-06 -3.08979273778856e-06 -2.83102181190526e-06 -2.83148019852832e-06 3.57431189920101e-06 1.8095236346443e-06 3.02303863192627e-05 -6.55847531260449e-06 6.60850869421833e-08 -3.75149124780738e-06 -5.31866201127004e-06 -3.08979273778856e-06 -6.55847531260449e-06 3.06046542940456e-05 -2.5371404203711e-06 2.2597438720775e-05 1.24934901031943e-05 -2.83102181190526e-06 6.60850869421833e-08 -2.5371404203711e-06 8.21448134462527e-05 1327 1327 0 0 0 1399 1426 0 0 0 0 0 0 0 0 0 0 0 1060 0 11 50 0 0 2848 +1275 1306 0.996572132815857 0.00273319394289348 0.0826832132039226 -0.0174933739342069 -0.0150478764511611 0.988770037238381 0.148685489789424 -0.0312056530368835 -0.0813482975185429 -0.149420022455094 0.985421793639837 0.00776323562184001 0.000130446573074894 -7.70826531181395e-05 2.38999217120888e-06 -8.78568702473096e-06 -9.17562214412636e-06 4.3250310783337e-05 -7.70826531181395e-05 9.04809957706271e-05 1.18237001172674e-06 2.5083351086756e-06 1.64520329202184e-06 -8.60955150350379e-06 2.38999217120888e-06 1.18237001172674e-06 1.73685482449497e-05 -2.82724599337836e-06 -4.02488061790829e-06 -7.79174980046013e-06 -8.78568702473096e-06 2.5083351086756e-06 -2.82724599337836e-06 2.79921350446919e-05 1.30762758372269e-06 -1.31542568764892e-06 -9.17562214412636e-06 1.64520329202184e-06 -4.02488061790829e-06 1.30762758372269e-06 2.85754704769649e-05 -1.38850190597849e-05 4.3250310783337e-05 -8.60955150350379e-06 -7.79174980046013e-06 -1.31542568764892e-06 -1.38850190597849e-05 9.64133242205172e-05 1317 1317 0 0 0 1372 1386 0 0 0 0 0 0 0 0 0 0 0 1053 0 21 79 0 0 2849 +1275 1277 0.999973082061558 -0.00100585102655291 0.00726797193311404 0.0023374488065142 0.00101968836967142 0.999997674307795 -0.00190042485534391 0.000489669619869956 -0.00726604348575673 0.00190778476627593 0.999971782086549 0.00650995233413714 5.69669593654165e-05 8.6221362012125e-06 5.34437999341657e-06 2.65668858308658e-06 1.15263624937916e-05 1.48659550653397e-05 8.6221362012125e-06 5.02912787478899e-05 7.67545249471749e-07 8.17351925699942e-06 4.08703953649337e-06 3.1677854441278e-05 5.34437999341657e-06 7.67545249471749e-07 1.16705261969586e-05 6.45899511592604e-07 -2.86340287313007e-06 -2.71126453506391e-06 2.65668858308658e-06 8.17351925699942e-06 6.45899511592604e-07 2.30332956332837e-05 -7.9908332770995e-08 6.08594645960294e-06 1.15263624937916e-05 4.08703953649337e-06 -2.86340287313007e-06 -7.9908332770995e-08 1.95700612214186e-05 1.14385643363231e-06 1.48659550653397e-05 3.1677854441278e-05 -2.71126453506391e-06 6.08594645960294e-06 1.14385643363231e-06 4.90266645431683e-05 1225 1233 0 0 0 1225 1301 0 0 0 0 0 0 0 0 0 0 0 777 0 0 0 0 0 3501 +1275 1307 0.996712226235672 0.00277500817272558 0.0809755358239268 -0.0186809577381353 -0.0149022364974041 0.988642118290221 0.149548270769006 -0.0327979715364203 -0.0796408275930517 -0.150263306473224 0.985433040499469 0.0117911230134585 9.86607369997648e-05 -4.94857605049506e-05 1.05570137382704e-06 -2.59305272169798e-06 -3.23098830748382e-06 1.28415857882496e-05 -4.94857605049506e-05 5.79821987854651e-05 -3.52736740942165e-07 1.04666851283277e-06 2.05263854787414e-06 1.636782692701e-05 1.05570137382704e-06 -3.52736740942165e-07 1.47049441119458e-05 3.00886385353282e-06 -1.04850860420664e-06 -2.52637666324339e-06 -2.59305272169798e-06 1.04666851283277e-06 3.00886385353282e-06 2.52205001878842e-05 5.06275817372308e-06 -5.23990773184588e-07 -3.23098830748382e-06 2.05263854787414e-06 -1.04850860420664e-06 5.06275817372308e-06 2.90549386832487e-05 -3.1441268500942e-06 1.28415857882496e-05 1.636782692701e-05 -2.52637666324339e-06 -5.23990773184588e-07 -3.1441268500942e-06 7.1153970790317e-05 1336 1337 0 0 0 1393 1410 0 0 0 0 0 0 0 0 0 0 0 1061 0 15 67 0 0 2617 +1275 1312 0.995755310677485 0.00168480766028382 0.0920245765039646 -0.0178467816206467 -0.0156170024698178 0.988427501242379 0.150887985014067 -0.0311295920942458 -0.0907054049737054 -0.151684660433728 0.984258245227166 0.00242017111241481 8.91491480873259e-05 -4.86926089347985e-05 3.73698157153695e-06 -4.19790269678883e-06 -3.89063420574936e-06 -3.52652785628401e-06 -4.86926089347985e-05 7.42296845990018e-05 -4.00644849346332e-06 5.28378745536082e-06 3.16033790389826e-06 3.31118548546721e-05 3.73698157153695e-06 -4.00644849346332e-06 1.6558264347462e-05 2.63429508045061e-06 -4.04475049558108e-06 -4.95035339299289e-06 -4.19790269678883e-06 5.28378745536082e-06 2.63429508045061e-06 2.5713139467766e-05 -8.62120379011388e-07 3.48802457302369e-06 -3.89063420574936e-06 3.16033790389826e-06 -4.04475049558108e-06 -8.62120379011388e-07 2.58521572648829e-05 1.89652544253855e-07 -3.52652785628401e-06 3.31118548546721e-05 -4.95035339299289e-06 3.48802457302369e-06 1.89652544253855e-07 6.0184782562619e-05 1323 1323 0 0 0 1372 1385 0 0 0 0 0 0 0 0 0 0 0 1056 0 19 78 0 0 2720 +1275 1278 0.99999313136335 -0.00159087529533368 -0.00334758747713981 -0.0057447639984935 0.0015787000053821 0.999992141615036 -0.00363653880322187 -0.00453736301687653 0.00335334645025128 0.00363122898878999 0.999987784547199 -0.00511508346457038 5.97145146668105e-05 6.2153588240583e-06 -1.18754883326172e-06 -3.7635429829737e-06 -3.06295371952117e-06 9.29468400300866e-06 6.2153588240583e-06 5.96266423141798e-05 2.57884840463403e-06 1.00113515727574e-06 -4.08105707927967e-06 2.07224152497986e-05 -1.18754883326172e-06 2.57884840463403e-06 1.20089076492215e-05 1.9543619397676e-06 -3.16174858253759e-06 2.03359839675317e-06 -3.7635429829737e-06 1.00113515727574e-06 1.9543619397676e-06 2.54221905159961e-05 5.95647928451864e-06 2.98250664440902e-06 -3.06295371952117e-06 -4.08105707927967e-06 -3.16174858253759e-06 5.95647928451864e-06 2.82981111522798e-05 1.86047154107127e-07 9.29468400300866e-06 2.07224152497986e-05 2.03359839675317e-06 2.98250664440902e-06 1.86047154107127e-07 4.99575684605658e-05 1173 1173 0 0 0 1190 1244 0 0 0 0 0 0 0 0 0 0 0 812 0 11 25 0 0 3480 +1275 1310 0.996113541191422 0.00233455608904448 0.0880475036724663 -0.0229649876456059 -0.0151855365234687 0.989231360261096 0.145570310697189 -0.0380889430901574 -0.0867595097702854 -0.146341606263731 0.985422204814044 0.00211563162611664 0.000121346169499343 -6.21478367186382e-05 7.8453149588417e-06 -7.84391505234538e-06 2.136511929524e-06 1.19580389022723e-05 -6.21478367186382e-05 8.25886087973861e-05 -7.51983233893218e-06 8.18072456776863e-06 -7.47236160789522e-06 2.305000806431e-05 7.8453149588417e-06 -7.51983233893218e-06 1.69704054219155e-05 2.21706059644583e-06 -5.50272427858594e-07 -1.29517912255107e-06 -7.84391505234538e-06 8.18072456776863e-06 2.21706059644583e-06 2.88035374354502e-05 5.96846550538784e-06 5.27423880823626e-06 2.136511929524e-06 -7.47236160789522e-06 -5.50272427858594e-07 5.96846550538784e-06 3.81867621471342e-05 -5.30533912722785e-06 1.19580389022723e-05 2.305000806431e-05 -1.29517912255107e-06 5.27423880823626e-06 -5.30533912722785e-06 8.27515547585545e-05 1318 1318 0 0 0 1383 1398 0 0 0 0 0 0 0 0 0 0 0 1059 0 21 76 0 0 2556 +1275 1309 0.996352004964779 0.000431703262527029 0.085337540595901 -0.0181259248162666 -0.0131683642903473 0.988788026243955 0.14874418757888 -0.0309809297563441 -0.0843165249792746 -0.149325325343283 0.985186617259158 0.00803656460083966 7.03370830134542e-05 -2.99949267761083e-05 1.02539544417017e-05 -5.85469776695903e-07 6.39915026382058e-06 1.44508744332516e-05 -2.99949267761083e-05 6.44910562764336e-05 -6.06732912383771e-06 2.0877726192245e-06 -3.64859937764945e-06 2.72950612523908e-05 1.02539544417017e-05 -6.06732912383771e-06 1.51589233776684e-05 2.85701318023581e-06 -4.85436129317669e-06 1.09303975247231e-06 -5.85469776695903e-07 2.0877726192245e-06 2.85701318023581e-06 2.0307749769745e-05 -2.99138204797479e-06 4.69141999727415e-06 6.39915026382058e-06 -3.64859937764945e-06 -4.85436129317669e-06 -2.99138204797479e-06 2.76394623436266e-05 8.44118011444924e-06 1.44508744332516e-05 2.72950612523908e-05 1.09303975247231e-06 4.69141999727415e-06 8.44118011444924e-06 7.85087877344817e-05 1325 1325 0 0 0 1379 1393 0 0 0 0 0 0 0 0 0 0 0 960 0 20 74 0 0 2545 +1275 1308 0.996301840520051 0.00122198782708401 0.0859136154640736 -0.0167472738752285 -0.01415299327091 0.988574826749465 0.150065001578444 -0.0296698504019282 -0.0847486599176166 -0.150725972091791 0.984936214167777 0.00501061277021107 0.000115377585549744 -6.74835705492768e-05 1.57388233424502e-06 -4.87270886108433e-06 -6.99143317913808e-06 3.45423976871474e-05 -6.74835705492768e-05 9.54598256868998e-05 -4.08226394200948e-06 1.28491317364409e-05 2.67170318809815e-06 8.64809548380815e-06 1.57388233424502e-06 -4.08226394200948e-06 1.41283285391392e-05 1.17065608536276e-06 -1.57446302227992e-06 -7.50374772045522e-06 -4.87270886108433e-06 1.28491317364409e-05 1.17065608536276e-06 2.77754876349408e-05 -2.74842283234961e-06 8.25296269947545e-07 -6.99143317913808e-06 2.67170318809815e-06 -1.57446302227992e-06 -2.74842283234961e-06 2.8331576644326e-05 -1.03420441688732e-05 3.45423976871474e-05 8.64809548380815e-06 -7.50374772045522e-06 8.25296269947545e-07 -1.03420441688732e-05 7.72133483427975e-05 1242 1242 0 0 0 1290 1310 0 0 1 0 0 0 0 0 0 0 0 1065 0 5 37 0 0 2830 +1275 1311 0.996130658459675 0.000495447660317292 0.0878832510112715 -0.0193256058924671 -0.0137911306312365 0.988476359233261 0.150745785854427 -0.0331256046019007 -0.0867958293503002 -0.151374508318186 0.984658439378255 0.0037850745100085 0.000176426011975395 -0.000102789197291901 4.47107957558054e-06 -3.51090918697147e-06 4.47100250149943e-06 3.85578561060094e-05 -0.000102789197291901 0.000116134696391714 -4.48327716848863e-06 1.03453981871151e-05 1.2715456262992e-06 -5.47209819718239e-06 4.47107957558054e-06 -4.48327716848863e-06 1.8079857437094e-05 2.89172417935405e-06 -1.19676894669648e-06 -4.95393883062796e-06 -3.51090918697147e-06 1.03453981871151e-05 2.89172417935405e-06 2.87678993029347e-05 -3.72948743007741e-06 1.77932855976337e-07 4.47100250149943e-06 1.2715456262992e-06 -1.19676894669648e-06 -3.72948743007741e-06 2.86339379869514e-05 4.38052751185481e-06 3.85578561060094e-05 -5.47209819718239e-06 -4.95393883062796e-06 1.77932855976337e-07 4.38052751185481e-06 7.60073093949311e-05 1313 1313 0 0 0 1383 1412 0 0 0 0 0 0 0 0 0 0 0 964 0 10 50 0 0 2855 +1275 1317 0.996317938335741 0.00258282929558895 0.0856965270197627 -0.0178780598610986 -0.015251804193388 0.988942471610161 0.14751328860287 -0.0338546344337017 -0.0843679335960389 -0.148277162228095 0.985340517253968 0.0103371543522014 9.23459894156956e-05 -5.92303605248198e-05 -2.02244472882944e-06 -9.35374106888797e-07 -3.45098716802767e-07 2.01452787896811e-06 -5.92303605248198e-05 0.000103736434194513 2.88043758382771e-06 -2.01778763514109e-06 7.69069778459833e-06 2.75752732343533e-05 -2.02244472882944e-06 2.88043758382771e-06 1.71894617450862e-05 2.66075003346406e-06 -3.75655380453777e-06 -5.32740040666654e-06 -9.35374106888797e-07 -2.01778763514109e-06 2.66075003346406e-06 2.70561596221152e-05 -8.92228535248015e-06 5.1471750696526e-06 -3.45098716802767e-07 7.69069778459833e-06 -3.75655380453777e-06 -8.92228535248015e-06 2.63808139841009e-05 -6.67360088822925e-07 2.01452787896811e-06 2.75752732343533e-05 -5.32740040666654e-06 5.1471750696526e-06 -6.67360088822925e-07 6.93647119434505e-05 1309 1309 0 0 0 1377 1403 0 0 0 0 0 0 0 0 0 0 0 963 0 11 52 0 0 2843 +1275 1313 0.996516865153976 0.00180811453174866 0.0833718668708653 -0.0188906042764944 -0.014055480269064 0.989103467090988 0.146549564526792 -0.0324367045947328 -0.0821984241825788 -0.147210944261718 0.985683700256565 0.0108298754774316 9.79323047268102e-05 -5.66079107397003e-05 3.89551498700566e-06 -2.2945090516627e-06 1.22251930986978e-06 3.01376291121616e-05 -5.66079107397003e-05 7.88568265783248e-05 -2.65811036038449e-08 6.89280401817345e-06 9.19466522977052e-06 2.71069246254853e-06 3.89551498700566e-06 -2.65811036038449e-08 1.54753597374882e-05 2.7105391388911e-06 -1.24981771439273e-06 -6.25779221702909e-06 -2.2945090516627e-06 6.89280401817345e-06 2.7105391388911e-06 3.46870811625361e-05 5.10299946987691e-06 6.02669567210298e-06 1.22251930986978e-06 9.19466522977052e-06 -1.24981771439273e-06 5.10299946987691e-06 3.16040362816457e-05 -4.02684742992252e-07 3.01376291121616e-05 2.71069246254853e-06 -6.25779221702909e-06 6.02669567210298e-06 -4.02684742992252e-07 8.56257411238729e-05 1321 1321 0 0 0 1372 1385 0 0 0 0 0 0 0 0 0 0 0 1070 0 19 77 0 0 2856 +1275 1304 0.996786451509073 0.00241661047298933 0.0800682838692794 -0.017861962502731 -0.0136161652752145 0.990110544057673 0.139627041037964 -0.0326724767140916 -0.0789390279338915 -0.140268565757411 0.986961680780572 0.00195531966304712 0.000151607989672697 -8.22870234127674e-05 4.40090137652996e-06 -7.92122278637114e-06 -6.83299915847022e-06 2.55166075638508e-05 -8.22870234127674e-05 8.00550805887045e-05 -3.12409119447568e-06 6.98770190656448e-06 4.39751356857432e-06 9.07780521057716e-06 4.40090137652996e-06 -3.12409119447568e-06 1.47140636051076e-05 8.28373371309682e-07 -3.82241190097841e-06 -1.84527846545966e-06 -7.92122278637114e-06 6.98770190656448e-06 8.28373371309682e-07 2.67720423165312e-05 3.46739602853422e-06 -4.87733650694827e-07 -6.83299915847022e-06 4.39751356857432e-06 -3.82241190097841e-06 3.46739602853422e-06 2.70326333641154e-05 -1.77891006311291e-06 2.55166075638508e-05 9.07780521057716e-06 -1.84527846545966e-06 -4.87733650694827e-07 -1.77891006311291e-06 7.69810648001479e-05 1325 1325 0 0 0 1374 1386 0 0 0 0 0 0 0 0 0 0 0 1058 0 22 78 0 0 2718 +1275 1316 0.99619827931518 0.00258095884643879 0.0870765579298342 -0.0190197957057117 -0.0156589814080475 0.988585551748772 0.149844596748895 -0.031934522459184 -0.0856958843278789 -0.150638459647626 0.984867640794566 0.00579968118104218 7.85363458470332e-05 -5.07761576164734e-05 7.25826279521209e-06 -7.99341707531729e-06 3.93633599556873e-06 1.02638661070917e-05 -5.07761576164734e-05 7.55140732197664e-05 -3.97618115347884e-06 4.96772325765647e-06 -4.29143255280614e-06 1.77300255035683e-05 7.25826279521209e-06 -3.97618115347884e-06 1.8220234406617e-05 4.00500131359284e-06 -3.54583276715415e-06 -5.8399271932783e-06 -7.99341707531729e-06 4.96772325765647e-06 4.00500131359284e-06 3.06837508298226e-05 -6.34251094560259e-06 2.14199491016459e-06 3.93633599556873e-06 -4.29143255280614e-06 -3.54583276715415e-06 -6.34251094560259e-06 3.01690380209178e-05 -2.66105591786474e-07 1.02638661070917e-05 1.77300255035683e-05 -5.8399271932783e-06 2.14199491016459e-06 -2.66105591786474e-07 6.55894307147108e-05 1237 1237 0 0 0 1289 1310 0 0 2 0 0 0 0 0 0 0 0 1053 0 8 45 0 0 2851 +1275 1315 0.996536718190178 0.00207875518569111 0.0831279019080141 -0.0212233095729098 -0.0141599751680281 0.989328886331219 0.145009826473486 -0.0325645557619371 -0.0819393946889484 -0.145684705606003 0.985931996717066 0.00531035752614651 0.000156616425373391 -9.09935607704665e-05 5.01514534774591e-06 -2.74014430985177e-06 3.38394405345158e-06 4.83613547441847e-05 -9.09935607704665e-05 0.000112170274255634 -4.57025037586008e-06 6.2526033581354e-06 -1.82089525263119e-06 -1.26787534253325e-06 5.01514534774591e-06 -4.57025037586008e-06 1.63582763850288e-05 1.66344647191247e-06 -2.45756787568353e-06 -7.42662174171247e-06 -2.74014430985177e-06 6.2526033581354e-06 1.66344647191247e-06 2.78672664513075e-05 -7.68731652093291e-06 5.54080073750148e-06 3.38394405345158e-06 -1.82089525263119e-06 -2.45756787568353e-06 -7.68731652093291e-06 2.6700883433497e-05 -1.64350557226559e-06 4.83613547441847e-05 -1.26787534253325e-06 -7.42662174171247e-06 5.54080073750148e-06 -1.64350557226559e-06 9.43949150426376e-05 1221 1221 0 0 0 1276 1293 0 0 2 0 0 0 0 0 0 0 0 1063 0 8 46 0 0 2838 +1275 1318 0.996371810169232 0.00226959600849106 0.0850768172538588 -0.0205105263525162 -0.0148857151752876 0.988882409067703 0.147952683382816 -0.0352175761020158 -0.0837951751821575 -0.148682312231192 0.985328340527044 0.0136736137009933 8.65597480485525e-05 -4.28691708780957e-05 6.24897642910517e-06 -2.2334139577874e-06 5.42448443858785e-06 2.2854662744123e-05 -4.28691708780957e-05 6.68968805973234e-05 -3.7985974523166e-06 4.96824986872532e-06 1.10530787971656e-07 1.52447468850718e-05 6.24897642910517e-06 -3.7985974523166e-06 1.7505924371756e-05 9.23411880325438e-07 -2.42063012803978e-06 -2.17777072858246e-06 -2.2334139577874e-06 4.96824986872532e-06 9.23411880325438e-07 3.13535365208303e-05 -4.05872980176566e-06 5.24328026726458e-06 5.42448443858785e-06 1.10530787971656e-07 -2.42063012803978e-06 -4.05872980176566e-06 3.23638536246976e-05 -2.39382823667289e-07 2.2854662744123e-05 1.52447468850718e-05 -2.17777072858246e-06 5.24328026726458e-06 -2.39382823667289e-07 7.22033169308539e-05 1333 1333 0 0 0 1391 1405 0 0 0 0 0 0 0 0 0 0 0 1067 0 17 70 0 0 2845 +1275 1303 0.996734674100507 0.00211948877565899 0.0807186299009515 -0.0181369487947001 -0.0141027457200432 0.988859975833145 0.148179150889822 -0.0315751622128968 -0.0795053583660418 -0.14883365198302 0.985660916354344 0.00421782038273395 0.000136374964930782 -5.1500166725839e-05 1.03405863219301e-06 -6.29198649906815e-06 -9.04355625211247e-06 2.90755788773167e-05 -5.1500166725839e-05 6.65105731311827e-05 -1.00819266331231e-06 5.78268814499972e-06 -6.25162498545225e-07 2.81836434743645e-05 1.03405863219301e-06 -1.00819266331231e-06 1.4993366117122e-05 5.51939488554677e-07 -3.23195897056865e-06 -3.91153792765094e-06 -6.29198649906815e-06 5.78268814499972e-06 5.51939488554677e-07 2.63335518318754e-05 2.26745647218435e-06 8.16632308913523e-06 -9.04355625211247e-06 -6.25162498545225e-07 -3.23195897056865e-06 2.26745647218435e-06 2.82081242468536e-05 -5.39505335065654e-06 2.90755788773167e-05 2.81836434743645e-05 -3.91153792765094e-06 8.16632308913523e-06 -5.39505335065654e-06 8.95066199513022e-05 1321 1321 0 0 0 1373 1387 0 0 0 0 0 0 0 0 0 0 0 952 0 20 76 0 0 2799 +1275 1314 0.996601390488768 0.00229139580035148 0.0823432934800398 -0.0213000575785405 -0.0147320379438509 0.988455146426752 0.150795857239144 -0.0303153892241775 -0.0810471192200856 -0.151496445528447 0.985129530294556 0.0088105379789456 9.09833006333759e-05 -2.61425611183325e-05 1.13400352484046e-06 4.14063672743826e-06 -2.94533150994935e-06 4.38128571353861e-06 -2.61425611183325e-05 7.68304773477306e-05 -6.97052430892521e-06 7.79157976712865e-06 -5.22595859388635e-06 3.63284825872316e-05 1.13400352484046e-06 -6.97052430892521e-06 1.78308354061954e-05 -7.57092095581234e-07 -4.56754037540398e-06 -5.19042705152386e-06 4.14063672743826e-06 7.79157976712865e-06 -7.57092095581234e-07 2.96414900559917e-05 -9.4796293872527e-06 1.12518132135215e-05 -2.94533150994935e-06 -5.22595859388635e-06 -4.56754037540398e-06 -9.4796293872527e-06 2.48736301819787e-05 -3.34121531860701e-06 4.38128571353861e-06 3.63284825872316e-05 -5.19042705152386e-06 1.12518132135215e-05 -3.34121531860701e-06 7.5657902857761e-05 1315 1315 0 0 0 1384 1414 0 0 0 0 0 0 0 0 0 0 0 1064 0 9 51 0 0 2551 +1275 1305 0.996442406968133 0.00200528890531627 0.0842526463202135 -0.0194782460908658 -0.0145383883980469 0.988819290532694 0.148408375549382 -0.0315357033722081 -0.0830130402909103 -0.149105296642424 0.985330627583876 0.00258200799678115 8.23414589771792e-05 -3.37943639407813e-05 7.95501530059971e-06 -8.03687865297562e-06 -2.18575103376967e-06 3.22960880838517e-06 -3.37943639407813e-05 4.79197369519169e-05 -6.67784675761271e-06 4.93442101657376e-06 -2.93441262951226e-06 3.28020122219544e-05 7.95501530059971e-06 -6.67784675761271e-06 1.57740220437369e-05 7.29950154533702e-07 -3.05929012376445e-06 -2.3807627954096e-06 -8.03687865297562e-06 4.93442101657376e-06 7.29950154533702e-07 2.99095210220864e-05 3.75997252996439e-06 2.27435203572536e-06 -2.18575103376967e-06 -2.93441262951226e-06 -3.05929012376445e-06 3.75997252996439e-06 3.02432658624334e-05 -5.6146124499144e-06 3.22960880838517e-06 3.28020122219544e-05 -2.3807627954096e-06 2.27435203572536e-06 -5.6146124499144e-06 6.25363144803388e-05 1227 1227 0 0 0 1280 1297 0 0 0 0 0 0 0 0 0 0 0 966 0 7 46 0 0 2702 +1275 1301 0.996298300784746 0.00228656385448784 0.0859329243024306 -0.0210599978045475 -0.0150133002808138 0.98891090888806 0.147749162761993 -0.0363634892999223 -0.0846421683802231 -0.148492376598703 0.985284587022431 0.0147636655155254 0.000107878933201058 -6.91604767890538e-05 3.14182015160461e-06 -1.35685733108789e-05 -7.3841666469862e-06 1.28215798285632e-05 -6.91604767890538e-05 9.92259496536358e-05 2.28921012933934e-07 1.0292908308294e-05 9.9350876799987e-08 4.89288799879663e-06 3.14182015160461e-06 2.28921012933934e-07 1.66020967839474e-05 2.49818396358563e-06 6.58816633825669e-07 -1.10859902412425e-05 -1.35685733108789e-05 1.0292908308294e-05 2.49818396358563e-06 3.07452750749425e-05 1.20315564405037e-05 -1.37009218748331e-05 -7.3841666469862e-06 9.9350876799987e-08 6.58816633825669e-07 1.20315564405037e-05 4.02987994041973e-05 -2.72805398324091e-05 1.28215798285632e-05 4.89288799879663e-06 -1.10859902412425e-05 -1.37009218748331e-05 -2.72805398324091e-05 0.000111882144831702 1327 1327 0 0 0 1389 1403 0 0 0 0 0 0 0 0 0 0 0 1052 0 19 73 0 0 2852 +1276 1279 0.999996208543287 0.000775120750298879 -0.00264236387997247 -0.00861937080599053 -0.000749555355845259 0.999953036054362 0.0096624972151041 -0.00487303858676543 0.00264972938622999 -0.00966047998216583 0.99994982577162 -0.00675615756204885 5.4256529554059e-05 3.29037612222116e-06 -1.2501646290294e-06 6.47344287963625e-06 4.0275616256909e-06 1.78358117937023e-05 3.29037612222116e-06 4.95549804949177e-05 -1.43909561275955e-06 2.73457782702147e-06 -2.21371955010104e-06 2.98707067440699e-05 -1.2501646290294e-06 -1.43909561275955e-06 1.2435169008985e-05 1.16710277486034e-06 -4.72372850652981e-06 -3.22159443782749e-06 6.47344287963625e-06 2.73457782702147e-06 1.16710277486034e-06 2.3014414948617e-05 -2.59374043844349e-06 7.70372387428652e-06 4.0275616256909e-06 -2.21371955010104e-06 -4.72372850652981e-06 -2.59374043844349e-06 2.02817848738282e-05 6.95793796974811e-07 1.78358117937023e-05 2.98707067440699e-05 -3.22159443782749e-06 7.70372387428652e-06 6.95793796974811e-07 4.91603931303728e-05 1214 1214 0 0 0 1231 1292 0 0 0 0 0 0 0 0 0 0 0 787 0 0 0 0 0 3471 +1275 1302 0.99645322109962 0.00139011483042605 0.0841370652028624 -0.020287591907671 -0.0141654052140878 0.988365849001186 0.151434110501188 -0.0312049092773953 -0.0829476910788551 -0.152088842815387 0.984880025401959 0.00311920924525172 0.000101663014321166 -2.10007232784307e-05 7.91182416783061e-06 2.43618078791936e-06 1.39654254697444e-06 1.02692621059411e-05 -2.10007232784307e-05 7.55855828832734e-05 -3.94996213034403e-06 3.12539898522394e-06 -7.66198814399035e-06 1.17330861376231e-05 7.91182416783061e-06 -3.94996213034403e-06 1.92501578365484e-05 -1.47979836023443e-06 -3.52594215227932e-07 -4.72697758689913e-06 2.43618078791936e-06 3.12539898522394e-06 -1.47979836023443e-06 2.50256380601327e-05 -2.88283315231571e-06 -2.30843226211179e-06 1.39654254697444e-06 -7.66198814399035e-06 -3.52594215227932e-07 -2.88283315231571e-06 3.14340507216116e-05 3.94746100415549e-06 1.02692621059411e-05 1.17330861376231e-05 -4.72697758689913e-06 -2.30843226211179e-06 3.94746100415549e-06 5.32421748217388e-05 1316 1316 0 0 0 1384 1416 0 0 1 0 0 0 0 0 0 0 0 961 0 8 48 0 0 2556 +1276 1311 0.996216188168465 0.00120364401935201 0.0869014250295601 -0.0261884993936217 -0.0147231032828598 0.987788990599516 0.155100419986893 -0.0342216165185729 -0.0856535852186925 -0.155793007838809 0.984069104305039 0.00890150783143928 7.29156550368583e-05 -3.67132819113541e-05 1.27049380080938e-06 -2.07967167414976e-06 -2.2710971226694e-06 2.10320181356386e-05 -3.67132819113541e-05 8.73119556351608e-05 -3.74645332326426e-06 7.59986593736428e-06 -3.598437997186e-06 3.34934074547174e-06 1.27049380080938e-06 -3.74645332326426e-06 1.32832370098708e-05 2.408742158743e-06 -6.18188344426188e-06 -4.68283093385408e-06 -2.07967167414976e-06 7.59986593736428e-06 2.408742158743e-06 3.46444324355347e-05 2.85909722923813e-06 4.90311799077036e-06 -2.2710971226694e-06 -3.598437997186e-06 -6.18188344426188e-06 2.85909722923813e-06 3.29065139470383e-05 1.06843571953821e-05 2.10320181356386e-05 3.34934074547174e-06 -4.68283093385408e-06 4.90311799077036e-06 1.06843571953821e-05 6.13319543688869e-05 1293 1293 0 0 0 1355 1360 0 0 0 0 0 0 0 0 0 0 0 962 0 16 66 0 0 2847 +1276 1278 0.999999171956941 0.00113333484965428 0.000609620826219188 -0.00415788956418147 -0.00113593294413208 0.999990202030266 0.00427849270363789 -0.00453822891078352 -0.000604765888287759 -0.00427918164924164 0.999990661387712 0.000381267796312567 5.50934681042639e-05 4.30296407850089e-06 4.13902558962655e-06 -6.30030544351162e-06 -4.99714348886986e-06 1.95974318774373e-05 4.30296407850089e-06 6.69361110039407e-05 7.19920049603315e-06 3.77258432956348e-06 9.33854257088693e-06 2.04357729209232e-05 4.13902558962655e-06 7.19920049603315e-06 1.47678856530631e-05 5.81489233615092e-07 2.13346333755037e-06 -1.08287141593154e-06 -6.30030544351162e-06 3.77258432956348e-06 5.81489233615092e-07 2.45163136993216e-05 -5.12117465310507e-07 5.47607503169951e-06 -4.99714348886986e-06 9.33854257088693e-06 2.13346333755037e-06 -5.12117465310507e-07 3.20211109609667e-05 -2.22398903938719e-06 1.95974318774373e-05 2.04357729209232e-05 -1.08287141593154e-06 5.47607503169951e-06 -2.22398903938719e-06 5.35161695131794e-05 1190 1204 0 0 0 1203 1268 0 0 4 0 0 0 0 0 0 0 0 818 0 0 0 0 0 3533 +1276 1308 0.996301357332969 0.00243500346928983 0.0858933998313546 -0.0214867041286953 -0.0154725160506075 0.988343614092797 0.151451318016886 -0.0290428006273469 -0.084523408731239 -0.152220140717622 0.984725759862287 0.00413021223434222 8.30850395446894e-05 -2.04102351968191e-05 5.40167440343988e-06 3.8927263479253e-06 2.76646378511471e-06 2.56363204884981e-05 -2.04102351968191e-05 6.70410987951091e-05 -5.46738533336812e-06 5.27137195329074e-06 -5.20103339705131e-06 2.69301056448831e-05 5.40167440343988e-06 -5.46738533336812e-06 1.5507986234744e-05 1.47533054955926e-06 -3.92187076679868e-06 -4.3925900044551e-06 3.8927263479253e-06 5.27137195329074e-06 1.47533054955926e-06 3.15330961840211e-05 3.03522211496204e-06 6.3446396220111e-06 2.76646378511471e-06 -5.20103339705131e-06 -3.92187076679868e-06 3.03522211496204e-06 3.36977790183522e-05 9.703520315257e-06 2.56363204884981e-05 2.69301056448831e-05 -4.3925900044551e-06 6.3446396220111e-06 9.703520315257e-06 8.21981184064224e-05 1225 1225 0 0 0 1279 1291 0 0 0 0 0 0 0 0 0 0 0 1069 0 7 43 0 0 2852 +1276 1316 0.99595264212245 0.00281692682942731 0.089835402668153 -0.0292165042996282 -0.0168958587481944 0.987557486698974 0.156348138530545 -0.0350049935960601 -0.0882772032093938 -0.157233187934492 0.983608082523463 0.00486751058174206 0.000134727800553657 -6.87786395192255e-05 7.66330995983648e-06 -3.19853472654707e-06 3.9456504347208e-06 2.38968893812162e-05 -6.87786395192255e-05 7.94978620198629e-05 -7.09179369847944e-06 3.31170387250385e-06 -4.33322160518325e-06 1.09388852285366e-05 7.66330995983648e-06 -7.09179369847944e-06 1.42494743347584e-05 -3.09372789416562e-07 -7.62553573623543e-06 -3.58557978722943e-06 -3.19853472654707e-06 3.31170387250385e-06 -3.09372789416562e-07 3.7711191808005e-05 4.04020405456274e-06 8.62460835852382e-06 3.9456504347208e-06 -4.33322160518325e-06 -7.62553573623543e-06 4.04020405456274e-06 3.23286148130255e-05 2.38672809071936e-06 2.38968893812162e-05 1.09388852285366e-05 -3.58557978722943e-06 8.62460835852382e-06 2.38672809071936e-06 7.53065717140931e-05 1202 1202 0 0 0 1266 1274 0 0 0 0 0 0 0 0 0 0 0 1056 0 15 58 0 0 2841 +1276 1318 0.996345022071123 0.00364025558264906 0.0853425189069664 -0.0279393174464751 -0.0165791236694821 0.988333743927703 0.151398623746059 -0.0383798602388025 -0.083795761542246 -0.152260169293029 0.984781758154777 0.0190432017894455 7.92363648716492e-05 -3.54799797496598e-05 4.10874674122199e-06 -8.31313483010771e-07 3.60942804027351e-06 1.79990761355454e-05 -3.54799797496598e-05 8.37822819584092e-05 -5.43219988302468e-08 2.8683752146464e-06 9.09870145403597e-06 1.66850747324035e-06 4.10874674122199e-06 -5.43219988302468e-08 1.61403619468241e-05 -8.00608036920949e-07 -3.45041118595958e-06 -2.55940107389112e-06 -8.31313483010771e-07 2.8683752146464e-06 -8.00608036920949e-07 4.44784858619795e-05 1.23368780020286e-05 -3.85552891282489e-06 3.60942804027351e-06 9.09870145403597e-06 -3.45041118595958e-06 1.23368780020286e-05 4.68103243899697e-05 4.85825813605439e-06 1.79990761355454e-05 1.66850747324035e-06 -2.55940107389112e-06 -3.85552891282489e-06 4.85825813605439e-06 6.93830940875205e-05 1315 1318 0 0 0 1380 1397 0 0 0 0 0 0 0 0 0 0 0 1068 0 25 79 0 0 2866 +1276 1280 0.999985427759684 0.000202370679984161 -0.005394748779092 -0.0129322423205688 -0.00014952770281939 0.999952027762096 0.00979386624058489 -0.00381431115795465 0.00539647197229092 -0.00979291685762019 0.999937486480866 -0.00240449247347849 6.80764988008055e-05 8.32753743252947e-06 3.1646860530803e-06 -6.55007839463229e-07 -5.30053418699188e-06 2.09535164587311e-05 8.32753743252947e-06 4.35804467182401e-05 7.86911828640932e-07 6.86239782584462e-06 3.59724616340747e-06 2.48737102062067e-05 3.1646860530803e-06 7.86911828640932e-07 1.17947705074973e-05 1.69747894486486e-06 -4.71745444386429e-06 -1.11870890667112e-07 -6.55007839463229e-07 6.86239782584462e-06 1.69747894486486e-06 2.4396038385248e-05 -1.20383494566102e-06 8.67893122402856e-06 -5.30053418699188e-06 3.59724616340747e-06 -4.71745444386429e-06 -1.20383494566102e-06 2.3518763445883e-05 6.68030469444764e-06 2.09535164587311e-05 2.48737102062067e-05 -1.11870890667112e-07 8.67893122402856e-06 6.68030469444764e-06 5.73986027863067e-05 1234 1234 0 0 0 1259 1307 0 0 0 0 0 0 0 0 0 0 0 789 0 0 4 0 0 3501 +1276 1309 0.996314300263032 0.00190366591525658 0.0857565807822812 -0.0238650517357246 -0.015096311701414 0.988040321586368 0.153454958513957 -0.0307277287817427 -0.0844388326802224 -0.154183977687663 0.984427439967015 0.0069341374776089 8.83904323322259e-05 -3.86111923382231e-05 4.27257731457575e-06 -2.94223582792454e-06 -7.44274945204642e-06 2.04525456575823e-05 -3.86111923382231e-05 7.51800832435095e-05 -3.19830003937507e-06 8.59163454660688e-06 4.00677396991477e-06 1.50921755111598e-05 4.27257731457575e-06 -3.19830003937507e-06 1.38901174661673e-05 3.37567548028241e-06 -5.30703298007117e-06 -3.75799627777977e-06 -2.94223582792454e-06 8.59163454660688e-06 3.37567548028241e-06 3.20295309687787e-05 3.43218627526454e-06 -3.19453851971428e-06 -7.44274945204642e-06 4.00677396991477e-06 -5.30703298007117e-06 3.43218627526454e-06 3.4186988056794e-05 -2.4045160925472e-06 2.04525456575823e-05 1.50921755111598e-05 -3.75799627777977e-06 -3.19453851971428e-06 -2.4045160925472e-06 8.20771264730619e-05 1328 1330 0 0 0 1385 1399 0 0 0 0 0 0 0 0 0 0 0 969 0 12 69 0 0 2573 +1276 1317 0.996243547149923 0.00372314370378749 0.0865155070672357 -0.0267013226795058 -0.0168524907576601 0.988309211199041 0.151528533994068 -0.0364362266721096 -0.0849399100388207 -0.152417325983923 0.984659418490733 0.00860741176768271 0.00010822454407375 -3.41743225947509e-05 2.07860637121169e-06 5.89805681989176e-06 -4.00956194841732e-06 2.16334250745333e-05 -3.41743225947509e-05 8.56184325764976e-05 -3.71355681218045e-06 3.04121955117821e-06 2.9039386243954e-06 2.46578783101508e-05 2.07860637121169e-06 -3.71355681218045e-06 1.7517064088586e-05 2.45400360392367e-06 -3.43056209372163e-06 -1.71318691507026e-06 5.89805681989176e-06 3.04121955117821e-06 2.45400360392367e-06 3.74174064046469e-05 2.87596400910181e-06 2.63342643606323e-06 -4.00956194841732e-06 2.9039386243954e-06 -3.43056209372163e-06 2.87596400910181e-06 3.73646901692059e-05 2.02843048001135e-06 2.16334250745333e-05 2.46578783101508e-05 -1.71318691507026e-06 2.63342643606323e-06 2.02843048001135e-06 6.80169730647135e-05 1284 1284 0 0 0 1345 1348 0 0 0 0 0 0 0 0 0 0 0 965 0 20 78 0 0 2861 +1276 1313 0.996738547108409 0.00277541167052536 0.0806508883911246 -0.0276706393240044 -0.0150337356353579 0.988298867365481 0.151787138970841 -0.0357212251687109 -0.079285909852033 -0.152504576502367 0.98511730197209 0.0132135711207863 7.75786764324763e-05 -3.04882503776321e-05 1.25419891903624e-06 -2.40268407234735e-06 -1.19064659772469e-05 8.90779101838528e-06 -3.04882503776321e-05 6.41030831061211e-05 -1.14420562955888e-06 -2.22900613649728e-06 -3.91071822512036e-07 1.8776648223584e-05 1.25419891903624e-06 -1.14420562955888e-06 1.39981760071596e-05 -5.30067205038394e-07 -3.09025611009918e-06 -6.25490531324873e-06 -2.40268407234735e-06 -2.22900613649728e-06 -5.30067205038394e-07 3.96300268854851e-05 1.397088197354e-05 5.03108269254818e-06 -1.19064659772469e-05 -3.91071822512036e-07 -3.09025611009918e-06 1.397088197354e-05 3.90461401189376e-05 -3.54534865746081e-07 8.90779101838528e-06 1.8776648223584e-05 -6.25490531324873e-06 5.03108269254818e-06 -3.54534865746081e-07 6.27291828455193e-05 1316 1316 0 0 0 1372 1375 0 0 0 0 0 0 0 0 0 0 0 1070 0 22 85 0 0 2819 +1276 1306 0.996618204845017 0.00322446564411893 0.0821082005210546 -0.0240492545502051 -0.0158090690065125 0.988086523349031 0.153085256354661 -0.0312404688267039 -0.0806363882415572 -0.15386560758446 0.984795992931542 0.00811938583517789 8.75581124606237e-05 -3.37469505357331e-05 4.15487315096362e-06 4.93833675456433e-06 6.70225818039589e-06 1.18498991697823e-05 -3.37469505357331e-05 7.63187106623182e-05 -4.3037796240017e-06 3.11825874651549e-06 -8.00911622804115e-06 1.61465164209975e-05 4.15487315096362e-06 -4.3037796240017e-06 1.65119348133133e-05 4.80091199036149e-07 -2.26973044197283e-06 -3.41827769275985e-06 4.93833675456433e-06 3.11825874651549e-06 4.80091199036149e-07 3.29409345478269e-05 8.04820461448611e-06 1.0260702573648e-05 6.70225818039589e-06 -8.00911622804115e-06 -2.26973044197283e-06 8.04820461448611e-06 3.56316788619447e-05 7.063089848887e-06 1.18498991697823e-05 1.61465164209975e-05 -3.41827769275985e-06 1.0260702573648e-05 7.063089848887e-06 6.89809355776164e-05 1326 1327 0 0 0 1383 1392 0 0 0 0 0 0 0 0 0 0 0 1055 0 14 73 0 0 2852 +1276 1314 0.996309579183212 0.00230950743702666 0.0858014487241858 -0.0294997510495606 -0.0158819527094863 0.987336638145326 0.157842093733003 -0.0329320528999347 -0.084350376441984 -0.158622284535569 0.983729629950635 0.00907062104564318 6.92444206510776e-05 -9.79113191864518e-07 1.72161081020141e-06 1.05056242026893e-06 -4.26085750285926e-06 9.88197603147704e-06 -9.79113191864518e-07 6.75227989120508e-05 -6.36037794287299e-06 1.34156907332664e-05 -6.16573943729973e-07 3.39171785183696e-05 1.72161081020141e-06 -6.36037794287299e-06 1.76284131396599e-05 8.07409922158678e-07 -4.4807287812568e-06 -2.17074830735099e-06 1.05056242026893e-06 1.34156907332664e-05 8.07409922158678e-07 4.30150707168729e-05 4.35143001313067e-06 9.10941176638942e-06 -4.26085750285926e-06 -6.16573943729973e-07 -4.4807287812568e-06 4.35143001313067e-06 3.29007987326583e-05 7.93243530698589e-06 9.88197603147704e-06 3.39171785183696e-05 -2.17074830735099e-06 9.10941176638942e-06 7.93243530698589e-06 6.01972290718977e-05 1290 1290 0 0 0 1356 1360 0 0 0 0 0 0 0 0 0 0 0 1061 0 19 69 0 0 2569 +1276 1307 0.996812045107262 0.0030310704250002 0.0797280335964531 -0.0254240082400219 -0.0149405208925567 0.98869288970895 0.14920841355106 -0.0324085015900056 -0.0783742787178137 -0.149923922210713 0.985586267144799 0.0131720114176547 0.00010608560955335 -4.16047975983016e-05 -9.9661780636333e-07 1.51423022474723e-06 1.65569832613601e-07 3.11289723720072e-05 -4.16047975983016e-05 7.93079729311252e-05 8.07868199907623e-07 4.78240168652351e-06 -5.9548831695651e-07 6.97285400107694e-06 -9.9661780636333e-07 8.07868199907623e-07 1.52825358306592e-05 8.42150487909809e-07 -4.59819088244567e-06 -2.85205837522276e-06 1.51423022474723e-06 4.78240168652351e-06 8.42150487909809e-07 3.59664616815371e-05 1.26784792549277e-05 -5.7097354266298e-06 1.65569832613601e-07 -5.9548831695651e-07 -4.59819088244567e-06 1.26784792549277e-05 4.13296044597325e-05 -5.75857616155277e-06 3.11289723720072e-05 6.97285400107694e-06 -2.85205837522276e-06 -5.7097354266298e-06 -5.75857616155277e-06 9.176712406092e-05 1330 1338 0 0 0 1389 1409 0 0 1 0 0 0 0 0 0 0 0 1063 0 17 66 0 0 2625 +1276 1305 0.996403708688328 0.00300069065188553 0.0846796620668596 -0.0248001709207972 -0.0161033752645589 0.987864909403244 0.15447848418084 -0.0318512490579261 -0.0831885245525767 -0.155286562925879 0.984360580660071 -0.00107840246939217 7.75899431595045e-05 -3.73734703284151e-05 2.75653931038484e-06 -1.58150356793603e-06 -7.41596078788048e-06 1.84893211257523e-05 -3.73734703284151e-05 7.80221040269117e-05 -2.73464067096018e-06 4.59258990484577e-06 -1.24148342459169e-06 2.29283877589398e-05 2.75653931038484e-06 -2.73464067096018e-06 1.4135524478351e-05 8.52907872861912e-08 -6.05788137060873e-06 -3.0181689443987e-06 -1.58150356793603e-06 4.59258990484577e-06 8.52907872861912e-08 3.035634184304e-05 5.45675240364153e-06 8.4210336849133e-06 -7.41596078788048e-06 -1.24148342459169e-06 -6.05788137060873e-06 5.45675240364153e-06 3.30839612317399e-05 -1.04337377066003e-06 1.84893211257523e-05 2.29283877589398e-05 -3.0181689443987e-06 8.4210336849133e-06 -1.04337377066003e-06 8.43069848590789e-05 1207 1207 0 0 0 1266 1275 0 0 0 0 0 0 0 0 0 0 0 965 0 10 50 0 0 2766 +1276 1312 0.995984292231899 0.00291043435662051 0.0894808303447163 -0.0281344027652007 -0.0168335763746518 0.987732926674863 0.155242701177053 -0.0363594605478747 -0.0879313387465633 -0.15612557424767 0.983815472907431 0.00166482786716816 0.000127263750654256 -3.27385769473999e-05 3.61282780714156e-06 8.26919468871661e-06 -8.18162770304627e-06 3.91545941009734e-05 -3.27385769473999e-05 0.000106399566862303 -2.75358067456587e-06 1.63520480979047e-05 8.79188641640373e-06 2.12618913356643e-05 3.61282780714156e-06 -2.75358067456587e-06 1.59619999100146e-05 1.2180024467923e-07 -5.83381802084521e-06 -2.65309385713743e-06 8.26919468871661e-06 1.63520480979047e-05 1.2180024467923e-07 3.67464769041389e-05 9.21424045044627e-06 1.08389997215902e-05 -8.18162770304627e-06 8.79188641640373e-06 -5.83381802084521e-06 9.21424045044627e-06 3.37456370790254e-05 2.16648941219833e-06 3.91545941009734e-05 2.12618913356643e-05 -2.65309385713743e-06 1.08389997215902e-05 2.16648941219833e-06 8.37226340360625e-05 1309 1310 0 0 0 1371 1380 0 0 0 0 0 0 0 0 0 0 0 1065 0 21 86 0 0 2771 +1276 1315 0.996014358187371 0.00251873256771766 0.0891574689571853 -0.0281682102710055 -0.0163436845806611 0.987830154324849 0.154675370311093 -0.0345082591426189 -0.0876828504265628 -0.155516051238444 0.983934182528626 0.00562177323979114 9.72398605186288e-05 -3.78311961072752e-05 -1.62090790595741e-06 4.93874288635374e-06 -4.17540592967653e-06 2.24359105971411e-05 -3.78311961072752e-05 8.14204948909912e-05 -2.33921707358824e-06 9.21756840568245e-06 3.23645208235445e-06 1.89440498052207e-05 -1.62090790595741e-06 -2.33921707358824e-06 1.52698430542472e-05 1.22855347106543e-06 -6.22652403393244e-06 -7.17570677870112e-06 4.93874288635374e-06 9.21756840568245e-06 1.22855347106543e-06 3.52950013074232e-05 -7.86810321093725e-07 1.35172793821116e-05 -4.17540592967653e-06 3.23645208235445e-06 -6.22652403393244e-06 -7.86810321093725e-07 2.62539344202053e-05 -4.57779414813819e-07 2.24359105971411e-05 1.89440498052207e-05 -7.17570677870112e-06 1.35172793821116e-05 -4.57779414813819e-07 7.62816981895052e-05 1196 1196 0 0 0 1258 1265 0 0 0 0 0 0 0 0 0 0 0 1069 0 14 57 0 0 2850 +1276 1303 0.996608368633794 0.0033527063883724 0.0822223748681665 -0.0247028292418476 -0.0160900042524096 0.987823318596258 0.154745607371041 -0.0329182781196678 -0.0807023626187324 -0.155543725676571 0.984526931104684 0.00753534062226914 7.06717112312098e-05 -2.39104384527619e-05 1.99182003992879e-06 -5.42968527163285e-07 -9.27462542186891e-06 6.79431099089676e-06 -2.39104384527619e-05 7.99984625798672e-05 -5.81713273740732e-06 9.22827345888442e-06 -3.49808564107269e-06 3.72319745434321e-05 1.99182003992879e-06 -5.81713273740732e-06 1.58524943914929e-05 7.87585520656609e-07 -4.93693750852361e-06 -7.68829982997021e-06 -5.42968527163285e-07 9.22827345888442e-06 7.87585520656609e-07 3.36836571628901e-05 5.91287572459635e-06 2.88513701112694e-06 -9.27462542186891e-06 -3.49808564107269e-06 -4.93693750852361e-06 5.91287572459635e-06 3.43955701154347e-05 -6.01570524617352e-06 6.79431099089676e-06 3.72319745434321e-05 -7.68829982997021e-06 2.88513701112694e-06 -6.01570524617352e-06 7.63295018033736e-05 1320 1320 0 0 0 1378 1386 0 0 0 0 0 0 0 0 0 0 0 957 0 16 77 0 0 2826 +1277 1279 0.99999864725044 0.00152919432288191 0.000605856429150079 -0.00367081966083847 -0.00152761354837494 0.999995450368013 -0.0026010844125715 -0.00723478545767831 -0.00060983123624333 0.00260015537946616 0.999996433642573 0.00274641089866031 5.58672766742627e-05 -2.67543262176813e-07 1.23723292405404e-06 -5.23057793790685e-06 -6.01890188246626e-06 1.25952311135078e-05 -2.67543262176813e-07 4.4879407684685e-05 3.55390930704487e-06 2.96318932969444e-06 2.94942646451539e-06 1.46085302191345e-05 1.23723292405404e-06 3.55390930704487e-06 1.01626784185208e-05 2.29085701157628e-06 -5.17482384734398e-06 2.60335006150147e-06 -5.23057793790685e-06 2.96318932969444e-06 2.29085701157628e-06 2.18640226808608e-05 4.19972931841134e-06 1.51040319276644e-06 -6.01890188246626e-06 2.94942646451539e-06 -5.17482384734398e-06 4.19972931841134e-06 2.16901876480284e-05 -2.20904857664766e-06 1.25952311135078e-05 1.46085302191345e-05 2.60335006150147e-06 1.51040319276644e-06 -2.20904857664766e-06 4.14590926756445e-05 1210 1210 0 0 0 1231 1289 0 0 0 0 0 0 0 0 0 0 0 788 0 0 0 0 0 3434 +1276 1304 0.996618593980451 0.00300406673528981 0.0821118366344319 -0.024598561881118 -0.0154728693847551 0.988314400399222 0.151641802536533 -0.0332157421097819 -0.080696768494358 -0.152399545755808 0.985018989668723 0.000390379339822515 6.91093366937424e-05 -3.06037486121415e-05 3.83283663179183e-06 5.42863122582871e-08 -9.54151231215761e-07 2.34798461953893e-06 -3.06037486121415e-05 9.31898001866151e-05 6.84594086514031e-07 4.34151121645775e-06 -2.6424714374946e-06 3.06411384073144e-05 3.83283663179183e-06 6.84594086514031e-07 1.90732880785672e-05 -2.47837642368048e-06 -4.40793490171996e-06 -2.37295230276534e-06 5.42863122582871e-08 4.34151121645775e-06 -2.47837642368048e-06 3.32383550234325e-05 3.91634240751287e-06 6.88126398812826e-06 -9.54151231215761e-07 -2.6424714374946e-06 -4.40793490171996e-06 3.91634240751287e-06 3.36777125155792e-05 4.23736779434231e-06 2.34798461953893e-06 3.06411384073144e-05 -2.37295230276534e-06 6.88126398812826e-06 4.23736779434231e-06 6.46846688501973e-05 1326 1328 0 0 0 1382 1394 0 0 0 0 0 0 0 0 0 0 0 1059 0 14 73 0 0 2771 +1277 1281 0.999977298466895 0.00105224275982324 -0.00665547413976949 -0.00818093649092049 -0.0010609824147808 0.999998579423485 -0.00130975849931001 -0.00861296444593106 0.00665408650126122 0.0013167901068084 0.999976994333694 0.00388789920875906 7.49627429180125e-05 -8.56681899472487e-08 4.06553034751538e-06 -3.88153422001456e-06 -4.03032006407993e-06 1.2859714885899e-05 -8.56681899472487e-08 3.60134402680397e-05 1.17326144904911e-06 4.31465528280249e-06 1.09104188989955e-06 1.95795622907519e-05 4.06553034751538e-06 1.17326144904911e-06 1.19699829062545e-05 2.48875934958142e-06 -5.28442218728705e-06 -2.02001859039503e-06 -3.88153422001456e-06 4.31465528280249e-06 2.48875934958142e-06 2.62915654807477e-05 4.86716812558434e-06 1.0951282127041e-06 -4.03032006407993e-06 1.09104188989955e-06 -5.28442218728705e-06 4.86716812558434e-06 2.17672265634605e-05 -2.63884858115334e-06 1.2859714885899e-05 1.95795622907519e-05 -2.02001859039503e-06 1.0951282127041e-06 -2.63884858115334e-06 4.55902319633711e-05 1213 1214 0 0 0 1235 1288 0 0 0 0 0 0 0 0 0 0 0 786 0 0 0 0 0 3451 +1276 1302 0.996713813227534 0.00276211752233602 0.0809564403134278 -0.0284621422094147 -0.0154334947070097 0.987586194958557 0.156317992465381 -0.0337248648141648 -0.0795196941804827 -0.157053743139318 0.984383431394176 0.00623525632129215 8.88101137751619e-05 -9.81030601876259e-06 1.22482033659746e-06 7.23096462216475e-06 -9.39604886946928e-06 1.11264686140314e-05 -9.81030601876259e-06 7.10492629511762e-05 -7.28851810763218e-06 1.39705322324762e-05 -4.66721800475398e-06 1.78449496282996e-05 1.22482033659746e-06 -7.28851810763218e-06 1.91099171296595e-05 -3.30389552903116e-06 -1.91057884832981e-06 -7.54246842161566e-06 7.23096462216475e-06 1.39705322324762e-05 -3.30389552903116e-06 3.61852115898741e-05 3.26064958145929e-06 3.28109005905251e-06 -9.39604886946928e-06 -4.66721800475398e-06 -1.91057884832981e-06 3.26064958145929e-06 3.65837667504587e-05 -4.28843327308684e-07 1.11264686140314e-05 1.78449496282996e-05 -7.54246842161566e-06 3.28109005905251e-06 -4.28843327308684e-07 6.28554390629587e-05 1284 1284 0 0 0 1352 1356 0 0 0 0 0 0 0 0 0 0 0 961 0 17 66 0 0 2556 +1277 1308 0.996368588370634 0.00219612986208665 0.0851164679832197 -0.0190737507566831 -0.0146658096237962 0.989152905563917 0.146155545370469 -0.0308284027607689 -0.0838722250592422 -0.146873096338607 0.985593092221898 0.00546586302274514 7.20290680168847e-05 -3.17854205341579e-05 5.08309665101828e-06 2.39993052316051e-06 -2.4458768143431e-06 -1.81570234026535e-05 -3.17854205341579e-05 7.04810712824728e-05 -2.97536734827599e-06 1.32194949194547e-05 2.82447574043102e-06 2.65097335659275e-05 5.08309665101828e-06 -2.97536734827599e-06 1.39364369940171e-05 1.14189338401124e-06 -3.94609035250193e-06 -3.74895910651537e-06 2.39993052316051e-06 1.32194949194547e-05 1.14189338401124e-06 3.39795882216547e-05 3.34256794675497e-06 1.31760395219834e-06 -2.4458768143431e-06 2.82447574043102e-06 -3.94609035250193e-06 3.34256794675497e-06 2.38141105230883e-05 1.36810441159518e-06 -1.81570234026535e-05 2.65097335659275e-05 -3.74895910651537e-06 1.31760395219834e-06 1.36810441159518e-06 6.94979346668276e-05 1222 1222 0 0 0 1283 1297 0 0 0 0 0 0 0 0 0 0 0 1075 0 7 43 0 0 2769 +1277 1310 0.995869560560494 0.00286571972352199 0.090750239666428 -0.0193066840759886 -0.0163032693856484 0.988900778573707 0.147680240870791 -0.0337671728325611 -0.0893197724828432 -0.148549782183556 0.984862904396765 0.00260592282507022 4.68777910835775e-05 -2.09666852456737e-05 3.73972797262655e-06 3.56919245772947e-07 4.99266143394531e-07 1.62479146797804e-07 -2.09666852456737e-05 4.81216614535766e-05 -5.23303727855425e-06 3.91279418992173e-06 3.20771570433044e-06 2.08115848723292e-05 3.73972797262655e-06 -5.23303727855425e-06 1.50133078972822e-05 3.51881652427376e-06 -1.17411791258064e-06 -1.80911630906191e-06 3.56919245772947e-07 3.91279418992173e-06 3.51881652427376e-06 2.82542180244444e-05 4.6159086059331e-06 2.58143700161731e-06 4.99266143394531e-07 3.20771570433044e-06 -1.17411791258064e-06 4.6159086059331e-06 3.45063968935908e-05 -3.82591919093859e-07 1.62479146797804e-07 2.08115848723292e-05 -1.80911630906191e-06 2.58143700161731e-06 -3.82591919093859e-07 7.12743861887388e-05 1326 1330 0 0 0 1386 1408 0 0 7 0 0 0 0 0 0 0 0 1069 0 14 59 0 0 2578 +1277 1311 0.996464112461596 0.00187725148733043 0.0839985029805669 -0.0257044702695735 -0.014076380270335 0.989349716103359 0.144875790816435 -0.0384191374884162 -0.0828319267831427 -0.145545921183164 0.985877911676865 0.00806903796846156 0.00019078778142931 -9.63739798182566e-05 1.41578420731532e-06 -9.51396304003195e-06 -1.29192552088205e-05 3.44814285931451e-05 -9.63739798182566e-05 0.00012903190652748 -3.07190177515967e-06 1.11272581934583e-05 3.28332358132159e-06 1.63940118356795e-05 1.41578420731532e-06 -3.07190177515967e-06 1.55057518081319e-05 3.03758649191819e-06 -2.32413355690316e-06 -3.10994444476699e-06 -9.51396304003195e-06 1.11272581934583e-05 3.03758649191819e-06 3.00018798879833e-05 1.41081212112912e-06 4.20990218218025e-07 -1.29192552088205e-05 3.28332358132159e-06 -2.32413355690316e-06 1.41081212112912e-06 3.27416628191433e-05 -8.23635864319348e-07 3.44814285931451e-05 1.63940118356795e-05 -3.10994444476699e-06 4.20990218218025e-07 -8.23635864319348e-07 8.92263912964031e-05 1294 1294 0 0 0 1353 1358 0 0 0 0 0 0 0 0 0 0 0 962 0 19 72 0 0 2747 +1277 1306 0.996568970666236 0.00375654328327652 0.0826811652542413 -0.0231530927127251 -0.0159854127417347 0.988896284038276 0.147745070966059 -0.0363890397044756 -0.0812080863258991 -0.148559845846212 0.985563401774556 0.00701396633422879 8.53195389601084e-05 -5.08821621323681e-05 4.60995365565429e-07 -1.09366445578812e-06 -7.16778341244054e-06 -6.12218860411382e-06 -5.08821621323681e-05 8.51344935661544e-05 1.02385775716335e-06 1.39069225001043e-06 6.59120161810334e-07 2.82864266774132e-05 4.60995365565429e-07 1.02385775716335e-06 1.58311234986791e-05 -2.32083866968729e-07 -1.92577890231682e-06 -1.72650208233399e-06 -1.09366445578812e-06 1.39069225001043e-06 -2.32083866968729e-07 3.30623232885578e-05 9.39900053756982e-06 9.11782331387913e-06 -7.16778341244054e-06 6.59120161810334e-07 -1.92577890231682e-06 9.39900053756982e-06 3.73828763227199e-05 6.80376344628436e-06 -6.12218860411382e-06 2.82864266774132e-05 -1.72650208233399e-06 9.11782331387913e-06 6.80376344628436e-06 6.44329381122241e-05 1318 1321 0 0 0 1376 1386 0 0 0 0 0 0 0 0 0 0 0 1058 0 13 73 0 0 2782 +1277 1280 0.999983926641108 0.00102665446247739 -0.00557605954471665 -0.00742623864698046 -0.00102604809285926 0.999999467384701 0.000111604770446949 -0.00534800366281276 0.00557617115435764 -0.000105881671321893 0.999984447431223 0.00735310840435765 5.97716242728164e-05 1.0769259315822e-05 1.25294911248088e-06 3.71181111586679e-06 -1.79275717582841e-06 1.63437798837119e-05 1.0769259315822e-05 3.63256299585596e-05 3.64818096217126e-06 1.89429538764869e-06 2.2943583280698e-06 1.65728636800924e-05 1.25294911248088e-06 3.64818096217126e-06 1.08799840931788e-05 1.37939810082008e-06 -5.37934521353923e-06 1.53114703019326e-06 3.71181111586679e-06 1.89429538764869e-06 1.37939810082008e-06 2.73712037797286e-05 3.54844738371397e-06 3.27523180090626e-06 -1.79275717582841e-06 2.2943583280698e-06 -5.37934521353923e-06 3.54844738371397e-06 2.08843239895681e-05 3.87271698054962e-06 1.63437798837119e-05 1.65728636800924e-05 1.53114703019326e-06 3.27523180090626e-06 3.87271698054962e-06 5.27646224592593e-05 1225 1225 0 0 0 1259 1312 0 0 0 0 0 0 0 0 0 0 0 790 0 0 2 0 0 3431 +1277 1307 0.996143595971919 0.00333895059314086 0.0876743269895522 -0.0202902611569166 -0.0166070180989419 0.98838732950046 0.151045337011145 -0.0355669768192349 -0.0861518610013491 -0.151918854300201 0.984631158634602 0.00950081288857895 7.33556866839905e-05 -2.87723686112939e-05 5.57093128732931e-06 4.39689198412064e-07 1.18716146198482e-06 -6.17657630524978e-08 -2.87723686112939e-05 6.8052598647711e-05 -4.04796998266014e-06 3.30413987503261e-06 -5.94547000970606e-06 2.071154904107e-05 5.57093128732931e-06 -4.04796998266014e-06 1.74029713789352e-05 8.58211679565069e-07 7.63345847705948e-08 4.8083713267358e-07 4.39689198412064e-07 3.30413987503261e-06 8.58211679565069e-07 3.20106568563519e-05 1.00121838079712e-05 1.76295399585019e-06 1.18716146198482e-06 -5.94547000970606e-06 7.63345847705948e-08 1.00121838079712e-05 3.76299565079088e-05 3.73386636525216e-06 -6.17657630524978e-08 2.071154904107e-05 4.8083713267358e-07 1.76295399585019e-06 3.73386636525216e-06 6.40689920415422e-05 1325 1327 0 0 0 1383 1402 0 0 4 0 0 0 0 0 0 0 0 1063 0 16 62 0 0 2619 +1277 1312 0.995451798633523 0.00364310623015627 0.0951968716622578 -0.0224933363103878 -0.0183183603796198 0.987941025234917 0.15374318954277 -0.0343560762960555 -0.0934887922175004 -0.154787785160127 0.983514406246769 0.00588446293037035 0.000174607933285847 -0.000122258918542871 5.18879825084847e-06 -7.20718821079996e-06 -7.87784366172094e-06 -9.5364500858461e-06 -0.000122258918542871 0.000135348049452327 -5.43395304362045e-06 1.07619550020192e-05 1.11732346604648e-05 3.4761383471045e-05 5.18879825084847e-06 -5.43395304362045e-06 1.59502811885729e-05 2.46997749376971e-06 -5.60024093638699e-06 -6.63805720571252e-06 -7.20718821079996e-06 1.07619550020192e-05 2.46997749376971e-06 3.70755576929341e-05 1.17867507235845e-05 9.78142831891827e-06 -7.87784366172094e-06 1.11732346604648e-05 -5.60024093638699e-06 1.17867507235845e-05 3.74118441924309e-05 1.36663748066907e-05 -9.5364500858461e-06 3.4761383471045e-05 -6.63805720571252e-06 9.78142831891827e-06 1.36663748066907e-05 7.13317571993738e-05 1316 1321 0 0 0 1372 1386 0 0 0 0 0 0 0 0 0 0 0 1067 0 14 71 0 0 2586 +1277 1309 0.995803513448893 0.00210349809914249 0.0914928297659815 -0.0202028358375061 -0.0156249270716706 0.988964892767365 0.147323801633133 -0.0331459557941316 -0.090173301241803 -0.148135128073596 0.984847581899745 0.0107345066976214 5.87480502040572e-05 -1.98453551076967e-05 5.97773395791407e-06 -4.73060340117781e-08 3.22170282045165e-06 1.7639561733555e-05 -1.98453551076967e-05 5.09593953767739e-05 -6.23372911325093e-06 2.28405720403743e-06 -3.32883726008544e-06 8.96040520201189e-06 5.97773395791407e-06 -6.23372911325093e-06 1.86291110689652e-05 -4.39965189720113e-07 6.59559059779909e-07 -1.0786892423957e-07 -4.73060340117781e-08 2.28405720403743e-06 -4.39965189720113e-07 2.81787154604657e-05 1.93716769653567e-06 2.12124422756696e-06 3.22170282045165e-06 -3.32883726008544e-06 6.59559059779909e-07 1.93716769653567e-06 3.26391807246046e-05 4.46737190393693e-06 1.7639561733555e-05 8.96040520201189e-06 -1.0786892423957e-07 2.12124422756696e-06 4.46737190393693e-06 6.49253446858554e-05 1328 1332 0 0 0 1382 1397 0 0 0 0 0 0 0 0 0 0 0 970 0 11 63 0 0 2539 +1277 1316 0.995619214784658 0.00316670652137825 0.0934470498271049 -0.0261105831780027 -0.0174128518096048 0.988221811793709 0.152034349036711 -0.0374432964437292 -0.0918649647223506 -0.152995498838911 0.983947765682505 0.00120155392661403 0.000135153563134355 -7.63952690548017e-05 7.87352811837892e-06 -1.21683636294416e-06 -6.70071151233954e-07 6.87291901373371e-06 -7.63952690548017e-05 9.09614108020666e-05 -5.98720795217915e-06 2.01003189696007e-06 -5.24066745272859e-06 1.62829547333556e-05 7.87352811837892e-06 -5.98720795217915e-06 1.81945491834215e-05 1.36679166473285e-06 -3.04431406336692e-06 -9.28392472276475e-06 -1.21683636294416e-06 2.01003189696007e-06 1.36679166473285e-06 3.34474243660707e-05 3.16120666199238e-06 1.15923764284157e-05 -6.70071151233954e-07 -5.24066745272859e-06 -3.04431406336692e-06 3.16120666199238e-06 3.73013950233771e-05 -1.18190070402288e-06 6.87291901373371e-06 1.62829547333556e-05 -9.28392472276475e-06 1.15923764284157e-05 -1.18190070402288e-06 7.70054524730369e-05 1202 1202 0 0 0 1266 1275 0 0 0 0 0 0 0 0 0 0 0 1056 0 15 60 0 0 2769 +1277 1314 0.995949437910013 0.00294106611475163 0.0898669419577474 -0.0242344727243575 -0.0164798086641109 0.988505110419189 0.150286601470462 -0.0342828923660364 -0.0883919285518919 -0.151158846268605 0.984549577300006 0.0065097610340246 9.99984703079951e-05 -4.73803136640124e-05 2.73796274622705e-07 2.64824682873666e-06 -5.17190198060957e-06 3.23729533356126e-06 -4.73803136640124e-05 8.03997833562374e-05 -9.09744934902787e-07 9.86728465010217e-06 6.12088094000758e-06 3.28808051204587e-05 2.73796274622705e-07 -9.09744934902787e-07 1.68923915329094e-05 1.39715773580133e-06 -5.1690196975416e-06 -6.18807809072425e-06 2.64824682873666e-06 9.86728465010217e-06 1.39715773580133e-06 4.14454056071439e-05 4.99518360130309e-06 1.5865916554299e-05 -5.17190198060957e-06 6.12088094000758e-06 -5.1690196975416e-06 4.99518360130309e-06 3.22344049237495e-05 6.79104238213512e-06 3.23729533356126e-06 3.28808051204587e-05 -6.18807809072425e-06 1.5865916554299e-05 6.79104238213512e-06 7.81672013427075e-05 1303 1303 0 0 0 1358 1365 0 0 0 0 0 0 0 0 0 0 0 1068 0 18 64 0 0 2576 +1277 1313 0.996812229910256 0.00357876080097469 0.079703016081409 -0.0251083234988238 -0.0152034193020246 0.989208138084706 0.145726166451037 -0.0373195566443795 -0.0783213530454547 -0.146473383309453 0.986109179370627 0.00877000680742745 0.000130943776821107 -6.9311809867427e-05 1.00843685558037e-05 -1.43927457082805e-05 -5.92682503870805e-06 7.34926812089543e-07 -6.9311809867427e-05 9.85172048150747e-05 -6.76840354528407e-06 1.19574188162659e-05 4.72796965080375e-06 1.88852530995243e-05 1.00843685558037e-05 -6.76840354528407e-06 1.46787544187231e-05 2.33529721122289e-06 -3.85738759750261e-06 -2.61436326401608e-06 -1.43927457082805e-05 1.19574188162659e-05 2.33529721122289e-06 3.59964569286571e-05 1.15590869736679e-05 9.83752162825841e-06 -5.92682503870805e-06 4.72796965080375e-06 -3.85738759750261e-06 1.15590869736679e-05 3.35387819076267e-05 8.81096380155233e-06 7.34926812089543e-07 1.88852530995243e-05 -2.61436326401608e-06 9.83752162825841e-06 8.81096380155233e-06 7.03236734004622e-05 1315 1316 0 0 0 1373 1380 0 0 0 0 0 0 0 0 0 0 0 1068 0 12 75 0 0 2726 +1277 1303 0.996377079581071 0.00344544577549778 0.0849755505360464 -0.0235784775525827 -0.0162984982249176 0.988394570048481 0.151031562444047 -0.0358125508396805 -0.0834690016779189 -0.151869360972139 0.98486985077055 0.00633035743611285 0.000148429934074306 -6.81635068439247e-05 -1.65833947147744e-06 -2.6352379315543e-06 -1.40020835670077e-05 -5.76109286508349e-06 -6.81635068439247e-05 0.00010017546537795 1.34088780592176e-06 9.13948507141618e-06 2.53826039512769e-06 4.59787387770268e-05 -1.65833947147744e-06 1.34088780592176e-06 1.49709541207404e-05 1.38745352447109e-06 -2.26350700434669e-06 -6.32318400905401e-07 -2.6352379315543e-06 9.13948507141618e-06 1.38745352447109e-06 3.56772234901192e-05 1.28373902903347e-05 1.42888146382327e-05 -1.40020835670077e-05 2.53826039512769e-06 -2.26350700434669e-06 1.28373902903347e-05 4.19316219487e-05 7.14854812163341e-06 -5.76109286508349e-06 4.59787387770268e-05 -6.32318400905401e-07 1.42888146382327e-05 7.14854812163341e-06 8.61636214982841e-05 1316 1319 0 0 0 1375 1386 0 0 0 0 0 0 0 0 0 0 0 956 0 14 73 0 0 2685 +1277 1305 0.996449681388674 0.00306580068724961 0.0841346143187012 -0.0230865555987992 -0.0155665198454118 0.988815300199342 0.148330662883933 -0.0330136927454759 -0.0827388416664927 -0.149113724914344 0.985352414683121 0.00792186774462404 0.000108223590643973 -4.34548910236315e-05 1.29789228836898e-06 -3.78689840020371e-06 -1.36118341193315e-05 -7.28870508517666e-06 -4.34548910236315e-05 7.0601487387568e-05 -1.38660654746866e-07 3.69876890599295e-06 4.36584274560778e-06 3.61753975809487e-05 1.29789228836898e-06 -1.38660654746866e-07 1.87146025809633e-05 -8.5349598592521e-07 -9.03190014771846e-07 2.16173674020921e-07 -3.78689840020371e-06 3.69876890599295e-06 -8.5349598592521e-07 3.6797780385139e-05 9.29398133066483e-06 4.15812746835683e-06 -1.36118341193315e-05 4.36584274560778e-06 -9.03190014771846e-07 9.29398133066483e-06 4.11775280523955e-05 4.31970848485931e-06 -7.28870508517666e-06 3.61753975809487e-05 2.16173674020921e-07 4.15812746835683e-06 4.31970848485931e-06 8.79997624484741e-05 1203 1203 0 0 0 1267 1278 0 0 0 0 0 0 0 0 0 0 0 968 0 10 52 0 0 2572 +1277 1315 0.996055889729166 0.00341411993801119 0.0886623275178845 -0.0241618378397513 -0.0166399490944615 0.988717511734793 0.148865019675859 -0.0335899009856689 -0.0871537528163502 -0.149753216239281 0.984874711623777 0.0022955425850711 8.25520609781079e-05 -4.70474024096318e-05 2.66532371216332e-06 -3.39189256269645e-06 -7.42041821840484e-06 -1.70246364835331e-05 -4.70474024096318e-05 8.62697764794429e-05 -4.53637399679441e-06 1.17901352246252e-05 2.48653027181597e-07 4.16171037842199e-05 2.66532371216332e-06 -4.53637399679441e-06 1.70637390534847e-05 2.73902329377587e-06 -1.94982852506457e-06 -2.03277118516068e-06 -3.39189256269645e-06 1.17901352246252e-05 2.73902329377587e-06 3.4041258286154e-05 -5.98628077023615e-06 1.22850672997237e-05 -7.42041821840484e-06 2.48653027181597e-07 -1.94982852506457e-06 -5.98628077023615e-06 3.23482833146302e-05 5.1401212290128e-06 -1.70246364835331e-05 4.16171037842199e-05 -2.03277118516068e-06 1.22850672997237e-05 5.1401212290128e-06 7.00925275868464e-05 1202 1202 0 0 0 1262 1273 0 0 0 0 0 0 0 0 0 0 0 1074 0 11 53 0 0 2759 +1277 1317 0.99633518962189 0.00477390475320257 0.0854014037034449 -0.023161273458106 -0.0171511352821965 0.989313540575224 0.144791425827108 -0.0372723321268402 -0.0837975445919701 -0.145725523735283 0.985769771930766 0.0120209967777977 0.000114928745976974 -5.15371472049635e-05 -1.84114955572479e-06 -3.87832137898838e-07 -5.48996438157596e-06 3.91054021592762e-06 -5.15371472049635e-05 6.63470150336075e-05 -1.65903298604183e-08 -4.96068707823358e-07 1.85281235896355e-06 2.48082680966639e-05 -1.84114955572479e-06 -1.65903298604183e-08 1.59876246223067e-05 2.36916068334603e-06 -5.68745485277894e-06 -1.53712149879422e-06 -3.87832137898838e-07 -4.96068707823358e-07 2.36916068334603e-06 3.37297309814946e-05 4.77502242572666e-06 9.66363893977847e-06 -5.48996438157596e-06 1.85281235896355e-06 -5.68745485277894e-06 4.77502242572666e-06 3.52719072621073e-05 4.41552421366895e-06 3.91054021592762e-06 2.48082680966639e-05 -1.53712149879422e-06 9.66363893977847e-06 4.41552421366895e-06 7.36189307305223e-05 1290 1290 0 0 0 1349 1353 0 0 0 0 0 0 0 0 0 0 0 970 0 15 73 0 0 2786 +1277 1304 0.996734424018854 0.00338485769830574 0.0806785641553255 -0.022792404382919 -0.0151327797421463 0.989249507373361 0.145452436001736 -0.0348890698271364 -0.079318894048508 -0.146198340961605 0.986070260248729 0.00285992406068421 9.59358886029936e-05 -6.22218568140149e-05 5.95285342295071e-06 -2.07734407660737e-06 2.66383405304253e-06 -1.51464898938978e-05 -6.22218568140149e-05 8.96555099199064e-05 1.04341688488706e-06 4.57889323230187e-06 -1.69317028846233e-06 3.73747574882707e-05 5.95285342295071e-06 1.04341688488706e-06 1.51859003631278e-05 1.8077234015338e-06 -5.23230007373593e-06 7.91718771187138e-07 -2.07734407660737e-06 4.57889323230187e-06 1.8077234015338e-06 3.2933257739171e-05 9.00602847668984e-06 5.94688479660392e-06 2.66383405304253e-06 -1.69317028846233e-06 -5.23230007373593e-06 9.00602847668984e-06 3.27838961524591e-05 6.72376966896639e-06 -1.51464898938978e-05 3.73747574882707e-05 7.91718771187138e-07 5.94688479660392e-06 6.72376966896639e-06 6.19513074285757e-05 1322 1325 0 0 0 1379 1389 0 0 0 0 0 0 0 0 0 0 0 1060 0 11 68 0 0 2606 +1278 1280 0.999989195394334 -0.000199692344629196 -0.00464426717149473 -0.00986042127261292 0.00020745708240664 0.999998581564332 0.00167147566011397 -0.00150953046586121 0.00464392680300697 -0.00167242108659589 0.999987818401583 0.00716158939493769 4.59823935818626e-05 -5.77201190482681e-06 3.81634494335985e-06 -3.57869668087546e-06 -4.03583922269753e-06 7.42833637283179e-06 -5.77201190482681e-06 4.03394875214259e-05 1.54784447939992e-07 5.21419392106316e-06 -3.37951864853195e-06 1.04449421785854e-05 3.81634494335985e-06 1.54784447939992e-07 1.19174025316799e-05 2.04997382000181e-06 -5.08004247780589e-06 1.45957114715807e-06 -3.57869668087546e-06 5.21419392106316e-06 2.04997382000181e-06 2.51791528429827e-05 -3.85833809918952e-06 -5.71140501773628e-08 -4.03583922269753e-06 -3.37951864853195e-06 -5.08004247780589e-06 -3.85833809918952e-06 2.00701421007279e-05 -1.09301486048288e-06 7.42833637283179e-06 1.04449421785854e-05 1.45957114715807e-06 -5.71140501773628e-08 -1.09301486048288e-06 3.97974660752755e-05 1242 1242 0 0 0 1259 1321 0 0 2 0 0 0 0 0 0 0 0 787 0 6 26 0 0 3508 +1277 1318 0.996099138136588 0.00360341201224903 0.0881675814878502 -0.0253194788832802 -0.0170699642661596 0.988161173907528 0.152466752774656 -0.0376834745307325 -0.0865743802952049 -0.153377018498751 0.984368003783613 0.0130121443678469 8.76300541601578e-05 -4.54201484371137e-05 3.7815811087185e-06 -4.54110218155879e-06 -2.38764990391695e-06 5.89390771560377e-06 -4.54201484371137e-05 7.16533822985533e-05 -2.61612486724379e-06 9.54553207948561e-06 4.09467104089432e-06 2.25323459300055e-05 3.7815811087185e-06 -2.61612486724379e-06 1.48855663047697e-05 3.23192107632689e-06 -4.32332663390356e-06 -4.45422030951185e-06 -4.54110218155879e-06 9.54553207948561e-06 3.23192107632689e-06 3.81348084454566e-05 4.46483196687899e-06 1.28177126100783e-05 -2.38764990391695e-06 4.09467104089432e-06 -4.32332663390356e-06 4.46483196687899e-06 3.23201935011974e-05 3.37587607842418e-06 5.89390771560377e-06 2.25323459300055e-05 -4.45422030951185e-06 1.28177126100783e-05 3.37587607842418e-06 6.97413285102204e-05 1318 1320 0 0 0 1379 1396 0 0 2 0 0 0 0 0 0 0 0 1072 0 21 71 0 0 2751 +1278 1309 0.99656644330307 0.00200337134409426 0.0827726439442757 -0.0231837948332164 -0.014252659470766 0.988934922652798 0.14766374116795 -0.0301210751610617 -0.0815609329291822 -0.148336459648202 0.985567911895857 0.0112733901462989 8.23790503830555e-05 -4.62579766334988e-05 4.23910080913376e-06 -4.17738030908649e-06 -1.57939398777415e-06 1.46753044551496e-05 -4.62579766334988e-05 6.84826245218206e-05 -3.74690278321746e-06 9.43392440772229e-06 6.58414342391409e-06 6.97630385278948e-06 4.23910080913376e-06 -3.74690278321746e-06 1.30175348948136e-05 3.13770105954274e-06 -5.66143260948728e-06 -3.74635487726044e-06 -4.17738030908649e-06 9.43392440772229e-06 3.13770105954274e-06 2.58303185993276e-05 -1.90612522682083e-06 2.5747086021246e-06 -1.57939398777415e-06 6.58414342391409e-06 -5.66143260948728e-06 -1.90612522682083e-06 2.66656229056327e-05 2.26088986646261e-06 1.46753044551496e-05 6.97630385278948e-06 -3.74635487726044e-06 2.5747086021246e-06 2.26088986646261e-06 6.02684868187352e-05 1327 1332 0 0 0 1386 1412 0 0 9 0 0 0 0 0 0 0 0 965 0 10 54 0 0 2583 +1278 1311 0.996732524698132 0.00179592096135717 0.0807530115648195 -0.0245975920375679 -0.0133350358784366 0.989692931561568 0.14258358262854 -0.0354256569976887 -0.0796646159032234 -0.143194538600358 0.986483083021712 0.0164103980598638 0.000187161813660271 -0.000125169591853366 -4.02926274928724e-06 -1.3365055920923e-05 -2.04116985026648e-05 6.90427182977336e-05 -0.000125169591853366 0.000132856436928202 -2.77021725968886e-08 1.52214971003669e-05 1.78921265251319e-05 -3.53960694573372e-05 -4.02926274928724e-06 -2.77021725968886e-08 1.43842012635742e-05 3.76120897288054e-06 -4.25334580664922e-06 -8.753121099227e-06 -1.3365055920923e-05 1.52214971003669e-05 3.76120897288054e-06 2.92776864538959e-05 5.7867792166668e-06 -1.35554916261167e-05 -2.04116985026648e-05 1.78921265251319e-05 -4.25334580664922e-06 5.7867792166668e-06 3.32377221068506e-05 -5.46675916488752e-06 6.90427182977336e-05 -3.53960694573372e-05 -8.753121099227e-06 -1.35554916261167e-05 -5.46675916488752e-06 9.80380251108718e-05 1321 1325 0 0 0 1378 1392 0 0 0 0 0 0 0 0 0 0 0 959 0 14 70 0 0 2843 +1278 1308 0.996638592743237 0.00303705579658207 0.0818675255939095 -0.0237931961806696 -0.0149468394264782 0.989280573760264 0.14526024360341 -0.0340325521354591 -0.0805487892270273 -0.145995625525737 0.986000593245972 0.00430863766910989 6.74867208839057e-05 -3.62780926996986e-05 5.36141359611701e-06 -3.77256218442871e-06 -2.36349254306729e-07 4.99651580606223e-07 -3.62780926996986e-05 5.98952770825336e-05 -2.37765635620966e-06 1.00588969337157e-05 -6.56478608978667e-07 1.41066065681755e-05 5.36141359611701e-06 -2.37765635620966e-06 1.20493837740266e-05 2.27126315917656e-06 -5.03027410505576e-06 -2.60527241292949e-06 -3.77256218442871e-06 1.00588969337157e-05 2.27126315917656e-06 2.86356842515936e-05 6.13336464184604e-06 7.40749578587772e-06 -2.36349254306729e-07 -6.56478608978667e-07 -5.03027410505576e-06 6.13336464184604e-06 3.38506862229282e-05 3.28126859251118e-06 4.99651580606223e-07 1.41066065681755e-05 -2.60527241292949e-06 7.40749578587772e-06 3.28126859251118e-06 5.93620974458856e-05 1229 1229 0 0 0 1281 1293 0 0 1 0 0 0 0 0 0 0 0 1068 0 11 52 0 0 2862 +1278 1281 0.999931852222179 -0.000167804915722621 -0.0116731637970366 -0.0105123070908141 0.000146263247654476 0.999998285019042 -0.00184623022309389 -0.0047530559601716 0.01167345358429 0.00184439705175949 0.999930161901785 0.00456985340291136 6.19926665724468e-05 9.9116259291891e-07 3.94323822534281e-06 -5.01601823644217e-06 -6.93048152595269e-06 2.92660878846768e-06 9.9116259291891e-07 4.39923649134782e-05 2.23998772294785e-06 8.73267067984187e-06 1.50109681571163e-07 8.09075596130982e-06 3.94323822534281e-06 2.23998772294785e-06 1.33563969336921e-05 6.37891317734786e-07 -1.79950353693208e-06 -3.38704486859831e-06 -5.01601823644217e-06 8.73267067984187e-06 6.37891317734786e-07 2.73975905455539e-05 -1.34913856310569e-06 -1.15363780378831e-06 -6.93048152595269e-06 1.50109681571163e-07 -1.79950353693208e-06 -1.34913856310569e-06 3.08192460152397e-05 -9.96805457218504e-06 2.92660878846768e-06 8.09075596130982e-06 -3.38704486859831e-06 -1.15363780378831e-06 -9.96805457218504e-06 5.06405146639321e-05 1199 1199 0 0 0 1235 1285 0 0 1 0 0 0 0 0 0 0 0 788 0 0 10 0 0 3436 +1278 1282 0.999996362908199 0.000410856776084775 -0.00266558944385886 -0.00907820728602855 -0.000413080398066172 0.999999567155765 -0.000833698307207419 -0.00432502868673271 0.00266524575947511 0.000834796377718692 0.999996099782419 -0.000707849557126881 5.18509060723276e-05 -1.61642496119771e-06 2.05522405270031e-06 3.75455853453689e-06 -8.73116595713074e-06 1.04453596720156e-05 -1.61642496119771e-06 2.83072499137706e-05 3.93007474463083e-07 1.11397483504242e-05 1.12735165300014e-06 9.44125698218641e-06 2.05522405270031e-06 3.93007474463083e-07 1.12204792820031e-05 -1.11257736463451e-07 -5.15676214294026e-06 -1.15604603483717e-06 3.75455853453689e-06 1.11397483504242e-05 -1.11257736463451e-07 3.27851579268479e-05 2.55996500681483e-06 6.03853682101427e-06 -8.73116595713074e-06 1.12735165300014e-06 -5.15676214294026e-06 2.55996500681483e-06 2.62569592450586e-05 -1.57790732407448e-06 1.04453596720156e-05 9.44125698218641e-06 -1.15604603483717e-06 6.03853682101427e-06 -1.57790732407448e-06 3.30999918743293e-05 1325 1339 0 0 0 1345 1417 0 0 7 0 0 0 0 0 0 0 0 785 0 0 1 0 0 3435 +1278 1312 0.996150514281525 0.00314465667991351 0.0876028768421379 -0.0211091961761406 -0.0160309836762646 0.989038001290447 0.146788417682626 -0.0312458135524884 -0.0861809750410417 -0.147627718053769 0.985281125569353 0.00634605288710505 8.06315081520093e-05 -5.35264720483274e-05 5.57408050881626e-06 -9.59882947254918e-06 -1.05525990802181e-05 1.02123078094619e-05 -5.35264720483274e-05 7.55740533127636e-05 -2.8146101330473e-06 7.28015479435577e-06 6.24778915385861e-06 5.32815440168286e-06 5.57408050881626e-06 -2.8146101330473e-06 1.41096753749658e-05 1.01415342100892e-06 -6.40266366147522e-06 -2.39104987930236e-06 -9.59882947254918e-06 7.28015479435577e-06 1.01415342100892e-06 3.43122892082461e-05 5.61715960778977e-06 3.89350328543453e-06 -1.05525990802181e-05 6.24778915385861e-06 -6.40266366147522e-06 5.61715960778977e-06 2.95944177048558e-05 2.9968242001348e-06 1.02123078094619e-05 5.32815440168286e-06 -2.39104987930236e-06 3.89350328543453e-06 2.9968242001348e-06 6.94190969640793e-05 1320 1327 0 0 0 1381 1408 0 0 9 0 0 0 0 0 0 0 0 1065 0 12 58 0 0 2772 +1278 1310 0.996189505387533 0.00253009581568401 0.0871783687098168 -0.0255539866738037 -0.0154189322501818 0.988943148261287 0.147491376138808 -0.0329477571925955 -0.0858412830985512 -0.148273558405464 0.98521379709877 -0.00973150278850791 7.46224185013179e-05 -4.26565276621367e-05 7.61651266367935e-06 -2.86371990581273e-06 7.72220330843281e-06 9.67399798628756e-06 -4.26565276621367e-05 6.45130312548518e-05 -7.36859175764287e-06 8.00908704032451e-06 -4.56335054925445e-06 8.90398616994603e-07 7.61651266367935e-06 -7.36859175764287e-06 1.45013923176893e-05 2.18416057921701e-06 -1.73394740205005e-06 -3.6388172772797e-06 -2.86371990581273e-06 8.00908704032451e-06 2.18416057921701e-06 2.42631026765125e-05 -6.12288995767331e-06 8.44310975727257e-06 7.72220330843281e-06 -4.56335054925445e-06 -1.73394740205005e-06 -6.12288995767331e-06 2.60210466678293e-05 6.16138615029016e-06 9.67399798628756e-06 8.90398616994603e-07 -3.6388172772797e-06 8.44310975727257e-06 6.16138615029016e-06 7.52806504785204e-05 1302 1302 0 0 0 1381 1397 0 0 0 0 0 0 0 0 0 0 0 1065 0 19 68 0 0 2564 +1278 1317 0.996806660888194 0.00383513779160236 0.0797607204521625 -0.0245651762571248 -0.0150897034382252 0.989896616899862 0.140985774815597 -0.0357768505303685 -0.0784141674640177 -0.141739125044312 0.986793412408391 0.0117519693048875 0.000144662592315662 -9.51377957011543e-05 7.82383009589572e-07 -1.92025041530164e-05 -1.50902232930731e-05 2.32547489160102e-05 -9.51377957011543e-05 0.000114845083056601 -5.12150254217389e-08 2.17645417216449e-05 1.10708286651754e-05 -8.1161724786164e-07 7.82383009589572e-07 -5.12150254217389e-08 1.53085675852529e-05 3.90874061041596e-06 -1.64443142705263e-06 -5.91007594579544e-06 -1.92025041530164e-05 2.17645417216449e-05 3.90874061041596e-06 3.83979375834631e-05 3.96284023250345e-06 1.37468799657683e-06 -1.50902232930731e-05 1.10708286651754e-05 -1.64443142705263e-06 3.96284023250345e-06 3.67507211993262e-05 -2.02495955705345e-06 2.32547489160102e-05 -8.1161724786164e-07 -5.91007594579544e-06 1.37468799657683e-06 -2.02495955705345e-06 7.07965062487352e-05 1314 1317 0 0 0 1375 1387 0 0 0 0 0 0 0 0 0 0 0 962 0 13 73 0 0 2862 +1278 1318 0.996748135119331 0.00374674308710516 0.080492962750641 -0.026378555986091 -0.0156780698554362 0.98884601443159 0.148114002944918 -0.0381213792564575 -0.0790402002891244 -0.148894330513282 0.98568916250472 0.0100519898085032 5.62627622836208e-05 -3.75484454637995e-05 2.21900221686189e-06 -1.08405883931878e-06 -3.26572138836283e-06 4.3889752668232e-06 -3.75484454637995e-05 5.37231169751938e-05 -4.05977963482825e-06 5.87263985563931e-06 6.69535261597946e-06 5.40714569365951e-06 2.21900221686189e-06 -4.05977963482825e-06 1.30899597330935e-05 2.30564139319214e-06 -5.70942049225421e-06 -3.64070498918011e-06 -1.08405883931878e-06 5.87263985563931e-06 2.30564139319214e-06 3.66643740349309e-05 2.2619382807598e-07 6.7478085313759e-06 -3.26572138836283e-06 6.69535261597946e-06 -5.70942049225421e-06 2.2619382807598e-07 2.65107420699932e-05 1.10975214858683e-05 4.3889752668232e-06 5.40714569365951e-06 -3.64070498918011e-06 6.7478085313759e-06 1.10975214858683e-05 6.42984897076617e-05 1295 1295 0 0 0 1380 1391 0 0 1 0 0 0 0 0 0 0 0 1064 0 24 79 0 0 2870 +1278 1316 0.996548075037408 0.00348958034906494 0.0829443003962576 -0.0245030033119688 -0.0152449032021294 0.989818087834985 0.141519418883245 -0.0342670122801828 -0.0816059254318882 -0.14229538229922 0.9864545083838 0.00998298039126694 8.70938448160351e-05 -5.3431132593067e-05 5.55553535909357e-06 -8.47129988876912e-06 4.21035439148098e-06 6.9474509720309e-06 -5.3431132593067e-05 8.00971561247992e-05 -2.45254157181542e-06 5.39144165635935e-06 -5.70875972709517e-06 8.09994559792053e-06 5.55553535909357e-06 -2.45254157181542e-06 1.38456993706955e-05 2.12144165989008e-06 -4.55999373333594e-06 -3.58718967663615e-06 -8.47129988876912e-06 5.39144165635935e-06 2.12144165989008e-06 3.28354368266861e-05 -3.84012698210314e-06 7.74375792434208e-06 4.21035439148098e-06 -5.70875972709517e-06 -4.55999373333594e-06 -3.84012698210314e-06 3.0843222069059e-05 -2.18567915523952e-06 6.9474509720309e-06 8.09994559792053e-06 -3.58718967663615e-06 7.74375792434208e-06 -2.18567915523952e-06 6.43772393443879e-05 1229 1229 0 0 0 1281 1292 0 0 0 0 0 0 0 0 0 0 0 1055 0 12 55 0 0 2854 +1278 1307 0.996916738077736 0.00334908025418839 0.0783951593014398 -0.0252820988940785 -0.015015357229558 0.988767893476093 0.148703032511505 -0.0329360149571637 -0.0770165981312852 -0.149421673435616 0.985769550716588 0.00847144338242166 8.37701206795785e-05 -4.23954781237643e-05 3.67661539974346e-06 -5.85787764702894e-06 -5.70877016578016e-06 1.44625167084325e-05 -4.23954781237643e-05 6.0967083388994e-05 -2.44916817880694e-06 1.10301843400581e-05 5.57559143843149e-06 5.31492520120972e-06 3.67661539974346e-06 -2.44916817880694e-06 1.27976850429008e-05 2.13819558492144e-06 -4.40067536660589e-06 -3.21502759785107e-06 -5.85787764702894e-06 1.10301843400581e-05 2.13819558492144e-06 3.0583663573275e-05 7.60969261053286e-06 7.26846859396144e-06 -5.70877016578016e-06 5.57559143843149e-06 -4.40067536660589e-06 7.60969261053286e-06 2.98431221672257e-05 6.27096844783112e-06 1.44625167084325e-05 5.31492520120972e-06 -3.21502759785107e-06 7.26846859396144e-06 6.27096844783112e-06 6.55508643213323e-05 1305 1305 0 0 0 1386 1401 0 0 0 0 0 0 0 0 0 0 0 1053 0 17 66 0 0 2610 +1278 1313 0.997018903258456 0.00253440507498689 0.0771160381258104 -0.0217735530162779 -0.0136333266462828 0.989521239508001 0.143742300548952 -0.0319511190359522 -0.0759436564161966 -0.1443651389826 0.986605933337456 0.0169502358523548 8.71673232414582e-05 -5.24322416566391e-05 8.56925138135204e-06 -7.83797047200888e-06 2.22661063108743e-06 1.50975230356797e-05 -5.24322416566391e-05 8.3443653085782e-05 -7.38857249958103e-06 1.50486037835362e-05 1.85629985596528e-06 5.92184414956584e-06 8.56925138135204e-06 -7.38857249958103e-06 1.27765086980985e-05 1.27742994254397e-06 -2.63020211503113e-06 -2.86879318896334e-06 -7.83797047200888e-06 1.50486037835362e-05 1.27742994254397e-06 3.5522362430129e-05 7.12221337533436e-06 1.05003210911645e-06 2.22661063108743e-06 1.85629985596528e-06 -2.63020211503113e-06 7.12221337533436e-06 3.2357599480448e-05 6.04369643416878e-06 1.50975230356797e-05 5.92184414956584e-06 -2.86879318896334e-06 1.05003210911645e-06 6.04369643416878e-06 6.46023914507114e-05 1326 1331 0 0 0 1384 1410 0 0 10 0 0 0 0 0 0 0 0 1064 0 9 53 0 0 2818 +1278 1306 0.996994751011213 0.00370973261462755 0.07738025807671 -0.0223754015967032 -0.0150842273355487 0.989031154490467 0.146934820695926 -0.0304403649517872 -0.0759863970838186 -0.147660466378725 0.986114828063668 0.00759908590873364 9.26845583388096e-05 -5.73380318906708e-05 3.5634909221715e-06 -5.12985644691005e-06 -1.20169663641464e-06 6.72224679279644e-06 -5.73380318906708e-05 8.1384277246804e-05 -1.66062949409517e-06 9.46239744501856e-06 -1.9780247593652e-06 2.1019066709863e-05 3.5634909221715e-06 -1.66062949409517e-06 1.53974463305409e-05 1.64478303814656e-06 -2.82569791732474e-06 -3.56580089788784e-06 -5.12985644691005e-06 9.46239744501856e-06 1.64478303814656e-06 3.29574166022628e-05 7.17944372209188e-06 6.79061273100348e-06 -1.20169663641464e-06 -1.9780247593652e-06 -2.82569791732474e-06 7.17944372209188e-06 3.5380821032986e-05 6.75853557115032e-08 6.72224679279644e-06 2.1019066709863e-05 -3.56580089788784e-06 6.79061273100348e-06 6.75853557115032e-08 6.46184078592926e-05 1326 1334 0 0 0 1385 1412 0 0 10 0 0 0 0 0 0 0 0 1050 0 11 56 0 0 2848 +1279 1308 0.996485501170815 0.00246150136926105 0.0837292479803709 -0.0240699749922032 -0.0147493707526388 0.989106876140705 0.146458334121267 -0.0340123076534463 -0.0824566675214959 -0.147178560198776 0.985666966778873 0.00511731021136168 8.90845129494674e-05 -2.81020560001523e-05 2.94559858509427e-06 1.94200854459427e-06 8.3429427524953e-08 1.7363123324074e-05 -2.81020560001523e-05 5.01728087858231e-05 -1.2662633117327e-06 6.7928268321367e-06 4.60032010729487e-06 1.29072674469038e-05 2.94559858509427e-06 -1.2662633117327e-06 1.21904794400761e-05 9.66677823684829e-07 -5.89963851587131e-06 -2.49836679739062e-06 1.94200854459427e-06 6.7928268321367e-06 9.66677823684829e-07 2.96588833946478e-05 8.41506414764157e-06 5.43788460101966e-06 8.3429427524953e-08 4.60032010729487e-06 -5.89963851587131e-06 8.41506414764157e-06 2.71639918156092e-05 2.95097618514276e-06 1.7363123324074e-05 1.29072674469038e-05 -2.49836679739062e-06 5.43788460101966e-06 2.95097618514276e-06 5.96751979002993e-05 1211 1211 0 0 0 1276 1284 0 0 0 0 0 0 0 0 0 0 0 1065 0 12 52 0 0 2786 +1279 1309 0.996070792318163 0.0016043618720189 0.0885460485490447 -0.020255375152511 -0.014673445302338 0.989006156646452 0.147144527993306 -0.0293813350934923 -0.0873365140913322 -0.147865642183697 0.985143687574547 0.00956971857500711 8.62491391385763e-05 -3.95921571509167e-05 3.735705795938e-06 -2.08193003853637e-06 3.1445391883266e-06 1.68795131689361e-05 -3.95921571509167e-05 6.99817179070114e-05 -8.83480367113603e-06 7.33776605120874e-06 -4.75289059894635e-06 5.78158079704233e-06 3.735705795938e-06 -8.83480367113603e-06 1.46566661702693e-05 7.09617421959354e-07 -5.66814692944258e-06 -5.34804112018288e-06 -2.08193003853637e-06 7.33776605120874e-06 7.09617421959354e-07 2.63092399446764e-05 -9.91682601889376e-08 1.69210208712899e-06 3.1445391883266e-06 -4.75289059894635e-06 -5.66814692944258e-06 -9.91682601889376e-08 2.48693133181857e-05 3.87055215576172e-07 1.68795131689361e-05 5.78158079704233e-06 -5.34804112018288e-06 1.69210208712899e-06 3.87055215576172e-07 7.00256485918493e-05 1332 1336 0 0 0 1380 1398 0 0 0 0 0 0 0 0 0 0 0 964 0 11 61 0 0 2598 +1278 1315 0.99640858479273 0.00315077063364966 0.0846168115433569 -0.0266480854807655 -0.0155139302650239 0.989184792869934 0.145851854710863 -0.0367683472306203 -0.0832421174591434 -0.146640779455378 0.985681100397911 0.00724189792939161 5.60548563807043e-05 -2.8448987177196e-05 6.8225844845676e-06 -5.75389812415606e-06 -1.36491707784381e-06 -5.13613328850703e-07 -2.8448987177196e-05 6.68407419142481e-05 -6.05023445193725e-06 6.31671607618549e-06 4.65172350991583e-07 1.63321168620286e-05 6.8225844845676e-06 -6.05023445193725e-06 1.38485734045416e-05 1.20262679790598e-06 -6.50006077262103e-06 -3.47774967881519e-06 -5.75389812415606e-06 6.31671607618549e-06 1.20262679790598e-06 3.65513837321182e-05 1.52103719518918e-06 9.96004051611982e-06 -1.36491707784381e-06 4.65172350991583e-07 -6.50006077262103e-06 1.52103719518918e-06 2.56195990717339e-05 1.10915050662289e-05 -5.13613328850703e-07 1.63321168620286e-05 -3.47774967881519e-06 9.96004051611982e-06 1.10915050662289e-05 6.21688076242864e-05 1208 1208 0 0 0 1264 1274 0 0 0 0 0 0 0 0 0 0 0 1069 0 16 59 0 0 2852 +1278 1314 0.996936320086441 0.00369764086043225 0.0781300271635262 -0.0269684247048356 -0.0151386260675575 0.989116043960197 0.146356665653858 -0.0342177316301446 -0.0767384889953715 -0.147091056942956 0.986141686206455 0.0136174047448235 7.36558717182343e-05 -4.85893166144194e-05 5.16579506394773e-06 -1.68044669453116e-06 -5.4563179975564e-06 3.02986822522596e-06 -4.85893166144194e-05 6.30284890176176e-05 -4.58893669937666e-06 5.78985983050401e-06 4.94326374692096e-06 1.30117177585984e-05 5.16579506394773e-06 -4.58893669937666e-06 1.62279294888218e-05 8.84932314384496e-07 -6.69839905186672e-06 -3.50730714873392e-06 -1.68044669453116e-06 5.78985983050401e-06 8.84932314384496e-07 4.18081963730465e-05 2.69321710145278e-06 1.26321965648206e-05 -5.4563179975564e-06 4.94326374692096e-06 -6.69839905186672e-06 2.69321710145278e-06 3.08768259794456e-05 7.11191555759513e-06 3.02986822522596e-06 1.30117177585984e-05 -3.50730714873392e-06 1.26321965648206e-05 7.11191555759513e-06 6.71157565509173e-05 1320 1320 0 0 0 1378 1385 0 0 0 0 0 0 0 0 0 0 0 1062 0 17 77 0 0 2563 +1278 1305 0.996304922767524 0.00349685910598701 0.0858153415514382 -0.0260196669634013 -0.0159944149167009 0.98924621344065 0.145382625801054 -0.0366655734802349 -0.0843841191259916 -0.146217991949451 0.985646802495499 0.0029973285633733 6.40206886759718e-05 -3.33486705305249e-05 7.5348526824963e-06 -2.79254378010939e-06 -3.47940117114969e-06 6.37126321700616e-06 -3.33486705305249e-05 6.01231399970212e-05 -2.71896398570422e-06 7.14511072652978e-07 -5.66842175876449e-07 1.22354061458962e-05 7.5348526824963e-06 -2.71896398570422e-06 1.42423308268781e-05 -2.72584931513007e-07 -6.28415557815014e-06 -2.05658072373277e-06 -2.79254378010939e-06 7.14511072652978e-07 -2.72584931513007e-07 3.2774853964565e-05 8.51354065056913e-06 -6.09499001947953e-07 -3.47940117114969e-06 -5.66842175876449e-07 -6.28415557815014e-06 8.51354065056913e-06 3.06775246076614e-05 3.2961245345029e-06 6.37126321700616e-06 1.22354061458962e-05 -2.05658072373277e-06 -6.09499001947953e-07 3.2961245345029e-06 6.24577012984805e-05 1212 1212 0 0 0 1269 1277 0 0 0 0 0 0 0 0 0 0 0 963 0 16 60 0 0 2784 +1279 1311 0.996347289278373 0.00143490138108171 0.0853816151502402 -0.0237694329985709 -0.0141370659128993 0.988833542232957 0.148352179365176 -0.031385273415693 -0.0842153342035256 -0.149017337290161 0.985241904646741 0.0135794752161416 0.000121989854169225 -3.92138826699616e-05 2.16580196517507e-06 -2.19084584415321e-06 -2.43485646249745e-06 4.25647150856754e-05 -3.92138826699616e-05 6.66668129922064e-05 -1.95461370487611e-06 1.14132207419668e-06 1.10256457118754e-06 4.78686519441574e-06 2.16580196517507e-06 -1.95461370487611e-06 1.38151130478813e-05 3.93976936730097e-06 -5.55461375813439e-06 -2.29631940258299e-06 -2.19084584415321e-06 1.14132207419668e-06 3.93976936730097e-06 2.5072694476231e-05 1.06874114516832e-06 -1.78905168018673e-06 -2.43485646249745e-06 1.10256457118754e-06 -5.55461375813439e-06 1.06874114516832e-06 2.4028673547838e-05 3.57342790865243e-06 4.25647150856754e-05 4.78686519441574e-06 -2.29631940258299e-06 -1.78905168018673e-06 3.57342790865243e-06 7.29864077515757e-05 1306 1306 0 0 0 1366 1374 0 0 0 0 0 0 0 0 0 0 0 962 0 12 57 0 0 2766 +1279 1307 0.997029888989306 0.00365781438032706 0.0769286738214737 -0.025804949243238 -0.014560909173465 0.989809380225653 0.141652288161366 -0.0355206243170098 -0.0756265851801714 -0.142351716572958 0.986922797589922 0.0144851994519734 7.06872550296195e-05 -2.33740606882435e-05 4.30616855339689e-06 -3.44088316585899e-06 -4.24739378996405e-06 4.39578225405519e-06 -2.33740606882435e-05 5.61655668490197e-05 -3.00331744265798e-06 5.8903062868334e-06 -2.84056269096066e-06 2.07823935713636e-05 4.30616855339689e-06 -3.00331744265798e-06 1.33971969620755e-05 2.34819617216656e-06 -4.06422580330961e-06 -3.59904114735032e-06 -3.44088316585899e-06 5.8903062868334e-06 2.34819617216656e-06 3.16187272869904e-05 7.69841842906338e-06 4.11678245916467e-06 -4.24739378996405e-06 -2.84056269096066e-06 -4.06422580330961e-06 7.69841842906338e-06 3.42216991036933e-05 -3.2489030865337e-06 4.39578225405519e-06 2.07823935713636e-05 -3.59904114735032e-06 4.11678245916467e-06 -3.2489030865337e-06 5.76686698249046e-05 1316 1316 0 0 0 1378 1396 0 0 0 0 0 0 0 0 0 0 0 1060 0 20 69 0 0 2610 +1278 1304 0.996686967656762 0.00310361628757968 0.0812739568933917 -0.0231984308620099 -0.0148577412148705 0.989404568497331 0.144422461419969 -0.0332023537098155 -0.0799645923466215 -0.145151532553225 0.986172751888983 0.00268267738393676 9.46115194172126e-05 -6.32974387603734e-05 3.6392186710087e-06 -8.94493714371411e-06 -1.71503168151292e-06 1.9200784602688e-05 -6.32974387603734e-05 8.66271306584728e-05 -4.26905536102121e-07 8.10454299309602e-06 3.64944466124438e-06 2.0960349549778e-06 3.6392186710087e-06 -4.26905536102121e-07 1.47698174365746e-05 -9.02345170314427e-07 -5.60801154819593e-06 -6.4670588979188e-06 -8.94493714371411e-06 8.10454299309602e-06 -9.02345170314427e-07 2.90064086493914e-05 6.45234421733856e-06 -2.09108289048297e-06 -1.71503168151292e-06 3.64944466124438e-06 -5.60801154819593e-06 6.45234421733856e-06 2.73005687703504e-05 -2.25998703826984e-06 1.9200784602688e-05 2.0960349549778e-06 -6.4670588979188e-06 -2.09108289048297e-06 -2.25998703826984e-06 7.57521503912218e-05 1323 1327 0 0 0 1382 1406 0 0 11 0 0 0 0 0 0 0 0 1056 0 13 59 0 0 2770 +1279 1312 0.996089354440719 0.0024369256284765 0.0883179447414502 -0.0223917532052837 -0.0152614871287597 0.98933922888521 0.144827404863294 -0.0317345434061037 -0.0870234737326158 -0.145608899392513 0.98550746493226 0.0103419769025208 8.44339681697299e-05 -5.7154010537135e-05 6.70660226070132e-06 -2.08762387431336e-06 -1.69611375043236e-06 1.21816060947896e-05 -5.7154010537135e-05 9.22489635065724e-05 -6.09385155247031e-06 -7.15901995386742e-07 -7.3420156542363e-07 3.41157670338846e-06 6.70660226070132e-06 -6.09385155247031e-06 1.52406269918928e-05 4.93561886987224e-07 -3.52253484833667e-06 -1.05299236906424e-06 -2.08762387431336e-06 -7.15901995386742e-07 4.93561886987224e-07 3.24610261030256e-05 6.91838186258378e-06 7.9843514642591e-07 -1.69611375043236e-06 -7.3420156542363e-07 -3.52253484833667e-06 6.91838186258378e-06 3.3909859996205e-05 8.61253265780859e-06 1.21816060947896e-05 3.41157670338846e-06 -1.05299236906424e-06 7.9843514642591e-07 8.61253265780859e-06 7.03079437328774e-05 1320 1323 0 0 0 1372 1387 0 0 0 0 0 0 0 0 0 0 0 1058 0 14 70 0 0 2717 +1279 1281 0.999995246920611 -2.73996136182149e-05 -0.00308308051269329 -0.00327304274489168 3.48686637315002e-05 0.999997064975733 0.00242256560201361 -0.00108185350733718 0.00308300508641571 -0.00242266159026464 0.999992312865682 0.000585107918557704 5.98480392473732e-05 6.78842706821351e-06 7.45117512316369e-06 -3.30420715587087e-06 2.27760198773041e-06 1.51201505962384e-05 6.78842706821351e-06 3.43492759161263e-05 5.17836520379729e-06 -2.12592510389156e-06 -1.45703524813576e-06 1.49277655730948e-05 7.45117512316369e-06 5.17836520379729e-06 1.11768268091549e-05 -1.33239490890143e-07 -3.95622518413882e-06 1.49693210274839e-06 -3.30420715587087e-06 -2.12592510389156e-06 -1.33239490890143e-07 2.08074862077521e-05 -2.42203415186416e-06 1.89921684855154e-06 2.27760198773041e-06 -1.45703524813576e-06 -3.95622518413882e-06 -2.42203415186416e-06 1.62208238166731e-05 1.81033464636538e-07 1.51201505962384e-05 1.49277655730948e-05 1.49693210274839e-06 1.89921684855154e-06 1.81033464636538e-07 4.39096727726375e-05 1228 1228 0 0 0 1235 1307 0 0 0 0 0 0 0 0 0 0 0 793 0 0 0 0 0 3547 +1279 1282 0.999999116168883 0.00125527806841363 0.000438107776557757 -0.00477010462242943 -0.00125536420139247 0.999999192746958 0.000196382672344989 -0.00474283880993424 -0.000437860908032311 -0.000196932483594914 0.999999884747704 -0.0012417765024823 5.99050045597222e-05 2.60805315788057e-05 1.01341460620117e-05 -9.75745311062329e-06 -1.96323054221038e-06 2.6645107527933e-05 2.60805315788057e-05 4.84126233997754e-05 8.59814900210139e-06 -4.35867081086681e-06 -7.48073349258405e-07 1.60268391565937e-05 1.01341460620117e-05 8.59814900210139e-06 1.29254885553198e-05 -3.58530369708676e-06 -5.42653292203555e-06 4.43699590891509e-06 -9.75745311062329e-06 -4.35867081086681e-06 -3.58530369708676e-06 3.15597044122364e-05 5.27671003670503e-06 -2.17681590950048e-06 -1.96323054221038e-06 -7.48073349258405e-07 -5.42653292203555e-06 5.27671003670503e-06 2.38819160605645e-05 -2.93176181174802e-06 2.6645107527933e-05 1.60268391565937e-05 4.43699590891509e-06 -2.17681590950048e-06 -2.93176181174802e-06 5.92894922362914e-05 1312 1312 0 0 0 1328 1383 0 0 0 0 0 0 0 0 0 0 0 783 0 7 24 0 0 3440 +1279 1283 0.999986639105952 0.0017451653686217 0.00486579977179311 -0.00438426328952185 -0.00178963763443187 0.999956532370252 0.00915044081993415 -0.00304510943265 -0.00484961923458362 -0.00915902658025707 0.999946295270592 -0.0033491258620946 6.20834854228424e-05 9.85724609130838e-06 1.33793059899944e-06 -3.31668698851778e-06 -2.26688460118292e-06 9.22932797635287e-06 9.85724609130838e-06 3.38260980259098e-05 2.97234819361101e-06 3.78248016114122e-06 8.94877209668853e-07 1.092387999512e-05 1.33793059899944e-06 2.97234819361101e-06 1.19721234784238e-05 6.12355354608324e-07 -4.32701276949396e-06 1.62740139706072e-07 -3.31668698851778e-06 3.78248016114122e-06 6.12355354608324e-07 2.86535199887242e-05 3.46168800608254e-06 4.25498876760078e-06 -2.26688460118292e-06 8.94877209668853e-07 -4.32701276949396e-06 3.46168800608254e-06 2.73187758035385e-05 1.63822726799122e-06 9.22932797635287e-06 1.092387999512e-05 1.62740139706072e-07 4.25498876760078e-06 1.63822726799122e-06 5.89891219215268e-05 1319 1319 0 0 0 1333 1393 0 0 0 0 0 0 0 0 0 0 0 789 0 3 21 0 0 3412 +1279 1310 0.996554765069331 0.00291087566686472 0.0828862293777638 -0.0232854197007224 -0.0148329552475628 0.989526393512598 0.1435879520732 -0.0306755373998151 -0.0816001449522917 -0.144322705576094 0.986160419505347 0.00483815940064782 0.000112933406607079 -4.85907285500608e-05 7.67629557117148e-06 -3.58144721181965e-06 -1.30202075785682e-07 -3.80353527622204e-06 -4.85907285500608e-05 6.35223737706104e-05 -5.40054107702376e-06 6.31753784346828e-06 2.25247093940282e-06 2.27691701409194e-05 7.67629557117148e-06 -5.40054107702376e-06 1.35831869287759e-05 3.06055283496979e-06 -2.78236957219471e-06 -4.24427794869694e-06 -3.58144721181965e-06 6.31753784346828e-06 3.06055283496979e-06 2.59431265190372e-05 -1.39469349000073e-06 6.62728603686397e-06 -1.30202075785682e-07 2.25247093940282e-06 -2.78236957219471e-06 -1.39469349000073e-06 2.63302730720947e-05 1.49009141824296e-06 -3.80353527622204e-06 2.27691701409194e-05 -4.24427794869694e-06 6.62728603686397e-06 1.49009141824296e-06 6.75992026995233e-05 1324 1324 0 0 0 1381 1402 0 0 1 0 0 0 0 0 0 0 0 1062 0 16 60 0 0 2537 +1279 1313 0.996704487248041 0.00297388214473121 0.0810636856095768 -0.0224490966914178 -0.0145326616164073 0.989705995753086 0.142375713226435 -0.0317306389724764 -0.0798058070942338 -0.143084583360271 0.986487625446288 0.0160482479929553 8.9018969530005e-05 -3.63118704565356e-05 4.08701911664384e-06 -1.84578983316485e-06 -1.64456665563101e-06 4.80925538012991e-06 -3.63118704565356e-05 5.56380734936043e-05 -1.19244868909298e-06 2.479858829072e-06 6.2238392672703e-06 1.68177931133338e-05 4.08701911664384e-06 -1.19244868909298e-06 1.32975613725148e-05 5.34043373064175e-07 -4.65568140967974e-06 -3.08924508492469e-06 -1.84578983316485e-06 2.479858829072e-06 5.34043373064175e-07 3.37186162826459e-05 8.14241975040131e-06 6.74615112941747e-06 -1.64456665563101e-06 6.2238392672703e-06 -4.65568140967974e-06 8.14241975040131e-06 2.98334611667535e-05 1.92183627322505e-06 4.80925538012991e-06 1.68177931133338e-05 -3.08924508492469e-06 6.74615112941747e-06 1.92183627322505e-06 6.24091297081416e-05 1324 1325 0 0 0 1375 1386 0 0 0 0 0 0 0 0 0 0 0 1073 0 12 71 0 0 2769 +1279 1314 0.996832324357879 0.00305112618061901 0.0794733146678696 -0.0271623388538338 -0.0138995180683307 0.990568490689175 0.136311659997367 -0.0340741264932866 -0.0783078572860759 -0.136984509645433 0.987473100192843 0.0129945528420948 0.000126159098568993 -5.51435129479483e-05 1.64793602020336e-06 -2.8527198742357e-06 -7.43218941748683e-07 5.47668723378941e-06 -5.51435129479483e-05 8.40280786880676e-05 1.12851384715189e-06 7.49450693958043e-06 4.80402252545052e-06 2.73071958286438e-05 1.64793602020336e-06 1.12851384715189e-06 1.50727361156082e-05 1.88553069956517e-06 -5.34386392933323e-06 -4.03991621322743e-09 -2.8527198742357e-06 7.49450693958043e-06 1.88553069956517e-06 3.72254790040064e-05 5.49181549182634e-06 4.12172670108679e-06 -7.43218941748683e-07 4.80402252545052e-06 -5.34386392933323e-06 5.49181549182634e-06 3.21469839713767e-05 1.9347319330721e-06 5.47668723378941e-06 2.73071958286438e-05 -4.03991621322743e-09 4.12172670108679e-06 1.9347319330721e-06 7.59936756444395e-05 1301 1301 0 0 0 1359 1363 0 0 0 0 0 0 0 0 0 0 0 1068 0 14 68 0 0 2537 +1279 1305 0.996699556988523 0.00275854394886346 0.081131889748507 -0.0234025998066774 -0.0144881197192468 0.989421430440488 0.144344474685036 -0.0317524322453587 -0.0798754498321135 -0.145043522504042 0.986195867509967 0.00598742467759794 9.33298125437658e-05 -4.001709861486e-05 1.35324759341931e-06 1.940540506557e-06 -1.27651847138064e-06 1.39223899134939e-05 -4.001709861486e-05 5.33360348570262e-05 -1.94574452506433e-06 2.31852330788164e-06 -6.53940275179239e-08 1.02976675674106e-05 1.35324759341931e-06 -1.94574452506433e-06 1.39183652071815e-05 -1.909216668732e-06 -5.97428602260644e-06 -1.43685921573609e-07 1.940540506557e-06 2.31852330788164e-06 -1.909216668732e-06 3.36089986176186e-05 7.66536135183916e-06 3.25861303505727e-06 -1.27651847138064e-06 -6.53940275179239e-08 -5.97428602260644e-06 7.66536135183916e-06 2.814884100788e-05 7.84650940577996e-06 1.39223899134939e-05 1.02976675674106e-05 -1.43685921573609e-07 3.25861303505727e-06 7.84650940577996e-06 7.83496830508188e-05 1209 1209 0 0 0 1271 1281 0 0 0 0 0 0 0 0 0 0 0 966 0 11 51 0 0 2711 +1279 1318 0.996824549610776 0.00356995470209895 0.0795491842616811 -0.0273974024622508 -0.0151564596656901 0.989237729106665 0.145530055460342 -0.0365612916529755 -0.0781735186855257 -0.146273615991787 0.986150561649189 0.0167306343866316 9.80097974990875e-05 -4.53284982759933e-05 4.38402519156942e-06 -2.66467198709746e-06 4.81655738877077e-06 1.67326818236479e-05 -4.53284982759933e-05 6.12761108132784e-05 -1.02997991895622e-06 1.90196200605548e-06 3.89300424782885e-06 8.84605195949626e-06 4.38402519156942e-06 -1.02997991895622e-06 1.48101500359019e-05 3.10539107965845e-06 -4.38670738192752e-06 -2.63010590848506e-06 -2.66467198709746e-06 1.90196200605548e-06 3.10539107965845e-06 3.36187849401063e-05 1.09110508992623e-05 6.64755923460306e-06 4.81655738877077e-06 3.89300424782885e-06 -4.38670738192752e-06 1.09110508992623e-05 3.85095545457894e-05 5.5865183448434e-06 1.67326818236479e-05 8.84605195949626e-06 -2.63010590848506e-06 6.64755923460306e-06 5.5865183448434e-06 6.72479184616571e-05 1314 1314 0 0 0 1377 1394 0 0 0 0 0 0 0 0 0 0 0 1071 0 23 76 0 0 2777 +1279 1315 0.996372720432905 0.00307416987168352 0.0850408810909868 -0.0278896535734723 -0.015509407783216 0.989169417021105 0.145956578133158 -0.0355424461107856 -0.0836711434566616 -0.146746086522697 0.985629101560485 0.00557341520306315 9.6907456142242e-05 -3.58458669044988e-05 1.22833026448126e-06 5.98578832660306e-06 1.28973359651058e-06 -1.7258804667811e-06 -3.58458669044988e-05 8.33471439705741e-05 -1.21909098052737e-06 7.13103463317629e-06 -1.76339393483438e-07 3.42881044522634e-05 1.22833026448126e-06 -1.21909098052737e-06 1.44634913060488e-05 1.33818833168596e-06 -4.04560499758908e-06 -1.1205193754248e-06 5.98578832660306e-06 7.13103463317629e-06 1.33818833168596e-06 3.62458202163435e-05 2.34745235916317e-06 8.62143891368858e-06 1.28973359651058e-06 -1.76339393483438e-07 -4.04560499758908e-06 2.34745235916317e-06 3.1167986510178e-05 5.320182357843e-06 -1.7258804667811e-06 3.42881044522634e-05 -1.1205193754248e-06 8.62143891368858e-06 5.320182357843e-06 9.15002800973672e-05 1193 1193 0 0 0 1261 1268 0 0 0 0 0 0 0 0 0 0 0 1064 0 14 58 0 0 2764 +1280 1282 0.999998104714747 0.00119656781595018 -0.00153583605119277 -0.00272544801217078 -0.00120221328427469 0.999992505440525 -0.00368018287608136 -0.00420049237646604 0.00153142095239181 0.00368202230358824 0.9999920486992 0.00413235332118746 4.0244766450708e-05 6.95104017937365e-06 4.19080011962011e-06 1.85880148598142e-06 2.84823561967144e-08 1.64905202798384e-05 6.95104017937365e-06 2.95465557185797e-05 1.92817773146479e-06 1.92089794219471e-06 -4.68339007119374e-06 1.20769837728726e-05 4.19080011962011e-06 1.92817773146479e-06 1.19758087119006e-05 2.56954548170438e-06 -2.76924064526721e-06 1.02350725719767e-06 1.85880148598142e-06 1.92089794219471e-06 2.56954548170438e-06 1.86133802524492e-05 -1.21407730458128e-06 2.12189468600947e-06 2.84823561967144e-08 -4.68339007119374e-06 -2.76924064526721e-06 -1.21407730458128e-06 2.11595423351946e-05 -3.17048409845671e-06 1.64905202798384e-05 1.20769837728726e-05 1.02350725719767e-06 2.12189468600947e-06 -3.17048409845671e-06 3.42543227951732e-05 1305 1305 0 0 0 1345 1413 0 0 0 0 0 0 0 0 0 0 0 789 0 0 11 0 0 3427 +1280 1283 0.999984945389762 0.00187407209637647 -0.00515721316327904 -0.003458979816368 -0.00186697030639211 0.999997302895473 0.00138152946188883 -0.00638802135307467 0.00515978833955092 -0.00137188029966167 0.999985747162796 0.00508874428111385 5.12620025966356e-05 2.70948833485649e-05 3.5872132758231e-06 -4.76864234402915e-06 -3.83592380374257e-07 1.46249468367126e-05 2.70948833485649e-05 5.5953685029203e-05 -8.13104292767082e-07 -1.54100159308458e-06 -8.35210298223135e-06 1.22317953581522e-05 3.5872132758231e-06 -8.13104292767082e-07 1.33989620109796e-05 1.90365903330777e-06 -1.13115212306967e-06 1.0899190343961e-06 -4.76864234402915e-06 -1.54100159308458e-06 1.90365903330777e-06 1.91693400254845e-05 7.0935316861643e-07 -5.13656414709524e-06 -3.83592380374257e-07 -8.35210298223135e-06 -1.13115212306967e-06 7.0935316861643e-07 2.5779099989386e-05 -2.73065262784821e-06 1.46249468367126e-05 1.22317953581522e-05 1.0899190343961e-06 -5.13656414709524e-06 -2.73065262784821e-06 4.5880941067213e-05 1311 1311 0 0 0 1352 1418 0 0 0 0 0 0 0 0 0 0 0 787 0 0 8 0 0 3501 +1279 1316 0.996270072180952 0.0023570231974669 0.0862576820822835 -0.0253804491867527 -0.0150846883116655 0.988991340170125 0.147202517801289 -0.0326980169065019 -0.084961140853343 -0.147954633283806 0.985338028817904 0.00579258893281521 0.00014722706048251 -4.99598961993895e-05 6.34185949422199e-06 -3.35586768297744e-07 1.35070029739921e-06 2.04003192635241e-05 -4.99598961993895e-05 7.95223916330978e-05 -3.78595849571515e-06 4.38865704553218e-06 -5.67365292157268e-06 1.12963938821837e-05 6.34185949422199e-06 -3.78595849571515e-06 1.38501055697001e-05 2.24803420327237e-06 -6.17792588332031e-06 -7.28347089931989e-06 -3.35586768297744e-07 4.38865704553218e-06 2.24803420327237e-06 2.99545691102008e-05 -2.05695105650828e-06 -2.31147021056148e-07 1.35070029739921e-06 -5.67365292157268e-06 -6.17792588332031e-06 -2.05695105650828e-06 2.68094573150099e-05 -9.47541495197369e-06 2.04003192635241e-05 1.12963938821837e-05 -7.28347089931989e-06 -2.31147021056148e-07 -9.47541495197369e-06 0.000161684873744896 1208 1208 0 0 0 1274 1282 0 0 0 0 0 0 0 0 0 0 0 1056 0 11 50 0 0 2790 +1279 1306 0.996740452407777 0.00325601531150792 0.0806093598673966 -0.0220264181530621 -0.015156129251758 0.98895183680296 0.147460354774277 -0.0316403424132873 -0.0792386413313872 -0.148201426606976 0.985777649813391 0.0127398154187402 0.000114727639595697 -4.59772610715662e-05 4.51599923974561e-06 -7.59040778163014e-06 -1.03317134985696e-05 1.65158307431873e-05 -4.59772610715662e-05 7.05608213303993e-05 -2.80056864614259e-07 2.72074596724938e-06 1.20313768108233e-06 1.54247987467143e-05 4.51599923974561e-06 -2.80056864614259e-07 1.42707405315829e-05 1.52956462804373e-07 -4.47509464349433e-06 -2.08597645818335e-06 -7.59040778163014e-06 2.72074596724938e-06 1.52956462804373e-07 3.06116117916446e-05 6.85840325391929e-06 5.69000213885983e-06 -1.03317134985696e-05 1.20313768108233e-06 -4.47509464349433e-06 6.85840325391929e-06 3.17882207621992e-05 -2.64996468802183e-06 1.65158307431873e-05 1.54247987467143e-05 -2.08597645818335e-06 5.69000213885983e-06 -2.64996468802183e-06 7.47488017112261e-05 1325 1328 0 0 0 1379 1391 0 0 0 0 0 0 0 0 0 0 0 1056 0 13 70 0 0 2797 +1280 1284 0.999990263870906 0.00201187459518698 -0.00392740677909998 -0.00274714975007877 -0.00200817367320101 0.999997536112452 0.000946048372452554 -0.00505724118314748 0.00392930043309767 -0.000938152246705731 0.999991840200943 0.00300229306548587 5.7986161427899e-05 1.00839782502272e-05 -1.24067968661277e-06 1.59676485614195e-06 -1.60293700546623e-06 1.05492929043774e-05 1.00839782502272e-05 4.63748150022439e-05 -3.75954329856644e-06 4.23420945425409e-06 -6.22948826224706e-06 1.60951461895312e-05 -1.24067968661277e-06 -3.75954329856644e-06 1.2113819498119e-05 3.99762103961477e-07 -3.34972373584136e-06 -1.18574566569047e-06 1.59676485614195e-06 4.23420945425409e-06 3.99762103961477e-07 2.31394589656271e-05 3.26586941485489e-06 -1.08052151873735e-06 -1.60293700546623e-06 -6.22948826224706e-06 -3.34972373584136e-06 3.26586941485489e-06 2.47957641972431e-05 -1.50492133259559e-06 1.05492929043774e-05 1.60951461895312e-05 -1.18574566569047e-06 -1.08052151873735e-06 -1.50492133259559e-06 4.20046618839155e-05 1259 1259 0 0 0 1277 1352 0 0 0 0 0 0 0 0 0 0 0 793 0 0 0 0 0 3442 +1280 1309 0.996232010437141 0.00193180012673551 0.0867066867585357 -0.0189068345771166 -0.0143909668434741 0.989574639138532 0.143300152292848 -0.0307085076837647 -0.0855259110076152 -0.144007991868902 0.98587373269816 0.00800047839778825 7.52121592303374e-05 -3.1754017486853e-05 4.90865220844225e-06 -6.31023972833427e-06 -4.51020026815669e-06 1.34794703913751e-05 -3.1754017486853e-05 4.85020250242816e-05 -6.04088427427393e-06 3.04787642397753e-06 8.05136283727979e-07 5.32405736833999e-06 4.90865220844225e-06 -6.04088427427393e-06 1.49640463710965e-05 1.8995455780249e-06 -4.12847890044657e-06 -4.42815771444631e-06 -6.31023972833427e-06 3.04787642397753e-06 1.8995455780249e-06 2.2174342865441e-05 -1.31956522287599e-06 -4.74231186990877e-06 -4.51020026815669e-06 8.05136283727979e-07 -4.12847890044657e-06 -1.31956522287599e-06 2.64691704129232e-05 -4.45401854146575e-06 1.34794703913751e-05 5.32405736833999e-06 -4.42815771444631e-06 -4.74231186990877e-06 -4.45401854146575e-06 5.95833556313123e-05 1316 1316 0 0 0 1381 1394 0 0 0 0 0 0 0 0 0 0 0 964 0 16 70 0 0 2643 +1279 1317 0.996590113222392 0.00319608423431143 0.0824495680579733 -0.024117540812399 -0.0151269005133128 0.989390619010764 0.144490068497312 -0.0349323904088917 -0.0811130267481094 -0.145244580136626 0.986065255869355 0.0112763267043852 0.000101642859669264 -3.86012956601803e-05 2.91075230163007e-06 3.91246544986573e-07 -1.4442066138164e-06 1.99211426129173e-05 -3.86012956601803e-05 5.80111934908903e-05 1.17170961492127e-06 -2.48319751852464e-06 -4.06471525727424e-07 8.97065842707448e-06 2.91075230163007e-06 1.17170961492127e-06 1.42844079899422e-05 2.3116563640678e-06 -6.24646302039647e-06 -1.65981574696142e-06 3.91246544986573e-07 -2.48319751852464e-06 2.3116563640678e-06 2.89075729959856e-05 -1.79465831952939e-06 4.80551811778632e-06 -1.4442066138164e-06 -4.06471525727424e-07 -6.24646302039647e-06 -1.79465831952939e-06 2.4353718486357e-05 1.08978452949677e-06 1.99211426129173e-05 8.97065842707448e-06 -1.65981574696142e-06 4.80551811778632e-06 1.08978452949677e-06 6.16801088956623e-05 1298 1298 0 0 0 1360 1365 0 0 0 0 0 0 0 0 0 0 0 961 0 14 71 0 0 2793 +1280 1308 0.996577952298496 0.00274977403583246 0.0826124913998435 -0.0201290380264877 -0.0141039086171434 0.990446798022689 0.137172227685935 -0.0338634379400122 -0.0814460849535239 -0.13786797680881 0.987096224395772 0.00622616925632708 9.47641371283401e-05 -3.87292833015821e-05 1.37276112009527e-07 -1.50489501203355e-06 -3.22182922368882e-06 2.10145772896337e-05 -3.87292833015821e-05 6.0247906585112e-05 -1.67651091223945e-06 6.96057196955485e-06 4.45574164038457e-07 1.58052536568461e-05 1.37276112009527e-07 -1.67651091223945e-06 1.28986417888574e-05 -1.9363349766462e-06 -6.41710458554788e-06 -2.8374848285787e-06 -1.50489501203355e-06 6.96057196955485e-06 -1.9363349766462e-06 3.34526470346407e-05 7.44805348074223e-06 2.98791454789098e-06 -3.22182922368882e-06 4.45574164038457e-07 -6.41710458554788e-06 7.44805348074223e-06 2.59075262878719e-05 1.03209482039627e-07 2.10145772896337e-05 1.58052536568461e-05 -2.8374848285787e-06 2.98791454789098e-06 1.03209482039627e-07 7.21420793723659e-05 1231 1231 0 0 0 1283 1298 0 0 0 0 0 0 0 0 0 0 0 1072 0 8 46 0 0 2813 +1280 1310 0.996622875192304 0.00323534375118182 0.0820510645527377 -0.0216482262854693 -0.0144444675774946 0.990549956679551 0.13638966485237 -0.0342424831871824 -0.0808344109883195 -0.137114243873315 0.987251478665502 1.04941079382293e-05 9.56266778855711e-05 -5.73393632795553e-05 2.56508760436316e-06 -3.77160571235089e-06 3.12119052295365e-06 1.36074076496871e-05 -5.73393632795553e-05 7.64679745409288e-05 -3.68549421945837e-06 5.41646722323662e-06 -2.66994913926059e-06 8.86106006375762e-06 2.56508760436316e-06 -3.68549421945837e-06 1.41402465423325e-05 1.57711072292429e-06 -7.02231525172638e-07 -4.02179938700821e-06 -3.77160571235089e-06 5.41646722323662e-06 1.57711072292429e-06 2.6821538589395e-05 1.54170268111089e-06 3.75851218982598e-06 3.12119052295365e-06 -2.66994913926059e-06 -7.02231525172638e-07 1.54170268111089e-06 2.77850016168426e-05 -2.78632087368817e-06 1.36074076496871e-05 8.86106006375762e-06 -4.02179938700821e-06 3.75851218982598e-06 -2.78632087368817e-06 7.88704012340576e-05 1326 1330 0 0 0 1383 1397 0 0 0 0 0 0 0 0 0 0 0 1060 0 16 69 0 0 2579 +1280 1311 0.996306632192465 0.00107650324398167 0.0858599778131442 -0.0199322947036938 -0.0131325904073818 0.990067902834163 0.13997529370126 -0.0326403863876024 -0.0848565243131007 -0.140585877378661 0.986425355190737 0.0125786182908397 0.000148487290427767 -7.8312333571954e-05 -4.31195265187881e-07 -6.24944886200243e-07 -1.04045177354705e-05 2.98509478426159e-05 -7.8312333571954e-05 0.000102800148645701 -8.67118414141937e-07 2.02155099653516e-06 2.21787881381514e-06 -6.82736104922911e-07 -4.31195265187881e-07 -8.67118414141937e-07 1.52588986940592e-05 3.03220134411147e-06 -3.64779245932224e-06 -6.12448552637655e-06 -6.24944886200243e-07 2.02155099653516e-06 3.03220134411147e-06 2.6900496963035e-05 3.5424532402422e-07 -3.74927434355024e-06 -1.04045177354705e-05 2.21787881381514e-06 -3.64779245932224e-06 3.5424532402422e-07 2.5722348511707e-05 -3.41832003843026e-06 2.98509478426159e-05 -6.82736104922911e-07 -6.12448552637655e-06 -3.74927434355024e-06 -3.41832003843026e-06 6.60389215736983e-05 1296 1296 0 0 0 1384 1414 0 0 0 0 0 0 0 0 0 0 0 969 0 9 48 0 0 2822 +1280 1307 0.997053050362917 0.0040028068210984 0.0766106539559292 -0.0225074021892755 -0.0147883430831607 0.989936033262045 0.140740736669456 -0.0365186622748506 -0.0752762889019969 -0.141458925441131 0.987077936508655 0.014847907103016 9.96827723530323e-05 -4.9416223095925e-05 4.4559871692114e-06 -4.58294138666772e-06 1.11130596104414e-06 2.46633756948374e-05 -4.9416223095925e-05 7.28626887525074e-05 -4.86572467407572e-06 9.75864704629241e-06 1.22876621395624e-06 -3.20123604238657e-06 4.4559871692114e-06 -4.86572467407572e-06 1.29493365086162e-05 1.36382309630929e-06 -3.49422129642538e-06 -5.81648538833175e-06 -4.58294138666772e-06 9.75864704629241e-06 1.36382309630929e-06 3.37339664533603e-05 1.30470635179875e-05 1.12357799067304e-06 1.11130596104414e-06 1.22876621395624e-06 -3.49422129642538e-06 1.30470635179875e-05 3.47250017911164e-05 1.88652149176697e-06 2.46633756948374e-05 -3.20123604238657e-06 -5.81648538833175e-06 1.12357799067304e-06 1.88652149176697e-06 8.37455169794233e-05 1326 1328 0 0 0 1384 1391 0 0 0 0 0 0 0 0 0 0 0 1065 0 20 79 0 0 2650 +1280 1315 0.996364934595979 0.00238271035724727 0.0851542118682617 -0.0229633581077075 -0.0143556647585836 0.990009222314663 0.140269934844413 -0.0344085728736289 -0.0839692324419516 -0.140982489775398 0.98644467943207 0.00643263156599157 0.000112915753164265 -6.13523819848706e-05 2.96891909502143e-06 -4.1665946322065e-06 2.10117645055388e-06 3.88537340758015e-05 -6.13523819848706e-05 8.29010627088853e-05 -4.56269196334558e-06 6.94237193588605e-06 -4.89699751242373e-06 -1.04114222976636e-05 2.96891909502143e-06 -4.56269196334558e-06 1.38915978611934e-05 6.90824683013938e-07 -6.25544277898357e-06 -4.99632194143825e-06 -4.1665946322065e-06 6.94237193588605e-06 6.90824683013938e-07 3.55119536142327e-05 1.05019458683831e-06 9.16213973910139e-06 2.10117645055388e-06 -4.89699751242373e-06 -6.25544277898357e-06 1.05019458683831e-06 2.92311919426859e-05 4.9861035546987e-06 3.88537340758015e-05 -1.04114222976636e-05 -4.99632194143825e-06 9.16213973910139e-06 4.9861035546987e-06 9.46689609032619e-05 1216 1216 0 0 0 1271 1285 0 0 0 0 0 0 0 0 0 0 0 1067 0 10 50 0 0 2816 +1280 1318 0.996679397413044 0.00404045377746979 0.0813256017847024 -0.022551256362508 -0.0152987984883358 0.990273047951799 0.138294024690393 -0.0380826179615209 -0.0799757809413897 -0.139078989187893 0.98704655879512 0.01805070003104 0.000150259720714691 -8.79596037300941e-05 -6.11812918230298e-06 -5.05654367975147e-06 -2.901296542819e-06 4.42188123730455e-05 -8.79596037300941e-05 8.47424845363327e-05 4.24492852438219e-06 -7.48201298009947e-07 3.27117664610513e-06 -1.65618030817245e-05 -6.11812918230298e-06 4.24492852438219e-06 1.3862468924766e-05 1.53857862045837e-06 -4.4223349530999e-06 -3.71944099390261e-06 -5.05654367975147e-06 -7.48201298009947e-07 1.53857862045837e-06 2.98730750935299e-05 4.81780849470253e-06 -1.55544467798131e-06 -2.901296542819e-06 3.27117664610513e-06 -4.4223349530999e-06 4.81780849470253e-06 3.14899155440658e-05 -2.99816459250555e-06 4.42188123730455e-05 -1.65618030817245e-05 -3.71944099390261e-06 -1.55544467798131e-06 -2.99816459250555e-06 7.89528362945613e-05 1322 1325 0 0 0 1383 1393 0 0 0 0 0 0 0 0 0 0 0 1078 0 18 80 0 0 2831 +1281 1284 0.999991472948602 0.00309736217883682 0.00273136918398384 -0.00178547422282068 -0.00309605521258664 0.999995090757276 -0.000482600732665268 -0.00544579760466554 -0.00273285056428639 0.000474140147704444 0.999996153352058 0.00163564263314929 4.40647048792377e-05 8.56151827291973e-06 2.39111536329138e-06 -1.22987709230046e-06 1.58475479302368e-06 1.01223014459057e-05 8.56151827291973e-06 3.74573614333277e-05 -9.1305217959319e-08 1.84363188441374e-06 -5.46761383535487e-06 1.84704035948206e-05 2.39111536329138e-06 -9.1305217959319e-08 1.43297808233011e-05 6.29305245436586e-07 -7.05299028131821e-07 2.43691315217234e-07 -1.22987709230046e-06 1.84363188441374e-06 6.29305245436586e-07 2.1689938595927e-05 8.02167992058824e-07 -2.11875535313096e-06 1.58475479302368e-06 -5.46761383535487e-06 -7.05299028131821e-07 8.02167992058824e-07 2.53741203101984e-05 -3.74624993682671e-06 1.01223014459057e-05 1.84704035948206e-05 2.43691315217234e-07 -2.11875535313096e-06 -3.74624993682671e-06 4.63710974789322e-05 1241 1241 0 0 0 1266 1320 0 0 0 0 0 0 0 0 0 0 0 791 0 0 4 0 0 3462 +1280 1317 0.996427472283159 0.00344265355487558 0.0843827032981024 -0.0190519198989488 -0.0151179558633002 0.990300532553941 0.138116988940157 -0.0350236217227207 -0.0830887470714885 -0.138899256153088 0.986814702337885 0.0104048443477239 9.28203690776065e-05 -5.76441681868093e-05 -4.3514042440644e-06 -1.57071927380008e-06 4.44876875950044e-06 1.25187791958796e-05 -5.76441681868093e-05 7.23463634781726e-05 1.9873358783524e-06 3.62538753050052e-06 -2.26180989380928e-06 1.89342604237596e-05 -4.3514042440644e-06 1.9873358783524e-06 1.36902675286908e-05 2.93986965856578e-06 -4.82930891238179e-06 -4.54378577905926e-06 -1.57071927380008e-06 3.62538753050052e-06 2.93986965856578e-06 2.9889873557571e-05 2.69387432260084e-06 9.26806994024873e-06 4.44876875950044e-06 -2.26180989380928e-06 -4.82930891238179e-06 2.69387432260084e-06 2.94798981695751e-05 -2.9724544210336e-06 1.25187791958796e-05 1.89342604237596e-05 -4.54378577905926e-06 9.26806994024873e-06 -2.9724544210336e-06 7.31043523085465e-05 1286 1286 0 0 0 1377 1403 0 0 0 0 0 0 0 0 0 0 0 970 0 12 55 0 0 2824 +1280 1312 0.995943245183876 0.00258924740009123 0.0899463627419712 -0.0186454694786699 -0.0152058059517544 0.990053381860487 0.139868096905516 -0.0338109539861591 -0.0886895475124704 -0.140668393267693 0.986076349628932 0.00627598173307051 7.02500748756646e-05 -2.73796486331337e-05 4.40049326100357e-06 -1.68919555151057e-06 -2.34106678317264e-06 8.82509997648174e-06 -2.73796486331337e-05 4.90045276591102e-05 -5.31490743504712e-06 6.7988245623574e-06 6.19723073791329e-06 1.33196998195315e-05 4.40049326100357e-06 -5.31490743504712e-06 1.28482978591911e-05 -2.09196116472438e-07 -6.08586832121788e-06 -4.75352793012021e-06 -1.68919555151057e-06 6.7988245623574e-06 -2.09196116472438e-07 2.88343035972589e-05 5.73484254577555e-06 5.44610383887644e-06 -2.34106678317264e-06 6.19723073791329e-06 -6.08586832121788e-06 5.73484254577555e-06 2.57006904996479e-05 5.67571998854446e-06 8.82509997648174e-06 1.33196998195315e-05 -4.75352793012021e-06 5.44610383887644e-06 5.67571998854446e-06 6.16210409213625e-05 1308 1308 0 0 0 1372 1383 0 0 0 0 0 0 0 0 0 0 0 1062 0 20 80 0 0 2785 +1280 1316 0.996065030847707 0.00259305215869025 0.0885874167297954 -0.0201546668706381 -0.0152320203812154 0.989706803176078 0.142296975730666 -0.0341600941093667 -0.0873065855331793 -0.143086406857849 0.985851834859097 0.0055096762066358 6.28360892986777e-05 -3.49270125380901e-05 7.82881639725582e-07 -1.33508068413966e-06 -2.10870801069123e-06 -1.65011462264455e-06 -3.49270125380901e-05 5.75857783928039e-05 -5.97041755931143e-07 1.46161017332833e-06 2.00807802811847e-06 2.45942433852204e-05 7.82881639725582e-07 -5.97041755931143e-07 1.49533938197487e-05 4.31563909084684e-07 -3.38277513474176e-06 -2.05558844338921e-06 -1.33508068413966e-06 1.46161017332833e-06 4.31563909084684e-07 2.91308445072641e-05 1.34130833257583e-06 6.11768515656426e-06 -2.10870801069123e-06 2.00807802811847e-06 -3.38277513474176e-06 1.34130833257583e-06 2.88940208469826e-05 8.04567854666119e-07 -1.65011462264455e-06 2.45942433852204e-05 -2.05558844338921e-06 6.11768515656426e-06 8.04567854666119e-07 5.87365066387628e-05 1235 1235 0 0 0 1283 1298 0 0 0 0 0 0 0 0 0 0 0 1062 0 10 47 0 0 2828 +1280 1306 0.996550312662125 0.00340454878968413 0.0829209465729869 -0.0178626095274324 -0.0153735907659207 0.989438333467819 0.144136868882976 -0.0320720360108591 -0.0815544421842458 -0.144914434450005 0.986077420717081 0.00957007965296263 8.74584599967022e-05 -4.71484009024023e-05 2.05018556956229e-06 -9.65467386660961e-07 -1.94881258839291e-06 1.53789640772997e-05 -4.71484009024023e-05 6.65175887953682e-05 5.0556313171728e-07 2.54468096488149e-07 -2.00914371770451e-06 9.81878506060271e-06 2.05018556956229e-06 5.0556313171728e-07 1.38236816734853e-05 1.2049433723329e-07 -3.81365119047745e-06 -1.92585012444684e-06 -9.65467386660961e-07 2.54468096488149e-07 1.2049433723329e-07 2.65122694916993e-05 7.14021246460953e-06 -8.77726657003939e-08 -1.94881258839291e-06 -2.00914371770451e-06 -3.81365119047745e-06 7.14021246460953e-06 2.99630682990892e-05 -3.11641081229192e-06 1.53789640772997e-05 9.81878506060271e-06 -1.92585012444684e-06 -8.77726657003939e-08 -3.11641081229192e-06 7.14652745734704e-05 1313 1313 0 0 0 1377 1389 0 0 0 0 0 0 0 0 0 0 0 1060 0 18 75 0 0 2826 +1281 1285 0.999976251859506 0.00457216817880167 0.00515664572749644 -0.00335304238409025 -0.00461328291784902 0.999957440688414 0.00798964533610224 -0.00553805323233048 -0.00511989626203854 -0.00801324466253035 0.999954786263981 -0.00521336012213663 5.10997113541114e-05 1.59562357814884e-05 4.01803648359769e-06 -9.28327839774209e-07 -1.496657589195e-06 1.15854473918758e-05 1.59562357814884e-05 4.32987490516196e-05 5.08797182907837e-06 -1.01812365201108e-06 -4.32549474753733e-06 6.70144144047229e-06 4.01803648359769e-06 5.08797182907837e-06 1.1756405432674e-05 -1.16155644000681e-06 -5.29473606611189e-06 2.22287519445512e-06 -9.28327839774209e-07 -1.01812365201108e-06 -1.16155644000681e-06 2.59553613068939e-05 2.23383883088513e-06 1.19629035509757e-06 -1.496657589195e-06 -4.32549474753733e-06 -5.29473606611189e-06 2.23383883088513e-06 1.87318268799067e-05 -2.29687244532777e-06 1.15854473918758e-05 6.70144144047229e-06 2.22287519445512e-06 1.19629035509757e-06 -2.29687244532777e-06 4.87829016652128e-05 1315 1315 0 0 0 1336 1389 0 0 0 0 0 0 0 0 0 0 0 838 0 0 19 0 0 3522 +1280 1313 0.996573401058787 0.00260488095180956 0.0826720684230693 -0.018653172136375 -0.0143045102701056 0.989871353002521 0.141244771552406 -0.0326950823371444 -0.0814667864105011 -0.141943365819561 0.986516722418713 0.0143356848209035 9.1985211380832e-05 -5.45746485829247e-05 4.48116351298099e-06 -5.36242828738882e-06 -8.56305101905853e-07 2.90220251284886e-05 -5.45746485829247e-05 8.18308417293131e-05 -2.82216848372629e-06 6.00149456218838e-06 2.23346005222378e-06 -2.09660995830607e-06 4.48116351298099e-06 -2.82216848372629e-06 1.40208667013974e-05 -1.06977237838414e-06 -4.17960216682019e-06 -6.704686043431e-06 -5.36242828738882e-06 6.00149456218838e-06 -1.06977237838414e-06 3.23191914832942e-05 7.81697036378912e-06 6.18390700321197e-06 -8.56305101905853e-07 2.23346005222378e-06 -4.17960216682019e-06 7.81697036378912e-06 2.96369878714539e-05 -7.77667528161628e-07 2.90220251284886e-05 -2.09660995830607e-06 -6.704686043431e-06 6.18390700321197e-06 -7.77667528161628e-07 8.58011666557328e-05 1313 1313 0 0 0 1373 1384 0 0 0 0 0 0 0 0 0 0 0 1078 0 19 76 0 0 2826 +1280 1314 0.996620905965092 0.00277098240662762 0.0820919694600011 -0.0231716482607473 -0.014322530173034 0.989982284961403 0.140463306924057 -0.0336164572504299 -0.0808803741507303 -0.141164432911061 0.986676729206753 0.00884052834190368 0.000118310390373934 -2.83152808175465e-05 -1.07767043021241e-05 9.11398107534754e-06 -8.44076888053377e-06 2.74814726143302e-05 -2.83152808175465e-05 5.70935342352938e-05 -2.58762563663093e-06 2.78944766317082e-06 -9.64000321836359e-07 1.53587361379852e-05 -1.07767043021241e-05 -2.58762563663093e-06 1.70468292821313e-05 -1.99656639578049e-06 -3.74814559823514e-06 -7.49221484359821e-06 9.11398107534754e-06 2.78944766317082e-06 -1.99656639578049e-06 3.16563616044309e-05 4.27343206416422e-07 1.07348146989355e-05 -8.44076888053377e-06 -9.64000321836359e-07 -3.74814559823514e-06 4.27343206416422e-07 2.95615419976286e-05 1.60897361003323e-06 2.74814726143302e-05 1.53587361379852e-05 -7.49221484359821e-06 1.07348146989355e-05 1.60897361003323e-06 6.79242756893368e-05 1289 1289 0 0 0 1380 1405 0 0 0 0 0 0 0 0 0 0 0 1072 0 12 54 0 0 2583 +1281 1308 0.996590356194576 0.00268856607152344 0.0824647412682969 -0.0226110993039241 -0.0145299151363094 0.989567964439738 0.143332220106734 -0.0329013068746319 -0.0812191080109831 -0.144041713982696 0.986232954796597 0.00507683389782263 0.000134060811600979 -7.20738858279193e-05 4.88064367429354e-06 -6.632187156145e-06 4.59953787001307e-06 2.00236362771056e-05 -7.20738858279193e-05 9.20681700335935e-05 -5.49981936931289e-06 9.91734889815144e-06 -5.8658095768112e-06 7.21280805352615e-06 4.88064367429354e-06 -5.49981936931289e-06 1.35329740865995e-05 -2.16845927506572e-06 -6.29879326936092e-06 -4.99820389098072e-06 -6.632187156145e-06 9.91734889815144e-06 -2.16845927506572e-06 3.25681862191978e-05 2.14775792928357e-06 -5.77843857243014e-08 4.59953787001307e-06 -5.8658095768112e-06 -6.29879326936092e-06 2.14775792928357e-06 2.3798395642054e-05 -1.6485979564736e-06 2.00236362771056e-05 7.21280805352615e-06 -4.99820389098072e-06 -5.77843857243014e-08 -1.6485979564736e-06 6.32745371807952e-05 1215 1215 0 0 0 1277 1289 0 0 0 0 0 0 0 0 0 0 0 1063 0 10 51 0 0 2779 +1281 1311 0.996443173957174 0.00225541210104635 0.0842372494233225 -0.0208119513581793 -0.0139732469646217 0.990225091442422 0.138776859191696 -0.0309832396042493 -0.0831008390055015 -0.139460321934594 0.986734548479215 0.0111651094198857 0.000135953184795644 -4.3729571205776e-05 3.4980741162617e-06 -3.44430843142771e-07 -6.08691612309556e-06 1.81683852710692e-05 -4.3729571205776e-05 8.73045884211244e-05 -5.33752806886412e-06 1.24490081836666e-05 2.76072097404065e-06 1.96616518942513e-05 3.4980741162617e-06 -5.33752806886412e-06 1.62321780480056e-05 3.66354178639328e-06 -4.9464164796918e-06 -4.81598781431512e-06 -3.44430843142771e-07 1.24490081836666e-05 3.66354178639328e-06 2.60033553602698e-05 -2.87495669528593e-06 3.00271519695595e-06 -6.08691612309556e-06 2.76072097404065e-06 -4.9464164796918e-06 -2.87495669528593e-06 2.53417559132651e-05 3.29570396681184e-06 1.81683852710692e-05 1.96616518942513e-05 -4.81598781431512e-06 3.00271519695595e-06 3.29570396681184e-06 6.00075645309484e-05 1314 1314 0 0 0 1366 1375 0 0 0 0 0 0 0 0 0 0 0 969 0 10 56 0 0 2760 +1281 1283 0.99999823889545 0.00186096574105723 0.000242924905907175 -0.00264693994258107 -0.00186280065046576 0.999967958592407 0.00778535562910387 -0.00181131223445486 -0.000228428842143541 -0.00778579443895138 0.999969664152477 -0.0046872061795452 5.73447218501372e-05 1.69747827144113e-05 2.53258821864773e-06 1.86059670426042e-07 -5.96250833561153e-07 1.21046943459851e-05 1.69747827144113e-05 3.5830759582514e-05 5.17534795801606e-06 -1.97695467076567e-08 -7.94657451788806e-07 7.61830563116298e-06 2.53258821864773e-06 5.17534795801606e-06 1.23824422139639e-05 1.1747641583309e-06 -3.62773358651022e-06 2.13291638089401e-07 1.86059670426042e-07 -1.97695467076567e-08 1.1747641583309e-06 2.31252710832202e-05 8.16200415629797e-07 -3.19804302522616e-06 -5.96250833561153e-07 -7.94657451788806e-07 -3.62773358651022e-06 8.16200415629797e-07 2.16979521448597e-05 -5.23474794875459e-06 1.21046943459851e-05 7.61830563116298e-06 2.13291638089401e-07 -3.19804302522616e-06 -5.23474794875459e-06 4.63322766700019e-05 1319 1319 0 0 0 1331 1394 0 0 0 0 0 0 0 0 0 0 0 794 0 0 16 0 0 3421 +1281 1312 0.996048690484976 0.00182313218810128 0.0887901028954811 -0.0210538961380675 -0.0148592092083005 0.989116644325774 0.14638124135088 -0.0307883265259114 -0.0875568962724774 -0.14712219447366 0.985235428620178 0.00699439149200312 8.52280459034054e-05 -2.86477795024226e-05 2.18392828617439e-06 2.18936649450743e-06 -1.82822473526897e-06 1.73557751514102e-05 -2.86477795024226e-05 4.85552092235878e-05 -7.00949603847173e-06 1.87243833209921e-06 -1.21696945722481e-06 1.42931569847756e-05 2.18392828617439e-06 -7.00949603847173e-06 1.69250575792553e-05 -4.30238985487341e-06 -3.63143074473472e-06 -6.81098406900479e-06 2.18936649450743e-06 1.87243833209921e-06 -4.30238985487341e-06 2.86927889522379e-05 1.86896529855352e-06 3.58331231032716e-06 -1.82822473526897e-06 -1.21696945722481e-06 -3.63143074473472e-06 1.86896529855352e-06 3.33109647876052e-05 1.21463698673731e-06 1.73557751514102e-05 1.42931569847756e-05 -6.81098406900479e-06 3.58331231032716e-06 1.21463698673731e-06 6.08435740937858e-05 1325 1332 0 0 0 1380 1399 0 0 0 0 0 0 0 0 0 0 0 1058 0 11 62 0 0 2697 +1281 1309 0.996016283178271 0.00125959522868354 0.0891626438796111 -0.0202677052754275 -0.0143695222350525 0.989099508814717 0.146545823868241 -0.0299404246136612 -0.0880061388454169 -0.147243251398308 0.985177316244734 0.00768821293895579 7.1156838300944e-05 -9.46533557737464e-06 4.16915254762016e-06 4.82072308993578e-06 -4.97666964474948e-06 1.32247270639882e-05 -9.46533557737464e-06 4.53322317133151e-05 -5.98574225831482e-06 1.69462686817045e-06 -4.10569169342019e-06 2.10746810268704e-05 4.16915254762016e-06 -5.98574225831482e-06 1.51400556811379e-05 -4.92237491489979e-07 -4.2134224040378e-06 -2.73373800618965e-06 4.82072308993578e-06 1.69462686817045e-06 -4.92237491489979e-07 2.66676706053006e-05 1.41911478196679e-06 3.04204410018535e-06 -4.97666964474948e-06 -4.10569169342019e-06 -4.2134224040378e-06 1.41911478196679e-06 2.89338349661975e-05 3.42411323047516e-06 1.32247270639882e-05 2.10746810268704e-05 -2.73373800618965e-06 3.04204410018535e-06 3.42411323047516e-06 5.85120615365373e-05 1334 1340 0 0 0 1384 1403 0 0 0 0 0 0 0 0 0 0 0 960 0 10 59 0 0 2571 +1281 1307 0.996832140706694 0.00293849956838761 0.0794798620682978 -0.0243096753064366 -0.014672601024859 0.988959250232924 0.147459540748974 -0.0334103587462761 -0.0781690350028345 -0.148158585978065 0.985869481913152 0.0130561111987526 0.000105845590662623 -3.94636069370936e-05 1.4681321572302e-06 2.79462766093918e-06 -1.5294488040874e-06 2.77403052899886e-05 -3.94636069370936e-05 7.02151806658712e-05 -4.43163262109461e-06 2.17449459854729e-06 -9.02006568917933e-06 3.11266076321837e-06 1.4681321572302e-06 -4.43163262109461e-06 1.51538209433698e-05 8.35192347616839e-07 -3.03535329933528e-06 -1.01587288082566e-06 2.79462766093918e-06 2.17449459854729e-06 8.35192347616839e-07 2.99532454059708e-05 4.95530366755734e-06 -1.74282209619355e-07 -1.5294488040874e-06 -9.02006568917933e-06 -3.03535329933528e-06 4.95530366755734e-06 3.22728150727803e-05 -2.28774322418591e-06 2.77403052899886e-05 3.11266076321837e-06 -1.01587288082566e-06 -1.74282209619355e-07 -2.28774322418591e-06 7.27559418540465e-05 1323 1323 0 0 0 1385 1406 0 0 1 0 0 0 0 0 0 0 0 1062 0 15 63 0 0 2557 +1281 1310 0.996521260407474 0.00311726606843387 0.083280611237903 -0.0211346012436474 -0.0145521411136099 0.990456580270963 0.13705472551853 -0.032393285468185 -0.0820585933641915 -0.137789859025288 0.987056402646212 0.00241394679062868 0.000124776262151422 -6.28582146995238e-05 -1.44348803505272e-06 -4.8972907487134e-06 -1.15908487926195e-05 4.58164649580575e-06 -6.28582146995238e-05 7.57350674016146e-05 1.47973768877377e-07 5.34328141906149e-06 6.99872670181694e-06 2.45806575736354e-05 -1.44348803505272e-06 1.47973768877377e-07 1.39468085594539e-05 1.90546350791868e-06 -3.59152646927621e-06 -7.66776254010361e-07 -4.8972907487134e-06 5.34328141906149e-06 1.90546350791868e-06 2.52922942772098e-05 2.58097268197908e-06 5.47777116347304e-06 -1.15908487926195e-05 6.99872670181694e-06 -3.59152646927621e-06 2.58097268197908e-06 2.77417981097464e-05 1.91861982327646e-06 4.58164649580575e-06 2.45806575736354e-05 -7.66776254010361e-07 5.47777116347304e-06 1.91861982327646e-06 9.14571405968756e-05 1325 1325 0 0 0 1387 1408 0 0 0 0 0 0 0 0 0 0 0 1061 0 14 62 0 0 2501 +1281 1318 0.996590908589533 0.00369936416076035 0.0824189033019431 -0.0238282700042051 -0.0155915855912775 0.989437502431798 0.144119156395936 -0.0348762448510538 -0.0810152045941922 -0.144912882402954 0.986122098494009 0.0131567083971553 0.000139570126240983 -6.81106100238379e-05 -8.38502356523244e-07 3.53725454036708e-07 4.94153235571626e-06 3.78717236320054e-05 -6.81106100238379e-05 7.166735180107e-05 2.43437967648876e-07 2.29021426435352e-06 -2.1330417805336e-06 -1.71407585489401e-06 -8.38502356523244e-07 2.43437967648876e-07 1.51543614465541e-05 1.23676347319155e-06 -3.66280112582864e-06 -4.49960492593884e-06 3.53725454036708e-07 2.29021426435352e-06 1.23676347319155e-06 2.89563319114461e-05 -2.74112644492623e-06 1.17421630329951e-05 4.94153235571626e-06 -2.1330417805336e-06 -3.66280112582864e-06 -2.74112644492623e-06 3.44126008347008e-05 -2.43823376540053e-06 3.78717236320054e-05 -1.71407585489401e-06 -4.49960492593884e-06 1.17421630329951e-05 -2.43823376540053e-06 7.70869304991192e-05 1323 1323 0 0 0 1382 1402 0 0 0 0 0 0 0 0 0 0 0 1073 0 18 70 0 0 2767 +1281 1314 0.996666748073123 0.00262780890305113 0.0815382603795007 -0.0248212899702182 -0.0141870779501483 0.989834788012427 0.141512611662811 -0.0315882138993272 -0.0803375385768236 -0.142197704133232 0.986572700227741 0.0133290501915037 0.000187302121016565 -7.77267531670786e-05 2.44523259217902e-06 -2.62967179806246e-06 -4.32137723400552e-06 4.42090638914026e-05 -7.77267531670786e-05 9.52341125648032e-05 -1.12284166648468e-06 5.65643543999982e-06 5.13294686367225e-06 4.69974464576721e-06 2.44523259217902e-06 -1.12284166648468e-06 1.72250259645386e-05 -1.11042327625014e-07 -4.06635333355516e-06 -2.4707720408512e-06 -2.62967179806246e-06 5.65643543999982e-06 -1.11042327625014e-07 3.23514841724693e-05 -1.20590975257924e-06 4.56838169203565e-06 -4.32137723400552e-06 5.13294686367225e-06 -4.06635333355516e-06 -1.20590975257924e-06 3.30606811962881e-05 3.71941266762372e-06 4.42090638914026e-05 4.69974464576721e-06 -2.4707720408512e-06 4.56838169203565e-06 3.71941266762372e-06 0.000100399513884766 1306 1306 0 0 0 1361 1369 0 0 0 0 0 0 0 0 0 0 0 1068 0 11 58 0 0 2512 +1282 1285 0.999988195538682 0.00369546347850297 0.00315473183810301 -0.00534078633934519 -0.00372487713937134 0.999949169750063 0.00936926925943705 -0.00235390612746978 -0.00311994768992669 -0.00938090964876509 0.999951131036199 0.000636103271396995 4.58026773151837e-05 6.50335412440359e-06 -8.62072300020804e-07 5.39721020338772e-06 -1.08640620359463e-05 -1.29706824180411e-06 6.50335412440359e-06 2.71778756832191e-05 3.85968501448645e-06 9.78057601215297e-07 -7.60006623694848e-06 8.8096918250289e-06 -8.62072300020804e-07 3.85968501448645e-06 1.28329835919991e-05 -3.26147701517236e-08 -9.83978195546415e-07 1.97842926245579e-06 5.39721020338772e-06 9.78057601215297e-07 -3.26147701517236e-08 2.14953407398502e-05 -1.10029663272205e-05 -1.24998393007056e-06 -1.08640620359463e-05 -7.60006623694848e-06 -9.83978195546415e-07 -1.10029663272205e-05 2.81416337367885e-05 -3.87711195326203e-06 -1.29706824180411e-06 8.8096918250289e-06 1.97842926245579e-06 -1.24998393007056e-06 -3.87711195326203e-06 4.02098663790169e-05 1341 1343 0 0 0 1360 1436 0 0 0 0 0 0 0 0 0 0 0 836 0 0 0 0 0 3493 +1281 1316 0.996287999215865 0.00299070710512471 0.0860306822561618 -0.022429672804007 -0.0155138991903331 0.989270382965775 0.145270190743527 -0.0326510206554563 -0.0846731453907406 -0.146065619013373 0.985644608057021 0.00502534127186289 0.000111854263155777 -5.03524046863595e-05 2.3055995350605e-06 -4.82151216259331e-06 -2.26495277180643e-06 1.06073457450536e-05 -5.03524046863595e-05 7.81821123351282e-05 -1.25568864695052e-06 3.73990244270723e-06 -1.56522636828549e-06 7.10321321359946e-06 2.3055995350605e-06 -1.25568864695052e-06 1.41045694125237e-05 1.45578496254086e-06 -6.69580865951953e-06 -1.94956137721072e-06 -4.82151216259331e-06 3.73990244270723e-06 1.45578496254086e-06 2.83780302657076e-05 -4.59825034923596e-06 1.65970804336487e-06 -2.26495277180643e-06 -1.56522636828549e-06 -6.69580865951953e-06 -4.59825034923596e-06 2.42435435736654e-05 -1.94609648942146e-06 1.06073457450536e-05 7.10321321359946e-06 -1.94956137721072e-06 1.65970804336487e-06 -1.94609648942146e-06 7.184057321425e-05 1213 1213 0 0 0 1276 1290 0 0 0 0 0 0 0 0 0 0 0 1059 0 11 52 0 0 2788 +1282 1308 0.996610548229837 0.00246762826267858 0.0822272823810933 -0.0219565671405853 -0.0139227535892302 0.99019015142769 0.139031007146252 -0.0337102133402725 -0.0810775683497995 -0.139704598443877 0.986868305846387 0.0102538601533666 9.20244952433959e-05 -5.36561337509671e-05 3.29425176397613e-06 -1.41759272490162e-05 -4.27419440543186e-06 1.82731050916146e-05 -5.36561337509671e-05 8.63098673953607e-05 -4.01446106381947e-06 1.51128566284435e-05 -1.23472046230196e-06 -3.81716963783037e-06 3.29425176397613e-06 -4.01446106381947e-06 1.34537326966516e-05 2.52858038471077e-06 -1.4305682618628e-06 -1.69138572079684e-06 -1.41759272490162e-05 1.51128566284435e-05 2.52858038471077e-06 3.27792582500254e-05 5.03155302203968e-06 -4.0073131381674e-06 -4.27419440543186e-06 -1.23472046230196e-06 -1.4305682618628e-06 5.03155302203968e-06 3.26755129790015e-05 -6.60180559931051e-06 1.82731050916146e-05 -3.81716963783037e-06 -1.69138572079684e-06 -4.0073131381674e-06 -6.60180559931051e-06 6.44033511850893e-05 1235 1236 0 0 0 1284 1297 0 0 6 0 0 0 0 0 0 0 0 1072 0 10 51 0 0 2835 +1281 1313 0.99681475310474 0.00251643680972553 0.0797120790000992 -0.0200251591080446 -0.013329388860392 0.99069983822485 0.135411070204268 -0.0309579005022056 -0.0786299903684584 -0.136042265811179 0.987577757205789 0.0155554689588483 0.000133763487520229 -7.05736269797645e-05 4.6118955538817e-06 -9.31147957954295e-06 -5.13094075452592e-06 3.51828117998094e-05 -7.05736269797645e-05 9.50823291794138e-05 -2.21115197007283e-06 3.30219714456441e-06 2.33897024079843e-06 1.12424915321475e-06 4.6118955538817e-06 -2.21115197007283e-06 1.60122318193273e-05 -2.89837367216611e-06 -2.96033341175753e-06 -2.12232879021783e-06 -9.31147957954295e-06 3.30219714456441e-06 -2.89837367216611e-06 3.34930400746244e-05 2.56609394804704e-06 -4.9852335801836e-07 -5.13094075452592e-06 2.33897024079843e-06 -2.96033341175753e-06 2.56609394804704e-06 2.57105720353242e-05 -9.04498478525427e-07 3.51828117998094e-05 1.12424915321475e-06 -2.12232879021783e-06 -4.9852335801836e-07 -9.04498478525427e-07 7.85200128057618e-05 1333 1337 0 0 0 1383 1398 0 0 0 0 0 0 0 0 0 0 0 1077 0 9 62 0 0 2748 +1282 1309 0.996223291333604 0.00133735270839707 0.0868180009685491 -0.0199112344376452 -0.0137130541377542 0.989756036302945 0.142108904534864 -0.0303696729602096 -0.0857385907900094 -0.142762740550949 0.986036355293113 0.0135995703418265 7.0416990493559e-05 -3.06823246903954e-05 3.01469289998426e-06 -9.68395285691143e-07 5.08203192060694e-06 2.95753619668827e-05 -3.06823246903954e-05 5.87517701997305e-05 -7.4827000345141e-07 -8.30278664797662e-07 -3.5897412471583e-06 4.12207100121652e-06 3.01469289998426e-06 -7.4827000345141e-07 1.35350394667891e-05 -1.20290647148181e-07 -6.21523528462897e-06 -1.98953928806606e-06 -9.68395285691143e-07 -8.30278664797662e-07 -1.20290647148181e-07 2.55729780678636e-05 1.88224830202184e-06 -4.83736213119052e-07 5.08203192060694e-06 -3.5897412471583e-06 -6.21523528462897e-06 1.88224830202184e-06 2.30244285393349e-05 1.37002781533915e-06 2.95753619668827e-05 4.12207100121652e-06 -1.98953928806606e-06 -4.83736213119052e-07 1.37002781533915e-06 7.0175382092134e-05 1322 1322 0 0 0 1386 1407 0 0 0 0 0 0 0 0 0 0 0 968 0 11 53 0 0 2712 +1282 1311 0.996654359222268 0.000558742163829002 0.0817298969193284 -0.0203755911731358 -0.0124676256282475 0.989313060086878 0.145272941226957 -0.0254434920135916 -0.0807752843043189 -0.145805887908313 0.98601014015923 0.00644876033563568 0.000209682755635101 -8.73893635037341e-05 -3.17671313228121e-06 2.50314684406802e-06 -1.82180681418974e-05 5.87680279302378e-05 -8.73893635037341e-05 9.5305657417744e-05 -6.48232431001596e-06 7.16525525300614e-06 -2.16144480970325e-06 -1.54765123212134e-05 -3.17671313228121e-06 -6.48232431001596e-06 1.53455909169757e-05 5.41056175990166e-06 -3.43173758113004e-06 -6.41070777428652e-06 2.50314684406802e-06 7.16525525300614e-06 5.41056175990166e-06 2.69758399555018e-05 -1.24004591464397e-05 -4.5546950099625e-06 -1.82180681418974e-05 -2.16144480970325e-06 -3.43173758113004e-06 -1.24004591464397e-05 3.10135929237311e-05 -1.07297883465751e-05 5.87680279302378e-05 -1.54765123212134e-05 -6.41070777428652e-06 -4.5546950099625e-06 -1.07297883465751e-05 8.10534259570406e-05 1341 1351 0 0 0 1394 1429 0 0 5 0 0 0 0 0 0 0 0 967 0 6 41 0 0 2854 +1281 1315 0.995996609323997 0.0022659829781841 0.0893622937051396 -0.0244553342626248 -0.0155770570343614 0.988783280917201 0.14854285130145 -0.0328988518108704 -0.0880233463874744 -0.149340177781329 0.984860092495879 0.00336432670203463 0.00010991288706681 -5.30515061282492e-05 -1.11377350212317e-07 3.29660436046739e-06 6.56246320361608e-07 2.04011420747905e-06 -5.30515061282492e-05 8.23150783227911e-05 -4.99606872911033e-06 9.19836303827162e-06 -6.19203305852946e-06 2.12618673049047e-05 -1.11377350212317e-07 -4.99606872911033e-06 1.65824671704645e-05 -6.94226385432475e-07 -5.36029789225907e-06 -5.4099370211062e-06 3.29660436046739e-06 9.19836303827162e-06 -6.94226385432475e-07 3.25861934350477e-05 -5.39055039752606e-06 9.89188223603669e-06 6.56246320361608e-07 -6.19203305852946e-06 -5.36029789225907e-06 -5.39055039752606e-06 2.56074671126157e-05 1.12236849188507e-07 2.04011420747905e-06 2.12618673049047e-05 -5.4099370211062e-06 9.89188223603669e-06 1.12236849188507e-07 7.59007214095815e-05 1203 1203 0 0 0 1265 1278 0 0 0 0 0 0 0 0 0 0 0 1062 0 12 52 0 0 2736 +1282 1286 0.999987946456857 0.00415062658927438 0.002622830515633 -0.00351643862149142 -0.00416119473846029 0.999983194358961 0.00403676330706434 -0.00307206009856229 -0.00260603134016794 -0.00404762875830519 0.99998841258391 -0.00085640791739314 4.46108873585317e-05 1.14502245353346e-05 2.82004056938515e-06 -5.89311764884525e-07 -1.90300380334079e-06 1.27915256336471e-05 1.14502245353346e-05 5.02410681180831e-05 4.14146863224144e-06 -2.38611995257797e-06 -4.219608697469e-06 1.7531428574969e-05 2.82004056938515e-06 4.14146863224144e-06 1.05484606897969e-05 2.30786772974319e-06 -6.06765326824532e-06 3.63426192763069e-06 -5.89311764884525e-07 -2.38611995257797e-06 2.30786772974319e-06 2.19283931470837e-05 -3.1844772532031e-06 -3.37880778958372e-06 -1.90300380334079e-06 -4.219608697469e-06 -6.06765326824532e-06 -3.1844772532031e-06 1.92920244230893e-05 -6.67570450332377e-07 1.27915256336471e-05 1.7531428574969e-05 3.63426192763069e-06 -3.37880778958372e-06 -6.67570450332377e-07 4.40867455828323e-05 1255 1271 0 0 0 1270 1348 0 0 2 0 0 0 0 0 0 0 0 831 0 0 0 0 0 3446 +1281 1317 0.996200566082094 0.00340904041049022 0.0870218971362701 -0.0206217178693734 -0.0158223633475668 0.989688607471414 0.14235909896944 -0.0332881499687061 -0.085639272275128 -0.143195107055978 0.985982290084063 0.0109108536857347 0.000179958406976297 -8.56562458794096e-05 -5.30635997904432e-06 4.9998395001425e-06 -8.50225831260035e-06 3.31150319131766e-05 -8.56562458794096e-05 8.72892654459157e-05 1.90055043973269e-06 -4.25470439106541e-07 4.41352740924598e-06 1.14925594154851e-05 -5.30635997904432e-06 1.90055043973269e-06 1.40185153060987e-05 5.91307682614678e-07 -4.64621223629292e-06 -2.40623475331231e-06 4.9998395001425e-06 -4.25470439106541e-07 5.91307682614678e-07 3.14190588437272e-05 -2.61545973644593e-06 3.32806821440845e-06 -8.50225831260035e-06 4.41352740924598e-06 -4.64621223629292e-06 -2.61545973644593e-06 2.68639207900303e-05 -5.48520076142751e-06 3.31150319131766e-05 1.14925594154851e-05 -2.40623475331231e-06 3.32806821440845e-06 -5.48520076142751e-06 8.60737868168933e-05 1304 1304 0 0 0 1360 1369 0 0 0 0 0 0 0 0 0 0 0 967 0 12 59 0 0 2784 +1282 1310 0.99653647537723 0.00202075195329704 0.0831322428680358 -0.0223026639335316 -0.013750919684725 0.989946259682371 0.140773986051069 -0.0317603623186609 -0.0820119835789324 -0.141429556679025 0.986545343634555 0.00334608482024273 7.12148188065587e-05 -3.58692308092065e-05 2.06566717793352e-06 -3.62252835120963e-06 2.42376053945543e-06 7.48318377028868e-06 -3.58692308092065e-05 6.60647782889388e-05 -2.79340046607003e-06 2.79431926347273e-06 -4.92492239468151e-06 1.8601246154175e-05 2.06566717793352e-06 -2.79340046607003e-06 1.46067711230859e-05 8.59115891979439e-07 -2.47789852481172e-06 4.67447645229458e-07 -3.62252835120963e-06 2.79431926347273e-06 8.59115891979439e-07 2.40964317596559e-05 -1.70225737409515e-06 7.22434643492716e-06 2.42376053945543e-06 -4.92492239468151e-06 -2.47789852481172e-06 -1.70225737409515e-06 2.26646968910242e-05 4.90993199844219e-07 7.48318377028868e-06 1.8601246154175e-05 4.67447645229458e-07 7.22434643492716e-06 4.90993199844219e-07 6.33953842418681e-05 1322 1322 0 0 0 1380 1389 0 0 0 0 0 0 0 0 0 0 0 1067 0 18 79 0 0 2641 +1282 1312 0.995973793276013 0.00122944313673317 0.0896364411217015 -0.0192768217786732 -0.0141499190572827 0.98952721864579 0.143651186384933 -0.0278837892061546 -0.0885210873072799 -0.144341165398856 0.98556057402538 0.00601476541421937 8.0103146918763e-05 -4.61818285067522e-05 5.823032217431e-06 -4.77354724548857e-06 -3.09949270446276e-06 9.73089916525971e-06 -4.61818285067522e-05 6.34991579576742e-05 -6.83053184237524e-06 2.13884734596384e-06 9.0874380726818e-07 -5.48210773509328e-06 5.823032217431e-06 -6.83053184237524e-06 1.57698564530965e-05 -1.53844464239243e-07 -4.08605965633087e-06 -4.78660781619023e-06 -4.77354724548857e-06 2.13884734596384e-06 -1.53844464239243e-07 2.55416239750954e-05 -2.27142424654898e-06 2.43452427640033e-07 -3.09949270446276e-06 9.0874380726818e-07 -4.08605965633087e-06 -2.27142424654898e-06 2.80333378666718e-05 -6.92578343282616e-06 9.73089916525971e-06 -5.48210773509328e-06 -4.78660781619023e-06 2.43452427640033e-07 -6.92578343282616e-06 7.05865654921435e-05 1323 1323 0 0 0 1384 1409 0 0 1 0 0 0 0 0 0 0 0 1065 0 10 51 0 0 2837 +1282 1284 0.999996392324064 0.00221725029434742 -0.00151629152469714 0.00028103940986863 -0.00221927239039396 0.999996648697901 -0.00133320029399611 -0.00229430026814921 0.00151333040440188 0.00133656054815804 0.999997961716417 -0.00652476084592001 6.05519557789447e-05 1.49785240704092e-05 -1.25274103061746e-06 5.38300414316659e-06 4.5293793152203e-06 4.33592787060485e-06 1.49785240704092e-05 4.33497855393092e-05 -3.13107356100202e-06 4.31595995011569e-06 -4.87440406012809e-06 1.62790396648954e-05 -1.25274103061746e-06 -3.13107356100202e-06 1.45502976409738e-05 1.19146144786611e-06 -1.06066308580259e-06 -3.30276515538757e-06 5.38300414316659e-06 4.31595995011569e-06 1.19146144786611e-06 1.97135458661356e-05 -6.1024035685374e-06 2.21303007654422e-06 4.5293793152203e-06 -4.87440406012809e-06 -1.06066308580259e-06 -6.1024035685374e-06 2.33864864743026e-05 -3.41976975022119e-06 4.33592787060485e-06 1.62790396648954e-05 -3.30276515538757e-06 2.21303007654422e-06 -3.41976975022119e-06 3.79033231917638e-05 1271 1282 0 0 0 1277 1361 0 0 3 0 0 0 0 0 0 0 0 793 0 0 0 0 0 3488 +1282 1313 0.996625488557751 0.0016944390469593 0.082065610540228 -0.0193097949936006 -0.0135810554196391 0.989411153284232 0.144503026578872 -0.0268070734190192 -0.0809517787989426 -0.145129937067035 0.986095386296988 0.0122384587683241 0.000148344706480406 -8.14559241741819e-05 1.17429397418888e-05 2.08184205650341e-07 5.30992107669744e-06 5.09041312346887e-05 -8.14559241741819e-05 0.000102062883011933 -7.67142181924131e-06 6.81058923721466e-06 -8.88315805350778e-06 -1.28540718939379e-05 1.17429397418888e-05 -7.67142181924131e-06 1.42028792699634e-05 1.59514856380055e-06 -2.58177841751606e-06 9.21438715276302e-07 2.08184205650341e-07 6.81058923721466e-06 1.59514856380055e-06 3.20280287750216e-05 -4.07081870104725e-06 9.08402872112765e-07 5.30992107669744e-06 -8.88315805350778e-06 -2.58177841751606e-06 -4.07081870104725e-06 3.00587765656318e-05 -1.01591605470125e-05 5.09041312346887e-05 -1.28540718939379e-05 9.21438715276302e-07 9.08402872112765e-07 -1.01591605470125e-05 8.2303371479541e-05 1328 1328 0 0 0 1390 1417 0 0 0 0 0 0 0 0 0 0 0 1077 0 8 48 0 0 2840 +1282 1315 0.996587449169536 0.00201511373384453 0.0825190612791837 -0.02452700517158 -0.0140120514221299 0.989322888230741 0.145065106892484 -0.0298197021830475 -0.0813456733496109 -0.145726326171437 0.985975009464172 0.0079250167416261 0.00010965383360679 -7.51844413322356e-05 2.94858941998233e-06 -1.30403241872149e-05 -9.58490091701915e-06 1.98295612719944e-05 -7.51844413322356e-05 9.82474235653317e-05 -3.65458520787945e-06 1.06986864827155e-05 5.40616307559474e-07 -1.28600342302761e-06 2.94858941998233e-06 -3.65458520787945e-06 1.53704181411613e-05 2.22465468055101e-06 -4.18344661022162e-06 -4.43974243644635e-06 -1.30403241872149e-05 1.06986864827155e-05 2.22465468055101e-06 2.92201302131214e-05 -6.54473251365564e-06 1.05021890010813e-06 -9.58490091701915e-06 5.40616307559474e-07 -4.18344661022162e-06 -6.54473251365564e-06 3.7158342522179e-05 -1.22150077106463e-05 1.98295612719944e-05 -1.28600342302761e-06 -4.43974243644635e-06 1.05021890010813e-06 -1.22150077106463e-05 6.55672849817055e-05 1223 1223 0 0 0 1279 1296 0 0 8 0 0 0 0 0 0 0 0 1072 0 8 47 0 0 2846 +1282 1316 0.996675190452395 0.00289119427898438 0.0814260752604707 -0.0229590150330913 -0.0143006671667724 0.990063845267731 0.139889503581436 -0.0337069771139354 -0.0802125654449966 -0.140588844825315 0.986813417549344 0.009167461903771 9.17244161151847e-05 -2.54451989949351e-05 1.99269114466467e-06 -2.99913172359319e-06 -8.010620980098e-06 2.7389546409434e-05 -2.54451989949351e-05 5.39184773871335e-05 -4.2377079562137e-06 4.73194174443817e-06 1.7530199431516e-06 6.71727825390258e-06 1.99269114466467e-06 -4.2377079562137e-06 1.56049576190553e-05 1.10360870654782e-06 -4.81082821343225e-06 -3.94633323136406e-06 -2.99913172359319e-06 4.73194174443817e-06 1.10360870654782e-06 3.24900421827336e-05 -1.46920075268344e-06 5.12029764574014e-08 -8.010620980098e-06 1.7530199431516e-06 -4.81082821343225e-06 -1.46920075268344e-06 3.13207117316873e-05 -1.2408676764205e-05 2.7389546409434e-05 6.71727825390258e-06 -3.94633323136406e-06 5.12029764574014e-08 -1.2408676764205e-05 7.11108518395637e-05 1234 1236 0 0 0 1284 1300 0 0 7 0 0 0 0 0 0 0 0 1063 0 10 52 0 0 2839 +1283 1285 0.999995006832109 0.00315897880070197 -8.46391587007477e-05 -0.00203821246140687 -0.00315896812422491 0.999995002512322 0.000125979248825718 -0.00338139183139315 8.50367014939638e-05 -0.000125711247385781 0.999999988482721 0.00247223575362398 6.15038664223419e-05 2.68029511681155e-05 9.21571877254187e-06 -1.16202086318705e-05 3.24940453204963e-06 2.62906280201886e-05 2.68029511681155e-05 5.87416463085176e-05 1.03837583153192e-05 -7.57913767716998e-06 -1.53743704800269e-06 1.49068363200011e-05 9.21571877254187e-06 1.03837583153192e-05 1.42406087857366e-05 -1.90268947649945e-06 -4.21653167266563e-06 5.95435935919538e-06 -1.16202086318705e-05 -7.57913767716998e-06 -1.90268947649945e-06 2.10341340513975e-05 -4.19747582917803e-06 -5.19847480752049e-06 3.24940453204963e-06 -1.53743704800269e-06 -4.21653167266563e-06 -4.19747582917803e-06 1.77302128905467e-05 -2.59867084238411e-06 2.62906280201886e-05 1.49068363200011e-05 5.95435935919538e-06 -5.19847480752049e-06 -2.59867084238411e-06 4.12789540985361e-05 1345 1347 0 0 0 1360 1438 0 0 0 0 0 0 0 0 0 0 0 835 0 0 0 0 0 3466 +1282 1314 0.996743845035067 0.00172942873480791 0.0806146169187808 -0.0198946362310514 -0.0136013407502841 0.989049955251236 0.146953018163365 -0.026193961180169 -0.0794777384838372 -0.147570983237827 0.985852977878403 0.00680611687254852 8.82410133117187e-05 -3.28401200129909e-05 5.63267955842693e-07 5.49682406932162e-06 -1.25096518796458e-06 1.78027832450205e-05 -3.28401200129909e-05 7.17901341616144e-05 -3.12866414615075e-06 3.28480004455876e-06 -5.27169033810192e-06 1.08961833703037e-05 5.63267955842693e-07 -3.12866414615075e-06 1.64587822285296e-05 1.27564491759777e-06 -3.96389142851486e-06 2.07680911590382e-07 5.49682406932162e-06 3.28480004455876e-06 1.27564491759777e-06 2.83090865441586e-05 -7.60349740577713e-06 2.09550428359528e-06 -1.25096518796458e-06 -5.27169033810192e-06 -3.96389142851486e-06 -7.60349740577713e-06 2.84994043727124e-05 -1.90568937847006e-06 1.78027832450205e-05 1.08961833703037e-05 2.07680911590382e-07 2.09550428359528e-06 -1.90568937847006e-06 5.53671349581687e-05 1341 1350 0 0 0 1391 1426 0 0 5 0 0 0 0 0 0 0 0 1068 0 7 43 0 0 2635 +1283 1313 0.996327289679216 0.00110466595683763 0.0856195745936105 -0.018168515861723 -0.0131273939394106 0.990066546806533 0.139985372174902 -0.0287664464361801 -0.0846144394818435 -0.140595208338372 0.986444820567001 0.0168737607462419 0.000109867270065395 -6.75714878784485e-05 1.12633311230682e-05 -1.42768107904101e-05 8.46536174310627e-06 3.83126885457632e-05 -6.75714878784485e-05 8.03080949424058e-05 -5.9250234883512e-06 7.19934472753157e-06 -5.20302954026269e-06 -7.53955285760678e-06 1.12633311230682e-05 -5.9250234883512e-06 1.60770144870288e-05 -3.89920152757686e-06 1.31337204490049e-06 8.79637793803398e-07 -1.42768107904101e-05 7.19934472753157e-06 -3.89920152757686e-06 3.15369995032745e-05 2.25888450199082e-06 -3.90939146845969e-06 8.46536174310627e-06 -5.20302954026269e-06 1.31337204490049e-06 2.25888450199082e-06 3.19808100873219e-05 1.1272190569559e-06 3.83126885457632e-05 -7.53955285760678e-06 8.79637793803398e-07 -3.90939146845969e-06 1.1272190569559e-06 7.55857026339748e-05 1320 1320 0 0 0 1385 1408 0 0 0 0 0 0 0 0 0 0 0 1074 0 6 47 0 0 2839 +1283 1309 0.990577792919311 -0.00503041799354634 0.136858799753308 -0.0176973537029537 -0.0196812509316905 0.983723091571588 0.178609987040479 -0.0266568792000125 -0.135529644494737 -0.17962063913606 0.974355243973923 0.0326560394618253 0.00704859883787697 -0.00835492798653077 -0.000947391584825932 0.000428709452145575 0.000626380564909249 -0.00343298218524465 -0.00835492798653077 0.0128682825632941 0.0015495355491634 -0.00105799523885674 -0.00114073264056832 0.0064432682501972 -0.000947391584825932 0.0015495355491634 0.000208496570830443 -0.000135989583448483 -0.000144336214489506 0.000797343311541344 0.000428709452145575 -0.00105799523885674 -0.000135989583448483 0.00016441138839417 0.000130609610840124 -0.000679768825863756 0.000626380564909249 -0.00114073264056832 -0.000144336214489506 0.000130609610840124 0.000159337958097655 -0.000660263270412404 -0.00343298218524465 0.0064432682501972 0.000797343311541344 -0.000679768825863756 -0.000660263270412404 0.00373892307096209 1323 1324 0 0 0 1382 1416 0 0 0 0 0 0 0 0 0 0 0 960 0 12 49 0 0 2611 +1283 1310 0.996948320523299 0.00196666463617534 0.0780395953089394 -0.0231803159232097 -0.0121080098662153 0.991480332440315 0.129692507420906 -0.0327688330165254 -0.0771196622324933 -0.130241631647684 0.988478464653072 0.00648687470772297 0.000169262590678337 -9.5610028004837e-05 4.38064042501897e-06 -1.58536085687315e-05 -3.81437575452216e-06 3.31103114882915e-05 -9.5610028004837e-05 8.97691768685864e-05 -3.65229248734057e-06 7.00153030974096e-06 8.55230918560437e-07 3.42436235191022e-06 4.38064042501897e-06 -3.65229248734057e-06 1.66493265523025e-05 -1.9092815851099e-06 -1.29771040983261e-06 -1.46425536536983e-06 -1.58536085687315e-05 7.00153030974096e-06 -1.9092815851099e-06 2.96747767946297e-05 -1.37155591734116e-06 1.15673981314322e-06 -3.81437575452216e-06 8.55230918560437e-07 -1.29771040983261e-06 -1.37155591734116e-06 2.63977130186185e-05 -4.48353651204496e-06 3.31103114882915e-05 3.42436235191022e-06 -1.46425536536983e-06 1.15673981314322e-06 -4.48353651204496e-06 9.072674575138e-05 1324 1324 0 0 0 1382 1391 0 0 0 0 0 0 0 0 0 0 0 1066 0 14 77 0 0 2634 +1282 1317 0.996448751838831 0.00225212329745397 0.0841713306268148 -0.0197955490568954 -0.013906103628615 0.990316777606211 0.138127840327434 -0.0322073763858692 -0.0830451999859458 -0.13880780933472 0.986831235230721 0.011198709082608 0.000127835319822456 -6.21891230447615e-05 4.16053596288663e-06 -1.2624611977228e-06 5.09810851275998e-06 3.96314915044097e-05 -6.21891230447615e-05 7.97384051168915e-05 2.1752118895146e-07 2.96031192360068e-06 1.14666167864931e-06 -2.38007896676349e-06 4.16053596288663e-06 2.1752118895146e-07 1.43346401722573e-05 3.90254762591044e-06 -4.53065764317332e-06 -3.88259609751884e-06 -1.2624611977228e-06 2.96031192360068e-06 3.90254762591044e-06 2.70080886726865e-05 -6.651368635513e-06 -2.641096378224e-06 5.09810851275998e-06 1.14666167864931e-06 -4.53065764317332e-06 -6.651368635513e-06 2.71088375444391e-05 -8.21299963912561e-06 3.96314915044097e-05 -2.38007896676349e-06 -3.88259609751884e-06 -2.641096378224e-06 -8.21299963912561e-06 7.39517231304393e-05 1328 1330 0 0 0 1382 1411 0 0 5 0 0 0 0 0 0 0 0 975 0 10 52 0 0 2839 +1283 1315 0.996080328598257 0.00157299054591862 0.0884392711431469 -0.0219789408273545 -0.0138452172255109 0.990290318043238 0.138323519149133 -0.0319634437143249 -0.0873629723599593 -0.139005797327178 0.986430483799983 0.0102872884630358 0.000124951054351311 -7.06232774509877e-05 -2.20253746941822e-06 6.7288740998172e-07 -1.92432334578898e-06 7.68348043077358e-05 -7.06232774509877e-05 0.000111359402868967 1.11045653302009e-06 6.46331926988323e-07 -1.95636002239072e-06 -3.83967342026134e-05 -2.20253746941822e-06 1.11045653302009e-06 1.42459044078009e-05 3.62502965408828e-07 -5.25932000747578e-06 -6.37130855997161e-06 6.7288740998172e-07 6.46331926988323e-07 3.62502965408828e-07 2.88100442037e-05 -4.53253558858003e-06 2.97059803313031e-06 -1.92432334578898e-06 -1.95636002239072e-06 -5.25932000747578e-06 -4.53253558858003e-06 2.35710022892837e-05 -5.00256607614554e-06 7.68348043077358e-05 -3.83967342026134e-05 -6.37130855997161e-06 2.97059803313031e-06 -5.00256607614554e-06 0.000122288884859549 1224 1224 0 0 0 1273 1290 0 0 5 0 0 0 0 0 0 0 0 1070 0 7 48 0 0 2828 +1283 1317 0.99601527496593 0.00123995670598841 0.0891741809152746 -0.0186859222302228 -0.0137907339235121 0.99001765636354 0.14026708718119 -0.0305647592060736 -0.0881100884824987 -0.140937938809293 0.986089808137065 0.0133708980587861 0.000118852412517832 -3.817768471695e-05 1.13072794343002e-06 -8.60324287169215e-06 -4.93554153202636e-06 3.60067585007379e-05 -3.817768471695e-05 6.79637628386253e-05 -1.38343296221572e-06 5.7138322609679e-06 -1.88511039356563e-06 1.23516989041549e-05 1.13072794343002e-06 -1.38343296221572e-06 1.30720397238022e-05 3.4462834857076e-07 -5.83380433050517e-06 -2.13365980718584e-06 -8.60324287169215e-06 5.7138322609679e-06 3.4462834857076e-07 2.64793802259339e-05 -3.99113958145074e-06 -4.78405451586977e-07 -4.93554153202636e-06 -1.88511039356563e-06 -5.83380433050517e-06 -3.99113958145074e-06 1.94922569325811e-05 -6.8705245031107e-06 3.60067585007379e-05 1.23516989041549e-05 -2.13365980718584e-06 -4.78405451586977e-07 -6.8705245031107e-06 6.86862943140295e-05 1332 1345 0 0 0 1381 1415 0 0 1 0 0 0 0 0 0 0 0 967 0 7 48 0 0 2828 +1283 1316 0.996291869731048 0.00129457727434025 0.0860281022543935 -0.0214634607630159 -0.0135766433729137 0.989725070282606 0.142337486309176 -0.0299495914338817 -0.0849599026749462 -0.142977653232143 0.986072616805523 0.0113418434122646 8.64886136069619e-05 -4.13710679050624e-05 7.15896982399599e-06 -4.50446920484513e-06 -1.46056296075299e-06 2.93980256386952e-05 -4.13710679050624e-05 5.01006303387494e-05 -4.96095255396e-06 -1.11907810514136e-07 -8.69065313144565e-07 -8.03596074675475e-06 7.15896982399599e-06 -4.96095255396e-06 1.25948293533875e-05 2.66008853745399e-06 -3.36715022851767e-06 -3.26287042134069e-06 -4.50446920484513e-06 -1.11907810514136e-07 2.66008853745399e-06 2.47038086042783e-05 -3.46874452470748e-06 -3.84756510229524e-06 -1.46056296075299e-06 -8.69065313144565e-07 -3.36715022851767e-06 -3.46874452470748e-06 2.41131978199484e-05 -6.33527817313879e-06 2.93980256386952e-05 -8.03596074675475e-06 -3.26287042134069e-06 -3.84756510229524e-06 -6.33527817313879e-06 7.78524871479458e-05 1238 1240 0 0 1 1289 1308 0 0 5 0 0 0 0 0 0 0 0 1057 0 5 43 0 0 2832 +1282 1318 0.996740267996321 0.00294619227962077 0.0806235580067909 -0.0214583856740563 -0.0144638588324282 0.98966749038289 0.142650114850662 -0.0284403007909698 -0.0793702396512601 -0.143351241467533 0.986484052900714 0.0132667480682622 0.000126141369158492 -6.33551099948575e-05 4.17820586154583e-06 -1.63166861472018e-06 6.50433713374914e-06 3.14403839695476e-05 -6.33551099948575e-05 7.4314073892293e-05 -3.58267237262815e-06 1.23015167517608e-06 -8.80526560647964e-06 -2.44501516854604e-06 4.17820586154583e-06 -3.58267237262815e-06 1.36256173356432e-05 2.53209353528507e-06 -4.01398274563483e-06 -3.78446226365209e-06 -1.63166861472018e-06 1.23015167517608e-06 2.53209353528507e-06 2.94311062007148e-05 -9.53726617619076e-06 4.07696919249236e-06 6.50433713374914e-06 -8.80526560647964e-06 -4.01398274563483e-06 -9.53726617619076e-06 3.12874222372481e-05 -1.33762521766706e-06 3.14403839695476e-05 -2.44501516854604e-06 -3.78446226365209e-06 4.07696919249236e-06 -1.33762521766706e-06 6.68111328279621e-05 1330 1330 0 0 0 1385 1393 0 0 1 0 0 0 0 0 0 0 0 1077 0 17 77 0 0 2868 +1283 1318 0.996351197521122 0.00167054676041171 0.0853317084778458 -0.0211045517448198 -0.0134795440511478 0.990340213074008 0.138002044407688 -0.0324768741710271 -0.0842768834877035 -0.13864873472935 0.986749175458257 0.0182718968036836 9.77946325423652e-05 -6.00595697748202e-05 2.78401081837523e-06 -4.94479538082555e-06 -2.81955789851196e-06 2.73533773362876e-05 -6.00595697748202e-05 9.51626962741559e-05 -1.17697545256394e-06 2.1012563821334e-06 -2.81330177168672e-06 1.86518217869218e-06 2.78401081837523e-06 -1.17697545256394e-06 1.36830435317381e-05 -2.47504079567633e-07 -5.55546123940195e-06 -1.80536676908187e-06 -4.94479538082555e-06 2.1012563821334e-06 -2.47504079567633e-07 3.13811849996683e-05 -6.86148126659773e-07 -2.01215290885216e-06 -2.81955789851196e-06 -2.81330177168672e-06 -5.55546123940195e-06 -6.86148126659773e-07 2.29885815981675e-05 -4.05097583319231e-06 2.73533773362876e-05 1.86518217869218e-06 -1.80536676908187e-06 -2.01215290885216e-06 -4.05097583319231e-06 7.35604945348073e-05 1333 1333 0 0 0 1387 1397 0 0 1 0 0 0 0 0 0 0 0 1075 0 13 74 0 0 2836 +1284 1286 0.999991019595733 0.00144819914660675 -0.00398289431430711 -0.00826699457178498 -0.00140091099881965 0.999928803973143 0.0118500815699106 0.00430432409777187 0.0039997720260733 -0.0118443954709354 0.999921853006357 0.00304470012395697 6.18179944873723e-05 2.79749255624633e-05 2.72544996188248e-07 1.46320637934993e-05 -4.87731233231443e-06 1.55249056296613e-05 2.79749255624633e-05 5.68397765240181e-05 1.82476275382872e-06 1.02641259495761e-05 -6.07877106113591e-06 1.03638785421051e-05 2.72544996188248e-07 1.82476275382872e-06 1.35103924111192e-05 2.54201466840471e-06 -5.37041830103597e-06 2.15260958582019e-06 1.46320637934993e-05 1.02641259495761e-05 2.54201466840471e-06 2.52733790293017e-05 -9.63288460648503e-06 6.50174359309943e-07 -4.87731233231443e-06 -6.07877106113591e-06 -5.37041830103597e-06 -9.63288460648503e-06 2.00903155048194e-05 -2.55717983121852e-07 1.55249056296613e-05 1.03638785421051e-05 2.15260958582019e-06 6.50174359309943e-07 -2.55717983121852e-07 4.64539908787021e-05 1260 1261 0 0 0 1270 1358 0 0 0 0 0 0 0 0 0 0 0 831 0 0 0 0 0 3355 +1283 1286 0.999986445903504 0.0032726610012996 -0.00404940727142467 -0.00183853683553092 -0.00326675036960974 0.999993590476525 0.00146538318927637 -0.00305156122310261 0.00405417701906921 -0.00145213492463059 0.999990727433439 0.00120952313080619 4.64570485707031e-05 1.31875366766376e-05 4.35818628732923e-06 3.51505324617666e-07 4.18378950335384e-06 1.65017327678602e-05 1.31875366766376e-05 4.51661704539018e-05 1.60133724632371e-06 1.09722426476083e-06 -2.61127550975137e-06 1.2106139076926e-05 4.35818628732923e-06 1.60133724632371e-06 1.28261392568951e-05 1.20304554250632e-06 -1.64918341567164e-06 4.2797768423976e-07 3.51505324617666e-07 1.09722426476083e-06 1.20304554250632e-06 2.33876673326802e-05 -6.18712840768409e-07 -2.54091191634e-06 4.18378950335384e-06 -2.61127550975137e-06 -1.64918341567164e-06 -6.18712840768409e-07 2.21209404169123e-05 -5.7259863680639e-06 1.65017327678602e-05 1.2106139076926e-05 4.2797768423976e-07 -2.54091191634e-06 -5.7259863680639e-06 3.90780762765606e-05 1256 1274 0 0 0 1270 1355 0 0 0 0 0 0 0 0 0 0 0 828 0 0 0 0 0 3461 +1283 1312 0.995829400759528 0.000766962573147573 0.0912316630963725 -0.0175052494055335 -0.0137812794334994 0.989755299157138 0.142107438677711 -0.0275314260154802 -0.0901880309137218 -0.14277205454421 0.985637996183756 0.014325744179892 0.000101148811102269 -4.90259629896907e-05 1.9957440813063e-06 -1.62541717585581e-06 -4.57446811260418e-06 8.13097159493052e-06 -4.90259629896907e-05 7.85263741882566e-05 -5.59127593535086e-06 -6.57763314905798e-07 -2.37443912671161e-06 1.8181370534099e-05 1.9957440813063e-06 -5.59127593535086e-06 1.44922522257567e-05 2.09494416253067e-07 -4.38199798011924e-06 -3.08586074385289e-06 -1.62541717585581e-06 -6.57763314905798e-07 2.09494416253067e-07 2.6269356323111e-05 -2.39511363111758e-07 -6.32706050622933e-06 -4.57446811260418e-06 -2.37443912671161e-06 -4.38199798011924e-06 -2.39511363111758e-07 2.46533782769819e-05 -1.66664693000765e-06 8.13097159493052e-06 1.8181370534099e-05 -3.08586074385289e-06 -6.32706050622933e-06 -1.66664693000765e-06 5.54883637601508e-05 1320 1320 0 0 0 1382 1411 0 0 1 0 0 0 0 0 0 0 0 1068 0 8 48 0 0 2776 +1283 1287 0.999989392341394 0.00399329192426829 0.00229539197042625 -0.00529118229253263 -0.00400094339948067 0.999986423219732 0.00333853682352889 -0.00544848847359881 -0.00228202905425756 -0.00334768514282332 0.99999179264011 0.00199366367812702 4.18508887401245e-05 1.39241330236338e-05 -1.89414569908836e-06 4.82901688197186e-06 -8.42420799502043e-08 1.78124154748013e-05 1.39241330236338e-05 3.66176226124307e-05 -9.95751790987117e-08 4.47679526296666e-06 5.36193422410495e-08 7.87299882968332e-06 -1.89414569908836e-06 -9.95751790987117e-08 1.09928489814251e-05 1.83345993925693e-06 -3.02403230223718e-06 7.74138619132504e-07 4.82901688197186e-06 4.47679526296666e-06 1.83345993925693e-06 2.16291432654572e-05 -6.89922923334357e-08 3.72445607276545e-06 -8.42420799502043e-08 5.36193422410495e-08 -3.02403230223718e-06 -6.89922923334357e-08 2.00149950094234e-05 -1.36442203240475e-06 1.78124154748013e-05 7.87299882968332e-06 7.74138619132504e-07 3.72445607276545e-06 -1.36442203240475e-06 4.72754254743805e-05 1213 1213 0 0 0 1244 1296 0 0 3 0 0 0 0 0 0 0 0 786 0 0 1 0 0 3381 +1283 1311 0.996347608426604 -0.000551895724886564 0.0853881642482982 -0.0175927842736151 -0.0115205445407427 0.989967409849662 0.140825439779306 -0.0261506052507965 -0.0846092207508748 -0.141294808279211 0.986345303084711 0.00875801935857979 8.62434698167859e-05 -4.07222639718908e-05 2.26925335843074e-06 -5.18514530222403e-06 -1.93028805713088e-07 3.15461735711392e-05 -4.07222639718908e-05 7.7167758139695e-05 -3.62018721515284e-06 5.99817563270711e-06 8.61906437419886e-07 3.93668501947716e-06 2.26925335843074e-06 -3.62018721515284e-06 1.35893564122417e-05 4.20166554100439e-06 -3.65700264598599e-06 -5.60498017600771e-06 -5.18514530222403e-06 5.99817563270711e-06 4.20166554100439e-06 2.23190983509932e-05 -6.2228373289963e-06 -6.46765371153411e-06 -1.93028805713088e-07 8.61906437419886e-07 -3.65700264598599e-06 -6.2228373289963e-06 2.39604446575021e-05 -6.1768960168625e-06 3.15461735711392e-05 3.93668501947716e-06 -5.60498017600771e-06 -6.46765371153411e-06 -6.1768960168625e-06 7.31644308461914e-05 1344 1358 0 0 0 1390 1430 0 0 2 0 0 0 0 0 0 0 0 968 0 3 38 0 0 2828 +1283 1314 0.9960458481619 0.000279403136657202 0.0888402515379619 -0.0187359457650586 -0.0128839293905337 0.989877706238883 0.141336941578296 -0.0250865708153068 -0.0879014944292807 -0.141922685378815 0.985967179297549 0.00721250082861257 9.88184249249551e-05 -4.34708458780481e-05 6.51071843462242e-08 5.81632126429666e-07 -2.59018735283242e-06 1.75460173695136e-05 -4.34708458780481e-05 7.11030915976381e-05 -3.53191028051952e-07 5.48789456871738e-06 -3.52456250738514e-06 2.29304579940469e-05 6.51071843462242e-08 -3.53191028051952e-07 1.52903759432274e-05 4.98466109458479e-07 -5.52367973792095e-06 -1.38663514756542e-06 5.81632126429666e-07 5.48789456871738e-06 4.98466109458479e-07 2.97469076158921e-05 -5.86681298419226e-06 3.044089622494e-06 -2.59018735283242e-06 -3.52456250738514e-06 -5.52367973792095e-06 -5.86681298419226e-06 2.09046909455619e-05 -7.27816030461272e-06 1.75460173695136e-05 2.29304579940469e-05 -1.38663514756542e-06 3.044089622494e-06 -7.27816030461272e-06 7.26299260824219e-05 1343 1358 0 0 0 1389 1430 0 0 1 0 0 0 0 0 0 0 0 1073 0 4 39 0 0 2628 +1284 1310 0.99756373820311 0.00186257797581849 0.0697360668916887 -0.0265518125050293 -0.0109028978415876 0.991521860768594 0.129481761019229 -0.0300938462166288 -0.0689036649307857 -0.129926634764658 0.989126561435814 0.00850432319152355 0.000129464463720334 -8.11472136578854e-05 9.23337060075375e-06 -1.02539471233007e-05 -1.14043522457499e-05 -8.51589896108805e-07 -8.11472136578854e-05 9.93854596304594e-05 -6.66103449075919e-06 9.60588541725391e-06 2.60892908705486e-06 3.09568795959237e-05 9.23337060075375e-06 -6.66103449075919e-06 1.83019981894957e-05 2.21313758244975e-06 -1.02443793359163e-06 2.66964883946658e-06 -1.02539471233007e-05 9.60588541725391e-06 2.21313758244975e-06 2.83251617531565e-05 -2.40312558224407e-06 3.24852155748325e-06 -1.14043522457499e-05 2.60892908705486e-06 -1.02443793359163e-06 -2.40312558224407e-06 3.47483199736471e-05 -2.4454605505317e-06 -8.51589896108805e-07 3.09568795959237e-05 2.66964883946658e-06 3.24852155748325e-06 -2.4454605505317e-06 7.64753835955488e-05 1325 1325 0 0 0 1387 1395 0 0 0 0 0 0 0 0 0 0 0 1067 0 11 69 0 0 2527 +1284 1311 0.996253982167489 -0.00258662301413838 0.0864367537382301 -0.020879344900001 -0.0107864202699021 0.988029251195322 0.15388908967231 -0.0209356347511298 -0.0858000941327092 -0.154244961550755 0.984300175598392 0.00298429749533633 0.000119634662328406 -5.88712620623398e-05 3.45615348143651e-06 7.07748457089036e-06 -2.41523666527632e-06 2.18781234935635e-05 -5.88712620623398e-05 9.75643501119391e-05 -3.92725593316222e-06 1.11122268308664e-06 -3.94523112920565e-06 1.04908777519733e-05 3.45615348143651e-06 -3.92725593316222e-06 1.5561280022624e-05 4.10856731530973e-06 -6.93494186083075e-06 -4.41476637490787e-06 7.07748457089036e-06 1.11122268308664e-06 4.10856731530973e-06 2.4894600673721e-05 -1.26416703973541e-05 2.64461258360635e-07 -2.41523666527632e-06 -3.94523112920565e-06 -6.93494186083075e-06 -1.26416703973541e-05 2.49934747079172e-05 -2.82397990693022e-06 2.18781234935635e-05 1.04908777519733e-05 -4.41476637490787e-06 2.64461258360635e-07 -2.82397990693022e-06 6.56670817343112e-05 1350 1353 0 0 0 1390 1432 0 0 0 0 0 0 0 0 0 0 0 968 0 2 32 0 0 2773 +1284 1313 0.996705228910295 -0.000673231215400523 0.0811063093884029 -0.0203913928956524 -0.0110629724075365 0.989491842082884 0.144164853875452 -0.0222565246420994 -0.0803510877610678 -0.144587140545593 0.986224245029731 0.0117926597962914 0.000107800069766378 -6.31809986880739e-05 2.55615499743981e-06 -2.08118856373877e-06 -2.31583415721929e-06 1.73670285146905e-05 -6.31809986880739e-05 8.14958890703116e-05 -1.22555314862033e-06 2.84980892660711e-07 -4.60796351272843e-06 1.30425845054067e-06 2.55615499743981e-06 -1.22555314862033e-06 1.28543323151033e-05 1.76075364852727e-06 -4.60599694116458e-06 -1.01356032510519e-06 -2.08118856373877e-06 2.84980892660711e-07 1.76075364852727e-06 2.91927403437031e-05 -1.43948769798482e-06 6.98750997993568e-08 -2.31583415721929e-06 -4.60796351272843e-06 -4.60599694116458e-06 -1.43948769798482e-06 2.51379547505137e-05 -4.53742665653796e-07 1.73670285146905e-05 1.30425845054067e-06 -1.01356032510519e-06 6.98750997993568e-08 -4.53742665653796e-07 5.83210079364838e-05 1331 1331 0 0 0 1390 1412 0 0 0 0 0 0 0 0 0 0 0 1075 0 4 44 0 0 2805 +1284 1314 0.99662736344774 -0.000504755864544295 0.0820587816673149 -0.0218659308825037 -0.011911079412978 0.988501091493225 0.150743883139319 -0.0199558149866992 -0.0811912841038038 -0.151212887473985 0.985161224392919 0.00862668756848026 0.000151600881405595 -4.98773082754486e-05 5.06770183453075e-07 4.80492913363607e-07 -1.71557185556213e-05 1.22260152976884e-05 -4.98773082754486e-05 6.36003350728362e-05 -1.26811880823559e-06 3.01486614256533e-06 1.52601679313382e-06 1.31526559886574e-05 5.06770183453075e-07 -1.26811880823559e-06 1.59403089151044e-05 1.98875854026585e-06 -5.99115315269897e-06 -1.35039716953276e-06 4.80492913363607e-07 3.01486614256533e-06 1.98875854026585e-06 2.52256674896944e-05 -9.24065497615635e-06 3.00738357259334e-06 -1.71557185556213e-05 1.52601679313382e-06 -5.99115315269897e-06 -9.24065497615635e-06 2.66378599921904e-05 -1.78133802803544e-06 1.22260152976884e-05 1.31526559886574e-05 -1.35039716953276e-06 3.00738357259334e-06 -1.78133802803544e-06 6.55123543420839e-05 1350 1351 0 0 0 1391 1433 0 0 0 0 0 0 0 0 0 0 0 1071 0 2 32 0 0 2537 +1284 1288 0.999981721589511 0.0017711901850223 0.00578094907490716 -0.00868266136044258 -0.00192648164155694 0.9996344264964 0.0269685378116526 0.00405387848121977 -0.00573106930362331 -0.0269791817619118 0.999619566933388 0.00906572939341054 0.000110573137922889 5.40117144276476e-05 4.69566661305031e-06 1.11273026374325e-05 -7.50557627100157e-06 1.55257620861588e-05 5.40117144276476e-05 9.13504753723453e-05 8.23946083650672e-06 -2.85665909552464e-06 -9.02054411137799e-06 1.89960348963377e-05 4.69566661305031e-06 8.23946083650672e-06 1.26752295549885e-05 6.31197396974519e-07 -5.65074709098705e-06 4.48401854924034e-06 1.11273026374325e-05 -2.85665909552464e-06 6.31197396974519e-07 2.37911580658231e-05 -1.0973554605813e-05 -8.97498554670094e-06 -7.50557627100157e-06 -9.02054411137799e-06 -5.65074709098705e-06 -1.0973554605813e-05 2.24718945036232e-05 2.21537071460216e-06 1.55257620861588e-05 1.89960348963377e-05 4.48401854924034e-06 -8.97498554670094e-06 2.21537071460216e-06 5.40122065283355e-05 1265 1268 0 0 0 1278 1363 0 0 0 0 0 0 0 0 0 0 0 789 0 0 0 0 0 3404 +1284 1287 0.999996408340961 0.00219046668352399 -0.00154439660937115 -0.00427701514578251 -0.00217414639089964 0.999942603597421 0.0104910723132742 0.00200034128981104 0.00156728831093829 -0.0104876768886051 0.999943774539764 -0.00491249120422057 5.48195479763988e-05 2.14883234923304e-05 7.31895414713537e-07 1.21291647470007e-05 -4.32547305752353e-06 1.90119286321626e-05 2.14883234923304e-05 3.54628317330659e-05 1.88182801761175e-06 6.14240984969756e-06 -8.39253792509007e-06 1.90636290387804e-05 7.31895414713537e-07 1.88182801761175e-06 1.09421352702482e-05 1.79155444353708e-06 -3.19439696620531e-06 -2.22829768141112e-07 1.21291647470007e-05 6.14240984969756e-06 1.79155444353708e-06 2.49295360286767e-05 -8.6123360243275e-06 3.60842454851602e-06 -4.32547305752353e-06 -8.39253792509007e-06 -3.19439696620531e-06 -8.6123360243275e-06 2.18479016738397e-05 -5.17477207406263e-06 1.90119286321626e-05 1.90636290387804e-05 -2.22829768141112e-07 3.60842454851602e-06 -5.17477207406263e-06 4.6921772823654e-05 1239 1241 0 0 0 1247 1315 0 0 0 0 0 0 0 0 0 0 0 788 0 0 0 0 0 3471 +1284 1315 0.996347774622779 -0.000682873039693081 0.0853852779385753 -0.0241123125040319 -0.012194173080533 0.98858070609359 0.150198168039366 -0.0234006758503057 -0.0845128046340796 -0.150690813336153 0.984961859479325 0.00452604317211688 0.000102450816212707 -5.1125167164766e-05 1.71367518463187e-06 -2.66774729509357e-07 1.25371939704124e-06 2.56087960526781e-05 -5.1125167164766e-05 8.3085199890618e-05 6.42516020834969e-07 8.78185172122679e-06 -5.75772612138243e-06 7.66237511636284e-06 1.71367518463187e-06 6.42516020834969e-07 1.41166676538984e-05 3.32710535545865e-06 -6.40424146174493e-06 -2.60027454579004e-06 -2.66774729509357e-07 8.78185172122679e-06 3.32710535545865e-06 2.62660784576447e-05 -9.72283571328777e-06 2.56546429300316e-06 1.25371939704124e-06 -5.75772612138243e-06 -6.40424146174493e-06 -9.72283571328777e-06 2.29659609029821e-05 -4.72150873217947e-06 2.56087960526781e-05 7.66237511636284e-06 -2.60027454579004e-06 2.56546429300316e-06 -4.72150873217947e-06 7.12245803327115e-05 1235 1235 0 0 0 1278 1301 0 0 3 0 0 0 0 0 0 0 0 1070 0 3 33 0 0 2776 +1284 1316 0.996229329474571 -0.00051488762211059 0.0867574664532318 -0.0221712601972145 -0.0128860603966637 0.988012786878688 0.153833294223528 -0.0203278687392758 -0.085796693072056 -0.154371201507748 0.984280681311461 0.00555564545608044 0.000118813943594267 -7.09805593724353e-05 5.07537555449613e-06 4.34921445650953e-07 3.97829627668215e-06 1.52425173477751e-05 -7.09805593724353e-05 9.10699093369356e-05 -5.93857690806406e-06 3.08090858371095e-06 -1.22816477348841e-05 1.44173104764502e-05 5.07537555449613e-06 -5.93857690806406e-06 1.37638482556181e-05 3.02593673689038e-06 -5.426924812517e-06 -4.95398105259005e-06 4.34921445650953e-07 3.08090858371095e-06 3.02593673689038e-06 2.52686461419512e-05 -1.09781778695422e-05 9.14854777008744e-06 3.97829627668215e-06 -1.22816477348841e-05 -5.426924812517e-06 -1.09781778695422e-05 2.5196186563218e-05 -7.20151089447615e-06 1.52425173477751e-05 1.44173104764502e-05 -4.95398105259005e-06 9.14854777008744e-06 -7.20151089447615e-06 6.94074477181088e-05 1253 1256 0 0 0 1293 1318 0 0 2 0 0 0 0 0 0 0 0 1058 0 2 32 0 0 2830 +1285 1287 0.999997892409082 0.00163040703517649 -0.00124777814305075 -0.00595204306247077 -0.00162922965485236 0.999998227219791 0.000944016952847152 -0.0058921358402098 0.0012493150628956 -0.000941982046092261 0.9999987759401 0.00526462153317905 6.28288088614218e-05 3.356216801701e-05 -3.68872122200566e-07 3.82950055606531e-06 -1.49990020028592e-06 2.33141196767945e-05 3.356216801701e-05 4.54551214286545e-05 1.90107568661131e-06 3.42761564633636e-06 -2.33963453312675e-06 1.34429759412909e-05 -3.68872122200566e-07 1.90107568661131e-06 1.23097823020577e-05 -2.81313323505624e-07 -1.7082527482657e-06 2.10561921540768e-07 3.82950055606531e-06 3.42761564633636e-06 -2.81313323505624e-07 2.18692162666918e-05 -7.47941654453016e-07 6.64507657477184e-07 -1.49990020028592e-06 -2.33963453312675e-06 -1.7082527482657e-06 -7.47941654453016e-07 2.25696127380369e-05 1.02066111852939e-06 2.33141196767945e-05 1.34429759412909e-05 2.10561921540768e-07 6.64507657477184e-07 1.02066111852939e-06 5.3942399810242e-05 1204 1206 0 0 0 1240 1297 0 0 3 0 0 0 0 0 0 0 0 786 0 1 2 0 0 3339 +1285 1289 0.999562772358408 0.00115716612904138 0.0295453055784404 -0.00581144809161911 -0.0026889832218189 0.998650774297941 0.0518594288761084 -0.00982941231432302 -0.0294454323182119 -0.0519162013313106 0.998217248175426 0.00252578046082187 6.74108004714751e-05 1.08314973421666e-05 2.65158724523469e-06 9.48368686797438e-06 1.41579368822856e-06 2.01328608276737e-05 1.08314973421666e-05 4.16560196563954e-05 5.04571779675221e-06 -2.58854609060061e-06 -6.62211167897502e-08 1.59408421255092e-05 2.65158724523469e-06 5.04571779675221e-06 1.14897653230405e-05 2.56491116112271e-06 -4.44981487717521e-06 1.52771733361034e-06 9.48368686797438e-06 -2.58854609060061e-06 2.56491116112271e-06 2.10212600507331e-05 -5.54778283912595e-06 1.59226615734879e-06 1.41579368822856e-06 -6.62211167897502e-08 -4.44981487717521e-06 -5.54778283912595e-06 1.5722926207406e-05 -1.20014881443919e-06 2.01328608276737e-05 1.59408421255092e-05 1.52771733361034e-06 1.59226615734879e-06 -1.20014881443919e-06 3.96554332441415e-05 1370 1372 0 0 0 1397 1464 0 0 0 0 0 0 0 0 0 0 0 820 0 0 6 0 0 3427 +1284 1312 0.99555442742063 -0.00119401678033203 0.0941804457788823 -0.0201480487728212 -0.0128623631684619 0.988828653764241 0.148500683865503 -0.0240794424545227 -0.0933056357188744 -0.149051896394268 0.984417386337914 -0.000363720114586709 9.54009939946515e-05 -4.77655557939373e-05 3.16376593272935e-06 7.89827683423308e-07 -6.3233687751666e-06 3.28363025122058e-05 -4.77655557939373e-05 8.30367122529485e-05 -3.4497181229101e-06 3.49883329699172e-06 -1.63568477448856e-06 -7.71686772016262e-06 3.16376593272935e-06 -3.4497181229101e-06 1.56190805497188e-05 -6.09035505317551e-07 -5.97891145737521e-06 -2.6502364234959e-06 7.89827683423308e-07 3.49883329699172e-06 -6.09035505317551e-07 2.55103540287555e-05 -3.85430751575578e-06 -1.61360039655498e-06 -6.3233687751666e-06 -1.63568477448856e-06 -5.97891145737521e-06 -3.85430751575578e-06 2.51892481247959e-05 -1.02794816237063e-06 3.28363025122058e-05 -7.71686772016262e-06 -2.6502364234959e-06 -1.61360039655498e-06 -1.02794816237063e-06 7.6007609113627e-05 1322 1322 0 0 0 1386 1406 0 0 0 0 0 0 0 0 0 0 0 1070 0 8 50 0 0 2682 +1284 1317 0.996552610214631 0.000126763293554171 0.0829631183446714 -0.0220326560249546 -0.01235405730238 0.989076331977976 0.146885624855404 -0.0233832492024961 -0.0820382370762199 -0.147404183970675 0.985668166375158 0.00990461339674766 0.000107772199041545 -4.59272272898289e-05 1.65184806550023e-06 1.08364704292541e-05 -6.40779209080376e-06 1.15209725254431e-05 -4.59272272898289e-05 8.81516417450776e-05 5.4228988506381e-07 1.8532615997372e-06 -5.73507243019121e-06 1.07895846048116e-05 1.65184806550023e-06 5.4228988506381e-07 1.42103072711914e-05 2.88999898520914e-06 -5.23253131565575e-06 4.98383585536004e-07 1.08364704292541e-05 1.8532615997372e-06 2.88999898520914e-06 2.50584455777703e-05 -1.34144690401233e-05 5.3725676998662e-06 -6.40779209080376e-06 -5.73507243019121e-06 -5.23253131565575e-06 -1.34144690401233e-05 2.6789334945981e-05 -5.94815617990495e-06 1.15209725254431e-05 1.07895846048116e-05 4.98383585536004e-07 5.3725676998662e-06 -5.94815617990495e-06 5.64452458674629e-05 1339 1339 0 0 0 1385 1423 0 0 0 0 0 0 0 0 0 0 0 967 0 3 36 0 0 2847 +1285 1311 0.996528080470605 -0.00251564581700914 0.0832193268399521 -0.021044919112225 -0.00899464483686855 0.990440303394237 0.137648471755375 -0.0286867351434661 -0.0827700501258154 -0.137919095626584 0.986978947021523 0.00730832618644238 0.000162771249789771 -7.99229197425312e-05 -1.12524501815755e-06 -8.89548791477678e-06 -2.48824560990196e-05 2.28440567210279e-05 -7.99229197425312e-05 0.000100216585068324 -1.91620991230767e-06 1.38352105182586e-05 1.44279062374218e-05 1.5572861211706e-06 -1.12524501815755e-06 -1.91620991230767e-06 1.46678969314112e-05 4.32024952287416e-06 -5.33349500776054e-06 -6.17899351710856e-06 -8.89548791477678e-06 1.38352105182586e-05 4.32024952287416e-06 2.89627588396582e-05 -4.8419901435708e-07 -4.00564554690216e-06 -2.48824560990196e-05 1.44279062374218e-05 -5.33349500776054e-06 -4.8419901435708e-07 3.17603655077431e-05 -6.00761183005007e-06 2.28440567210279e-05 1.5572861211706e-06 -6.17899351710856e-06 -4.00564554690216e-06 -6.00761183005007e-06 6.3334448476354e-05 1337 1337 0 0 0 1393 1429 0 0 1 0 0 0 0 0 0 0 0 970 0 5 35 0 0 2734 +1285 1317 0.996135074997638 -0.000666350731994582 0.0878320461799235 -0.0176192966750361 -0.0118419091048069 0.989822657630165 0.141812818992891 -0.028694019149476 -0.0870326464506495 -0.142304822190462 0.985989176427986 0.00742239945659286 0.000106510776828802 -3.97532915195667e-05 1.88802374421883e-06 1.76182465847384e-06 -1.21401916047445e-06 1.45803151770059e-05 -3.97532915195667e-05 6.53085218540253e-05 -1.79860344103956e-06 2.14685403021659e-06 -5.78195828345465e-07 1.62655007771362e-05 1.88802374421883e-06 -1.79860344103956e-06 1.46017092743078e-05 1.30369876048884e-06 -5.27206833763877e-06 -1.81385885461435e-06 1.76182465847384e-06 2.14685403021659e-06 1.30369876048884e-06 2.47610882095595e-05 -8.3749828611172e-06 3.78275409565028e-06 -1.21401916047445e-06 -5.78195828345465e-07 -5.27206833763877e-06 -8.3749828611172e-06 2.14282935289625e-05 -2.90418257730723e-06 1.45803151770059e-05 1.62655007771362e-05 -1.81385885461435e-06 3.78275409565028e-06 -2.90418257730723e-06 4.9265997130082e-05 1336 1336 0 0 0 1389 1426 0 0 3 0 0 0 0 0 0 0 0 970 0 5 38 0 0 2752 +1284 1318 0.996786920794177 0.000204815334530984 0.0800986428370775 -0.0240625227151062 -0.0119227673067398 0.989235861049376 0.145843268043641 -0.0262771145996612 -0.0792065789780893 -0.146329659551913 0.986059809840158 0.01429361328852 0.000112107677679081 -6.39374962820708e-05 4.25043752824853e-06 -1.93553857489308e-06 -5.88574498324272e-06 1.50011513597409e-05 -6.39374962820708e-05 7.62970075240853e-05 -3.85039976701887e-06 2.48064891057396e-06 2.00475722141869e-06 -7.15144169838978e-07 4.25043752824853e-06 -3.85039976701887e-06 1.39941560604207e-05 3.29673063711985e-06 -4.77421488993314e-06 -1.94637601613714e-06 -1.93553857489308e-06 2.48064891057396e-06 3.29673063711985e-06 2.67676604625382e-05 -5.59615806245885e-06 -6.32173431666845e-06 -5.88574498324272e-06 2.00475722141869e-06 -4.77421488993314e-06 -5.59615806245885e-06 2.43718610664065e-05 -4.33895213044209e-06 1.50011513597409e-05 -7.15144169838978e-07 -1.94637601613714e-06 -6.32173431666845e-06 -4.33895213044209e-06 6.50405918115839e-05 1338 1340 0 0 0 1396 1413 0 0 0 0 0 0 0 0 0 0 0 1078 0 9 58 0 0 2816 +1285 1316 0.995784415059156 -0.00081113755925387 0.0917209942224448 -0.0197881738307907 -0.0124085074636135 0.989577393749846 0.143466409733383 -0.0298018850155373 -0.0908813934082177 -0.143999735538374 0.985395681184497 0.00528274937352933 0.000102421375662351 -3.78432737353852e-05 9.22477238960878e-06 -6.07690374132614e-06 -6.56008590754005e-08 1.51251849157865e-05 -3.78432737353852e-05 4.90799832590574e-05 -4.60756659183498e-06 7.5831998907683e-07 8.34369914227919e-07 9.0760618318048e-06 9.22477238960878e-06 -4.60756659183498e-06 1.42188418353037e-05 6.57062267959491e-07 -4.60712294193035e-06 -2.54920230781131e-06 -6.07690374132614e-06 7.5831998907683e-07 6.57062267959491e-07 2.63393630002062e-05 -6.94965222581556e-06 2.53615318024653e-06 -6.56008590754005e-08 8.34369914227919e-07 -4.60712294193035e-06 -6.94965222581556e-06 2.41727806809849e-05 -4.82040321035124e-06 1.51251849157865e-05 9.0760618318048e-06 -2.54920230781131e-06 2.53615318024653e-06 -4.82040321035124e-06 5.10551357921423e-05 1244 1246 0 0 0 1290 1311 0 0 6 0 0 0 0 0 0 0 0 1061 0 5 39 0 0 2753 +1285 1288 0.999977435659509 0.00154344837229933 0.0065380378519908 -0.00425263630685092 -0.00164862801539367 0.999868824180824 0.0161126179413247 -0.0028125497889956 -0.00651231122558475 -0.0161230331630958 0.999848807372456 -0.000375740826843797 5.17992997065e-05 1.97110955807921e-05 2.93541065576936e-06 4.80804448596679e-06 8.5601821140768e-07 2.07842238359778e-05 1.97110955807921e-05 3.62038180667691e-05 4.34978061316206e-06 -2.22977724122622e-06 -3.05260344074124e-06 1.23315815301727e-05 2.93541065576936e-06 4.34978061316206e-06 1.06273060860817e-05 1.11281842880334e-06 -5.62700453476422e-06 1.65341408617987e-06 4.80804448596679e-06 -2.22977724122622e-06 1.11281842880334e-06 2.24272878472258e-05 -2.51193792663891e-06 7.67912918220303e-08 8.5601821140768e-07 -3.05260344074124e-06 -5.62700453476422e-06 -2.51193792663891e-06 1.69418940918075e-05 1.59483577356335e-06 2.07842238359778e-05 1.23315815301727e-05 1.65341408617987e-06 7.67912918220303e-08 1.59483577356335e-06 4.10141593050862e-05 1266 1271 0 0 0 1278 1358 0 0 1 0 0 0 0 0 0 0 0 790 0 0 0 0 0 3388 +1285 1312 0.995700167025144 -0.00175963731683191 0.092617930567535 -0.0187769176467351 -0.0122342377330574 0.988563632462644 0.150307245332196 -0.0257389131908405 -0.0918232041108921 -0.150794059063264 0.98429144613678 0.00892116566138381 0.000101844460848816 -4.51782969732842e-05 6.26562944182205e-06 -3.17648345912124e-06 1.2600934565282e-06 1.14170370275729e-05 -4.51782969732842e-05 7.34706223155692e-05 -5.60329112505e-06 4.98374571678129e-06 -2.4407020267009e-06 1.41673969807572e-05 6.26562944182205e-06 -5.60329112505e-06 1.56937156040148e-05 -1.83786839737863e-06 -6.01717482470085e-06 -4.2198245595269e-06 -3.17648345912124e-06 4.98374571678129e-06 -1.83786839737863e-06 2.51949191024737e-05 -4.20861310929486e-06 2.00512097458732e-06 1.2600934565282e-06 -2.4407020267009e-06 -6.01717482470085e-06 -4.20861310929486e-06 2.31053938457243e-05 2.09668068859972e-06 1.14170370275729e-05 1.41673969807572e-05 -4.2198245595269e-06 2.00512097458732e-06 2.09668068859972e-06 5.50618648587989e-05 1321 1322 0 0 0 1388 1421 0 0 1 0 0 0 0 0 0 0 0 1068 0 6 39 0 0 2675 +1285 1313 0.996677927611655 -0.000954346442726223 0.0814383069237274 -0.0174261590636127 -0.0104593757066305 0.990151370969289 0.139609684576199 -0.0267891878898532 -0.0807694872557918 -0.13999768494695 0.986852034571511 0.0141083647676121 0.000129432197116673 -7.34652744329658e-05 2.32849200089449e-06 -2.10429380972896e-06 -5.14979686791902e-06 1.52131081137628e-05 -7.34652744329658e-05 8.09057750233048e-05 1.15871226662683e-07 1.25788758639426e-06 5.46155843021648e-06 8.94483359198743e-06 2.32849200089449e-06 1.15871226662683e-07 1.19746183032971e-05 6.07468485645055e-07 -5.69071993839395e-06 -2.53721229617722e-06 -2.10429380972896e-06 1.25788758639426e-06 6.07468485645055e-07 3.1113113584453e-05 2.1044213909213e-06 -2.85403667438244e-06 -5.14979686791902e-06 5.46155843021648e-06 -5.69071993839395e-06 2.1044213909213e-06 2.03972197352574e-05 -5.90891899990095e-06 1.52131081137628e-05 8.94483359198743e-06 -2.53721229617722e-06 -2.85403667438244e-06 -5.90891899990095e-06 6.17455679747618e-05 1323 1323 0 0 0 1392 1420 0 0 0 0 0 0 0 0 0 0 0 1075 0 5 38 0 0 2739 +1286 1288 0.999997844635821 0.000499999533664891 0.00201512386188963 -0.00357145915360772 -0.000528434710890054 0.999899954260129 0.0141351415751125 -0.0019361422141719 -0.00200785469313609 -0.01413617597013 0.999898063328694 -0.000810185108765141 5.63742757260486e-05 1.99249157720655e-05 2.95323787031326e-06 5.90108586228413e-06 3.1684691136939e-06 2.75609659368159e-05 1.99249157720655e-05 3.36503258973659e-05 3.183727765841e-06 1.0072529769282e-06 -2.80522328872854e-06 1.39878320647086e-05 2.95323787031326e-06 3.183727765841e-06 1.1250126386967e-05 1.98207355027477e-06 -4.19800646365169e-06 8.43727293072925e-07 5.90108586228413e-06 1.0072529769282e-06 1.98207355027477e-06 2.03771624328443e-05 -2.3323510777209e-06 4.90012865965041e-07 3.1684691136939e-06 -2.80522328872854e-06 -4.19800646365169e-06 -2.3323510777209e-06 1.79820336154621e-05 -6.48582589209423e-07 2.75609659368159e-05 1.39878320647086e-05 8.43727293072925e-07 4.90012865965041e-07 -6.48582589209423e-07 3.9204398727552e-05 1266 1266 0 0 0 1278 1363 0 0 0 0 0 0 0 0 0 0 0 783 0 0 0 0 0 3476 +1286 1289 0.99953625980023 -0.000355884967810969 0.0304489522062065 -0.0067741648927989 -0.00109587548467726 0.998863562582084 0.0476485299117261 -0.0107243652743173 -0.0304313062731169 -0.047659801633203 0.998399959388418 0.00125887012843588 4.28240493722181e-05 7.46133897664078e-06 4.78483770105304e-07 5.28715512393023e-07 3.84452194735302e-06 1.87218564162847e-05 7.46133897664078e-06 3.18660178239848e-05 2.36239110420648e-06 -4.60600426995618e-06 -1.70937900942001e-06 1.21231124703703e-05 4.78483770105304e-07 2.36239110420648e-06 1.16705733937167e-05 3.69921097680733e-07 -3.73921631187594e-06 1.32942498270541e-06 5.28715512393023e-07 -4.60600426995618e-06 3.69921097680733e-07 1.84623811831777e-05 -3.63546749946588e-06 2.91267753776346e-06 3.84452194735302e-06 -1.70937900942001e-06 -3.73921631187594e-06 -3.63546749946588e-06 1.68720999678492e-05 2.38296670889107e-07 1.87218564162847e-05 1.21231124703703e-05 1.32942498270541e-06 2.91267753776346e-06 2.38296670889107e-07 4.51840038565076e-05 1364 1364 0 0 0 1397 1462 0 0 0 0 0 0 0 0 0 0 0 814 0 0 4 0 0 3479 +1285 1314 0.996294733387406 -0.00133824965737394 0.085994263252686 -0.0199307331003862 -0.0111819531465604 0.98937633030547 0.144946338191445 -0.0255949777564361 -0.0852746629916873 -0.145370857186491 0.985695462976531 0.0081641673003856 0.000225169254187111 -4.72843110179984e-05 -1.35524801657118e-06 1.06786598498962e-05 -1.2620392153263e-05 4.25011384305329e-05 -4.72843110179984e-05 7.87638151699698e-05 -9.05291062537455e-07 5.38662364741654e-06 -3.70361208118736e-08 1.1374822467771e-05 -1.35524801657118e-06 -9.05291062537455e-07 1.78300692881212e-05 -2.6367403943816e-06 -4.91770236138984e-06 -3.44745837376917e-06 1.06786598498962e-05 5.38662364741654e-06 -2.6367403943816e-06 3.40885141914436e-05 -6.44908168538828e-06 8.16124159541639e-06 -1.2620392153263e-05 -3.70361208118736e-08 -4.91770236138984e-06 -6.44908168538828e-06 2.64525706671261e-05 -1.67637201634597e-06 4.25011384305329e-05 1.1374822467771e-05 -3.44745837376917e-06 8.16124159541639e-06 -1.67637201634597e-06 7.16695530864357e-05 1343 1344 0 0 0 1393 1431 0 0 2 0 0 0 0 0 0 0 0 1075 0 5 34 0 0 2483 +1285 1315 0.996201631657899 -0.000843710015073317 0.0870723678071921 -0.0211624024341917 -0.0116259645734576 0.989711597273714 0.142603615556023 -0.0296860775767414 -0.0862968483194907 -0.143074254760679 0.985942499132074 0.00464266626263894 0.000138307650506527 -7.6753661805685e-05 3.03693617373425e-06 -5.46692519878744e-06 -5.30390471544145e-06 2.46713500892765e-05 -7.6753661805685e-05 8.27844628296301e-05 -5.03830128775599e-06 9.30616716696019e-06 4.76678194560104e-06 -2.33848388469508e-06 3.03693617373425e-06 -5.03830128775599e-06 1.50639598394491e-05 1.33836621310631e-06 -5.12126566028614e-06 -2.86115165990747e-06 -5.46692519878744e-06 9.30616716696019e-06 1.33836621310631e-06 3.13129655410566e-05 -7.55329994905495e-06 3.2009859085645e-06 -5.30390471544145e-06 4.76678194560104e-06 -5.12126566028614e-06 -7.55329994905495e-06 2.57019620624903e-05 -5.26029079692142e-06 2.46713500892765e-05 -2.33848388469508e-06 -2.86115165990747e-06 3.2009859085645e-06 -5.26029079692142e-06 6.45119027231569e-05 1230 1231 0 0 0 1278 1297 0 0 6 0 0 0 0 0 0 0 0 1074 0 5 37 0 0 2725 +1285 1318 0.996494056650929 0.000433071729731978 0.0836624617630336 -0.0201697126378445 -0.0122113294361087 0.990030481667075 0.140322944679272 -0.0319680046264345 -0.082767617416336 -0.140852610266676 0.986564779266059 0.0129528552480831 0.000103809584691891 -4.67771897154832e-05 3.28399399627549e-06 1.06579252453848e-06 5.94574318812677e-06 1.31538888000894e-05 -4.67771897154832e-05 7.05723572605128e-05 -4.97036170845214e-06 2.83241769850692e-06 -3.80974552525183e-06 1.29379985692851e-05 3.28399399627549e-06 -4.97036170845214e-06 1.62067347253402e-05 8.15703013426071e-07 -1.49380030654608e-06 -1.8470084755297e-06 1.06579252453848e-06 2.83241769850692e-06 8.15703013426071e-07 3.05249754995432e-05 -6.38607115504936e-06 2.78599004690805e-06 5.94574318812677e-06 -3.80974552525183e-06 -1.49380030654608e-06 -6.38607115504936e-06 2.92839171851647e-05 8.85625381754753e-07 1.31538888000894e-05 1.29379985692851e-05 -1.8470084755297e-06 2.78599004690805e-06 8.85625381754753e-07 6.05857900398169e-05 1336 1336 0 0 0 1394 1403 0 0 1 0 0 0 0 0 0 0 0 1081 0 12 69 0 0 2744 +1286 1313 0.996362626723435 -0.00230893418167577 0.0851832430218569 -0.0175636549842638 -0.00994980691843317 0.989643081915449 0.143204649921635 -0.0264184174330825 -0.0846316572628821 -0.143531317975684 0.986020407166658 0.0106909780785228 8.88125316120688e-05 -3.36291970121829e-05 6.51723694934911e-06 -4.99910592169953e-06 2.01312534478585e-06 2.92211387521525e-05 -3.36291970121829e-05 6.57052032292503e-05 -1.1532431336051e-06 2.36629563215325e-06 3.13379201314994e-07 -3.82832601536798e-06 6.51723694934911e-06 -1.1532431336051e-06 1.50942115080582e-05 -2.67523607056427e-06 -3.2557618740863e-06 -5.45169909625358e-06 -4.99910592169953e-06 2.36629563215325e-06 -2.67523607056427e-06 3.49908634075276e-05 1.14011916984628e-06 -2.26790138806166e-07 2.01312534478585e-06 3.13379201314994e-07 -3.2557618740863e-06 1.14011916984628e-06 2.61728742217676e-05 -6.66244284496321e-07 2.92211387521525e-05 -3.82832601536798e-06 -5.45169909625358e-06 -2.26790138806166e-07 -6.66244284496321e-07 6.46614825079847e-05 1334 1334 0 0 0 1386 1407 0 0 0 0 0 0 0 0 0 0 0 1074 0 11 57 0 0 2765 +1286 1314 0.995929353998826 -0.00248411658324354 0.0901030022156977 -0.0193092901753238 -0.0100382587365623 0.990345266956237 0.138258763117995 -0.026171026266925 -0.0895765326691037 -0.138600437885963 0.986288985750525 0.00605216610049113 0.000133825698952953 -3.81960623219212e-05 -5.34675871550435e-06 1.4660415576846e-05 -1.12921100272458e-05 5.29945772592245e-05 -3.81960623219212e-05 0.000122275750495674 -3.34509910363029e-06 6.09060552202928e-06 -3.44922716965302e-06 -1.25199889331634e-06 -5.34675871550435e-06 -3.34509910363029e-06 1.82996920646246e-05 -1.16332462604488e-06 -3.64952640259569e-06 -1.18282895507254e-05 1.4660415576846e-05 6.09060552202928e-06 -1.16332462604488e-06 3.03938087943762e-05 -8.98298342836179e-06 1.31123600939367e-05 -1.12921100272458e-05 -3.44922716965302e-06 -3.64952640259569e-06 -8.98298342836179e-06 2.42895277480185e-05 -6.79744883223294e-06 5.29945772592245e-05 -1.25199889331634e-06 -1.18282895507254e-05 1.31123600939367e-05 -6.79744883223294e-06 0.000100035726814459 1333 1333 0 0 0 1390 1430 0 0 0 0 0 0 0 0 0 0 0 1073 0 4 33 0 0 2679 +1286 1315 0.995970113415858 -0.0022891252735917 0.089656528417535 -0.0185663258294192 -0.0107507118632767 0.989418812665418 0.14468875332308 -0.0250235883486548 -0.0890390665766171 -0.145069545560866 0.985406957339925 0.0086804569181032 0.000142185424886111 -1.63763051258747e-05 6.39072505652636e-06 4.30483023057584e-06 -1.61985239504626e-06 4.10312211818946e-05 -1.63763051258747e-05 9.58072016520472e-05 -1.21611290730786e-05 1.25899789734158e-05 -1.22723849979371e-05 1.23883208030906e-05 6.39072505652636e-06 -1.21611290730786e-05 1.67345938415834e-05 -6.72508272653481e-08 -5.18440840249342e-06 -5.12205876150038e-06 4.30483023057584e-06 1.25899789734158e-05 -6.72508272653481e-08 3.18139488545658e-05 -1.38488260175955e-05 4.81965087087061e-06 -1.61985239504626e-06 -1.22723849979371e-05 -5.18440840249342e-06 -1.38488260175955e-05 2.40178738016743e-05 1.07372861969751e-06 4.10312211818946e-05 1.23883208030906e-05 -5.12205876150038e-06 4.81965087087061e-06 1.07372861969751e-06 7.63397482946936e-05 1243 1243 0 0 0 1282 1309 0 0 2 0 0 0 0 0 0 0 0 1062 0 2 29 0 0 2786 +1286 1318 0.996475193458399 -0.000684753553434278 0.0838851592036211 -0.0200396263743355 -0.0117091548534717 0.989042340309644 0.147167064139501 -0.0306976152219576 -0.0830667473461145 -0.147630553028137 0.985548139513207 0.0138428775864472 0.000150957776774604 -8.46294964758606e-05 6.12261039150872e-06 -1.19321639634606e-05 2.42671164514222e-06 4.70478474966314e-05 -8.46294964758606e-05 0.000107522343859413 -2.33065993043539e-06 4.26225949796271e-06 5.61387381294758e-08 -1.86276409340892e-05 6.12261039150872e-06 -2.33065993043539e-06 1.6756345693099e-05 6.7231760515707e-07 -3.9016171919219e-06 -3.73532669352176e-07 -1.19321639634606e-05 4.26225949796271e-06 6.7231760515707e-07 2.991238881613e-05 -6.90103924620555e-06 -2.00837225235795e-06 2.42671164514222e-06 5.61387381294758e-08 -3.9016171919219e-06 -6.90103924620555e-06 2.55849381455146e-05 -3.79940880755504e-06 4.70478474966314e-05 -1.86276409340892e-05 -3.73532669352176e-07 -2.00837225235795e-06 -3.79940880755504e-06 9.07195408067138e-05 1343 1348 0 0 0 1397 1423 0 0 0 0 0 0 0 0 0 0 0 1072 0 8 49 0 0 2807 +1286 1312 0.99543260070235 -0.00307345598304325 0.0954174581891372 -0.0172019850173632 -0.0109325331190423 0.989236511411275 0.145916428857248 -0.0256978550049084 -0.0948389011880489 -0.146293124784357 0.984684672604521 0.0018607274623934 9.7548146088372e-05 -5.7458039707016e-05 7.45250230649807e-06 7.33196850653124e-07 4.2232344818398e-06 3.32712975333781e-05 -5.7458039707016e-05 8.4768480583003e-05 -8.67097856596681e-06 5.28463430420918e-06 -3.99582023799707e-06 -1.05550909404047e-05 7.45250230649807e-06 -8.67097856596681e-06 1.62513125912435e-05 -2.16186143282243e-06 -2.4200876466021e-06 -3.12968678135594e-06 7.33196850653124e-07 5.28463430420918e-06 -2.16186143282243e-06 2.87931544432115e-05 -4.55193315110898e-06 -1.23365723869075e-06 4.2232344818398e-06 -3.99582023799707e-06 -2.4200876466021e-06 -4.55193315110898e-06 2.46135423750662e-05 5.81287877206912e-06 3.32712975333781e-05 -1.05550909404047e-05 -3.12968678135594e-06 -1.23365723869075e-06 5.81287877206912e-06 7.67794865044143e-05 1333 1333 0 0 0 1388 1410 0 0 0 0 0 0 0 0 0 0 0 1054 0 6 53 0 0 2768 +1287 1289 0.999605962344578 -0.00060273458606232 0.0280634416312325 -0.0118283660400488 -0.000706712345557579 0.99891212219198 0.04662695245859 -0.00784191722577859 -0.0280610157127547 -0.0466284124642233 0.998518087241405 -0.0139250825061046 5.7533105837641e-05 -3.76473296029062e-06 2.15479685632988e-06 3.21074395123851e-06 3.78522131311415e-06 1.8346472292018e-05 -3.76473296029062e-06 3.84416540236414e-05 2.96431991927552e-06 -1.87240564746281e-06 -9.19042546626661e-06 4.98641702460619e-06 2.15479685632988e-06 2.96431991927552e-06 1.22127990224436e-05 1.87003901929007e-06 -3.43682654326991e-06 1.98066561722693e-06 3.21074395123851e-06 -1.87240564746281e-06 1.87003901929007e-06 2.49149130271862e-05 -9.41659932700442e-06 1.45272041121682e-05 3.78522131311415e-06 -9.19042546626661e-06 -3.43682654326991e-06 -9.41659932700442e-06 2.0645888110537e-05 -8.51369426234251e-06 1.8346472292018e-05 4.98641702460619e-06 1.98066561722693e-06 1.45272041121682e-05 -8.51369426234251e-06 5.76139598209328e-05 1344 1344 0 0 0 1370 1419 0 0 0 0 0 0 0 0 0 0 0 820 0 0 21 0 0 3463 +1286 1290 0.998732538781742 -0.00038886069637253 0.0503305549933233 -0.0134956557340295 -0.00369653619269595 0.996702958925083 0.081052743878051 -0.0201265462303185 -0.0501961313126142 -0.0811360613866834 0.995438239140884 -0.00285371020519509 6.47012254585629e-05 2.13334187351973e-05 -3.14944379917373e-06 3.30609973397964e-06 -1.07614374077933e-06 3.78325452538312e-05 2.13334187351973e-05 4.06351278603458e-05 3.78380874130978e-07 2.14783940089368e-07 2.30521922342942e-07 1.62313306354355e-05 -3.14944379917373e-06 3.78380874130978e-07 1.22259454788413e-05 1.79695450322741e-06 -3.50960542379511e-06 -2.3681379823939e-06 3.30609973397964e-06 2.14783940089368e-07 1.79695450322741e-06 2.17549829233681e-05 2.1788753604239e-06 5.45041562307084e-06 -1.07614374077933e-06 2.30521922342942e-07 -3.50960542379511e-06 2.1788753604239e-06 2.44468673224217e-05 -1.8793608410467e-08 3.78325452538312e-05 1.62313306354355e-05 -2.3681379823939e-06 5.45041562307084e-06 -1.8793608410467e-08 6.3581302551639e-05 1344 1344 0 0 0 1389 1437 0 0 0 0 0 0 0 0 0 0 0 923 0 0 24 0 0 3383 +1287 1290 0.998864870887494 -0.00070461490538985 0.0476284917328456 -0.0116300328520378 -0.00295947349160032 0.997040871440515 0.0768162885968337 -0.0146435560288481 -0.0475416788046358 -0.0768700474500611 0.995907016031849 -0.00230636784137952 4.83271205264067e-05 6.02657217965255e-06 -3.83308999523531e-06 -8.44315434549642e-08 -3.76178657670036e-06 2.29325162618157e-05 6.02657217965255e-06 4.1339263594696e-05 1.09367924982624e-06 -1.98085300866566e-07 1.97141745024147e-06 1.22955285056123e-05 -3.83308999523531e-06 1.09367924982624e-06 1.12938911634732e-05 3.28147175857985e-06 -4.05980253062934e-06 -1.62371777219881e-06 -8.44315434549642e-08 -1.98085300866566e-07 3.28147175857985e-06 2.00989574369311e-05 -2.82808696585198e-06 6.99706248077785e-07 -3.76178657670036e-06 1.97141745024147e-06 -4.05980253062934e-06 -2.82808696585198e-06 1.91870511289239e-05 -4.23477875581197e-06 2.29325162618157e-05 1.22955285056123e-05 -1.62371777219881e-06 6.99706248077785e-07 -4.23477875581197e-06 4.29764779126568e-05 1344 1346 0 0 0 1384 1415 0 0 0 0 0 0 0 0 0 0 0 930 0 0 17 0 0 3403 +1287 1313 0.996506809843123 -0.00271095242074193 0.083467530652671 -0.0188762082902408 -0.00881329440887053 0.990477751264092 0.137390502191708 -0.0274492208707768 -0.0830451911789278 -0.137646194963027 0.986993931710958 0.00978847573902462 9.76063107526268e-05 -5.4140223539516e-05 4.59471198052201e-06 -5.45436019146411e-06 -2.94388585510862e-06 2.97125047102403e-05 -5.4140223539516e-05 6.73553951585729e-05 -2.50362196391882e-06 3.83708859887441e-06 -1.81451542791166e-06 -4.89996649012053e-06 4.59471198052201e-06 -2.50362196391882e-06 1.51397898282386e-05 -1.36742739029689e-06 -4.06457382620556e-06 -4.08386390711271e-06 -5.45436019146411e-06 3.83708859887441e-06 -1.36742739029689e-06 3.1441858111299e-05 -2.20783531578547e-07 4.36955026036611e-06 -2.94388585510862e-06 -1.81451542791166e-06 -4.06457382620556e-06 -2.20783531578547e-07 2.49226882967624e-05 -4.72176152952191e-06 2.97125047102403e-05 -4.89996649012053e-06 -4.08386390711271e-06 4.36955026036611e-06 -4.72176152952191e-06 6.90558125925757e-05 1346 1353 0 0 0 1394 1418 0 0 0 0 0 0 0 0 0 0 0 1081 0 5 48 0 0 2850 +1287 1316 0.996481037253964 -0.00206515736377432 0.0837930636647611 -0.0201134396722488 -0.00935547095224134 0.99070939502462 0.135673762287382 -0.0280251519175254 -0.0832947630798337 -0.135980254945393 0.987203805051652 0.00666768476791561 6.53195259626356e-05 -3.0184812521074e-05 5.97109819570582e-06 3.74887861848334e-06 1.77366091541844e-06 1.64056082567555e-05 -3.0184812521074e-05 4.95191414576922e-05 -6.00711372077962e-06 -3.69361466262159e-06 -4.72662930263291e-06 4.40461556097974e-06 5.97109819570582e-06 -6.00711372077962e-06 1.27815229181703e-05 2.19944736823159e-06 -6.16231890098283e-06 -1.25662152895e-06 3.74887861848334e-06 -3.69361466262159e-06 2.19944736823159e-06 2.6569186051668e-05 -8.25467619006827e-06 4.83017480310988e-06 1.77366091541844e-06 -4.72662930263291e-06 -6.16231890098283e-06 -8.25467619006827e-06 2.16637509390277e-05 -2.82368326029328e-06 1.64056082567555e-05 4.40461556097974e-06 -1.25662152895e-06 4.83017480310988e-06 -2.82368326029328e-06 5.68156520935581e-05 1236 1236 0 0 0 1286 1303 0 0 0 0 0 0 0 0 0 0 0 1067 0 3 34 0 0 2943 +1287 1315 0.996033418288769 -0.00297411809516356 0.0889302213735317 -0.0204382506238755 -0.00984715505436865 0.989617870597377 0.143385856107386 -0.0266029319636928 -0.0884333827766673 -0.143692814071786 0.985663183848726 0.00337964171670391 9.65001676897042e-05 -4.63020566293644e-05 2.19586239604582e-06 -1.01944875052008e-06 -4.7617533872271e-06 2.48809856942935e-05 -4.63020566293644e-05 7.19581665799287e-05 -5.7503742820263e-06 4.52546931601421e-06 -2.87931742657809e-06 -1.37871065535753e-06 2.19586239604582e-06 -5.7503742820263e-06 1.3528266997058e-05 1.47274646780393e-06 -4.50252997690067e-06 -1.86927298315443e-06 -1.01944875052008e-06 4.52546931601421e-06 1.47274646780393e-06 2.94748973178645e-05 -1.19633145037223e-05 3.80475923980082e-06 -4.7617533872271e-06 -2.87931742657809e-06 -4.50252997690067e-06 -1.19633145037223e-05 2.29885025651607e-05 -4.44640832355139e-06 2.48809856942935e-05 -1.37871065535753e-06 -1.86927298315443e-06 3.80475923980082e-06 -4.44640832355139e-06 6.55754810448987e-05 1235 1235 0 0 0 1280 1300 0 0 0 0 0 0 0 0 0 0 0 1068 0 3 32 0 0 2853 +1287 1318 0.996708884592544 -0.00094196882122903 0.0810586952092479 -0.0205446178595371 -0.0102483641166339 0.990445264226214 0.137525087183387 -0.0324692751064242 -0.0804137451386192 -0.13790319527337 0.987175940917411 0.0125666793904445 9.50671128898641e-05 -5.0196804546639e-05 4.17649759909505e-06 -9.22174692586096e-06 -8.78431527718753e-06 3.00835058448872e-05 -5.0196804546639e-05 7.02756673195601e-05 -1.63588327428482e-06 7.34213010534504e-06 6.94588607849203e-06 -1.42688123339325e-06 4.17649759909505e-06 -1.63588327428482e-06 1.43076876314059e-05 2.7780378290619e-06 -1.37323894658492e-06 -1.98428867828338e-06 -9.22174692586096e-06 7.34213010534504e-06 2.7780378290619e-06 3.02181298423224e-05 2.23848139857869e-06 -4.21215063217099e-06 -8.78431527718753e-06 6.94588607849203e-06 -1.37323894658492e-06 2.23848139857869e-06 3.42771362495731e-05 -8.23584333837603e-06 3.00835058448872e-05 -1.42688123339325e-06 -1.98428867828338e-06 -4.21215063217099e-06 -8.23584333837603e-06 6.72078452320991e-05 1342 1343 0 0 0 1395 1418 0 0 0 0 0 0 0 0 0 0 0 1082 0 11 52 0 0 2866 +1286 1316 0.995639448420034 -0.00266904804378253 0.0932467958290769 -0.0177677649057525 -0.0110492235076035 0.989179821423737 0.146291474625089 -0.0269388729541163 -0.0926283078207121 -0.14668386779276 0.984836960882169 0.000449651309279261 0.000108793396466835 -3.7617329660423e-05 1.19630676534572e-05 -6.87342417630484e-06 7.84686344086407e-06 2.31204287712657e-05 -3.7617329660423e-05 5.20451800771242e-05 -7.36084130389744e-06 1.6347964046682e-06 -5.60830282356139e-06 1.27912871279306e-05 1.19630676534572e-05 -7.36084130389744e-06 1.41396536142308e-05 1.32612399798924e-06 -4.79253181699458e-06 -4.19509782838841e-06 -6.87342417630484e-06 1.6347964046682e-06 1.32612399798924e-06 2.32335442593739e-05 -8.13765946756309e-06 2.51340776989625e-06 7.84686344086407e-06 -5.60830282356139e-06 -4.79253181699458e-06 -8.13765946756309e-06 2.03645015727159e-05 2.06559035541631e-06 2.31204287712657e-05 1.27912871279306e-05 -4.19509782838841e-06 2.51340776989625e-06 2.06559035541631e-06 6.63682354637354e-05 1252 1252 0 0 0 1294 1320 0 0 2 0 0 0 0 0 0 0 0 1059 0 3 31 0 0 2844 +1286 1317 0.995765845642482 -0.00166728368155455 0.0919108307928825 -0.0167439324717846 -0.0117050039783708 0.989397501892454 0.144760409404084 -0.0283717829450268 -0.0911777030516725 -0.145223288125896 0.985188724586373 0.00529342645886531 0.000116974915728441 -5.2173609197309e-05 2.42639253249476e-06 1.42863659412816e-07 -1.78376234430574e-06 2.9124586473825e-05 -5.2173609197309e-05 0.000113529484747778 1.48075475710027e-06 1.52201035441007e-06 -3.05928683485231e-07 5.42718089877225e-06 2.42639253249476e-06 1.48075475710027e-06 1.81036166513849e-05 8.47089796326612e-07 -4.12160091555995e-06 -3.43271281496954e-06 1.42863659412816e-07 1.52201035441007e-06 8.47089796326612e-07 2.61034485027067e-05 -1.20363262821642e-05 2.20739800789598e-06 -1.78376234430574e-06 -3.05928683485231e-07 -4.12160091555995e-06 -1.20363262821642e-05 2.48719937662857e-05 -1.28903546989879e-06 2.9124586473825e-05 5.42718089877225e-06 -3.43271281496954e-06 2.20739800789598e-06 -1.28903546989879e-06 6.81311535875448e-05 1328 1328 0 0 0 1386 1425 0 0 0 0 0 0 0 0 0 0 0 968 0 4 37 0 0 2861 +1288 1315 0.996558924210919 -0.00236013187378171 0.0828537286615006 -0.0175653817644808 -0.0084078792415565 0.991560157522659 0.129374501275559 -0.0255885260769654 -0.0824597971270522 -0.129625937956794 0.988128280167402 0.00318040730127002 8.96020844657432e-05 -4.68799099954617e-05 4.20234045831961e-06 -4.73738304784228e-06 1.39079289872315e-06 1.4759858391636e-05 -4.68799099954617e-05 6.06050367237935e-05 -6.12996165497647e-06 6.81291627192118e-06 -3.78520644865312e-06 6.79048477214179e-06 4.20234045831961e-06 -6.12996165497647e-06 1.33216634265003e-05 1.39858664053554e-06 -3.82059721792264e-06 -1.34626598951999e-06 -4.73738304784228e-06 6.81291627192118e-06 1.39858664053554e-06 2.76439342300203e-05 -9.81930686464205e-06 1.13907292712063e-06 1.39079289872315e-06 -3.78520644865312e-06 -3.82059721792264e-06 -9.81930686464205e-06 2.257593308945e-05 -3.52634324223139e-06 1.4759858391636e-05 6.79048477214179e-06 -1.34626598951999e-06 1.13907292712063e-06 -3.52634324223139e-06 6.31572077521376e-05 1242 1242 0 0 0 1284 1309 0 0 0 0 0 0 0 0 0 0 0 1063 0 2 31 0 0 2854 +1287 1291 0.998196183804787 -0.00148880984240683 0.0600180146523726 -0.0145469289104132 -0.00447343242152728 0.995069006199181 0.0990841122690382 -0.0196970495981279 -0.0598695835957566 -0.0991738692752607 0.993267424520227 0.00191872634638477 5.64742512154509e-05 1.15205050894831e-05 1.28673754030824e-06 1.50971063382622e-06 -4.53719694767639e-06 2.96864226181288e-05 1.15205050894831e-05 3.63599294004098e-05 5.79368526809826e-07 3.86616790735574e-06 2.62705899844192e-07 1.4144704271989e-05 1.28673754030824e-06 5.79368526809826e-07 1.22402746130953e-05 1.27301479871709e-06 -2.41525651224112e-06 1.17942669621767e-07 1.50971063382622e-06 3.86616790735574e-06 1.27301479871709e-06 2.25837321166136e-05 -4.7225873979734e-06 -2.27888389876633e-06 -4.53719694767639e-06 2.62705899844192e-07 -2.41525651224112e-06 -4.7225873979734e-06 2.1230868187276e-05 -3.13871549978462e-06 2.96864226181288e-05 1.4144704271989e-05 1.17942669621767e-07 -2.27888389876633e-06 -3.13871549978462e-06 4.52058172634121e-05 1281 1288 0 0 0 1321 1353 0 0 0 0 0 0 0 0 0 0 0 928 0 0 30 0 0 3113 +1287 1314 0.996564463662175 -0.00295099642302109 0.0827681181725915 -0.0199447608209588 -0.00856260259581827 0.990338446468172 0.138406803603701 -0.0245624842109305 -0.0823768875504947 -0.138640012504034 0.986910834538954 0.0122910881720927 8.61186924465915e-05 -2.98145678826783e-05 1.45627054358803e-06 -2.61852411525575e-06 -4.39624164461894e-06 1.47796946456825e-05 -2.98145678826783e-05 6.2544799809744e-05 -3.45523429183602e-06 7.47146318837153e-06 -5.37942559286616e-06 1.04335193033537e-05 1.45627054358803e-06 -3.45523429183602e-06 1.62331099657126e-05 -1.59724875992677e-06 -2.39936802604494e-06 -3.26274742532313e-06 -2.61852411525575e-06 7.47146318837153e-06 -1.59724875992677e-06 3.35607358925426e-05 -8.62242106216097e-06 2.27199527708148e-06 -4.39624164461894e-06 -5.37942559286616e-06 -2.39936802604494e-06 -8.62242106216097e-06 3.02819515094486e-05 -4.83245018565969e-06 1.47796946456825e-05 1.04335193033537e-05 -3.26274742532313e-06 2.27199527708148e-06 -4.83245018565969e-06 5.44735168130426e-05 1338 1338 0 0 0 1381 1399 0 0 0 0 0 0 0 0 0 0 0 1080 0 4 41 0 0 2664 +1288 1290 0.998987230261222 -0.000239856223818953 0.0449939578610804 -0.00968825712270859 -0.00297661416288543 0.997442885912535 0.0714060859492959 -0.0163332483750785 -0.0448960303717165 -0.0714676976784954 0.996431991982091 -0.00598942280059565 5.91906754157476e-05 1.68495282839745e-05 -1.90787001104567e-06 4.36770022399221e-08 -3.10567493433529e-06 1.55581008975347e-05 1.68495282839745e-05 3.8096459063415e-05 -1.22158478294022e-07 5.3930041633316e-07 -1.85785707843379e-06 8.93190531545042e-06 -1.90787001104567e-06 -1.22158478294022e-07 1.091571673486e-05 2.65912353181391e-06 -3.10880454328858e-06 -6.80487653573015e-07 4.36770022399221e-08 5.3930041633316e-07 2.65912353181391e-06 2.04883605718707e-05 -1.61621066151519e-06 3.67559657355604e-07 -3.10567493433529e-06 -1.85785707843379e-06 -3.10880454328858e-06 -1.61621066151519e-06 1.98024964351065e-05 -3.16966174520331e-06 1.55581008975347e-05 8.93190531545042e-06 -6.80487653573015e-07 3.67559657355604e-07 -3.16966174520331e-06 4.3111732379676e-05 1354 1354 0 0 0 1393 1449 0 0 0 0 0 0 0 0 0 0 0 922 0 0 17 0 0 3345 +1288 1317 0.996597224103787 -0.0011061187243191 0.0824181376275458 -0.0141342058658673 -0.00949153512553283 0.991718293493191 0.128080978727965 -0.0273839427079709 -0.0818772475696768 -0.128427422509059 0.988333199623534 0.00915753832941613 7.65994301237816e-05 -3.62239354671505e-05 6.16758001462661e-06 -6.91197248163099e-06 6.53336513753929e-07 1.67193743046558e-05 -3.62239354671505e-05 6.25693606757458e-05 -1.80597526859029e-06 -3.70589285310899e-07 1.68502454727655e-06 5.57564941180912e-06 6.16758001462661e-06 -1.80597526859029e-06 1.42282779804961e-05 1.1360723101527e-06 -2.40460470199773e-06 5.53204410667656e-07 -6.91197248163099e-06 -3.70589285310899e-07 1.1360723101527e-06 2.3375592896934e-05 -8.70211103038125e-06 -2.34769122688724e-06 6.53336513753929e-07 1.68502454727655e-06 -2.40460470199773e-06 -8.70211103038125e-06 2.45184517623288e-05 -1.16461675329348e-06 1.67193743046558e-05 5.57564941180912e-06 5.53204410667656e-07 -2.34769122688724e-06 -1.16461675329348e-06 5.55389335795655e-05 1317 1317 0 0 0 1392 1424 0 0 0 0 0 0 0 0 0 0 0 965 0 3 33 0 0 2923 +1288 1292 0.997711739332548 -0.00187531183589595 0.0675852676516079 -0.0161935269063853 -0.0063744981389572 0.992553476251835 0.121642766138697 -0.0249301491054379 -0.0673101104701052 -0.121795237944328 0.990270300999978 0.00859703328583251 5.64450882035474e-05 2.63248279456442e-05 5.00670991892285e-07 -5.00782363904731e-06 -8.69444056600221e-06 2.66422381219145e-05 2.63248279456442e-05 5.68519759061997e-05 6.62374965552775e-06 -5.18943656607673e-06 -4.72171860835627e-06 2.14298984777698e-05 5.00670991892285e-07 6.62374965552775e-06 1.41773322646437e-05 6.90489463070909e-07 -8.87529724945351e-07 4.4831205010512e-06 -5.00782363904731e-06 -5.18943656607673e-06 6.90489463070909e-07 2.02246477552671e-05 -1.19899366097581e-08 -5.26284884712763e-06 -8.69444056600221e-06 -4.72171860835627e-06 -8.87529724945351e-07 -1.19899366097581e-08 2.82313098573333e-05 -4.65983478333699e-06 2.66422381219145e-05 2.14298984777698e-05 4.4831205010512e-06 -5.26284884712763e-06 -4.65983478333699e-06 4.7421960734382e-05 1299 1299 0 0 0 1376 1398 0 0 0 0 0 0 0 0 0 0 0 1027 0 2 32 0 0 3033 +1289 1317 0.99821860656156 -3.2884973272462e-05 0.0596624876524256 -0.0144296523833 -0.0057960867977981 0.995216353129525 0.0975234117604599 -0.0171073930978924 -0.0593802904348715 -0.0976954931516616 0.993443290644073 0.0083922549178503 0.000106333906641403 -4.46426470990625e-05 5.08975348047097e-06 -7.70575086102552e-06 -3.82599194503796e-06 2.57408642819438e-05 -4.46426470990625e-05 8.00560611521331e-05 2.59223198177893e-07 7.57236784496496e-06 -1.17761935478818e-07 1.6214171281768e-05 5.08975348047097e-06 2.59223198177893e-07 1.34314147347166e-05 2.05544074168994e-06 -5.70351132175255e-06 -9.86877235362444e-08 -7.70575086102552e-06 7.57236784496496e-06 2.05544074168994e-06 2.58458047969462e-05 -3.23500327598957e-06 -2.67440708086654e-07 -3.82599194503796e-06 -1.17761935478818e-07 -5.70351132175255e-06 -3.23500327598957e-06 2.09968990983181e-05 -7.85603475433138e-06 2.57408642819438e-05 1.6214171281768e-05 -9.86877235362444e-08 -2.67440708086654e-07 -7.85603475433138e-06 6.6442982814669e-05 1360 1360 0 0 0 1399 1444 0 0 0 0 0 0 0 0 0 0 0 971 0 0 22 0 0 2978 +1288 1314 0.99671483286082 -0.00190556533190585 0.0809685789426585 -0.0156130755173453 -0.00857866467721795 0.991615319424797 0.128939771965105 -0.0229209392525498 -0.0805353864309568 -0.129210785551451 0.988341350156712 0.00647667524950298 7.81735876829867e-05 -4.35244250852613e-05 9.95701031399744e-07 -1.31396254942212e-06 2.79307730533697e-06 7.27765417117433e-06 -4.35244250852613e-05 6.36199598039212e-05 2.43823884791735e-06 -2.73185256459637e-06 -1.23642784878689e-06 9.17855787007631e-06 9.95701031399744e-07 2.43823884791735e-06 1.58437631559963e-05 2.54801304190748e-06 -2.30399445269724e-06 -1.11519099179514e-06 -1.31396254942212e-06 -2.73185256459637e-06 2.54801304190748e-06 2.68637186676555e-05 -5.54427858895133e-06 6.34851877698405e-06 2.79307730533697e-06 -1.23642784878689e-06 -2.30399445269724e-06 -5.54427858895133e-06 2.53318500464405e-05 8.27502361354227e-07 7.27765417117433e-06 9.17855787007631e-06 -1.11519099179514e-06 6.34851877698405e-06 8.27502361354227e-07 5.81191065005994e-05 1327 1327 0 0 0 1396 1436 0 0 0 0 0 0 0 0 0 0 0 1070 0 2 29 0 0 2667 +1289 1315 0.998454447505568 0.000688810902163718 0.0555719515213614 -0.019089910614675 -0.00642101238772397 0.99465681596125 0.1030368335196 -0.0179249172594784 -0.0552040474627375 -0.103234412873664 0.993123944501572 0.00859529962768651 8.42014184837389e-05 -2.37713188437507e-05 1.0532685804366e-06 7.0717802770892e-06 -1.70662559974646e-06 1.87980212471034e-05 -2.37713188437507e-05 6.17953702456984e-05 -4.79274297492688e-06 3.42028059141483e-06 -3.82221115921505e-06 1.06250825651241e-05 1.0532685804366e-06 -4.79274297492688e-06 1.55063440095381e-05 1.53736438203503e-06 -5.39959748319323e-06 -3.39353227697802e-06 7.0717802770892e-06 3.42028059141483e-06 1.53736438203503e-06 3.18441121466756e-05 -6.5512685352359e-06 1.86208618279185e-06 -1.70662559974646e-06 -3.82221115921505e-06 -5.39959748319323e-06 -6.5512685352359e-06 2.48162189185252e-05 -1.38802142759058e-06 1.87980212471034e-05 1.06250825651241e-05 -3.39353227697802e-06 1.86208618279185e-06 -1.38802142759058e-06 6.38963616737236e-05 1249 1249 0 0 0 1291 1317 0 0 5 0 0 0 0 0 0 0 0 1082 0 0 22 0 0 2889 +1288 1291 0.998386713977474 -0.000805502296571115 0.0567742945294073 -0.0135862819538957 -0.00431791792554409 0.995926853365225 0.0900614142173525 -0.0199320261334114 -0.0566155891786877 -0.0901612661406854 0.994316660400427 -0.000940227256541202 7.03988607438289e-05 2.17423790262437e-05 -4.85554186560353e-07 -2.95186780802806e-06 -4.03497994920329e-06 2.32771116966887e-05 2.17423790262437e-05 4.23137476605341e-05 5.32643573626278e-06 -2.61455600828359e-06 1.08916719984876e-06 1.59334100293029e-05 -4.85554186560353e-07 5.32643573626278e-06 1.53971083048629e-05 -2.15878840057838e-06 -5.81048687769869e-07 -1.6416480819396e-06 -2.95186780802806e-06 -2.61455600828359e-06 -2.15878840057838e-06 2.49183240773163e-05 -3.5592211026752e-06 6.30892143905154e-07 -4.03497994920329e-06 1.08916719984876e-06 -5.81048687769869e-07 -3.5592211026752e-06 2.56323909101475e-05 -1.00045690578966e-06 2.32771116966887e-05 1.59334100293029e-05 -1.6416480819396e-06 6.30892143905154e-07 -1.00045690578966e-06 4.0501677854716e-05 1254 1254 0 0 0 1309 1334 0 0 0 0 0 0 0 0 0 0 0 928 0 1 35 0 0 3092 +1288 1318 0.996804264196346 -0.000815753029447759 0.0798786168318885 -0.0163813778390022 -0.00959295115458701 0.991489101268531 0.129835809212505 -0.0285820101125919 -0.0793046919679184 -0.130187159937972 0.988312738569709 0.0105473416480164 8.29143521605644e-05 -4.73140686136389e-05 8.11748955646803e-06 -4.66785890571403e-06 4.48879726275297e-06 3.15179135365497e-05 -4.73140686136389e-05 6.90262904055113e-05 -7.27463815763864e-06 -8.98991614902151e-07 -2.35896582254292e-06 -8.88491942118595e-06 8.11748955646803e-06 -7.27463815763864e-06 1.79215776558795e-05 8.1710737909414e-07 1.89684317372891e-06 -2.15411385755542e-06 -4.66785890571403e-06 -8.98991614902151e-07 8.1710737909414e-07 2.60147326207422e-05 -3.69877200837362e-06 -1.33867214901086e-06 4.48879726275297e-06 -2.35896582254292e-06 1.89684317372891e-06 -3.69877200837362e-06 2.98726765061877e-05 -1.4338998413735e-06 3.15179135365497e-05 -8.88491942118595e-06 -2.15411385755542e-06 -1.33867214901086e-06 -1.4338998413735e-06 8.14163158489366e-05 1350 1353 0 0 0 1404 1429 0 0 0 0 0 0 0 0 0 0 0 1073 0 6 46 0 0 2865 +1289 1292 0.998105731636254 -0.00143548674904394 0.0615051855752889 -0.0132157871347465 -0.00456751929247872 0.995239742118257 0.0973498509289999 -0.0136669630126112 -0.061352149451916 -0.0974463703078723 0.993347934346999 0.00668447303278196 8.25717837133241e-05 1.60991353890923e-05 1.48512567787982e-06 3.69206298525549e-07 -9.89324044930788e-06 3.4492928345728e-05 1.60991353890923e-05 8.53081272893816e-05 1.34270000003804e-05 1.87289570246842e-06 -2.13473839507226e-07 1.73424139558867e-05 1.48512567787982e-06 1.34270000003804e-05 1.4672316183321e-05 1.77449968415242e-06 -5.10051345941744e-06 3.6060649493874e-06 3.69206298525549e-07 1.87289570246842e-06 1.77449968415242e-06 2.53817469159879e-05 -1.24014369766276e-06 -7.75864985169462e-06 -9.89324044930788e-06 -2.13473839507226e-07 -5.10051345941744e-06 -1.24014369766276e-06 2.2148205517803e-05 -1.06943357219963e-05 3.4492928345728e-05 1.73424139558867e-05 3.6060649493874e-06 -7.75864985169462e-06 -1.06943357219963e-05 5.06447794462617e-05 1343 1343 0 0 0 1384 1431 0 0 0 0 0 0 0 0 0 0 0 1032 0 0 16 0 0 3020 +1289 1318 0.998451205430829 0.00159236483426685 0.055611642198012 -0.0172728115231883 -0.00713739765889942 0.994996509795136 0.099654418116597 -0.0205405169631958 -0.0551747037000096 -0.0998969962998557 0.993466829945461 0.0146833405837257 0.000103442752036588 -4.33653842791079e-05 2.51587839335246e-06 -2.41984890712958e-06 -9.46586795209336e-07 4.3971223044642e-05 -4.33653842791079e-05 7.91016430834426e-05 4.00128225938982e-07 7.19282623471504e-07 -3.13374711491077e-06 -7.78367985980339e-06 2.51587839335246e-06 4.00128225938982e-07 1.41605327809878e-05 1.05884104313791e-06 -7.33904190188028e-06 -1.79563238327948e-06 -2.41984890712958e-06 7.19282623471504e-07 1.05884104313791e-06 2.53111812779215e-05 -1.82081843517804e-06 1.0224800216168e-06 -9.46586795209336e-07 -3.13374711491077e-06 -7.33904190188028e-06 -1.82081843517804e-06 2.39292008859104e-05 -6.56236517842145e-06 4.3971223044642e-05 -7.78367985980339e-06 -1.79563238327948e-06 1.0224800216168e-06 -6.56236517842145e-06 7.66736861194595e-05 1359 1359 0 0 0 1410 1425 0 0 1 0 0 0 0 0 0 0 0 1078 0 2 50 0 0 2946 +1289 1293 0.998177594621395 -0.00129878414679938 0.06033077784669 -0.0147693496398035 -0.00544095352073444 0.99375914125024 0.111414385096231 -0.0128360800984058 -0.060098965220974 -0.111539599879711 0.991941042622011 0.00135093949857355 8.61596196171519e-05 -1.40819934763404e-05 -8.89706169457992e-06 9.467703482649e-07 -1.90583934351805e-05 3.87809518074449e-05 -1.40819934763404e-05 4.39104267698293e-05 8.99958964218115e-06 5.34459520854457e-07 6.09524444033776e-06 -1.68142859381881e-07 -8.89706169457992e-06 8.99958964218115e-06 1.29235231836233e-05 1.25066176502812e-06 -1.8241015805852e-06 -2.44382840513675e-06 9.467703482649e-07 5.34459520854457e-07 1.25066176502812e-06 2.41027056360389e-05 5.97571047950686e-07 -4.79500502842151e-06 -1.90583934351805e-05 6.09524444033776e-06 -1.8241015805852e-06 5.97571047950686e-07 2.70510602103555e-05 -1.27849642764682e-05 3.87809518074449e-05 -1.68142859381881e-07 -2.44382840513675e-06 -4.79500502842151e-06 -1.27849642764682e-05 6.16250959883929e-05 1373 1375 0 0 0 1407 1459 0 0 2 0 0 0 0 0 0 0 0 1083 0 0 16 0 0 2860 +1290 1316 0.999227822699118 0.00133402808012932 0.0392680367864392 -0.0104558183291646 -0.00350302508117139 0.998468130724319 0.0552188440947885 -0.014187303198907 -0.039134219798795 -0.0553137622745489 0.997701809431944 0.00983534206785734 8.5246612607806e-05 -4.63006792410988e-05 7.12443175204054e-06 -1.69549613735162e-06 -1.24964433661978e-06 2.30512032111744e-05 -4.63006792410988e-05 6.8323665996038e-05 -4.82102065468408e-06 -1.0897752588043e-06 -1.61427637989317e-06 -7.74602862538918e-06 7.12443175204054e-06 -4.82102065468408e-06 1.35319688154859e-05 2.25055864092675e-06 -5.22964299288652e-06 -4.71869766917977e-07 -1.69549613735162e-06 -1.0897752588043e-06 2.25055864092675e-06 2.54725496863428e-05 -7.49233442800969e-06 3.18005147716051e-06 -1.24964433661978e-06 -1.61427637989317e-06 -5.22964299288652e-06 -7.49233442800969e-06 2.26670922546509e-05 -3.3005741677896e-06 2.30512032111744e-05 -7.74602862538918e-06 -4.71869766917977e-07 3.18005147716051e-06 -3.3005741677896e-06 8.35676690171873e-05 1273 1273 0 0 0 1306 1342 0 0 0 0 0 0 0 0 0 0 0 1081 0 0 10 0 0 3050 +1289 1291 0.999627937808342 0.00130907887082884 0.0272446740767937 -0.0126574563138428 -0.0028535979465854 0.998385519406722 0.0567292835996503 -0.00992630655317114 -0.0271264249727089 -0.0567859221240639 0.99801779348703 0.0137709354118908 6.72030894783384e-05 1.85326436498936e-05 -4.88587017343365e-06 5.29585031362961e-06 -1.08452626453296e-05 2.91926270600608e-05 1.85326436498936e-05 5.26810887786553e-05 2.14476701794727e-06 7.2696607149643e-06 -2.89268698964228e-06 4.7701111706315e-06 -4.88587017343365e-06 2.14476701794727e-06 1.42743669132084e-05 -6.03556219681352e-07 -3.70973954113949e-06 -1.38961367763592e-06 5.29585031362961e-06 7.2696607149643e-06 -6.03556219681352e-07 2.54747697723423e-05 -1.5020468054341e-06 -5.34643719570648e-06 -1.08452626453296e-05 -2.89268698964228e-06 -3.70973954113949e-06 -1.5020468054341e-06 2.78003842980237e-05 -7.21631867395495e-06 2.91926270600608e-05 4.7701111706315e-06 -1.38961367763592e-06 -5.34643719570648e-06 -7.21631867395495e-06 6.06911893257459e-05 1275 1275 0 0 0 1323 1365 0 0 2 0 0 0 0 0 0 0 0 937 0 0 10 0 0 3077 +1289 1316 0.998448116195799 0.000769773043179454 0.0556845285022929 -0.0169641136318823 -0.00626110232786388 0.995116561597022 0.0985080069484675 -0.0169881246205679 -0.0553367677290668 -0.0987037804989317 0.99357707594958 0.00497821846747496 0.000105420277317689 -5.52997186399817e-05 4.99081379365026e-06 -4.40133795799592e-06 -4.12486552007673e-06 3.73016097211511e-05 -5.52997186399817e-05 7.17948030704603e-05 -2.91549972096345e-06 2.71434815472804e-07 3.29141132933433e-06 -7.1581149096572e-06 4.99081379365026e-06 -2.91549972096345e-06 1.25680610144234e-05 3.04570816242737e-06 -5.18674368272501e-06 -9.51160619443194e-07 -4.40133795799592e-06 2.71434815472804e-07 3.04570816242737e-06 2.67220718700887e-05 -6.18550717017557e-06 -2.99950775114164e-06 -4.12486552007673e-06 3.29141132933433e-06 -5.18674368272501e-06 -6.18550717017557e-06 2.10754948005112e-05 -5.50892990140108e-06 3.73016097211511e-05 -7.1581149096572e-06 -9.51160619443194e-07 -2.99950775114164e-06 -5.50892990140108e-06 9.4692839424749e-05 1267 1269 0 0 0 1305 1333 0 0 5 0 0 0 0 0 0 0 0 1061 0 0 20 0 0 2961 +1290 1318 0.999136251756519 0.0018289481900387 0.0415139178403148 -0.008447681055567 -0.00447358040007092 0.99795896659638 0.0637015546771843 -0.0137173540070053 -0.0413126797041581 -0.0638322484204054 0.997105163238691 0.00599325778067691 9.15979475278639e-05 -6.10934455378241e-05 9.48195202700711e-06 -5.5118056506549e-06 3.78680929595225e-06 3.47106482077099e-05 -6.10934455378241e-05 8.01127286051897e-05 -6.35060337678256e-06 4.7207083490889e-06 -2.02794031261958e-06 -1.84814043081546e-05 9.48195202700711e-06 -6.35060337678256e-06 1.5739565587727e-05 1.93740717274204e-06 -3.61544068491721e-06 -1.63883459437042e-07 -5.5118056506549e-06 4.7207083490889e-06 1.93740717274204e-06 2.47774326842457e-05 -9.2417618420965e-06 -3.0184029215006e-06 3.78680929595225e-06 -2.02794031261958e-06 -3.61544068491721e-06 -9.2417618420965e-06 2.29170192321265e-05 3.10691682539166e-07 3.47106482077099e-05 -1.84814043081546e-05 -1.63883459437042e-07 -3.0184029215006e-06 3.10691682539166e-07 7.11900962524714e-05 1383 1383 0 0 0 1419 1454 0 0 0 0 0 0 0 0 0 0 0 1103 0 0 19 0 0 3048 +1291 1293 0.999635340220769 -0.000138524776273697 0.0270030996849314 -0.00473998948214417 -0.000925442275809606 0.999223674091878 0.0393851836471965 -0.00834771606752214 -0.0269875923027996 -0.0393958112648491 0.998859169210796 -0.00101273749939178 4.34030909170222e-05 6.95868840060547e-06 -3.46357184604522e-06 -1.36782193380602e-07 -3.12382541171235e-06 1.51934352588766e-05 6.95868840060547e-06 5.24513229949285e-05 8.70515123538276e-06 -8.17280444858335e-06 -9.75422472271571e-07 6.88168647899121e-06 -3.46357184604522e-06 8.70515123538276e-06 1.22677028734752e-05 1.15028635825282e-06 -3.19955774955694e-06 2.48641392267935e-07 -1.36782193380602e-07 -8.17280444858335e-06 1.15028635825282e-06 1.99659435397608e-05 4.34433504924194e-06 -1.93640405304516e-06 -3.12382541171235e-06 -9.75422472271571e-07 -3.19955774955694e-06 4.34433504924194e-06 2.25048567561619e-05 -9.09788118223801e-06 1.51934352588766e-05 6.88168647899121e-06 2.48641392267935e-07 -1.93640405304516e-06 -9.09788118223801e-06 3.54116620279273e-05 1391 1398 0 0 0 1407 1476 0 0 7 0 0 0 0 0 0 0 0 1103 0 0 3 0 0 3115 +1291 1317 0.999612091599993 0.00174063970455551 0.0277963396961948 -0.00286387220944468 -0.00291215670072346 0.999106553680192 0.0421617568021082 -0.00777675738477756 -0.0276981167308855 -0.0422263491993875 0.998724060871096 0.00190129309778483 6.93260386780859e-05 -3.64032632115154e-05 4.97943101426097e-06 -1.58440269004371e-06 5.02296627742511e-06 2.65257925485848e-05 -3.64032632115154e-05 5.94904123657239e-05 -5.10152924492583e-06 6.83139609905141e-07 -5.95667813267627e-06 -7.13799659497521e-06 4.97943101426097e-06 -5.10152924492583e-06 1.3895983694622e-05 1.13071586830408e-07 -4.10072914112251e-06 -2.83602541718629e-06 -1.58440269004371e-06 6.83139609905141e-07 1.13071586830408e-07 2.55779229576453e-05 -5.84703062471543e-06 -8.66559787730774e-07 5.02296627742511e-06 -5.95667813267627e-06 -4.10072914112251e-06 -5.84703062471543e-06 1.92176838661531e-05 -2.69753618504426e-06 2.65257925485848e-05 -7.13799659497521e-06 -2.83602541718629e-06 -8.66559787730774e-07 -2.69753618504426e-06 5.77774349694554e-05 1386 1394 0 0 0 1402 1471 0 0 6 0 0 0 0 0 0 0 0 996 0 0 2 0 0 3051 +1290 1317 0.999271921729104 0.00163895837700875 0.0381174534729536 -0.0102528753806635 -0.00385503839490438 0.998301135463172 0.0581376092724368 -0.0155185655359404 -0.0379574119612779 -0.0582422247890579 0.997580612346101 0.0103738899256523 6.0817940551817e-05 -1.68573751937249e-05 7.37922226881474e-06 -5.37176679326807e-06 9.04713124380235e-07 1.66120764332753e-05 -1.68573751937249e-05 7.13223713420506e-05 -5.20433534655695e-07 7.26253130531891e-06 5.11726907572776e-06 -3.06434421305957e-06 7.37922226881474e-06 -5.20433534655695e-07 1.40779601753721e-05 3.64498202746881e-06 -3.85040472570484e-06 -3.10170943580519e-06 -5.37176679326807e-06 7.26253130531891e-06 3.64498202746881e-06 2.55680085544527e-05 -7.59029871063542e-06 -6.46275266254791e-06 9.04713124380235e-07 5.11726907572776e-06 -3.85040472570484e-06 -7.59029871063542e-06 2.12698096186529e-05 -3.37398808178712e-06 1.66120764332753e-05 -3.06434421305957e-06 -3.10170943580519e-06 -6.46275266254791e-06 -3.37398808178712e-06 5.66984528911333e-05 1359 1359 0 0 0 1401 1444 0 0 0 0 0 0 0 0 0 0 0 997 0 0 14 0 0 3055 +1291 1295 0.999665227227975 0.000215775706326417 0.0258725126743808 -0.00498283144466794 -0.00118401920562217 0.999299143735092 0.0374141608062009 -0.00746790791067627 -0.0258463066948095 -0.037432269115779 0.998964861073242 0.00720332046093595 6.71005850712292e-05 1.44549983952577e-05 4.00428172407397e-06 1.24692509285008e-06 3.06205029392295e-06 3.89875411489928e-05 1.44549983952577e-05 3.96319359450344e-05 -3.39153990896325e-06 -2.46477040773915e-06 -3.94051949098096e-06 1.80868482756736e-05 4.00428172407397e-06 -3.39153990896325e-06 1.10765973851373e-05 1.963466035716e-06 -3.98022568735432e-06 2.33846093028945e-06 1.24692509285008e-06 -2.46477040773915e-06 1.963466035716e-06 1.73885837160506e-05 -1.04466520859914e-06 -2.52559118613915e-06 3.06205029392295e-06 -3.94051949098096e-06 -3.98022568735432e-06 -1.04466520859914e-06 1.61666902029721e-05 -2.20423702508931e-06 3.89875411489928e-05 1.80868482756736e-05 2.33846093028945e-06 -2.52559118613915e-06 -2.20423702508931e-06 5.03080841996202e-05 1391 1398 0 0 0 1404 1474 0 0 4 0 0 0 0 0 0 0 0 955 0 0 2 0 0 2736 +1291 1294 0.999693781795216 -0.000211328068491594 0.0247446555932141 -0.00668022744267041 -0.000800591658149172 0.999163847906096 0.0408774276402078 -0.0074011446113462 -0.024732603845455 -0.0408847205925513 0.998857716558816 0.00665131304691429 5.92043812500902e-05 4.69934441926751e-06 -8.56843379698669e-07 -3.67447724987322e-06 -1.90572807067004e-07 3.24587508993908e-05 4.69934441926751e-06 7.67153169414771e-05 4.62095016211689e-06 -1.01000197750727e-05 -1.02676738234061e-05 5.31376244877007e-06 -8.56843379698669e-07 4.62095016211689e-06 1.56810194131726e-05 -4.63837447852669e-08 -3.99684610895587e-06 2.61768829233883e-06 -3.67447724987322e-06 -1.01000197750727e-05 -4.63837447852669e-08 1.99599747635794e-05 -3.73136775760224e-07 -3.09682980400093e-06 -1.90572807067004e-07 -1.02676738234061e-05 -3.99684610895587e-06 -3.73136775760224e-07 2.29011624680476e-05 -3.41635866072507e-06 3.24587508993908e-05 5.31376244877007e-06 2.61768829233883e-06 -3.09682980400093e-06 -3.41635866072507e-06 5.00369268360359e-05 1389 1389 0 0 0 1411 1473 0 0 0 0 0 0 0 0 0 0 0 1083 0 0 2 0 0 2754 +1292 1294 0.999932406985423 -0.000156711617426543 0.0116257000566723 -0.00389097213569735 0.000134772705680577 0.999998208901291 0.00188786401218504 -0.00471196681874282 -0.0116259750841188 -0.00188616957871328 0.999930637128228 0.00257487166332292 5.86592301735007e-05 1.51491501809629e-05 5.40702053424157e-07 -3.07101831778972e-06 -3.6429943437774e-06 2.65094660700713e-05 1.51491501809629e-05 3.88375941322949e-05 6.96455104720539e-06 -5.88415408846517e-06 -1.23042068022082e-06 5.29349461288189e-06 5.40702053424157e-07 6.96455104720539e-06 1.41023170477684e-05 -9.0433382630236e-07 -3.42966019235417e-06 2.11011152422648e-06 -3.07101831778972e-06 -5.88415408846517e-06 -9.0433382630236e-07 2.09189699373291e-05 1.38350529332169e-06 3.74380915431896e-07 -3.6429943437774e-06 -1.23042068022082e-06 -3.42966019235417e-06 1.38350529332169e-06 2.07767454870994e-05 -3.9941744320302e-06 2.65094660700713e-05 5.29349461288189e-06 2.11011152422648e-06 3.74380915431896e-07 -3.9941744320302e-06 4.55515819216234e-05 1397 1397 0 0 0 1411 1474 0 0 0 0 0 0 0 0 0 0 0 1090 0 0 0 0 0 2720 +1290 1292 0.999245234332741 -0.000373576685720266 0.0388435593601349 -0.00974644242609139 -0.00162955359341941 0.998670389805397 0.051524723007713 -0.0117302179115032 -0.0388111610028689 -0.0515491315775083 0.997916018919034 0.00267433322425173 5.78866183650446e-05 -4.51710775161284e-06 -5.14624085687848e-06 -1.99659527543091e-06 -8.87667730515379e-06 2.58366475306168e-05 -4.51710775161284e-06 5.1660805421703e-05 4.11693341010737e-06 2.67938017888432e-06 2.92355447022494e-06 -2.30321437386935e-06 -5.14624085687848e-06 4.11693341010737e-06 1.19954324052709e-05 1.68525037698641e-06 -2.94597214684845e-06 1.0360007275932e-07 -1.99659527543091e-06 2.67938017888432e-06 1.68525037698641e-06 2.2313495198782e-05 -2.84511417552384e-06 -1.41914425775289e-06 -8.87667730515379e-06 2.92355447022494e-06 -2.94597214684845e-06 -2.84511417552384e-06 2.53813178268193e-05 -1.11930005576564e-05 2.58366475306168e-05 -2.30321437386935e-06 1.0360007275932e-07 -1.41914425775289e-06 -1.11930005576564e-05 5.07556795004335e-05 1342 1342 0 0 0 1385 1422 0 0 0 0 0 0 0 0 0 0 0 1042 0 0 10 0 0 3124 +1290 1293 0.999371944564386 0.00136681171493682 0.0354097196166988 -0.00989470034432382 -0.00368580691198934 0.997845226566032 0.065508157101179 -0.0114758414978769 -0.0352438823770146 -0.0655975277363494 0.997223562251652 0.0086497708174444 7.08634390107912e-05 1.03674408156786e-05 -3.46130530393359e-06 5.02103834568846e-06 -7.42406499568346e-06 3.11042763269414e-05 1.03674408156786e-05 4.83911470136875e-05 5.83099464663533e-06 2.65131720924615e-06 3.92681960027746e-06 3.28836646175181e-06 -3.46130530393359e-06 5.83099464663533e-06 1.32031286455545e-05 1.02720132073497e-06 -3.17549126780565e-06 6.2180857316606e-07 5.02103834568846e-06 2.65131720924615e-06 1.02720132073497e-06 2.24445008326251e-05 -3.66585167775659e-06 8.24264402926026e-07 -7.42406499568346e-06 3.92681960027746e-06 -3.17549126780565e-06 -3.66585167775659e-06 2.27428172780127e-05 -4.56503440492778e-06 3.11042763269414e-05 3.28836646175181e-06 6.2180857316606e-07 8.24264402926026e-07 -4.56503440492778e-06 5.2262205447906e-05 1369 1369 0 0 0 1407 1455 0 0 0 0 0 0 0 0 0 0 0 1094 0 0 11 0 0 3034 +1293 1295 0.999998816522698 -0.00011802569337394 -0.00153395669399801 -0.0034047303416021 0.000113689928176401 0.999995999532795 -0.00282630377117961 0.00182565897825089 0.00153428413391684 0.00282612603088688 0.99999482947856 0.0104796729883979 0.000102462595092227 1.23510430154644e-05 1.24081518573818e-05 7.49809116533099e-07 9.26314383889167e-07 5.12864766936811e-05 1.23510430154644e-05 4.37993298408156e-05 -9.87738171445269e-06 6.122332313003e-06 -7.12997322012451e-06 1.33615335037203e-05 1.24081518573818e-05 -9.87738171445269e-06 1.64221403669492e-05 6.76488149089665e-07 -1.47247344234953e-06 4.25449700956395e-06 7.49809116533099e-07 6.122332313003e-06 6.76488149089665e-07 2.23527980168699e-05 -7.87405926803918e-06 -2.20387612611383e-06 9.26314383889167e-07 -7.12997322012451e-06 -1.47247344234953e-06 -7.87405926803918e-06 2.53391552837694e-05 4.04000971117209e-06 5.12864766936811e-05 1.33615335037203e-05 4.25449700956395e-06 -2.20387612611383e-06 4.04000971117209e-06 4.976817072146e-05 1399 1400 0 0 0 1404 1482 0 0 0 0 0 0 0 0 0 0 0 967 0 0 0 0 0 2695 +1290 1294 0.99910668479244 0.00022740423580496 0.0422584984396438 -0.00957075679946177 -0.00308743419028016 0.997705931968309 0.0676264819827896 -0.0107152307196782 -0.0421461760208507 -0.0676965405509131 0.996815368182222 0.00355658035917143 5.82567141752656e-05 9.91657189404585e-06 -2.18833287368022e-06 2.01758014710223e-07 -5.09092129217376e-06 2.94709513725826e-05 9.91657189404585e-06 8.19167765238309e-05 5.25697448174104e-06 -1.39167546463102e-06 -2.50143270335926e-06 -2.01480717276782e-06 -2.18833287368022e-06 5.25697448174104e-06 1.4310449315232e-05 2.59337037034915e-06 -3.88171887213093e-06 -1.01809091068863e-06 2.01758014710223e-07 -1.39167546463102e-06 2.59337037034915e-06 1.75905483936126e-05 -4.14560778181177e-06 -3.02222402607763e-06 -5.09092129217376e-06 -2.50143270335926e-06 -3.88171887213093e-06 -4.14560778181177e-06 2.21953018441319e-05 -6.44103599399097e-06 2.94709513725826e-05 -2.01480717276782e-06 -1.01809091068863e-06 -3.02222402607763e-06 -6.44103599399097e-06 5.38375085617504e-05 1359 1359 0 0 0 1401 1435 0 0 0 0 0 0 0 0 0 0 0 1074 0 7 34 0 0 2763 +1294 1296 0.999994133576869 -0.000405243742546505 -0.0034012629061014 -0.00510684464258448 0.00042173216723542 0.999988157414522 0.00484841960721479 0.00190570270584374 0.00339925783464764 -0.00484982558631059 0.999982461965187 -0.0108248325438019 7.41027765504119e-05 -1.2998561840523e-05 1.30372948195799e-05 6.68498900370709e-06 9.60121096776083e-06 2.70963282063209e-05 -1.2998561840523e-05 5.77957402993424e-05 -2.05751604380711e-05 1.42525265844362e-05 -1.5264959243142e-05 -3.14076771596946e-06 1.30372948195799e-05 -2.05751604380711e-05 1.93320382811536e-05 5.39069002353137e-07 2.46416609624613e-06 2.33083876837904e-06 6.68498900370709e-06 1.42525265844362e-05 5.39069002353137e-07 3.33364155037621e-05 -1.46880342725446e-05 -3.97550355112003e-06 9.60121096776083e-06 -1.5264959243142e-05 2.46416609624613e-06 -1.46880342725446e-05 3.22250019175816e-05 1.59114175179499e-05 2.70963282063209e-05 -3.14076771596946e-06 2.33083876837904e-06 -3.97550355112003e-06 1.59114175179499e-05 5.46839794692578e-05 1402 1404 0 0 0 1408 1486 0 0 0 0 0 0 0 0 0 0 0 1071 0 0 4 0 0 2974 +1293 1297 0.999995405470422 0.000648541043548553 -0.00296115392383343 -0.0045747283945253 -0.000655429177438165 0.999997080557425 -0.00232578787065836 -0.00306770456787003 0.00295963691002189 0.00232771801143776 0.999992911113984 0.000506671995296396 5.51323606083822e-05 -1.01613208109512e-05 5.69174193364743e-06 -5.09929429309854e-07 8.62220904553438e-07 2.11854534462255e-05 -1.01613208109512e-05 4.60584115642157e-05 -7.69066883194818e-06 2.59106389269492e-06 -1.16266831763988e-06 -4.20645682105954e-06 5.69174193364743e-06 -7.69066883194818e-06 1.28761808935582e-05 2.06281136689576e-06 -2.55646288253217e-06 -9.46276365901473e-07 -5.09929429309854e-07 2.59106389269492e-06 2.06281136689576e-06 2.04475673630425e-05 -1.17420044290955e-06 -1.62764290920001e-06 8.62220904553438e-07 -1.16266831763988e-06 -2.55646288253217e-06 -1.17420044290955e-06 2.34191330789994e-05 7.68029453430453e-07 2.11854534462255e-05 -4.20645682105954e-06 -9.46276365901473e-07 -1.62764290920001e-06 7.68029453430453e-07 4.16291240424562e-05 1408 1410 0 0 0 1418 1470 0 0 0 0 0 0 0 0 0 0 0 1107 0 0 11 0 0 2861 +1291 1318 0.999767642417865 0.00237689287883621 0.0214245549420651 -0.0081537100048239 -0.00313291354832941 0.999371023990223 0.0353233812287411 -0.0135964253127307 -0.0213271195176874 -0.0353822948517309 0.999146259155337 0.00570704192099996 6.2599437948496e-05 -3.74946814488123e-05 4.47562645584112e-06 -3.49652143056591e-06 -2.12148400107352e-06 2.21483618709961e-05 -3.74946814488123e-05 5.12936978720348e-05 -5.06526715108286e-06 1.21838870909252e-06 5.87748083504761e-06 -1.06997525562208e-05 4.47562645584112e-06 -5.06526715108286e-06 1.29130493078637e-05 2.0168595139605e-06 -3.2426687410314e-06 -3.77415086546213e-06 -3.49652143056591e-06 1.21838870909252e-06 2.0168595139605e-06 2.41823058183058e-05 1.26278422409305e-06 -1.80453057534792e-06 -2.12148400107352e-06 5.87748083504761e-06 -3.2426687410314e-06 1.26278422409305e-06 3.02696868466933e-05 -2.40125162141965e-06 2.21483618709961e-05 -1.06997525562208e-05 -3.77415086546213e-06 -1.80453057534792e-06 -2.40125162141965e-06 6.74254580860518e-05 1380 1380 0 0 0 1418 1448 0 0 0 0 0 0 0 0 0 0 0 1105 0 1 25 0 0 3126 +1292 1296 0.999992989084589 0.000571755279010284 0.00370065907239554 -0.00661066964658146 -0.000624181545950288 0.999899248018195 0.0141811216074766 0.000685075954278186 -0.00369217809251865 -0.0141833320679334 0.999892594688241 -0.00698044904921146 5.58091467639599e-05 -6.28880260141993e-06 5.44068425674636e-06 -7.39184368482414e-08 8.71475157713957e-06 2.63314496409729e-05 -6.28880260141993e-06 3.19234143264986e-05 -8.95800706282341e-06 9.74348553922546e-07 -2.1997445877921e-06 -1.29663404940788e-06 5.44068425674636e-06 -8.95800706282341e-06 1.28038207128514e-05 2.24261356510359e-06 -2.36246300807828e-06 1.87354957205585e-06 -7.39184368482414e-08 9.74348553922546e-07 2.24261356510359e-06 1.90182974523147e-05 -5.9154292660701e-06 -2.33791625305408e-06 8.71475157713957e-06 -2.1997445877921e-06 -2.36246300807828e-06 -5.9154292660701e-06 2.1476028426862e-05 5.31972480618634e-06 2.63314496409729e-05 -1.29663404940788e-06 1.87354957205585e-06 -2.33791625305408e-06 5.31972480618634e-06 4.9105037256907e-05 1401 1402 0 0 0 1408 1485 0 0 1 0 0 0 0 0 0 0 0 1076 0 0 0 0 0 3086 +1292 1295 0.999970062470086 0.000734417289407656 0.00770290820517117 -0.00157923395626325 -0.000730301500776218 0.999999589083323 -0.000537115354350705 -0.00224739419017839 -0.00770329950672037 0.000531473829021139 0.999970187911759 0.00610734195912884 5.31475317580422e-05 1.19854418480741e-05 3.50545913975882e-06 -1.76751042573497e-06 4.36867872769243e-06 2.86272645599804e-05 1.19854418480741e-05 4.68330602004203e-05 -7.46213785326139e-06 5.63236596213912e-06 -4.32361032103741e-06 1.14060118407644e-05 3.50545913975882e-06 -7.46213785326139e-06 1.29745592050152e-05 9.00692116471991e-07 -2.62333468986983e-06 1.26724907128383e-07 -1.76751042573497e-06 5.63236596213912e-06 9.00692116471991e-07 1.81592779278745e-05 -3.80066855848487e-06 2.36220288387039e-07 4.36867872769243e-06 -4.32361032103741e-06 -2.62333468986983e-06 -3.80066855848487e-06 1.96485942137794e-05 3.15031037230549e-06 2.86272645599804e-05 1.14060118407644e-05 1.26724907128383e-07 2.36220288387039e-07 3.15031037230549e-06 3.81226189970785e-05 1399 1400 0 0 0 1404 1483 0 0 0 0 0 0 0 0 0 0 0 964 0 0 0 0 0 2687 +1293 1296 0.999997857014974 0.000239714594371189 -0.00205633226245419 -0.000729737680289463 -0.000227340412191048 0.999981879531393 0.00601572316513408 -0.000152066004965637 0.00205773705738837 -0.00601524278610527 0.999979791082013 -0.00483013580951801 5.66625109591116e-05 -5.0849201059706e-06 6.38293469615034e-06 -1.99916411504293e-06 8.79388813923697e-06 2.96849060258665e-05 -5.0849201059706e-06 3.42009990525518e-05 -8.76052042666269e-06 -1.84131448557368e-06 -4.14061537583009e-07 5.05073089123307e-06 6.38293469615034e-06 -8.76052042666269e-06 1.28716866125562e-05 1.75888168766929e-06 -4.4813315729264e-06 6.85200071482485e-07 -1.99916411504293e-06 -1.84131448557368e-06 1.75888168766929e-06 1.95859836177191e-05 -1.12742212324478e-06 -4.41336545116541e-06 8.79388813923697e-06 -4.14061537583009e-07 -4.4813315729264e-06 -1.12742212324478e-06 1.68497891177843e-05 5.95613230147907e-06 2.96849060258665e-05 5.05073089123307e-06 6.85200071482485e-07 -4.41336545116541e-06 5.95613230147907e-06 3.74228708012963e-05 1404 1405 0 0 0 1408 1489 0 0 0 0 0 0 0 0 0 0 0 1076 0 0 0 0 0 3122 +1292 1318 0.999992449274471 0.00210198645270136 -0.00326849307739097 -0.0100453150232422 -0.00208157119500961 0.999978383316034 0.00623698340641201 -0.00359239209154284 0.00328153247803507 -0.0062301327116212 0.999975208188179 0.00668441586140652 0.000122507317187865 -7.80867890031256e-05 1.01067314971387e-05 -1.69558560739897e-05 -5.36005583608302e-06 6.56995372730702e-05 -7.80867890031256e-05 9.67228758352659e-05 -8.91854972506077e-06 7.19867017172082e-06 7.44800468733823e-06 -4.23182601430687e-05 1.01067314971387e-05 -8.91854972506077e-06 1.53840287803837e-05 2.77867687694556e-06 -2.74351424098536e-06 2.52414262815601e-06 -1.69558560739897e-05 7.19867017172082e-06 2.77867687694556e-06 3.17899497495533e-05 -2.90809101152964e-06 -1.07170946418287e-05 -5.36005583608302e-06 7.44800468733823e-06 -2.74351424098536e-06 -2.90809101152964e-06 3.18756070252005e-05 -7.93416142930641e-06 6.56995372730702e-05 -4.23182601430687e-05 2.52414262815601e-06 -1.07170946418287e-05 -7.93416142930641e-06 0.000103437096777953 1398 1398 0 0 0 1416 1463 0 0 0 0 0 0 0 0 0 0 0 1112 0 3 17 0 0 3105 +1294 1297 0.999998806166507 -0.000519520709842888 -0.00145525385860981 -0.00307057374846005 0.000522814450098768 0.999997300755183 0.00226387883912502 0.00292091967689743 0.00145407379858187 -0.00226463696417648 0.999996378537847 -0.00137479741513811 5.90081806201208e-05 -1.78608753022547e-05 1.32401660021597e-05 6.11223344987023e-07 9.56808596820055e-06 1.40361887350202e-05 -1.78608753022547e-05 4.98079869414051e-05 -1.27191776569959e-05 2.65761661648369e-06 -5.35982864412421e-06 -1.3199211347598e-05 1.32401660021597e-05 -1.27191776569959e-05 1.75566315659688e-05 3.21080582048868e-06 -2.1203048930387e-06 -3.03636520515671e-06 6.11223344987023e-07 2.65761661648369e-06 3.21080582048868e-06 1.88309057437916e-05 -8.43700243202734e-06 5.48976721224587e-07 9.56808596820055e-06 -5.35982864412421e-06 -2.1203048930387e-06 -8.43700243202734e-06 2.46522990894107e-05 4.98222089858153e-06 1.40361887350202e-05 -1.3199211347598e-05 -3.03636520515671e-06 5.48976721224587e-07 4.98222089858153e-06 5.05787903992161e-05 1418 1423 0 0 0 1418 1491 0 0 0 0 0 0 0 0 0 0 0 1102 0 0 5 0 0 2858 +1295 1297 0.999995898997024 0.000169999204307532 -0.00285886155724998 -0.00460356657332554 -0.000175677109552084 0.999998012591343 -0.00198593829620567 -8.8203845275962e-05 0.00285851826759361 0.00198643238840179 0.999993941461487 0.00479841428903825 6.1686576107373e-05 -2.47933696711654e-05 9.58454960702355e-06 -6.6629234390243e-07 6.80423615015363e-06 2.28620473190918e-05 -2.47933696711654e-05 3.66702801691077e-05 -1.04553167218584e-05 -7.74095073955155e-07 -2.2236509922435e-06 -1.22470175447256e-05 9.58454960702355e-06 -1.04553167218584e-05 1.38717422786185e-05 4.2650833567391e-06 -1.56231403708879e-06 -2.20398543720008e-06 -6.6629234390243e-07 -7.74095073955155e-07 4.2650833567391e-06 1.96266875912587e-05 -4.46943336421259e-06 -1.19095929949773e-06 6.80423615015363e-06 -2.2236509922435e-06 -1.56231403708879e-06 -4.46943336421259e-06 2.68357296598375e-05 -1.37993750126441e-06 2.28620473190918e-05 -1.22470175447256e-05 -2.20398543720008e-06 -1.19095929949773e-06 -1.37993750126441e-06 6.13411103663372e-05 1413 1413 0 0 0 1418 1477 0 0 0 0 0 0 0 0 0 0 0 1106 0 0 12 0 0 2847 +1295 1298 0.999999356810572 -0.000420982792929785 0.00105316282270625 -0.00162245261996308 0.000424076535430546 0.999995590985172 -0.00293907626803453 -0.00054407280834311 -0.00105192087875979 0.00293952099929284 0.999995126327503 0.000822348759405995 3.6451991444175e-05 -1.2655367937302e-05 8.03899653436845e-06 -2.27893490247667e-06 5.80740013711024e-06 1.78701232430467e-05 -1.2655367937302e-05 3.12693314170218e-05 -9.9811362154413e-06 -8.48244563965669e-08 -2.30103364105537e-06 -4.94915418198714e-06 8.03899653436845e-06 -9.9811362154413e-06 1.36892606976636e-05 1.83180888783316e-06 -2.92189820276837e-06 1.78715427303964e-07 -2.27893490247667e-06 -8.48244563965669e-08 1.83180888783316e-06 1.98115240767983e-05 -6.91660767001495e-06 -7.02025919643311e-06 5.80740013711024e-06 -2.30103364105537e-06 -2.92189820276837e-06 -6.91660767001495e-06 1.70146906287285e-05 6.76008518159182e-06 1.78701232430467e-05 -4.94915418198714e-06 1.78715427303964e-07 -7.02025919643311e-06 6.76008518159182e-06 3.76229615181573e-05 1294 1296 0 0 0 1296 1360 0 0 0 0 0 0 0 0 0 0 0 1005 0 0 0 0 0 2829 +1295 1299 0.999986937857726 0.000323554521074357 0.005100924073186 -0.00308668559190829 -0.000294797764221099 0.999984066830176 -0.00563730255183039 -0.00221505793990063 -0.00510266677402379 0.00563572517557018 0.999971100279172 -0.0020068261278256 0.000101113105507453 -1.59482273629916e-05 8.07145710562906e-06 -9.23683264306875e-06 -1.39411898289907e-06 5.62267922861535e-05 -1.59482273629916e-05 3.52272300512843e-05 -6.84889887308762e-06 -7.33156871566357e-07 -1.36106164365761e-06 -8.57279992339163e-06 8.07145710562906e-06 -6.84889887308762e-06 1.70731450034796e-05 1.59204367763717e-06 2.66679218019924e-06 4.92662362077282e-06 -9.23683264306875e-06 -7.33156871566357e-07 1.59204367763717e-06 2.43031899079065e-05 -4.15703458175774e-06 -7.0212537511316e-06 -1.39411898289907e-06 -1.36106164365761e-06 2.66679218019924e-06 -4.15703458175774e-06 3.17966347307246e-05 -3.83655232914496e-06 5.62267922861535e-05 -8.57279992339163e-06 4.92662362077282e-06 -7.0212537511316e-06 -3.83655232914496e-06 6.67568160724241e-05 1403 1403 0 0 0 1410 1474 0 0 0 0 0 0 0 0 0 0 0 1006 0 0 8 0 0 3015 +1296 1300 0.999950716651566 0.00171163166608677 -0.00977929368916533 -0.0062104776686702 -0.00166334277974719 0.999986395617935 0.00494387194893062 -0.00358058494054346 0.00978762273569853 -0.00492736198081784 0.999939959970144 0.00708835545740169 4.71912374166026e-05 -1.23303626058456e-05 8.56107192146076e-06 1.64961127077124e-07 3.79893223474128e-06 1.07514830961859e-05 -1.23303626058456e-05 3.7908726899941e-05 -1.00294385782798e-05 -3.6996734258556e-06 -3.12566474956301e-06 2.36903377895675e-06 8.56107192146076e-06 -1.00294385782798e-05 1.80799461354088e-05 1.62259893497074e-06 2.59920763090516e-06 7.6952071442027e-07 1.64961127077124e-07 -3.6996734258556e-06 1.62259893497074e-06 2.61590909942017e-05 -5.50610421781922e-06 -7.35450875883623e-06 3.79893223474128e-06 -3.12566474956301e-06 2.59920763090516e-06 -5.50610421781922e-06 3.78451329662029e-05 3.14825299134731e-06 1.07514830961859e-05 2.36903377895675e-06 7.6952071442027e-07 -7.35450875883623e-06 3.14825299134731e-06 4.16637274445975e-05 1397 1397 0 0 0 1413 1464 0 0 0 0 0 0 0 0 0 0 0 999 0 4 17 0 0 3080 +1298 1300 0.999999363241694 0.00112848029150721 6.95974424168744e-06 -0.00208992397257596 -0.00112846504898391 0.999997562007092 -0.00189803754067292 -0.00451707928232376 -9.10162523107053e-06 0.00189802847825363 0.999998198700906 0.00153132199796856 3.41539151910969e-05 3.22277688595711e-06 1.14211356725294e-06 6.57649557216873e-06 -3.42788044742718e-06 3.31135731127722e-06 3.22277688595711e-06 4.52472754326173e-05 -6.26247331812497e-06 4.99161780526193e-06 -3.59332287361941e-06 1.8956194761023e-06 1.14211356725294e-06 -6.26247331812497e-06 1.58372147038772e-05 2.2650905197482e-07 -2.46875913576784e-06 -3.11827199019911e-06 6.57649557216873e-06 4.99161780526193e-06 2.2650905197482e-07 3.19424237359982e-05 5.99951636814022e-06 -2.25764612397892e-06 -3.42788044742718e-06 -3.59332287361941e-06 -2.46875913576784e-06 5.99951636814022e-06 3.51304863512227e-05 5.49943688856208e-06 3.31135731127722e-06 1.8956194761023e-06 -3.11827199019911e-06 -2.25764612397892e-06 5.49943688856208e-06 3.51386687017682e-05 1409 1416 0 0 0 1417 1481 0 0 0 0 0 0 0 0 0 0 0 997 0 0 2 0 0 3080 +1294 1298 0.999999923461743 0.000389422781691215 3.77677664242881e-05 -0.00488613968184368 -0.000389265872098728 0.999991644886206 -0.00406922963980208 -0.00593468094520533 -3.9352101595974e-05 0.0040692146266478 0.999991719937588 0.000579839807439469 4.17200764455704e-05 -4.97917254610581e-06 6.01130690712133e-06 -1.92701195825493e-06 1.83560548896337e-07 1.74482423086027e-05 -4.97917254610581e-06 4.07666943212051e-05 -9.71422214533537e-06 -2.76688915122262e-06 -2.87152377521244e-06 -1.26003842734348e-06 6.01130690712133e-06 -9.71422214533537e-06 1.4211357512674e-05 2.11775317394612e-06 -1.80848349185524e-07 -1.45478977556425e-06 -1.92701195825493e-06 -2.76688915122262e-06 2.11775317394612e-06 2.26098774746086e-05 -2.08663964542722e-06 -4.63087536683868e-06 1.83560548896337e-07 -2.87152377521244e-06 -1.80848349185524e-07 -2.08663964542722e-06 2.90829646584634e-05 2.53873568917506e-06 1.74482423086027e-05 -1.26003842734348e-06 -1.45478977556425e-06 -4.63087536683868e-06 2.53873568917506e-06 4.15594325653417e-05 1282 1282 0 0 0 1296 1350 0 0 0 0 0 0 0 0 0 0 0 1003 0 0 3 0 0 2851 +1297 1299 0.999997982376556 -0.000513016485793256 0.00194217839110873 -0.00564724920726461 0.000509247297907399 0.999997987176182 0.00194069852728104 0.00388409704898857 -0.00194317009218426 -0.00193970556258447 0.999996230809058 -0.00274857549886063 8.22451484575012e-05 5.14738175624208e-06 6.05842665547565e-07 9.34405048022023e-06 -1.15325556317589e-05 2.0020778240612e-05 5.14738175624208e-06 2.78056260040078e-05 -4.58532274496237e-06 1.00399692789822e-06 -3.42445607436614e-06 6.03980243220017e-06 6.05842665547565e-07 -4.58532274496237e-06 1.65461691403964e-05 3.58254321029168e-06 -2.27307256674401e-06 9.40060091298189e-07 9.34405048022023e-06 1.00399692789822e-06 3.58254321029168e-06 2.5402689352067e-05 -1.22434387667064e-05 -7.54995204193279e-07 -1.15325556317589e-05 -3.42445607436614e-06 -2.27307256674401e-06 -1.22434387667064e-05 2.92509217050009e-05 1.78212068897374e-06 2.0020778240612e-05 6.03980243220017e-06 9.40060091298189e-07 -7.54995204193279e-07 1.78212068897374e-06 3.87780288865359e-05 1408 1414 0 0 0 1410 1483 0 0 0 0 0 0 0 0 0 0 0 1003 0 0 6 0 0 2977 +1296 1299 0.99998930063804 0.000321839181471459 -0.00461465372325693 -0.00476564772790252 -0.000290723302675562 0.999977230686891 0.00674192759813205 0.000527399225566659 0.00461671846722113 -0.00674051387643724 0.999966625134697 0.00296947496454391 0.000105902571605884 -9.19706665061473e-06 9.98040579767562e-07 -4.00639102823275e-06 -5.09194305323748e-06 5.08276240540006e-05 -9.19706665061473e-06 4.13327679421301e-05 -3.94360592522601e-06 -4.21042172772073e-06 1.25937651580713e-06 -2.67649087902187e-06 9.98040579767562e-07 -3.94360592522601e-06 1.48528828932556e-05 3.29512199827391e-06 -4.91470823047997e-07 2.57568610874719e-06 -4.00639102823275e-06 -4.21042172772073e-06 3.29512199827391e-06 2.09853566690618e-05 -5.97760567220799e-06 -6.58412085305601e-06 -5.09194305323748e-06 1.25937651580713e-06 -4.91470823047997e-07 -5.97760567220799e-06 3.2292693549343e-05 -2.41082442659486e-06 5.08276240540006e-05 -2.67649087902187e-06 2.57568610874719e-06 -6.58412085305601e-06 -2.41082442659486e-06 5.72746437767278e-05 1402 1402 0 0 0 1410 1480 0 0 0 0 0 0 0 0 0 0 0 1004 0 0 7 0 0 3079 +1296 1298 0.999992566478362 0.000540123162494633 -0.00381775522893496 -0.00471388025984285 -0.000521282025806471 0.999987689864674 0.00493440818766486 0.00146419404483846 0.00382037342000681 -0.00493238138045505 0.99998053799104 0.00297610600841732 7.3592832441795e-05 -2.37456560129686e-05 1.74094693721647e-05 -4.30110554427939e-06 1.31614027827897e-05 3.07131803960533e-05 -2.37456560129686e-05 3.96531692023124e-05 -1.39693534933812e-05 -8.8192674464401e-07 -6.72234634581843e-06 -1.1087634539396e-05 1.74094693721647e-05 -1.39693534933812e-05 1.57149388189279e-05 4.15029539414725e-06 -2.00711456507162e-08 4.04481274057521e-06 -4.30110554427939e-06 -8.8192674464401e-07 4.15029539414725e-06 2.09941486744221e-05 -9.29912242007205e-06 -8.17430922495553e-06 1.31614027827897e-05 -6.72234634581843e-06 -2.00711456507162e-08 -9.29912242007205e-06 2.33251664701682e-05 1.1964771794657e-05 3.07131803960533e-05 -1.1087634539396e-05 4.04481274057521e-06 -8.17430922495553e-06 1.1964771794657e-05 5.27582842699627e-05 1292 1293 0 0 0 1296 1360 0 0 0 0 0 0 0 0 0 0 0 1005 0 0 0 0 0 2710 +1298 1267 0.998257436037101 -0.0073114539117474 -0.0585545390070562 -0.00369613076662639 -0.00221707978395661 0.986946484748956 -0.161033290964668 0.0338872098718825 0.0589675839242549 0.160882500239698 0.985210457294663 -0.0379903578294435 0.000125084854783704 0.000110539426789362 -1.67077899192718e-05 3.16748599284402e-05 -1.21833709079153e-05 -4.93714987793884e-05 0.000110539426789362 0.000452529119475191 -5.92074160143869e-05 8.30764339910105e-05 -3.40000572930931e-05 -0.000397124093333234 -1.67077899192718e-05 -5.92074160143869e-05 2.41137912149967e-05 -8.67342681432334e-06 2.03628078212925e-06 4.99191121842333e-05 3.16748599284402e-05 8.30764339910105e-05 -8.67342681432334e-06 4.62596808627205e-05 -1.17219565064399e-05 -7.5314087314985e-05 -1.21833709079153e-05 -3.40000572930931e-05 2.03628078212925e-06 -1.17219565064399e-05 3.99687869778086e-05 6.52621518886856e-05 -4.93714987793884e-05 -0.000397124093333234 4.99191121842333e-05 -7.5314087314985e-05 6.52621518886856e-05 0.000646835273876217 1548 1595 0 0 3 1555 1635 0 0 25 0 0 0 0 0 0 0 0 783 0 0 0 0 0 2693 +1297 1300 0.999977621475725 0.00113597107154276 -0.00659288385125471 -0.00563229274312365 -0.00108839709201709 0.999973378749391 0.00721506647910657 0.00158667134069161 0.00660090444724099 -0.00720772934095451 0.999952237208471 -0.000880646248799545 5.06418347210829e-05 -1.38427815275554e-05 7.39455607766068e-06 4.05587449920782e-06 -2.7492035996799e-06 1.32904965773649e-06 -1.38427815275554e-05 2.49030977990131e-05 -7.72198682358656e-06 -2.16488249195272e-06 -4.17034594633387e-06 2.35898276677442e-06 7.39455607766068e-06 -7.72198682358656e-06 1.68497743044728e-05 2.58092444201255e-06 -1.58280120773548e-06 1.03093241319312e-06 4.05587449920782e-06 -2.16488249195272e-06 2.58092444201255e-06 2.55686996601525e-05 -1.03978962859082e-05 -4.67172678499642e-06 -2.7492035996799e-06 -4.17034594633387e-06 -1.58280120773548e-06 -1.03978962859082e-05 2.76772396558499e-05 9.92082554590376e-06 1.32904965773649e-06 2.35898276677442e-06 1.03093241319312e-06 -4.67172678499642e-06 9.92082554590376e-06 3.54854283384532e-05 1407 1408 0 0 0 1417 1486 0 0 0 0 0 0 0 0 0 0 0 999 0 0 0 0 0 2967 +1297 1301 0.999994875391908 0.000407189725375283 -0.00317543484421051 -0.0035179698105446 -0.000394549509505334 0.999992000993308 0.00398023618442786 0.00417698761863104 0.00317703015516481 -0.00397896292101705 0.999987037082715 0.00329683940925315 4.43140626121652e-05 -8.96779241333803e-06 8.94536382888434e-06 3.83747088889257e-07 1.88026729394906e-06 -1.41143078645479e-07 -8.96779241333803e-06 3.67718154346621e-05 -6.10341193996437e-06 -1.2178117509523e-07 -5.66279721466659e-06 6.30581268355644e-06 8.94536382888434e-06 -6.10341193996437e-06 1.79818702571624e-05 1.59239270038617e-06 -4.73152420878662e-07 -3.22429763174917e-06 3.83747088889257e-07 -1.2178117509523e-07 1.59239270038617e-06 2.39554604359909e-05 -9.21629600530319e-06 -4.85849341548617e-06 1.88026729394906e-06 -5.66279721466659e-06 -4.73152420878662e-07 -9.21629600530319e-06 2.97658773335818e-05 1.08461644853579e-07 -1.41143078645479e-07 6.30581268355644e-06 -3.22429763174917e-06 -4.85849341548617e-06 1.08461644853579e-07 3.60878563199672e-05 1414 1416 0 0 0 1417 1490 0 0 0 0 0 0 0 0 0 0 0 1094 0 0 0 0 0 3080 +1298 1266 0.997301381957116 -0.0200207660104232 -0.0706337205220216 -0.000962996993020764 0.00696720452906109 0.983566008285441 -0.180414426824724 0.0407238546962114 0.0730849615685567 0.179435437619772 0.981051228080738 -0.0250407595786329 0.000181255551930689 1.45397247408019e-05 3.08026953268937e-06 8.67088811882292e-06 -2.04810858555114e-05 -2.79565496751855e-06 1.45397247408019e-05 7.52008216064259e-05 -1.45059199887828e-05 1.19861339150112e-05 -3.61859347773588e-06 3.20163264741252e-05 3.08026953268937e-06 -1.45059199887828e-05 1.87280789917816e-05 2.24248766158694e-07 -8.69280508510785e-06 -8.39689168189441e-06 8.67088811882292e-06 1.19861339150112e-05 2.24248766158694e-07 2.9923096832086e-05 -1.30597039937948e-05 3.76688485484971e-06 -2.04810858555114e-05 -3.61859347773588e-06 -8.69280508510785e-06 -1.30597039937948e-05 3.09122609904382e-05 1.89301575042094e-05 -2.79565496751855e-06 3.20163264741252e-05 -8.39689168189441e-06 3.76688485484971e-06 1.89301575042094e-05 9.31449200294182e-05 1471 1523 0 0 19 1476 1556 0 0 54 0 0 0 0 0 0 0 0 677 0 0 0 0 0 2820 +1298 1272 0.995115606325349 0.000869197758356574 -0.0987125855349246 0.00718298878912617 -0.0160833177609061 0.988027842333153 -0.153435034018624 0.022292356203059 0.097397417509576 0.154273222789153 0.983215904973426 -0.0137330301612932 6.10443699173913e-05 1.70058726717252e-05 -1.29227529873851e-06 3.70935548874612e-06 3.09653909855171e-06 1.40189170672826e-05 1.70058726717252e-05 4.66112604486239e-05 -4.76234350528886e-06 7.32740415776108e-06 -3.37225238971771e-06 2.60835488743486e-05 -1.29227529873851e-06 -4.76234350528886e-06 1.63789912017756e-05 -2.72520943737653e-06 -6.74596892247063e-06 -8.02263022156163e-07 3.70935548874612e-06 7.32740415776108e-06 -2.72520943737653e-06 3.52841448758646e-05 -1.30580978060958e-06 1.72431859417208e-06 3.09653909855171e-06 -3.37225238971771e-06 -6.74596892247063e-06 -1.30580978060958e-06 2.04066430965631e-05 -1.7467325299467e-06 1.40189170672826e-05 2.60835488743486e-05 -8.02263022156163e-07 1.72431859417208e-06 -1.7467325299467e-06 5.35408639300016e-05 1440 1475 0 0 3 1450 1510 0 0 21 0 0 0 0 0 0 0 0 805 0 19 36 0 0 2860 +1298 1301 0.99999895635677 0.000999990360983215 0.00104273901300405 -0.00502934805755797 -0.000998566484063829 0.999998569622662 -0.00136514380418699 -0.00200849026556375 -0.00104410265213934 0.00136410113523389 0.999998524537784 -0.00291294992684685 6.97794726246168e-05 -4.69098211977352e-06 3.89682636543431e-06 1.39970934989569e-05 -1.35584948049898e-05 5.66539354029656e-06 -4.69098211977352e-06 4.57722096164991e-05 -8.81442259287244e-06 1.2187155502908e-05 -1.04561483205518e-05 -2.46041648357199e-06 3.89682636543431e-06 -8.81442259287244e-06 1.58083823732747e-05 2.88065008914399e-06 -3.43099920932166e-06 -3.65262435452557e-06 1.39970934989569e-05 1.2187155502908e-05 2.88065008914399e-06 3.57939799578089e-05 -7.32866593787634e-06 -4.06083123294998e-06 -1.35584948049898e-05 -1.04561483205518e-05 -3.43099920932166e-06 -7.32866593787634e-06 4.04403491043907e-05 8.71795027459648e-07 5.66539354029656e-06 -2.46041648357199e-06 -3.65262435452557e-06 -4.06083123294998e-06 8.71795027459648e-07 4.27896398574066e-05 1407 1415 0 0 0 1417 1483 0 0 0 0 0 0 0 0 0 0 0 1094 0 0 4 0 0 3017 +1299 1303 0.999999325777212 -0.000576842257627754 -0.00100781850132381 -0.00126394121902286 0.000574886952959714 0.999997954212418 -0.00193934936759917 0.0058505085322026 0.00100893513820877 0.00193876867833827 0.999997611610097 -0.00625418687411341 5.20738207340311e-05 -2.82216138756649e-06 -1.10385393772543e-06 7.45398427460963e-06 -4.99953445279644e-06 3.79918535674383e-06 -2.82216138756649e-06 3.9088752212956e-05 -9.20257774951303e-06 7.51501066981993e-06 -4.15149698254034e-06 3.49309594289761e-06 -1.10385393772543e-06 -9.20257774951303e-06 1.85762782238879e-05 2.16668298781013e-06 1.65866470863309e-06 -2.14993828780495e-06 7.45398427460963e-06 7.51501066981993e-06 2.16668298781013e-06 2.41942868952007e-05 -7.5147636838196e-06 -1.28861137201725e-06 -4.99953445279644e-06 -4.15149698254034e-06 1.65866470863309e-06 -7.5147636838196e-06 3.7954433626394e-05 -9.08604158348288e-06 3.79918535674383e-06 3.49309594289761e-06 -2.14993828780495e-06 -1.28861137201725e-06 -9.08604158348288e-06 4.4663051125514e-05 1405 1409 0 0 0 1406 1487 0 0 0 0 0 0 0 0 0 0 0 1001 0 0 0 0 0 2888 +1298 1302 0.999993864489511 0.000239352327858798 -0.00349480955087523 -0.000382290341724285 -0.000230247001354669 0.999996579027485 0.00260555553506643 0.00278027678589452 0.0034954212410105 -0.00260473487923372 0.99999049864814 0.000718309225674923 4.29918107082362e-05 5.19442377701513e-06 1.82180259912382e-06 6.38556107465697e-06 -5.42696099029633e-06 7.62392606777994e-06 5.19442377701513e-06 4.19810401846206e-05 -5.61038685199374e-06 2.43054262015279e-06 -1.00537592767867e-05 1.12666452959243e-05 1.82180259912382e-06 -5.61038685199374e-06 1.81162721090921e-05 -1.92690492016313e-06 -4.27458963198972e-06 -5.06233719376947e-06 6.38556107465697e-06 2.43054262015279e-06 -1.92690492016313e-06 2.15011092490186e-05 -3.4071986521016e-06 -2.98404553800222e-07 -5.42696099029633e-06 -1.00537592767867e-05 -4.27458963198972e-06 -3.4071986521016e-06 2.59484931116603e-05 -8.62367999305442e-07 7.62392606777994e-06 1.12666452959243e-05 -5.06233719376947e-06 -2.98404553800222e-07 -8.62367999305442e-07 3.47458128673255e-05 1394 1395 0 0 0 1404 1481 0 0 0 0 0 0 0 0 0 0 0 1002 0 0 1 0 0 2878 +1298 1271 0.995379622655479 0.000540651335237649 -0.0960162199754245 0.00196019618172922 -0.0147102891898976 0.989037604573451 -0.146929316787218 0.0229872039998693 0.0948842146733849 0.147662874263448 0.984475830769894 -0.0174487951043422 6.7501968261374e-05 2.22379759830718e-05 -3.79043050176084e-06 4.93295943204288e-06 -2.21038042092767e-06 2.26964050906604e-05 2.22379759830718e-05 7.29622266233644e-05 -8.76092730864518e-06 1.0294711694704e-05 -4.17410250299253e-06 2.05831327842637e-05 -3.79043050176084e-06 -8.76092730864518e-06 1.72940817938778e-05 -2.4738516455811e-06 -5.26698968040867e-06 8.65402009438314e-07 4.93295943204288e-06 1.0294711694704e-05 -2.4738516455811e-06 3.39944177400662e-05 -2.30076173238494e-06 -2.37288500844735e-06 -2.21038042092767e-06 -4.17410250299253e-06 -5.26698968040867e-06 -2.30076173238494e-06 2.66145949914177e-05 2.15269467705439e-06 2.26964050906604e-05 2.05831327842637e-05 8.65402009438314e-07 -2.37288500844735e-06 2.15269467705439e-06 6.6359631032122e-05 1387 1415 0 0 0 1420 1479 0 0 13 0 0 0 0 0 0 0 0 804 0 6 26 0 0 2940 +1299 1271 0.995183239486632 0.000244473442320245 -0.098031933968627 0.000745234575857027 -0.0147266122661452 0.989022015718634 -0.147032579093927 0.0242413781135924 0.0969197953777033 0.147768036654025 0.984261733792063 -0.0150548321542123 6.93311892657301e-05 1.62747909043083e-05 -4.81922053881732e-06 1.02853010232528e-05 -2.07430924757095e-07 2.96296307494712e-05 1.62747909043083e-05 6.18306254775261e-05 -1.58237608973358e-06 2.44234978475895e-06 9.31957167253648e-07 3.06173910437197e-05 -4.81922053881732e-06 -1.58237608973358e-06 1.48034502184404e-05 -2.53357766484063e-06 -6.47146610738868e-06 -1.25691620632704e-06 1.02853010232528e-05 2.44234978475895e-06 -2.53357766484063e-06 3.57341170604556e-05 -1.29809410428438e-06 -8.41595780535173e-07 -2.07430924757095e-07 9.31957167253648e-07 -6.47146610738868e-06 -1.29809410428438e-06 2.27166771410978e-05 1.947513212243e-06 2.96296307494712e-05 3.06173910437197e-05 -1.25691620632704e-06 -8.41595780535173e-07 1.947513212243e-06 7.7646711183463e-05 1397 1423 0 0 0 1424 1484 0 0 20 0 0 0 0 0 0 0 0 803 0 0 7 0 0 3194 +1299 1272 0.994656249528166 0.00078539745481077 -0.103239180669942 0.00660600950643086 -0.0161351288978803 0.98886608700791 -0.147930793214644 0.0234249251872994 0.101973540146509 0.148806065456026 0.98359450587805 -0.0181130424737144 6.98058418424714e-05 8.50171084175562e-06 -3.36848859486549e-06 3.06203227856905e-06 3.00017458568064e-06 1.70476531973229e-05 8.50171084175562e-06 3.9983973990658e-05 -2.15798134243318e-07 -2.25838284671708e-06 -1.07964613820647e-06 2.13422605583343e-05 -3.36848859486549e-06 -2.15798134243318e-07 1.56309188874805e-05 -1.49420803594529e-06 -2.24270925331193e-06 8.48672388427835e-07 3.06203227856905e-06 -2.25838284671708e-06 -1.49420803594529e-06 3.30586171273127e-05 -7.45533135157563e-07 8.9987914591949e-07 3.00017458568064e-06 -1.07964613820647e-06 -2.24270925331193e-06 -7.45533135157563e-07 2.75600940227991e-05 -2.87676606553982e-08 1.70476531973229e-05 2.13422605583343e-05 8.48672388427835e-07 8.9987914591949e-07 -2.87676606553982e-08 5.89369940816645e-05 1446 1482 0 0 3 1469 1534 0 0 29 0 0 0 0 0 0 0 0 801 0 0 11 0 0 3080 +1298 1269 0.996253427160595 -0.00994254428301343 -0.0859084086917522 -0.00893696244951013 -0.00273625976299482 0.98924810003938 -0.146221439778801 0.0340487568502618 0.0864385432158492 0.145908678225993 0.985514604592477 -0.0063922597605089 0.000104308826007494 2.51814391603124e-05 -3.2791421403209e-06 3.0215453133001e-06 -1.93128331176439e-05 -2.67610897244299e-05 2.51814391603124e-05 5.7831468711254e-05 -6.51015361705008e-06 1.75929888456461e-07 -9.80279898888718e-06 -3.68539763716545e-06 -3.2791421403209e-06 -6.51015361705008e-06 1.76206604570173e-05 -1.02668427831101e-06 -4.92748670101878e-06 -4.56164542640752e-06 3.0215453133001e-06 1.75929888456461e-07 -1.02668427831101e-06 3.19134552762475e-05 -1.17719723960754e-05 8.6822698424098e-07 -1.93128331176439e-05 -9.80279898888718e-06 -4.92748670101878e-06 -1.17719723960754e-05 3.40472039438043e-05 2.18212807639908e-05 -2.67610897244299e-05 -3.68539763716545e-06 -4.56164542640752e-06 8.6822698424098e-07 2.18212807639908e-05 9.78802339916058e-05 1515 1558 0 0 6 1527 1603 0 0 33 0 0 0 0 0 0 0 0 765 0 0 1 0 0 2870 +1299 1269 0.996900971290895 -0.00941208939350614 -0.0781016389874004 -0.0083593278413849 -0.00274957504109962 0.988041197194133 -0.154165600846224 0.0366014241683366 0.0786186573045033 0.153902583540474 0.984953349912169 -0.022292138294028 0.000129874418911759 2.420722040478e-05 -6.82119342884235e-06 1.31142202785943e-05 -1.18013543802514e-05 -3.12654104712653e-06 2.420722040478e-05 0.000129914360165324 -2.24578084051059e-05 2.20037900682622e-05 -3.27123969466197e-06 1.93997869055244e-06 -6.82119342884235e-06 -2.24578084051059e-05 2.38477309588998e-05 -5.69453498646005e-06 -2.99431306287955e-06 -6.1839213835829e-07 1.31142202785943e-05 2.20037900682622e-05 -5.69453498646005e-06 4.42635063048266e-05 -1.90088299469953e-05 -7.42173989293668e-06 -1.18013543802514e-05 -3.27123969466197e-06 -2.99431306287955e-06 -1.90088299469953e-05 3.5490506776384e-05 2.18147746243099e-05 -3.12654104712653e-06 1.93997869055244e-06 -6.1839213835829e-07 -7.42173989293668e-06 2.18147746243099e-05 0.000123436111568059 1517 1561 0 0 10 1527 1607 0 0 44 0 0 0 0 0 0 0 0 765 0 0 0 0 0 3000 +1298 1268 0.997776427943416 -0.00361714202024136 -0.0665516049699919 -0.00566489034568487 -0.00733886215801915 0.986492024273852 -0.163644820102266 0.0337391692031163 0.0662445540607078 0.163769357108351 0.984271942467942 -0.0113798222188244 7.41528403652828e-05 2.70140836352015e-05 -5.33107221587558e-06 6.75170196775484e-06 -3.12215277785838e-06 1.45853795352267e-05 2.70140836352015e-05 7.36341156789236e-05 -8.9491028726302e-06 6.63312220463783e-06 -1.91044847935412e-06 3.00740014233252e-05 -5.33107221587558e-06 -8.9491028726302e-06 1.74018259049634e-05 -1.67441412724976e-06 -4.28030763798321e-06 -2.45272864286903e-06 6.75170196775484e-06 6.63312220463783e-06 -1.67441412724976e-06 3.07635000721458e-05 -1.02335157192363e-05 4.25993544328652e-06 -3.12215277785838e-06 -1.91044847935412e-06 -4.28030763798321e-06 -1.02335157192363e-05 2.58211127045544e-05 3.93782385217344e-06 1.45853795352267e-05 3.00740014233252e-05 -2.45272864286903e-06 4.25993544328652e-06 3.93782385217344e-06 6.57436580460296e-05 1502 1536 0 0 2 1513 1583 0 0 20 0 0 0 0 0 0 0 0 777 0 0 6 0 0 2960 +1299 1302 0.999993522268572 0.000811006495675776 -0.00350680614791889 -0.00240980704306429 -0.00079665876734931 0.999991315070861 0.00409085781447256 0.00284777657195274 0.00351009340381642 -0.00408803758713119 0.999985483491127 7.589287845172e-05 5.58786881069659e-05 3.41817225956672e-06 -3.39523564119519e-07 1.02876553005986e-05 -1.11241849469711e-05 7.10586679180191e-06 3.41817225956672e-06 5.20264145855598e-05 -1.54294518292797e-05 6.83368402773757e-06 -1.64741225498731e-05 3.8780873315989e-06 -3.39523564119519e-07 -1.54294518292797e-05 2.65126581725959e-05 -2.42795630427354e-06 6.7075149380584e-06 4.64222581343912e-07 1.02876553005986e-05 6.83368402773757e-06 -2.42795630427354e-06 2.52436773010757e-05 -1.30199642199491e-05 -5.21243660938238e-06 -1.11241849469711e-05 -1.64741225498731e-05 6.7075149380584e-06 -1.30199642199491e-05 4.54647722160352e-05 5.1484857824586e-06 7.10586679180191e-06 3.8780873315989e-06 4.64222581343912e-07 -5.21243660938238e-06 5.1484857824586e-06 3.84670082676785e-05 1397 1397 0 0 0 1404 1473 0 0 0 0 0 0 0 0 0 0 0 999 0 0 12 0 0 2782 +1299 1301 0.999997853728552 -0.000135996698231425 0.00206737591852654 -0.00295051772103437 0.000139433498529061 0.999998608584146 -0.00166234414973331 -9.969738208574e-05 -0.00206714696863122 0.00166262884334862 0.999996481278179 -0.00724868862323056 7.82028228564869e-05 1.29620289424387e-05 -2.69583103899067e-06 2.08487322247709e-05 -1.19541777383256e-05 1.44659203771903e-05 1.29620289424387e-05 5.76951834401758e-05 -1.73648698067947e-05 1.5024018865885e-05 -2.18153707024146e-05 9.51683103885825e-06 -2.69583103899067e-06 -1.73648698067947e-05 2.17656356919416e-05 -3.50788054715741e-06 5.33039717324989e-06 -3.35820862041611e-06 2.08487322247709e-05 1.5024018865885e-05 -3.50788054715741e-06 3.05463133461393e-05 -1.31231728600584e-05 4.56870323908179e-06 -1.19541777383256e-05 -2.18153707024146e-05 5.33039717324989e-06 -1.31231728600584e-05 4.18484181164528e-05 3.82545059926476e-06 1.44659203771903e-05 9.51683103885825e-06 -3.35820862041611e-06 4.56870323908179e-06 3.82545059926476e-06 4.55291681637044e-05 1408 1408 0 0 0 1417 1487 0 0 0 0 0 0 0 0 0 0 0 1090 0 0 5 0 0 3102 +1299 1268 0.998595625512557 -0.00116052065707643 -0.0529663090935175 -0.00532547503649583 -0.00719801927790937 0.987517579570718 -0.157344267633957 0.0338003255815869 0.0524877626276867 0.157504549872681 0.986122381626005 -0.0322492016602534 9.43443620418504e-05 3.06628249849952e-06 -1.78407975735907e-06 1.49591053093331e-06 -1.20514977394724e-05 8.69887183686794e-06 3.06628249849952e-06 7.19981354334602e-05 -4.61339529518268e-06 5.14119092249203e-06 3.57882056572579e-07 2.97364669054623e-05 -1.78407975735907e-06 -4.61339529518268e-06 1.4818121200234e-05 -1.06322974357482e-06 -4.34790781571527e-06 -5.42667752110423e-06 1.49591053093331e-06 5.14119092249203e-06 -1.06322974357482e-06 3.66753504192896e-05 -9.72932123346043e-06 -5.29606432858025e-07 -1.20514977394724e-05 3.57882056572579e-07 -4.34790781571527e-06 -9.72932123346043e-06 3.22074295146112e-05 5.37524071581359e-06 8.69887183686794e-06 2.97364669054623e-05 -5.42667752110423e-06 -5.29606432858025e-07 5.37524071581359e-06 8.59208228860726e-05 1495 1529 0 0 1 1512 1581 0 0 25 0 0 0 0 0 0 0 0 774 0 1 12 0 0 3101 +1299 1270 0.9949252154368 -0.00781922799328025 -0.100312887315766 -0.000463103333197445 -0.0082955604728933 0.987206922314238 -0.159228377531424 0.0313121364659696 0.10027461974237 0.159252479442043 0.982132194985525 -0.0178331637919013 0.000178505668081703 1.67347363662117e-05 -1.13353528666672e-06 2.38555461571469e-05 -2.26788991662839e-05 3.2575087410981e-05 1.67347363662117e-05 8.66940700178753e-05 -1.02611321779732e-05 7.56951402097064e-06 -1.2017939910134e-05 1.83714785293706e-05 -1.13353528666672e-06 -1.02611321779732e-05 1.59985220692302e-05 -1.03257724492598e-06 -6.1351883125735e-06 1.05237730245607e-07 2.38555461571469e-05 7.56951402097064e-06 -1.03257724492598e-06 3.47963308365778e-05 -1.36251049031868e-05 -4.52799891426449e-07 -2.26788991662839e-05 -1.2017939910134e-05 -6.1351883125735e-06 -1.36251049031868e-05 2.83060607260953e-05 -2.12587343831156e-07 3.2575087410981e-05 1.83714785293706e-05 1.05237730245607e-07 -4.52799891426449e-07 -2.12587343831156e-07 7.30439062249367e-05 1427 1468 0 0 6 1446 1518 0 0 39 0 0 0 0 0 0 0 0 791 0 0 9 0 0 3043 +1299 1267 0.997877613344827 -0.00922395575825506 -0.0644607432892382 -0.00984029396239079 -0.00114117141369622 0.987287447925545 -0.158940847161667 0.0370640782502821 0.0651073460758145 0.158677073986237 0.985181516106616 -0.0280640261743667 9.73910269590734e-05 -1.12295340547098e-06 -5.62309893569795e-07 6.19938132414036e-06 -1.85564432492455e-05 -8.27148288127855e-06 -1.12295340547098e-06 5.40723783588533e-05 -5.18194882939322e-06 3.43436567781771e-06 1.26614126759758e-06 2.14699006359626e-05 -5.62309893569795e-07 -5.18194882939322e-06 1.75292388765503e-05 -1.22945513309858e-06 -5.2420977624675e-06 -2.85493558215485e-06 6.19938132414036e-06 3.43436567781771e-06 -1.22945513309858e-06 3.87362307447212e-05 -1.44763963499815e-05 7.55809780370656e-06 -1.85564432492455e-05 1.26614126759758e-06 -5.2420977624675e-06 -1.44763963499815e-05 3.54268744851919e-05 1.58189404646276e-05 -8.27148288127855e-06 2.14699006359626e-05 -2.85493558215485e-06 7.55809780370656e-06 1.58189404646276e-05 8.57856840872159e-05 1546 1590 0 0 9 1555 1634 0 0 43 0 0 0 0 0 0 0 0 784 0 0 0 0 0 2879 +1300 1304 0.999998412569792 -0.000373308372675555 0.00174226827884488 -0.000178861286075128 0.000372727026674999 0.999999874764388 0.000333984687811982 0.0066535073341558 -0.00174239273993115 -0.000333334767159355 0.999998426476498 -0.00733296480968824 2.8769206390191e-05 -1.4184425279437e-05 4.45367958306087e-06 4.24086336453676e-06 -2.59323514666533e-07 -4.81724006014941e-06 -1.4184425279437e-05 2.1978499098195e-05 -8.64012490216149e-06 -2.30084608389426e-06 -2.04276691966538e-06 5.7864724423842e-06 4.45367958306087e-06 -8.64012490216149e-06 1.82223285966195e-05 1.34148960566152e-06 1.77528541380375e-06 -3.55010508106197e-06 4.24086336453676e-06 -2.30084608389426e-06 1.34148960566152e-06 2.41889413737912e-05 -7.58167863536094e-06 5.82112811156216e-08 -2.59323514666533e-07 -2.04276691966538e-06 1.77528541380375e-06 -7.58167863536094e-06 4.00271004010551e-05 -7.27811034160599e-06 -4.81724006014941e-06 5.7864724423842e-06 -3.55010508106197e-06 5.82112811156216e-08 -7.27811034160599e-06 3.90931026709017e-05 1400 1407 0 0 0 1409 1484 0 0 0 0 0 0 0 0 0 0 0 1100 0 0 5 0 0 2825 +1301 1304 0.999997014340252 -0.000288599944727946 0.00242652439802015 0.000339826200608222 0.00029460611030317 0.99999689324088 -0.00247522035922217 0.00272555313868601 -0.00242580251093449 0.00247592783797084 0.999993992613715 -0.00489211928893653 2.7529078866711e-05 -1.30163911633598e-05 2.05030707662323e-06 2.75245607200063e-06 -1.58256193480156e-06 -1.58620742272883e-06 -1.30163911633598e-05 2.37484858304122e-05 -4.26590087684719e-06 -2.50017958476465e-06 -1.12490742328995e-06 8.64413015991135e-06 2.05030707662323e-06 -4.26590087684719e-06 1.85968922719369e-05 -5.56144585068366e-07 1.38012178787159e-06 -2.04793139250521e-06 2.75245607200063e-06 -2.50017958476465e-06 -5.56144585068366e-07 2.27630062697804e-05 -1.15437728197675e-05 -6.77834635190059e-07 -1.58256193480156e-06 -1.12490742328995e-06 1.38012178787159e-06 -1.15437728197675e-05 3.36278937429251e-05 -7.31235034502265e-07 -1.58620742272883e-06 8.64413015991135e-06 -2.04793139250521e-06 -6.77834635190059e-07 -7.31235034502265e-07 2.71544448546049e-05 1402 1407 0 0 0 1409 1489 0 0 0 0 0 0 0 0 0 0 0 1100 0 0 0 0 0 2933 +1300 1303 0.999999110834034 -0.000805413295836288 0.00106284550357637 -0.00153374844143339 0.000805949190391872 0.999999548277615 -0.000503875449824994 0.00683917659724244 -0.00106243919547853 0.000504731601269212 0.999999308234244 -0.0084537146272158 4.90170122133593e-05 9.01049308217953e-06 -1.83294287635334e-06 5.83441527838408e-06 -6.76854884149155e-06 -3.77849756265951e-07 9.01049308217953e-06 3.68933124903048e-05 -8.12518426423979e-06 6.34716464428152e-06 -7.73320392770741e-06 5.30793003039196e-06 -1.83294287635334e-06 -8.12518426423979e-06 2.3624016955011e-05 -5.09303376218741e-07 2.6231231030645e-06 5.54284478835089e-07 5.83441527838408e-06 6.34716464428152e-06 -5.09303376218741e-07 2.7543113364931e-05 -1.44033027261916e-05 1.00977565687692e-06 -6.76854884149155e-06 -7.73320392770741e-06 2.6231231030645e-06 -1.44033027261916e-05 4.2630005407314e-05 -4.41493021393721e-06 -3.77849756265951e-07 5.30793003039196e-06 5.54284478835089e-07 1.00977565687692e-06 -4.41493021393721e-06 4.14551585073267e-05 1399 1406 0 0 0 1406 1480 0 0 0 0 0 0 0 0 0 0 0 1001 0 0 7 0 0 2898 +1300 1269 0.997491598393119 -0.00856301817021838 -0.070265111221411 -0.00547012080786572 -0.00257018783557246 0.987619850006804 -0.156845229468507 0.0374440096094698 0.0707382871550522 0.156632393177003 0.985120494222922 -0.0229834079429481 0.000107320429573231 1.85207053622449e-05 -2.65997028263977e-06 3.27537390821447e-06 -1.35021671669659e-05 -8.28855759317894e-06 1.85207053622449e-05 6.21417228670772e-05 -4.83295151407475e-06 2.30553755363871e-06 -2.36249952011632e-06 2.87756027137292e-05 -2.65997028263977e-06 -4.83295151407475e-06 1.74196141622769e-05 -3.33016800824185e-06 -3.30252135112909e-06 -3.02691349185242e-06 3.27537390821447e-06 2.30553755363871e-06 -3.33016800824185e-06 3.91694278144091e-05 -1.61945292381868e-05 -4.52115126501671e-06 -1.35021671669659e-05 -2.36249952011632e-06 -3.30252135112909e-06 -1.61945292381868e-05 3.201168914969e-05 6.9679493055941e-06 -8.28855759317894e-06 2.87756027137292e-05 -3.02691349185242e-06 -4.52115126501671e-06 6.9679493055941e-06 6.44294903952338e-05 1522 1571 0 0 10 1527 1602 0 0 49 0 0 0 0 0 0 0 0 760 0 0 0 0 0 2984 +1302 1306 0.999998520876792 0.000585755541518095 -0.00161713780324451 -0.00103589028617175 -0.00058384507571497 0.999999131465058 0.00118160655754717 -0.000299177106876633 0.0016178285312928 -0.00118066065186231 0.999997994333623 -0.00282643126704412 2.84759013457756e-05 -1.06133098258591e-05 -1.01494945222497e-06 -7.51618323990906e-09 -6.91136686592141e-06 -9.17551093903162e-07 -1.06133098258591e-05 2.34633260542625e-05 -4.08024697140757e-06 -1.62693012985642e-06 -5.82559230045358e-06 5.8061282305898e-06 -1.01494945222497e-06 -4.08024697140757e-06 1.84249487293324e-05 7.96833448257415e-07 3.28395415032552e-06 -1.90195552901561e-06 -7.51618323990906e-09 -1.62693012985642e-06 7.96833448257415e-07 2.09810819549061e-05 -3.41714118172486e-06 -2.53311831981076e-06 -6.91136686592141e-06 -5.82559230045358e-06 3.28395415032552e-06 -3.41714118172486e-06 4.306946673835e-05 -8.51702876182217e-07 -9.17551093903162e-07 5.8061282305898e-06 -1.90195552901561e-06 -2.53311831981076e-06 -8.51702876182217e-07 3.14028258022769e-05 1407 1407 0 0 0 1408 1478 0 0 0 0 0 0 0 0 0 0 0 1103 0 0 7 0 0 3060 +1302 1304 0.999999909964064 -0.000316269759476774 0.000282922788240607 -0.00305460224950999 0.000316540003407138 0.999999493265825 -0.000955651882145081 0.00146647723842043 -0.000282620401083052 0.000955741352482423 0.999999503341965 0.000591402330739391 3.00722449996569e-05 -1.3073546401095e-05 3.09510866211589e-07 2.34274716569814e-06 -6.12750791084837e-06 -3.65832082885036e-06 -1.3073546401095e-05 2.09079730283866e-05 -5.74852462244297e-06 -1.59056036527165e-06 -1.40370992627616e-06 6.4159802055316e-06 3.09510866211589e-07 -5.74852462244297e-06 1.94865907698013e-05 1.25481165037086e-06 8.11641155955667e-07 1.096874843256e-06 2.34274716569814e-06 -1.59056036527165e-06 1.25481165037086e-06 2.389392204598e-05 -8.0081860706485e-06 2.13956847915898e-07 -6.12750791084837e-06 -1.40370992627616e-06 8.11641155955667e-07 -8.0081860706485e-06 3.7229277873782e-05 1.51020952557392e-06 -3.65832082885036e-06 6.4159802055316e-06 1.096874843256e-06 2.13956847915898e-07 1.51020952557392e-06 3.09253950772277e-05 1408 1410 0 0 0 1409 1480 0 0 0 0 0 0 0 0 0 0 0 1099 0 0 8 0 0 2928 +1303 1305 0.999999520826342 0.000446237567175068 0.000871331807814839 -0.00182758402658293 -0.000444888973460363 0.999998703937519 -0.00154731932189396 -0.0029477818282824 -0.000872021150524219 0.00154693093454577 0.999998423290655 -0.00185810092153799 2.54392188367491e-05 -1.89665877518108e-05 6.75441248417334e-06 -2.10879097742069e-07 2.27255674214749e-06 4.64930415950217e-07 -1.89665877518108e-05 2.63055176613739e-05 -9.84481043840046e-06 -1.26335017688595e-06 -3.54583634567167e-06 1.18961808123167e-06 6.75441248417334e-06 -9.84481043840046e-06 2.08631220545711e-05 2.10449251127387e-06 3.6436161828857e-06 3.67383217476834e-06 -2.10879097742069e-07 -1.26335017688595e-06 2.10449251127387e-06 2.18960977298992e-05 -1.24717302207256e-06 -3.19169634248518e-06 2.27255674214749e-06 -3.54583634567167e-06 3.6436161828857e-06 -1.24717302207256e-06 4.03055068901204e-05 8.50664801366565e-06 4.64930415950217e-07 1.18961808123167e-06 3.67383217476834e-06 -3.19169634248518e-06 8.50664801366565e-06 4.01461518660028e-05 1291 1292 0 0 0 1297 1355 0 0 0 0 0 0 0 0 0 0 0 1007 0 0 1 0 0 2950 +1300 1268 0.998329671723962 -0.00307202042346923 -0.0576925406447298 -0.00710221524468823 -0.00633630284147754 0.986739629821363 -0.162187404585871 0.0369173016965482 0.0574257592185518 0.162282055787193 0.985071985464847 -0.0192080264305769 0.000181227443553092 1.55376489217923e-05 6.79016178450491e-06 7.79609141436593e-07 -2.20493538048742e-05 5.52402283200027e-06 1.55376489217923e-05 0.000158595185333415 -2.77987023072841e-05 1.99235782326952e-05 -2.10304808313485e-05 -3.59472669707816e-05 6.79016178450491e-06 -2.77987023072841e-05 2.44474890715958e-05 -7.16117754664692e-06 2.07705883682321e-06 1.49553700046782e-05 7.79609141436593e-07 1.99235782326952e-05 -7.16117754664692e-06 4.22183853099628e-05 -2.00500945346148e-05 -3.10197188743608e-05 -2.20493538048742e-05 -2.10304808313485e-05 2.07705883682321e-06 -2.00500945346148e-05 4.01673243742304e-05 4.48963186394866e-05 5.52402283200027e-06 -3.59472669707816e-05 1.49553700046782e-05 -3.10197188743608e-05 4.48963186394866e-05 0.000245324963391898 1498 1536 0 0 2 1513 1585 0 0 29 0 0 0 0 0 0 0 0 777 0 0 7 0 0 3095 +1303 1307 0.999999781547736 6.25957627276737e-05 -0.000658016908410776 -0.00273596327441328 -6.07867964458027e-05 0.99999622025274 0.00274877885598719 0.00131986803226737 0.00065818648318223 -0.00274873825677035 0.999996005606297 -0.00402746587048207 5.10528473368473e-05 -1.32401515474981e-05 3.91684516877613e-06 2.8492686705603e-06 -6.20727742220348e-06 6.02519501080167e-06 -1.32401515474981e-05 5.67185983553217e-05 -1.13642792354627e-05 7.14646421992228e-06 -1.0593951616058e-05 -4.04984931160069e-06 3.91684516877613e-06 -1.13642792354627e-05 2.13897494960652e-05 -1.85939873250501e-06 4.98861285071728e-06 1.30642862520287e-06 2.8492686705603e-06 7.14646421992228e-06 -1.85939873250501e-06 2.48108125247647e-05 -1.0789420779881e-05 -3.16283427714796e-06 -6.20727742220348e-06 -1.0593951616058e-05 4.98861285071728e-06 -1.0789420779881e-05 4.470564338655e-05 4.90770413299373e-06 6.02519501080167e-06 -4.04984931160069e-06 1.30642862520287e-06 -3.16283427714796e-06 4.90770413299373e-06 4.26168585513583e-05 1414 1420 0 0 0 1418 1485 0 0 0 0 0 0 0 0 0 0 0 1102 0 0 7 0 0 2923 +1302 1305 0.999999978742639 -8.42145281863187e-05 0.000188209021613122 -0.00295516086183252 8.40567055236335e-05 0.9999996450094 0.000838400586702723 0.00183022768044347 -0.000188279560310529 -0.000838384748650232 0.999999630830842 -0.0015355239563808 2.36289657982308e-05 -1.43304395456743e-05 5.02862224545166e-06 3.70284026744324e-06 -2.39574770595255e-06 -3.66038243836268e-06 -1.43304395456743e-05 2.65657494628159e-05 -6.29101557784728e-06 -4.82300434502571e-06 1.81141212628359e-06 3.64545040962101e-06 5.02862224545166e-06 -6.29101557784728e-06 1.96068753968398e-05 3.9888612543494e-06 7.3867829681227e-07 -6.16411130376003e-07 3.70284026744324e-06 -4.82300434502571e-06 3.9888612543494e-06 2.51303500500462e-05 -5.83550564323263e-06 -6.31160705543133e-06 -2.39574770595255e-06 1.81141212628359e-06 7.3867829681227e-07 -5.83550564323263e-06 3.51819760834887e-05 3.30756970106274e-06 -3.66038243836268e-06 3.64545040962101e-06 -6.16411130376003e-07 -6.31160705543133e-06 3.30756970106274e-06 3.58953736704387e-05 1297 1299 0 0 0 1297 1359 0 0 0 0 0 0 0 0 0 0 0 1008 0 0 0 0 0 2919 +1301 1303 0.999999495181218 0.000174343480965601 -0.000989566399717215 -0.00427757065791773 -0.000172989996640977 0.999999049768275 0.00136767576880466 -0.00116919006375116 0.000989803904754193 -0.00136750389328808 0.999998575109651 -0.0041077419031855 3.7290048800304e-05 3.41457509618398e-06 -3.50505021579287e-06 8.74968771567176e-06 -4.66016918574394e-06 8.44161919189438e-07 3.41457509618398e-06 4.17898096961368e-05 -7.9581794646984e-06 1.2402605742008e-05 -5.23598732990515e-06 5.1690907142589e-06 -3.50505021579287e-06 -7.9581794646984e-06 1.92344819299828e-05 2.30835511950847e-07 3.08767517632341e-06 -3.20078070800668e-07 8.74968771567176e-06 1.2402605742008e-05 2.30835511950847e-07 2.96812400547393e-05 -7.42656903276187e-06 -2.13397138386355e-06 -4.66016918574394e-06 -5.23598732990515e-06 3.08767517632341e-06 -7.42656903276187e-06 3.94542050870418e-05 1.93206101837496e-06 8.44161919189438e-07 5.1690907142589e-06 -3.20078070800668e-07 -2.13397138386355e-06 1.93206101837496e-06 3.42879474791807e-05 1389 1389 0 0 0 1406 1479 0 0 0 0 0 0 0 0 0 0 0 999 0 0 2 0 0 3025 +1301 1267 0.997561945072498 -0.00913479456704877 -0.0691861349649744 -0.00767903249142264 -0.00186010443136133 0.987563429796897 -0.157210089177809 0.0340882406567903 0.0697617786089078 0.156955495781473 0.985138704238806 -0.0179553045697049 7.92537762801839e-05 1.43688008867592e-05 -3.24549596140185e-06 6.25941047495122e-06 -7.74312387685328e-06 -7.12987286547516e-06 1.43688008867592e-05 4.76017205553716e-05 -5.96666710201612e-06 5.90991911555595e-06 -2.60650983443669e-06 1.86012553300972e-05 -3.24549596140185e-06 -5.96666710201612e-06 1.68118828771999e-05 -2.72905788075002e-07 -4.75861425803832e-06 -4.82058947531557e-06 6.25941047495122e-06 5.90991911555595e-06 -2.72905788075002e-07 2.84271035995008e-05 -1.12366306006849e-05 -1.73557729478944e-06 -7.74312387685328e-06 -2.60650983443669e-06 -4.75861425803832e-06 -1.12366306006849e-05 2.77571370035805e-05 7.8246194078278e-06 -7.12987286547516e-06 1.86012553300972e-05 -4.82058947531557e-06 -1.73557729478944e-06 7.8246194078278e-06 9.79338778249357e-05 1551 1601 0 0 9 1555 1635 0 0 42 0 0 0 0 0 0 0 0 783 0 0 2 0 0 2853 +1301 1305 0.999998265091482 -0.000865529777466674 -0.00164944603735542 -0.00498086981941014 0.000865633667556798 0.999999623400207 6.22719694427974e-05 0.00355487824210111 0.00164939151793053 -6.36996774293802e-05 0.999998637724058 -0.0050129535986231 2.74246758145217e-05 -1.42379896282908e-05 5.29671321005771e-06 -1.62756640056625e-07 -5.4567423212689e-06 -2.77767883580689e-06 -1.42379896282908e-05 2.28440635845374e-05 -8.75251720927496e-06 -2.79758283248453e-06 -1.13074832690961e-06 5.89549277055331e-06 5.29671321005771e-06 -8.75251720927496e-06 2.48019038042071e-05 1.17555556793797e-06 6.40519556831359e-06 1.67482541041165e-06 -1.62756640056625e-07 -2.79758283248453e-06 1.17555556793797e-06 2.56780901952766e-05 -9.48429966814267e-06 -2.17375960040798e-06 -5.4567423212689e-06 -1.13074832690961e-06 6.40519556831359e-06 -9.48429966814267e-06 4.44453869115219e-05 6.28908964154807e-06 -2.77767883580689e-06 5.89549277055331e-06 1.67482541041165e-06 -2.17375960040798e-06 6.28908964154807e-06 3.18748085567983e-05 1233 1240 0 0 0 1235 1299 0 0 0 0 0 0 0 0 0 0 0 1008 0 23 24 0 0 2930 +1306 1310 0.999987214384812 -0.000808090386583867 -0.00499179895742282 -0.00589009593666278 0.000826295264372799 0.999993012037175 0.00364597215482161 0.00414760468588474 0.00498881779986921 -0.00365005023866387 0.999980894232592 0.00195164310804726 3.59490886592598e-05 -2.53222437414155e-05 8.56651099359495e-06 -6.62222189594672e-07 5.69417895861042e-06 2.04260269397869e-07 -2.53222437414155e-05 3.27707982107702e-05 -1.19228857670205e-05 1.73440207558018e-06 -6.96391765684349e-06 3.33388041035043e-06 8.56651099359495e-06 -1.19228857670205e-05 2.44617629364874e-05 1.59992227662657e-06 5.3237578402212e-06 2.91951977459467e-06 -6.62222189594672e-07 1.73440207558018e-06 1.59992227662657e-06 2.34713833600669e-05 -1.21795074218149e-05 -3.07900322886393e-06 5.69417895861042e-06 -6.96391765684349e-06 5.3237578402212e-06 -1.21795074218149e-05 4.18086957088983e-05 1.18669948344984e-05 2.04260269397869e-07 3.33388041035043e-06 2.91951977459467e-06 -3.07900322886393e-06 1.18669948344984e-05 3.51754860614991e-05 1410 1413 0 0 0 1415 1486 0 0 0 0 0 0 0 0 0 0 0 1098 0 0 5 0 0 2839 +1303 1306 0.999998013853152 -0.000786212555587494 -0.00183143647703989 -0.00381668781599765 0.000790052561464355 0.999997489328666 0.00209693903442862 0.00508768332884385 0.00182978323910765 -0.00209838180067961 0.999996124336048 -0.000489276665063345 2.29315166246545e-05 -1.39963322936483e-05 3.33743856914146e-07 4.80308338430695e-06 -4.96061237997645e-06 -6.61446078863821e-06 -1.39963322936483e-05 2.19150649852795e-05 -7.23387089932223e-06 -3.83146013181879e-06 -6.10310651081041e-06 5.08466546101072e-06 3.33743856914146e-07 -7.23387089932223e-06 2.58336477515234e-05 5.23731730765911e-07 6.57788217452233e-06 2.45704159097927e-06 4.80308338430695e-06 -3.83146013181879e-06 5.23731730765911e-07 2.59462425983866e-05 -1.02516361290422e-05 -2.00615105840951e-06 -4.96061237997645e-06 -6.10310651081041e-06 6.57788217452233e-06 -1.02516361290422e-05 4.34545438129753e-05 7.16236885383805e-06 -6.61446078863821e-06 5.08466546101072e-06 2.45704159097927e-06 -2.00615105840951e-06 7.16236885383805e-06 2.61459300425636e-05 1408 1416 0 0 0 1408 1489 0 0 0 0 0 0 0 0 0 0 0 1103 0 0 0 0 0 3069 +1306 1309 0.999993619967678 -0.000502851615083498 -0.00353654693066981 -0.00478929011518329 0.000515432679352483 0.999993539483242 0.00355743178862151 0.0023143082296089 0.00353473522242864 -0.00355923194395184 0.999987418678293 0.00454436082733327 3.49952420099411e-05 -1.33758430183142e-05 3.40125176185019e-06 1.11962846862032e-06 4.15818370773259e-06 -2.33313205093026e-06 -1.33758430183142e-05 3.11355082453973e-05 -6.91720103866938e-06 3.68350305877658e-06 -6.38853828005492e-06 9.50353273632271e-06 3.40125176185019e-06 -6.91720103866938e-06 2.18231305870728e-05 6.89870421894059e-07 4.32508937215518e-06 2.14197120329081e-06 1.11962846862032e-06 3.68350305877658e-06 6.89870421894059e-07 2.3602427129978e-05 -1.13486316103129e-05 -4.15716321689808e-06 4.15818370773259e-06 -6.38853828005492e-06 4.32508937215518e-06 -1.13486316103129e-05 4.1457884784707e-05 1.86248649073801e-06 -2.33313205093026e-06 9.50353273632271e-06 2.14197120329081e-06 -4.15716321689808e-06 1.86248649073801e-06 3.23068725209765e-05 1407 1408 0 0 0 1409 1488 0 0 0 0 0 0 0 0 0 0 0 996 0 0 0 0 0 2793 +1304 1307 0.999996592205665 0.00126373232254569 -0.00228441626562706 -0.0049941757013247 -0.001249568951667 0.999980055922312 0.00619082668507592 0.00031727827863022 0.00229219425283679 -0.0061879510523736 0.999978227316616 -0.00441801952210461 5.73661710344774e-05 -1.33796995489243e-05 3.209188044006e-07 2.39940893513101e-06 -7.74310350024115e-06 3.50389900656951e-06 -1.33796995489243e-05 3.17891767213965e-05 -7.97781588157872e-06 6.06647419300784e-06 -5.34492417345179e-06 8.89499614563032e-06 3.209188044006e-07 -7.97781588157872e-06 2.14005512782485e-05 1.5860340852396e-06 -1.98902859759866e-07 -2.1540116410942e-06 2.39940893513101e-06 6.06647419300784e-06 1.5860340852396e-06 2.52458781129037e-05 -9.53234801675692e-06 1.34060156414623e-06 -7.74310350024115e-06 -5.34492417345179e-06 -1.98902859759866e-07 -9.53234801675692e-06 3.69818137142566e-05 1.0979108422723e-06 3.50389900656951e-06 8.89499614563032e-06 -2.1540116410942e-06 1.34060156414623e-06 1.0979108422723e-06 3.33167441977177e-05 1407 1407 0 0 0 1418 1479 0 0 0 0 0 0 0 0 0 0 0 1106 0 0 6 0 0 2874 +1305 1308 0.999990751297964 -0.000654964536688533 -0.0042506870020363 -0.00493509593137116 0.000673833235775446 0.999989920281894 0.00443906334504361 0.00533381318751576 0.00424773672724245 -0.00444188654364626 0.999981113009956 0.000381611072122382 5.10113519889948e-05 -1.64434857350527e-05 3.01540141515869e-06 3.97559944711291e-06 -4.44730544971779e-06 -1.05215522446247e-06 -1.64434857350527e-05 4.48664547812064e-05 -1.1617418637268e-05 7.85999332085953e-06 -9.79988726472603e-06 -6.40504888459927e-06 3.01540141515869e-06 -1.1617418637268e-05 1.801449190396e-05 2.80037071696338e-06 4.1744961731701e-07 4.36705381427367e-06 3.97559944711291e-06 7.85999332085953e-06 2.80037071696338e-06 2.6272081036681e-05 -1.47075346908197e-05 -6.90572657682281e-06 -4.44730544971779e-06 -9.79988726472603e-06 4.1744961731701e-07 -1.47075346908197e-05 3.25602181865406e-05 1.30738542742443e-05 -1.05215522446247e-06 -6.40504888459927e-06 4.36705381427367e-06 -6.90572657682281e-06 1.30738542742443e-05 4.76212952847659e-05 1302 1304 0 0 0 1305 1370 0 0 0 0 0 0 0 0 0 0 0 1104 0 0 0 0 0 2966 +1304 1306 0.999992432567535 0.000577652437465947 -0.00384722306665273 -0.0046259161535012 -0.000562826762549499 0.999992416573282 0.00385357262321 0.00209632777217808 0.00384941991713729 -0.00385137814145602 0.999985174316456 -0.00219798959937491 3.14222571387972e-05 -9.32189853048118e-06 1.90832145129033e-06 3.53396840462706e-07 -5.40096952903064e-06 -5.56694084183201e-06 -9.32189853048118e-06 2.62470163070609e-05 -6.80704632187494e-06 -1.18985638511093e-07 -9.45258124451401e-06 3.95111285308252e-06 1.90832145129033e-06 -6.80704632187494e-06 1.97818438525388e-05 2.79816502412116e-06 1.20789419286314e-06 6.26265122260333e-07 3.53396840462706e-07 -1.18985638511093e-07 2.79816502412116e-06 2.50091052493029e-05 -8.02094185932496e-06 -1.44809622623284e-06 -5.40096952903064e-06 -9.45258124451401e-06 1.20789419286314e-06 -8.02094185932496e-06 3.73995563027323e-05 7.59227998918285e-06 -5.56694084183201e-06 3.95111285308252e-06 6.26265122260333e-07 -1.44809622623284e-06 7.59227998918285e-06 3.26480129813755e-05 1405 1405 0 0 0 1408 1484 0 0 0 0 0 0 0 0 0 0 0 1102 0 0 0 0 0 2990 +1304 1308 0.999980820405557 -0.000785355290768294 -0.00614345489905305 -0.00762363782503911 0.000807199637608581 0.999993358594187 0.00355403942904549 0.00506241300047541 0.00614062291420677 -0.00355893025857879 0.999974813065629 -0.00108220607472883 4.12031437957094e-05 -1.32517377297944e-05 7.29020966965077e-06 5.29731204556573e-06 -1.91231126617438e-06 -3.83154731517082e-06 -1.32517377297944e-05 3.8528046259296e-05 -9.03424373104848e-06 5.38371171769586e-06 -5.93073671356757e-06 1.85201141896256e-07 7.29020966965077e-06 -9.03424373104848e-06 1.74526723308778e-05 4.07050949643316e-06 1.6958173205545e-07 1.724563092023e-06 5.29731204556573e-06 5.38371171769586e-06 4.07050949643316e-06 3.04564099821439e-05 -1.19449551527152e-05 -3.08816192487974e-06 -1.91231126617438e-06 -5.93073671356757e-06 1.6958173205545e-07 -1.19449551527152e-05 3.6335108145447e-05 9.90515819284051e-06 -3.83154731517082e-06 1.85201141896256e-07 1.724563092023e-06 -3.08816192487974e-06 9.90515819284051e-06 4.64247518206749e-05 1298 1298 0 0 0 1303 1365 0 0 0 0 0 0 0 0 0 0 0 1107 0 2 3 0 0 2999 +1305 1307 0.999996207031044 0.000673404264463965 -0.00267066475280142 -0.00646743361000294 -0.000664715782358129 0.999994488520286 0.00325285751014154 -0.00226036351404221 0.00267284052160583 -0.00325106993914341 0.999991143194677 0.000424812709205893 4.11426041066016e-05 -1.45431825512068e-05 3.48089350484487e-06 5.9974625408164e-06 -4.48102394457541e-06 -2.13747220770753e-06 -1.45431825512068e-05 3.74258536168338e-05 -7.99909538531698e-06 3.20168441068762e-06 1.05006835217371e-08 3.1659709228221e-06 3.48089350484487e-06 -7.99909538531698e-06 2.15082228726871e-05 3.69901800398788e-06 3.50815285227545e-06 1.06585169107024e-06 5.9974625408164e-06 3.20168441068762e-06 3.69901800398788e-06 2.48622886230291e-05 -3.40897281331407e-06 -5.06883936219643e-06 -4.48102394457541e-06 1.05006835217371e-08 3.50815285227545e-06 -3.40897281331407e-06 4.62172920782263e-05 5.04258809315775e-06 -2.13747220770753e-06 3.1659709228221e-06 1.06585169107024e-06 -5.06883936219643e-06 5.04258809315775e-06 3.86472759103012e-05 1395 1395 0 0 0 1418 1480 0 0 0 0 0 0 0 0 0 0 0 1100 0 0 5 0 0 2885 +1308 1310 0.999980595485324 0.00111325785060216 -0.0061293808638833 -0.00658250901711359 -0.00107771024868396 0.999982600315919 0.00579979361979385 -0.00059653439828665 0.00613573088037177 -0.00579307538103835 0.999964395908271 0.00656813807885154 3.18856520019559e-05 -1.98630658034663e-05 6.55986710768814e-06 1.1887846051895e-06 -8.62845542001697e-07 -1.95086379468168e-06 -1.98630658034663e-05 2.62784184040533e-05 -9.78489158546138e-06 8.7974448579226e-07 -9.63961120758096e-07 4.79146854600605e-06 6.55986710768814e-06 -9.78489158546138e-06 2.01811701290771e-05 3.93762571604401e-06 2.515322017316e-06 3.72884831002611e-07 1.1887846051895e-06 8.7974448579226e-07 3.93762571604401e-06 2.73001025272217e-05 9.20230086480093e-07 -4.54362836213415e-06 -8.62845542001697e-07 -9.63961120758096e-07 2.515322017316e-06 9.20230086480093e-07 4.2144982178473e-05 9.32431859606308e-06 -1.95086379468168e-06 4.79146854600605e-06 3.72884831002611e-07 -4.54362836213415e-06 9.32431859606308e-06 4.01739601307381e-05 1408 1408 0 0 0 1415 1480 0 0 0 0 0 0 0 0 0 0 0 1099 0 0 6 0 0 2833 +1305 1309 0.99999961053852 -0.000197455358299941 -0.000860194275019446 -0.00246594442564765 0.000196886986125745 0.999999762300515 -0.000660783192312015 0.00127692242044557 0.000860324545733706 0.000660613573904123 0.999999411715518 0.000105324540315986 3.04165862927926e-05 -1.46897586651375e-05 -3.63134314299126e-07 3.40310912000518e-07 -5.69965735755741e-06 -5.2550534828245e-06 -1.46897586651375e-05 2.87187222134469e-05 -6.5023240679736e-06 2.16473034775074e-06 -3.38816539048573e-07 3.59048860136626e-06 -3.63134314299126e-07 -6.5023240679736e-06 2.22788384931466e-05 2.07926277125521e-06 5.0191252909786e-06 2.16645815715723e-06 3.40310912000518e-07 2.16473034775074e-06 2.07926277125521e-06 1.82401374022389e-05 -7.87729189326496e-06 -2.26241977032581e-06 -5.69965735755741e-06 -3.38816539048573e-07 5.0191252909786e-06 -7.87729189326496e-06 4.30025833016022e-05 3.03181501468724e-06 -5.2550534828245e-06 3.59048860136626e-06 2.16645815715723e-06 -2.26241977032581e-06 3.03181501468724e-06 3.47823591211598e-05 1389 1390 0 0 0 1395 1457 0 0 0 0 0 0 0 0 0 0 0 1000 0 14 29 0 0 2868 +1307 1310 0.999994279177823 -0.000677109647205585 -0.00331408119282079 -0.00153210423582159 0.000681238320944875 0.999998993159355 0.00124482714739967 0.00197859033085815 0.00331323497159854 -0.00124707770507219 0.999993733615977 -0.000998489628502269 4.78162412323056e-05 -3.10724154212236e-05 1.04082288643405e-05 -4.96202585804784e-06 1.15802777973739e-06 5.50154171791012e-06 -3.10724154212236e-05 3.59609219790192e-05 -1.22855370016763e-05 2.98450359433011e-06 -4.45658848054739e-06 4.10080169155567e-06 1.04082288643405e-05 -1.22855370016763e-05 1.98161495478722e-05 1.11032915367136e-06 -1.96183135828563e-07 1.21477827230852e-06 -4.96202585804784e-06 2.98450359433011e-06 1.11032915367136e-06 2.42546847888842e-05 -7.2652576061232e-06 -8.72527927351014e-06 1.15802777973739e-06 -4.45658848054739e-06 -1.96183135828563e-07 -7.2652576061232e-06 3.35641227521111e-05 2.5223316318559e-06 5.50154171791012e-06 4.10080169155567e-06 1.21477827230852e-06 -8.72527927351014e-06 2.5223316318559e-06 4.24797836730892e-05 1414 1415 0 0 0 1415 1492 0 0 0 0 0 0 0 0 0 0 0 1097 0 0 0 0 0 2851 +1307 1311 0.999989106441456 -0.00125368219171916 -0.00449614049836258 -0.00795687279739402 0.00127118981800583 0.999991613570738 0.00389318181435033 0.00463871478014087 0.00449122197908856 -0.00389885485176816 0.999982313771588 -0.00152830564903553 3.27290936644264e-05 -7.74445409090521e-06 2.47047801514291e-06 4.14744170127478e-06 -8.02821443154399e-07 -7.88775048831198e-06 -7.74445409090521e-06 3.42345849844067e-05 -1.05933941159785e-05 7.13066446431029e-06 -9.74572954089185e-06 -3.60048002952557e-07 2.47047801514291e-06 -1.05933941159785e-05 1.8632900797655e-05 1.87463924001168e-06 2.43850296001121e-06 7.12514287448012e-07 4.14744170127478e-06 7.13066446431029e-06 1.87463924001168e-06 2.97725369912966e-05 -2.09847272093635e-05 -8.94004752168446e-06 -8.02821443154399e-07 -9.74572954089185e-06 2.43850296001121e-06 -2.09847272093635e-05 4.48388477760518e-05 1.67393737165376e-05 -7.88775048831198e-06 -3.60048002952557e-07 7.12514287448012e-07 -8.94004752168446e-06 1.67393737165376e-05 5.13970941519159e-05 1372 1374 0 0 0 1375 1439 0 0 0 0 0 0 0 0 0 0 0 1004 0 30 48 0 0 3131 +1308 1312 0.999997009261104 -0.000146246459106368 0.00244132767574143 -0.00272581130555015 0.000151611833524542 0.999997573588336 -0.00219768771484204 0.00408545861512043 -0.00244100034802897 0.00219805127629707 0.999994605029391 -0.00606191024544986 4.35648812551482e-05 -2.6883982294634e-05 6.58434249632402e-06 -1.04647467938192e-06 -5.55511473798715e-07 -6.38218392878823e-06 -2.6883982294634e-05 4.33367518261319e-05 -1.0500332762561e-05 4.94986923104788e-06 -4.55469369767676e-06 -3.19623257908595e-06 6.58434249632402e-06 -1.0500332762561e-05 2.13099800455501e-05 -4.43822487521354e-07 1.55122596594267e-06 3.19647745625843e-06 -1.04647467938192e-06 4.94986923104788e-06 -4.43822487521354e-07 2.73612143041516e-05 -1.09095831883757e-05 -3.91400703848916e-06 -5.55511473798715e-07 -4.55469369767676e-06 1.55122596594267e-06 -1.09095831883757e-05 4.02435026505886e-05 4.73957112137507e-06 -6.38218392878823e-06 -3.19623257908595e-06 3.19647745625843e-06 -3.91400703848916e-06 4.73957112137507e-06 5.37729416559956e-05 1394 1399 0 0 0 1394 1460 0 0 0 0 0 0 0 0 0 0 0 1100 0 10 26 0 0 2761 +1306 1308 0.999999799192771 -0.000465000026278577 -0.000430568686172648 -0.00428661139085057 0.000464954391352746 0.999999886282048 -0.000106081595459221 -0.00133130710558316 0.000430617965153935 0.000105881379355854 0.999999901678646 -0.00136462484411587 3.58164415379554e-05 -1.38234563735647e-05 5.56092489669033e-06 4.53588810220028e-06 -8.57384372335445e-07 4.1463435748536e-06 -1.38234563735647e-05 2.1831864649606e-05 -7.99944536752016e-06 1.81648151091659e-06 -2.76285900914818e-06 4.42443262921055e-06 5.56092489669033e-06 -7.99944536752016e-06 1.96497964866981e-05 7.79668863909873e-07 3.43850595396169e-06 6.10140701226855e-07 4.53588810220028e-06 1.81648151091659e-06 7.79668863909873e-07 2.42650378705087e-05 -5.96308689738659e-06 -3.08117915823434e-06 -8.57384372335445e-07 -2.76285900914818e-06 3.43850595396169e-06 -5.96308689738659e-06 3.92730465329857e-05 5.38332387840499e-06 4.1463435748536e-06 4.42443262921055e-06 6.10140701226855e-07 -3.08117915823434e-06 5.38332387840499e-06 3.36899197091248e-05 1299 1299 0 0 0 1305 1365 0 0 0 0 0 0 0 0 0 0 0 1102 0 0 0 0 0 3200 +1309 1312 0.999999628862369 -7.66379537706643e-05 -0.000858138536870979 -0.00145908732649572 7.90053519725529e-05 0.999996190649352 0.00275906595396755 0.00474860246595943 0.000857923818751358 -0.0027591327275115 0.999995825567944 -3.87828108330387e-05 3.70117018623252e-05 -1.91540521077746e-05 2.61470238878006e-06 -4.989753429919e-06 -2.5877937181859e-06 -2.06531728676984e-06 -1.91540521077746e-05 3.47165594622137e-05 -6.97987372677578e-06 -7.71607551739474e-07 -2.39178944304906e-06 2.46160845205928e-06 2.61470238878006e-06 -6.97987372677578e-06 1.66148931694689e-05 1.60575162416034e-06 -2.33969916901512e-06 1.50696680326138e-07 -4.989753429919e-06 -7.71607551739474e-07 1.60575162416034e-06 2.47967608698803e-05 -5.52804491245507e-06 5.92235583444199e-07 -2.5877937181859e-06 -2.39178944304906e-06 -2.33969916901512e-06 -5.52804491245507e-06 3.47489503675639e-05 -4.91860797047961e-08 -2.06531728676984e-06 2.46160845205928e-06 1.50696680326138e-07 5.92235583444199e-07 -4.91860797047961e-08 3.65763962796847e-05 1404 1409 0 0 0 1404 1486 0 0 1 0 0 0 0 0 0 0 0 1102 0 0 0 0 0 2985 +1307 1309 0.999999513676335 0.000283582831898945 0.000944578144560958 -0.000430756294805293 -0.000282280596011356 0.999999010039682 -0.00137849095818021 -0.000700131501108615 -0.000944968125835745 0.0013782236517058 0.999998603766429 -0.00123812390132129 3.00548157090054e-05 -1.07707021433796e-05 1.49371499730982e-06 8.63668622233852e-07 -2.61968104444809e-06 -2.49384594602939e-06 -1.07707021433796e-05 3.85780370835303e-05 -7.93541157153045e-06 5.09921344246131e-06 -5.79289006283869e-06 3.49842581213397e-06 1.49371499730982e-06 -7.93541157153045e-06 1.84813868772857e-05 1.79837043760475e-06 8.7874648183095e-07 3.46102643450671e-07 8.63668622233852e-07 5.09921344246131e-06 1.79837043760475e-06 2.29588811628807e-05 -6.85962703126557e-06 -4.87656971918233e-06 -2.61968104444809e-06 -5.79289006283869e-06 8.7874648183095e-07 -6.85962703126557e-06 3.49614554931552e-05 4.52695344483075e-06 -2.49384594602939e-06 3.49842581213397e-06 3.46102643450671e-07 -4.87656971918233e-06 4.52695344483075e-06 3.46161516996182e-05 1405 1405 0 0 0 1409 1481 0 0 0 0 0 0 0 0 0 0 0 1001 0 0 6 0 0 2867 +1310 1312 0.999997685784296 0.000757478155922443 0.00201361686929855 -0.00123171417343628 -0.000766373818489337 0.999989935173336 0.00442065868369954 0.00461112896519248 -0.00201024805020611 -0.00442219163659089 0.999988201492351 -0.0034547510737199 5.69233574387118e-05 -3.28262641542872e-05 4.36353360524236e-06 5.41180664493112e-07 -3.12185223333554e-06 1.46688462140027e-06 -3.28262641542872e-05 4.21209149850237e-05 -6.62887926477317e-06 3.07818625731801e-06 2.08845141479122e-06 -3.65279131142859e-07 4.36353360524236e-06 -6.62887926477317e-06 1.61687346231499e-05 2.12822430577383e-06 -9.97794734345021e-07 -1.36048017585722e-06 5.41180664493112e-07 3.07818625731801e-06 2.12822430577383e-06 2.89005715362239e-05 -9.86791886966609e-06 -7.08415879997476e-06 -3.12185223333554e-06 2.08845141479122e-06 -9.97794734345021e-07 -9.86791886966609e-06 3.27185079756049e-05 -1.8718029162694e-06 1.46688462140027e-06 -3.65279131142859e-07 -1.36048017585722e-06 -7.08415879997476e-06 -1.8718029162694e-06 4.1579867471167e-05 1403 1404 0 0 0 1404 1477 0 0 0 0 0 0 0 0 0 0 0 1101 0 0 8 0 0 2907 +1310 1313 0.999997251911802 5.19708220639038e-05 -0.00234381481291348 -0.00646810448486761 -4.78988590086206e-05 0.999998489666961 0.0017373455316894 0.0034314437762616 0.00234390156424802 -0.00173722849125539 0.999995744072257 -0.00237969103367426 4.07205600060113e-05 -2.22454234570068e-05 5.23927234281673e-06 -8.90886450561865e-07 -2.36909144763392e-06 -2.23819721011614e-06 -2.22454234570068e-05 3.13580546499572e-05 -7.75569041483604e-06 1.89715148192919e-06 -5.07148115084042e-06 2.91028579248259e-06 5.23927234281673e-06 -7.75569041483604e-06 1.62796485253664e-05 -7.78800312979614e-07 -1.06630247465863e-06 2.1721219654945e-06 -8.90886450561865e-07 1.89715148192919e-06 -7.78800312979614e-07 3.75393616215345e-05 -1.7084592562199e-05 -1.47390178385976e-05 -2.36909144763392e-06 -5.07148115084042e-06 -1.06630247465863e-06 -1.7084592562199e-05 3.51851811472672e-05 1.1565382858499e-05 -2.23819721011614e-06 2.91028579248259e-06 2.1721219654945e-06 -1.47390178385976e-05 1.1565382858499e-05 4.39897907965624e-05 1399 1399 0 0 0 1407 1473 0 0 0 0 0 0 0 0 0 0 0 1110 0 0 11 0 0 3008 +1308 1311 0.999999372927265 0.000346950947637946 -0.00106478641830524 -0.00415018499161957 -0.000348631803361252 0.999998692913754 -0.00157880545029433 -0.00469102419216896 0.00106423725849044 0.00157917567867768 0.999998186799973 -0.00058154427304758 3.6676262357581e-05 -1.26755200048017e-05 2.5736432830941e-06 9.11450391591539e-08 1.54472085539104e-06 -7.76736295987886e-07 -1.26755200048017e-05 3.10561903392929e-05 -1.08004797149161e-05 2.29384267133446e-06 -8.15862939615491e-06 4.7130257727144e-06 2.5736432830941e-06 -1.08004797149161e-05 2.22490973442229e-05 2.87125572883702e-06 6.24056184872688e-06 6.84269208894281e-07 9.11450391591539e-08 2.29384267133446e-06 2.87125572883702e-06 2.55887905978453e-05 -6.67762826979196e-06 -2.53650367628051e-06 1.54472085539104e-06 -8.15862939615491e-06 6.24056184872688e-06 -6.67762826979196e-06 5.16345138147785e-05 1.17338714536472e-05 -7.76736295987886e-07 4.7130257727144e-06 6.84269208894281e-07 -2.53650367628051e-06 1.17338714536472e-05 3.60112188840652e-05 1382 1382 0 0 0 1405 1466 0 0 0 0 0 0 0 0 0 0 0 1003 0 0 2 0 0 3102 +1309 1313 0.999995096410626 -0.000338430015139121 -0.00311329725983205 -0.0054671606326016 0.000347282719414282 0.999995897190236 0.00284341298580524 0.00515688917321067 0.00311232219026582 -0.00284448023721427 0.999991111151876 0.00126133692308538 3.19640281246825e-05 -1.71391638432199e-05 8.65591380288896e-06 2.29539133331723e-06 8.51265609806134e-09 -2.31820379530627e-06 -1.71391638432199e-05 2.49981723151372e-05 -9.88882857592567e-06 3.29194232849696e-08 -4.93587002734647e-06 7.07424190111787e-06 8.65591380288896e-06 -9.88882857592567e-06 1.85066123154263e-05 5.16582313795541e-07 3.69882824794638e-07 2.90802354326656e-06 2.29539133331723e-06 3.29194232849696e-08 5.16582313795541e-07 2.94551841948808e-05 -1.5968359846162e-05 -6.19322116529892e-06 8.51265609806134e-09 -4.93587002734647e-06 3.69882824794638e-07 -1.5968359846162e-05 3.5529412689366e-05 1.16345116740003e-05 -2.31820379530627e-06 7.07424190111787e-06 2.90802354326656e-06 -6.19322116529892e-06 1.16345116740003e-05 3.27791500107764e-05 1404 1407 0 0 0 1407 1487 0 0 0 0 0 0 0 0 0 0 0 1109 0 0 0 0 0 3050 +1309 1311 0.999999579930262 -0.000850416466673458 -0.000341951946112843 -0.00278142642033075 0.000850823143859868 0.99999892892778 0.00119090019354109 0.00313752827122216 0.000340938818722861 -0.0011911906339098 0.999999232412503 -0.00634569725197382 4.87785263969204e-05 -1.22714945114904e-05 4.53160276319911e-06 2.07530779343798e-06 2.49561945355784e-07 2.18788339448562e-06 -1.22714945114904e-05 3.99471881342949e-05 -7.04784559766259e-06 5.50817292466975e-06 -2.45821111182533e-06 4.55435830572974e-06 4.53160276319911e-06 -7.04784559766259e-06 1.9231791936922e-05 3.13261714773939e-07 1.80445435212472e-06 3.5394266576004e-06 2.07530779343798e-06 5.50817292466975e-06 3.13261714773939e-07 3.33056956062546e-05 -1.83761076348415e-05 -4.35539555330524e-06 2.49561945355784e-07 -2.45821111182533e-06 1.80445435212472e-06 -1.83761076348415e-05 4.30161647393528e-05 8.87517999491025e-06 2.18788339448562e-06 4.55435830572974e-06 3.5394266576004e-06 -4.35539555330524e-06 8.87517999491025e-06 3.658085973212e-05 1397 1401 0 0 0 1405 1487 0 0 1 0 0 0 0 0 0 0 0 1002 0 0 0 0 0 3031 +1311 1313 0.999998189995086 0.00056860337742075 0.00181568079537781 0.00556622179133127 -0.000575205832071929 0.999993217377936 0.00363790274393231 0.00146851362133471 -0.00181359995651426 -0.00363894054949315 0.999991734449278 -0.00822441890322425 4.22807766554106e-05 -2.62806090717724e-05 6.92319263399174e-06 -6.03455151557541e-06 1.21864359189609e-06 5.88232824403584e-06 -2.62806090717724e-05 3.4275920345102e-05 -9.98410593439027e-06 3.1457656468327e-06 -6.04202487894843e-06 -1.01588219795263e-06 6.92319263399174e-06 -9.98410593439027e-06 2.02649057296273e-05 7.50040060889818e-07 4.00469488354854e-06 1.85642406660633e-06 -6.03455151557541e-06 3.1457656468327e-06 7.50040060889818e-07 3.46734464055385e-05 -3.70142472886837e-06 -1.2216877740866e-06 1.21864359189609e-06 -6.04202487894843e-06 4.00469488354854e-06 -3.70142472886837e-06 4.21740803359189e-05 2.09634824649754e-06 5.88232824403584e-06 -1.01588219795263e-06 1.85642406660633e-06 -1.2216877740866e-06 2.09634824649754e-06 5.46286934862718e-05 1402 1408 0 0 0 1407 1487 0 0 0 0 0 0 0 0 0 0 0 1114 0 0 1 0 0 3119 +1310 1314 0.999996254578055 0.000461760490293822 -0.00269770404439153 -0.00920399840498492 -0.00045509133048594 0.999996840424937 0.002472252419191 0.00170102746070243 0.00269883710928232 -0.00247101545783972 0.999993305158022 0.00244466812325151 3.83209121928242e-05 -5.04680643732506e-06 -3.06001446063287e-06 1.78153348982252e-06 -3.36691209252199e-06 -8.95450904125777e-07 -5.04680643732506e-06 4.86394793540727e-05 -5.49152977936538e-06 8.73745686636529e-06 -1.38591099138328e-05 -1.99447207370801e-06 -3.06001446063287e-06 -5.49152977936538e-06 1.8990516495748e-05 -1.53723524474792e-07 2.97381516704389e-06 8.75427186428384e-07 1.78153348982252e-06 8.73745686636529e-06 -1.53723524474792e-07 3.21202960050393e-05 -1.4580424256062e-05 -4.22580530816487e-06 -3.36691209252199e-06 -1.38591099138328e-05 2.97381516704389e-06 -1.4580424256062e-05 3.97287140614249e-05 2.47817206760443e-06 -8.95450904125777e-07 -1.99447207370801e-06 8.75427186428384e-07 -4.22580530816487e-06 2.47817206760443e-06 5.06112239341584e-05 1366 1366 0 0 0 1377 1437 0 0 0 0 0 0 0 0 0 0 0 1106 0 28 46 0 0 2892 +1311 1314 0.999997995496218 -0.00151526520504811 -0.00130880667210023 0.000943262063641864 0.00151477808418053 0.999998783121821 -0.000373098153626844 0.00807831725800325 0.00130937042209221 0.000371114854086858 0.999999073911003 -0.00744244795020326 4.65802307086941e-05 -1.33375601630817e-05 -3.63012974640463e-06 1.06912475844399e-07 -5.74613415893253e-06 4.77945421029669e-06 -1.33375601630817e-05 3.81519661489095e-05 -4.54506777078338e-06 7.2720110203644e-06 -3.27779451952932e-06 1.63972539216652e-05 -3.63012974640463e-06 -4.54506777078338e-06 1.89219479082151e-05 8.61587475928911e-07 -1.29482012586702e-06 -2.33401661403496e-07 1.06912475844399e-07 7.2720110203644e-06 8.61587475928911e-07 3.43425547669677e-05 -1.37265402307466e-05 3.01782694950365e-06 -5.74613415893253e-06 -3.27779451952932e-06 -1.29482012586702e-06 -1.37265402307466e-05 3.45162917337001e-05 -1.72286998025162e-06 4.77945421029669e-06 1.63972539216652e-05 -2.33401661403496e-07 3.01782694950365e-06 -1.72286998025162e-06 5.56188553882716e-05 1405 1418 0 0 0 1405 1489 0 0 0 0 0 0 0 0 0 0 0 1110 0 0 0 0 0 2740 +1313 1317 0.999996285615343 0.000298439345668287 -0.00270918612760751 0.000566036762301062 -0.000292849407262134 0.999997828122141 0.00206348981737474 -0.000248616624632272 0.00270979607013703 -0.00206268876922819 0.999994201143336 0.00137045266504559 4.40484572331798e-05 -2.53368766116014e-05 2.15733697556389e-06 -4.27812731697673e-06 2.39721555330801e-06 5.24174357673215e-06 -2.53368766116014e-05 3.44678828206474e-05 -4.12089761126348e-06 2.79994744611256e-06 -3.63764043966719e-06 2.82241174511094e-06 2.15733697556389e-06 -4.12089761126348e-06 1.6815439827441e-05 -9.32115771082753e-07 8.97153189116208e-07 2.88347452843052e-06 -4.27812731697673e-06 2.79994744611256e-06 -9.32115771082753e-07 2.48936100878119e-05 -1.00562863590797e-05 -5.49154568760155e-06 2.39721555330801e-06 -3.63764043966719e-06 8.97153189116208e-07 -1.00562863590797e-05 3.15172664630903e-05 9.68260709147014e-07 5.24174357673215e-06 2.82241174511094e-06 2.88347452843052e-06 -5.49154568760155e-06 9.68260709147014e-07 4.13666655789313e-05 1385 1386 0 0 0 1402 1482 0 0 0 0 0 0 0 0 0 0 0 1007 0 0 0 0 0 3174 +1311 1315 0.999994821590133 0.000726112452347801 0.00313521189459676 0.00269213396371924 -0.000725585355600637 0.999999722439156 -0.000169255732302428 -0.00165198102176791 -0.00313533392307956 0.00016697999198945 0.999995070887288 -0.0142637894153305 4.40240233600345e-05 -1.97375478817701e-05 3.44320859113135e-06 -4.50302260001171e-08 -9.97564555718622e-08 1.35973342176798e-06 -1.97375478817701e-05 3.81833508654004e-05 -8.81388490412874e-06 6.09827567394667e-06 -8.88760038225192e-06 1.6404603381533e-05 3.44320859113135e-06 -8.81388490412874e-06 1.80495188145299e-05 -5.57099045380823e-07 1.40730769935618e-06 -8.74904012534459e-07 -4.50302260001171e-08 6.09827567394667e-06 -5.57099045380823e-07 3.17174749944513e-05 -1.30480450016733e-05 3.02396472498313e-06 -9.97564555718622e-08 -8.88760038225192e-06 1.40730769935618e-06 -1.30480450016733e-05 3.26362827272069e-05 -3.48394225790672e-06 1.35973342176798e-06 1.6404603381533e-05 -8.74904012534459e-07 3.02396472498313e-06 -3.48394225790672e-06 5.82232583084109e-05 1291 1293 0 0 0 1293 1358 0 0 0 0 0 0 0 0 0 0 0 1102 0 0 0 0 0 3171 +1314 1316 0.999997897395199 0.000890712205388523 0.00184711584568874 0.000549830374725495 -0.000896448992898664 0.999994770489753 0.00310730950318365 -0.00117530184012854 -0.0018443384676771 -0.00310895881487941 0.999993466374008 -0.00799790255142703 8.48063635400202e-05 -3.61781681529404e-05 9.50735631703777e-06 -3.25985754439612e-06 -4.97304911922256e-06 2.13009187752365e-05 -3.61781681529404e-05 5.99713639469393e-05 -1.17797579543344e-05 9.10371373897766e-06 -5.0687787869752e-06 -2.82045491626443e-07 9.50735631703777e-06 -1.17797579543344e-05 1.87132552755956e-05 9.52454760490852e-07 4.03904462675343e-07 2.42132646643265e-06 -3.25985754439612e-06 9.10371373897766e-06 9.52454760490852e-07 2.05547469988877e-05 -1.02653500249751e-05 -6.98143880191496e-06 -4.97304911922256e-06 -5.0687787869752e-06 4.03904462675343e-07 -1.02653500249751e-05 3.03674115974715e-05 1.73984879212845e-06 2.13009187752365e-05 -2.82045491626443e-07 2.42132646643265e-06 -6.98143880191496e-06 1.73984879212845e-06 5.87686953119244e-05 1305 1307 0 0 0 1306 1369 0 0 0 0 0 0 0 0 0 0 0 1093 0 0 0 0 0 3051 +1312 1314 0.999992664931222 0.000519979807731803 0.0037946942896392 0.00217045593819121 -0.000516616717837599 0.999999473002627 -0.00088718748557978 0.00256600979329536 -0.00379515360942345 0.000885220575489444 0.999992406567977 -0.00972446164091679 3.8510258503642e-05 -5.9692806200864e-06 -1.56619702680438e-06 8.05515127995416e-06 -9.49707030340126e-06 5.96117327388898e-06 -5.9692806200864e-06 3.26770153197714e-05 -7.56175541146338e-06 1.7131688055864e-06 -5.19694549611121e-06 1.27999390522559e-05 -1.56619702680438e-06 -7.56175541146338e-06 2.43204281819697e-05 4.13646181494721e-07 3.68253245105553e-06 -1.63167506941453e-06 8.05515127995416e-06 1.7131688055864e-06 4.13646181494721e-07 3.17147397981398e-05 -1.6704802041773e-05 2.12872628335798e-06 -9.49707030340126e-06 -5.19694549611121e-06 3.68253245105553e-06 -1.6704802041773e-05 4.86666647856865e-05 -1.48142545896407e-06 5.96117327388898e-06 1.27999390522559e-05 -1.63167506941453e-06 2.12872628335798e-06 -1.48142545896407e-06 3.57675143202765e-05 1405 1413 0 0 0 1405 1481 0 0 0 0 0 0 0 0 0 0 0 1111 0 0 1 0 0 2800 +1313 1316 0.999997055777264 0.000386866386433981 -0.00239557325130324 -0.00263858557806386 -0.000380272441073103 0.999996139840948 0.00275239824049377 -0.00109787651024217 0.0023966288143708 -0.00275147916633225 0.999993342744202 0.000656768163719805 2.71341911063883e-05 -1.0292526450674e-05 9.82722012267827e-06 -1.45965138693793e-06 3.84485835473215e-06 2.01661072120981e-06 -1.0292526450674e-05 3.18561424968696e-05 -1.24635111714659e-05 2.26804946223584e-06 -9.29493335815989e-06 -2.58117316329768e-07 9.82722012267827e-06 -1.24635111714659e-05 2.05699003183848e-05 1.0606228564117e-08 6.26187415370214e-06 6.1550894591615e-06 -1.45965138693793e-06 2.26804946223584e-06 1.0606228564117e-08 2.72728487882345e-05 -1.43994154536697e-05 -8.86302163118282e-06 3.84485835473215e-06 -9.29493335815989e-06 6.26187415370214e-06 -1.43994154536697e-05 4.10919810832074e-05 1.08886270839914e-05 2.01661072120981e-06 -2.58117316329768e-07 6.1550894591615e-06 -8.86302163118282e-06 1.08886270839914e-05 4.29166842088931e-05 1297 1297 0 0 0 1306 1370 0 0 0 0 0 0 0 0 0 0 0 1095 0 0 0 0 0 3191 +1313 1315 0.999996642758973 -0.000308047609520408 0.00257285395106842 -0.00114996711163783 0.000313263014833447 0.999997896703062 -0.00202693259250941 -0.00281926659472973 -0.0025722241478528 0.00202773176759359 0.999994635969019 -0.00420853354700768 6.01337592354091e-05 -3.04507536406992e-05 6.61730229800257e-06 2.07987589319848e-06 -1.08972306262642e-06 1.70770619802702e-05 -3.04507536406992e-05 3.87469515615563e-05 -7.3177740757204e-06 2.20344537299289e-06 -3.27642447990145e-06 -6.46678580145097e-07 6.61730229800257e-06 -7.3177740757204e-06 1.80045779813245e-05 1.47251197581867e-06 1.76371746450587e-06 4.49404544866639e-06 2.07987589319848e-06 2.20344537299289e-06 1.47251197581867e-06 2.53168877819765e-05 -7.08816296095481e-06 -5.1076650066449e-06 -1.08972306262642e-06 -3.27642447990145e-06 1.76371746450587e-06 -7.08816296095481e-06 3.29839762076449e-05 5.16107715796802e-06 1.70770619802702e-05 -6.46678580145097e-07 4.49404544866639e-06 -5.1076650066449e-06 5.16107715796802e-06 4.96463077340449e-05 1289 1290 0 0 0 1293 1355 0 0 0 0 0 0 0 0 0 0 0 1099 0 0 0 0 0 3181 +1315 1317 0.999997849753276 -0.000232141331229844 -0.00206072783882719 -0.00201811289902186 0.000235291265458719 0.999998804248672 0.00152844340652991 0.00167869414749455 0.00206037055982203 -0.00152892499126045 0.999996708625347 0.00731992326549959 3.64131424195011e-05 -1.48986999469249e-05 -6.69226310085218e-07 -2.10321788813443e-06 -3.16338212742587e-06 -8.04184251098589e-07 -1.48986999469249e-05 2.76377684704732e-05 -1.81143199287744e-06 -2.53641999209913e-06 -3.46997611066518e-06 9.67798510880162e-06 -6.69226310085218e-07 -1.81143199287744e-06 1.56187914974312e-05 1.82646459877999e-06 -7.92316443827194e-07 -7.47095296601975e-07 -2.10321788813443e-06 -2.53641999209913e-06 1.82646459877999e-06 2.04343563680803e-05 -7.27873558600147e-06 -2.04557715253333e-06 -3.16338212742587e-06 -3.46997611066518e-06 -7.92316443827194e-07 -7.27873558600147e-06 3.18602668535733e-05 -2.7576741045299e-06 -8.04184251098589e-07 9.67798510880162e-06 -7.47095296601975e-07 -2.04557715253333e-06 -2.7576741045299e-06 2.77775302097493e-05 1401 1407 0 0 0 1402 1472 0 0 0 0 0 0 0 0 0 0 0 1006 0 0 6 0 0 3149 +1312 1315 0.999998560350255 -0.000131414333569625 -0.00169175284558636 -0.00234880445040362 0.000135447290900488 0.999997149097489 0.00238399893588565 0.00434595250497436 0.00169143473093253 -0.00238422464710199 0.999995727251563 -0.00305504721789979 5.99081992243782e-05 -3.44623592691694e-05 7.33539960714327e-06 -6.90338729822807e-06 3.67124221855154e-06 1.81182064101882e-06 -3.44623592691694e-05 4.41429119964842e-05 -9.66969505133729e-06 1.15301496776683e-05 -7.34564280632591e-06 1.5465121953042e-06 7.33539960714327e-06 -9.66969505133729e-06 1.71706016838524e-05 6.20503766582095e-07 1.67028798483066e-06 -3.13283542012298e-07 -6.90338729822807e-06 1.15301496776683e-05 6.20503766582095e-07 3.99159391945728e-05 -1.67830011952145e-05 -2.54540901592044e-06 3.67124221855154e-06 -7.34564280632591e-06 1.67028798483066e-06 -1.67830011952145e-05 3.86063984742324e-05 -3.3312997791935e-06 1.81182064101882e-06 1.5465121953042e-06 -3.13283542012298e-07 -2.54540901592044e-06 -3.3312997791935e-06 5.95647574530148e-05 1292 1298 0 0 0 1292 1355 0 0 0 0 0 0 0 0 0 0 0 1104 0 1 1 0 0 3100 +1314 1317 0.999996359398051 0.000222795419788568 0.00268915467112615 0.000237942347375417 -0.000215984775816842 0.99999676949043 -0.00253265854014035 -0.00223608382271304 -0.00268971024850888 0.00253206850326995 0.99999317702066 -0.00324114011472185 2.17420596053808e-05 -9.54798105415537e-06 -1.28067201288665e-06 -1.89043511446365e-06 -1.38671235185647e-06 -2.75932988563485e-06 -9.54798105415537e-06 2.29518081890364e-05 -1.58536526263745e-06 4.36341886172812e-07 -6.67224167583316e-07 8.75857538107046e-06 -1.28067201288665e-06 -1.58536526263745e-06 1.45188588821754e-05 2.97445141577296e-06 -1.87386102895411e-06 -1.17957478636005e-07 -1.89043511446365e-06 4.36341886172812e-07 2.97445141577296e-06 1.98832414586023e-05 -6.23387633081707e-06 9.10208140781891e-07 -1.38671235185647e-06 -6.67224167583316e-07 -1.87386102895411e-06 -6.23387633081707e-06 2.83721978567632e-05 -1.20211616588452e-06 -2.75932988563485e-06 8.75857538107046e-06 -1.17957478636005e-07 9.10208140781891e-07 -1.20211616588452e-06 2.29594044294018e-05 1401 1405 0 0 0 1402 1483 0 0 0 0 0 0 0 0 0 0 0 1005 0 0 0 0 0 3049 +1312 1316 0.999998690443219 0.00103364729155409 -0.00124526508153727 -0.000746840348606996 -0.00103546237169298 0.999998401282938 -0.00145782346152506 0.000356438180428057 0.00124375621543817 0.00145911097755717 0.999998162031127 -0.00555349747914197 5.27268644800583e-05 -2.35695856223081e-05 7.59695226173091e-06 -6.85699780895141e-06 5.81633367653781e-06 1.20357899693178e-06 -2.35695856223081e-05 4.50239823801693e-05 -7.93310091104536e-06 6.83493123500269e-06 -4.95596724078284e-06 1.44293455595109e-06 7.59695226173091e-06 -7.93310091104536e-06 1.80164452748469e-05 9.4974112896248e-07 -8.42928861406207e-07 3.41526659880538e-06 -6.85699780895141e-06 6.83493123500269e-06 9.4974112896248e-07 3.64736394936373e-05 -9.5298813089253e-06 -3.57664984296889e-06 5.81633367653781e-06 -4.95596724078284e-06 -8.42928861406207e-07 -9.5298813089253e-06 3.24674810678264e-05 9.12333821537384e-06 1.20357899693178e-06 1.44293455595109e-06 3.41526659880538e-06 -3.57664984296889e-06 9.12333821537384e-06 4.88483292796894e-05 1300 1301 0 0 0 1305 1369 0 0 0 0 0 0 0 0 0 0 0 1095 0 1 3 0 0 2987 +1316 1318 0.999999990780656 7.30117263217547e-05 -0.000114490064538297 -0.00434808337161894 -7.30014609640237e-05 0.999999993315651 8.9663175246847e-05 -0.00345879658819892 0.000114496610236217 -8.96548164782342e-05 0.99999998942627 -0.000778772668100082 4.55309526930594e-05 -1.76442533870173e-05 1.32160882912146e-06 -8.3498969995059e-07 -3.76624235450894e-06 4.16600817090912e-06 -1.76442533870173e-05 4.70598441710075e-05 -4.70260855286793e-06 2.16126839328708e-06 -6.29644166769886e-06 2.79393628435835e-06 1.32160882912146e-06 -4.70260855286793e-06 1.73898890574387e-05 2.11181467705357e-06 4.31384492058435e-07 5.98462718071807e-07 -8.3498969995059e-07 2.16126839328708e-06 2.11181467705357e-06 2.81731840234229e-05 -8.11842142215607e-07 -5.36049005429722e-06 -3.76624235450894e-06 -6.29644166769886e-06 4.31384492058435e-07 -8.11842142215607e-07 4.10827200877503e-05 -1.70877181342978e-06 4.16600817090912e-06 2.79393628435835e-06 5.98462718071807e-07 -5.36049005429722e-06 -1.70877181342978e-06 4.32742522245872e-05 1410 1412 0 0 0 1419 1485 0 0 0 0 0 0 0 0 0 0 0 1115 0 0 2 0 0 3100 +1314 1318 0.999999911210524 0.00041199507629121 -8.85381351989776e-05 -0.00481679181237523 -0.000411886104479913 0.999999162037863 0.00122730330754194 -0.00182736824913684 8.90437039271958e-05 -0.00122726673094272 0.999999242943508 -0.00188826844528764 3.26760915209837e-05 -1.87946077013747e-05 4.68707202448223e-06 8.59724126623077e-07 1.74673942529729e-06 -2.70540071805604e-06 -1.87946077013747e-05 3.66574300500579e-05 -5.07410499125657e-06 1.7438630673089e-06 -3.75919282853504e-06 -2.08048045710127e-06 4.68707202448223e-06 -5.07410499125657e-06 1.66060874290051e-05 1.55140814731419e-06 4.99008843880807e-07 2.07151289788615e-06 8.59724126623077e-07 1.7438630673089e-06 1.55140814731419e-06 2.52068098944911e-05 -1.32826564816101e-05 -7.73170100424788e-06 1.74673942529729e-06 -3.75919282853504e-06 4.99008843880807e-07 -1.32826564816101e-05 3.39273102257344e-05 6.98834962743851e-06 -2.70540071805604e-06 -2.08048045710127e-06 2.07151289788615e-06 -7.73170100424788e-06 6.98834962743851e-06 4.50638081505147e-05 1412 1412 0 0 0 1419 1471 0 0 0 0 0 0 0 0 0 0 0 1116 0 0 12 0 0 3059 +1315 1318 0.999999830387142 0.000564779190410368 0.000142303032604388 -0.00314793854709359 -0.000564992432700679 0.999998710960111 0.00150295098650528 -0.00573491924216242 -0.000141454013728717 -0.00150303113172204 0.99999886044344 0.00128709833036041 4.28371929643935e-05 -2.19912882144002e-05 5.78669226344986e-06 -3.79722860571503e-06 1.20629572158302e-06 8.05303854837504e-06 -2.19912882144002e-05 3.39166154404929e-05 -2.15814505839725e-06 4.87337771696579e-07 1.10531513156102e-06 2.09107449325239e-06 5.78669226344986e-06 -2.15814505839725e-06 2.29346854119237e-05 9.66305910540071e-07 9.35665379762931e-06 2.74193033811439e-06 -3.79722860571503e-06 4.87337771696579e-07 9.66305910540071e-07 2.50593273523384e-05 2.63875709487668e-06 -5.9626799495517e-06 1.20629572158302e-06 1.10531513156102e-06 9.35665379762931e-06 2.63875709487668e-06 5.37033518537521e-05 -1.26075283753604e-06 8.05303854837504e-06 2.09107449325239e-06 2.74193033811439e-06 -5.9626799495517e-06 -1.26075283753604e-06 4.0606694951944e-05 1400 1400 0 0 0 1419 1485 0 0 0 0 0 0 0 0 0 0 0 1110 0 0 1 0 0 3180 diff --git a/tests/data/exp07/fastlio_odom.txt b/tests/data/exp07/fastlio_odom.txt new file mode 100644 index 000000000..fa15bda0a --- /dev/null +++ b/tests/data/exp07/fastlio_odom.txt @@ -0,0 +1,1319 @@ +1646404202.43857 0.00173955978520877 0.00874473674751593 -0.00114492329432708 -0.00697715206841427 0.00108664207754586 -0.000111546654129695 0.999975062746744 +1646404202.53856 0.00430902766381122 0.00719580667248675 -0.0339541814879588 -0.00829386082892953 0.00332894196740765 -0.000329561381447429 0.999960009904008 +1646404202.63856 0.00714289270750439 0.00625609184624618 -0.0533163577835982 -0.00764222423636712 0.00531394340347903 -0.00048956041546984 0.999956558428828 +1646404202.73855 0.00704085514844097 0.00376554528584585 -0.0481777364065133 -0.00482783776568014 0.00415907694700471 -0.000342024454845211 0.999979638333067 +1646404202.83853 0.00881064738687359 0.00367555443025336 -0.0455415679642199 -0.00373747128563336 0.00424848787189926 -0.000373323870556164 0.999983921014973 +1646404202.93852 0.00887524645485046 0.0033699878076097 -0.0422180014334814 -0.00285155760548683 0.00403911323315071 -0.000365181209000324 0.999987710337581 +1646404203.03853 0.00863944912800732 0.00405266661137414 -0.0374329255179217 -0.00272905932090906 0.0042205148747645 -0.000317361583506607 0.999987319305121 +1646404203.13855 0.00867475264298661 0.00362937476364876 -0.0277017785969015 -0.00245367017964824 0.00416954274695936 -0.000284900266980801 0.999988256554932 +1646404203.23855 0.00754471184087003 0.0035899216715419 -0.0213191943572655 -0.00322845023694372 0.00404293093599228 -0.0003435628289804 0.99998655680119 +1646404203.3385 0.00673570127295639 0.00362341174535676 -0.0159799195754235 -0.00316394313482049 0.00421185290914012 -0.000278578070390068 0.999986085979787 +1646404203.43845 0.00592649985978015 0.004223682409077 -0.0121089038541678 -0.00323502922627113 0.00419799954587962 -0.000313059596182538 0.999985906590394 +1646404203.53839 0.00485095424778475 0.00386953150031803 -0.010805810776334 -0.00334006134316873 0.00421462495746264 -0.000272630391907851 0.999985503194604 +1646404203.63834 0.00454652415720844 0.00472850869645058 -0.0104670726580489 -0.00359625946082087 0.00402241325869703 -0.000283415032328496 0.999985403286163 +1646404203.73831 0.00459334374561999 0.00454738601170173 -0.0101156910879403 -0.00346372182638889 0.00406728787745467 -0.000348985834384061 0.99998566890197 +1646404203.8383 0.00437120532574365 0.00522554244295158 -0.0099850046513088 -0.00362308358133282 0.00410262401033709 -0.000350110545319938 0.999984959468991 +1646404203.93829 0.00385097640662944 0.00552102689549949 -0.00991861958781341 -0.00380202347827797 0.00397833591554232 -0.000371470844396645 0.999984789619435 +1646404204.03829 0.00384712161453678 0.00587455875868151 -0.0120584216702628 -0.00390643188454187 0.00383010443709498 -0.000359361418329818 0.999984970361707 +1646404204.13827 0.00398514468843379 0.00613052952829885 -0.014939881469679 -0.00400844834023591 0.00382518035073525 -0.000323590292101978 0.999984597694639 +1646404204.23826 0.00352569630161517 0.00634985656764529 -0.0162128493788352 -0.00402195978998849 0.00380470034541774 -0.000293074097333918 0.999984630983048 +1646404204.33825 0.00347967237031143 0.00614948294024395 -0.0166645886658665 -0.00386338160434223 0.00375339192453513 -0.00026036494217619 0.999985459165151 +1646404204.43826 0.00393331412516152 0.00659673180326744 -0.0173555941455775 -0.00398860864362674 0.00374119636599415 -0.000252692391716324 0.999985015186425 +1646404204.53825 0.0043876492906972 0.00631523090364574 -0.0189274977319235 -0.00407807018061329 0.00361480184253824 -0.000265378834422721 0.99998511595189 +1646404204.63824 0.00449698109615931 0.0062827389172294 -0.0203163701783404 -0.0038975560791287 0.00354896857580904 -0.000258707151919523 0.999986073377658 +1646404204.73824 0.00451616691935984 0.00605454889752895 -0.0222202667446743 -0.00390571580945377 0.00346067270294554 -0.000256559904724043 0.999986351559597 +1646404204.83825 0.00464418262848535 0.00614919149070015 -0.0233112042687543 -0.00391402877928139 0.00348601154239734 -0.000311104299288666 0.999986215563173 +1646404204.93827 0.00460324708964353 0.00648950684684859 -0.0245491261883706 -0.00391890475891903 0.00358126118652775 -0.000338304553880696 0.999985851051821 +1646404205.03825 0.00496809415425231 0.00720877811323698 -0.0246898860535748 -0.00405254008432407 0.00354861208061948 -0.000387274775721285 0.999985417038376 +1646404205.13822 0.0049978692122031 0.0074346692515723 -0.0247773006388628 -0.0040648890302851 0.00356446922694981 -0.000370284295285619 0.999985316955126 +1646404205.23819 0.00505921289789847 0.00688571625661558 -0.0265966398078843 -0.00414100890597475 0.00356641469518716 -0.000348549048937561 0.999985005510095 +1646404205.33667 0.0056725561230378 0.00726531372227883 -0.0266367838268072 -0.00441467705282389 0.00346856803957041 -0.000436275759526851 0.999984144537171 +1646404205.4381 0.0052390376173667 0.00718924513215707 -0.0266085070902376 -0.00441829232182762 0.00355656562181151 -0.000464148362859626 0.999983806919009 +1646404205.53815 0.00564931155859547 0.00676260163677533 -0.0264828857824443 -0.00438293455544141 0.00355738283671783 -0.000422132854579489 0.999983978229597 +1646404205.63816 0.00575488743851282 0.00693596289355565 -0.027857112462009 -0.00462292306142485 0.00361211287327925 -0.00043944155527076 0.999982693907289 +1646404205.73816 0.00596823054704395 0.00629135410581054 -0.0302050122518113 -0.00482129662335353 0.00358043322076999 -0.000411437951521282 0.999981882993702 +1646404205.83815 0.00571988162885691 0.00574690709338309 -0.0307916165114081 -0.00484575814526947 0.00360858651067232 -0.000373972524766612 0.999981678270128 +1646404205.93812 0.00603806727033063 0.005575774780305 -0.03178717689937 -0.00497357961643802 0.00359143458801968 -0.000322792515030605 0.999981130276161 +1646404206.0381 0.00581981477436755 0.00563085693704532 -0.0325923329841321 -0.00489268867509306 0.00364000908418773 -0.000290751526702941 0.999981363523813 +1646404206.13809 0.00563614636468649 0.00582153052750385 -0.0332910692869093 -0.00503408371525606 0.0036183195959574 -0.000304173232855832 0.999980736436003 +1646404206.23808 0.00510729956137836 0.00596389589054121 -0.0329258785250464 -0.005040878701105 0.0036425350918361 -0.000273141434510251 0.99998062324916 +1646404206.33806 0.00511044565331106 0.00628786393509161 -0.0333329111690209 -0.00496720906425619 0.00360583258116784 -0.000243464207643885 0.999981132587353 +1646404206.43803 0.00503927512995547 0.00618888664580487 -0.0327299008968211 -0.00483310885117381 0.00355204356340622 -0.000278547314367866 0.999981973065888 +1646404206.53802 0.00495361181336498 0.00613686691320421 -0.0331110561353843 -0.00481859835056485 0.00356411475374928 -0.00028721399257312 0.999981997689997 +1646404206.63801 0.00459356908432964 0.0062854568695647 -0.0327773307248732 -0.00483842775140708 0.00359652284914288 -0.000257175043328355 0.999981794084914 +1646404206.73801 0.00474168691753202 0.00674430397563511 -0.0325149799031998 -0.00485116033435226 0.00358818723838544 -0.000306832718087228 0.999981748338154 +1646404206.83803 0.00507118028360407 0.00630557104462932 -0.0323799338984719 -0.0049919614464494 0.00361113168526376 -0.000286065212843208 0.999980978926878 +1646404206.93803 0.00470929484515995 0.00579335865477336 -0.0326227211630934 -0.00490584727772419 0.003543242385378 -0.000314023987633094 0.999981639573855 +1646404207.03802 0.00421466701891284 0.0054828778825222 -0.0330608980277853 -0.00485762251926672 0.00345535754884244 -0.000264343647372532 0.999982196906575 +1646404207.13801 0.00429954376263989 0.00556053663748636 -0.0325012321399197 -0.00485550085559494 0.00341491302023477 -0.000284021591501973 0.999982340750193 +1646404207.23801 0.0047614484117409 0.00546493182554985 -0.0325205060710802 -0.00486548963821229 0.00337790148634982 -0.000232923549836202 0.999982431115038 +1646404207.33801 0.00528421756354134 0.00539487733680213 -0.0323624579149409 -0.00491108207078577 0.00345324786491793 -0.000209692772112059 0.999981956027714 +1646404207.43801 0.00493911448415028 0.00520409033929893 -0.0324331202954424 -0.00488780819301586 0.00340928334719344 -0.000218945194787041 0.999982218932478 +1646404207.538 0.00462896900121086 0.00496683828856504 -0.0328463634858311 -0.00480195407707029 0.00330784759371452 -0.000239402102225382 0.999982970888989 +1646404207.63792 0.00345565559221358 0.00545515923100322 -0.0328493522739009 -0.00508694368891594 -0.00251069140630046 -0.00223472912560368 0.999981412536402 +1646404207.73784 0.00367205319425781 0.00275664853395886 -0.0516689783939771 -0.00382102721570588 -0.0206078488797668 -0.00521796376168539 0.99976671737448 +1646404207.8378 0.00708736048546247 -0.00358416487421734 -0.10978359564074 0.000231673879526709 -0.0159200202927009 -0.0084877335422119 0.99983721558082 +1646404207.93775 0.0190275104773356 -0.016319411892404 -0.196094696562951 0.00229744607071172 -0.0297861729795672 -0.0136952659811176 0.999459826771685 +1646404208.03763 0.0323987156789679 -0.0327167982395817 -0.320037137730919 0.00151711300552106 -0.0339930732815385 -0.0232086637159945 0.999151403574813 +1646404208.13745 0.0551947978550999 -0.047738443642775 -0.469633439225721 0.00264512077316821 -0.0397568351641425 -0.0390976715315089 0.998440668980705 +1646404208.23739 0.0784875567604614 -0.0570290836123285 -0.633021513638137 0.00684918515518393 -0.0281466759419209 -0.0576317828005844 0.997917547148738 +1646404208.33761 0.106067369290907 -0.0569171358255992 -0.778982308344346 0.0148781526516932 -0.00878748531703055 -0.0720205253301015 0.997253460563887 +1646404208.43198 0.145618029964471 -0.0541776296935089 -0.881279752817961 0.0188530519354207 0.00822150064956488 -0.0818345196179172 0.996433681063968 +1646404208.53182 0.194573023271752 -0.0533969661567985 -0.954729207151075 0.0206117982636021 0.0290580396801411 -0.0896421911475165 0.99533665745242 +1646404208.63199 0.255701377066229 -0.0558890954750614 -0.998169402465581 0.0244443808142151 0.0326191656010034 -0.0951350275788269 0.994629473125382 +1646404208.73174 0.323522711440976 -0.0634603458475694 -1.01820310657588 0.027261579835412 0.0180833471486726 -0.0910810491042432 0.995306003857528 +1646404208.83153 0.392028416401297 -0.0764191003917437 -1.0369124135778 0.0147667062854593 0.0227570810031412 -0.0783982618727882 0.996552944998414 +1646404208.93108 0.463335256863667 -0.0876084113240662 -1.05318199774584 0.00837301613550243 0.0268911493430398 -0.0663652234071147 0.997397822240413 +1646404209.03061 0.543012785285443 -0.0963534435669879 -1.063962723983 0.0063692688981997 0.0209963192869992 -0.0571232627818235 0.9981260039891 +1646404209.12998 0.636562165154798 -0.102655660812896 -1.05963017930292 0.00387841136363834 -0.00863176413666377 -0.0448869026122831 0.998947254136598 +1646404209.2298 0.733066263267464 -0.108170787365818 -1.04267095201895 0.00231039019119471 -0.0172856782528169 -0.0359192969321608 0.999202517777249 +1646404209.32944 0.836141024930481 -0.115330697542862 -1.02490465584348 -0.00550885497532137 -0.000287788046606248 -0.0272121930291874 0.999614458801709 +1646404209.42867 0.950439021222492 -0.128376312646942 -1.0204912985907 -0.0115203529064954 0.00404266922645791 -0.0342334826801139 0.999339285206989 +1646404209.52804 1.07321066802204 -0.143235014701162 -1.03138108014416 -0.00153425671668249 0.00251229648216425 -0.0424857826658282 0.999092734781899 +1646404209.62824 1.20263892881305 -0.1585543389162 -1.04639005951356 0.00704971928147089 -0.00390154946593645 -0.0417544193902994 0.999095414778381 +1646404209.72866 1.33171443843391 -0.177028845120192 -1.05584505050552 0.00455701103630052 -0.00733529644526645 -0.0457767380818779 0.998914369366587 +1646404209.82903 1.4667912147778 -0.197371763639334 -1.04954536793106 0.00387426092989024 0.00844328164192706 -0.0549998471274675 0.998443147061116 +1646404209.9295 1.61028858628784 -0.21716219080602 -1.02949283786951 0.00183178351331822 0.00960582443851489 -0.0562241787105847 0.998370279222255 +1646404210.03033 1.75660715671768 -0.231022652597988 -1.02224548737594 0.00536319323305898 0.00238298469340937 -0.0542238441626698 0.998511558404059 +1646404210.13097 1.89937013943355 -0.240858106019399 -1.03394071668249 -0.00331277490220286 -0.00748678279506727 -0.0469887789213157 0.998861866456667 +1646404210.23126 2.03879544113712 -0.24463135439902 -1.05008221214386 -0.00805873387799704 -0.0074489293122931 -0.0412744869724497 0.999087577235114 +1646404210.33108 2.17822424307403 -0.246770592527997 -1.05260646011381 -0.00442806984177951 0.0023858049605217 -0.0380855964875589 0.999261821282259 +1646404210.43078 2.32272590760525 -0.258052792739716 -1.03955814612254 -0.0142721651905946 0.0136623892910677 -0.0463319319865102 0.998730692678468 +1646404210.52962 2.46943060327794 -0.272042601396238 -1.03349491071529 -0.0085139327776575 0.0202006405810327 -0.0662651414059268 0.997561215215993 +1646404210.62943 2.61508754816551 -0.285464173670919 -1.04737590011546 0.00886081478663745 0.0166252926565951 -0.0784894262817541 0.99673692395102 +1646404210.72987 2.75527715764428 -0.306799185324179 -1.06647215867889 0.0152829438797316 0.00735672442283669 -0.0937035458100145 0.995455652319455 +1646404210.83074 2.89284811691149 -0.330597372920392 -1.07067994905195 0.00669960423624569 0.0133817087526357 -0.103919106132241 0.994473159293201 +1646404210.93138 3.03710499990934 -0.350267248672664 -1.05474894283542 0.00639789415312724 0.0252518956736658 -0.101899190643045 0.994453600557396 +1646404211.03185 3.18491820882645 -0.364990232813699 -1.03194764004928 0.00107227057013703 0.0142402204249086 -0.0881678269768452 0.996003263370277 +1646404211.13185 3.32737895797595 -0.372832431447502 -1.02638556608904 -0.00428355302749872 -0.00296858891172869 -0.0697941878126824 0.997547798353988 +1646404211.23113 3.46660293616988 -0.370346875280521 -1.03608085024483 -0.00217402725261526 -0.0177103452413749 -0.049580498818385 0.998610730672289 +1646404211.3306 3.60602169259551 -0.363072575137609 -1.04284756148224 0.00153131161013276 -0.0234437456514211 -0.0238903739333431 0.999438490307382 +1646404211.42952 3.75069882779793 -0.3610334652392 -1.03159164939278 -0.000904596797597006 -0.0182982911244471 -0.0116659745413559 0.999764101818298 +1646404211.52825 3.9028832491794 -0.366025982142174 -1.00818857233169 -0.00590923873323898 -0.0224873626078785 -0.0154404018733461 0.999610420819289 +1646404211.62688 4.04912512746737 -0.376548626225091 -0.997662187309364 -0.00225232560521325 -0.0325063514817545 -0.0278520734403012 0.999080840646931 +1646404211.72657 4.19048665314363 -0.38943473750979 -1.00121094257053 0.0142582483094103 -0.0485452669362382 -0.0432055409040464 0.997784215473674 +1646404211.82722 4.33140678634579 -0.409850172315925 -1.00286801965738 0.0105957557336255 -0.0783828341390595 -0.066099457136443 0.994673173981795 +1646404211.92868 4.47444336373192 -0.425668837983068 -0.993909479855292 -0.00126848972418931 -0.0785142456906523 -0.0723834192274793 0.994280918442255 +1646404212.0297 4.62281278024577 -0.432720219357073 -0.966902373040893 -0.0136331453837361 -0.0764430677424933 -0.0633622159633206 0.994965237749173 +1646404212.1308 4.78102811634373 -0.428275466045115 -0.956134057932259 -0.0175636192509946 -0.088915449102204 -0.0474970289415015 0.994751021327185 +1646404212.23122 4.93353363518206 -0.421756597340266 -0.963959125332232 -0.0229178650230491 -0.103596384291426 -0.0294176680999821 0.993920098110546 +1646404212.3312 5.08164221134927 -0.414242606985703 -0.974350709119452 -0.0234232508665086 -0.129157335707207 -0.0102089922343347 0.991294865531648 +1646404212.4304 5.21778034943268 -0.407463320886006 -0.963068224316113 -0.0174149337017738 -0.139819235498803 0.003033854670158 0.99001924082036 +1646404212.52928 5.36822304504605 -0.407550151527537 -0.933101439372564 -0.0137171857747267 -0.150995722926134 0.00114005069819918 0.988438582187497 +1646404212.62781 5.51599112452287 -0.420322480502573 -0.917953461011998 -0.0109466291180204 -0.153601101726554 -0.0228671610495759 0.987807656279735 +1646404212.72753 5.65985019905267 -0.435743002491208 -0.924020991396599 0.00692004979196888 -0.162929229299482 -0.0482947410217761 0.98543076729945 +1646404212.82809 5.79687245444131 -0.4574021392616 -0.944579466119398 0.0041517289992445 -0.166761130812376 -0.0697488000363503 0.983518476333807 +1646404212.9294 5.93320214649052 -0.481002497247444 -0.960430662827016 -0.00794043072189319 -0.138233907164809 -0.0908840961332203 0.986188834625468 +1646404213.03076 6.08497512093163 -0.500486100706914 -0.950530559671719 -0.0174235585940433 -0.11555419983649 -0.0954322388139135 0.988552646195953 +1646404213.13176 6.24123834998828 -0.509690058742128 -0.939513730103318 -0.0192302057092527 -0.112365577864599 -0.0836411491512719 0.989953703093321 +1646404213.23208 6.3916571388769 -0.511020552880862 -0.944390549251922 -0.0175441992876129 -0.125332044744478 -0.060513118465519 0.990112237135312 +1646404213.33142 6.53491546348766 -0.503517765999558 -0.96788234110293 -0.00785322061342533 -0.127649880038993 -0.0369267651293855 0.99110052419979 +1646404213.43029 6.67434594423863 -0.492289808103063 -0.985288555119566 -0.00013860342569283 -0.11828185630861 -0.0152798917405173 0.992862482001243 +1646404213.52886 6.81926524260965 -0.486631197645663 -0.978575212162757 -0.00918105606067391 -0.104336142574415 -0.00186638863293538 0.994497960860536 +1646404213.62714 6.96492767443557 -0.489002998352005 -0.967193846842637 -0.00990432672592614 -0.0926539263077308 -0.0156930032663085 0.995525431066602 +1646404213.72571 7.10683316499474 -0.497687296278854 -0.975871480180354 0.00507007977579669 -0.0781157096149333 -0.0370781699912052 0.996241657185905 +1646404213.82602 7.24839164392527 -0.518716977623898 -0.997443911900231 0.0110129565468572 -0.0901094850035827 -0.0540602352223172 0.994402577665699 +1646404213.92702 7.38157777623488 -0.549745955684922 -1.01353916547878 -0.000775556290024113 -0.0861672085738535 -0.0680027472210784 0.993956858746601 +1646404214.02812 7.51574993612897 -0.57870712114462 -1.00557883127346 -0.00756722675718341 -0.0706982442139156 -0.0731102895100221 0.994786098069344 +1646404214.12901 7.65437982940804 -0.601722423144363 -0.983252910778141 -0.00918674423689872 -0.0657750420252533 -0.0694280102050566 0.995373798618319 +1646404214.23013 7.79074308175763 -0.613558292080332 -0.977958802630486 -0.0122452940609589 -0.0680156837075511 -0.0532611603808484 0.99618631206117 +1646404214.33056 7.92707108841628 -0.618248422065541 -0.989696103110287 -0.0191818734839659 -0.0851844176829853 -0.0308119283396362 0.995703919740021 +1646404214.43056 8.05425779245764 -0.613117328172239 -1.00537426305658 -0.00873104925498367 -0.0945648729167174 -0.00783706386828633 0.995449563774613 +1646404214.53 8.17958329522158 -0.610662045934146 -1.00509837756412 -0.00352879852913698 -0.0680261574627283 0.00632792998403334 0.997657229104218 +1646404214.62937 8.31980230265768 -0.615338010985587 -0.98671921178244 -0.0095534161294831 -0.0506606758239199 0.0080696402756858 0.998637626504796 +1646404214.7279 8.46228796845949 -0.622856265886945 -0.972792571715095 -0.00427872075058822 -0.0468800335361666 -0.00791640010772131 0.998859992998875 +1646404214.82749 8.60642531657185 -0.635183226690043 -0.979572382282356 0.0118152298800166 -0.0563199501780945 -0.0277980846009959 0.997955775596959 +1646404214.92811 8.74340756687219 -0.657652707182101 -1.00195865930423 0.00818365600345037 -0.0572486610822481 -0.0498895424896666 0.997079060119544 +1646404215.02949 8.87799967358772 -0.674778081101031 -1.0168674653783 0.00408536753627699 -0.0531560949184145 -0.0657084033846731 0.996413641551414 +1646404215.13071 9.01953790914691 -0.68559094086177 -1.00944402869576 -0.0011686183670635 -0.0425370408368541 -0.0678990130818152 0.996784308920674 +1646404215.23152 9.16157147685099 -0.688197099807535 -0.993467430642708 -0.0105205782520812 -0.0303495077193819 -0.0591484642236917 0.997732270699112 +1646404215.33183 9.30063929641761 -0.682433307898079 -0.988242665695864 -0.0186317727030993 -0.041187898668028 -0.0439804440642323 0.998009085424156 +1646404215.43121 9.43370191741548 -0.667415966776748 -0.99701238753356 -0.0231770326092303 -0.0593577610900025 -0.017757489160829 0.997809677712393 +1646404215.53063 9.56158522691953 -0.646108911380174 -1.01218177652842 -0.0132988029567087 -0.0631261345622389 0.0106068587774683 0.997860575191754 +1646404215.62916 9.69565421751449 -0.633425959887153 -1.01439805866648 -0.0123806957277575 -0.0509549957485001 0.0256743034988739 0.99829411343622 +1646404215.72793 9.837983115676 -0.631310557078496 -1.00261513342154 -0.0218348850951122 -0.0315265737174484 0.023353940403384 0.998991444613091 +1646404215.82615 9.98046154159277 -0.639282054270433 -0.994090531054461 -0.0166681226832586 -0.0291061647248403 0.00283119634947967 0.99943333403907 +1646404215.92545 10.1233938575743 -0.655673611728229 -0.998074488612422 -0.000856227375049156 -0.0410789639615202 -0.0184486707647415 0.998985201162429 +1646404216.0258 10.2564588362934 -0.682156003524088 -1.00876034482634 -0.00180368304308656 -0.0522110364940166 -0.0415819470913987 0.997768357922711 +1646404216.12712 10.3892117740618 -0.711251634606569 -1.00706509170087 -0.00971776629711377 -0.0482504971081192 -0.0624171403007071 0.996835771400531 +1646404216.22848 10.5346221081672 -0.730838649549426 -0.982255897343186 -0.0077906155029076 -0.0420863212742318 -0.0641149404572914 0.997024233547932 +1646404216.32966 10.6891342306994 -0.736194145619097 -0.949040649485746 -0.00269982895916806 -0.0616120379708239 -0.0495059774116505 0.996868008264477 +1646404216.43025 10.8371949663137 -0.738996155306056 -0.934648388462321 -0.0153116358985025 -0.100840320671171 -0.0382823126610524 0.994047910349578 +1646404216.53078 10.9749156963592 -0.729684606237075 -0.939526131086653 -0.015645688318011 -0.123875473233535 -0.0209275157550403 0.991953687755905 +1646404216.63046 11.1087791991409 -0.710090931465974 -0.942833396946566 -0.000963807034050325 -0.132005394048989 0.00776843544830439 0.991218088227132 +1646404216.73 11.2465424001346 -0.693293166233183 -0.931443744858347 -0.00233434624424598 -0.112552403777436 0.0251433967428608 0.993324879801043 +1646404216.82838 11.3951128084477 -0.685360848757739 -0.910819322472267 -0.0111589045277947 -0.108862324745043 0.0204601852021938 0.993783605178878 +1646404216.92705 11.5424289247164 -0.683995452891046 -0.909604327096078 0.00276156175923737 -0.118090327119074 0.00270974167922396 0.99299532008846 +1646404217.02705 11.6860283271183 -0.69821683659772 -0.92689407069086 0.0100016559746072 -0.129111439282176 -0.0219423521949383 0.991336843007661 +1646404217.12798 11.8246826434931 -0.72696469568404 -0.93885145299481 -0.00549173453562606 -0.128725603846059 -0.0552139554206567 0.990126748902915 +1646404217.22907 11.9674993018599 -0.750984917540385 -0.932217357857673 -0.0170020089520355 -0.102703891683116 -0.0730000007005899 0.991883986271804 +1646404217.33043 12.1223550589409 -0.759676501055285 -0.915703396714208 -0.0176919736786749 -0.0850066774473147 -0.0618384391442223 0.994302200691982 +1646404217.43136 12.2831017593208 -0.753994632342316 -0.919718945559025 -0.0123473840635109 -0.0759395984753955 -0.0337386100045695 0.996464964604946 +1646404217.53118 12.4288955014633 -0.742036687313795 -0.949192949239273 -0.0149138369080019 -0.0670335564284875 -0.0120531125465524 0.9975664400225 +1646404217.6299 12.5669677401197 -0.728428659895282 -0.979949725963176 -0.0105248084038309 -0.0431726452158858 -0.00281209217149837 0.999008229821326 +1646404217.72898 12.7144817150456 -0.720070157499479 -0.98284999269132 -0.0112432181316769 -0.0300204419563858 0.00190456857335225 0.999484234857824 +1646404217.8279 12.8708043245515 -0.716806633267381 -0.961943457972847 -0.00704719150814356 -0.0328922409412907 -0.00144764895262859 0.999433010206392 +1646404217.92593 13.0217406056264 -0.722255110444453 -0.952614259667672 0.00210757569974864 -0.031462529174767 -0.0214890676304847 0.999271678451342 +1646404218.02562 13.1635631963917 -0.736159561998319 -0.964201868178587 0.00579170811395672 -0.0447747265609226 -0.0431263582704667 0.998048995390927 +1646404218.12693 13.3049042845702 -0.754698276230088 -0.980566034913882 0.00632503742798155 -0.059607073821312 -0.0642146310916226 0.996134263945256 +1646404218.22799 13.4441207100725 -0.768226816887259 -0.974825199780556 0.00336379469030615 -0.0527376516357842 -0.0635411239332154 0.996579124081235 +1646404218.32868 13.5907832964301 -0.775511146348175 -0.948335046398193 0.0016880220686638 -0.0431403736417701 -0.0463683927641943 0.997990997402283 +1646404218.42922 13.7415766092097 -0.779107429847013 -0.9365721107933 -0.00291147868791849 -0.0409862098714566 -0.0314576069869945 0.998660138813435 +1646404218.52925 13.886951638005 -0.788162466211594 -0.952709340341778 -0.0264006597482319 -0.0429381735143659 -0.027976703363041 0.998336928340848 +1646404218.62934 14.0284913522697 -0.790085069062994 -0.981262058174492 -0.0334896413565468 -0.0510503240871944 -0.0208743362390912 0.997916113918888 +1646404218.72927 14.1656470238088 -0.784695123590577 -0.998040085738721 -0.0186408829154344 -0.0382780960311619 -0.00332793398295096 0.999087698705056 +1646404218.82907 14.3112047603333 -0.781261079472631 -0.987446863757974 -0.0082168153031294 -0.0235687577052525 0.010913765927954 0.999628874792927 +1646404218.928 14.4591474462575 -0.79001987486179 -0.972842611110905 -0.0129184707380865 -0.0273076493031366 -0.00829148188169385 0.999509207927335 +1646404219.02712 14.600837004084 -0.80732428709256 -0.969776068899399 -0.0147615619930382 -0.0264640536574143 -0.0433140301588603 0.998601845052841 +1646404219.12767 14.7466689815252 -0.825435451425817 -0.97648052540958 -0.00941976968047833 -0.0460334664016342 -0.0542555732418689 0.997420934551913 +1646404219.22884 14.8865065474437 -0.840597606218839 -0.981216923062959 -0.00405167116997452 -0.0520520160561055 -0.0488621691575185 0.997440053341776 +1646404219.32986 15.0258691827677 -0.857549927387651 -0.970425978292611 -0.00536024318363358 -0.0393366284195979 -0.0481971786588907 0.998048560655699 +1646404219.43015 15.1728496973267 -0.879003253468571 -0.951998743579437 -0.0119937995726388 -0.029614654919258 -0.0503664350690188 0.998219586666311 +1646404219.53092 15.3195167977733 -0.899736618156483 -0.94343734851559 -0.0136353936815849 -0.0340669375603701 -0.0472086370990228 0.998210831632105 +1646404219.63111 15.4657064552396 -0.916556269317451 -0.953928821622323 -0.0202259406520153 -0.0492241856138814 -0.030425605600086 0.998119318217646 +1646404219.73096 15.6062995922261 -0.92237179559057 -0.968855577027575 -0.010783542508076 -0.0598528953789807 -0.0136259757634341 0.998055949789501 +1646404219.82984 15.7488675449589 -0.926846896052954 -0.971085066431805 -0.00599585088204455 -0.0509379973379938 -0.000727481538672421 0.998683553969927 +1646404219.92926 15.8984874487679 -0.932529251841333 -0.951785566474973 -0.00908346095820708 -0.0427424310690933 0.00423590118724805 0.999035851441007 +1646404220.02759 16.0496518549543 -0.940221367203402 -0.937874123206212 -0.00670820791413801 -0.0398029035782899 -0.00544367471166273 0.999170203328218 +1646404220.12666 16.1983552085053 -0.948376522841352 -0.939521115809251 0.00347612198495518 -0.0435519083085214 -0.0209029835897605 0.998826417920391 +1646404220.22703 16.3507872545144 -0.959879618385429 -0.953114697593922 0.000755933946894261 -0.0576120768536606 -0.0324414154036196 0.997811521145696 +1646404220.32807 16.5020600638412 -0.969392988537255 -0.955993795229499 -0.00687929492483447 -0.058744269592662 -0.0343286610866953 0.997658924241826 +1646404220.42891 16.6574566010199 -0.971929982715057 -0.938439801923312 -0.00550822008694777 -0.0481831890406419 -0.0252242236799926 0.998504771318139 +1646404220.5295 16.8182749248214 -0.971574750216228 -0.920176343843827 -0.00668887179236167 -0.0422058550387626 -0.0135020192627659 0.998995305429621 +1646404220.62993 16.9768544664629 -0.9693126437253 -0.923511440874142 -0.00996851677282462 -0.0459060822554885 0.00198664345981515 0.998894045198522 +1646404220.72985 17.1290059354972 -0.962388626458157 -0.944923271514388 -0.0147114101840457 -0.0566000228075344 0.0201137841812805 0.998085891852245 +1646404220.82942 17.2748776488965 -0.949214065723634 -0.96523145199071 -0.00503997311551039 -0.0489268204470517 0.0368134487995765 0.998110983257583 +1646404220.92875 17.4277869649639 -0.941757182719734 -0.963663381672667 -0.00334637030796143 -0.0323739481893241 0.0370827180089255 0.998782058964551 +1646404221.02822 17.5888318759398 -0.94408931399759 -0.944223838310526 -0.0146885184313693 -0.0225208917485347 0.0183303543181389 0.999470387241019 +1646404221.12687 17.7456343541157 -0.950865717902794 -0.939996390297812 -0.0107487453835648 -0.016872487103154 -0.0115900752158924 0.999732691177057 +1646404221.22745 17.9010492842516 -0.961317050909313 -0.959077370145901 0.000778991318193718 -0.0298872830059321 -0.0348423668605492 0.99894552051581 +1646404221.32874 18.0499057586716 -0.978032354684647 -0.975512373806 -0.00224903196801552 -0.0358848159500862 -0.0580510820993437 0.997665922895299 +1646404221.43046 18.1964321563961 -0.988461540464266 -0.967134906527786 -0.00609577206808136 -0.0313415909604273 -0.0710968903124843 0.99695826313184 +1646404221.53134 18.3492912848223 -0.996143746655243 -0.943981734030344 -0.0181332832638077 -0.0261922771653852 -0.0722340160471911 0.996878826929661 +1646404221.63192 18.5055884940348 -0.999001668706507 -0.934985184844594 -0.0292559660951701 -0.0215664778808239 -0.0614008603880564 0.997451206738082 +1646404221.7321 18.666021189412 -0.994266139922416 -0.946707682040368 -0.0322083465450504 -0.0253545852776514 -0.0373432549566732 0.998461440781499 +1646404221.83152 18.8207852098588 -0.986544731567714 -0.968208857438477 -0.0237577730035766 -0.0350754101215023 -0.019204831363984 0.998917643391583 +1646404221.9301 18.9699166897209 -0.98310515520755 -0.983030767947624 -0.0199272771252851 -0.0207654303081278 -0.00643196756741973 0.999565070580047 +1646404222.02883 19.1209254666496 -0.981862664545375 -0.979207026116192 -0.0159506417714645 0.00661582032058793 -0.00328841322815831 0.999845485206089 +1646404222.12745 19.2737457509842 -0.983924827390495 -0.968684113132338 -0.0103306328235437 0.00744908631318251 -0.00850777557484722 0.999882696566614 +1646404222.22702 19.41964723444 -0.991347591233479 -0.971447003338053 -0.00641976406636916 0.0101382556849109 -0.0205336503000325 0.999717145799925 +1646404222.32712 19.5708021126645 -1.00687106008634 -0.980842180065285 -0.00748502424976647 -0.0047171240636091 -0.0301833343727921 0.999505222336873 +1646404222.42796 19.7185255826934 -1.02561155338027 -0.984372988936997 -0.0120921651728085 -0.010145219582251 -0.0398290465581986 0.9990818290367 +1646404222.5285 19.8588958289698 -1.04046787292634 -0.972499217768039 -0.00857337659653895 0.00390309772951143 -0.041984661356947 0.999073846746366 +1646404222.62945 20.0052698087686 -1.05073091968846 -0.9553433985512 -0.0040487986652933 -0.00747941698701502 -0.0307253260337221 0.999491680751278 +1646404222.73007 20.1479514442202 -1.05391449089324 -0.954546770866184 -0.000993180764405559 -0.0104483001654858 -0.0118715478555233 0.999874448601987 +1646404222.8301 20.2932361875607 -1.05608388896315 -0.964465023876507 -0.00986181340019097 -0.0267255942106112 0.00519478244782126 0.999580662821096 +1646404222.92959 20.4339386525702 -1.05622601284648 -0.974067576873809 -0.0144608708778232 -0.0347209031540473 0.0167138011183146 0.999152636462412 +1646404223.02972 20.5761741063268 -1.055074065771 -0.970018505438747 -0.0118187976582184 -0.0159540684079562 0.020479900563998 0.999593095912546 +1646404223.12893 20.7253399361457 -1.05566990280279 -0.950448728571676 -0.00990606837634156 -0.0105999050077539 0.0176427264979364 0.999739088975148 +1646404223.22771 20.8643209783938 -1.05831405693161 -0.944029634879089 -0.00249081073776104 -0.00272350128153994 0.00365334181001574 0.999986515657209 +1646404223.32764 21.0019610672187 -1.06950242989639 -0.951324128782563 0.00113807349626504 -0.00903997774572745 -0.024689169732827 0.9996536542668 +1646404223.42885 21.1440892890626 -1.08849456980859 -0.956130201325442 -0.00457753187864049 -0.0326298690084049 -0.0475209458728094 0.998326648724624 +1646404223.52988 21.2892422720394 -1.10305091409822 -0.945864447910207 -0.00458682299766278 -0.0406943504556473 -0.0533327830954335 0.997736711333739 +1646404223.63063 21.4344884950873 -1.11266182247694 -0.923531978772047 -0.00250981595624227 -0.0282801492690821 -0.0483691308499895 0.99842594175131 +1646404223.73099 21.5823757394065 -1.12026134357444 -0.908614874326345 -0.00578970289059456 -0.0243973555311261 -0.0410834591312376 0.998841027275776 +1646404223.83092 21.7301178286447 -1.12366745599096 -0.916608068104854 -0.0122318851963041 -0.0286873408972928 -0.028447693327693 0.999108675871203 +1646404223.93031 21.8735701679097 -1.12237582385737 -0.940033896046449 -0.0180191164039435 -0.0361104589616371 -0.0158097080751323 0.99906025810667 +1646404224.02968 22.0145784053842 -1.11825157612345 -0.954116850705979 -0.0153619013091937 -0.0281319644457337 -0.0111473591673374 0.999424004588729 +1646404224.12876 22.1621150730424 -1.11380576336749 -0.941284111137173 -0.0134697411714661 -0.018875642037322 -0.0113366895291461 0.999666822336802 +1646404224.22798 22.3099659138087 -1.11347068800603 -0.926787433971801 -0.0134785872844929 -0.017384329168349 -0.0218477154542735 0.999519279510704 +1646404224.3267 22.4483632372376 -1.11173719040194 -0.93124693581308 -0.00446223177377286 -0.0119917498690601 -0.0350786638522006 0.999302643729618 +1646404224.4275 22.5884592806653 -1.11313914267182 -0.945874671431716 0.00127439866954004 -0.028952534542255 -0.0442705208490585 0.99859914261697 +1646404224.52862 22.7215960215806 -1.11996358840569 -0.955233283149172 -0.0107872183884457 -0.0348091914236306 -0.0517452483937955 0.997995183044749 +1646404224.62864 22.8548119360361 -1.12479025424432 -0.94421917900402 -0.0115195279535139 -0.0176548244543276 -0.0505626151508939 0.99849838737892 +1646404224.72976 22.9986337800874 -1.1305341631741 -0.92128510811654 -0.0134112684001661 -0.0186762410161979 -0.0404066932055453 0.998918732953578 +1646404224.82997 23.1398497652084 -1.13673545015974 -0.914860721833952 -0.0116060542831872 -0.0160205131243934 -0.0325371493488377 0.99927472527601 +1646404224.93017 23.2853835961633 -1.13910730277174 -0.92647052241665 -0.00967222448420033 -0.0257630949534668 -0.0116219906965774 0.999553720589435 +1646404225.03001 23.4283355553855 -1.13175946857624 -0.944715331387279 -0.000492154667565708 -0.0339789223984501 0.0148357413503716 0.999312309238206 +1646404225.12931 23.5699431171496 -1.12030220435334 -0.947763980128514 0.000833793903387593 -0.0297245490297123 0.0422802260757678 0.998663175678205 +1646404225.22859 23.7074240339867 -1.10866563923356 -0.934372045229634 -0.00195221741159761 -0.0114895394097003 0.0596774374444366 0.998149679552814 +1646404225.32776 23.8489186609774 -1.09675442929757 -0.919992597297464 -0.00535617156728352 -0.0165159817816455 0.0700939936373956 0.997389274971352 +1646404225.42678 23.9873822186776 -1.07968753956913 -0.919488666462922 0.00785226556716204 -0.0296407191682875 0.0916798210712619 0.995316321628948 +1646404225.52707 24.1165860002764 -1.0695978847121 -0.928413877575149 0.00747247157403974 -0.0397611343099406 0.115933231530279 0.992432718220181 +1646404225.62758 24.2457823534344 -1.06304461111724 -0.932613244261952 -0.000678618399482393 -0.037501556695636 0.136414348583862 0.989941563034355 +1646404225.72778 24.3790384852621 -1.0535905388842 -0.919962912064909 0.00232287706275728 -0.0300092905104656 0.167586028223108 0.985397873891355 +1646404225.82815 24.5065795524173 -1.04441898595587 -0.901182476155473 0.00834657419653765 -0.0236890651797669 0.204121478452574 0.978623311046908 +1646404225.92861 24.6306887915047 -1.03596747015015 -0.897787665929008 0.0113463386244523 -0.0276160190368905 0.250514861671089 0.967652272344915 +1646404226.02565 24.7394247799432 -1.02476595488321 -0.908037023757055 0.00496887718567332 -0.0320303564994657 0.316668568307565 0.94798227007052 +1646404226.12542 24.8353803779411 -1.00109233163878 -0.915561792144621 0.0196275642837907 -0.0579618876226605 0.408441930531363 0.910730677910493 +1646404226.22324 24.9221419251673 -0.977354365127682 -0.909067774056716 0.0389683654766528 -0.0549592863926306 0.479713175350707 0.874834963136603 +1646404226.32057 25.0148469948571 -0.960254855971967 -0.890447825851941 0.0290063458807083 -0.03570888984055 0.508747731886667 0.859685554365761 +1646404226.41835 25.1142004862237 -0.945283728602754 -0.877679705102963 0.0270724101997426 -0.0329563677881757 0.525284280521609 0.849857274526182 +1646404226.51764 25.2090014500695 -0.934773410644949 -0.879049763317428 0.0421945682016284 -0.0435462917688957 0.558701136304984 0.827149550673254 +1646404226.61727 25.2981638963557 -0.934351086512685 -0.889246384188035 0.0495143334288552 -0.051347747818607 0.581249432918529 0.810592891845796 +1646404226.71729 25.3926996515648 -0.942677765120444 -0.895234900163865 0.0363036903777098 -0.0482671756519701 0.597609456913362 0.79950938632842 +1646404226.81792 25.4933902216172 -0.95412592951836 -0.887540153795717 0.0290897135898449 -0.0391433273352478 0.606897818309418 0.793282185996663 +1646404226.9192 25.6018999201522 -0.973646059802442 -0.877057311170523 0.0309024662713435 -0.0345416074727628 0.624314632324349 0.779796867650317 +1646404227.0202 25.718843629209 -0.994048526426199 -0.877975839589077 0.0387484198165897 -0.0348584608510534 0.64211707283972 0.76483273494049 +1646404227.12049 25.8322346148596 -1.01327463334916 -0.890426891283739 0.0383689852162468 -0.0333889815482253 0.648439440242552 0.759565197479821 +1646404227.22039 25.9434628731771 -1.02537901264924 -0.904513193067499 0.0443404035485469 -0.0433358915091649 0.639669456385583 0.766145492506233 +1646404227.32057 26.0551517055308 -1.03306925257097 -0.910246041698962 0.0332594527821654 -0.0371438073425083 0.633822165828132 0.771870201835554 +1646404227.42092 26.1664246482448 -1.03176302821247 -0.898877642088717 0.0315369391606271 -0.0250214935063914 0.625755014715561 0.77898010750558 +1646404227.52119 26.2866841316256 -1.02343380982041 -0.880767137382289 0.02916244121435 -0.0316795193997956 0.611742321877542 0.78988435336882 +1646404227.62188 26.4052728427143 -1.01835565064227 -0.871283790498539 0.0403657197885434 -0.0394085049780743 0.600407377561355 0.797702049245976 +1646404227.72256 26.521619870721 -1.01549592216197 -0.87388423953657 0.0536865814078829 -0.048708170321747 0.597902962126219 0.798283980173298 +1646404227.82245 26.6372629993014 -1.01578499536862 -0.883517840527105 0.0508434190179645 -0.0621215658284881 0.587175173027426 0.805469536346211 +1646404227.92254 26.7510720955092 -1.01929708934135 -0.892048321675813 0.0363748677368754 -0.0532413013312076 0.578454451039035 0.81316214920691 +1646404228.02284 26.8713189154762 -1.02465313711025 -0.886323507060237 0.0230639266397304 -0.0387807411923481 0.577199480778656 0.815355670115421 +1646404228.12294 26.9986097898774 -1.03105318985587 -0.872888229214631 0.0208789239267861 -0.040140521345168 0.578759735213821 0.814241965251739 +1646404228.22313 27.1212203331011 -1.04437043315368 -0.876871811656909 0.0265297789430345 -0.0359775356044875 0.584625077763556 0.810071173546501 +1646404228.32254 27.2371354987278 -1.05617097522969 -0.894948505740086 0.0293592486206712 -0.0259961362234544 0.594557756983466 0.803096077087081 +1646404228.42177 27.3511022438357 -1.05833152615225 -0.909604630217921 0.0358031790732703 -0.0316754010571314 0.592619090087683 0.804063066804931 +1646404228.52129 27.4613877837594 -1.05770775611459 -0.914265817181393 0.030816479965346 -0.0227888514147078 0.593539966078713 0.80389136174051 +1646404228.62076 27.5743257672079 -1.05157441118749 -0.898805262842181 0.0278429604389718 -0.0143501650068939 0.590952251659554 0.806098181722773 +1646404228.72063 27.6938448190078 -1.04452642345187 -0.873721721280528 0.0301550706196153 -0.0230674979523351 0.578036856140985 0.815126956490079 +1646404228.82087 27.8121290503591 -1.04555847034651 -0.863561077555549 0.0482569448473311 -0.0390725278524998 0.568575080643991 0.820284696012236 +1646404228.92111 27.9301175080211 -1.05378675577201 -0.873950465421162 0.0553596421826463 -0.049136187901062 0.564999346857595 0.821764372010882 +1646404229.02125 28.0440534743563 -1.06375461708789 -0.891271582645536 0.0456909748456314 -0.0445662737449467 0.555018170007552 0.829385925262541 +1646404229.12177 28.1533463388824 -1.07032771699265 -0.893296050860082 0.0289810130461646 -0.034118191689704 0.557086475177283 0.829247073587348 +1646404229.22249 28.2669731717731 -1.07670816895239 -0.872882849304421 0.022785662715085 -0.0349925675553968 0.565739804927672 0.823525838641935 +1646404229.32284 28.3834172281061 -1.0919102568366 -0.860190596199896 0.0267081817178342 -0.0373209479718808 0.575334363282493 0.816629775539762 +1646404229.42301 28.501428534361 -1.1157429000491 -0.871908239629963 0.0265318637978634 -0.0328616053577821 0.590952616350889 0.805599888483574 +1646404229.52255 28.6189087841742 -1.13125547291599 -0.889526532312332 0.0295693900496377 -0.0366170140015357 0.598114242503192 0.800027623505914 +1646404229.62157 28.7350014889658 -1.14110030887983 -0.903514776825643 0.0388551664576759 -0.0433871603336195 0.591509368673143 0.804191828564314 +1646404229.72104 28.8542369302569 -1.15217928772053 -0.894244016295393 0.0238859829843849 -0.0322108817016467 0.583452840511243 0.811156397876649 +1646404229.82105 28.9771375582006 -1.15107401792048 -0.87686197984769 0.0210435113982893 -0.0254998184728761 0.577024822446524 0.816057157413882 +1646404229.92113 29.1054595660889 -1.14957489759779 -0.861598627895782 0.024862747526662 -0.0315706876329649 0.561166635168362 0.826726764440109 +1646404230.02504 29.2332698105643 -1.15922851330054 -0.860507462074617 0.0257186616322572 -0.0543478736307463 0.552919199031267 0.831062704263806 +1646404230.12195 29.3445643191392 -1.1719179815681 -0.872455507570284 0.0335151775814998 -0.0570795456921717 0.547115461761725 0.834435935130131 +1646404230.22221 29.4621625588633 -1.18555687457268 -0.874156561547028 0.0297494972026091 -0.0547904617510744 0.539819515995645 0.839468798030937 +1646404230.32269 29.5798461355112 -1.19963561246057 -0.853861218457547 0.0285477016119178 -0.0603248702374121 0.547041246851187 0.834441018291286 +1646404230.42334 29.6925993667126 -1.21080145276899 -0.831115345298778 0.0508082572624848 -0.0688495475657601 0.567892354317132 0.818643105817223 +1646404230.52285 29.8097450092648 -1.23256320022082 -0.822566880352547 0.0555287310666854 -0.0837084254145935 0.575552330101761 0.811571916009389 +1646404230.62178 29.928550822327 -1.26145349893273 -0.827800215257566 0.0415491189171087 -0.0705088269237033 0.570105062592015 0.817485408830026 +1646404230.7206 30.0511726954392 -1.28035623108612 -0.82698352933081 0.0610202710322612 -0.0843940689441719 0.547053787687636 0.830593956772375 +1646404230.81952 30.1855354825466 -1.30422517549896 -0.817872324323425 0.0573720906218952 -0.0992388470749195 0.505691245297166 0.855065178146496 +1646404230.91921 30.3251772784685 -1.33298642941975 -0.798406704676347 0.0341567923193342 -0.0942701348617624 0.452281360624744 0.886221206044525 +1646404231.01967 30.4692267615571 -1.35600951568619 -0.778885959408242 0.0337402589503973 -0.103977711564609 0.390234034095938 0.914203275566731 +1646404231.12105 30.6113101489084 -1.38114635476114 -0.769787585031542 0.0322945507992575 -0.122184239949339 0.339751884711168 0.931985370234892 +1646404231.22226 30.7436070261714 -1.41006378890114 -0.778455037278738 0.0276452959483584 -0.115182154919132 0.289012746028351 0.949968652868739 +1646404231.32306 30.8750523450047 -1.44093536385824 -0.783407975340972 0.0154899617305745 -0.107633195840674 0.236260160510802 0.965585984153716 +1646404231.42799 31.0159345604749 -1.4745495286647 -0.776651708276239 -0.000722116354413591 -0.102552024004749 0.189853056976835 0.976441691898207 +1646404231.52883 31.1536298905941 -1.50947717655678 -0.764880937391692 -0.0123840535336122 -0.0933591001227558 0.154679603331551 0.983465776707823 +1646404231.6291 31.2887053730811 -1.54364535442305 -0.76061407306433 -0.0125836689230791 -0.0985148490487108 0.120787879594955 0.987697708783554 +1646404231.72908 31.4183200025796 -1.57749546960723 -0.770461700141089 -0.0137138062288414 -0.0983059508211409 0.0868559983589985 0.991263792893149 +1646404231.82887 31.5397344651272 -1.60878750749646 -0.787792473853773 -0.0170271277135877 -0.0908496437584959 0.0609840621694775 0.993849768985269 +1646404231.92843 31.6603847201679 -1.63573284542605 -0.800638272558435 -0.0205127602921245 -0.0796701162664764 0.0384554166837799 0.995868003385461 +1646404232.0278 31.7844370790425 -1.65801184114414 -0.798080606976069 -0.024828765607781 -0.0674500374740494 0.0115075367802168 0.997347282264497 +1646404232.12678 31.90946994924 -1.67603044372513 -0.792429413679675 -0.0222544597031892 -0.0643647213759573 -0.019461728256705 0.99748842740092 +1646404232.22647 32.0308529399953 -1.68997929951473 -0.800242948001713 -0.0115978073064343 -0.0667950288628484 -0.0409725575621553 0.996857645058557 +1646404232.32672 32.1435872864758 -1.7057590758004 -0.822591745708843 -0.017206320010382 -0.0622209738767333 -0.0534783192661697 0.996480086268652 +1646404232.42712 32.2555779372158 -1.72239677440965 -0.838911823369831 -0.0249309480876271 -0.0551708759501874 -0.0723388136226878 0.995540917450401 +1646404232.52789 32.370230251968 -1.73372984308603 -0.839723684657841 -0.0212581781061142 -0.0468034750582323 -0.0760695430337729 0.995776555864165 +1646404232.62804 32.4795803825196 -1.74247426213737 -0.834495849414655 -0.0149684611260824 -0.0270507871516641 -0.0689267615317365 0.997142568357566 +1646404232.72776 32.5798092615004 -1.7504726140991 -0.834840954765678 -0.00840042914458066 -0.0204910032726687 -0.0678627422056061 0.99744884570357 +1646404232.82723 32.6679270786664 -1.76204054200895 -0.851172248192498 -0.0107857143198513 -0.0107325586966069 -0.0793706233625076 0.996729042768125 +1646404232.9272 32.7517894529564 -1.77640144086794 -0.864991317918774 -0.0164428935097861 -0.0109785216789703 -0.0988118356534099 0.994909706681745 +1646404233.02677 32.8290504446257 -1.79181518522243 -0.869392046630208 -0.0196369884725727 -0.0165361456345678 -0.12666052620179 0.991613864199945 +1646404233.12647 32.9012635807463 -1.80730683818301 -0.866937214503111 -0.0182383128692679 -0.0256450545653179 -0.162108712608674 0.986270987313509 +1646404233.22605 32.9650228091243 -1.82548385222665 -0.863915256976677 -0.0257925198366863 -0.0307623270175478 -0.196561614211229 0.979669310010066 +1646404233.32649 33.0143631252276 -1.84278773550126 -0.868229421772629 -0.0320183834469145 -0.0258551622402937 -0.236946379017438 0.970650682365949 +1646404233.42714 33.0495561375821 -1.86303192588214 -0.877166479423725 -0.0361247757687085 -0.0187406320261666 -0.280005021047671 0.959135536551011 +1646404233.52793 33.070408364559 -1.88666950520871 -0.882649848804012 -0.0397509486042408 -0.0189038819767322 -0.31612483114165 0.947695940936184 +1646404233.62858 33.0761491993566 -1.91172076906937 -0.886132036881593 -0.0393245406114949 -0.0206832329225135 -0.3486176318091 0.936211264177785 +1646404233.72905 33.0726057913387 -1.93477936978718 -0.887144483530799 -0.036380067873466 -0.0228435932437046 -0.376559180260106 0.925396047468898 +1646404233.82932 33.0594823820654 -1.96038249680655 -0.885636522842173 -0.0403004522569182 -0.0213869798036245 -0.404583685868401 0.913362201851975 +1646404233.92937 33.0328074095515 -1.99078335834057 -0.881612556097249 -0.0456441956153054 -0.018969512009781 -0.439097616708686 0.897078618640238 +1646404234.02949 32.9924064924441 -2.02617995687613 -0.876757118396493 -0.0465304688482369 -0.0172674234122416 -0.475876132849706 0.878110845930886 +1646404234.12951 32.9392260218075 -2.06679407024706 -0.870644188332609 -0.0448686796822561 -0.0100098738887821 -0.514466981036407 0.856277016760096 +1646404234.22922 32.8746755909558 -2.11234566868795 -0.860708298138972 -0.042784060579639 -0.00909106366077345 -0.560854086458918 0.826758471637363 +1646404234.32894 32.8055152710801 -2.15985469893209 -0.846790672636095 -0.0441840650777751 -0.0159596306704809 -0.610230780485815 0.790829598035961 +1646404234.42902 32.7361942209061 -2.20628812015583 -0.832678213381809 -0.0405472955342574 -0.0224698702322634 -0.656882987490589 0.752566118359061 +1646404234.52938 32.6674207678066 -2.24954869495111 -0.814359632478689 -0.0377994055210753 -0.025376044938777 -0.696840480075333 0.715779719336808 +1646404234.63013 32.6019173861574 -2.28884294941698 -0.790862356992564 -0.0368960705663918 -0.0376215499881269 -0.730524019403693 0.680850905872576 +1646404234.73054 32.5386023056355 -2.32180599472034 -0.761846465240919 -0.0273184993200425 -0.0524031353255102 -0.76185283096868 0.645048738428306 +1646404234.83062 32.4712076408321 -2.34960217179396 -0.725569389001422 -0.0347755837621704 -0.0644363283431955 -0.790827586126017 0.607643273134598 +1646404234.93016 32.4035526590695 -2.37097473789616 -0.678297796969561 -0.0396467268905297 -0.0658657394734452 -0.818496536279727 0.569344589425907 +1646404235.03062 32.3315260990836 -2.38931539343408 -0.617568906431842 -0.0401592985401943 -0.0720508093216057 -0.842431442891278 0.532452040699407 +1646404235.13117 32.2549135840728 -2.40315999494536 -0.540102995245433 -0.0528123029306607 -0.0704158864735919 -0.858196812523754 0.505717999052188 +1646404235.23517 32.1785648465837 -2.40921251326285 -0.449638194821141 -0.0604515302093624 -0.0536011783461247 -0.871485801468277 0.483719985130273 +1646404235.33488 32.1144099094037 -2.41175840901726 -0.355051166370394 -0.0641707074597556 -0.0398411751796437 -0.883180925432715 0.462910632861482 +1646404235.4344 32.0643828127053 -2.42107229564656 -0.257258692187234 -0.0565838355046116 -0.0428759300161513 -0.893307129315197 0.443804345291327 +1646404235.53394 32.0329040222812 -2.43243822064507 -0.16582567404891 -0.0359160157428985 -0.0595046381028038 -0.901803931829043 0.426519526393662 +1646404235.63404 32.0130325335877 -2.43537378449006 -0.0904769724649693 -0.0357116536041628 -0.066491500063846 -0.903058606511594 0.422834141740513 +1646404235.73297 31.9993458594962 -2.44098051600716 -0.0380414084157887 -0.0317624556673886 -0.0873845681297336 -0.905912393709505 0.413131720624616 +1646404235.83321 31.9809913818038 -2.45068465575997 -0.00493550817839698 -0.0412087842053969 -0.089641184415783 -0.905537891988982 0.412634729916159 +1646404235.93328 31.958329611978 -2.45817782305192 0.0122415230378053 -0.0509381038434519 -0.0856433484543675 -0.903950401989943 0.415865599905257 +1646404236.03297 31.9402038440599 -2.46401172402393 0.0234947263013069 -0.0548995622784557 -0.0838799122020812 -0.899515440867542 0.42523190147431 +1646404236.1322 31.9302265778445 -2.46901898149484 0.0389431794346591 -0.0572284970210345 -0.0817385497931695 -0.893460303531589 0.437918251069358 +1646404236.2316 31.9238720176326 -2.47276850457261 0.057042623051471 -0.0537913616342984 -0.0940802837801103 -0.892580812804576 0.437669832442775 +1646404236.33127 31.9211352223906 -2.47441005905098 0.0677019908041196 -0.0492052554394877 -0.10050509510113 -0.896302888008905 0.42909055179848 +1646404236.43141 31.9136138705845 -2.4790593627697 0.0708429870879186 -0.0420172456915174 -0.0994196169813442 -0.904131030417469 0.413397352023462 +1646404236.53181 31.8985535291601 -2.48410747624223 0.0741185872289851 -0.0437552562868387 -0.0944454279323444 -0.908579893039915 0.4045344443351 +1646404236.63252 31.890927019984 -2.49049895236483 0.0805291778424663 -0.0429184928088033 -0.100182442605605 -0.907878772936401 0.40481800209486 +1646404236.73277 31.8885602400668 -2.49409225902857 0.089000264318007 -0.044698433181168 -0.100830411570879 -0.906689642543062 0.407123040712158 +1646404236.83309 31.889523460023 -2.49169244150184 0.0953888806217225 -0.0462512579262586 -0.0980345926084306 -0.909572525168338 0.401158149924955 +1646404236.93322 31.8930108393042 -2.48755641979316 0.101116333203713 -0.04758563569791 -0.0951071522362636 -0.910890173690943 0.39870957894437 +1646404237.03335 31.8972386788056 -2.48551083874677 0.10316882234111 -0.0442456981645191 -0.0901299629249606 -0.910446981869957 0.401254534156246 +1646404237.13335 31.8992378307279 -2.48702672758413 0.10383257222949 -0.0424656161443048 -0.0893472712269365 -0.910553382844387 0.401380459863714 +1646404237.23334 31.899756746654 -2.48915728402843 0.104031808596478 -0.0411661765375875 -0.0903294193097655 -0.910687579402172 0.400991364793592 +1646404237.33321 31.8996026987238 -2.48870926618196 0.103320725085424 -0.0395879351929751 -0.0902152094355837 -0.91073383047232 0.401070943109626 +1646404237.43323 31.9013543265934 -2.48718765793107 0.103163941330553 -0.03734633892358 -0.089165455121238 -0.910933574395923 0.401067071224094 +1646404237.53319 31.9045434852014 -2.48743225741895 0.103523567988966 -0.0343912267789822 -0.0902654642254729 -0.911266694523244 0.400327866806015 +1646404237.6333 31.9068178930136 -2.4873845051395 0.104407242571268 -0.0314509295869302 -0.0923040808461754 -0.911470176628383 0.399640979886025 +1646404237.73325 31.9073925051242 -2.4871933391704 0.104986557281719 -0.0307481553706066 -0.0913780607191649 -0.911374360868133 0.40012669907504 +1646404237.83329 31.9078250524335 -2.48728037226955 0.104856799812695 -0.0304606913078073 -0.0917003602693297 -0.911430190755461 0.39994774357529 +1646404237.93323 31.9099587858427 -2.48723587056701 0.104909918032031 -0.0281722276805224 -0.0915272912353844 -0.911395577764904 0.400233908330094 +1646404238.03329 31.9127399819317 -2.48617957782185 0.104797810997829 -0.0219856096198818 -0.0911829835147055 -0.911159539200745 0.401236327630562 +1646404238.13321 31.9139934257076 -2.48384559248976 0.104752123341514 -0.0184141203883026 -0.0865318823158916 -0.911872698881482 0.400825815720207 +1646404238.23318 31.914220524653 -2.48414701868232 0.104883492353789 -0.0186055232075593 -0.0865645566455265 -0.911802289901856 0.400970068918667 +1646404238.33318 31.9144175967204 -2.48453032359274 0.104776005744931 -0.0167105532802788 -0.0869678899368547 -0.91257041109282 0.399214965058741 +1646404238.43313 31.9164716685317 -2.48159227616773 0.105612406085081 -0.00933828778339458 -0.0806412271111686 -0.913325965279124 0.399055722948823 +1646404238.53282 31.9151748764957 -2.47763420641232 0.105379075766636 -0.00784235786725898 -0.0698249979749832 -0.914276720965506 0.398949927411209 +1646404238.63272 31.9145878882287 -2.47439080674895 0.104932200356624 -0.00674827218375136 -0.0607719602449291 -0.914839687572824 0.399161089927553 +1646404238.73243 31.9131281095198 -2.46669293503006 0.104613074590645 -0.00432567470377187 -0.0410784959008062 -0.915834109185572 0.399426751939733 +1646404238.83211 31.9106139235123 -2.45648782735041 0.1050479768691 -0.00116612689670981 -0.0149392028710056 -0.916596711750581 0.399532136847126 +1646404238.93181 31.9083736503182 -2.45047657859587 0.106007024571226 0.000488796083016097 -0.00300426954265713 -0.917020686111376 0.39882802896323 +1646404239.03164 31.9079390040553 -2.45041686089183 0.105943896725115 0.000483891785587106 -0.00299117096518752 -0.917029483744447 0.398807904495836 +1646404239.13167 31.9079113904283 -2.44967624785207 0.105350564679872 0.000368054054309297 -0.0028842735265595 -0.917040339141222 0.39878385359761 +1646404239.23144 31.9076520091991 -2.44911987036759 0.104924475234088 0.00043607054180206 -0.00289285136182003 -0.917040983300255 0.398782241581984 +1646404239.3313 31.9074169865451 -2.44903053389006 0.103938023554132 0.000531851235288242 -0.00288352489141577 -0.917050397154462 0.398760544057805 +1646404239.43118 31.9075481549394 -2.44917999682905 0.10362175386662 0.000484206197868161 -0.0029363342176398 -0.917048762553895 0.398763978543774 +1646404239.53095 31.9082210736435 -2.44988454026318 0.103305490411645 0.000438331904305564 -0.00291854002197842 -0.917047810417265 0.398766351888106 +1646404239.62962 31.908804011821 -2.45056788968398 0.102524909937598 0.000405937279550428 -0.00292935489582272 -0.917046300156522 0.398769780028554 +1646404239.73047 31.9090751089652 -2.4508470990582 0.102400501429311 0.00036288057048533 -0.00295896205153743 -0.917055354701023 0.398748779653828 +1646404239.83038 31.9095630793017 -2.45106011937709 0.10250795020145 0.000375658286549144 -0.00294358606364621 -0.917061806283946 0.398734043739848 +1646404239.93014 31.9099192642603 -2.45159355719119 0.102392091541035 0.000367442394630661 -0.00299898180220752 -0.917063744061512 0.398729181803998 +1646404240.03009 31.9098316176805 -2.45168029864484 0.102266888025218 0.00033499740521486 -0.00299338742659353 -0.91705396416249 0.398751745102495 +1646404240.13005 31.9092124782025 -2.45183865121369 0.10215656932673 0.000378284252577286 -0.00294071143337147 -0.917055346930468 0.398748918222355 +1646404240.23017 31.9096258344827 -2.45222282004038 0.101719908353496 0.000445054682940901 -0.00285034253636925 -0.917058188870544 0.398742969466801 +1646404240.33023 31.9100765054432 -2.4520639631764 0.101663855103057 0.000417890915586518 -0.00291981205021741 -0.917049206858906 0.398763153092403 +1646404240.43029 31.9101498172766 -2.45206368277656 0.101719669388769 0.000405246711218106 -0.00287477974176676 -0.917057970126772 0.398743339560014 +1646404240.53018 31.9102539054575 -2.45237813501796 0.101981763356338 0.000398756977725664 -0.00288621485414802 -0.917064816269377 0.398727517883419 +1646404240.6302 31.9102707296735 -2.45241441964752 0.10181583629279 0.000356869464885338 -0.00288513552240629 -0.917058536708454 0.398742007929088 +1646404240.73026 31.9104542570953 -2.45241555419335 0.101988034356112 0.000421806447817492 -0.00281140553242145 -0.91704209937446 0.39878027289863 +1646404240.83021 31.9106495395446 -2.45245874899209 0.101800009158936 0.000439008232136943 -0.00281677194276949 -0.917036888238706 0.398792199869852 +1646404240.93012 31.9099851222674 -2.45245609532619 0.10192286361382 0.000471010122611123 -0.00285761879188963 -0.917027779282962 0.398812818484603 +1646404241.03004 31.9099446279843 -2.45269713904113 0.102206424070594 0.000459465742806599 -0.0028061519760546 -0.917030638814922 0.398806622157888 +1646404241.12992 31.9097176816635 -2.45274006918192 0.102155854906952 0.000490180838393227 -0.00277188371466924 -0.917040294476582 0.398784621932307 +1646404241.23062 31.9094304834603 -2.45233206702825 0.102099118651653 0.000444655635882978 -0.00280574514383129 -0.91704200549567 0.398780503826361 +1646404241.33086 31.908593175501 -2.45222202845596 0.102205650462325 0.000522695941180231 -0.00271473073132026 -0.917045190069041 0.39877371578029 +1646404241.43105 31.9088097729922 -2.45197780853437 0.102165202487054 0.000540189503880283 -0.0027158692232877 -0.917049747092406 0.398763204931683 +1646404241.53103 31.9087981103062 -2.45180607554137 0.101930197285846 0.000576311968486943 -0.00272528789978005 -0.917057142788714 0.398746081523756 +1646404241.63097 31.9090229709193 -2.4516661262609 0.10174050743991 0.000637973639113241 -0.00260445322181898 -0.917058627188961 0.398743381275878 +1646404241.73076 31.9090378667087 -2.45179069466955 0.101885927417248 0.000563764699209704 -0.00262021479540193 -0.917079886392246 0.398694492836995 +1646404241.8306 31.9096063075979 -2.45197377939872 0.101938461388643 0.000599810667420417 -0.00259707542172474 -0.91708884600041 0.398673982055549 +1646404241.93049 31.9091406995054 -2.45237035675822 0.102095653812651 0.000628557212072815 -0.00253356358383151 -0.917083265411067 0.398687183483928 +1646404242.03046 31.9082300479881 -2.45239045750019 0.10206442983789 0.000640334061393406 -0.00245873104966328 -0.917067965925781 0.398722824135564 +1646404242.13041 31.9070131963382 -2.45217933080695 0.10210505800728 0.00065044545514155 -0.00247830190074127 -0.917059154883339 0.398742951517676 +1646404242.23057 31.9061133678187 -2.45172566170697 0.102500421127177 0.000621751673885707 -0.00252831016594399 -0.917044263340007 0.398776930310316 +1646404242.33068 31.9051391673837 -2.45109072086586 0.102487005026015 0.000569006158667001 -0.00249462377239418 -0.917033726378149 0.398801451563565 +1646404242.43068 31.9045745514031 -2.45073498092453 0.102697346201104 0.000568552579480215 -0.00252387441585008 -0.917027201824505 0.398816270881456 +1646404242.53067 31.9044266621446 -2.4505023969451 0.102955686053716 0.000596053711787294 -0.00254969019006333 -0.917028342443943 0.39881344379847 +1646404242.63061 31.9040906076949 -2.45010795750407 0.103224337845173 0.000566408439919782 -0.00261739367796353 -0.917012158511595 0.398850259588349 +1646404242.73061 31.9035106733699 -2.45003709416337 0.10290260474089 0.000566221713727934 -0.00265875892903287 -0.917010401607341 0.398854025600653 +1646404242.83044 31.9036483576287 -2.45032629273118 0.102729207842096 0.000575337086352883 -0.0026851301083926 -0.917001537521386 0.398874214818316 +1646404242.93045 31.9044431533773 -2.45040183775298 0.102795216386935 0.000533703948174997 -0.00272133028487665 -0.917012151551177 0.398849625083231 +1646404243.03047 31.9049923031371 -2.45116744397285 0.10306178372413 0.000496578313771491 -0.00277039179378526 -0.917026824431913 0.398815598505858 +1646404243.13054 31.9058278662494 -2.45129703650989 0.103131176853763 0.000508590468872328 -0.00277459229474726 -0.917020658310082 0.398829732098617 +1646404243.23047 31.9067644407382 -2.45188907898417 0.10293702479891 0.000515141347666227 -0.00273862771638517 -0.917035232158102 0.398796461278604 +1646404243.3304 31.907175672934 -2.45221034021206 0.102272960882069 0.00051324260288817 -0.0027539777988465 -0.91703863587745 0.398788531049124 +1646404243.43039 31.9070136058551 -2.4526020810807 0.102130774513078 0.000559666550375352 -0.0026435486693399 -0.917032870256201 0.398802474031239 +1646404243.53033 31.9077092071267 -2.45239280447359 0.101685963813907 0.000614380614883998 -0.00259095215125521 -0.917035949342211 0.398795658348254 +1646404243.63032 31.908231203668 -2.45213393001504 0.101515920839684 0.000671025008708571 -0.00252867757851034 -0.917028097476183 0.398814021762442 +1646404243.73031 31.908788199439 -2.45186189108593 0.101424756054421 0.000660255487573172 -0.00247624448636209 -0.917037818986692 0.398792014493827 +1646404243.83025 31.9096880578826 -2.45173661354277 0.101275581812336 0.0006260353938958 -0.00254883830114965 -0.917036659688503 0.398794278156458 +1646404243.93025 31.9099114612423 -2.45149589817918 0.101550246208692 0.000578178642931151 -0.00262656185332378 -0.917046917085553 0.398770258101263 +1646404244.03024 31.9104449948051 -2.4513943033891 0.101572805337191 0.000585816495939629 -0.00261367567067803 -0.917049866934887 0.398763547824028 +1646404244.13028 31.9109823930824 -2.45118065471759 0.102044862165316 0.000538577624192483 -0.00270726942836781 -0.917049813396687 0.39876311310785 +1646404244.23021 31.9107569337207 -2.45087735111955 0.102165164751771 0.00052828875659316 -0.00272289547871534 -0.917061675041358 0.398735740712464 +1646404244.3302 31.9110454861231 -2.45071996352268 0.102600783589261 0.000517974297476205 -0.00273162655011685 -0.917069588211934 0.39871749434379 +1646404244.43025 31.9107941410996 -2.45090325024152 0.102286278643653 0.000546533641190085 -0.00268573897300337 -0.917052907256978 0.398756132741119 +1646404244.5302 31.9108522279121 -2.45037766636867 0.10236401882879 0.000514666116832188 -0.00278738642860419 -0.917065609774136 0.398726263199777 +1646404244.63019 31.9112732607915 -2.45020426954285 0.102306889806552 0.000447243738994588 -0.00288486354703071 -0.917070579700669 0.398714220191368 +1646404244.73027 31.9110207442227 -2.45029891990985 0.10240422437 0.000442614807275177 -0.00287615868602953 -0.917054364396356 0.398751582498325 +1646404244.83036 31.9113182371751 -2.45050257907966 0.102329198128026 0.000453833122318699 -0.00294523845252576 -0.917049760019472 0.398761654693832 +1646404244.9306 31.9108851892522 -2.45049577370227 0.101997829862231 0.000476787305762087 -0.00296486689231669 -0.917028577889402 0.398810192412752 +1646404245.03088 31.9107974313571 -2.45057435168484 0.102123106973871 0.000463342948578889 -0.00295558269200244 -0.91701569251163 0.39883990463801 +1646404245.13105 31.9107176834346 -2.45069141084452 0.102183914548989 0.000401559497458661 -0.00298174470508786 -0.917029668130008 0.398807642501783 +1646404245.23114 31.9103121579953 -2.45052848475818 0.102674199031403 0.000297411353785012 -0.00302301238962211 -0.917043327106851 0.398776013761302 +1646404245.3311 31.9089393026725 -2.44917520606389 0.102136713885733 -0.00130972833730513 -0.00292752744354003 -0.915501488046973 0.402301801609822 +1646404245.43068 31.9095806939199 -2.44286146666337 0.0916571521961657 -0.00237855662069905 -0.0252240542061319 -0.900087932026123 0.434971038321777 +1646404245.53531 31.9122348774274 -2.43166407811764 0.061826878609758 0.00726634705694287 -0.0588369274830458 -0.868009907248869 0.492995149147122 +1646404245.63499 31.9156181296258 -2.41394232142981 0.0144450473835754 0.0289061047451274 -0.0632862289779785 -0.830608720978028 0.552492934765177 +1646404245.7335 31.9204013747435 -2.39936466660542 -0.0424343719649132 0.0305965671098735 -0.0634775915770872 -0.793825389178032 0.604049415979349 +1646404245.83144 31.9298155880779 -2.39057576519324 -0.120610778925458 -0.00785915229133919 -0.0594513400180794 -0.760337295506151 0.646754179698663 +1646404245.92964 31.9668508418344 -2.38014989688698 -0.220293662497552 0.00069433176782399 -0.0777077288077116 -0.732556221625249 0.676256171095735 +1646404246.02822 32.0074116961236 -2.36401239479788 -0.325663367234346 -0.0026052963353396 -0.0546956483566975 -0.711626179243457 0.700421144381854 +1646404246.1273 32.0603334050693 -2.33773932353871 -0.4274122427974 -0.0112176081777873 -0.0288695813763418 -0.700656561281824 0.71282613284772 +1646404246.22784 32.1269071917251 -2.30468482089345 -0.524849755535583 -0.0217110195234899 -0.0214663467103873 -0.674740982283755 0.73742283285568 +1646404246.31602 32.1901075861918 -2.27647867995417 -0.60021449326385 -0.0455152791871099 -0.0305195665325122 -0.638372337605462 0.767774494235975 +1646404246.41735 32.2618467718562 -2.23707438189612 -0.674445238808273 -0.0506652043359151 -0.0313131073967386 -0.59185590045187 0.803840232555605 +1646404246.51835 32.3324040657832 -2.19500580564777 -0.734277732611168 -0.0439482391235928 -0.0302324516871784 -0.535925241297869 0.842578593890636 +1646404246.61888 32.4035800264923 -2.1549152076357 -0.784315189037327 -0.0371717286087542 -0.0344050208669574 -0.482827599169003 0.874249430432791 +1646404246.7221 32.4827907013911 -2.10910877399719 -0.826249836454883 -0.0154528915351324 -0.0285078583472764 -0.431922282443134 0.901327716252391 +1646404246.8229 32.5648068572593 -2.06719123659113 -0.848775211398701 -0.00841684290085182 -0.0296268671944332 -0.38826747458638 0.921031906979407 +1646404246.92379 32.6515082394185 -2.02736773872493 -0.858840912669324 -0.017255280758134 -0.037593318026664 -0.354112048519139 0.934287779444463 +1646404247.0237 32.7375729106099 -1.9827510278768 -0.86691717750176 -0.0172274452502602 -0.034874022060129 -0.319555786719423 0.946768776887794 +1646404247.12295 32.8220307549434 -1.9420746795827 -0.87541214481723 -0.0311507145183439 -0.0360775803625627 -0.283286696980183 0.95785003444914 +1646404247.22373 32.9115068875814 -1.90248327707461 -0.88337589820708 -0.0399883381645591 -0.0415608163632952 -0.250552283719811 0.966383559709509 +1646404247.32481 33.0057100908955 -1.86381672458848 -0.888336596648145 -0.0331900150062231 -0.0457003705828913 -0.217902480024124 0.974334854263046 +1646404247.42528 33.1051419349395 -1.83249889247642 -0.884980356545122 -0.0200071876999222 -0.0484956523894614 -0.182595416250813 0.981787552428647 +1646404247.52557 33.2104920917176 -1.8100855875085 -0.874013850670348 -0.0136954183144892 -0.0526588940688194 -0.148149978110349 0.987466992045063 +1646404247.62556 33.3197991856067 -1.79342704399346 -0.860208558210392 -0.00929776399094772 -0.0506571805017551 -0.116974166020945 0.991798591515468 +1646404247.72538 33.4356526378924 -1.78256806620896 -0.849715985643385 -0.00958776744034108 -0.051065441965088 -0.0903808442119889 0.994551003393958 +1646404247.82538 33.5546079283173 -1.77076365048832 -0.853478110293375 -0.000512978913364044 -0.0510713583294003 -0.0671318599674302 0.996436032361496 +1646404247.92501 33.674111434811 -1.76254817278839 -0.871959209993018 -0.00340851587061516 -0.0463085678853163 -0.047158103443694 0.99780760261663 +1646404248.02516 33.7970030547182 -1.75361242930652 -0.892046616565179 -0.00655280985659549 -0.0415925518446966 -0.0373259029735585 0.998415693627269 +1646404248.1255 33.9205933861383 -1.74236353489709 -0.904199641364996 -0.00810281160812537 -0.0315381647409919 -0.0273276249107114 0.999096036187481 +1646404248.22527 34.044897667859 -1.732093149071 -0.907016122299525 -0.0167197532259777 -0.0141027025159964 -0.0253231599074916 0.999439993799574 +1646404248.32446 34.1737280699327 -1.72299103072683 -0.910429377912644 -0.0179982739986787 -0.00565893758481631 -0.0389207881254422 0.999064167513858 +1646404248.42447 34.3012201795803 -1.71590594681922 -0.927444127738627 -0.0120540000731478 -0.00243676071496685 -0.0533899532547453 0.998498010098615 +1646404248.52546 34.42876909445 -1.71259005576756 -0.949911254935616 -0.0117005470215256 -0.00240423543311492 -0.0587189007175745 0.998203089330964 +1646404248.62627 34.5561346797312 -1.7131039251073 -0.958224702619242 -0.0106495568591821 0.00591554737337965 -0.0627234161355447 0.997956595401946 +1646404248.72677 34.6886873876741 -1.71639864435287 -0.946271619694138 -0.00946960476191791 0.0143586255168954 -0.0577055507493842 0.998185466670202 +1646404248.82696 34.8232922024809 -1.72009139502117 -0.930024804660471 -0.0062731928939825 0.0203358411310103 -0.0406229173835513 0.99894788612802 +1646404248.92633 34.9576894685374 -1.72621953310008 -0.929213715402654 -0.00692285191344993 0.0164605903459941 -0.0250014746298836 0.999527913243626 +1646404249.02564 35.0964878469864 -1.7339914436524 -0.938753247448301 -0.00947866839629119 0.00788255989352509 -0.018470167781119 0.999753406094261 +1646404249.12477 35.238711033088 -1.73734950038062 -0.948459590526873 -0.0110963898346312 -0.00238784183988536 -0.0125507064508309 0.999856813804633 +1646404249.22464 35.3837994665658 -1.73805547591114 -0.946454386608299 -0.0108817545588191 0.00410577106019008 -0.00255260111443933 0.99992910463155 +1646404249.32412 35.5337102758222 -1.73863552418512 -0.929160346638997 -0.00830803602358712 0.0120051921006581 -0.00187205300157512 0.999891667790865 +1646404249.42314 35.6844166328865 -1.74631877813114 -0.92016500842675 -0.0103528936523421 0.0125951627880263 -0.0169611183547858 0.999723211659859 +1646404249.52303 35.8395084098158 -1.75436650779655 -0.932090296633639 0.00544952827108181 0.00849359127138632 -0.033938285480683 0.999372980587103 +1646404249.62388 35.9878940080831 -1.77023864104212 -0.955581197300474 0.002182357983851 0.0156542162729325 -0.0456429736008395 0.998832769680372 +1646404249.72514 36.1326789755943 -1.78755645724641 -0.966505147300339 -0.00973686297162016 0.0315272595751701 -0.0556587627901061 0.997904468137008 +1646404249.82628 36.2827823084745 -1.80011255593566 -0.961534477945213 -0.0117886024776039 0.0484687212887687 -0.0514876480464269 0.997427107114541 +1646404249.92696 36.4330095200635 -1.80784950393716 -0.95372833123189 -0.00772637313343091 0.0618323765093797 -0.0349153815455282 0.997445726094866 +1646404250.02736 36.585479543528 -1.81653763096185 -0.956347769660321 0.00126813470903055 0.0633940654210325 -0.0282537734442519 0.99758774480739 +1646404250.12714 36.7365346146014 -1.82845992740628 -0.968971445965068 -0.0106297458693097 0.0536484285980886 -0.0221100816398245 0.998258483010071 +1646404250.22711 36.8784856917812 -1.83355456861853 -0.98087794754679 -0.00799894265276188 0.0474057950934825 -0.0220945367969242 0.998599288479468 +1646404250.32708 37.017118539028 -1.83279743226186 -0.980288745823891 0.00703585336842135 0.0563105276185231 -0.0181407648323107 0.998223689309153 +1646404250.42659 37.1588510415781 -1.83585046085856 -0.969887156271746 0.00686719172138761 0.0644050147114341 -0.0182800668456921 0.997732767284895 +1646404250.52582 37.2972767768333 -1.8424087847668 -0.965628507447098 0.00231397259765711 0.0691155048000883 -0.0281512462733419 0.997208704264198 +1646404250.62574 37.4358965607176 -1.84983024694331 -0.976331486645655 0.00961545014477976 0.0652747887588809 -0.0427820227515177 0.996903427419257 +1646404250.72617 37.5664865852792 -1.86201465124765 -0.984801994232579 0.00408534446155903 0.045260094043173 -0.054834720008068 0.99746076981977 +1646404250.82689 37.6942730735008 -1.8739705520769 -0.983735064673669 -0.00353871553161053 0.0498801684534071 -0.0638531440413441 0.996705684885693 +1646404250.92748 37.8293831646026 -1.88592354566666 -0.970120627126596 -0.0114258266170211 0.057354724095579 -0.0672733211795864 0.996019169678718 +1646404251.02787 37.9649420985146 -1.89456700886639 -0.95778702006229 -0.00651023742876926 0.0618078779873588 -0.0599424432358913 0.996265178818476 +1646404251.12779 38.0993972500551 -1.90562917485697 -0.955199193483208 -0.00381717226049027 0.0652647439073171 -0.0490528862322957 0.996654281459176 +1646404251.22742 38.2358451600045 -1.91994248220914 -0.964322911603646 -0.0197421649036152 0.056368379055366 -0.0422827145725257 0.997318918308455 +1646404251.32674 38.3701039477532 -1.92931843579463 -0.971646970440687 -0.0235831758222012 0.0493221741454522 -0.0398599088496906 0.997708546932509 +1646404251.42636 38.5056356928828 -1.9372625260439 -0.96624321966008 -0.0237049209258428 0.0501821009487582 -0.0404412748335974 0.997639382120654 +1646404251.52564 38.6434149870101 -1.94520378367991 -0.951939538931582 -0.0196871371057967 0.0562827884952806 -0.0492381804750888 0.997005649901371 +1646404251.62503 38.7824983111036 -1.95291174320818 -0.945555224900803 -0.0137330282796392 0.0524804346140564 -0.0577376096673057 0.996856848472675 +1646404251.72514 38.9260090451251 -1.96039317643479 -0.952186013568415 -0.00227342836961736 0.0401261562793674 -0.0681955910478123 0.996862119085337 +1646404251.82567 39.0651840885304 -1.97491468831138 -0.962601333959527 -0.0140453104317791 0.0294339253547996 -0.0786410784286283 0.996369386360623 +1646404251.92646 39.2040719696982 -1.98688177816265 -0.964108674934707 -0.0193631989008867 0.0339341794614451 -0.0813932099618654 0.995916002163177 +1646404252.02716 39.349575735545 -1.99588406099993 -0.94939588676549 -0.0129529760850197 0.0395919921684835 -0.0710697549383225 0.996601116043754 +1646404252.12744 39.4916800654444 -1.99832581762423 -0.941279066652982 0.00189766377543239 0.0456491411896392 -0.0495141422193069 0.997727870965379 +1646404252.22721 39.6299058574732 -1.99809155811519 -0.947208413238334 0.0181058641425014 0.0435182580364214 -0.0329697420403334 0.998344296828956 +1646404252.32659 39.7753550478321 -1.99720727692774 -0.958360608133941 0.0161385679801491 0.0246739173764913 -0.0154604779424468 0.999445705402059 +1646404252.42591 39.9230382894552 -1.99233937276161 -0.962544003973175 0.0133559932825743 0.0142720880696643 -0.000655406300307813 0.999808729401844 +1646404252.52519 40.0717764357864 -1.9889570826151 -0.957808624827878 0.00289149857568726 0.0307047335283679 0.00130451960952808 0.999523464858883 +1646404252.62446 40.2242590782895 -1.98969465346273 -0.950882134406777 -0.00936515486289602 0.042611590143973 -0.00928420922323541 0.999004679528017 +1646404252.72421 40.373352622353 -1.99033505260358 -0.956639145017324 -0.0137203086492609 0.0417011307806926 -0.0233781707473587 0.998762349087444 +1646404252.82474 40.5186237806361 -1.99328409705066 -0.973842514427174 -0.00111293248864926 0.0309470093987929 -0.0356605572362238 0.998884061664882 +1646404252.92565 40.6614696708314 -2.00210419584402 -0.980992479561302 -0.00781212138402861 0.0185577420813864 -0.0420699324840431 0.998911758740027 +1646404253.02652 40.8052629195792 -2.01300553501898 -0.975227593845817 -0.0148059994838783 0.0228164475286397 -0.0459778477083612 0.998572095354935 +1646404253.12711 40.9503917080621 -2.02400015158345 -0.963249147122353 -0.0202818061429109 0.0335911832541767 -0.0476767953556069 0.998091781316612 +1646404253.22762 41.0901935222653 -2.02971888915358 -0.96398921961728 -0.0164228972120472 0.042912160406622 -0.0417422752640336 0.998071348848449 +1646404253.32757 41.2292766013164 -2.03582339381831 -0.972997790086347 -0.0204176325532255 0.037094139235308 -0.0327660550848923 0.998565736819299 +1646404253.42735 41.3671906266368 -2.04077734682874 -0.981490782332309 -0.0233311687859571 0.0177646269712232 -0.0278694502598134 0.999181349072256 +1646404253.52704 41.5011327984896 -2.04160449900863 -0.983095069630795 -0.0156710078164073 0.0234830760945258 -0.0236180202169959 0.99932234727948 +1646404253.62649 41.6428440814637 -2.04472576641081 -0.96870306497062 -0.0137819791781458 0.0299304834278312 -0.023612868574834 0.99917798997444 +1646404253.72582 41.783413303006 -2.05369309191549 -0.957169754975867 -0.0205806580244669 0.04084943514027 -0.0316346325258888 0.998452307418305 +1646404253.82554 41.9233140489502 -2.06062120486874 -0.959728663028632 -0.00701108022262611 0.0377973117554687 -0.0406223079345109 0.998434793101798 +1646404253.92574 42.0672270616542 -2.07568383733494 -0.965585998525912 -0.00533000175825443 0.0134695807477379 -0.050617168199923 0.998613070092287 +1646404254.02624 42.1976032590687 -2.09189104118858 -0.97153360407372 -0.00781683703499541 0.0199304148204934 -0.0575557630154473 0.998112723978383 +1646404254.12679 42.3341495142143 -2.10861276765131 -0.963161714080388 -0.00755402168451254 0.0348841943135021 -0.0562379451534564 0.997779195648212 +1646404254.22726 42.4762401921298 -2.12308998496607 -0.953511421998174 -0.00390293651795129 0.0374322014681822 -0.0451601329237645 0.998270584447963 +1646404254.32745 42.6139263238986 -2.13564859475955 -0.954414520742556 0.00637271942393702 0.0262145839661187 -0.0327555349210397 0.999099223784431 +1646404254.4272 42.7514041915249 -2.14587720581434 -0.963864919084529 0.00381481952842293 0.0162177748054993 -0.0164579800073255 0.999725745305378 +1646404254.52663 42.886266425412 -2.15084559748205 -0.975303096093724 0.00975511136644023 0.00823508072688262 -0.0049085876341334 0.999906459132592 +1646404254.62605 43.0207762228355 -2.15650082024796 -0.976906941203107 0.00761689451790767 0.0224526996056398 -0.0014658401201099 0.999717815441466 +1646404254.72553 43.160862161357 -2.16238520794337 -0.964732313730793 0.00812342455044546 0.0339597179343574 -0.00425604401196592 0.999381125307434 +1646404254.82493 43.3050854593025 -2.17315305741652 -0.957321218502051 0.00673467682397232 0.034497585193201 -0.0158424167192904 0.999256512901667 +1646404254.92494 43.4450537675658 -2.18436165349785 -0.962126845487075 0.0129507426982432 0.0365649350812272 -0.0274326830542675 0.998870728215871 +1646404255.02556 43.5870770333598 -2.19663245450612 -0.972371325374896 0.0130098355210385 0.0131886738149794 -0.037242659085449 0.999134519174947 +1646404255.12628 43.7236854549842 -2.21044063771964 -0.979899941421435 -0.000868772749673999 0.019087056830298 -0.0447828964011242 0.99881400755365 +1646404255.22697 43.8620552972085 -2.22175651295464 -0.976256838824714 -0.00853105153094434 0.0359559452958448 -0.0444445759707064 0.998328137850692 +1646404255.32735 44.0043248703404 -2.22265705547196 -0.971441959302689 0.000368446076541057 0.0413399676369679 -0.0326562688426745 0.998611255408492 +1646404255.42753 44.1434594790643 -2.22305394122386 -0.975629609807505 0.000286020581017783 0.0416307916021558 -0.0169970751861509 0.998988435777867 +1646404255.52718 44.275478616567 -2.21205416855546 -0.988214634700579 -0.000654648355553614 0.0385246765781282 6.06387178928772e-05 0.999257432823502 +1646404255.62661 44.4100979790999 -2.19975190319285 -0.999287572159788 0.00567824100578103 0.0282929803663812 0.0132374290416714 0.999495890593564 +1646404255.72593 44.5408359748272 -2.19372668485131 -0.996276032750443 -0.00138961805062563 0.0405885464627683 0.0199740185732436 0.998975313728892 +1646404255.82536 44.6871672138424 -2.19265524050019 -0.980877559349454 -0.0121558666527615 0.0453949630594312 0.0133311737021775 0.998806193434173 +1646404255.92448 44.8272488704475 -2.19434252099051 -0.972834314256348 -0.0191873885821328 0.0508372730617592 0.0021436566426016 0.998520315528547 +1646404256.02438 44.9699137087734 -2.19635221609901 -0.977196486976127 -0.00651675360484415 0.0505526225697707 -0.0184050328113492 0.998530529849225 +1646404256.12503 45.1161661228782 -2.2092036847686 -0.982452795604757 -0.00909971626848883 0.0340495575849086 -0.0345229778333363 0.99878225194164 +1646404256.22598 45.2621754868085 -2.22385431968162 -0.975950555786631 -0.014110788354026 0.0324814983849442 -0.041409582984154 0.998514438729738 +1646404256.32673 45.4079811310546 -2.23495335986825 -0.959292680912325 -0.0137847874560724 0.0400460579075928 -0.0390601122582425 0.998338920663326 +1646404256.42717 45.5525144898109 -2.24013904226037 -0.951147879773721 -0.00161134389960771 0.0439058207337364 -0.0295177084750786 0.998598211175497 +1646404256.52736 45.6915914927547 -2.24387886372224 -0.958938149907104 0.00104954466644405 0.0400809371553466 -0.0147170740282021 0.999087496000615 +1646404256.62692 45.8260554658012 -2.24238883482236 -0.974046496290948 -0.0047122773247006 0.0263868717762188 -0.000451574833705745 0.999640597175025 +1646404256.72644 45.9595519503473 -2.23793535157657 -0.98061184947502 -0.00653954047721418 0.0203545252881155 0.00860692512457953 0.999734389000665 +1646404256.82576 46.0965557741629 -2.23549813848874 -0.967176467556757 -0.0119068470817432 0.0191352072790873 0.0136962806085084 0.99965218087715 +1646404256.92503 46.2347543566717 -2.23719313106684 -0.956385677429064 -0.0127909931234856 0.0217353809057105 0.00913979567667421 0.999640149177081 +1646404257.0241 46.3707323752063 -2.24238433896073 -0.952727512940636 -0.00167194643939339 0.027953772137058 -0.00336989037808448 0.999602138381687 +1646404257.12399 46.5137999267511 -2.25522638392971 -0.957025697249673 0.0104692104948386 0.0113754660717162 -0.0207545998459198 0.999665064403319 +1646404257.22452 46.651521724759 -2.27425944521736 -0.961070091733689 0.00723391008475696 -0.00577020744431884 -0.0340381429218417 0.999377696407798 +1646404257.32523 46.7903105875734 -2.29261226153955 -0.956162369142344 -0.00160705344402372 -0.00335913861289547 -0.0406932907082444 0.999164746004548 +1646404257.42595 46.9364052745435 -2.30525640563 -0.946278968369395 -0.00701628033187961 0.00863584622140793 -0.0369784396714374 0.999254116313664 +1646404257.52637 47.0779680992752 -2.30913994770296 -0.943709521597729 0.00342659403804058 0.0184665710313674 -0.0308489731380717 0.99934757970586 +1646404257.62651 47.2177922870539 -2.31248967107562 -0.955523276481111 -0.0078982934779206 0.0207454580898395 -0.0177383878231302 0.999596214741836 +1646404257.72656 47.3564628498108 -2.3065494874813 -0.972120967928817 -0.0141519685841631 0.0082642944748968 -0.00721370386137002 0.999839679998057 +1646404257.82626 47.492665644878 -2.29791180753715 -0.977361268448389 -0.0169695249505861 0.0108548560877993 0.000713669389221272 0.999796828359772 +1646404257.92582 47.6316672056159 -2.29052523288528 -0.966993757060795 -0.0211519156298659 0.0249976341740988 0.00510600170873101 0.999450670867465 +1646404258.02515 47.7704037677421 -2.28866180157264 -0.955237498406196 -0.0240451876561508 0.0343208498639535 0.000734174729180837 0.999121298543202 +1646404258.12452 47.9061133589638 -2.29263074701591 -0.960210406008996 -0.0139415859126323 0.0484810170352647 -0.018363612243419 0.998557960718771 +1646404258.22459 48.0441366381 -2.3102101639321 -0.972341806319722 -0.0107373742553719 0.0204504419462257 -0.0354908052848 0.999103043213527 +1646404258.32524 48.1822897689657 -2.33337883796118 -0.97551881353948 -0.0114516684700241 0.00987231034151866 -0.0499395460378821 0.998637791453585 +1646404258.42596 48.3227243074587 -2.35276745874422 -0.964591580304276 -0.0140854198282784 0.0199452227092362 -0.0533454423847551 0.998277542978958 +1646404258.52651 48.467524967988 -2.36124636848428 -0.949328557666379 -0.00738050495790566 0.0347941012863964 -0.0444660612464389 0.998377517805493 +1646404258.62681 48.6106288398343 -2.36565574420108 -0.94462351820993 -0.00837707425709509 0.0295198512296584 -0.0382620747038167 0.998796484099549 +1646404258.72667 48.7510150692742 -2.36349298380275 -0.955618418212388 -0.0255361338829752 0.0202610598533363 -0.0269225188163632 0.999105886931162 +1646404258.82645 48.8882519467775 -2.34655970975407 -0.967374672370525 -0.0158889510221744 0.00955410963309948 -0.0184411086122217 0.999658034398603 +1646404258.9261 49.0292510052018 -2.33083040748251 -0.965024480496999 -0.0229803902400598 0.0134022303744539 -0.00807092059625511 0.999613496370535 +1646404259.02533 49.1708169939301 -2.31938261737432 -0.950593247548376 -0.0307921872756645 0.0211957802918996 -0.00937360407156874 0.999257081859968 +1646404259.1243 49.3134132446377 -2.31486349133513 -0.947037029883004 -0.0224851333966495 0.0253967679780966 -0.0232951642317672 0.999153020450726 +1646404259.22393 49.4521078901845 -2.3193016995313 -0.958410526982411 0.000261297688922557 0.0263152610340228 -0.047405851392728 0.99852898005714 +1646404259.3242 49.5864546394099 -2.33640395555172 -0.971352404865999 0.00464542123537642 0.0134542643105097 -0.0610725842511628 0.998031834305041 +1646404259.42487 49.7229846010781 -2.35354338751854 -0.971840100689225 0.00507598008673563 0.018669087698785 -0.0701614299942074 0.997348020167392 +1646404259.52542 49.8662052154769 -2.36570905132101 -0.958163879260485 -0.000747902458710427 0.0281406582874383 -0.0695159489546179 0.997183572284459 +1646404259.62589 50.0120052604569 -2.36712622274356 -0.949326851380741 0.00687181391591237 0.036802638751898 -0.0679416256782434 0.996986599435817 +1646404259.72628 50.151530648977 -2.3664456153956 -0.955691675194858 -0.0122793640596164 0.046669902922421 -0.0608782325646069 0.99697792261379 +1646404259.82663 50.2954204146682 -2.35425051494149 -0.967318861203932 -0.0260514371048776 0.0356093124716385 -0.0455672016860952 0.997986437593498 +1646404259.92656 50.4432980623304 -2.33625033143344 -0.97217246417081 -0.0290545462111733 0.0221017230868792 -0.0275193538791442 0.998954469604658 +1646404260.02585 50.5889173454074 -2.31894538701972 -0.963379756198431 -0.0329694240920254 0.030721225390902 -0.0168077823834033 0.998842691236647 +1646404260.12487 50.7403198333052 -2.30880547424561 -0.947065602236728 -0.0394670367792111 0.0309551780686407 -0.0220950856160898 0.998496838828356 +1646404260.22394 50.8869765420506 -2.30613091530305 -0.944797024672298 -0.0261436397296743 0.0334099077846128 -0.036665314939468 0.998426733838739 +1646404260.32366 51.0332538770092 -2.31911891257986 -0.952812095223299 -0.0091985190280572 0.0126965632389341 -0.0547181245336443 0.998378741448917 +1646404260.42412 51.1728888944051 -2.34254042033655 -0.959307059540549 -0.0140171423649037 0.00708178288820586 -0.0661042993584001 0.997689124766514 +1646404260.52484 51.3131301749311 -2.36153530062453 -0.948000467143782 -0.00944050570903573 0.0173640740085103 -0.0746028800280281 0.997017440207191 +1646404260.62546 51.4442953070738 -2.37737842712044 -0.932868062339207 -0.00668586375554104 0.0471641876016756 -0.077603229034533 0.995845659465924 +1646404260.72555 51.5610013590653 -2.39798958860535 -0.928162302361394 -0.0093868575875481 0.0758507522079847 -0.0904057286511542 0.992967952413953 +1646404260.82528 51.6672109344958 -2.42137323295633 -0.936665430489955 -0.0113035976966739 0.0669032410466202 -0.11341380243657 0.991228275642618 +1646404260.92489 51.7568444197207 -2.4496744416586 -0.947934869080675 -0.0154888072177635 0.0683572219638104 -0.148735310273923 0.986389980957872 +1646404261.02446 51.832595335543 -2.48575819013059 -0.948118806851654 -0.034223862667759 0.092658835819527 -0.199881284817677 0.974828466627998 +1646404261.12416 51.8872794769166 -2.5200977679326 -0.930834780052598 -0.0216503058266972 0.104771475968306 -0.263203370531556 0.95878996022166 +1646404261.22413 51.9128071117362 -2.55769372854537 -0.929306990289508 -0.0110989171447804 0.0958246432964198 -0.33092638973585 0.938713042602324 +1646404261.3248 51.9151664199654 -2.59882879447184 -0.937760098066039 -0.0122977672824087 0.0775009669501148 -0.394008486206715 0.915750881975414 +1646404261.42558 51.9008722674469 -2.63352615410082 -0.940756163022015 -0.000985305940672218 0.061673223329519 -0.452929014950338 0.889410338433536 +1646404261.52671 51.8760182063742 -2.65467902640788 -0.945033888467744 0.0014530703476127 0.0588870069314088 -0.489858736330406 0.869809535152376 +1646404261.62749 51.8536748115958 -2.66417972083082 -0.94666277340548 0.00348557188808575 0.0568603001308521 -0.517323547590818 0.853891740307682 +1646404261.72757 51.8336709998243 -2.67101639929202 -0.945717671977622 0.00149916831669694 0.0437713494084641 -0.531247966825289 0.846083576964655 +1646404261.82732 51.8188381960951 -2.67064768774183 -0.946293380462605 0.00233875468037997 0.0337950811726684 -0.526649869837427 0.849407050427112 +1646404261.92679 51.8111372045906 -2.66197616288975 -0.950305793668164 0.0177201986916842 0.0277503671428117 -0.499794006630415 0.865518262440528 +1646404262.02582 51.8076079275006 -2.65042078090156 -0.953438732170198 0.0174487662434752 0.0311337968474607 -0.447947966109581 0.893346991324601 +1646404262.12504 51.8108089089652 -2.63073851169855 -0.952756749624118 0.0178217147072473 0.0400266356181178 -0.383602252228231 0.922458436468225 +1646404262.22381 51.8184846238467 -2.60179194942157 -0.946389217662532 0.0207180592840097 0.0342955494310177 -0.309149185913257 0.950169120818965 +1646404262.32238 51.8296327570162 -2.56555348628582 -0.936972883498618 0.0227299120463955 0.0232783473408818 -0.24146424323315 0.96986416001586 +1646404262.42086 51.8324883849553 -2.5205732938997 -0.932795101801246 0.0137026608453329 0.02876422817435 -0.177104367556539 0.983676216676848 +1646404262.51993 51.8303814417294 -2.46567508807783 -0.924690555449871 0.0053850596044297 0.0304676511445342 -0.117677613208098 0.992569747028602 +1646404262.61948 51.8224117510815 -2.40183143458037 -0.909891269659636 -0.000566022062290508 0.0295454055268352 -0.0592451220257432 0.997805975201301 +1646404262.72023 51.8090026496963 -2.33245980555483 -0.881267949125322 -0.0180845623333474 0.0250919994920416 0.00448908711105035 0.999511474803365 +1646404262.82178 51.792416519008 -2.25701569649716 -0.837079312312581 -0.036295765304889 0.0124474897251356 0.0757359257817584 0.99638935510494 +1646404262.92365 51.7736392213838 -2.17559153116564 -0.778093793198003 -0.0412119577008772 -0.0216075669229862 0.150597559607962 0.987499398801964 +1646404263.02411 51.7497154828731 -2.09755243108908 -0.715831419900546 -0.0187488732565964 -0.0396873811243911 0.215695948920118 0.975473551230646 +1646404263.12396 51.7206940290737 -2.02833935866404 -0.653109944186874 -0.00210509670893159 -0.0491716476950461 0.271134165007254 0.961282467434314 +1646404263.22393 51.70302201382 -1.97114023086065 -0.578905286942757 -0.000881990693645528 -0.0418085922440064 0.310758515097898 0.949568538337872 +1646404263.32767 51.7015701676415 -1.9223063502183 -0.483532774592119 0.00238966036997533 -0.0397858868342456 0.344526151336597 0.937930223298783 +1646404263.42737 51.7183091335163 -1.88592878240834 -0.386296305168213 -0.00445443440427138 -0.0500131893845591 0.377394926484631 0.924690168848661 +1646404263.52618 51.731796151592 -1.86014035191472 -0.302327298766119 0.00522579004570319 -0.0511878066317908 0.407600963481257 0.911709358370176 +1646404263.62541 51.7435874811722 -1.84618217089992 -0.232518788407091 0.0105056849180632 -0.0365099789471909 0.432608523024366 0.900781059874339 +1646404263.7251 51.7578290719003 -1.84251786302462 -0.171280925473742 -0.0149710370868953 -0.0292530052608267 0.451826464618021 0.891500406955888 +1646404263.82965 51.7744500013901 -1.83385415205734 -0.117606976182229 -0.0206779861475074 -0.0280367683780633 0.46180611555643 0.886296492231838 +1646404263.92987 51.7940046442037 -1.82630486535301 -0.0819620792854517 -0.0269014710962693 -0.0268495189624873 0.469473826144147 0.882127961664233 +1646404264.03019 51.8106791995375 -1.82166088712528 -0.0612555884263962 -0.0292912441125432 -0.019947631933397 0.476030145717031 0.878714638188754 +1646404264.13041 51.827854696166 -1.81900073652613 -0.0523632938148917 -0.0299299144822355 -0.0228965704804034 0.478416357199793 0.877324191187604 +1646404264.2305 51.8409917277296 -1.81818848530916 -0.0449656685343009 -0.0342753006802805 -0.0353202504229638 0.475060291985577 0.878575780824794 +1646404264.33048 51.8482594089321 -1.81619792537441 -0.0388078802943402 -0.014436094033419 -0.0371870388559556 0.465428126091272 0.884186282846173 +1646404264.43057 51.8486194580972 -1.82298254748799 -0.0333863312350373 -0.00578039496286586 -0.0442794497133859 0.452928747755742 0.890427687588133 +1646404264.53057 51.8512726279695 -1.83828886291253 -0.0328967534963358 0.00141965549416155 -0.0349597768706603 0.432544024867738 0.900933663002238 +1646404264.63093 51.8599028458673 -1.85141737890583 -0.0313806457756876 -0.00429138071476999 -0.0330041463422892 0.416887971076886 0.908348352751937 +1646404264.73172 51.864180261329 -1.85353383088922 -0.0240810035346126 -0.0147772257393025 -0.027651593891971 0.415864621233407 0.908885933305748 +1646404264.83253 51.8650789713087 -1.84654347871624 -0.0101844576532215 -0.0360427795120804 -0.0251780980262852 0.432027771168385 0.90078798080574 +1646404264.93294 51.8507543918925 -1.8310409879668 0.00548859500817121 -0.0481265265719289 -0.000830333591235473 0.465324420278299 0.883830488203986 +1646404265.03213 51.8380596072276 -1.81077634272303 0.0221545572936076 -0.0593361919514974 0.00840995722143874 0.49585970755104 0.866332291543844 +1646404265.13025 51.8288779036958 -1.78264844065822 0.0460839791753494 -0.0490789991715456 -0.00932389729790206 0.514363775135334 0.85611577698814 +1646404265.22863 51.8213011693257 -1.75570613757407 0.0734141851477834 -0.0278250129040619 -0.0338610317711899 0.533564882467748 0.844622824331334 +1646404265.3273 51.8158264842082 -1.74075660142917 0.0939474917525091 -0.0278637762550631 -0.0550011720903793 0.543997718505497 0.836818357412341 +1646404265.42652 51.8138496197401 -1.73498319711608 0.107758308439522 -0.0391086254390226 -0.069378168596167 0.549995531276135 0.831361594442982 +1646404265.52627 51.8070774528513 -1.73136737820986 0.115555207889113 -0.0388041840180125 -0.0712445347756656 0.556157949338304 0.827107482105616 +1646404265.62644 51.7997808161156 -1.72460697359457 0.124912862960082 -0.0297000874326267 -0.0792613130426354 0.560845742199222 0.823582177149457 +1646404265.72666 51.7965669301094 -1.71873430535366 0.137800416104357 -0.0109910098079931 -0.0965204684550784 0.558154162727019 0.82403090203165 +1646404265.82714 51.7947792580652 -1.72062199251988 0.145843271176947 -0.000846307501292549 -0.101886197417382 0.553375895769682 0.826676239237906 +1646404265.92794 51.794162350975 -1.72547845983846 0.146126270306233 -0.000867293159309064 -0.0926861812686499 0.553918271732017 0.827395351597898 +1646404266.02861 51.7917051310924 -1.7277509144902 0.148398507666819 -0.0026784765136375 -0.0871491938167859 0.553789046722778 0.828079425846645 +1646404266.12907 51.7913885520613 -1.72927202915891 0.148329603091201 -0.00852555465658361 -0.0829477813111401 0.551847189462924 0.82976602724817 +1646404266.22936 51.7923669347712 -1.73036430252856 0.149075384818534 -0.0182769730455461 -0.0844302666268485 0.547167633155128 0.832553339769296 +1646404266.32978 51.7927204885672 -1.73138881745732 0.150645442155098 -0.0222266570699712 -0.0809934201681421 0.547067549577765 0.832864417419739 +1646404266.43008 51.7933978440011 -1.7309061125236 0.150910239306291 -0.0248218668725188 -0.0798674865810737 0.54782659332243 0.832400794786324 +1646404266.53019 51.7934338363546 -1.7324276530333 0.152034555755463 -0.0304732857129207 -0.0794521003440828 0.546756215012149 0.832956411797363 +1646404266.63023 51.7916277131713 -1.73486001351139 0.153387725698549 -0.0363330363192694 -0.0755153705532523 0.545053803183401 0.834202428021708 +1646404266.73021 51.7898532141151 -1.73843261505173 0.154648662719546 -0.0451719583070965 -0.0701956872936508 0.540636764396735 0.837104502825469 +1646404266.83033 51.7873009137679 -1.73878952650147 0.153646523208275 -0.0438836079739602 -0.065027299797294 0.540284081423295 0.837817874357441 +1646404266.93045 51.786372562475 -1.73856470689607 0.153293474105105 -0.0428412665889613 -0.0630848051610654 0.540375630902289 0.837961282376322 +1646404267.03053 51.7822415428546 -1.73805230175247 0.154473135809028 -0.0397875913270826 -0.0574134887798329 0.540619457058421 0.838362237658845 +1646404267.13057 51.7780628857548 -1.73815856825191 0.154887849823798 -0.0346306755953953 -0.0470062276910457 0.54098736880227 0.839001667258434 +1646404267.23059 51.7736044866914 -1.73824698195638 0.15381433649486 -0.0307347608688917 -0.038976272376643 0.541269295213283 0.839382972620507 +1646404267.33059 51.7707954424392 -1.73752927639976 0.153873884937312 -0.0292909943779104 -0.0361692843964461 0.541381026739678 0.83948818002451 +1646404267.4306 51.7679782838052 -1.73744657476154 0.153478534278884 -0.0271737451253497 -0.0318480198712607 0.541458685109745 0.839684335643662 +1646404267.53062 51.7664242090459 -1.73782813114862 0.15321065554381 -0.0248744145806166 -0.0269847337974596 0.541974585818793 0.839593137160891 +1646404267.63062 51.7624730710732 -1.73794122785496 0.15271326486225 -0.0231884275663132 -0.0234054457007055 0.542426172959982 0.839457163187323 +1646404267.73059 51.7591089132514 -1.73828480970072 0.153385036607482 -0.0184886501184094 -0.0141552208679068 0.542726253006229 0.839586811376147 +1646404267.83059 51.7521959578883 -1.73835845825275 0.154420122233358 -0.0102155930845304 0.00213010525053402 0.543036263544735 0.839644401389596 +1646404267.93061 51.7518918778858 -1.73762642291519 0.155934811740327 -0.00865996757070245 0.0047976742818592 0.543747538639071 0.839190444122834 +1646404268.03058 51.7530261449311 -1.73727412070172 0.156528366325031 -0.00866540687604281 0.00499838072454871 0.543731719473254 0.839199466248895 +1646404268.13055 51.7536596574457 -1.7366915794065 0.157468508382641 -0.00857118631375512 0.00490839224365152 0.543725387858024 0.839205067340138 +1646404268.23055 51.7541455016758 -1.73649844578897 0.157897002402587 -0.00860666500356821 0.00487991950291774 0.543659475203506 0.839247571771631 +1646404268.33055 51.7549835716994 -1.73630421167724 0.1579367444139 -0.0086263223114848 0.00482910044460219 0.543599868547617 0.83928627372742 +1646404268.43055 51.7582136371237 -1.73617411520458 0.15808805871246 -0.008638251767337 0.00481644970164243 0.543603903284158 0.839283610439805 +1646404268.53056 51.7602352318056 -1.73639061858655 0.15791190930172 -0.00878016958113917 0.00486161080048443 0.543600947549608 0.839283791804471 +1646404268.63057 51.7604516764477 -1.73595705169404 0.157240415689804 -0.00878054133562433 0.0049452525322057 0.543699462944224 0.839219482951499 +1646404268.73056 51.7619419253441 -1.73611035106249 0.157123547795537 -0.00887767179300597 0.00500953163176981 0.543802686255528 0.839151196124756 +1646404268.83058 51.7637847059945 -1.73585557632533 0.156795685068339 -0.00893123483660365 0.00501495445715727 0.543805286155489 0.839148910519107 +1646404268.9306 51.7660283549253 -1.73622355749946 0.157096535533989 -0.00895233879606778 0.0050168354697559 0.543826737837875 0.839134772372433 +1646404269.03062 51.7695036048102 -1.73676146640071 0.157062746536389 -0.00906622061234386 0.00509969331062607 0.543810580216599 0.839143521464833 +1646404269.13061 51.7735497942352 -1.73705506885851 0.156975978150213 -0.00905694110978173 0.00509651868981433 0.543791298590928 0.839156136181903 +1646404269.23055 51.7770232090671 -1.73752883995942 0.15708395107823 -0.00901360949097988 0.00507498869398581 0.54378052080907 0.839163717353346 +1646404269.3305 51.7812483567184 -1.73786203086239 0.156812134868855 -0.00896427336045473 0.00502174587210482 0.543785859087184 0.839161106896822 +1646404269.43045 51.7836415345072 -1.73844492341501 0.156835824494232 -0.00893717116245581 0.00506526600925189 0.543820012704286 0.839139001497456 +1646404269.53042 51.7885877642653 -1.73927956049064 0.156781366966387 -0.00890664010116855 0.00502629837167461 0.543793540346264 0.839156715735763 +1646404269.63039 51.7929092430141 -1.73974658646114 0.156537651550613 -0.00888389585625174 0.00499267179226303 0.54383849149312 0.839128026461545 +1646404269.73038 51.7976048503294 -1.73988864831853 0.156702578875032 -0.00879500699379465 0.00497702977230211 0.543852713299028 0.839119838440183 +1646404269.83038 51.802728087025 -1.74077541657813 0.15669314070203 -0.00872318538400812 0.00492889778789648 0.54381063383674 0.839148143374818 +1646404269.93038 51.8076061961917 -1.74102690569322 0.156806804083292 -0.00864990688572369 0.0048923018666985 0.543785788216098 0.83916521676454 +1646404270.03038 51.812416975194 -1.74127281200316 0.15681522925052 -0.00851150173486575 0.00477917991898177 0.543791192219926 0.839163782012497 +1646404270.13039 51.8198187847222 -1.74180251594193 0.156425252679436 -0.00857244667538166 0.00479994309868697 0.543788861845088 0.839164553253674 +1646404270.2304 51.8257594451827 -1.7418771256971 0.155717097793433 -0.00845862982925799 0.00474490632639096 0.543777540662937 0.839173357367774 +1646404270.33042 51.8316477944608 -1.74188776572419 0.156086717679634 -0.0084785242332592 0.00470030951933207 0.54376449953673 0.839181857978821 +1646404270.43044 51.8386453329734 -1.74213265901741 0.156417817854966 -0.00848433822577057 0.00471818053780494 0.543800365458307 0.839158457804403 +1646404270.53045 51.8442175574304 -1.74207484996297 0.156211793521437 -0.00836526401855625 0.0046224394106908 0.543790605532148 0.839166510739521 +1646404270.63046 51.8502132646798 -1.74253002383372 0.156987981722148 -0.00837739674800978 0.00455295845708259 0.543796237887746 0.839163119692541 +1646404270.73045 51.8561120038399 -1.74262244225534 0.157119821196296 -0.00833345307974555 0.00451383127044722 0.543805483724254 0.839157777035063 +1646404270.8304 51.8616286941022 -1.74213558975814 0.156789720251869 -0.00832765161312702 0.00451002668353593 0.543785178007953 0.839171013594222 +1646404270.93033 51.8667364311607 -1.74204758191688 0.15674723255529 -0.00832843139627378 0.0045276109797114 0.543770303777327 0.839180549523867 +1646404271.03025 51.872312929037 -1.74210171313099 0.156743536050031 -0.00832678591786543 0.00452187157819093 0.543813792371645 0.839152415559921 +1646404271.13019 51.876774116997 -1.74209091326214 0.156578388708196 -0.00844107890559808 0.00459172649122862 0.54375674029221 0.839187864319726 +1646404271.23018 51.8807000292712 -1.74275531808186 0.156862073897156 -0.00839970630622661 0.00457792389343474 0.543826658466769 0.839143046856515 +1646404271.32855 51.8871425082318 -1.74310257192769 0.156697110441593 -0.00839134008146384 0.00456677504354637 0.54385769936023 0.839123073704869 +1646404271.43019 51.8923182593301 -1.74357515117019 0.156768834387585 -0.00844768931821423 0.00464319158381383 0.543831445183131 0.83913910440826 +1646404271.5302 51.8964406274209 -1.74377701091353 0.156245447281964 -0.00851179960069928 0.00472654359561677 0.543817475495221 0.839147044563211 +1646404271.63021 51.9016187173165 -1.7437852356838 0.155867407597015 -0.00851721673049878 0.00477283211381951 0.543782796032462 0.839169200955247 +1646404271.73022 51.9066690764697 -1.74409636077156 0.155408464780457 -0.00858572930042206 0.00481732728943028 0.543764960804218 0.839179805531403 +1646404271.83022 51.9158177992141 -1.74491629128101 0.155511606206471 -0.00862409949787205 0.00481510625054693 0.543760897267204 0.839182057877063 +1646404271.93021 51.925249371883 -1.74508798330973 0.154991693759775 -0.00871878005803403 0.0048731522093918 0.54380381319264 0.839152934821154 +1646404272.0302 51.9356086888728 -1.74547677074327 0.154674580518232 -0.0087211655766196 0.0048504573567587 0.543823438452448 0.839140323261932 +1646404272.13019 51.9466705671745 -1.74606243210231 0.154676313683134 -0.00870885414520395 0.00481834427591428 0.543881992451161 0.839102686031478 +1646404272.22993 51.9571976167324 -1.74753888138661 0.154343650063077 -0.00396498094087028 0.0047884718635908 0.537017720159328 0.843548052987023 +1646404272.32935 51.9636181905581 -1.75377296393838 0.145456373956571 0.00759746962779265 -0.00520058389106812 0.515862051105712 0.856622190123173 +1646404272.42924 51.9707870403605 -1.7727098979359 0.114404974363499 -0.00845024238531474 -0.0216060443044498 0.494456327868601 0.868892808166699 +1646404272.52983 51.9700286706693 -1.79074896639761 0.0587245670970915 -0.00291506139916546 -0.0481597327089877 0.484614533967019 0.873396185033079 +1646404272.63048 51.9675375785683 -1.80555368075086 -0.0137070425407491 0.00723454037612692 -0.0737207369450353 0.480955172315254 0.873610345974109 +1646404272.73042 51.977883701613 -1.81474707877223 -0.0977185285395621 0.00624234673446263 -0.109634253196792 0.467381342611041 0.877209236278495 +1646404272.83004 51.9968081808702 -1.81757376228855 -0.196924724985179 0.00434732416867752 -0.128222491232602 0.447253948050804 0.885157612782953 +1646404272.92966 52.0227315079214 -1.81921416378568 -0.300490237582219 -0.00363148237976216 -0.119059590262648 0.424635999456958 0.897494230771083 +1646404273.02516 52.0545501482916 -1.82028448996805 -0.395715246619382 -0.0130682366941433 -0.099655014967674 0.405359995534477 0.908615085281859 +1646404273.11789 52.0852155376225 -1.82031322265892 -0.481173495388721 -0.017821564207908 -0.0666368820232406 0.385875933101316 0.919968304919558 +1646404273.21813 52.1303919148374 -1.81621853244553 -0.557892773222525 -0.0193940452848727 -0.0536502017786304 0.365628125250532 0.929011087599257 +1646404273.32117 52.1860103018597 -1.80956184520067 -0.620072055003666 -0.0190952088553245 -0.0533294844363076 0.349101628726569 0.935371258864073 +1646404273.4206 52.2435794479922 -1.80021487404849 -0.666067239034088 -0.01436947795157 -0.0451049550008521 0.343621963429173 0.937914179115993 +1646404273.51872 52.3091606950904 -1.79258204672013 -0.69435026026979 -0.0190509706170305 -0.0450092874125824 0.349896299039185 0.935512589163725 +1646404273.61842 52.3829511234346 -1.78522720401207 -0.708756748832437 -0.0163965656774777 -0.0466754274742077 0.353061645244657 0.934291192167192 +1646404273.7174 52.4704490444807 -1.78564075325706 -0.709803011380631 -0.0197221740901654 -0.0494243329009688 0.346885211482946 0.936396775528866 +1646404273.81722 52.5717507127463 -1.79329425696619 -0.703880180943403 -0.0278192292959096 -0.0367286631228519 0.342600185770564 0.938350791813243 +1646404273.91693 52.6804357243176 -1.80015680187787 -0.690442015086578 -0.0240985371430394 -0.0320012936911787 0.347300881671759 0.936897686676433 +1646404274.01719 52.7950508876011 -1.80829793017179 -0.688726103974987 -0.0279890442941649 -0.0386305042819338 0.358729174351724 0.932221903308075 +1646404274.11747 52.8997761409231 -1.8160488063341 -0.707361602578171 -0.0342824491298698 -0.0259230344003301 0.378858585456874 0.924455992567916 +1646404274.2168 53.0158501453764 -1.82278566092549 -0.733870419713869 -0.0325691873046767 -0.0315215595125462 0.38258509947083 0.922807824515527 +1646404274.31684 53.1367061495084 -1.82490451746615 -0.749578197977079 -0.0279357815828173 -0.0225534414013802 0.387250586852958 0.921275158337793 +1646404274.41625 53.2629533374484 -1.82061484330267 -0.75285232694175 -0.0260131080722147 -0.00147562800421239 0.392009354012355 0.919592196083246 +1646404274.51607 53.4025361552786 -1.82002887961096 -0.745730984892174 -0.0194702973565877 0.012265081746108 0.382435481324528 0.923695608907318 +1646404274.61619 53.5384176926651 -1.82065407386255 -0.751268771089806 -0.0118145843354705 0.0163834722079566 0.372952791553402 0.927630428946729 +1646404274.71664 53.6721077943054 -1.82004171027236 -0.768588341888823 0.00758118362123043 0.00349887593060157 0.373534811605977 0.927578583215777 +1646404274.81689 53.8000738719645 -1.82961172786936 -0.778341443583836 0.0113941679003075 -0.00884825216252726 0.368306200675653 0.929592611801197 +1646404274.91733 53.9264883687373 -1.84687005779288 -0.78091638498368 0.00298827942972803 0.0108327386016279 0.367822110612149 0.929828272803769 +1646404275.01778 54.0567725172103 -1.86168895125997 -0.76699399008287 -0.000912981125054233 0.0226593666163267 0.372472807295686 0.92776598741022 +1646404275.11788 54.1885549805547 -1.87272859953216 -0.760903643926694 0.00273402260347917 0.0290879265151249 0.381006830785615 0.92411049801749 +1646404275.21807 54.3162610775549 -1.88817182990992 -0.774759757728676 0.000831668839694202 0.0263323767384901 0.388959908110306 0.920877898608193 +1646404275.31755 54.4435234850663 -1.90305881217764 -0.796452314473659 -0.00603643902452417 0.0147672854140688 0.387308968253831 0.921811939494999 +1646404275.41731 54.5589605634652 -1.9143146353402 -0.808199774917153 -0.00551763560109925 0.0167325445918937 0.38208949853686 0.923957354403698 +1646404275.5171 54.6766991826825 -1.92409499739914 -0.802879397129036 -0.0108566832045914 0.0366600250197688 0.374479533643349 0.926446573676852 +1646404275.61683 54.809220452909 -1.93155197826819 -0.781670215311401 -0.00855604325545342 0.0366392684920813 0.355518067332072 0.933911806290411 +1646404275.71682 54.9434889752125 -1.94493611541712 -0.770658440471458 -0.00465766031229994 0.0370236551842492 0.323507550132082 0.945489513513886 +1646404275.81692 55.0737814148167 -1.96637474944309 -0.776644305462598 -0.0038860100686758 0.0326038193786026 0.300647880275919 0.953169838996831 +1646404275.9173 55.1988324741883 -1.99531797193086 -0.78764368018143 -0.00261027786178193 0.0265437147858869 0.26666705963239 0.963419585103935 +1646404276.01755 55.3283260452671 -2.03098989186416 -0.790754729454479 -0.00437084158664823 0.0215266431540407 0.224426135922785 0.974243505953765 +1646404276.11791 55.4590255376673 -2.07346022408535 -0.782097434885775 -0.00817235621361227 0.0348805196141696 0.188491955859573 0.98142108420472 +1646404276.2222 55.5977211489353 -2.1169624392875 -0.772533370110468 -0.00607890862016096 0.0402121378567542 0.158809518738149 0.986471270538128 +1646404276.32313 55.734764841803 -2.16007908462174 -0.77688751636959 0.00251929864948074 0.0319527066637466 0.128697495286909 0.991165794596457 +1646404276.42303 55.8720112669931 -2.20536742344248 -0.794263842604907 0.000298537373802079 0.0361181141139862 0.0962140744083366 0.994705104336962 +1646404276.523 56.0087399656298 -2.24408842323782 -0.809650090177284 0.0144242273259113 0.0364532000754366 0.0670883722461591 0.99697655748751 +1646404276.62291 56.148405094556 -2.27961984876702 -0.811036651676262 0.0206479228548879 0.0447861064288385 0.0457755994893771 0.997733663080527 +1646404276.72249 56.2915159094372 -2.31181394793319 -0.799718330147638 0.0131522316854251 0.0528070442007179 0.0195901916467087 0.998325928379955 +1646404276.82149 56.43418912308 -2.34504988301355 -0.795202163344787 -0.00109319684354156 0.0527745715300353 -0.0129710380590396 0.998521608024649 +1646404276.92125 56.5718920979777 -2.37006442157852 -0.803471297862929 0.0114642539927901 0.0424911576710616 -0.0379886262036027 0.998308537817493 +1646404277.02174 56.7027751894662 -2.39431589105754 -0.812439888484787 0.0168996067755502 0.0313001544005204 -0.054850509279907 0.997860774485622 +1646404277.12227 56.836550657245 -2.41603352572847 -0.811500144089947 0.0122253812584283 0.0265192885763389 -0.0697138626139177 0.997139531232171 +1646404277.22306 56.9693713864776 -2.42911973144392 -0.794302886949484 0.0104837008419586 0.0398087615068683 -0.0683847137129652 0.99680935261178 +1646404277.32311 57.1070569559217 -2.43572338882271 -0.774180131195817 0.00502318783072269 0.0449667042798768 -0.0548828147570038 0.997467112106734 +1646404277.42297 57.2457416014596 -2.43526968585425 -0.769496300132853 -0.00050827359688191 0.0281899589170175 -0.0397034770958811 0.998813647173826 +1646404277.52219 57.376112898034 -2.42855026579928 -0.782448882089406 -0.00720532720095955 0.0180948968126612 -0.0273247665285861 0.999436848982166 +1646404277.62173 57.5062128073749 -2.41471361675777 -0.79729174989573 -0.0137422750124756 0.0132079877184433 -0.00655080223277812 0.999796872333573 +1646404277.72144 57.6389546071574 -2.39681538791339 -0.793142220065542 -0.00834133359489608 0.0260875497826984 0.0114090401543192 0.999559750941847 +1646404277.82062 57.7801660777581 -2.38783084649362 -0.772431635388695 0.00144027037124906 0.0350622485097053 0.00838777552516146 0.999348892815926 +1646404277.91934 57.9293893521389 -2.39232666139761 -0.763557438971694 0.0109855135119261 0.0326728089469868 -0.0152936009796641 0.999288702936966 +1646404278.01933 58.0822742267245 -2.40574611085409 -0.769671764159825 0.0186158921152886 0.0203441330359185 -0.0321432996528307 0.999102784051357 +1646404278.12064 58.2291625845837 -2.42466691321609 -0.787655525421164 0.016785433597027 0.0174701132713355 -0.0458799401427966 0.998653130698401 +1646404278.22222 58.3803737279565 -2.44206012173841 -0.802081515028818 0.00957782941770065 0.0345158375216834 -0.0547908661019266 0.997855141358504 +1646404278.32343 58.5362197225022 -2.45500925210325 -0.805519199972562 0.00409227748427197 0.0653986066965313 -0.0507276845431117 0.99656057393819 +1646404278.42413 58.6953587445301 -2.46298848691239 -0.806769432125126 -0.000845188316300412 0.068554713492271 -0.0380879289017663 0.996919679104918 +1646404278.52428 58.848152479013 -2.46753096958853 -0.816995313059938 -0.0100227476747545 0.0654703300184995 -0.022406328001048 0.997552573492647 +1646404278.62404 58.9897403392045 -2.46606089891032 -0.823923699697425 -0.0188174047701604 0.0506802082376322 -0.00933630903898776 0.998493993524353 +1646404278.72363 59.123021400728 -2.45938749130453 -0.821738028088727 -0.0117990927133625 0.0392899380837277 0.0039832766633521 0.99915024680151 +1646404278.82289 59.2597720824858 -2.45482564473356 -0.805102468631066 -0.00477612038431858 0.0353353190765299 0.0137289381931844 0.999269793477166 +1646404278.92161 59.396730461613 -2.45917363517968 -0.783513522228378 0.00211468670594696 0.0380913284133347 0.00734515796696493 0.999245028736326 +1646404279.02025 59.5388128506044 -2.47214249275471 -0.774552359340034 0.0115993984103952 0.0396984340764042 -0.00882678806919137 0.999105387884961 +1646404279.12022 59.6842559490625 -2.4941797736601 -0.779847065795309 0.0160237627823883 0.013083108024437 -0.0216123490108564 0.999552388662508 +1646404279.22093 59.8255963930908 -2.52118126057968 -0.790822621719782 0.0116049378474215 0.003500040508924 -0.0408297984596117 0.999092589649088 +1646404279.32165 59.9636805555169 -2.54527964916494 -0.791583315393778 0.00682761216119639 0.0253828393923092 -0.0486849892597184 0.998468260385537 +1646404279.42237 60.10952611305 -2.56358207867866 -0.77908479184829 0.00446208243147955 0.0376682541341476 -0.0437132400846343 0.998323767668657 +1646404279.52305 60.2548903699001 -2.57264848832162 -0.774394671559921 0.00801954025252798 0.0359086326485895 -0.0291405114266557 0.998897936562699 +1646404279.62286 60.3983882055845 -2.57584233673993 -0.786676475604368 0.00230798848533267 0.0299333119887435 -0.0109180736253587 0.999489602592656 +1646404279.72232 60.5391137731687 -2.57342248345756 -0.798938223950358 0.00430264923636001 0.0152510062155501 0.00421905050177276 0.999865537775856 +1646404279.82199 60.6807003221957 -2.57089392328705 -0.802708981916229 0.00356598327126496 0.0200849350963786 0.0160877813110426 0.999662474257161 +1646404279.92096 60.826150588809 -2.5715784579896 -0.78949259787723 0.00429649365406863 0.0338082337875664 0.0180510869270767 0.999256074152754 +1646404280.01974 60.9706578782849 -2.58493061911592 -0.775728400038679 -0.00456925452891727 0.0317458813559712 0.00244259303139987 0.999482543453984 +1646404280.11896 61.1127567448895 -2.60312395576188 -0.781813778837221 -0.00261904300906106 0.0322759451785339 -0.0247500033957417 0.999169075436404 +1646404280.21978 61.2552708522514 -2.62121649420102 -0.798428864848876 0.00170490992066837 0.0194279247011149 -0.0389922581414419 0.99904917437981 +1646404280.32084 61.3985187860344 -2.63644473687461 -0.803827831336381 0.0060848297528304 0.0198766913989949 -0.0493445283033607 0.998565475826401 +1646404280.42222 61.545469231689 -2.64717781859089 -0.796056632459841 0.020151435254754 0.0365705598131056 -0.0532268394684273 0.997709084539331 +1646404280.52307 61.6971428171437 -2.65252401544762 -0.785353608027549 0.0303829647057645 0.0442520135501673 -0.0445392087340368 0.997564480942344 +1646404280.6235 61.8495224802096 -2.65837439779212 -0.791719426588442 0.0176518359056663 0.0408179567062159 -0.0298523533564913 0.998564541779122 +1646404280.72345 61.9942640349117 -2.66007051092918 -0.809955261571122 -0.00258772324105305 0.038909189017247 -0.0170000970454365 0.99909477798599 +1646404280.82324 62.1408250638021 -2.6523406407516 -0.824542591863001 0.00249099927826367 0.0330610618505851 -0.00450024197124794 0.999440097721764 +1646404280.92312 62.2903897619297 -2.64765861522759 -0.820274284210113 0.00817095980718551 0.038081601034848 0.00365672451996014 0.999234534753587 +1646404281.02206 62.4390780230896 -2.64916388651166 -0.805662327902448 0.00581945592490035 0.0524146248649284 -0.000825529556748097 0.9986081110896 +1646404281.12123 62.5898769696548 -2.65738107037419 -0.798192425766229 -0.000386484293253735 0.0471877542617154 -0.0208954798895378 0.998667384767218 +1646404281.22127 62.7471846289319 -2.66304135101148 -0.804343925131366 0.0109939989016829 0.0266764969728872 -0.0351819256319648 0.998964327994855 +1646404281.32201 62.8959200124432 -2.67476815017216 -0.813960664293943 0.00524359021138006 0.0320043431043723 -0.045342337388395 0.998444940507132 +1646404281.42281 63.0447351315967 -2.68439509853436 -0.809932155549804 0.00983733600225436 0.0411644180535715 -0.047062944620873 0.997994888138353 +1646404281.52342 63.1953091197957 -2.69355032924454 -0.7980533021325 0.0150020636112899 0.0498765799137985 -0.0345261440491731 0.998045695467187 +1646404281.62373 63.3468792263588 -2.69988401668098 -0.796687950521304 0.0231581385770847 0.0502861575665305 -0.0194319610237604 0.998277216942063 +1646404281.72348 63.5027589190949 -2.70834429270025 -0.807801382207015 0.00424570529675393 0.040815054380466 -0.00174208030482534 0.99915617922257 +1646404281.82301 63.6575670172291 -2.71019269662554 -0.821107227843371 -0.00525928406047627 0.0300713870534328 0.0131924104437667 0.999446852973442 +1646404281.92223 63.8093154997267 -2.70776060714012 -0.82275890880088 0.00698986005755271 0.0289767691603031 0.0204609067728469 0.999346206276594 +1646404282.02136 63.9670158653485 -2.71080155400102 -0.809233793059032 0.00750477000862948 0.0433705186939393 0.0233202153705421 0.998758651572235 +1646404282.12023 64.1225231845431 -2.72100887666863 -0.807053250618792 0.00353989774022838 0.0462838045834489 0.0112924051186009 0.998858228250581 +1646404282.21986 64.2807625038205 -2.73274045192189 -0.816575650917532 0.0256738585593429 0.0459273829296909 -0.00329928316521683 0.998609354660011 +1646404282.32031 64.4366691282023 -2.7560963297867 -0.828687558736099 0.0264129125081046 0.0311701592583989 -0.0127460241322236 0.999083739279872 +1646404282.42119 64.590746618452 -2.77871533024546 -0.827275888512697 0.0319183190172645 0.0346943514577894 -0.0210651862385391 0.99866600063122 +1646404282.52179 64.7440071473196 -2.79936866240773 -0.814410355536909 0.0404070134287271 0.0542485374185203 -0.0122876425978638 0.997633892413993 +1646404282.62223 64.8987350991395 -2.81519236608258 -0.805995949003131 0.0465919316286435 0.0512963136224071 -0.00509126260939579 0.99758305877801 +1646404282.72271 65.050789193563 -2.82692073742852 -0.813610236945685 0.0216621307097224 0.0495280688994743 0.0111043123740158 0.998476047149298 +1646404282.82279 65.2020146060423 -2.82716551572974 -0.829209681841714 0.0122949565484432 0.0349505545091807 0.0275805941256036 0.998932732275119 +1646404282.92263 65.347391459374 -2.82121377769734 -0.839565224098858 0.0207681706708554 0.0343362072858869 0.0395570025595182 0.998411213631286 +1646404283.02192 65.4942020649238 -2.82381248074596 -0.834770378899696 0.0182754482942144 0.054746394960635 0.0436225993165031 0.997379521073757 +1646404283.12124 65.6470390863138 -2.83333336441488 -0.818764394315781 0.0111417272709119 0.0566271670209011 0.0331440563166407 0.997782890913385 +1646404283.22049 65.792893638908 -2.84620270558816 -0.825068250112365 0.0132637096499966 0.0629111271693665 0.0140364491615043 0.99783227156648 +1646404283.32051 65.9391372727435 -2.8668713638812 -0.833206739050855 0.0307976597489223 0.0423042785195927 0.00120267311514979 0.998629263415752 +1646404283.42092 66.0834153221276 -2.89619585962029 -0.836723893822341 0.0290511165184782 0.0229418540005292 -0.0146923547168665 0.999206604600322 +1646404283.52199 66.2253640975833 -2.92048687834272 -0.824873334859489 0.0230624243959682 0.0429193012683964 -0.026326087461645 0.998465320017955 +1646404283.6227 66.3734347264787 -2.93838999266631 -0.814063629148345 0.0146440428237696 0.0531703289079046 -0.0236544418553317 0.998197843873697 +1646404283.72327 66.5255734038831 -2.94543283411589 -0.817092750525472 0.0175647741134311 0.0489362415781663 -0.0181705833069593 0.998482124463336 +1646404283.82333 66.6752903706541 -2.94604062902616 -0.825896239407566 0.00995731301210174 0.0473528420466157 0.000338369329634463 0.99882853672383 +1646404283.92282 66.8217592266001 -2.94257446688868 -0.837854989688816 0.00656008302074774 0.0371823234657175 0.0184783302204826 0.99911610508724 +1646404284.02194 66.9669700049607 -2.94097669252291 -0.842652082226391 0.00877622560904901 0.0501379870954739 0.0250008298808608 0.998390764490199 +1646404284.12101 67.1151434967471 -2.94315432657051 -0.830331711417166 0.00462833746613793 0.0698699309649578 0.0221603332755844 0.99729919826918 +1646404284.21979 67.259483037937 -2.95887173788699 -0.827043784783995 -0.0127866127745041 0.0705119108968587 0.00663407401839903 0.997406918974061 +1646404284.31909 67.4014343942163 -2.9766234822137 -0.832655833402569 0.00174252148989892 0.0774219186541529 -0.0152887633332273 0.996879663673851 +1646404284.41953 67.5484029336554 -3.00220314709385 -0.841852263107389 0.0095543994898629 0.0497936262494651 -0.0310277478242584 0.998231730161015 +1646404284.52039 67.6961516037533 -3.02720947946256 -0.849175881083363 0.0139409925440428 0.0466591445408615 -0.0517127517694741 0.997473991772223 +1646404284.62156 67.848429627146 -3.04750889480622 -0.825096691015797 0.0119783110499398 0.0654093753623109 -0.0605879762633434 0.995945395496861 +1646404284.72278 68.0021382929992 -3.05535136191392 -0.810776031726061 0.0177405611746742 0.0719985647265656 -0.0519059068636674 0.995895203321698 +1646404284.82361 68.1560797363949 -3.06140386289554 -0.816712030580239 0.00270906164391421 0.0654363205805821 -0.0270417337863941 0.997486588164319 +1646404284.9235 68.3058681132391 -3.04785222840341 -0.834705831732333 0.00609707104583693 0.053854330732931 0.00605309447916469 0.998511841108146 +1646404285.02292 68.4525767262035 -3.04115551641729 -0.840644241037681 0.0112034305742534 0.0459486609100353 0.0242153691535212 0.998587412098052 +1646404285.12175 68.5992228126951 -3.04220768814796 -0.83334240672006 0.0103524717726344 0.0607898142432746 0.0247663939957212 0.997789582297238 +1646404285.22092 68.7468654129817 -3.04963853119265 -0.815718514235973 0.0122028503631089 0.0661916077907459 0.0111192261329779 0.997670348517625 +1646404285.31995 68.8877466883134 -3.06233735049107 -0.806363979298073 0.0132273436781429 0.0697079699478777 -0.000490034422183648 0.997479621932806 +1646404285.41997 69.0294193758735 -3.07809339532702 -0.809275009685325 0.0298598779556175 0.0517830496929583 -0.0123552709129295 0.998135386975947 +1646404285.52067 69.171631244447 -3.10219664123758 -0.807322034783893 0.0342321893060034 0.0351799954093032 -0.0286984319825493 0.998382153856952 +1646404285.6214 69.3155718518386 -3.12614037875501 -0.794106611865219 0.025857432170336 0.0363114733252348 -0.0389678331124215 0.998245650172849 +1646404285.72232 69.4610117088976 -3.13855135516337 -0.774032908929788 0.0245072861892537 0.0470435443833287 -0.0328038540056712 0.998053207508424 +1646404285.823 69.6050013131104 -3.14160514803599 -0.764054673297421 0.030834452526472 0.0455351176562036 -0.0214555732577955 0.998256203573809 +1646404285.92299 69.750013079253 -3.15108310198692 -0.768053357503288 0.0011214226100137 0.0328779744724258 -0.0182252239280012 0.999292560974353 +1646404286.02282 69.8856086939105 -3.15382681057403 -0.776141729730353 -0.00703382545797693 0.0298360973742081 -0.015382948720308 0.999411675678026 +1646404286.12262 70.0207374735992 -3.15538875097629 -0.77254704221693 0.000260640921490535 0.0371758304415805 -0.0224050411642176 0.99905750776805 +1646404286.22195 70.1575139216156 -3.16267885414817 -0.752578280076535 0.000872929534920659 0.0461397314154966 -0.0408552514355655 0.998098798520996 +1646404286.32109 70.2886769265714 -3.17461568908225 -0.732412891945794 0.0106298016606129 0.0438310270208908 -0.069844716065645 0.996537788558289 +1646404286.42115 70.4151731619296 -3.1862074090043 -0.726570785689159 0.0245702211885597 0.0240936886885504 -0.0872023034286545 0.99559608108552 +1646404286.52186 70.5394001652847 -3.21003629853464 -0.725587645656255 0.021840751556059 0.00570448579020526 -0.104781885027177 0.994239003954015 +1646404286.62243 70.660953920353 -3.23826867528415 -0.71632441667105 0.0152901715105424 0.00378837480741824 -0.11872723655552 0.992801945088432 +1646404286.7226 70.7825265259092 -3.26840277759503 -0.693421332503487 0.0129851695164083 0.0155891157411601 -0.121594078833213 0.992372533293687 +1646404286.82283 70.9058331618402 -3.30011081781218 -0.661447590170489 0.0103556917742058 0.0114777779225528 -0.12236284552905 0.992365030770361 +1646404286.9226 71.0235838101916 -3.336541314834 -0.635003462686122 -0.00248876424629511 0.00456705519945304 -0.12842369024076 0.99170575466933 +1646404287.02247 71.1354799242083 -3.37851080256754 -0.612214214810874 -0.0149814655809425 -0.000978179141466741 -0.141018635618255 0.989893096886209 +1646404287.12268 71.2460327446885 -3.41903816329904 -0.580578976293921 -0.0102799842048761 -0.0100911183803234 -0.150264693653766 0.988540850494157 +1646404287.22234 71.3536038543327 -3.46423480045149 -0.537329390345817 -0.00865780008868026 -0.0176237879931345 -0.164946983263096 0.986106960378432 +1646404287.32232 71.4572990319881 -3.51294789005773 -0.488213808510211 -0.00375334540443359 -0.0228747167550249 -0.184686710360426 0.982524034692224 +1646404287.42236 71.5544504992869 -3.56598512870876 -0.434586054384063 -0.002740096194692 -0.0173945254953918 -0.204245414886465 0.978761325785546 +1646404287.5274 71.6502900984217 -3.62344706780484 -0.367668685409026 0.010257058492393 -0.0210876604162346 -0.219824926708465 0.975257455714572 +1646404287.62779 71.727499823628 -3.68319084056713 -0.298958623941972 0.0194165579242217 -0.0189746660746428 -0.229429275693736 0.972946641281201 +1646404287.72801 71.7865045551972 -3.74450261614993 -0.222319851175424 0.0259400031125917 -0.00578173949094726 -0.239214850839448 0.970602875982154 +1646404287.8282 71.8351185264331 -3.80154119630896 -0.138924743724045 0.0402843269969856 -0.00155901807887714 -0.244061739666121 0.9689213640395 +1646404287.92827 71.8753204820322 -3.84994179709744 -0.0558583841961173 0.0633884491563961 -0.0066800645466141 -0.247198225588171 0.966866236103655 +1646404288.02819 71.904079863631 -3.89258085050468 0.0186090062095227 0.0656079668840179 0.00268589962414528 -0.251788419482664 0.965552159357001 +1646404288.12798 71.9315174452288 -3.93090100572684 0.0826804410272306 0.0475823378971076 -0.019506604074046 -0.261637739088116 0.963795158217033 +1646404288.22796 71.953307467791 -3.95395850006707 0.129596235364053 0.043614635214311 -0.0304572257800791 -0.267758086381066 0.962016490591739 +1646404288.32827 71.9629285225921 -3.96359042274855 0.160378522812537 0.0418090687811487 -0.0188388149088603 -0.26213672748268 0.963940577486572 +1646404288.42847 71.9708179598725 -3.96403111769851 0.185209842569697 0.0552992077447268 -0.018154471544012 -0.253059317223796 0.965698397405723 +1646404288.5282 71.9782559644214 -3.96542669000653 0.210842888117109 0.0570457854283804 -0.0361828473438321 -0.252081937864002 0.965345159269819 +1646404288.62788 71.9812415688584 -3.96938394232346 0.229189252980509 0.0413201456993538 -0.050052628451171 -0.254611765115043 0.964862803205464 +1646404288.72776 71.9833564921935 -3.97137920526368 0.240372743834626 0.0403018046739367 -0.0558681118483538 -0.253848336808647 0.9647878215017 +1646404288.8278 71.9902807289949 -3.9756548913492 0.248677867507287 0.0411157821716767 -0.0620491844341168 -0.249544479099164 0.965498287993608 +1646404288.92746 71.9971479456545 -3.98201406957305 0.252687798150312 0.0480350251506319 -0.0621622573735836 -0.25836267605315 0.962848491580914 +1646404289.02755 72.0010067175155 -3.98616778405646 0.252616376132783 0.0513216106724319 -0.0527862226994722 -0.259878422905611 0.962830676847799 +1646404289.12756 72.0047681843651 -3.98658145775334 0.253699061021616 0.0588034105760029 -0.0489150791088954 -0.266211779891116 0.960874998211314 +1646404289.2276 72.0043361828151 -3.98933870668657 0.254182027530119 0.0602136708421914 -0.0417239959283656 -0.274192053126242 0.958880670370345 +1646404289.32779 72.0020706130841 -3.99382166745509 0.255151912464119 0.0583218565113339 -0.0381701052131196 -0.279769737689039 0.957533549278816 +1646404289.42813 72.0022798234305 -3.99725707230262 0.259903239847695 0.0577755818334508 -0.0448968443353916 -0.279932237323325 0.957227349180787 +1646404289.52832 72.0037278144353 -3.99834318778342 0.267856071009108 0.0534108352005097 -0.0527053769701532 -0.279201409001453 0.957296191955871 +1646404289.62843 72.007288502275 -3.99089773314518 0.271140547176096 0.0563735532832918 -0.0574515979199397 -0.273817880093128 0.958407588100155 +1646404289.7283 72.0107074260869 -3.98510217756965 0.27283389691334 0.0606512152230488 -0.0582556014329884 -0.268210893640572 0.95968256810581 +1646404289.82787 72.013579408663 -3.98800573718948 0.276069741973244 0.0575338260679902 -0.0643684846629711 -0.270354945538054 0.958882036782041 +1646404289.92745 72.0132892051862 -3.99133079478751 0.279528952915134 0.0593371804936018 -0.0629253893481204 -0.273793126721482 0.957891861405305 +1646404290.02741 72.015952388757 -3.99184580683398 0.281779893269671 0.0594923579155108 -0.0614874169771069 -0.273000941468384 0.958201671288722 +1646404290.12743 72.0186720249432 -3.99140865734363 0.284239512578218 0.0620612769779567 -0.0609862468379622 -0.272390635222745 0.958244445556259 +1646404290.22738 72.0187478099474 -3.99023003659224 0.285964054458193 0.0643478787613407 -0.0582877401622494 -0.274279932313539 0.957722511260836 +1646404290.32741 72.0172867845027 -3.9905642687656 0.286646256893944 0.0623774635991869 -0.0553919627133352 -0.275503627222732 0.957673500671707 +1646404290.42749 72.016707087985 -3.99081077183342 0.287046101160857 0.0608447374595812 -0.0535633559672393 -0.275484009844906 0.957881749038345 +1646404290.52753 72.0168798540147 -3.99080542349856 0.286944294636179 0.0596990271149532 -0.0521525007131248 -0.275730922390354 0.957960647035486 +1646404290.62758 72.0155087643158 -3.99086771151827 0.285730845315577 0.0582847517244761 -0.0506616209114754 -0.275739162828098 0.958125358168692 +1646404290.72761 72.015263333086 -3.99063023395637 0.284955546224718 0.057934229658603 -0.050108932939266 -0.27575198753818 0.958171989385143 +1646404290.82758 72.0153960884427 -3.9905429562131 0.284293601185989 0.0573612271740211 -0.0496581449283639 -0.275777229757671 0.958222666088909 +1646404290.92765 72.0145319525547 -3.99094942790132 0.282458619645224 0.0558155048896 -0.0478906071971961 -0.275833271965474 0.95838777393757 +1646404291.02766 72.0146635729636 -3.99083573160523 0.281644482973525 0.0552249136031287 -0.0474364241275538 -0.275898468032857 0.958425808250501 +1646404291.12769 72.0112958407879 -3.99303334277907 0.280198861637427 0.0472001512054468 -0.0389102409090256 -0.276188515579825 0.95915485858144 +1646404291.22772 72.0050784846231 -3.99653836439678 0.279741856848854 0.0342797399743243 -0.0253217639661017 -0.276362997577805 0.960107911261403 +1646404291.32777 71.999286608099 -3.99873648401293 0.27993464332794 0.0251176620282284 -0.0155368738402926 -0.276290225193559 0.960620330863336 +1646404291.4278 71.9941480392648 -4.00077780670691 0.2798759748744 0.0172103383663619 -0.00708838486645993 -0.276311090378283 0.96088799575562 +1646404291.5278 71.9882242143146 -4.00271040684387 0.280298202066939 0.00780193880881445 0.00267629830329854 -0.276308259115269 0.961033669089118 +1646404291.62781 71.9860035529377 -4.00240670357596 0.280818956622396 0.00627475346231402 0.00405572209665974 -0.276098981425506 0.961100167018531 +1646404291.72779 71.9841831446501 -4.00227959145994 0.281427002886476 0.00593691992982941 0.00394708188984919 -0.276107545960856 0.961100305165785 +1646404291.82776 71.9832972955354 -4.00186882842907 0.281402209504977 0.00560229664627217 0.00371085844240977 -0.276261654446154 0.961058969098448 +1646404291.92776 71.9832094609878 -4.00200095030495 0.280397633244522 0.00563680773327849 0.00359392584640962 -0.27623966988448 0.961065531000719 +1646404292.02778 71.9836030283515 -4.0022145955258 0.279825760804731 0.00572321423183484 0.0035426109187199 -0.276214632136914 0.961072407116236 +1646404292.12778 71.9837777870778 -4.002798566772 0.279398268416747 0.00561195905376419 0.0033876671251395 -0.276217425177622 0.961072819122081 +1646404292.22778 71.9850257371943 -4.00266276690775 0.277743975161245 0.00574929230900029 0.00336761096363716 -0.2763214397021 0.961042177427866 +1646404292.32776 71.9854718272171 -4.0021473877768 0.278949147274814 0.00568137374504644 0.00332867694051044 -0.276418864828136 0.961014699715521 +1646404292.42774 71.9857652887289 -4.0021014193842 0.279382913778228 0.00556464504007101 0.00329531461128776 -0.276460309103608 0.961003576017031 +1646404292.52773 71.9865799190808 -4.00222098102748 0.280657931777465 0.00543749880984064 0.00335277611600674 -0.276557029253474 0.960976275497734 +1646404292.62772 71.986628381818 -4.00195122230131 0.28152245310055 0.005335202857424 0.00338350157906375 -0.27653870599225 0.960982014199882 +1646404292.72773 71.9873877714753 -4.00183580460456 0.282528330834735 0.00528736910123119 0.00347521160766673 -0.276524211434768 0.960986122232078 +1646404292.82773 71.9879212457564 -4.00172303032167 0.282814376253774 0.00528756250112316 0.00350618812258076 -0.276558677612005 0.960976090319183 +1646404292.92772 71.9885094906052 -4.00222879898359 0.283020426939772 0.00522660420456503 0.00354075085227529 -0.276559668533611 0.96097601189232 +1646404293.0277 71.9887215209076 -4.00270918573647 0.283159404325614 0.00525713622818626 0.00355895937735877 -0.276566351805474 0.960973854678595 +1646404293.12766 71.9885680483197 -4.0031649482262 0.282770626937831 0.00525455536789848 0.00354272941224582 -0.276566204227558 0.96097397123718 +1646404293.22764 71.9889008190847 -4.00324142473896 0.283214940715672 0.00526207097224697 0.00353820674101609 -0.276529281749871 0.960984572215933 +1646404293.32759 71.9888196353975 -4.00355937352042 0.282971686138571 0.00529407451891472 0.0035798392398353 -0.276499494010288 0.960992813364418 +1646404293.42755 71.9889899516666 -4.00392793785684 0.282454759983614 0.00532663136214682 0.0036543317086754 -0.276515124605134 0.960987855658281 +1646404293.52752 71.9887348304973 -4.00399257911165 0.282313326243476 0.0053643115296798 0.00362541917131687 -0.276515044336835 0.96098777866997 +1646404293.62751 71.9891860575707 -4.00402934997507 0.281903005892656 0.00554683487993142 0.00360752285535297 -0.27648776150173 0.960994659788194 +1646404293.7275 71.9893784728184 -4.00350750116561 0.282140632782848 0.0055643154742287 0.00356726957883947 -0.276496226666332 0.96099227344466 +1646404293.82751 71.9896226435776 -4.00378148298409 0.282106554312839 0.00560142648075015 0.00350487003500916 -0.276480241375259 0.960996886590429 +1646404293.92752 71.9898962862499 -4.00334462558757 0.282255010107843 0.00558469844688963 0.00355029188930764 -0.276534348801436 0.960981248778417 +1646404294.02753 71.9900763195665 -4.00315052297018 0.282715648935623 0.00557772204439392 0.0035662829762757 -0.276576293811955 0.960969158893131 +1646404294.12752 71.9903629949987 -4.00298289971716 0.283046117361292 0.00557348935171346 0.00357365106314621 -0.276608545467615 0.960959873152265 +1646404294.2275 71.9903707304967 -4.00318171531936 0.283049317628641 0.00564700184597478 0.0035782610551066 -0.276578234701465 0.960968151141023 +1646404294.32749 71.9903387401722 -4.00334728763071 0.283105112244912 0.0055752003965512 0.00351338650705815 -0.276522605126049 0.960984818875977 +1646404294.42748 71.9901107205315 -4.00393755165874 0.282514817493769 0.00549702976353366 0.00347220684733195 -0.276360252645068 0.961032120795836 +1646404294.52748 71.9905268790127 -4.00380738849184 0.281809250664182 0.00562012937682813 0.00347768818015155 -0.276314684414089 0.961044491690084 +1646404294.62749 71.9905132439165 -4.0037053510519 0.282417957934354 0.00556369331629691 0.00345882567832839 -0.276324010838035 0.961042206604887 +1646404294.72752 71.9901835992381 -4.00395977633947 0.282461725580095 0.00550380550943953 0.00343504625668926 -0.276315554523138 0.961045068095509 +1646404294.82752 71.9901537497308 -4.00393380742761 0.28276015630247 0.00548655377972644 0.00340173127353851 -0.276286459486105 0.961053650040724 +1646404294.92752 71.9903195095851 -4.00407245141803 0.281892600818077 0.00565230971028909 0.00347558591096446 -0.276342754918504 0.961036239431983 +1646404295.02748 71.991162180146 -4.00339604836367 0.282114247354399 0.00561778240748443 0.00348700637629907 -0.276407410722138 0.961017806601542 +1646404295.12744 71.9913719438102 -4.00312167928436 0.281944732087002 0.00550581698200683 0.00343329362517366 -0.27636421079843 0.961031072059591 +1646404295.22741 71.991073556763 -4.00330845857079 0.281848985380605 0.00526825465419612 0.00311320289177287 -0.276373251343655 0.961030894093624 +1646404295.3277 71.9895074931887 -4.00274996686479 0.273689862036746 -0.00251705763009429 0.00744837393102755 -0.266384630975142 0.963834744407416 +1646404295.4283 71.9887036285681 -3.99080451903034 0.233445305210161 0.00367749038006115 0.0297113831928919 -0.236681489829553 0.971125935265522 +1646404295.52837 72.0017954273466 -3.97730333719083 0.172520101053874 0.0101934960788105 0.0157120849289967 -0.201721506691841 0.979263834093168 +1646404295.62786 72.0208194498387 -3.95789549656078 0.0953117541509936 0.00520654806675133 -0.0131573404145191 -0.164016006383299 0.986356186121687 +1646404295.72724 72.0498887674433 -3.92703277942821 0.00141688700277854 0.0100817809525765 -0.037907981679462 -0.11911878676034 0.992104862027477 +1646404295.82621 72.0866658123013 -3.89492495634102 -0.108228218129197 0.000183427752720905 -0.0674646324759896 -0.0828548752576734 0.994275394126384 +1646404295.92354 72.1263338714691 -3.85679374660203 -0.23578058546067 0.00214543166264751 -0.0785581876016996 -0.0580795722179513 0.99521393256661 +1646404296.01844 72.1682095685244 -3.81795556311983 -0.363678800513097 0.00198533218742794 -0.0777062399724888 -0.0341145845229043 0.996390482616265 +1646404296.1187 72.221908047529 -3.77655040301787 -0.484259129136834 -0.00189733631437034 -0.0674941456102308 -0.0150106284089045 0.997604942578988 +1646404296.21957 72.2900038459008 -3.73011331774291 -0.567952840597154 -0.0103515562793347 -0.0686801740539863 0.00711091321017657 0.997559679361505 +1646404296.31999 72.3691321998202 -3.67548294170278 -0.616880784283595 -0.00556592960432215 -0.0796350400113889 0.0326421608065642 0.996273943334816 +1646404296.42023 72.4596311329947 -3.62168388385709 -0.647490024902346 0.0242561875950393 -0.0823623109134073 0.0377416363044384 0.995592113263972 +1646404296.51877 72.5551616697507 -3.58249511971116 -0.669374401509554 0.0391592599351497 -0.0707312562993935 0.0251035246816832 0.996410284366937 +1646404296.61899 72.6610075418481 -3.55850583920829 -0.695144979132686 0.0231734347624164 -0.0652400563112648 0.00404272583038087 0.997592293144688 +1646404296.71999 72.7724837296228 -3.53813088532756 -0.710328023931051 0.019995761471383 -0.0721812068181159 -0.0193522898476364 0.997003275713332 +1646404296.82127 72.8915171097779 -3.51782660062996 -0.712138375290763 0.0315706444716118 -0.0682525544296649 -0.0251005730678988 0.996852468750084 +1646404296.92212 73.0176144748576 -3.50076137651793 -0.704766131169349 0.03472264233661 -0.0539764715315217 -0.0215912604910254 0.997704713881107 +1646404297.02253 73.1468348608636 -3.48599498770411 -0.69527918716638 0.027124338768717 -0.0326831111902967 -0.0178008699712576 0.998939043944901 +1646404297.1227 73.2835009627238 -3.46537798245104 -0.697082092511609 0.0296355850762344 -0.0445125909337523 -0.0173142860068996 0.998419038703503 +1646404297.22268 73.4283397295041 -3.44254134895261 -0.710427823364472 0.0182391523347104 -0.0602874233764275 -0.015061752116923 0.997900748335181 +1646404297.3224 73.57267646439 -3.41867464702664 -0.722065061392004 0.0019134201214687 -0.0562309244259013 -0.0181337111197637 0.998251266206399 +1646404297.42184 73.7195440911762 -3.39458764612543 -0.725923758872912 -0.0126087015340638 -0.0336799580311701 -0.0184922153266585 0.999182024980915 +1646404297.52053 73.8642306944393 -3.37592178914975 -0.730658726594026 -0.0197934541014458 -0.00990540560119505 -0.0171158246713728 0.999608498693581 +1646404297.61912 74.0100862088357 -3.36452863566024 -0.754829355347743 -0.00739559531117555 0.00710865800813282 -0.0362052744336203 0.999291724300021 +1646404297.71997 74.1544002933756 -3.35845686679782 -0.781704845553593 0.0147846345875171 -0.00245117260437484 -0.0620612679845515 0.997959821510431 +1646404297.82053 74.2978751002562 -3.36576992803046 -0.790702533300623 0.00560695648380958 -0.00851169051653854 -0.0749505773846441 0.997135158397923 +1646404297.92147 74.4460379306499 -3.36993180689812 -0.781211685972853 0.00354849228603201 0.00648809221108119 -0.0765744699908394 0.997036440360924 +1646404298.02224 74.6005861025478 -3.3683134463237 -0.762542666792176 0.00127924415815156 0.00870155785114409 -0.0609406696586535 0.998102640617139 +1646404298.12221 74.7536010162093 -3.3611738012634 -0.760791638712027 0.0187700445065663 0.00707741207784128 -0.0519827526031744 0.998446487849651 +1646404298.22177 74.9002425233174 -3.35611884145512 -0.773484671079234 0.0114043677105973 0.0050214784826622 -0.0427276756422907 0.999009044446136 +1646404298.3214 75.0531191815934 -3.35114685507881 -0.779530679285871 0.0024111268595008 -0.0157919702057081 -0.0418505553982158 0.998996161732944 +1646404298.42107 75.2065644510232 -3.34477570553962 -0.774533085377414 -0.00660123084065794 -0.0097912935469429 -0.0370776514796833 0.999242614224804 +1646404298.52035 75.356547654851 -3.34367885941358 -0.765861966317478 -0.0128364965263209 0.0165119514991163 -0.0438820259188998 0.998817774979939 +1646404298.61964 75.5085707488011 -3.34920180385275 -0.767063763026309 -0.0101490897855486 0.0198621406779496 -0.0601366481605078 0.997940917535821 +1646404298.71967 75.6588941490934 -3.36041381357041 -0.783935267316141 0.00538449618384949 0.0050835136480814 -0.0776674096409132 0.996951823595056 +1646404298.82039 75.8001700246696 -3.3822221457624 -0.797009725029085 -0.0031522120081857 0.00716285035721645 -0.0938270165504839 0.995557757289577 +1646404298.92127 75.9480211066543 -3.40440128290882 -0.785467668942027 -0.0113596994544735 0.0187547752577573 -0.103516750088948 0.994385990490794 +1646404299.02216 76.1048256260884 -3.42188875425548 -0.766229574888854 -0.0127316973123356 0.0308273502737891 -0.100116036306523 0.994416591591732 +1646404299.12267 76.2581955473777 -3.43226785655266 -0.754972498035669 -0.00280665871212778 0.0355897722876714 -0.0870242729825105 0.995566304515803 +1646404299.22265 76.4041070989031 -3.43950692995023 -0.764376276669412 -0.00265034150534554 0.034860708122846 -0.0665278721488747 0.997171875328633 +1646404299.32203 76.5432169143975 -3.43791320762332 -0.768175714254262 -0.00209783763259495 0.0167658659476394 -0.0513233069143522 0.998539144442354 +1646404299.42131 76.6842906149877 -3.43684439980032 -0.76787893629707 0.00191745990340008 0.0134878068060843 -0.0417212095370478 0.999036407289468 +1646404299.52023 76.8270912487003 -3.43694497474946 -0.749179225493071 -0.000362622373096722 0.0274102789275515 -0.0297678090597965 0.999180875846765 +1646404299.61916 76.9691191572461 -3.44472986310227 -0.729123139667519 0.000904933537833914 0.0263388759339303 -0.0286269554000494 0.999242684303645 +1646404299.71718 77.1214785972641 -3.45363678430615 -0.734799696166228 0.0174039513583062 0.01941737369926 -0.0320213003021228 0.999146988386946 +1646404299.81714 77.2712322304246 -3.47000682149127 -0.752886576081769 0.0154330131137932 -0.00568229232298993 -0.0345315560210225 0.999268284946016 +1646404299.91872 77.4132084601319 -3.49328007095786 -0.759838949979944 0.0053939824623434 -0.00200555796310603 -0.0516086916914359 0.99865080264943 +1646404300.01954 77.5595499366069 -3.5137504062512 -0.751256449350302 -0.00460399591830972 0.0103305426843242 -0.0625655750691072 0.99797676923148 +1646404300.1206 77.7015413993933 -3.52941667734221 -0.717194974518854 -0.00524354787684453 0.0254122435636074 -0.0634174253359421 0.997649714702753 +1646404300.22159 77.8481395278912 -3.53618975755389 -0.728123198522284 -0.00548205909495861 0.0276854197215439 -0.0483792327287551 0.998430225105137 +1646404300.32178 77.98399004579 -3.5350741191275 -0.740699451635944 -0.0186384275818702 0.0213605736637728 -0.0220451408235307 0.999354965303168 +1646404300.42132 78.1176737915562 -3.52907637785081 -0.752359619230033 -0.0283082770007397 0.00557699429795414 -0.00979274712208456 0.999535712564413 +1646404300.5206 78.2552184301514 -3.52332438499724 -0.747125311001791 -0.0261154266306247 0.0127826917095127 0.000670963873628791 0.999576979072666 +1646404300.61997 78.4001052944724 -3.52070973419362 -0.729978650963203 -0.0171688906119066 0.0281634769202598 0.00222370609373401 0.99945340206241 +1646404300.7191 78.5482238375144 -3.52672647798229 -0.723199688895682 -0.0187057041185361 0.0266429345550358 -0.0102428132232225 0.99941749807025 +1646404300.81905 78.6995805235774 -3.53088184451742 -0.729955697008923 -0.00228969338556503 0.0127080642200078 -0.0174674999573996 0.999764046589602 +1646404300.91977 78.8444806326419 -3.53819719853928 -0.744250872808238 -8.86207040831841e-05 0.000250241384726361 -0.0178406156334362 0.999840808308721 +1646404301.02031 78.989059768881 -3.54746241388472 -0.745081371469495 -0.00860510461108008 0.0047049532774201 -0.0201289180968978 0.99974928969494 +1646404301.1211 79.1374699688584 -3.55096413547167 -0.730713032828451 -0.0122084722631931 0.0181713981278259 -0.00688560281096998 0.999736636304286 +1646404301.22147 79.2862102074475 -3.54618686008728 -0.721410215192928 -0.000445499254682053 0.0222007962770289 0.00956205662501926 0.999707703905586 +1646404301.3215 79.4327028589971 -3.54221075377318 -0.728847677539834 -0.0032863736802926 0.0285843804336655 0.026731405015819 0.999228484846753 +1646404301.42103 79.5756120541952 -3.53638570531713 -0.742348473640255 -0.0127999473903109 0.0142851686291965 0.0438771151575189 0.998852788988194 +1646404301.52059 79.7183445902188 -3.52588776983656 -0.749700772132228 -0.0088401104634617 0.00607415394968597 0.0504821939606866 0.998667364638349 +1646404301.62037 79.8658900960533 -3.51344781683786 -0.739329989923875 -0.0137740486126015 0.0129036876935664 0.0613375396188383 0.997938613674324 +1646404301.72014 80.0181892745925 -3.50225116011484 -0.723609117778252 -0.0149987534779974 0.022835661049893 0.063451412969886 0.997610890162415 +1646404301.81969 80.1686028085451 -3.48863816818213 -0.722046093399865 -0.0123785987119939 0.0305564648121448 0.0545056557845274 0.997969040722011 +1646404301.92008 80.3204315010598 -3.47549533455748 -0.735062267199656 0.00045167531708414 0.0117096624180936 0.0452285835237482 0.998907931206825 +1646404302.02098 80.4719407925838 -3.46733181147657 -0.74770809854571 0.00139487114725169 0.00101683520415722 0.0408709057781668 0.999162944389714 +1646404302.12173 80.6217214535288 -3.45892674904194 -0.746233124621273 -0.00454015043527792 0.0068375374321282 0.0401263033804266 0.999160905406587 +1646404302.22227 80.7757687222534 -3.44675134010106 -0.740056568520033 -0.00742075304811455 0.0172651242003476 0.0483186084843499 0.998655175716164 +1646404302.32259 80.9284257649481 -3.42813336805287 -0.741916517188588 0.00258818108584293 0.00578629463794634 0.0599355151205665 0.998182124734892 +1646404302.42249 81.0792409116422 -3.41336183341271 -0.763507498023714 -0.0178329587948145 -0.0139274606261214 0.066999195306365 0.997496425682534 +1646404302.52241 81.2205749083081 -3.38533410188203 -0.790636987167612 -0.0189991045935593 -0.0143211572608068 0.0677523462529784 0.997418446819876 +1646404302.6223 81.3640420139403 -3.3512805070305 -0.803557254204804 -0.0184356412179568 -0.0121545193178088 0.0768219128989981 0.996800275126154 +1646404302.72195 81.5082647550487 -3.31360697746123 -0.805396405397074 -0.0179989268533867 0.00469368277123275 0.0837791296281432 0.996310727340081 +1646404302.82104 81.6537727798889 -3.27943534136269 -0.807163535368423 -0.0198287117907172 0.00792766273153809 0.0782217498083575 0.996707244986839 +1646404302.92071 81.7987489701919 -3.24809453759099 -0.82728625130791 -0.0131336373338359 0.00237430436161331 0.0635987723995619 0.997886299333972 +1646404303.02086 81.9443691792305 -3.2217871405983 -0.851920632495712 -0.00259042846483589 -0.00835615008794092 0.0553317167081388 0.998429699859838 +1646404303.12142 82.091386492092 -3.2018597954442 -0.864810649661508 -0.00677418925679697 -0.00548377953676417 0.0463448211632138 0.998887479185346 +1646404303.22186 82.240667503492 -3.18318737299198 -0.862840699934748 -0.0124157829724655 0.00926212863195723 0.0435215784674272 0.998932396868822 +1646404303.32229 82.3922499467928 -3.16434870212036 -0.858227199254513 -0.0111470702115924 0.010233939326747 0.0473367360323059 0.998764357961057 +1646404303.42242 82.5412164961106 -3.15236379717588 -0.86630869162888 -0.0210529043694508 0.003184967552454 0.0470413551486445 0.998665981249526 +1646404303.5224 82.6873941317339 -3.14025501594036 -0.882151391228111 -0.0278234113284257 -0.0121559623781692 0.0482895530834451 0.998371779160304 +1646404303.62213 82.8253931068508 -3.12394894794339 -0.898758924274441 -0.0191604424755009 -0.0206790681142388 0.0446208096927929 0.998606147051193 +1646404303.72199 82.9661794904345 -3.11137281399866 -0.904154998403689 -0.0245034588621042 -0.0113952404908338 0.0445444592087574 0.998641837773557 +1646404303.82163 83.1133115338674 -3.10059544086505 -0.899540219231049 -0.0298038178382221 0.000230406017206111 0.0372510640795345 0.998861370551627 +1646404303.92101 83.2583123019678 -3.09606502643669 -0.899597669503671 -0.0353645277249072 0.00641835505018064 0.0147543746321305 0.999244946610418 +1646404304.02101 83.4048424948542 -3.09181972918394 -0.910990458295853 -0.0235013694216373 0.00219315747244209 -0.00541996891052211 0.999706706805859 +1646404304.12153 83.5507627409597 -3.09262549454087 -0.923679106877942 -0.0155681293782361 -0.00990274821380702 -0.021158291586045 0.999605870142144 +1646404304.22208 83.6957457981989 -3.09974121191528 -0.930291622099723 -0.0201675141697564 -0.00359673091996242 -0.0302302215759735 0.999333011864597 +1646404304.32248 83.842415491319 -3.10685341701666 -0.926910407410127 -0.0218973164675411 0.00951784319439094 -0.0316336851135797 0.999214305421303 +1646404304.42272 83.9908707348151 -3.11245649259477 -0.925765495272316 -0.0157749549880396 0.0223240474828725 -0.0261712810173281 0.999283669309678 +1646404304.52218 84.1405874173437 -3.12417988898145 -0.934672051898299 -0.0217109632660056 0.012070725538982 -0.0234323751086871 0.999416757642068 +1646404304.62165 84.2846898737942 -3.13346676023435 -0.955193407958968 -0.0271357965901575 0.004062509494024 -0.0181280958364911 0.999459112070808 +1646404304.72108 84.4293237617452 -3.1368152276932 -0.969510464900714 -0.0186113895352552 0.000447356034099721 -0.0116702941980163 0.999758581001171 +1646404304.82035 84.5727846440002 -3.14403313919685 -0.968264288788611 -0.0227145054670204 0.0121221797594389 -0.00842679426798962 0.999632979216687 +1646404304.91957 84.7188369566299 -3.15405132855872 -0.95382892552939 -0.0267287577389444 0.0288448210677189 -0.0186529603977184 0.999052359426523 +1646404305.0188 84.865948448885 -3.16594714281844 -0.945037065182118 -0.0271843775760144 0.0361958013945204 -0.0377463686375299 0.998261531479546 +1646404305.1189 85.0161897884588 -3.18120016128767 -0.95064714322481 -0.0193070487544551 0.0154551936404964 -0.052502627756414 0.998314504019949 +1646404305.2196 85.162395383211 -3.20325210137751 -0.962279784284534 -0.020179432019914 -0.00111131353961081 -0.0597836562506714 0.998006748449562 +1646404305.32036 85.3080607700878 -3.22834885090374 -0.96246360429064 -0.0298358620082534 0.00777945785199874 -0.0683099053292229 0.997187574234488 +1646404305.42106 85.4573477322752 -3.25295634355479 -0.94873656537239 -0.0334353801736152 0.0284773049018123 -0.0702048564747174 0.996565299709727 +1646404305.52148 85.6126145359956 -3.27286833397935 -0.939368956561296 -0.0222248920722857 0.0317485824004891 -0.0601984255441158 0.997433822992755 +1646404305.62153 85.7663420185026 -3.29565605695238 -0.941177201985946 -0.0204247735197593 0.0180582356301794 -0.0481685662315752 0.998467084074274 +1646404305.72117 85.9082605316089 -3.31578065079901 -0.953341932209581 -0.0236310325081112 0.00630628891384962 -0.0420757988926842 0.998815013989214 +1646404305.82064 86.0468138707874 -3.33523017768019 -0.964698166410573 -0.0272082445421786 0.00835995986130626 -0.0420849977979785 0.998708503748912 +1646404305.92031 86.1865637816662 -3.3532812750635 -0.962556929940015 -0.0272868038559473 0.0236639978330038 -0.0476090258825652 0.998212816085026 +1646404306.01981 86.3284637134432 -3.37641947255203 -0.950446501944259 -0.0284937008391185 0.0358235943835013 -0.0587133728426979 0.997224908908401 +1646404306.11936 86.468246455491 -3.40664886533612 -0.951234933329552 -0.0315337054641269 0.031262938837535 -0.0783862814641328 0.995933654895328 +1646404306.21966 86.6014014402215 -3.44103221633157 -0.964510885465789 -0.0125046391307792 0.015160041470085 -0.0957617179119349 0.995210279551707 +1646404306.32001 86.7284904389492 -3.49057436216392 -0.976996898162901 -0.0216771395200307 0.0112126066244235 -0.112097684161678 0.9933974472891 +1646404306.42038 86.8504730887583 -3.54309848965573 -0.977985161675983 -0.021194700655842 0.0218617700594829 -0.130859168015279 0.990933260023258 +1646404306.52089 86.9677973790983 -3.59333122386272 -0.972389859283305 -0.0117691775816127 0.0356318554320156 -0.141238405868321 0.989264155847819 +1646404306.62135 87.0840690930666 -3.64820583648082 -0.967306534746776 -0.00749786365242429 0.027981980782801 -0.144863105966154 0.989027538202024 +1646404306.72157 87.2020021797382 -3.69575090208611 -0.965694311798168 -0.00407578895926047 0.00670888870936066 -0.131883587400296 0.991234128816735 +1646404306.82137 87.3185883453626 -3.72477964201172 -0.968557497294136 0.0195860210108153 -0.0118297074155741 -0.107460265425774 0.993946043383667 +1646404306.9206 87.4305927875617 -3.74930341689456 -0.968800090253792 0.030346358866276 -0.00266950280119019 -0.0780606324938667 0.996483070560162 +1646404307.01914 87.5427125922997 -3.77046227725824 -0.964957964242201 0.027639232155397 0.008993995107126 -0.0545441282719431 0.998088232056126 +1646404307.1181 87.6531483716007 -3.78770233731344 -0.962070586047717 0.0275808735089219 0.0185355038793497 -0.0452154784680901 0.998424404258692 +1646404307.21651 87.7641478013797 -3.79676083251853 -0.95840972227511 0.0326903819162959 0.00722894023023575 -0.021020053002455 0.999218313845921 +1646404307.31682 87.8668661503647 -3.79730090637063 -0.953853080037384 0.0341245528767114 0.00824669490354807 0.00548788720103263 0.999368495605199 +1646404307.41726 87.9660915274092 -3.78930188635732 -0.93782545080812 0.0276105102641594 0.0114611245090254 0.0382087108004637 0.998822505136377 +1646404307.51826 88.0657910342182 -3.77331404023726 -0.912040126518167 0.0213945340005629 0.00277951050664253 0.0923286712664275 0.995494834089267 +1646404307.61952 88.1575218098418 -3.74800125290642 -0.884009081594202 0.0259865880289253 0.00325419299946583 0.144450044270521 0.989165452379317 +1646404307.7198 88.2398029324029 -3.71643793468995 -0.854776860275431 0.0307292089738167 0.0115105298248931 0.184147999818009 0.982350618456577 +1646404307.81988 88.3134832611037 -3.67897347246492 -0.819350752623362 0.0309711314647256 0.012023287111696 0.211288208546748 0.976859008512452 +1646404307.91963 88.3780644315438 -3.63762392469948 -0.778642286286484 0.0248863964629577 0.00736597417997248 0.232834676518654 0.97216995587496 +1646404308.01977 88.4390192742202 -3.59270623582667 -0.73535335076452 0.0177481258109192 0.00207236748906189 0.252780633980939 0.967358599696816 +1646404308.12389 88.497555703086 -3.54420523925892 -0.683631710621226 0.00834705332530595 -0.00399590476821072 0.277578880180895 0.960658276768272 +1646404308.22465 88.5530052260601 -3.50011906106902 -0.623517820539861 0.00890685198937541 -0.000744729909254757 0.308638266491959 0.951137494698762 +1646404308.32438 88.6084820601273 -3.46181586712853 -0.556441794528909 0.00787916146869426 0.0040070263557485 0.340794797138119 0.94009614869859 +1646404308.42298 88.6623762853122 -3.4269810571093 -0.481942605831695 0.00377162751300988 0.00523782159250433 0.37161493735955 0.928364518054263 +1646404308.52241 88.7066604814665 -3.3919701209859 -0.407866516613337 -0.00620739726403271 -0.000564997382181158 0.410829819359585 0.911690741711318 +1646404308.62154 88.7378369442456 -3.36071520402011 -0.33829584397092 -0.0123340527622215 0.0161333976223076 0.451236776109471 0.892173165091816 +1646404308.72556 88.7629183894464 -3.33450035432917 -0.27100070444456 -0.0247297084674122 0.0248046228284776 0.485517299039466 0.873525113856994 +1646404308.82521 88.781521526311 -3.31246977703669 -0.218491857067256 -0.0285403746436725 0.0239995322418032 0.512396888328322 0.857938749736149 +1646404308.92502 88.7977128726916 -3.29537423799447 -0.182872218525232 -0.0292713135074594 0.0208198247176205 0.537855255381343 0.842271600710214 +1646404309.02469 88.8161564287687 -3.28643814892292 -0.160673213510192 -0.0405310869805452 0.0141171262731772 0.55239799909487 0.832474857476157 +1646404309.12446 88.8296728400916 -3.28277319261993 -0.137975990581309 -0.0435680348585128 -0.00565002617162093 0.560411844688297 0.827048044478608 +1646404309.2245 88.8336006005996 -3.28179540482724 -0.116019541497997 -0.0224963589178992 -0.0132284357204407 0.565765614493641 0.824153014785762 +1646404309.32459 88.8405663021613 -3.27877213288114 -0.101914923339496 -0.0133637533246554 -0.0232201080020067 0.564759644784085 0.824820453374435 +1646404309.42494 88.8429525279795 -3.2711101077703 -0.0954442321233142 -0.00432935238582546 -0.0297562778610194 0.564724631365282 0.82473141771435 +1646404309.52547 88.8419304903173 -3.26049574882058 -0.0863379675505973 0.0107116811881664 -0.0429507617501324 0.568914407990067 0.821204535017017 +1646404309.62576 88.845578149219 -3.25181763806551 -0.0725136370359803 0.0214996667571124 -0.0609348224622153 0.570701247964883 0.818611505729155 +1646404309.72574 88.8481477019374 -3.24689337177284 -0.0603411874662723 0.0157720608034491 -0.0474979702218339 0.567794597742861 0.821647418116091 +1646404309.82592 88.8501426960742 -3.24677746842697 -0.0498767599279418 0.0124690157605029 -0.0370765788360293 0.56981092179243 0.820844299702349 +1646404309.92605 88.8502835443337 -3.25188134625976 -0.0416087472524155 0.00806041759850531 -0.0207889803174855 0.574124166689693 0.818464592507433 +1646404310.02573 88.8502107051091 -3.25809547797112 -0.0368979038045037 0.00195117155450708 -0.00603091255176627 0.570932487489854 0.820972542629779 +1646404310.12551 88.8501569355636 -3.26291931657359 -0.0340325825690024 -0.0024596971476532 0.00564509489509128 0.569379859805643 0.822051493546038 +1646404310.22545 88.8523774933747 -3.26429762382376 -0.0346820068936785 -0.0018778032853671 0.00763431750797339 0.570816949877381 0.821039707190638 +1646404310.3254 88.8519164006513 -3.26688855380483 -0.036871545624766 0.000356987660615149 0.0133928759609556 0.573071552514725 0.819395813469694 +1646404310.42525 88.852114365175 -3.26971142459865 -0.0385132693494171 0.00269782251683831 0.0191715603128184 0.573112439036049 0.819248012051895 +1646404310.5251 88.8517014292066 -3.27302589422287 -0.0411240204435863 0.00489055655804311 0.023961452080947 0.571432868722783 0.820284345708222 +1646404310.62497 88.8536179271882 -3.28010577469872 -0.0437005430814395 0.00662245586659824 0.0280924457318759 0.566891566504638 0.823286650806997 +1646404310.72513 88.8521365731493 -3.2830125484062 -0.0468288876509861 0.00750012098737513 0.0298185641001097 0.566592229570009 0.823424463330461 +1646404310.82527 88.8513362784451 -3.28432895024573 -0.049797658817349 0.00766612841098867 0.0297808299048155 0.566537213785349 0.823462153375424 +1646404310.92533 88.8494032626322 -3.28490882209027 -0.0527021955162154 0.00804564054766504 0.0294792647613089 0.566134317482215 0.823746426508938 +1646404311.02534 88.8471941704161 -3.28431087995522 -0.055384318547994 0.00832110713371526 0.0292772428521783 0.565362132017638 0.824281057593526 +1646404311.12536 88.8438169193383 -3.28479226211581 -0.0582424511875446 0.00847258270274764 0.0292463697269793 0.565156259649556 0.82442177759873 +1646404311.22538 88.8416083104447 -3.28498994668531 -0.0608192313336832 0.0086550165780734 0.0291356076838879 0.565062257179683 0.824488236765033 +1646404311.32537 88.8390212836539 -3.28490940446966 -0.0627376769211442 0.00887005110640245 0.0290131848227219 0.564992593774755 0.824538007783435 +1646404311.42537 88.8362589629653 -3.28469535844711 -0.0644068809116819 0.00921752635922741 0.0288059202224548 0.565158745217404 0.824427588616631 +1646404311.52536 88.8324744022585 -3.28416603390867 -0.0652975772401793 0.00950473910034955 0.0286312882938011 0.565309516944915 0.824327034202305 +1646404311.62535 88.8295864347239 -3.28363551971557 -0.0658764673488651 0.00977472447582042 0.028430802266919 0.565171860541689 0.824425201152728 +1646404311.72534 88.8274993348209 -3.28268743579136 -0.0659649838415981 0.00996699240417343 0.028345233431433 0.564916535493967 0.824600821446119 +1646404311.82535 88.8240520881323 -3.28201652565864 -0.0663036851858174 0.010201447228544 0.0282263995560862 0.564898240889459 0.824614563467397 +1646404311.92536 88.8212831397321 -3.28152056599389 -0.0666375114165533 0.0102562778519516 0.0281913424875906 0.564613463082973 0.824810095888023 +1646404312.02535 88.8174206357713 -3.28045325071987 -0.0668107622235866 0.0103109484717589 0.0280647152183526 0.564447309612136 0.82492744576292 +1646404312.12534 88.8144996211347 -3.27973553268655 -0.0667002371936021 0.0103062581432725 0.0280727502592071 0.564193003185922 0.825101179790701 +1646404312.22534 88.8120238902775 -3.27998727772082 -0.066119200735017 0.0102571541879653 0.0281393581888392 0.564144133587773 0.825132937075702 +1646404312.32533 88.8104054271444 -3.2803902059082 -0.066193663471422 0.0101988321303887 0.0282076367120973 0.563981853486489 0.825242256547874 +1646404312.42532 88.8094448668397 -3.28105975429889 -0.065939639890441 0.0101290837421294 0.0282191196629122 0.563957744896643 0.825259198627363 +1646404312.52533 88.8088328311271 -3.28132669367202 -0.066105184980123 0.0101156910761317 0.0281882793660723 0.564089957680988 0.825170051167565 +1646404312.62536 88.8082573645158 -3.28081351598667 -0.0660340530925388 0.0101384185172444 0.0281856887442229 0.564066168774196 0.825186122438067 +1646404312.72536 88.8097470964667 -3.28045117443892 -0.0657194055028549 0.0101606892005916 0.028152934914453 0.56403614451248 0.825207489262038 +1646404312.82535 88.8106420447811 -3.27965983865054 -0.065395133558761 0.0102632854883668 0.0280349232111439 0.563978395523543 0.825249706109738 +1646404312.92532 88.811387719489 -3.27948668272968 -0.0647522678805174 0.0102112012769129 0.0280215459857846 0.564011137078317 0.825228429939651 +1646404313.02529 88.812964906296 -3.27952724125405 -0.0641503762032279 0.0102134443129376 0.0280044726194344 0.564002363029112 0.825234978394723 +1646404313.12524 88.8146482330085 -3.27988298832148 -0.0637043753494243 0.0102229406611491 0.0279710315272161 0.563985607833142 0.825247445943706 +1646404313.22519 88.8169585124616 -3.28019812513526 -0.0637159762409851 0.0102385625923893 0.0279802073500465 0.563972189332745 0.825256111453836 +1646404313.3252 88.8182601760252 -3.28000885677608 -0.0638482114947142 0.010350015166986 0.027944860312509 0.56397659145651 0.825252910480927 +1646404313.42519 88.8199926574422 -3.27976235059531 -0.0632929354975548 0.0103505880312758 0.0278664741978011 0.564015396915251 0.825229033048224 +1646404313.52518 88.8217168100666 -3.27968915766227 -0.0630677849522178 0.0102988770701754 0.0279620852339628 0.563998970626239 0.825237672463509 +1646404313.62518 88.822845656733 -3.27963859587457 -0.0629760239349824 0.0102582840970306 0.0280181456849856 0.563975450896406 0.825252350439514 +1646404313.72516 88.8244972498078 -3.27925314445156 -0.0629723829396805 0.0101992520667635 0.0280643931116931 0.563939070009864 0.825276372140236 +1646404313.82514 88.8262604418228 -3.27883226575499 -0.0629807636659625 0.0101997289772054 0.0281326034424836 0.563933220538846 0.825278040980742 +1646404313.92512 88.8274834709282 -3.27858380905471 -0.0634147509419855 0.0102378375989979 0.0281329504549991 0.563869167552802 0.825321322675774 +1646404314.02513 88.8287395542563 -3.27823128654802 -0.0633353490411559 0.0102016948952684 0.0281213503454634 0.563836517461384 0.825344471510543 +1646404314.12513 88.8303537084503 -3.27773503679556 -0.0633340107956734 0.0101982048866386 0.0281552292550888 0.563824122684545 0.825351827017832 +1646404314.22513 88.8305671396016 -3.27780424782766 -0.0632615691687107 0.00998846939799445 0.0282759186656165 0.563834155039952 0.825343412473298 +1646404314.32512 88.8302525890408 -3.27770433847275 -0.0630749809236672 0.00996760932819348 0.0282922824839821 0.563836033144298 0.825341820850134 +1646404314.42511 88.829980310846 -3.27817433463736 -0.0634198074997464 0.00982588042018678 0.0284046253532055 0.563877995042333 0.825310993528825 +1646404314.52511 88.8296378582985 -3.27836960586624 -0.0635252199542549 0.00987094913737368 0.0283768430506556 0.563813590286384 0.825355411050276 +1646404314.62507 88.8290845968423 -3.27858202028451 -0.0640216815909628 0.00989815712149372 0.0284062304165085 0.563844102865613 0.825333229806471 +1646404314.72504 88.8275575720078 -3.2782364916441 -0.0639890824173017 0.00994325816083045 0.0283704536942437 0.56382703323469 0.825345579480549 +1646404314.82502 88.8262163836622 -3.27808664729622 -0.0639310835130907 0.00988824566959031 0.0284222171453824 0.563855865459038 0.825324762234566 +1646404314.92503 88.8248411773408 -3.27822421365525 -0.063929608647358 0.00981475078375235 0.0284457797921632 0.563874933683948 0.825311800134942 +1646404315.02503 88.8230218480022 -3.27822486184829 -0.0638134661531167 0.00977442609150567 0.0284378210738113 0.563875658732847 0.825312057597452 +1646404315.12503 88.8214637403681 -3.27815804894036 -0.0637542259567174 0.00980107447367639 0.0283739106956095 0.563884207787547 0.825308100250322 +1646404315.22504 88.8197575870784 -3.27818195359904 -0.0636163062318669 0.00979514907123376 0.028410002497556 0.563919045709607 0.825283125175059 +1646404315.32504 88.818409231029 -3.27846020064148 -0.0638637400463398 0.00968466411654983 0.0284931778727623 0.563923870864433 0.825278264565911 +1646404315.42504 88.8174143590136 -3.27851601825079 -0.0637836228834627 0.00975256346330469 0.0284752718096027 0.563922995413488 0.825278681201162 +1646404315.52501 88.8165140093795 -3.2786905084387 -0.0635408550539073 0.00972361487341058 0.0284935644193637 0.563904054229304 0.825291333847759 +1646404315.625 88.8157168317203 -3.2787961614012 -0.0632593194859196 0.00977970424339071 0.0284067588811562 0.563891827084104 0.825302017919814 +1646404315.72498 88.8147980410772 -3.27896733799118 -0.0629754608154152 0.00982312189709051 0.0283874386413113 0.563859289871241 0.825324397330811 +1646404315.82495 88.8139319745923 -3.27889284793147 -0.0629077315340102 0.00981091977100322 0.0283663317679657 0.563847816012337 0.825333106965533 +1646404315.92495 88.8137823235154 -3.27933112883792 -0.0628889153099555 0.00977179389999859 0.0283905383328641 0.563867727446936 0.825319135438503 +1646404316.02494 88.8130011182688 -3.27909673583018 -0.0625941160183003 0.00985452037069024 0.028358682460754 0.563887460569869 0.825305764774124 +1646404316.12491 88.8116104043129 -3.2788379178063 -0.0623586248231727 0.00994436084221996 0.0282965835482399 0.563879675834266 0.825312137453439 +1646404316.22488 88.8114515666955 -3.27872587332161 -0.0624105773265161 0.00999614137513989 0.0282170238793639 0.563884507936172 0.825310934394161 +1646404316.32486 88.8107900043786 -3.27901607707881 -0.0625537623170857 0.0100408747265112 0.0281971508093159 0.56389770709053 0.825302052256621 +1646404316.42484 88.8107207819602 -3.27872716905206 -0.062246372312518 0.0101260800071843 0.0281600376163913 0.56390975632552 0.825294045480765 +1646404316.52481 88.8105315028447 -3.27827517444898 -0.0623152411630473 0.0100943257353555 0.0281556866041035 0.563921263186794 0.825286720373952 +1646404316.62478 88.8101425195109 -3.27809366371721 -0.0623717454850397 0.0100600652778272 0.0282166916124203 0.563916389580248 0.825288385331949 +1646404316.72476 88.8101683599477 -3.27808460664946 -0.0623832136497474 0.0100211240143735 0.0282322441250949 0.563955196740856 0.82526180908492 +1646404316.82476 88.8094121931667 -3.27789444049623 -0.0618106642161982 0.0100277996346138 0.0281765657811048 0.563921792851919 0.825286456887505 +1646404316.92476 88.8076463661639 -3.27698620851067 -0.0629184451648342 0.0138995616041492 0.0243947294469464 0.563652202857282 0.825534913602409 +1646404317.02471 88.8083259179185 -3.27670021005926 -0.0808691916204809 0.0169080089892959 0.0116523859501118 0.561937452955731 0.826924809217437 +1646404317.12464 88.814445211296 -3.28685391573421 -0.131513539635953 0.0132675512998367 -0.00654629703892132 0.557427590114317 0.830093729561254 +1646404317.225 88.8186816113445 -3.30930144386952 -0.211162995219004 0.0116965905683593 -0.0123276165723386 0.564088208193031 0.825539649572496 +1646404317.3248 88.8299561611142 -3.33962445602315 -0.303746499441669 0.0160290932153448 -0.0188660545786505 0.560467551226084 0.82780629629035 +1646404317.42403 88.8551509528707 -3.37569834528152 -0.401912408146598 0.0195786397307353 -0.0237153152169899 0.540466813968764 0.840803118267819 +1646404317.5234 88.8913853444788 -3.4139270881981 -0.502126281755861 0.0141498537880177 -0.0212606704886099 0.508943863324333 0.860420774686802 +1646404317.62306 88.9345709310083 -3.45289652843454 -0.598064247554063 0.0106523613611404 -0.0141387933542545 0.474847546968981 0.879890009522463 +1646404317.72299 88.9862997947942 -3.49204725887195 -0.687593519851685 0.00635071733526434 -0.00794002854523035 0.444366075193671 0.895787595110015 +1646404317.82314 89.0412314018023 -3.53084340677931 -0.764854832574349 -0.00190575146557436 -0.00248734118284967 0.419128958762305 0.907921305605282 +1646404317.91921 89.0963876040528 -3.5697165150478 -0.831354710958694 -0.00822289169937757 0.0028993748132534 0.399895005148584 0.916519482899839 +1646404318.01911 89.1536678237519 -3.61068641284469 -0.892917870480338 -0.00381992199195369 0.00712797603041343 0.380244519009635 0.924850639788284 +1646404318.11872 89.2160358799501 -3.6526919882479 -0.945355547779627 0.00572572749340147 0.0121109489094925 0.353704173338046 0.935261406626198 +1646404318.21731 89.2904148566562 -3.69617091962117 -0.980795528847587 0.0046023568860032 -0.00754134531543866 0.319810389034263 0.947440373579079 +1646404318.31417 89.3682230918818 -3.73876056470078 -1.00276173086058 0.00147020912016823 -0.0176737542275102 0.282375051663316 0.959140139445103 +1646404318.41701 89.4598291059778 -3.78341536636181 -1.01665363017626 -0.00743296395796284 -0.0158785530409378 0.240564398445677 0.970474828524975 +1646404318.51723 89.5572377208043 -3.82670187566898 -1.02156137326753 -0.00912894444540163 -0.0143929061170679 0.198051247606611 0.980043473499145 +1646404318.61743 89.6669786663914 -3.87001473689402 -1.02120955826781 -0.00330897067875102 -0.016868260848776 0.155367016737446 0.987707245391607 +1646404318.71726 89.782208973715 -3.91710621014105 -1.03118595025813 0.00274739556617215 -0.0175767036021501 0.110258640269752 0.993743701139251 +1646404318.81746 89.9037252954713 -3.96583731439105 -1.05303899584315 0.0141739251793332 -0.0228423655974305 0.0686404152962591 0.997279208430051 +1646404318.91819 90.0333795363471 -4.01338463947068 -1.07728625234438 0.0231528294063704 -0.0307954638519608 0.0339133930434885 0.99868186509463 +1646404319.01832 90.1698920101982 -4.06045484454859 -1.09540846798704 0.0203533799355508 -0.0370440776086354 0.00787763840200292 0.999075281974546 +1646404319.11848 90.3054350888668 -4.10127407910026 -1.10736201923592 0.0187517725145169 -0.0159986066555854 -0.0125561112909274 0.999617306613827 +1646404319.21873 90.444557192474 -4.13210125515581 -1.12278521776786 0.017626494654934 -0.00421256247435487 -0.0179154363223932 0.999675246340003 +1646404319.31854 90.5868367818203 -4.15113133763587 -1.14850464690462 0.0294255492418854 -0.00540642060994222 -0.0134249160912881 0.999462195030873 +1646404319.41773 90.7274789739577 -4.16920595298573 -1.17965584354495 0.0225873866432683 -0.0158012431331193 -0.0112690859753386 0.99955647083161 +1646404319.51763 90.8638968800062 -4.17981390136459 -1.20525443854167 0.0207528493826391 -0.00685840569295395 -0.0110777625417743 0.9996997372666 +1646404319.61715 91.0007881820249 -4.18650740676404 -1.21672437884357 0.0127134597617357 0.0107105639550561 -0.00989625931168485 0.999812840391779 +1646404319.71643 91.1423846542948 -4.19207616831026 -1.21667575912288 0.00808782716974146 0.0186318219096131 -0.0173823624413185 0.999642583996875 +1646404319.81343 91.2836509714526 -4.19945294148379 -1.22372012279279 0.00614797826768074 0.0159407176251384 -0.0327499474516735 0.999317535534485 +1646404319.91334 91.430525467867 -4.20939539400448 -1.23951233143727 0.00703240636554369 0.000585567619187099 -0.0489097978755416 0.99877827071029 +1646404320.01563 91.5789556374774 -4.21638765525361 -1.2579082584108 0.0142950951747414 -0.000752796970252369 -0.0576768961203249 0.998232667870863 +1646404320.1168 91.7293127236616 -4.22491186542777 -1.25803891556322 0.0150424011027621 0.00221117058222434 -0.0649063273357415 0.997775528646347 +1646404320.21758 91.8831028087427 -4.2321108854399 -1.2505003446419 0.0129509228540968 0.0134923872744826 -0.0641904995460612 0.997762401000801 +1646404320.31806 92.034332679472 -4.23347715630073 -1.25319064416953 0.0118165062104714 0.0210013913050819 -0.0551468636191069 0.998187424874305 +1646404320.41827 92.1866564655821 -4.23142818409004 -1.26776598322251 0.00463930689298413 0.0158086129556784 -0.0391321523336801 0.999098213010961 +1646404320.51839 92.3400542072392 -4.22359118216194 -1.28831749503871 -0.00526728012558462 0.0048094152089845 -0.0234493778885821 0.999699580855197 +1646404320.61832 92.4864293400655 -4.21285613808797 -1.30276524270937 -0.00980438383810554 0.0102387411630569 -0.0122079019440934 0.999824989369172 +1646404320.7179 92.6326213115906 -4.20189923079072 -1.30433941620502 -0.00510060334351906 0.0274646431948057 -0.00564802766395019 0.999593806004825 +1646404320.81717 92.783672678272 -4.19863667635067 -1.3022932033497 0.000850784276192009 0.0368167785956117 -0.0129030014799305 0.999238366723754 +1646404320.91652 92.9360669347986 -4.19931002493511 -1.31205981230251 0.00796045457857901 0.0393829389213379 -0.0280806241603362 0.998797824302584 +1646404321.01689 93.0858754579375 -4.20157699517762 -1.33510679654019 0.0204555717329652 0.0287224441135258 -0.0418390002984654 0.998501922303225 +1646404321.11764 93.2299924594698 -4.20773937512042 -1.3558126806743 0.0180067543673969 0.0320837375423554 -0.0562183720872744 0.997740389691783 +1646404321.21855 93.3745827083895 -4.21591037454757 -1.3564628895913 0.0056689658328552 0.0443827517041076 -0.0709943471356112 0.996472697494686 +1646404321.31919 93.5208017716594 -4.21667202474996 -1.34876912452871 -0.000235277090505055 0.0592806118941241 -0.0691871501095555 0.995840796492018 +1646404321.41953 93.6684075525208 -4.20780598047238 -1.35018911681633 0.0094378255928815 0.0586936786481411 -0.0638393377021523 0.996187993551703 +1646404321.51954 93.8191895110204 -4.19832642366031 -1.36113783208871 0.00413482167292949 0.0429891384832264 -0.053060473204886 0.997656966800446 +1646404321.61937 93.9660309678795 -4.18469926170764 -1.37477233571358 -0.00302813608743372 0.0252793658114765 -0.0464511718138864 0.998596050809892 +1646404321.71888 94.1072442142238 -4.16704167167065 -1.38108747459501 0.000960340428246102 0.0315977562868011 -0.0333391268361322 0.998944023539706 +1646404321.81777 94.2480345223588 -4.15423692645433 -1.37604220829594 0.00178968192022242 0.0422663303039671 -0.0241847892609425 0.998812019516012 +1646404321.91664 94.3911463959808 -4.14997339606029 -1.37207981539446 -0.000389997091094887 0.0483109805659335 -0.032488019695788 0.998303774226695 +1646404322.01555 94.5380725033516 -4.15171652779084 -1.37991908530435 -0.0049809013670124 0.0386763022429036 -0.0402357983988442 0.998428973334401 +1646404322.11593 94.6823153192628 -4.15618656904091 -1.39794844645725 0.000306541352261652 0.0341384075470293 -0.0489885675754612 0.998215705851921 +1646404322.21659 94.8211098145762 -4.16728800633585 -1.40984748551984 0.00375859278536866 0.0399080222510805 -0.0608907731741779 0.997339228388478 +1646404322.31726 94.9661384851316 -4.1798145070609 -1.41465392944974 0.0126171085981826 0.0483013865672431 -0.0609216407833302 0.99689334349797 +1646404322.41776 95.1092677017029 -4.19137464494504 -1.41297775522025 0.0237780780466892 0.0597002828992377 -0.0565850721853426 0.996327561011903 +1646404322.51823 95.2520950740036 -4.2048100700048 -1.42261541860489 0.0173965700291768 0.0572410268260495 -0.0537383421919218 0.99676126267907 +1646404322.61823 95.3970954098867 -4.21723352045338 -1.43435698081937 0.000279449938991533 0.0465267253230807 -0.0437776889012287 0.997957263460165 +1646404322.7184 95.5408106013466 -4.2229722933162 -1.44984870861862 -0.0100495283362564 0.0298604966024763 -0.037317024405121 0.998806686707899 +1646404322.81829 95.6824207317025 -4.22332787368049 -1.45511414108149 -0.00777727865703756 0.0344304633230315 -0.0290989851688576 0.99895310510263 +1646404322.91801 95.8296221920303 -4.22607843892255 -1.44835349800195 0.00156417155180349 0.0486805236035313 -0.0298335095060225 0.99836752836798 +1646404323.01748 95.9781709877853 -4.23881646645889 -1.44312384472616 -0.00223164514841543 0.0445424995026771 -0.0442372864392487 0.998025073826541 +1646404323.11714 96.1282653343446 -4.25057532570081 -1.45424975008902 0.0096360323600716 0.0361614333388531 -0.0594389354583809 0.997530205342577 +1646404323.21763 96.2730454109857 -4.26329051738231 -1.47703701975995 0.0220283961421771 0.0198587661643199 -0.068097072014472 0.997237769016439 +1646404323.31814 96.4127902054612 -4.27953798630265 -1.49635462941429 0.02005194374765 0.0286241687581472 -0.0841536799032791 0.995839713344259 +1646404323.41897 96.557544089682 -4.29546221667126 -1.49201967837907 0.0152431508266937 0.0457850115458612 -0.0923388319852518 0.994557650002359 +1646404323.51935 96.7073491081731 -4.30615357151023 -1.48747398368885 0.0120986580153705 0.0533743083947912 -0.0872418117211913 0.994682699138375 +1646404323.61959 96.8541584839405 -4.30884081453631 -1.48700575858141 0.0143544597320051 0.0406240239415313 -0.0744454594651227 0.996293888232594 +1646404323.71919 96.9984111639816 -4.30616175885873 -1.49796333620761 0.00106394433608297 0.0307210801878948 -0.0548667513768791 0.998020402019859 +1646404323.81847 97.1441939184013 -4.29625182616338 -1.51602597365338 -0.00895964193455178 0.0138025947048212 -0.0417858707711367 0.998991068128094 +1646404323.91764 97.2892019348002 -4.28349133248698 -1.52335293387565 -0.00724231872526778 0.0179440678688513 -0.0266590682042358 0.99945727939231 +1646404324.01681 97.4371554511245 -4.27386735320635 -1.51786043153691 -0.00310973920957786 0.0311047515866498 -0.0202612174638193 0.999305912630192 +1646404324.11584 97.5889482156726 -4.27551328874072 -1.51761135489175 -0.00648640367234283 0.0303824553268743 -0.0318428385256644 0.999009943198933 +1646404324.21539 97.7450890628809 -4.28004869835181 -1.53456712325732 0.00670477188474592 0.0206388942164018 -0.0470281259813343 0.998657817996824 +1646404324.31579 97.8908162744289 -4.29165312541056 -1.55763076338667 0.0160855739496594 0.0229877096980343 -0.0534153756102455 0.998178149010467 +1646404324.41634 98.0342908584487 -4.30909286986456 -1.56570548677991 0.0079425835246899 0.0308786648806263 -0.0625851342880383 0.997530212268424 +1646404324.51717 98.1815266873127 -4.3225937675803 -1.55972593277817 0.00692136275724651 0.038604932278058 -0.0616873005217316 0.997324636663372 +1646404324.61783 98.3275332920525 -4.32726524274934 -1.55080746533393 0.0147933705028874 0.0438548449322625 -0.0484292226042764 0.997753736732202 +1646404324.71819 98.4726675754019 -4.32175901354811 -1.55873155343619 0.0309400155813881 0.0222576925967385 -0.0341521641907694 0.998689611559654 +1646404324.81815 98.6122041597472 -4.31612761745197 -1.58156083824853 0.0188900423517212 0.0210035487358209 -0.0114867436133817 0.999534927834744 +1646404324.91801 98.7521503625284 -4.30230259361834 -1.60367776474002 0.0118072582622129 0.0173721796076477 0.00134990031059389 0.999778462359114 +1646404325.01764 98.890849779289 -4.28706011255117 -1.61441596959596 0.00855723622577029 0.0359155227903688 0.0160801849924895 0.999188809275541 +1646404325.11717 99.0347987625716 -4.27844718136464 -1.6089510274174 0.00370675754951558 0.0473973973466475 0.0150109851346729 0.998756435272642 +1646404325.21651 99.1772604838469 -4.28402625958025 -1.61777069190797 -0.0101293456403677 0.0412086088704911 0.000738082687070894 0.999098945122953 +1646404325.31627 99.315783241474 -4.29203029083425 -1.63653428903775 0.00962978147223141 0.0397321030516335 -0.0174932441734086 0.999010817611187 +1646404325.41671 99.4567034677195 -4.30810393923529 -1.65693072618072 0.0105176553614025 0.0287455157823988 -0.0350728919068604 0.998915895609526 +1646404325.51738 99.595005310652 -4.32462942189423 -1.65834378749955 0.00636779703071096 0.0376600488504287 -0.0525672408723481 0.997886695506367 +1646404325.61819 99.7342493247237 -4.33932739048499 -1.64231971972 -0.00316557330983939 0.0492135815427043 -0.0564681603778618 0.997185714599286 +1646404325.71892 99.873401009205 -4.34004362022928 -1.64391587673807 0.00848890029805501 0.0539326780203573 -0.0506795753911399 0.997221532785691 +1646404325.81915 100.009745870962 -4.3320687839235 -1.6515980027689 0.0137807837878573 0.0572799314119594 -0.0381225570090395 0.997534846560618 +1646404325.91889 100.145059126485 -4.31843925350844 -1.66442393677126 0.0103408625981739 0.0494051588745772 -0.0237496428665882 0.998442863313169 +1646404326.01831 100.276904392269 -4.302293946092 -1.6672229580156 0.0127436225027752 0.0532374886959101 -0.01914555804082 0.998316992487934 +1646404326.11738 100.406974559356 -4.28531048905992 -1.66063642966542 0.0166230080501743 0.0702207519450665 -0.01934860544621 0.997205271279143 +1646404326.21645 100.537618050254 -4.27342091570578 -1.64418283206561 0.0143667724244785 0.070198637190385 -0.0309134159384531 0.996950403932774 +1646404326.31558 100.668584296526 -4.26548437015624 -1.63884372907463 0.0143331848480327 0.0682826271052227 -0.0525228125318045 0.996179399913218 +1646404326.41595 100.802160938809 -4.25929365315551 -1.63557951698344 0.0192797907576179 0.0492490606862349 -0.0746162865389679 0.995808831791017 +1646404326.51689 100.92766726944 -4.25641690656692 -1.63098842624361 0.0142392991978307 0.0455846227220924 -0.0908612955513116 0.994717803952642 +1646404326.61797 101.054646164878 -4.25115605171073 -1.6116868120338 0.0141666200504321 0.057107296180791 -0.111942970419104 0.991971186563906 +1646404326.7189 101.180701580272 -4.24726046840333 -1.5927876993943 0.00211317801934761 0.077158258692539 -0.120990061986157 0.98964819127545 +1646404326.81955 101.312399067227 -4.24113794944921 -1.58075355168749 0.0081658127544265 0.0766211245978316 -0.126160774295652 0.989012629745714 +1646404326.92 101.445909142174 -4.23857656233852 -1.5729601218721 0.0088231898066505 0.0620164511591494 -0.142031445935338 0.987878119745936 +1646404327.02038 101.573564962894 -4.23823400041324 -1.56376546902052 0.00744649290552484 0.060987898230952 -0.153434233145906 0.986246907276111 +1646404327.12085 101.698327023944 -4.23711842449939 -1.55143042501585 0.0139410568773005 0.0684284254657474 -0.171960107863813 0.982625523190232 +1646404327.22062 101.822738196463 -4.23824807146129 -1.52429529744732 0.0136648978205843 0.080049652253273 -0.193936245866374 0.977647204405008 +1646404327.32027 101.949253121026 -4.24605926919723 -1.4860949194042 0.01485979840362 0.0773097013367194 -0.220432328462039 0.972220131986281 +1646404327.42041 102.069375367116 -4.26223633198967 -1.44184560367197 0.00854855104653112 0.0673542112028907 -0.241962696835973 0.967907219648709 +1646404327.52075 102.180442447845 -4.28336772048884 -1.38891871854706 0.00234590246679994 0.0492986686259866 -0.255668262409345 0.965503950074725 +1646404327.62087 102.284053701163 -4.30795126296367 -1.324580789129 0.00273448277606119 0.028620056570013 -0.26504449662874 0.963807465094914 +1646404327.72108 102.379602496097 -4.33691688752684 -1.25818176980081 0.000715107450806949 0.0179082860490686 -0.276428146758091 0.960867452665556 +1646404327.82117 102.466452951684 -4.36638081815688 -1.19207959833445 -0.00108432638619728 0.0112161033812066 -0.290948670110281 0.95667230263151 +1646404327.9205 102.544138957486 -4.39495214730467 -1.12618300252555 0.00733870715430777 0.0141458094540349 -0.311340728464486 0.950164717431343 +1646404328.02272 102.617779132983 -4.42034331757781 -1.05095103074465 0.018312616157008 0.00665399703425436 -0.337818640958639 0.941009531425585 +1646404328.12262 102.676336700012 -4.44370154281702 -0.968059727752231 0.0272861271515031 -0.00837991665760849 -0.363423395721968 0.931186705072502 +1646404328.22271 102.725248439687 -4.46092695850566 -0.888098672448415 0.0492266047729751 -0.0308870153929702 -0.388142533861132 0.919765245630909 +1646404328.32322 102.771837519097 -4.46985953160538 -0.810573817683469 0.0695215436505393 -0.040927817239853 -0.40116999657511 0.912444136696784 +1646404328.42372 102.808768573958 -4.4707836178526 -0.743335156630566 0.0850091703064069 -0.0366124839666728 -0.404595165838534 0.909799823456611 +1646404328.52364 102.837514168063 -4.47058362301672 -0.684643954875377 0.103372265994275 -0.0433506585806281 -0.415234325372813 0.902782005833084 +1646404328.62369 102.856193240543 -4.47240654125301 -0.637194965633484 0.10678989219774 -0.0516334785337169 -0.416982877053755 0.901141045043928 +1646404328.72322 102.866445833734 -4.48028473599735 -0.60119256419141 0.0949480637860559 -0.0732024281350357 -0.429625872822799 0.895012781528649 +1646404328.82028 102.871529938071 -4.48471008168328 -0.579633815453536 0.0915868067438653 -0.0783516136959139 -0.431835779761419 0.893862819888792 +1646404328.9202 102.870186267172 -4.48643933337975 -0.567166583002498 0.0933451570416896 -0.066116008571918 -0.427472029851809 0.896762520827973 +1646404329.02319 102.869746238664 -4.48663305629605 -0.556871406891096 0.0859745750928157 -0.0678468509690184 -0.41912143154708 0.901300395467077 +1646404329.11957 102.866809301414 -4.4875113554038 -0.551296786440711 0.0735209553580801 -0.0600765219912138 -0.424135461222432 0.900607900899329 +1646404329.21942 102.866575820441 -4.48329170707549 -0.551276606260563 0.0716239876721761 -0.0571912487253324 -0.426380118115303 0.899888415491131 +1646404329.31955 102.868718453282 -4.48153919614645 -0.546467842931424 0.0655846826089056 -0.0649912905530067 -0.423748009671014 0.901061821330358 +1646404329.41934 102.869350704917 -4.48321734958416 -0.542023057420367 0.0564707948390944 -0.0729862696502108 -0.425404824482939 0.900285948507147 +1646404329.51943 102.867233778137 -4.48278763898359 -0.542932761324842 0.0542892945333858 -0.0679419249822807 -0.42813411002051 0.899520845320275 +1646404329.61962 102.867600816118 -4.48271649829525 -0.540189782032716 0.0513883619620352 -0.0722338224005996 -0.428246854181701 0.899303143016703 +1646404329.71973 102.871840445604 -4.48137310191088 -0.539156214118188 0.0502009364198472 -0.0752069820754133 -0.424163706947784 0.901059890094981 +1646404329.81986 102.877290296421 -4.47830669197147 -0.540887043177986 0.0515352115043214 -0.0742341776033567 -0.42283999865137 0.901687165479944 +1646404329.92003 102.881327025692 -4.47720980779086 -0.541775399619992 0.051945959169774 -0.0739846119037673 -0.420599686516894 0.902731299019403 +1646404330.02 102.88241767563 -4.47657523950343 -0.541992623986901 0.0521803079885496 -0.0744241000172798 -0.419803452741027 0.903052229863554 +1646404330.11999 102.882348791306 -4.47609217194778 -0.54245830023692 0.0512912815663026 -0.073347544542067 -0.420070431988825 0.903067092919261 +1646404330.2198 102.881067010718 -4.47568067752525 -0.543327167406386 0.050545119492193 -0.0721659935258795 -0.420238583730346 0.903126122431548 +1646404330.32006 102.880483179283 -4.47621068779654 -0.544555361777378 0.05035149794388 -0.0720985619936101 -0.420539912368475 0.903002052111934 +1646404330.4199 102.879285167144 -4.47577218338826 -0.545320764133795 0.0499602526944199 -0.0714909077541409 -0.420582717987416 0.903052158288492 +1646404330.5201 102.878133387423 -4.4763764524825 -0.546079994821981 0.0493820067020098 -0.071008044274528 -0.420687881766243 0.903073076332923 +1646404330.62001 102.877286429751 -4.47704697699715 -0.545718683773437 0.0495759860149426 -0.0715396240259103 -0.420979124480463 0.902884754858851 +1646404330.72018 102.875561346844 -4.47838079854678 -0.546441396483278 0.0491833665932138 -0.0711248568543215 -0.421376574182309 0.90275358427335 +1646404330.82018 102.874993571324 -4.47954722757861 -0.54716791651852 0.0486654545303218 -0.0707449790937937 -0.422000438775253 0.902520055811426 +1646404330.92 102.874035146661 -4.4804681018673 -0.548440321960994 0.0479956810991622 -0.0699469796052155 -0.422808797115151 0.902239744038115 +1646404331.02022 102.873501054172 -4.48107697538649 -0.548005134376928 0.0479254542926316 -0.0699305494887804 -0.423272031753683 0.902027525197619 +1646404331.12029 102.871896655786 -4.48203446428034 -0.547889316993794 0.0469170322560737 -0.0684313563761896 -0.423432862498528 0.902120032204745 +1646404331.22003 102.869992072542 -4.48151452259463 -0.548322680890863 0.0446859773561855 -0.0651934900886857 -0.423543805804902 0.902420975400101 +1646404331.3201 102.861770818401 -4.48365547786239 -0.549618859839623 0.0331026467941002 -0.048196074010115 -0.424393736803867 0.903588019722969 +1646404331.42 102.853603527977 -4.48433028323443 -0.548356407432401 0.0223211433156841 -0.0321855993608333 -0.424876213298108 0.904403702518027 +1646404331.52309 102.848246280702 -4.4837870505104 -0.547050871074248 0.0146764056616558 -0.0207604679438764 -0.42517237126266 0.904755249115739 +1646404331.62306 102.841043298323 -4.48441064570007 -0.54626326492063 0.00405337925540539 -0.00516208669256966 -0.425654003921174 0.904862194990737 +1646404331.72304 102.839920819178 -4.48414364644468 -0.545257023340442 0.00137204928842643 -0.00139563958661185 -0.425961220331802 0.904739304133698 +1646404331.82302 102.839764989733 -4.48374707067337 -0.543883405712142 0.00146362296637951 -0.00144351802399947 -0.426075892769687 0.904685087565852 +1646404331.92299 102.839671149905 -4.48333290718459 -0.542479315059972 0.00168172428189099 -0.00157322891278056 -0.426147686675029 0.904650676170499 +1646404332.02298 102.840214636111 -4.48409442669571 -0.540424296834356 0.00241371133164835 -0.00138201185918064 -0.426264197629461 0.904594438331417 +1646404332.12299 102.84015674939 -4.48458647050264 -0.539093749114736 0.00247683314827526 -0.00141690659143235 -0.426343178572984 0.90455699198975 +1646404332.223 102.839733672835 -4.48512739685112 -0.537810986117091 0.00263933763754861 -0.00152216968723312 -0.426449737264015 0.904506129599863 +1646404332.32299 102.840808642891 -4.48561933679964 -0.536948435244753 0.00248023555201352 -0.0017506811478629 -0.426411664753497 0.904524115604039 +1646404332.42296 102.84241380501 -4.48595829318259 -0.536204181799677 0.00258461268671521 -0.00185010474801035 -0.426398854482086 0.904529664403572 +1646404332.52294 102.843789103003 -4.48667048665471 -0.535520981672686 0.00266877565831297 -0.00189749877111812 -0.426404715682654 0.904526558802165 +1646404332.6206 102.844787351284 -4.48689520796082 -0.535163767890267 0.00268452216659796 -0.00200363330502957 -0.42637517955408 0.904540206433377 +1646404332.72293 102.845664438774 -4.48772572324838 -0.535084782307527 0.00264751260135527 -0.00194475399550917 -0.426315816052763 0.904568423941597 +1646404332.82286 102.846421654423 -4.48800038788881 -0.534926174681615 0.00271410295670366 -0.00185996908270592 -0.426249798096269 0.90459951568804 +1646404332.92291 102.847538691787 -4.48787987725792 -0.535122561566183 0.00269744962984476 -0.00187032355750725 -0.426202196773124 0.904621972495165 +1646404333.02107 102.847746209421 -4.48821874184842 -0.535433204148604 0.0026421689185189 -0.00193458853585118 -0.426196198104387 0.904624826672342 +1646404333.12078 102.84782951145 -4.48823065182964 -0.535765580688717 0.00273775577608525 -0.00184603102370465 -0.426163217801425 0.904640264777054 +1646404333.22056 102.848072633839 -4.48827546878242 -0.535735079157711 0.0027729975606643 -0.00180489472129695 -0.426160338063022 0.90464159704359 +1646404333.32059 102.847743894719 -4.48857921292235 -0.53599884554868 0.002639915606532 -0.00185357692159337 -0.426157357260327 0.904643300948542 +1646404333.42051 102.847774812136 -4.48833483017179 -0.535773964638242 0.00267648880691581 -0.00183019287429726 -0.426180315830193 0.904632425463834 +1646404333.52053 102.847826963174 -4.48844111560338 -0.536503287981557 0.00268799712688479 -0.00178950581895491 -0.426199860497603 0.904623264819222 +1646404333.62044 102.847771323937 -4.48899262083715 -0.536172832502006 0.00275825271169988 -0.00170309309258335 -0.42618397174199 0.904630705728096 +1646404333.72043 102.847889394122 -4.48945363109598 -0.536294294297459 0.00271257413320533 -0.00170616291783657 -0.426167566615346 0.904638566563916 +1646404333.82044 102.847773583638 -4.48992762220662 -0.536104064124433 0.00278001485403741 -0.00159068761723214 -0.426151840300213 0.904645980612886 +1646404333.92054 102.848194312914 -4.48953971376246 -0.536648113727741 0.00296885119928363 -0.00148145305702611 -0.426162419458732 0.904640582474868 +1646404334.02066 102.848319790591 -4.48998677337519 -0.537688812424491 0.00294465080798612 -0.00150495373568534 -0.42623947313004 0.904604319960772 +1646404334.12081 102.848196736765 -4.49012670233436 -0.537830598072074 0.0030445783376745 -0.00149595019482329 -0.426240689700375 0.904603430857688 +1646404334.22079 102.8478420132 -4.49065026062062 -0.538254561956028 0.00309636461602308 -0.00146522505227556 -0.426245671958132 0.90460095775909 \ No newline at end of file diff --git a/tests/data/hilti_exp4_small/images/0.jpg b/tests/data/hilti_exp4_small/images/0.jpg deleted file mode 100755 index c8187d87c..000000000 Binary files a/tests/data/hilti_exp4_small/images/0.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/0_0.png b/tests/data/hilti_exp4_small/images/0_0.png new file mode 100644 index 000000000..cdbf0f271 Binary files /dev/null and b/tests/data/hilti_exp4_small/images/0_0.png differ diff --git a/tests/data/hilti_exp4_small/images/0_1.png b/tests/data/hilti_exp4_small/images/0_1.png new file mode 100644 index 000000000..c8310f9e4 Binary files /dev/null and b/tests/data/hilti_exp4_small/images/0_1.png differ diff --git a/tests/data/hilti_exp4_small/images/0_2.png b/tests/data/hilti_exp4_small/images/0_2.png new file mode 100644 index 000000000..4c1c31479 Binary files /dev/null and b/tests/data/hilti_exp4_small/images/0_2.png differ diff --git a/tests/data/hilti_exp4_small/images/0_3.png b/tests/data/hilti_exp4_small/images/0_3.png new file mode 100644 index 000000000..0d142ca12 Binary files /dev/null and b/tests/data/hilti_exp4_small/images/0_3.png differ diff --git a/tests/data/hilti_exp4_small/images/0_4.png b/tests/data/hilti_exp4_small/images/0_4.png new file mode 100644 index 000000000..70f46c83e Binary files /dev/null and b/tests/data/hilti_exp4_small/images/0_4.png differ diff --git a/tests/data/hilti_exp4_small/images/1.jpg b/tests/data/hilti_exp4_small/images/1.jpg deleted file mode 100755 index 519383c2a..000000000 Binary files a/tests/data/hilti_exp4_small/images/1.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/10.jpg b/tests/data/hilti_exp4_small/images/10.jpg deleted file mode 100755 index 2dfd2101e..000000000 Binary files a/tests/data/hilti_exp4_small/images/10.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/11.jpg b/tests/data/hilti_exp4_small/images/11.jpg deleted file mode 100755 index aaf96b449..000000000 Binary files a/tests/data/hilti_exp4_small/images/11.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/12.jpg b/tests/data/hilti_exp4_small/images/12.jpg deleted file mode 100755 index d358c35b3..000000000 Binary files a/tests/data/hilti_exp4_small/images/12.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/13.jpg b/tests/data/hilti_exp4_small/images/13.jpg deleted file mode 100755 index b7f784e87..000000000 Binary files a/tests/data/hilti_exp4_small/images/13.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/14.jpg b/tests/data/hilti_exp4_small/images/14.jpg deleted file mode 100755 index 555566029..000000000 Binary files a/tests/data/hilti_exp4_small/images/14.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/15.jpg b/tests/data/hilti_exp4_small/images/15.jpg deleted file mode 100755 index c960ecc1a..000000000 Binary files a/tests/data/hilti_exp4_small/images/15.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/1_0.png b/tests/data/hilti_exp4_small/images/1_0.png new file mode 100644 index 000000000..470497cfe Binary files /dev/null and b/tests/data/hilti_exp4_small/images/1_0.png differ diff --git a/tests/data/hilti_exp4_small/images/1_1.png b/tests/data/hilti_exp4_small/images/1_1.png new file mode 100644 index 000000000..cd60a8560 Binary files /dev/null and b/tests/data/hilti_exp4_small/images/1_1.png differ diff --git a/tests/data/hilti_exp4_small/images/1_2.png b/tests/data/hilti_exp4_small/images/1_2.png new file mode 100644 index 000000000..ae5224b7e Binary files /dev/null and b/tests/data/hilti_exp4_small/images/1_2.png differ diff --git a/tests/data/hilti_exp4_small/images/1_3.png b/tests/data/hilti_exp4_small/images/1_3.png new file mode 100644 index 000000000..431e8d87e Binary files /dev/null and b/tests/data/hilti_exp4_small/images/1_3.png differ diff --git a/tests/data/hilti_exp4_small/images/1_4.png b/tests/data/hilti_exp4_small/images/1_4.png new file mode 100644 index 000000000..2c1ed4892 Binary files /dev/null and b/tests/data/hilti_exp4_small/images/1_4.png differ diff --git a/tests/data/hilti_exp4_small/images/2.jpg b/tests/data/hilti_exp4_small/images/2.jpg deleted file mode 100755 index 6b2d1bba7..000000000 Binary files a/tests/data/hilti_exp4_small/images/2.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/2_0.png b/tests/data/hilti_exp4_small/images/2_0.png new file mode 100644 index 000000000..0a8854937 Binary files /dev/null and b/tests/data/hilti_exp4_small/images/2_0.png differ diff --git a/tests/data/hilti_exp4_small/images/2_1.png b/tests/data/hilti_exp4_small/images/2_1.png new file mode 100644 index 000000000..73b14d46d Binary files /dev/null and b/tests/data/hilti_exp4_small/images/2_1.png differ diff --git a/tests/data/hilti_exp4_small/images/2_2.png b/tests/data/hilti_exp4_small/images/2_2.png new file mode 100644 index 000000000..8e22a8815 Binary files /dev/null and b/tests/data/hilti_exp4_small/images/2_2.png differ diff --git a/tests/data/hilti_exp4_small/images/2_3.png b/tests/data/hilti_exp4_small/images/2_3.png new file mode 100644 index 000000000..cc69c9616 Binary files /dev/null and b/tests/data/hilti_exp4_small/images/2_3.png differ diff --git a/tests/data/hilti_exp4_small/images/2_4.png b/tests/data/hilti_exp4_small/images/2_4.png new file mode 100644 index 000000000..01567624f Binary files /dev/null and b/tests/data/hilti_exp4_small/images/2_4.png differ diff --git a/tests/data/hilti_exp4_small/images/3.jpg b/tests/data/hilti_exp4_small/images/3.jpg deleted file mode 100755 index b000a0166..000000000 Binary files a/tests/data/hilti_exp4_small/images/3.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/4.jpg b/tests/data/hilti_exp4_small/images/4.jpg deleted file mode 100755 index 24902d5e6..000000000 Binary files a/tests/data/hilti_exp4_small/images/4.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/5.jpg b/tests/data/hilti_exp4_small/images/5.jpg deleted file mode 100755 index 686d57f2e..000000000 Binary files a/tests/data/hilti_exp4_small/images/5.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/6.jpg b/tests/data/hilti_exp4_small/images/6.jpg deleted file mode 100755 index 9cc789c45..000000000 Binary files a/tests/data/hilti_exp4_small/images/6.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/7.jpg b/tests/data/hilti_exp4_small/images/7.jpg deleted file mode 100755 index 341d74eaa..000000000 Binary files a/tests/data/hilti_exp4_small/images/7.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/8.jpg b/tests/data/hilti_exp4_small/images/8.jpg deleted file mode 100755 index e6bf3ff50..000000000 Binary files a/tests/data/hilti_exp4_small/images/8.jpg and /dev/null differ diff --git a/tests/data/hilti_exp4_small/images/9.jpg b/tests/data/hilti_exp4_small/images/9.jpg deleted file mode 100755 index cdc5ca887..000000000 Binary files a/tests/data/hilti_exp4_small/images/9.jpg and /dev/null differ diff --git a/tests/data_association/test_data_association.py b/tests/data_association/test_data_association.py index 0fe7d0026..621cb2e3f 100644 --- a/tests/data_association/test_data_association.py +++ b/tests/data_association/test_data_association.py @@ -137,7 +137,7 @@ def verify_triangulation_sharedCal_2poses(self, triangulation_mode: Triangulatio reproj_error_threshold=5, mode=triangulation_mode, min_num_hypotheses=20 ) da = DataAssociation(min_track_len=3, triangulation_options=triangulation_options) - triangulated_landmark_map, _ = da.run( + triangulated_landmark_map, _ = da.run_da( len(cameras), cameras, matches_dict, @@ -176,7 +176,7 @@ def test_triangulation_individualCal_without_ransac(self): triangulation_options = TriangulationOptions(reproj_error_threshold=5, mode=TriangulationSamplingMode.NO_RANSAC) da = DataAssociation(min_track_len=2, triangulation_options=triangulation_options) - sfm_data, _ = da.run( + sfm_data, _ = da.run_da( len(cameras), cameras, matches_dict, keypoints_list, [None] * len(cameras), relative_pose_priors={} ) estimated_landmark = sfm_data.get_track(0).point3() @@ -226,7 +226,7 @@ def verify_triangulation_sharedCal_3poses(self, triangulation_mode: Triangulatio reproj_error_threshold=5, mode=triangulation_mode, min_num_hypotheses=20 ) da = DataAssociation(min_track_len=3, triangulation_options=triangulation_options) - sfm_data, _ = da.run( + sfm_data, _ = da.run_da( len(cameras), cameras, matches_dict, @@ -265,7 +265,7 @@ def test_data_association_with_missing_camera(self): # will lead to a cheirality exception because keypoints are identical in two cameras # no track will be formed, and thus connected component will be empty - sfm_data, _ = da.run( + sfm_data, _ = da.run_da( num_images=3, cameras=cameras, corr_idxs_dict=corr_idxs_dict, @@ -298,7 +298,7 @@ def test_create_computation_graph(self): reproj_error_threshold=5, mode=TriangulationSamplingMode.RANSAC_TOPK_BASELINES, min_num_hypotheses=20 ) da = DataAssociation(min_track_len=3, triangulation_options=triangulation_options) - expected_sfm_data, expected_metrics = da.run( + expected_sfm_data, expected_metrics = da.run_da( len(cameras), cameras, corr_idxs_graph, keypoints_list, cameras_gt=cameras_gt, relative_pose_priors={} ) diff --git a/tests/loader/test_hilti_loader.py b/tests/loader/test_hilti_loader.py index abe1d6f65..514ddc47d 100644 --- a/tests/loader/test_hilti_loader.py +++ b/tests/loader/test_hilti_loader.py @@ -4,14 +4,75 @@ """ import unittest from pathlib import Path +from typing import Iterable, List, Tuple import numpy as np +from gtsam import ( + BetweenFactorPose3, + InitializePose3, + LevenbergMarquardtOptimizer, + NonlinearFactorGraph, + Point3, + Pose3, + PriorFactorPose3, + Rot3, + Values, + noiseModel, +) -import gtsfm.utils.geometry_comparisons as comp_utils +from gtsfm.common.constraint import Constraint from gtsfm.loader.hilti_loader import HiltiLoader DATA_ROOT_PATH = Path(__file__).resolve().parent.parent / "data" TEST_DATASET_DIR_PATH = DATA_ROOT_PATH / "hilti_exp4_small" +EXP07_PATH = DATA_ROOT_PATH / "exp07" + + +def pose_of_vector(pose_vector): + """Convert from vector to Pose3""" + pose_rotation = Rot3(pose_vector[-1], pose_vector[3], pose_vector[4], pose_vector[5]) + pose_translation = Point3(pose_vector[:3]) + return Pose3(pose_rotation, pose_translation) + + +def create_initial_estimate(poses: List[Pose3]): + """Create initial estimate""" + initial_estimate = Values() + for i, pose_vector in enumerate(poses): + initial_estimate.insert(i, pose_vector) + return initial_estimate + + +def read_fastlio_result(poses_txt_path: str) -> Tuple[List[Pose3], np.ndarray]: + """ + Read FastLIO result + Args: + 1. The poses txt file path + 2. The covariance txt file path + Returns: + 1. (poses, covariances) + """ + # remove timestamp column from txt + poses = np.loadtxt(poses_txt_path)[:, 1:] + timestamps = np.loadtxt(poses_txt_path)[:, 0] + return [pose_of_vector(pose) for pose in poses], timestamps + + +def generate_pose_graph(poses: List[Pose3], constraints: Iterable[Constraint]): + """Generate pose graph.""" + graph = NonlinearFactorGraph() + + # Add the prior factor to the initial pose. + prior_pose_factor = PriorFactorPose3(0, poses[0], noiseModel.Isotropic.Sigma(6, 5e-2)) + graph.add(prior_pose_factor) + + # Add pose priors + for c in constraints: + measurement_noise = noiseModel.Gaussian.Covariance(c.cov) + factor_aTb = BetweenFactorPose3(c.a, c.b, c.aTb, measurement_noise) + graph.add(factor_aTb) + + return graph class TestHiltiLoader(unittest.TestCase): @@ -48,66 +109,151 @@ def test_number_of_absolute_pose_priors(self) -> None: for i in range(len(self.loader)): if self.loader.get_absolute_pose_prior(i) is not None: num_valid_priors += 1 - else: - print(f"not found for i={i}") - - # assert all poses have absolute pose priors - self.assertEqual(num_valid_priors, len(self.loader)) - def test_get_absolute_pose_priors(self) -> None: - # starting frames have no camera movement - t0_cam0_prior = self.loader.get_absolute_pose_prior(0) - t1_cam0_prior = self.loader.get_absolute_pose_prior(5) + # assert no index should have pose prior + self.assertEqual(num_valid_priors, 0) - self.assertLessEqual( - comp_utils.compute_relative_rotation_angle(t0_cam0_prior.value.rotation(), t1_cam0_prior.value.rotation()), - 2, - ) + def test_number_of_relative_pose_priors_without_subsampling(self) -> None: + """Check that 3 relative constraints translate into many relative pose priors.""" + expected = [ + # rig 0 + (0, 2), + (1, 2), + (2, 3), + (2, 4), + (2, 7), + (2, 12), + # rig 1 + (5, 7), + (6, 7), + (7, 8), + (7, 9), + (7, 12), + # rig 2 + (10, 12), + (11, 12), + (12, 13), + (12, 14), + ] + expected.sort() + # Check that "stars" have been added + relative_pose_priors = self.loader.get_relative_pose_priors() + actual = list(relative_pose_priors.keys()) + actual.sort() + self.assertEqual(len(actual), len(expected)) + self.assertEqual(actual, expected) - self.assertLessEqual( - np.linalg.norm(t0_cam0_prior.value.translation() - t1_cam0_prior.value.translation()), 0.01 + def test_covariance_filtered_constraints(self) -> None: + """Check that outlier filtering works.""" + loader = HiltiLoader( + base_folder=str(TEST_DATASET_DIR_PATH), + max_length=None, + subsample=2, ) + all_constraints = loader._load_constraints() - # self.assertLessEqual( - # comp_utils.compute_relative_unit_translation_angle( - # Unit3(t0_cam0_prior.value.translation()), Unit3(t1_cam0_prior.value.translation()) - # ), - # 2, - # ) + expected = [(0, 1), (0, 2), (1, 2)] + expected.sort() + actual = [(c.a, c.b) for c in loader._covariance_filtered_constraints(all_constraints)] + actual.sort() + self.assertEqual(actual, expected) - def test_number_of_relative_pose_priors(self) -> None: + def test_number_of_relative_pose_priors_with_subsampling(self) -> None: """Check that 3 relative constraints translate into many relative pose priors.""" - # Just give 3 pairs - pairs = [ - (0, 1), - (0, 3), - (0, 5), - ] + loader = HiltiLoader( + base_folder=str(TEST_DATASET_DIR_PATH), + max_length=None, + subsample=2, + ) + expected = [ - (0, 1), - (0, 3), - (0, 5), - (2, 0), - (2, 1), + # rig 0 + (0, 2), + (1, 2), (2, 3), (2, 4), - (7, 5), - (7, 6), - (7, 8), - (7, 9), - (12, 10), - (12, 11), + (2, 7), + (2, 12), + # rig 1 + (7, 12), + # rig 2 + (10, 12), + (11, 12), (12, 13), (12, 14), ] expected.sort() # Check that "stars" have been added - relative_pose_priors = self.loader.get_relative_pose_priors(pairs) + relative_pose_priors = loader.get_relative_pose_priors() actual = list(relative_pose_priors.keys()) actual.sort() - self.assertEqual(len(actual), len(pairs) + 3 * 4) self.assertEqual(actual, expected) + def test_filters_constraints(self) -> None: + constraints = [ + Constraint(0, 1, Pose3(Rot3(), Point3(5, 0, 0)), cov=np.zeros((6, 6))), # outlier, has both 2 & 3 step + Constraint(2, 1, Pose3(Rot3(), Point3(-1, 0, 0)), cov=np.zeros((6, 6))), + Constraint(2, 3, Pose3(Rot3(), Point3(4, 0, 0)), cov=np.zeros((6, 6))), # outlier, only 3 step + Constraint(3, 4, Pose3(Rot3(), Point3(3, 0, 0)), cov=np.zeros((6, 6))), # outlier, only 2 step + Constraint(4, 5, Pose3(Rot3(), Point3(1, 0, 0)), cov=np.zeros((6, 6))), + Constraint(2, 0, Pose3(Rot3(), Point3(-2, 0, 0)), cov=np.zeros((6, 6))), + Constraint(1, 3, Pose3(Rot3(), Point3(2, 0, 0)), cov=np.zeros((6, 6))), + Constraint(3, 5, Pose3(Rot3(), Point3(2, 0, 0)), cov=np.zeros((6, 6))), + Constraint(0, 3, Pose3(Rot3(), Point3(3, 0, 0)), cov=np.zeros((6, 6))), + Constraint(1, 4, Pose3(Rot3(), Point3(3, 0, 0)), cov=np.zeros((6, 6))), + Constraint(2, 5, Pose3(Rot3(), Point3(3, 0, 0)), cov=np.zeros((6, 6))), + ] + + expected_outliers = [(0, 1), (2, 3), (3, 4)] + + filtered = HiltiLoader._filter_outlier_constraints(constraints) + outlier_keys = [(c.a, c.b) for c in filtered if c.cov[0, 0] > np.deg2rad(10)] + self.assertSetEqual(set(outlier_keys), set(expected_outliers)) + + def test_updates_stationary_constraints(self) -> None: + constraints = [ + Constraint(0, 1, Pose3(Rot3(), Point3(5, 0, 0))), + Constraint(2, 1, Pose3(Rot3(), Point3(0.01, 0, 0))), # stationary + Constraint(2, 3, Pose3(Rot3(), Point3(0, 0.01, 0))), # stationary + Constraint(3, 4, Pose3(Rot3(), Point3(3, 0, 0))), + Constraint(4, 5, Pose3(Rot3.Rz(np.deg2rad(20)), Point3(0, 0, 0))), + ] + updated_constraints = HiltiLoader._update_stationary_constraints(constraints) + zero_keys = [(c.a, c.b) for c in updated_constraints if c.aTb.equals(Pose3(), 1e-4)] + self.assertSetEqual(set([(2, 1), (2, 3)]), set(zero_keys)) + + def test_filter_constraints(self) -> None: + """Check that filtering and then doing pose slam on exp07 works as in notebook.""" + # Read constraints and poses from file. + ws = Path(EXP07_PATH) + poses_txt_path = ws / "fastlio_odom.txt" + constraint_txt_path = ws / "constraints.txt" + poses, _ = read_fastlio_result(str(poses_txt_path)) + constraints = Constraint.read(str(constraint_txt_path)) + self.assertEqual(len(poses), 1319) + self.assertEqual(len(constraints), 10328) + + # Create graph. + filtered_constraints = list(HiltiLoader._covariance_filtered_constraints(constraints)) + filtered_constraints = HiltiLoader._filter_outlier_constraints(filtered_constraints) + graph = generate_pose_graph(poses, filtered_constraints) + self.assertEqual(graph.size(), 10328) + + # Check initial error. + initial_estimate = create_initial_estimate(poses) + self.assertAlmostEqual(graph.error(initial_estimate), 60807.0197569433) + + # Check that we can initialize with Pose3Initialize + # TODO(Frank): this is still high, and an outlier is certainly present + initial_estimate2 = InitializePose3.initialize(graph) + self.assertAlmostEqual(graph.error(initial_estimate2), 3390522.412178782, places=1) + + # Optimize and Check final error. + optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate2) + result = optimizer.optimize() + final_error = graph.error(result) + self.assertAlmostEqual(final_error, 27083.849612680227, places=1) + if __name__ == "__main__": unittest.main() diff --git a/tests/loader/test_olsson_loader.py b/tests/loader/test_olsson_loader.py index 1a755767f..b459f2270 100644 --- a/tests/loader/test_olsson_loader.py +++ b/tests/loader/test_olsson_loader.py @@ -63,7 +63,7 @@ def test_image_contents(self) -> None: index_to_test = 5 file_path = DEFAULT_FOLDER / "images" / "DSC_0006.JPG" loader_image = self.loader.get_image_full_res(index_to_test) - expected_image = io_utils.load_image(file_path) + expected_image = io_utils.load_image(str(file_path)) np.testing.assert_allclose(expected_image.value_array, loader_image.value_array) def test_get_camera_pose_exists(self) -> None: @@ -104,14 +104,14 @@ def test_get_camera_intrinsics_explicit(self) -> None: def test_get_camera_intrinsics_exif(self) -> None: """Tests getter for intrinsics when explicit numpy arrays are absent and we fall back on exif.""" - loader = OlssonLoader(EXIF_FOLDER, image_extension="JPG", use_gt_intrinsics=False) + loader = OlssonLoader(str(EXIF_FOLDER), image_extension="JPG", use_gt_intrinsics=False) computed = loader.get_camera_intrinsics_full_res(5) expected = Cal3Bundler(fx=2378.983, k1=0, k2=0, u0=648.0, v0=968.0) self.assertTrue(expected.equals(computed, 1e-3)) def test_get_camera_intrinsics_missing(self) -> None: """Tests getter for intrinsics when explicit numpy arrays are absent, exif is missing, and we raise an error.""" - loader = OlssonLoader(NO_EXIF_FOLDER, image_extension="JPG") + loader = OlssonLoader(str(NO_EXIF_FOLDER), image_extension="JPG") with pytest.raises(ValueError): _ = loader.get_camera_intrinsics(5) diff --git a/tests/pose_slam/test_pose_slam.py b/tests/pose_slam/test_pose_slam.py new file mode 100644 index 000000000..a89b55598 --- /dev/null +++ b/tests/pose_slam/test_pose_slam.py @@ -0,0 +1,56 @@ +"""Tests for the PoseSlam module. + +Authors: Akshay Krishnan, Frank Dellaert +""" +import unittest +from typing import Dict, List, Optional, Tuple + +import numpy as np +from dask.delayed import Delayed +from gtsam import Point3, Pose3, Rot3 +from gtsam.utils.test_case import GtsamTestCase + +from gtsfm.common.pose_prior import PosePrior, PosePriorType +from gtsfm.pose_slam.pose_slam import PoseSlam + + +class TestPoseSlam(GtsamTestCase): + """Test class for 1DSFM rotation averaging.""" + + def setUp(self) -> None: + super().setUp() + + self.slam: PoseSlam = PoseSlam() + + def test_run_pose_slam(self) -> None: + """Check that a simple pose graph works.""" + sigma = np.deg2rad(5) + cov = np.diag([sigma, sigma, sigma, 0.1, 0.1, 0.1]) + relative_pose_priors = { + (0, 1): PosePrior(Pose3(Rot3(), Point3(1, 0, 0)), cov, type=PosePriorType.SOFT_CONSTRAINT), + (0, 2): PosePrior(Pose3(Rot3(), Point3(2, 0, 0)), cov, type=PosePriorType.SOFT_CONSTRAINT), + (1, 2): PosePrior(Pose3(Rot3(), Point3(1, 0, 0)), cov, type=PosePriorType.SOFT_CONSTRAINT), + } + + gt_wTi_list = [None, None, None] + poses, _ = self.slam.run_pose_slam(3, relative_pose_priors=relative_pose_priors, gt_wTi_list=gt_wTi_list) + self.assertEqual(len(poses), 3) + for pose in poses: + self.assertIsInstance(pose, Pose3) + self.gtsamAssertEquals(poses[0], Pose3()) + self.gtsamAssertEquals(poses[1], Pose3(Rot3(), Point3(1, 0, 0))) + self.gtsamAssertEquals(poses[2], Pose3(Rot3(), Point3(2, 0, 0))) + + def test_create_computation_graph(self) -> None: + """Check that the interface works.""" + relative_pose_priors: Dict[Tuple[int, int], PosePrior] = {} + gt_wTi_list: Optional[List[Optional[Pose3]]] = [None, None, None] + delayed_poses, metrics = self.slam.create_computation_graph( + 3, relative_pose_priors=relative_pose_priors, gt_wTi_list=gt_wTi_list + ) + self.assertIsInstance(delayed_poses, Delayed) + self.assertIsInstance(metrics, Delayed) + + +if __name__ == "__main__": + unittest.main() diff --git a/tests/repro_tests/averaging/rotation/test_shonan_reproducibility.py b/tests/repro_tests/averaging/rotation/test_shonan_reproducibility.py index 2659c5b41..bba181f78 100644 --- a/tests/repro_tests/averaging/rotation/test_shonan_reproducibility.py +++ b/tests/repro_tests/averaging/rotation/test_shonan_reproducibility.py @@ -27,11 +27,13 @@ def setUp(self) -> None: super().setUp() with open(str(RELATIVE_ROTATIONS_PATH), "rb") as f: self._input: Dict[Tuple[int, int], Rot3] = pickle.load(f) - self._priors = {edge: None for edge in self._input.keys()} + self._priors = {} self._shonan_obj: RotationAveragingBase = ShonanRotationAveraging() def run_once(self) -> List[Optional[Rot3]]: - return self._shonan_obj.run(num_images=NUM_IMAGES_IN_INPUT, i2Ri1_dict=self._input, i2Ri1_priors=self._priors) + return self._shonan_obj.run_rotation_averaging( + num_images=NUM_IMAGES_IN_INPUT, i2Ri1_dict=self._input, relative_pose_priors=self._priors + ) def assert_results(self, results_a: List[Optional[Rot3]], results_b: List[Optional[Rot3]]) -> None: self.assertTrue(geometry_comparisons.compare_rotations(results_a, results_b, ROT3_DIFF_ANGLE_THRESHOLD_DEG)) diff --git a/tests/repro_tests/averaging/translation/test_1dsfm_reproducibility.py b/tests/repro_tests/averaging/translation/test_1dsfm_reproducibility.py index b6aa3653d..0f27a23c7 100644 --- a/tests/repro_tests/averaging/translation/test_1dsfm_reproducibility.py +++ b/tests/repro_tests/averaging/translation/test_1dsfm_reproducibility.py @@ -8,7 +8,7 @@ from typing import Dict, List, Optional, Set, Tuple import gtsam -from gtsam import BinaryMeasurementsUnit3, Point3, Pose3, Rot3, Unit3 +from gtsam import BinaryMeasurementsUnit3, Pose3, Rot3, Unit3 import gtsfm.averaging.translation.averaging_1dsfm as averaging_1dsfm import gtsfm.utils.geometry_comparisons as geometry_comparisons @@ -36,17 +36,15 @@ def setUp(self) -> None: with open(str(GLOBAL_ROTATIONS_PATH), "rb") as f: self._global_rotations_input: List[Optional[Rot3]] = pickle.load(f) - def run_once(self) -> List[Optional[Point3]]: - return self._1dsfm_obj.run( + def run_once(self) -> List[Optional[Pose3]]: + return self._1dsfm_obj.run_translation_averaging( num_images=NUM_IMAGES_IN_INPUT, i2Ui1_dict=self._relative_unit_translations_input, wRi_list=self._global_rotations_input, )[0] - def assert_results(self, results_a: List[Optional[Point3]], results_b: List[Optional[Point3]]) -> None: - poses_a = [Pose3(R, t) if t is not None else None for R, t in zip(self._global_rotations_input, results_a)] - poses_b = [Pose3(R, t) if t is not None else None for R, t in zip(self._global_rotations_input, results_b)] - self.assertTrue(geometry_comparisons.compare_global_poses(poses_a, poses_b)) + def assert_results(self, results_a: List[Optional[Pose3]], results_b: List[Optional[Pose3]]) -> None: + self.assertTrue(geometry_comparisons.compare_global_poses(results_a, results_b)) class Test1DSFMInlierMaskReproducibility(ReproducibilityTestBase, unittest.TestCase): diff --git a/tests/retriever/test_rig_retriever.py b/tests/retriever/test_rig_retriever.py index a32e157ca..5da4814c9 100644 --- a/tests/retriever/test_rig_retriever.py +++ b/tests/retriever/test_rig_retriever.py @@ -16,9 +16,8 @@ class TestRigRetriever(unittest.TestCase): def test_rig_retriever(self) -> None: """Assert that we can parse a constraints file from the Hilti SLAM team and get constraints.""" - loader = HiltiLoader(TEST_DATASET_DIR_PATH) - retriever = RigRetriever(threshold=30) + retriever = RigRetriever(subsample=1, threshold=30) pairs = retriever.run(loader=loader) # We know these to be the right values from setUp() method. @@ -71,6 +70,35 @@ def test_rig_retriever(self) -> None: ] # regression self.assertEqual(pairs, expected) + def test_rig_retriever_with_subsample(self) -> None: + """Assert that we can parse a constraints file from the Hilti SLAM team and get constraints.""" + + loader = HiltiLoader(TEST_DATASET_DIR_PATH, subsample=2) + retriever = RigRetriever(threshold=30, subsample=2) + + pairs = retriever.run(loader=loader) + # We know these to be the right values from setUp() method. + expected = [ + (0, 1), + (0, 3), + (0, 10), + (0, 11), + (0, 14), + (1, 4), + (1, 10), + (1, 11), + (1, 14), + (2, 12), + (3, 13), + (4, 10), + (4, 11), + (4, 14), + (10, 11), + (10, 13), + (11, 14), + ] # regression + self.assertEqual(pairs, expected) + if __name__ == "__main__": unittest.main() diff --git a/tests/retriever/test_sequential_hilti_retriever.py b/tests/retriever/test_sequential_hilti_retriever.py index 99cf8909e..e8142e078 100644 --- a/tests/retriever/test_sequential_hilti_retriever.py +++ b/tests/retriever/test_sequential_hilti_retriever.py @@ -17,7 +17,7 @@ class TestSequentialHiltiRetriever(unittest.TestCase): def test_sequential_retriever(self) -> None: """Assert that we get 30 total matches with a lookahead of 3 frames on the Door Dataset.""" - loader = HiltiLoader(TEST_DATASET_DIR_PATH) + loader = HiltiLoader(base_folder=str(TEST_DATASET_DIR_PATH)) max_frame_lookahead = 3 retriever = SequentialHiltiRetriever(max_frame_lookahead=max_frame_lookahead) pairs = retriever.run(loader=loader) diff --git a/tests/test_scene_optimizer.py b/tests/test_scene_optimizer.py index cbce6739d..c6a77daef 100644 --- a/tests/test_scene_optimizer.py +++ b/tests/test_scene_optimizer.py @@ -39,23 +39,17 @@ def test_create_computation_graph(self): # generate the dask computation graph delayed_sfm_result, delayed_io = scene_optimizer.create_computation_graph( - num_images=len(self.loader), - image_pair_indices=self.loader.get_valid_pairs(), - image_graph=self.loader.create_computation_graph_for_images(), - all_intrinsics=self.loader.get_all_intrinsics(), - image_shapes=self.loader.get_image_shapes(), + self.loader, + self.loader.create_computation_graph_for_images(), + image_pair_indices=self.loader.get_valid_pairs(), # TODO: replace with retriever absolute_pose_priors=self.loader.get_absolute_pose_priors(), - relative_pose_priors=self.loader.get_relative_pose_priors( - self.loader.get_valid_pairs() - ), - cameras_gt=self.loader.get_gt_cameras(), - gt_wTi_list=self.loader.get_gt_poses(), + relative_pose_priors=self.loader.get_relative_pose_priors(), ) # create dask client cluster = LocalCluster(n_workers=1, threads_per_worker=4) with Client(cluster): - sfm_result, *io = dask.compute(delayed_sfm_result, *delayed_io) + sfm_result, *io = dask.compute(delayed_sfm_result, *delayed_io.values()) self.assertIsInstance(sfm_result, GtsfmData) diff --git a/tests/utils/test_geometry_comparisons.py b/tests/utils/test_geometry_comparisons.py index 0bc64eb72..21131260b 100644 --- a/tests/utils/test_geometry_comparisons.py +++ b/tests/utils/test_geometry_comparisons.py @@ -11,7 +11,7 @@ from gtsam.examples import SFMdata import gtsfm.utils.geometry_comparisons as geometry_comparisons -import tests.data.sample_poses as sample_poses +import gtsfm.utils.sample_poses as sample_poses POSE_LIST = SFMdata.createPoses(Cal3_S2()) diff --git a/tests/utils/test_io_utils.py b/tests/utils/test_io_utils.py index f4eab7d99..032eed3a6 100644 --- a/tests/utils/test_io_utils.py +++ b/tests/utils/test_io_utils.py @@ -125,7 +125,7 @@ def test_round_trip_images_txt(self) -> None: with tempfile.TemporaryDirectory() as tempdir: images_fpath = os.path.join(tempdir, "images.txt") - io_utils.write_images(gtsfm_data, images, tempdir) + io_utils.write_images(gtsfm_data, [image.file_name for image in images], tempdir) wTi_list, _ = io_utils.read_images_txt(images_fpath) recovered_wTc = wTi_list[0] @@ -156,7 +156,7 @@ def test_round_trip_cameras_txt(self) -> None: with tempfile.TemporaryDirectory() as tempdir: cameras_fpath = os.path.join(tempdir, "cameras.txt") - io_utils.write_cameras(gtsfm_data, images, tempdir) + io_utils.write_cameras(gtsfm_data, [(image.height, image.width) for image in images], tempdir) recovered_calibrations = io_utils.read_cameras_txt(cameras_fpath) self.assertEqual(len(original_calibrations), len(recovered_calibrations)) diff --git a/tests/utils/test_reprojection.py b/tests/utils/test_reprojection.py index c4fb3a88f..b344dda54 100644 --- a/tests/utils/test_reprojection.py +++ b/tests/utils/test_reprojection.py @@ -1,88 +1,96 @@ import numpy as np -from gtsam import Cal3Bundler, Rot3, PinholeCameraCal3Bundler, Pose3, SfmTrack +import unittest -from gtsfm.common.sfm_track import SfmMeasurement import gtsfm.utils.reprojection as reproj_utils +from gtsam import Cal3Bundler, PinholeCameraCal3Bundler, Pose3, Rot3, SfmTrack +from gtsfm.common.sfm_track import SfmMeasurement -def test_compute_track_reprojection_errors(): - """Ensure that reprojection error is computed properly within a track. - - # For camera 0: - # [13] = [10,0,3] [1,0,0 | 0] [1] - # [24] = [0,10,4] * [0,1,0 | 0] *[2] - # [1] = [0, 0,1] [0,0,1 | 0] [1] - # [1] - - # For camera 1: - # [-7] = [10,0,3] [1,0,0 |-2] [1] - # [44] = [0,10,4] * [0,1,0 | 2] *[2] - # [1] = [0, 0,1] [0,0,1 | 0] [1] - # [1] - """ - wTi0 = Pose3(Rot3.RzRyRx(0, 0, 0), np.zeros((3, 1))) - wTi1 = Pose3(Rot3.RzRyRx(0, 0, 0), np.array([2, -2, 0])) - - f = 10 - k1 = 0 - k2 = 0 - u0 = 3 - v0 = 4 - - K0 = Cal3Bundler(f, k1, k2, u0, v0) - K1 = Cal3Bundler(f, k1, k2, u0, v0) - - track_camera_dict = {0: PinholeCameraCal3Bundler(wTi0, K0), 1: PinholeCameraCal3Bundler(wTi1, K1)} - - triangulated_pt = np.array([1, 2, 1]) - track_3d = SfmTrack(triangulated_pt) - - # in camera 0 - track_3d.addMeasurement(idx=0, m=np.array([13, 24])) - # in camera 1 - track_3d.addMeasurement(idx=1, m=np.array([-8, 43])) # should be (-7,44), 1 px error in each dim - - errors, avg_track_reproj_error = reproj_utils.compute_track_reprojection_errors(track_camera_dict, track_3d) - - expected_errors = np.array([0, np.sqrt(2)]) - np.testing.assert_allclose(errors, expected_errors) - assert avg_track_reproj_error == np.sqrt(2) / 2 - - -def test_compute_point_reprojection_errors(): - """Ensure a hypothesized 3d point is projected correctly and compared w/ 2 measurements. - # For camera 0: - # [13] = [10,0,3] [1,0,0 | 0] [1] - # [24] = [0,10,4] * [0,1,0 | 0] *[2] - # [1] = [0, 0,1] [0,0,1 | 0] [1] - # [1] - - # For camera 1: - # [-7] = [10,0,3] [1,0,0 |-2] [1] - # [44] = [0,10,4] * [0,1,0 | 2] *[2] - # [1] = [0, 0,1] [0,0,1 | 0] [1] - # [1] - """ - wTi0 = Pose3(Rot3.RzRyRx(0, 0, 0), np.zeros((3, 1))) - wTi1 = Pose3(Rot3.RzRyRx(0, 0, 0), np.array([2, -2, 0])) - - f = 10 - k1 = 0 - k2 = 0 - u0 = 3 - v0 = 4 - - K0 = Cal3Bundler(f, k1, k2, u0, v0) - K1 = Cal3Bundler(f, k1, k2, u0, v0) - - track_camera_dict = {0: PinholeCameraCal3Bundler(wTi0, K0), 1: PinholeCameraCal3Bundler(wTi1, K1)} - point3d = np.array([1, 2, 1]) - measurements = [SfmMeasurement(i=1, uv=np.array([-8, 43])), SfmMeasurement(i=0, uv=np.array([13, 24]))] - - errors, avg_track_reproj_error = reproj_utils.compute_point_reprojection_errors( - track_camera_dict, point3d, measurements - ) - expected_errors = np.array([np.sqrt(2), 0]) - np.testing.assert_allclose(errors, expected_errors) - assert avg_track_reproj_error == np.sqrt(2) / 2 - +class TestReprojection(unittest.TestCase): + def test_compute_track_reprojection_errors(self): + """Ensure that reprojection error is computed properly within a track. + + # For camera 0: + # [13] = [10,0,3] [1,0,0 | 0] [1] + # [24] = [0,10,4] * [0,1,0 | 0] *[2] + # [1] = [0, 0,1] [0,0,1 | 0] [1] + # [1] + + # For camera 1: + # [-7] = [10,0,3] [1,0,0 |-2] [1] + # [44] = [0,10,4] * [0,1,0 | 2] *[2] + # [1] = [0, 0,1] [0,0,1 | 0] [1] + # [1] + """ + wTi0 = Pose3(Rot3.RzRyRx(0, 0, 0), np.zeros((3, 1))) + wTi1 = Pose3(Rot3.RzRyRx(0, 0, 0), np.array([2, -2, 0])) + + f = 10 + k1 = 0 + k2 = 0 + u0 = 3 + v0 = 4 + + K0 = Cal3Bundler(f, k1, k2, u0, v0) + K1 = Cal3Bundler(f, k1, k2, u0, v0) + + track_camera_dict = {0: PinholeCameraCal3Bundler(wTi0, K0), 1: PinholeCameraCal3Bundler(wTi1, K1)} + + triangulated_pt = np.array([1, 2, 1]) + track_3d = SfmTrack(triangulated_pt) + + # in camera 0 + track_3d.addMeasurement(idx=0, m=np.array([13, 24])) + # in camera 1 + track_3d.addMeasurement(idx=1, m=np.array([-8, 43])) # should be (-7,44), 1 px error in each dim + + errors, avg_track_reproj_error = reproj_utils.compute_track_reprojection_errors(track_camera_dict, track_3d) + + expected_errors = np.array([0, np.sqrt(2)]) + np.testing.assert_allclose(errors, expected_errors) + assert avg_track_reproj_error == np.sqrt(2) / 2 + + def test_compute_point_reprojection_errors(self): + """Ensure a hypothesized 3d point is projected correctly and compared w/ 2 measurements. + # For camera 0: + # [13] = [10,0,3] [1,0,0 | 0] [1] + # [24] = [0,10,4] * [0,1,0 | 0] *[2] + # [1] = [0, 0,1] [0,0,1 | 0] [1] + # [1] + + # For camera 1: + # [-7] = [10,0,3] [1,0,0 |-2] [1] + # [44] = [0,10,4] * [0,1,0 | 2] *[2] + # [1] = [0, 0,1] [0,0,1 | 0] [1] + # [1] + """ + wTi0 = Pose3(Rot3.RzRyRx(0, 0, 0), np.zeros((3, 1))) + wTi1 = Pose3(Rot3.RzRyRx(0, 0, 0), np.array([2, -2, 0])) + + f = 10 + k1 = 0 + k2 = 0 + u0 = 3 + v0 = 4 + + K0 = Cal3Bundler(f, k1, k2, u0, v0) + K1 = Cal3Bundler(f, k1, k2, u0, v0) + + track_camera_dict = {0: PinholeCameraCal3Bundler(wTi0, K0), 1: PinholeCameraCal3Bundler(wTi1, K1)} + point3d = np.array([1, 2, 1]) + measurements = [ + SfmMeasurement(i=1, uv=np.array([-8, 43])), + SfmMeasurement(i=2, uv=np.array([0, 0])), # not in track_camera_dict! + SfmMeasurement(i=0, uv=np.array([13, 24])), + ] + + errors, avg_track_reproj_error = reproj_utils.compute_point_reprojection_errors( + track_camera_dict, point3d, measurements + ) + expected_errors = np.array([np.sqrt(2), np.nan, 0]) + np.testing.assert_allclose(errors, expected_errors) + assert avg_track_reproj_error == np.sqrt(2) / 2 + + +if __name__ == "__main__": + unittest.main()